From 6e29d97a1583192defcd34d66fe934c7b32ca0bd Mon Sep 17 00:00:00 2001 From: Peter Purnyn Date: Fri, 6 Dec 2019 15:42:22 +0900 Subject: [PATCH 001/627] Change launchfile name carla_waypoint_ros_publisher.launch should be carla_waypoint_publisher.launch because that's the only one in the folder I'm assuming it's the right one. --- carla_waypoint_publisher/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_waypoint_publisher/README.md b/carla_waypoint_publisher/README.md index 1c4254d4..5c79a665 100644 --- a/carla_waypoint_publisher/README.md +++ b/carla_waypoint_publisher/README.md @@ -15,7 +15,7 @@ have to extend your PYTHONPATH. To run it: - roslaunch carla_waypoint_publisher carla_ros_waypoint_publisher.launch + roslaunch carla_waypoint_publisher carla_waypoint_publisher.launch ## Set a goal From 6afe9b249de9a78b14749b6bc66f4ab10b693dbe Mon Sep 17 00:00:00 2001 From: Vimal Date: Mon, 13 Jan 2020 12:46:42 +0530 Subject: [PATCH 002/627] Added new IMU Sensor --- carla_ego_vehicle/config/sensors.json | 5 ++ .../carla_ego_vehicle/carla_ego_vehicle.py | 4 ++ .../carla_infrastructure.py | 4 ++ .../src/carla_ros_bridge/bridge.py | 3 + carla_ros_bridge/src/carla_ros_bridge/imu.py | 62 +++++++++++++++++++ carla_ros_bridge/test/ros_bridge_client.py | 11 +++- 6 files changed, 88 insertions(+), 1 deletion(-) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/imu.py diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 9e004d1b..f4edb378 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -35,6 +35,11 @@ "id": "gnss1", "x": 1.0, "y": 0.0, "z": 2.0 }, + { + "type": "sensor.other.imu", + "id": "imu1", + "x": 0.0, "y": 0.0, "z": 0.0 + }, { "type": "sensor.other.collision", "id": "collision1", diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 00ae2dfb..74bb8c56 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -207,6 +207,10 @@ def setup_sensors(self, sensors): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() + elif sensor_spec['type'].startswith('sensor.other.imu'): + sensor_location = carla.Location(x=sensor_spec['y'], y=sensor_spec['y'], + z=sensor_spec['z']) + sensor_rotation = carla.Rotation() except KeyError as e: rospy.logfatal( "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 41998ff5..1a943193 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -97,6 +97,10 @@ def setup_sensors(self, sensors): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() + elif sensor_spec['type'].startswith('sensor.other.imu'): + sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], + z=sensor_spec['z']) + sensor_rotation = carla.Rotation() except KeyError as e: rospy.logfatal( "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 6a774535..a9399515 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -33,6 +33,7 @@ from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.lidar import Lidar from carla_ros_bridge.gnss import Gnss +from carla_ros_bridge.imu import ImuSensor from carla_ros_bridge.ego_vehicle import EgoVehicle from carla_ros_bridge.collision_sensor import CollisionSensor from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor @@ -382,6 +383,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + elif carla_actor.type_id.startswith("sensor.other.imu"): + actor = ImuSensor(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): actor = CollisionSensor( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py new file mode 100644 index 00000000..7a35d298 --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -0,0 +1,62 @@ +#!usr/bin/env python +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +Classes to handle Carla imu sensor +""" +import tf +from sensor_msgs.msg import Imu + +from carla_ros_bridge.sensor import Sensor +import carla_ros_bridge.transforms as trans + +class ImuSensor(Sensor): + """ + Actor implementation details for imu sensor + """ + + def __init__(self, carla_actor, parent, communication, synchronous_mode): + """ + Constructor + + :param carla_actor : carla actor object + :type carla_actor: carla.Actor + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param communication: communication-handle + :type communication: carla_ros_bridge.communication + :param synchronous_mode: use in synchronous mode? + :type synchronous_mode: bool + """ + super(ImuSensor, self).__init__(carla_actor=carla_actor, + parent=parent, + communication=communication, + synchronous_mode=synchronous_mode, + prefix="imu/" + carla_actor.attributes.get('role_name')) + + # pylint: disable=arguments-differ + def sensor_data_updated(self, carla_imu_measurement): + """ + Function to transform a recieved imu measurement into a ROS Imu message + + :param carla_imu_measurement: carla imu measurement object + :type carla_imu_measurement: carla.ImuMeasurement + """ + imu_msg = Imu() + imu_msg.header = self.get_msg_header(timestamp=carla_imu_measurement.timestamp) + + imu_msg.angular_velocity.x = carla_imu_measurement.gyroscope.x + imu_msg.angular_velocity.y = carla_imu_measurement.gyroscope.y + imu_msg.angular_velocity.z = carla_imu_measurement.gyroscope.z + + imu_msg.linear_acceleration.x = carla_imu_measurement.accelerometer.x + imu_msg.linear_acceleration.y = carla_imu_measurement.accelerometer.y + imu_msg.linear_acceleration.z = carla_imu_measurement.accelerometer.z + + quat = tf.transformations.quaternion_from_euler(0, 0, carla_imu_measurement.compass) + + imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) + self.publish_message( + self.get_topic_prefix() + "/imu_info", imu_msg) diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 94e90b9f..578ca4d4 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -12,7 +12,7 @@ import unittest from std_msgs.msg import Header from rosgraph_msgs.msg import Clock -from sensor_msgs.msg import CameraInfo, NavSatFix, Image, PointCloud2 +from sensor_msgs.msg import CameraInfo, NavSatFix, Image, PointCloud2, Imu from carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, CarlaActorList from geometry_msgs.msg import Quaternion, Vector3, Pose from nav_msgs.msg import Odometry @@ -65,6 +65,15 @@ def test_gnss(self): self.assertNotEqual(msg.longitude, 0.0) self.assertNotEqual(msg.altitude, 0.0) + def test_imu(self): + rospy.init_node('test_node', anonymous=True) + print("testing for ros bridge") + msg = rospy.wait_for_message("/carla/ego_vehicle/imu/imu1/imu_info", Imu, timeout=15) + self.assertEqual(msg.header.frame_id, "ego_vehicle/imu/imu1") + self.assertNotEqual(msg.linear_acceleration, 0.0) + self.assertNotEqual(msg.angular_velocity, 0.0) + self.assertNotEqual(msg.orientation, 0.0) + def test_camera_info(self): rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message("/carla/ego_vehicle/camera/rgb/front/camera_info", CameraInfo, timeout=15) From bf47922869cc87779fc2f45afed3b412bd5c31f8 Mon Sep 17 00:00:00 2001 From: Vimal Date: Mon, 13 Jan 2020 13:44:41 +0530 Subject: [PATCH 003/627] minor fixes --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 3 ++- carla_ros_bridge/src/carla_ros_bridge/imu.py | 6 +++--- carla_ros_bridge/test/ros_bridge_client.py | 2 +- 3 files changed, 6 insertions(+), 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index a9399515..fc7dc89c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -384,7 +384,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): - actor = ImuSensor(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = ImuSensor( + carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): actor = CollisionSensor( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 7a35d298..a2e575dd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -47,9 +47,9 @@ def sensor_data_updated(self, carla_imu_measurement): imu_msg = Imu() imu_msg.header = self.get_msg_header(timestamp=carla_imu_measurement.timestamp) - imu_msg.angular_velocity.x = carla_imu_measurement.gyroscope.x - imu_msg.angular_velocity.y = carla_imu_measurement.gyroscope.y - imu_msg.angular_velocity.z = carla_imu_measurement.gyroscope.z + imu_msg.angular_velocity.x = carla_imu_measurement.gyroscope.x + imu_msg.angular_velocity.y = carla_imu_measurement.gyroscope.y + imu_msg.angular_velocity.z = carla_imu_measurement.gyroscope.z imu_msg.linear_acceleration.x = carla_imu_measurement.accelerometer.x imu_msg.linear_acceleration.y = carla_imu_measurement.accelerometer.y diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 578ca4d4..0588388d 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -71,7 +71,7 @@ def test_imu(self): msg = rospy.wait_for_message("/carla/ego_vehicle/imu/imu1/imu_info", Imu, timeout=15) self.assertEqual(msg.header.frame_id, "ego_vehicle/imu/imu1") self.assertNotEqual(msg.linear_acceleration, 0.0) - self.assertNotEqual(msg.angular_velocity, 0.0) + self.assertNotEqual(msg.angular_velocity, 0.0) self.assertNotEqual(msg.orientation, 0.0) def test_camera_info(self): From d3541c79b90e6b5480f52105c26cdb5a5d30be38 Mon Sep 17 00:00:00 2001 From: Vimal Date: Mon, 13 Jan 2020 20:03:07 +0530 Subject: [PATCH 004/627] changed topic name of imu sensor and added noise parameters --- carla_ego_vehicle/config/sensors.json | 4 +++- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 13 +++++++++++-- carla_ros_bridge/src/carla_ros_bridge/imu.py | 12 +++++++++--- 3 files changed, 23 insertions(+), 6 deletions(-) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index f4edb378..9dedd396 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -38,7 +38,9 @@ { "type": "sensor.other.imu", "id": "imu1", - "x": 0.0, "y": 0.0, "z": 0.0 + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "noise_accel_stddev_x": 0.1, "noise_accel_stddev_y": 0.1, "noise_accel_stddev_z": 0.1, + "noise_gyro_stddev_x": 0.01, "noise_gyro_stddev_y": 0.01, "noise_gyro_stddev_z": 0.01 }, { "type": "sensor.other.collision", diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 74bb8c56..01040853 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -208,9 +208,18 @@ def setup_sensors(self, sensors): z=sensor_spec['z']) sensor_rotation = carla.Rotation() elif sensor_spec['type'].startswith('sensor.other.imu'): - sensor_location = carla.Location(x=sensor_spec['y'], y=sensor_spec['y'], + sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) - sensor_rotation = carla.Rotation() + sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], + roll=sensor_spec['roll'], + yaw=sensor_spec['yaw']) + bp.set_attribute('noise_accel_stddev_x', str(sensor_spec['noise_accel_stddev_x'])) + bp.set_attribute('noise_accel_stddev_y', str(sensor_spec['noise_accel_stddev_y'])) + bp.set_attribute('noise_accel_stddev_z', str(sensor_spec['noise_accel_stddev_z'])) + + bp.set_attribute('noise_gyro_stddev_x', str(sensor_spec['noise_gyro_stddev_x'])) + bp.set_attribute('noise_gyro_stddev_y', str(sensor_spec['noise_gyro_stddev_y'])) + bp.set_attribute('noise_gyro_stddev_z', str(sensor_spec['noise_gyro_stddev_z'])) except KeyError as e: rospy.logfatal( "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index a2e575dd..8c5ce33d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -6,7 +6,10 @@ """ Classes to handle Carla imu sensor """ +import math + import tf + from sensor_msgs.msg import Imu from carla_ros_bridge.sensor import Sensor @@ -34,7 +37,7 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): parent=parent, communication=communication, synchronous_mode=synchronous_mode, - prefix="imu/" + carla_actor.attributes.get('role_name')) + prefix="imu/") # pylint: disable=arguments-differ def sensor_data_updated(self, carla_imu_measurement): @@ -55,8 +58,11 @@ def sensor_data_updated(self, carla_imu_measurement): imu_msg.linear_acceleration.y = carla_imu_measurement.accelerometer.y imu_msg.linear_acceleration.z = carla_imu_measurement.accelerometer.z - quat = tf.transformations.quaternion_from_euler(0, 0, carla_imu_measurement.compass) + imu_rotation = carla_imu_measurement.transform.rotation + quat = tf.transformations.quaternion_from_euler(math.radians(imu_rotation.roll), + math.radians(imu_rotation.pitch), + math.radians(imu_rotation.yaw)) imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) self.publish_message( - self.get_topic_prefix() + "/imu_info", imu_msg) + self.get_topic_prefix(), imu_msg) From 04aaaf379e44205bd5bc37413c13ea25684fad2c Mon Sep 17 00:00:00 2001 From: Vimal Date: Mon, 13 Jan 2020 20:42:45 +0530 Subject: [PATCH 005/627] fix rostest issue --- carla_ros_bridge/src/carla_ros_bridge/imu.py | 6 +++--- carla_ros_bridge/test/ros_bridge_client.py | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 8c5ce33d..9b214b97 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -37,15 +37,15 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): parent=parent, communication=communication, synchronous_mode=synchronous_mode, - prefix="imu/") + prefix="imu") # pylint: disable=arguments-differ def sensor_data_updated(self, carla_imu_measurement): """ - Function to transform a recieved imu measurement into a ROS Imu message + Function to transform a received imu measurement into a ROS Imu message :param carla_imu_measurement: carla imu measurement object - :type carla_imu_measurement: carla.ImuMeasurement + :type carla_imu_measurement: carla.IMUMeasurement """ imu_msg = Imu() imu_msg.header = self.get_msg_header(timestamp=carla_imu_measurement.timestamp) diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 0588388d..c4467c57 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -68,8 +68,8 @@ def test_gnss(self): def test_imu(self): rospy.init_node('test_node', anonymous=True) print("testing for ros bridge") - msg = rospy.wait_for_message("/carla/ego_vehicle/imu/imu1/imu_info", Imu, timeout=15) - self.assertEqual(msg.header.frame_id, "ego_vehicle/imu/imu1") + msg = rospy.wait_for_message("/carla/ego_vehicle/imu", Imu, timeout=15) + self.assertEqual(msg.header.frame_id, "ego_vehicle/imu") self.assertNotEqual(msg.linear_acceleration, 0.0) self.assertNotEqual(msg.angular_velocity, 0.0) self.assertNotEqual(msg.orientation, 0.0) From 872f39e722375d74245b1e20691898b5de5ee194 Mon Sep 17 00:00:00 2001 From: Vimal Date: Tue, 14 Jan 2020 19:24:50 +0530 Subject: [PATCH 006/627] Added support for Radar Sensor --- carla_ego_vehicle/config/sensors.json | 9 +++ .../carla_ego_vehicle/carla_ego_vehicle.py | 11 ++++ .../carla_infrastructure.py | 11 ++++ carla_ros_bridge/CMakeLists.txt | 1 + carla_ros_bridge/package.xml | 1 + .../src/carla_ros_bridge/bridge.py | 3 + .../src/carla_ros_bridge/radar.py | 58 +++++++++++++++++++ carla_ros_bridge/test/ros_bridge_client.py | 6 ++ 8 files changed, 100 insertions(+) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/radar.py diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 9dedd396..2e900ac2 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -30,6 +30,15 @@ "rotation_frequency": 20, "sensor_tick": 0.05 }, + { + "type": "sensor.other.radar", + "id": "front", + "x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "horizontal_fov": 30.0, + "vertical_fov": 10.0, + "points_per_second": 1500, + "range": 100.0 + }, { "type": "sensor.other.gnss", "id": "gnss1", diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 01040853..bce9c1ca 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -220,6 +220,17 @@ def setup_sensors(self, sensors): bp.set_attribute('noise_gyro_stddev_x', str(sensor_spec['noise_gyro_stddev_x'])) bp.set_attribute('noise_gyro_stddev_y', str(sensor_spec['noise_gyro_stddev_y'])) bp.set_attribute('noise_gyro_stddev_z', str(sensor_spec['noise_gyro_stddev_z'])) + elif sensor_spec['type'].startswith('sensor.other.radar'): + sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], + z=sensor_spec['z']) + sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], + roll=sensor_spec['roll'], + yaw=sensor_spec['yaw']) + + bp.set_attribute('horizontal_fov', str(sensor_spec['horizontal_fov'])) + bp.set_attribute('vertical_fov', str(sensor_spec['vertical_fov'])) + bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) + bp.set_attribute('range', str(sensor_spec['range'])) except KeyError as e: rospy.logfatal( "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 1a943193..e0312913 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -101,6 +101,17 @@ def setup_sensors(self, sensors): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() + elif sensor_spec['type'].startswith('sensor.other.radar'): + sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], + z=sensor_spec['z']) + sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], + roll=sensor_spec['roll'], + yaw=sensor_spec['yaw']) + + bp.set_attribute('horizontal_fov', str(sensor_spec['horizontal_fov'])) + bp.set_attribute('vertical_fov', str(sensor_spec['vertical_fov'])) + bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) + bp.set_attribute('range', str(sensor_spec['range'])) except KeyError as e: rospy.logfatal( "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index aa759b64..fb76b2b1 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -7,6 +7,7 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs geometry_msgs derived_object_msgs + ainstein_radar_msgs tf roslaunch ) diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 426f6145..e94f23d1 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -7,6 +7,7 @@ MIT catkin roslaunch + ainstein_radar_msgs rospy sensor_msgs visualization_msgs diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index fc7dc89c..04711a0e 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -32,6 +32,7 @@ from carla_ros_bridge.traffic import Traffic, TrafficLight from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.lidar import Lidar +from carla_ros_bridge.radar import Radar from carla_ros_bridge.gnss import Gnss from carla_ros_bridge.imu import ImuSensor from carla_ros_bridge.ego_vehicle import EgoVehicle @@ -381,6 +382,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.lidar"): actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + elif carla_actor.type_id.startswith("sensor.other.radar"): + actor = Radar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py new file mode 100644 index 00000000..047a42ee --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -0,0 +1,58 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2019-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +Classes to handle Carla Radar +""" +import math + +from ainstein_radar_msgs.msg import RadarTarget, RadarTargetArray + +from carla_ros_bridge.sensor import Sensor + +class Radar(Sensor): + + """ + Actor implementation details of Carla RADAR + """ + def __init__(self, carla_actor, parent, communication, synchronous_mode): + """ + Constructor + :param carla_actor: carla actor object + :type carla_actor: carla.Actor + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param communication: communication-handle + :type communication: carla_ros_bridge.communication + :param synchronous_mode: use in synchronous mode? + :type synchronous_mode: bool + """ + super(Radar, self).__init__(carla_actor=carla_actor, + parent=parent, + communication=communication, + synchronous_mode=synchronous_mode, + prefix="radar/" + carla_actor.attributes.get('role_name')) + + # pylint: disable=arguments-differ + def sensor_data_updated(self, carla_radar_measurement): + """ + Function to transform the a received Radar measurement into a ROS message + + :param carla_radar_measurement: carla Radar measurement object + :type carla_radar_measurement: carla.RadarMeasurement + """ + radar_target_array = RadarTargetArray() + radar_target_array.header = self.get_msg_header(timestamp=carla_radar_measurement.timestamp) + for detection in carla_radar_measurement: + radar_target = RadarTarget() + radar_target.elevation = math.degrees(detection.altitude) + radar_target.speed = detection.velocity + radar_target.azimuth = math.degrees(detection.azimuth) + radar_target.range = detection.depth + radar_target_array.targets.append(radar_target) + self.publish_message(self.get_topic_prefix() + "/radar", radar_target_array) \ No newline at end of file diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index c4467c57..78e3b72b 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -18,6 +18,7 @@ from nav_msgs.msg import Odometry from derived_object_msgs.msg import ObjectArray from visualization_msgs.msg import Marker +from ainstein_radar_msgs.msg import RadarTargetArray class TestClock(unittest.TestCase): def test_clock(self): @@ -94,6 +95,11 @@ def test_lidar(self): msg = rospy.wait_for_message("/carla/ego_vehicle/lidar/lidar1/point_cloud", PointCloud2, timeout=15) self.assertEqual(msg.header.frame_id, "ego_vehicle/lidar/lidar1") + def test_radar(self): + rospy.init_node('test_node', anonymous=True) + msg = rospy.wait_for_message("/carla/ego_vehicle/radar/front/radar", RadarTargetArray, timeout=15) + self.assertEqual(msg.header.frame_id, "ego_vehicle/radar/front") + def test_ego_vehicle_objects(self): rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message("/carla/ego_vehicle/objects", ObjectArray, timeout=15) From 93c300847caea89ddc20e217ce0eba7314abc226 Mon Sep 17 00:00:00 2001 From: Vimal Date: Wed, 15 Jan 2020 15:59:48 +0530 Subject: [PATCH 007/627] Updated README with Radar and IMU sensors --- README.md | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 7f359a54..fbd76b57 100644 --- a/README.md +++ b/README.md @@ -134,11 +134,25 @@ Currently the following sensors are supported: |--------------------------------------|------| | `/carla//lidar//point_cloud` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | +#### Radar + +|Topic | Type | +|--------------------------------------|------| +| `/carla//radar//radar` | [ainstein_radar_msgs.RadarTargetArray](https://github.com/AinsteinAI/ainstein_radar/blob/master/ainstein_radar_msgs/msg/RadarTargetArray.msg) | + +Radar data can be visualized on rviz using [ainstein_radar_rviz_plugins](https://wiki.ros.org/ainstein_radar_rviz_plugins). + +#### IMU + +|Topic | Type | +|--------------------------------------|------| +| `/carla//imu` | [sensor_msgs.Imu](https://docs.ros.org/melodic/api/sensor_msgs/html/msg/Imu.html) | + #### GNSS |Topic | Type | Description | |--------------------------------------|------|-------------| -| `/carla//gnss/front/gnss` | [sensor_msgs.NavSatFix](http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html) | publish gnss location | +| `/carla//gnss//fix` | [sensor_msgs.NavSatFix](http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html) | publish gnss location | #### Collision Sensor From 49655d6952c7bb396d8a3e7570687b47973d99cd Mon Sep 17 00:00:00 2001 From: Vimal Date: Fri, 17 Jan 2020 16:58:09 +0530 Subject: [PATCH 008/627] additional attributes for Gnss and Camera sensor --- .pylintrc | 2 +- CHANGELOG.md | 11 +++ carla_ego_vehicle/config/sensors.json | 83 +++++++++++++++++-- .../carla_ego_vehicle/carla_ego_vehicle.py | 62 +++++++++++++- carla_infrastructure/config/sensors.json | 39 ++++++++- .../carla_infrastructure.py | 64 +++++++++++++- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 14 ++-- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 + .../src/carla_ros_bridge/radar.py | 4 +- 9 files changed, 261 insertions(+), 20 deletions(-) diff --git a/.pylintrc b/.pylintrc index 3585ae0e..3c916da6 100644 --- a/.pylintrc +++ b/.pylintrc @@ -1,6 +1,6 @@ [TYPECHECK] ignored-modules=numpy,carla,pygame,agents -disable=logging-format-interpolation,locally-disabled,cyclic-import,too-many-instance-attributes,invalid-name,no-else-return +disable=logging-format-interpolation,locally-disabled,cyclic-import,too-many-instance-attributes,invalid-name,no-else-return,too-many-statements [SIMILARITIES] min-similarity-lines=9 diff --git a/CHANGELOG.md b/CHANGELOG.md index 83ea2d9a..cddcc537 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,16 @@ ## Latest changed +* change Lidar range in meters +* add new attributes for Gnss and Camera sensor +* add IMU and Radar sensor + +## CARLA-ROS-Bridge 0.9.6 + +* remove launchfile check from rqt_carla_control +* Add roslaunch check to all nodes +* support kinetic and melodic +* added possibility to connect to an existing ego vehicle +* support different ego vehicle rolenames in pclrecorder * publish odometry for all traffic participants * support drawing markers in CARLA * replace /carla/map (msg: CarlaMapInfo) by /carla/world_info (msg: CarlaWorldInfo) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 2e900ac2..3d09bd66 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -7,7 +7,42 @@ "width": 800, "height": 600, "fov": 100, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 60.0, + "iso": 1200.0, + "fstop": 1.4, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "manual", + "exposure_compensation": 3.0, + "exposure_min_bright": 0.1, + "exposure_max_bright": 2.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 }, { "type": "sensor.camera.rgb", @@ -16,13 +51,48 @@ "width": 800, "height": 600, "fov": 100, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 60.0, + "iso": 1200.0, + "fstop": 1.4, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "manual", + "exposure_compensation": 3.0, + "exposure_min_bright": 0.1, + "exposure_max_bright": 2.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 }, { "type": "sensor.lidar.ray_cast", "id": "lidar1", "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 5000, + "range": 50, "channels": 32, "points_per_second": 320000, "upper_fov": 2.0, @@ -42,14 +112,17 @@ { "type": "sensor.other.gnss", "id": "gnss1", - "x": 1.0, "y": 0.0, "z": 2.0 + "x": 1.0, "y": 0.0, "z": 2.0, + "noise_alt_stddev": 0.1, "noise_lat_stddev": 0.1, "noise_lon_stddev": 0.1, + "noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0 }, { "type": "sensor.other.imu", "id": "imu1", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "noise_accel_stddev_x": 0.1, "noise_accel_stddev_y": 0.1, "noise_accel_stddev_z": 0.1, - "noise_gyro_stddev_x": 0.01, "noise_gyro_stddev_y": 0.01, "noise_gyro_stddev_z": 0.01 + "noise_gyro_stddev_x": 0.01, "noise_gyro_stddev_y": 0.01, "noise_gyro_stddev_z": 0.01, + "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 }, { "type": "sensor.other.collision", diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index bce9c1ca..8bea8879 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -178,6 +178,50 @@ def setup_sensors(self, sensors): bp.set_attribute('image_size_x', str(sensor_spec['width'])) bp.set_attribute('image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) + bp.set_attribute('gamma', str(sensor_spec['gamma'])) + bp.set_attribute('shutter_speed', str(sensor_spec['shutter_speed'])) + bp.set_attribute('iso', str(sensor_spec['iso'])) + bp.set_attribute('fstop', str(sensor_spec['fstop'])) + bp.set_attribute('min_fstop', str(sensor_spec['min_fstop'])) + bp.set_attribute('blade_count', str(sensor_spec['blade_count'])) + bp.set_attribute('exposure_mode', str(sensor_spec['exposure_mode'])) + bp.set_attribute('exposure_compensation', str( + sensor_spec['exposure_compensation'])) + bp.set_attribute('exposure_min_bright', str(sensor_spec['exposure_min_bright'])) + bp.set_attribute('exposure_max_bright', str(sensor_spec['exposure_max_bright'])) + bp.set_attribute('exposure_speed_up', str(sensor_spec['exposure_speed_up'])) + bp.set_attribute('exposure_speed_down', str(sensor_spec['exposure_speed_down'])) + bp.set_attribute('calibration_constant', str( + sensor_spec['calibration_constant'])) + bp.set_attribute('focal_distance', str(sensor_spec['focal_distance'])) + bp.set_attribute('blur_amount', str(sensor_spec['blur_amount'])) + bp.set_attribute('blur_radius', str(sensor_spec['blur_radius'])) + bp.set_attribute('motion_blur_intensity', str( + sensor_spec['motion_blur_intensity'])) + bp.set_attribute('motion_blur_max_distortion', str( + sensor_spec['motion_blur_max_distortion'])) + bp.set_attribute('motion_blur_min_object_screen_size', str( + sensor_spec['motion_blur_min_object_screen_size'])) + bp.set_attribute('slope', str(sensor_spec['slope'])) + bp.set_attribute('toe', str(sensor_spec['toe'])) + bp.set_attribute('shoulder', str(sensor_spec['shoulder'])) + bp.set_attribute('black_clip', str(sensor_spec['black_clip'])) + bp.set_attribute('white_clip', str(sensor_spec['white_clip'])) + bp.set_attribute('temp', str(sensor_spec['temp'])) + bp.set_attribute('tint', str(sensor_spec['tint'])) + bp.set_attribute('chromatic_aberration_intensity', str( + sensor_spec['chromatic_aberration_intensity'])) + bp.set_attribute('chromatic_aberration_offset', str( + sensor_spec['chromatic_aberration_offset'])) + bp.set_attribute('enable_postprocess_effects', str( + sensor_spec['enable_postprocess_effects'])) + bp.set_attribute('lens_circle_falloff', str(sensor_spec['lens_circle_falloff'])) + bp.set_attribute('lens_circle_multiplier', str( + sensor_spec['lens_circle_multiplier'])) + bp.set_attribute('lens_k', str(sensor_spec['lens_k'])) + bp.set_attribute('lens_kcube', str(sensor_spec['lens_kcube'])) + bp.set_attribute('lens_x_size', str(sensor_spec['lens_x_size'])) + bp.set_attribute('lens_y_size', str(sensor_spec['lens_y_size'])) try: bp.set_attribute('sensor_tick', str(sensor_spec['sensor_tick'])) except KeyError: @@ -207,19 +251,31 @@ def setup_sensors(self, sensors): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() + bp.set_attribute('noise_alt_stddev', str(sensor_spec['noise_alt_stddev'])) + bp.set_attribute('noise_lat_stddev', str(sensor_spec['noise_lat_stddev'])) + bp.set_attribute('noise_lon_stddev', str(sensor_spec['noise_lon_stddev'])) + bp.set_attribute('noise_alt_bias', str(sensor_spec['noise_alt_bias'])) + bp.set_attribute('noise_lat_bias', str(sensor_spec['noise_lat_bias'])) + bp.set_attribute('noise_lon_bias', str(sensor_spec['noise_lon_bias'])) elif sensor_spec['type'].startswith('sensor.other.imu'): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) - bp.set_attribute('noise_accel_stddev_x', str(sensor_spec['noise_accel_stddev_x'])) - bp.set_attribute('noise_accel_stddev_y', str(sensor_spec['noise_accel_stddev_y'])) - bp.set_attribute('noise_accel_stddev_z', str(sensor_spec['noise_accel_stddev_z'])) + bp.set_attribute('noise_accel_stddev_x', + str(sensor_spec['noise_accel_stddev_x'])) + bp.set_attribute('noise_accel_stddev_y', + str(sensor_spec['noise_accel_stddev_y'])) + bp.set_attribute('noise_accel_stddev_z', + str(sensor_spec['noise_accel_stddev_z'])) bp.set_attribute('noise_gyro_stddev_x', str(sensor_spec['noise_gyro_stddev_x'])) bp.set_attribute('noise_gyro_stddev_y', str(sensor_spec['noise_gyro_stddev_y'])) bp.set_attribute('noise_gyro_stddev_z', str(sensor_spec['noise_gyro_stddev_z'])) + bp.set_attribute('noise_gyro_bias_x', str(sensor_spec['noise_gyro_bias_x'])) + bp.set_attribute('noise_gyro_bias_y', str(sensor_spec['noise_gyro_bias_y'])) + bp.set_attribute('noise_gyro_bias_z', str(sensor_spec['noise_gyro_bias_z'])) elif sensor_spec['type'].startswith('sensor.other.radar'): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) diff --git a/carla_infrastructure/config/sensors.json b/carla_infrastructure/config/sensors.json index a3954090..59a3d517 100644 --- a/carla_infrastructure/config/sensors.json +++ b/carla_infrastructure/config/sensors.json @@ -6,13 +6,48 @@ "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "width": 800, "height": 600, - "fov": 100 + "fov": 100, + "gamma": 2.2, + "shutter_speed": 60.0, + "iso": 1200.0, + "fstop": 1.4, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "manual", + "exposure_compensation": 3.0, + "exposure_min_bright": 0.1, + "exposure_max_bright": 2.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 }, { "type": "sensor.lidar.ray_cast", "id": "lidar01", "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 5000, + "range": 50, "channels": 32, "points_per_second": 320000, "upper_fov": 2.0, diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index e0312913..285a5922 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -74,8 +74,70 @@ def setup_sensors(self, sensors): bp.set_attribute('role_name', str(sensor_spec['id'])) if sensor_spec['type'].startswith('sensor.camera'): bp.set_attribute('image_size_x', str(sensor_spec['width'])) - bp.set_attribute('image_size_y', str(sensor_spec['height'])) + bp.set_attribute( + 'image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) + bp.set_attribute('gamma', str(sensor_spec['gamma'])) + bp.set_attribute('shutter_speed', str( + sensor_spec['shutter_speed'])) + bp.set_attribute('iso', str(sensor_spec['iso'])) + bp.set_attribute('fstop', str(sensor_spec['fstop'])) + bp.set_attribute('min_fstop', str( + sensor_spec['min_fstop'])) + bp.set_attribute('blade_count', str( + sensor_spec['blade_count'])) + bp.set_attribute('exposure_mode', str( + sensor_spec['exposure_mode'])) + bp.set_attribute('exposure_compensation', str( + sensor_spec['exposure_compensation'])) + bp.set_attribute('exposure_min_bright', str( + sensor_spec['exposure_min_bright'])) + bp.set_attribute('exposure_max_bright', str( + sensor_spec['exposure_max_bright'])) + bp.set_attribute('exposure_speed_up', str( + sensor_spec['exposure_speed_up'])) + bp.set_attribute('exposure_speed_down', str( + sensor_spec['exposure_speed_down'])) + bp.set_attribute('calibration_constant', str( + sensor_spec['calibration_constant'])) + bp.set_attribute('focal_distance', str( + sensor_spec['focal_distance'])) + bp.set_attribute('blur_amount', str( + sensor_spec['blur_amount'])) + bp.set_attribute('blur_radius', str( + sensor_spec['blur_radius'])) + bp.set_attribute('motion_blur_intensity', str( + sensor_spec['motion_blur_intensity'])) + bp.set_attribute('motion_blur_max_distortion', str( + sensor_spec['motion_blur_max_distortion'])) + bp.set_attribute('motion_blur_min_object_screen_size', str( + sensor_spec['motion_blur_min_object_screen_size'])) + bp.set_attribute('slope', str(sensor_spec['slope'])) + bp.set_attribute('toe', str(sensor_spec['toe'])) + bp.set_attribute('shoulder', str(sensor_spec['shoulder'])) + bp.set_attribute('black_clip', str( + sensor_spec['black_clip'])) + bp.set_attribute('white_clip', str( + sensor_spec['white_clip'])) + bp.set_attribute('temp', str(sensor_spec['temp'])) + bp.set_attribute('tint', str(sensor_spec['tint'])) + bp.set_attribute('chromatic_aberration_intensity', str( + sensor_spec['chromatic_aberration_intensity'])) + bp.set_attribute('chromatic_aberration_offset', str( + sensor_spec['chromatic_aberration_offset'])) + bp.set_attribute('enable_postprocess_effects', str( + sensor_spec['enable_postprocess_effects'])) + bp.set_attribute('lens_circle_falloff', str( + sensor_spec['lens_circle_falloff'])) + bp.set_attribute('lens_circle_multiplier', str( + sensor_spec['lens_circle_multiplier'])) + bp.set_attribute('lens_k', str(sensor_spec['lens_k'])) + bp.set_attribute('lens_kcube', str( + sensor_spec['lens_kcube'])) + bp.set_attribute('lens_x_size', str( + sensor_spec['lens_x_size'])) + bp.set_attribute('lens_y_size', str( + sensor_spec['lens_y_size'])) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index a7c058f3..49a8cc52 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -41,17 +41,17 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): prefix="gnss/" + carla_actor.attributes.get('role_name')) # pylint: disable=arguments-differ - def sensor_data_updated(self, carla_gnss_event): + def sensor_data_updated(self, carla_gnss_measurement): """ Function to transform a received gnss event into a ROS NavSatFix message - :param carla_gnss_event: carla gnss event object - :type carla_gnss_event: carla.GnssEvent + :param carla_gnss_measurement: carla gnss measurement object + :type carla_gnss_measurement: carla.GnssMeasurement """ navsatfix_msg = NavSatFix() - navsatfix_msg.header = self.get_msg_header(timestamp=carla_gnss_event.timestamp) - navsatfix_msg.latitude = carla_gnss_event.latitude - navsatfix_msg.longitude = carla_gnss_event.longitude - navsatfix_msg.altitude = carla_gnss_event.altitude + navsatfix_msg.header = self.get_msg_header(timestamp=carla_gnss_measurement.timestamp) + navsatfix_msg.latitude = carla_gnss_measurement.latitude + navsatfix_msg.longitude = carla_gnss_measurement.longitude + navsatfix_msg.altitude = carla_gnss_measurement.altitude self.publish_message( self.get_topic_prefix() + "/fix", navsatfix_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 9b214b97..83f0e4e7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -15,7 +15,9 @@ from carla_ros_bridge.sensor import Sensor import carla_ros_bridge.transforms as trans + class ImuSensor(Sensor): + """ Actor implementation details for imu sensor """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 047a42ee..65d042cc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -15,11 +15,13 @@ from carla_ros_bridge.sensor import Sensor + class Radar(Sensor): """ Actor implementation details of Carla RADAR """ + def __init__(self, carla_actor, parent, communication, synchronous_mode): """ Constructor @@ -55,4 +57,4 @@ def sensor_data_updated(self, carla_radar_measurement): radar_target.azimuth = math.degrees(detection.azimuth) radar_target.range = detection.depth radar_target_array.targets.append(radar_target) - self.publish_message(self.get_topic_prefix() + "/radar", radar_target_array) \ No newline at end of file + self.publish_message(self.get_topic_prefix() + "/radar", radar_target_array) From 1827c6229d3a80adee57741ac3f10ee2482d5bd2 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Tue, 21 Jan 2020 15:14:29 +0100 Subject: [PATCH 009/627] fix camera properties for depth and segmentation cameras --- .../carla_ego_vehicle/carla_ego_vehicle.py | 89 ++++++++++--------- 1 file changed, 45 insertions(+), 44 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 8bea8879..3a2e3fd7 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -178,50 +178,6 @@ def setup_sensors(self, sensors): bp.set_attribute('image_size_x', str(sensor_spec['width'])) bp.set_attribute('image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) - bp.set_attribute('gamma', str(sensor_spec['gamma'])) - bp.set_attribute('shutter_speed', str(sensor_spec['shutter_speed'])) - bp.set_attribute('iso', str(sensor_spec['iso'])) - bp.set_attribute('fstop', str(sensor_spec['fstop'])) - bp.set_attribute('min_fstop', str(sensor_spec['min_fstop'])) - bp.set_attribute('blade_count', str(sensor_spec['blade_count'])) - bp.set_attribute('exposure_mode', str(sensor_spec['exposure_mode'])) - bp.set_attribute('exposure_compensation', str( - sensor_spec['exposure_compensation'])) - bp.set_attribute('exposure_min_bright', str(sensor_spec['exposure_min_bright'])) - bp.set_attribute('exposure_max_bright', str(sensor_spec['exposure_max_bright'])) - bp.set_attribute('exposure_speed_up', str(sensor_spec['exposure_speed_up'])) - bp.set_attribute('exposure_speed_down', str(sensor_spec['exposure_speed_down'])) - bp.set_attribute('calibration_constant', str( - sensor_spec['calibration_constant'])) - bp.set_attribute('focal_distance', str(sensor_spec['focal_distance'])) - bp.set_attribute('blur_amount', str(sensor_spec['blur_amount'])) - bp.set_attribute('blur_radius', str(sensor_spec['blur_radius'])) - bp.set_attribute('motion_blur_intensity', str( - sensor_spec['motion_blur_intensity'])) - bp.set_attribute('motion_blur_max_distortion', str( - sensor_spec['motion_blur_max_distortion'])) - bp.set_attribute('motion_blur_min_object_screen_size', str( - sensor_spec['motion_blur_min_object_screen_size'])) - bp.set_attribute('slope', str(sensor_spec['slope'])) - bp.set_attribute('toe', str(sensor_spec['toe'])) - bp.set_attribute('shoulder', str(sensor_spec['shoulder'])) - bp.set_attribute('black_clip', str(sensor_spec['black_clip'])) - bp.set_attribute('white_clip', str(sensor_spec['white_clip'])) - bp.set_attribute('temp', str(sensor_spec['temp'])) - bp.set_attribute('tint', str(sensor_spec['tint'])) - bp.set_attribute('chromatic_aberration_intensity', str( - sensor_spec['chromatic_aberration_intensity'])) - bp.set_attribute('chromatic_aberration_offset', str( - sensor_spec['chromatic_aberration_offset'])) - bp.set_attribute('enable_postprocess_effects', str( - sensor_spec['enable_postprocess_effects'])) - bp.set_attribute('lens_circle_falloff', str(sensor_spec['lens_circle_falloff'])) - bp.set_attribute('lens_circle_multiplier', str( - sensor_spec['lens_circle_multiplier'])) - bp.set_attribute('lens_k', str(sensor_spec['lens_k'])) - bp.set_attribute('lens_kcube', str(sensor_spec['lens_kcube'])) - bp.set_attribute('lens_x_size', str(sensor_spec['lens_x_size'])) - bp.set_attribute('lens_y_size', str(sensor_spec['lens_y_size'])) try: bp.set_attribute('sensor_tick', str(sensor_spec['sensor_tick'])) except KeyError: @@ -231,6 +187,51 @@ def setup_sensors(self, sensors): sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) + if sensor_spec['type'].startswith('sensor.camera.rgb'): + bp.set_attribute('gamma', str(sensor_spec['gamma'])) + bp.set_attribute('shutter_speed', str(sensor_spec['shutter_speed'])) + bp.set_attribute('iso', str(sensor_spec['iso'])) + bp.set_attribute('fstop', str(sensor_spec['fstop'])) + bp.set_attribute('min_fstop', str(sensor_spec['min_fstop'])) + bp.set_attribute('blade_count', str(sensor_spec['blade_count'])) + bp.set_attribute('exposure_mode', str(sensor_spec['exposure_mode'])) + bp.set_attribute('exposure_compensation', str( + sensor_spec['exposure_compensation'])) + bp.set_attribute('exposure_min_bright', str(sensor_spec['exposure_min_bright'])) + bp.set_attribute('exposure_max_bright', str(sensor_spec['exposure_max_bright'])) + bp.set_attribute('exposure_speed_up', str(sensor_spec['exposure_speed_up'])) + bp.set_attribute('exposure_speed_down', str(sensor_spec['exposure_speed_down'])) + bp.set_attribute('calibration_constant', str( + sensor_spec['calibration_constant'])) + bp.set_attribute('focal_distance', str(sensor_spec['focal_distance'])) + bp.set_attribute('blur_amount', str(sensor_spec['blur_amount'])) + bp.set_attribute('blur_radius', str(sensor_spec['blur_radius'])) + bp.set_attribute('motion_blur_intensity', str( + sensor_spec['motion_blur_intensity'])) + bp.set_attribute('motion_blur_max_distortion', str( + sensor_spec['motion_blur_max_distortion'])) + bp.set_attribute('motion_blur_min_object_screen_size', str( + sensor_spec['motion_blur_min_object_screen_size'])) + bp.set_attribute('slope', str(sensor_spec['slope'])) + bp.set_attribute('toe', str(sensor_spec['toe'])) + bp.set_attribute('shoulder', str(sensor_spec['shoulder'])) + bp.set_attribute('black_clip', str(sensor_spec['black_clip'])) + bp.set_attribute('white_clip', str(sensor_spec['white_clip'])) + bp.set_attribute('temp', str(sensor_spec['temp'])) + bp.set_attribute('tint', str(sensor_spec['tint'])) + bp.set_attribute('chromatic_aberration_intensity', str( + sensor_spec['chromatic_aberration_intensity'])) + bp.set_attribute('chromatic_aberration_offset', str( + sensor_spec['chromatic_aberration_offset'])) + bp.set_attribute('enable_postprocess_effects', str( + sensor_spec['enable_postprocess_effects'])) + bp.set_attribute('lens_circle_falloff', str(sensor_spec['lens_circle_falloff'])) + bp.set_attribute('lens_circle_multiplier', str( + sensor_spec['lens_circle_multiplier'])) + bp.set_attribute('lens_k', str(sensor_spec['lens_k'])) + bp.set_attribute('lens_kcube', str(sensor_spec['lens_kcube'])) + bp.set_attribute('lens_x_size', str(sensor_spec['lens_x_size'])) + bp.set_attribute('lens_y_size', str(sensor_spec['lens_y_size'])) elif sensor_spec['type'].startswith('sensor.lidar'): bp.set_attribute('range', str(sensor_spec['range'])) bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) From 169bde453b9afbf5e279e8256703fb7e6f2ded6e Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Tue, 21 Jan 2020 15:46:54 +0100 Subject: [PATCH 010/627] fix python format issues --- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 3a2e3fd7..90c0b6ce 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -197,10 +197,13 @@ def setup_sensors(self, sensors): bp.set_attribute('exposure_mode', str(sensor_spec['exposure_mode'])) bp.set_attribute('exposure_compensation', str( sensor_spec['exposure_compensation'])) - bp.set_attribute('exposure_min_bright', str(sensor_spec['exposure_min_bright'])) - bp.set_attribute('exposure_max_bright', str(sensor_spec['exposure_max_bright'])) + bp.set_attribute('exposure_min_bright', str( + sensor_spec['exposure_min_bright'])) + bp.set_attribute('exposure_max_bright', str( + sensor_spec['exposure_max_bright'])) bp.set_attribute('exposure_speed_up', str(sensor_spec['exposure_speed_up'])) - bp.set_attribute('exposure_speed_down', str(sensor_spec['exposure_speed_down'])) + bp.set_attribute('exposure_speed_down', str( + sensor_spec['exposure_speed_down'])) bp.set_attribute('calibration_constant', str( sensor_spec['calibration_constant'])) bp.set_attribute('focal_distance', str(sensor_spec['focal_distance'])) @@ -225,7 +228,8 @@ def setup_sensors(self, sensors): sensor_spec['chromatic_aberration_offset'])) bp.set_attribute('enable_postprocess_effects', str( sensor_spec['enable_postprocess_effects'])) - bp.set_attribute('lens_circle_falloff', str(sensor_spec['lens_circle_falloff'])) + bp.set_attribute('lens_circle_falloff', str( + sensor_spec['lens_circle_falloff'])) bp.set_attribute('lens_circle_multiplier', str( sensor_spec['lens_circle_multiplier'])) bp.set_attribute('lens_k', str(sensor_spec['lens_k'])) From c37e4b61cd776efeb09a69a52515a47ccac0c07d Mon Sep 17 00:00:00 2001 From: Vimal Date: Thu, 23 Jan 2020 19:01:26 +0530 Subject: [PATCH 011/627] fix codacy --- CHANGELOG.md | 88 ++++--- README.md | 221 ++++++++---------- carla_ackermann_control/README.md | 26 +-- carla_ackermann_control/setup.py | 5 +- carla_ego_vehicle/README.md | 7 +- carla_ego_vehicle/setup.py | 5 +- .../carla_ego_vehicle/carla_ego_vehicle.py | 10 +- carla_infrastructure/README.md | 1 - carla_infrastructure/setup.py | 5 +- .../carla_infrastructure.py | 8 +- carla_manual_control/README.md | 10 +- carla_manual_control/setup.py | 5 +- .../carla_manual_control.py | 32 ++- carla_ros_bridge/setup.py | 5 +- .../src/carla_ros_bridge/bridge.py | 2 +- .../src/carla_ros_bridge/vehicle.py | 2 +- carla_ros_bridge/test/ros_bridge_client.py | 106 +++++++-- carla_waypoint_publisher/README.md | 8 +- carla_waypoint_publisher/setup.py | 5 + pcl_recorder/README.md | 3 - rqt_carla_control/README.md | 1 - rqt_carla_control/setup.py | 5 + 22 files changed, 316 insertions(+), 244 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index cddcc537..fec62ea0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,62 +1,60 @@ ## Latest changed -* change Lidar range in meters -* add new attributes for Gnss and Camera sensor -* add IMU and Radar sensor +* change Lidar range in meters +* add new attributes for Gnss and Camera sensor +* add IMU and Radar sensor ## CARLA-ROS-Bridge 0.9.6 -* remove launchfile check from rqt_carla_control -* Add roslaunch check to all nodes -* support kinetic and melodic -* added possibility to connect to an existing ego vehicle -* support different ego vehicle rolenames in pclrecorder -* publish odometry for all traffic participants -* support drawing markers in CARLA -* replace /carla/map (msg: CarlaMapInfo) by /carla/world_info (msg: CarlaWorldInfo) -* added option to reload the CARLA world -* added node to spawn infrastructure sensors -* rename /carla/vehicle_marker to /carla/marker (and include walkers) -* support walkers -* create rqt plugin to control synchronous mode -* support synchronous mode -* publish CarlaStatus -* remove global_id mapping -* publish /carla/actor_list -* carla_ego_vehicle: support sensor_tick within camera/lidar definition -* support twist_cmd to set velocity of ego vehicle (without respecting the vehicle constraints) +* remove launchfile check from rqt_carla_control +* Add roslaunch check to all nodes +* support kinetic and melodic +* added possibility to connect to an existing ego vehicle +* support different ego vehicle rolenames in pclrecorder +* publish odometry for all traffic participants +* support drawing markers in CARLA +* replace /carla/map (msg: CarlaMapInfo) by /carla/world_info (msg: CarlaWorldInfo) +* added option to reload the CARLA world +* added node to spawn infrastructure sensors +* rename /carla/vehicle_marker to /carla/marker (and include walkers) +* support walkers +* create rqt plugin to control synchronous mode +* support synchronous mode +* publish CarlaStatus +* remove global_id mapping +* publish /carla/actor_list +* carla_ego_vehicle: support sensor_tick within camera/lidar definition +* support twist_cmd to set velocity of ego vehicle (without respecting the vehicle constraints) ## CARLA-ROS-Bridge 0.9.5.1 -* add id to CarlaEgoVehicleInfo datatype -* rename carla_ros_bridge_msgs to carla_msgs -* remove 'challenge' mode +* add id to CarlaEgoVehicleInfo datatype +* rename carla_ros_bridge_msgs to carla_msgs +* remove 'challenge' mode ## CARLA-ROS-Bridge 0.9.5 -* rename gnss topic from '../gnss' to '../fix' -* Add lane invasion sensor -* Add collision sensor -* Rename CarlaVehicleControl to CarlaEgoVehicleControl (and add some more message types) -* move PID controller into separate ROS node -* Add challenge mode -* Split actor-monitoring + data publishing -* Use sensor data timestamp -* support simple-pid 0.1.5 - +* rename gnss topic from '../gnss' to '../fix' +* Add lane invasion sensor +* Add collision sensor +* Rename CarlaVehicleControl to CarlaEgoVehicleControl (and add some more message types) +* move PID controller into separate ROS node +* Add challenge mode +* Split actor-monitoring + data publishing +* Use sensor data timestamp +* support simple-pid 0.1.5 ## CARLA-ROS-Bridge 0.9.3 -* Send vehicle commands to CARLA, only when a ROS command provider is available -* Added interface for GNSS sensor - +* Send vehicle commands to CARLA, only when a ROS command provider is available +* Added interface for GNSS sensor ## CARLA-ROS-Bridge 0.9.2 -* Updated ROS-bridge to PythonAPI of CARLA 0.9.x - * Supported sensors: LiDAR, RGB camera, depth camera, segmentation camera - * Vehicle control options: Ackermann-command or Throttle/Brake/Steering - * Added PID controller to convert Ackermann-command into Throttle/Brake/Steering - * RViz support - * Publish TF tree, map, CARLA clock - * Separate ROS topic for each vehicle +* Updated ROS-bridge to PythonAPI of CARLA 0.9.x +* Supported sensors: LiDAR, RGB camera, depth camera, segmentation camera +* Vehicle control options: Ackermann-command or Throttle/Brake/Steering +* Added PID controller to convert Ackermann-command into Throttle/Brake/Steering +* RViz support +* Publish TF tree, map, CARLA clock +* Separate ROS topic for each vehicle diff --git a/README.md b/README.md index fbd76b57..94a3d485 100644 --- a/README.md +++ b/README.md @@ -1,31 +1,29 @@ - # ROS bridge for CARLA simulator This ROS package aims at providing a simple ROS bridge for CARLA simulator. -__Important Note:__ -This documentation is for CARLA versions *newer* than 0.9.4. +**Important Note:** +This documentation is for CARLA versions _newer_ than 0.9.4. ![rviz setup](./docs/images/rviz_carla_default.png "rviz") ![depthcloud](./docs/images/depth_cloud_and_lidar.png "depthcloud") ![short video](https://youtu.be/S_NoN2GBtdY) +## Features -# Features - -- [x] Cameras (depth, segmentation, rgb) support -- [x] Transform publications -- [x] Manual control using ackermann msg -- [x] Handle ROS dependencies -- [x] Marker/bounding box messages for cars/pedestrian -- [x] Lidar sensor support -- [x] Support CARLA synchronous mode -- [ ] Add traffic light support +- [x] Cameras (depth, segmentation, rgb) support +- [x] Transform publications +- [x] Manual control using ackermann msg +- [x] Handle ROS dependencies +- [x] Marker/bounding box messages for cars/pedestrian +- [x] Lidar sensor support +- [x] Support CARLA synchronous mode +- [ ] Add traffic light support -# Setup +## Setup -## Create a catkin workspace and install carla_ros_bridge package +### Create a catkin workspace and install carla_ros_bridge package #setup folder structure mkdir -p ~/carla-ros-bridge/catkin_ws/src @@ -44,15 +42,14 @@ This documentation is for CARLA versions *newer* than 0.9.4. catkin_make For more information about configuring a ROS environment see -http://wiki.ros.org/ROS/Tutorials/InstallingandConfiguringROSEnvironment + -# Start the ROS bridge +## Start the ROS bridge -First run the simulator (see carla documentation: http://carla.readthedocs.io/en/latest/) +First run the simulator (see carla documentation: ) ./CarlaUE4.sh -windowed -ResX=320 -ResY=240 - Wait for the message: Waiting for the client to connect... @@ -71,23 +68,22 @@ Then start the ros bridge (choose one option): # Option 3: start the ros bridge together with an example ego vehicle roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch -# Settings +## Settings You can setup the ros bridge configuration [carla_ros_bridge/config/settings.yaml](carla_ros_bridge/config/settings.yaml). If the rolename is within the list specified by ROS parameter `/carla/ego_vehicle/rolename`, the client is interpreted as an controllable ego vehicle and all relevant ROS topics are created. -## Mode +### Mode -### Default Mode +#### Default Mode In default mode (`synchronous_mode: false`) data is published: - - on every `world.on_tick()` callback - - on every `sensor.listen()` callback - +- on every `world.on_tick()` callback +- on every `sensor.listen()` callback -### Synchronous Mode +#### Synchronous Mode CAUTION: In synchronous mode, only the ros-bridge is allowed to tick. Other CARLA clients must passively wait. @@ -95,103 +91,101 @@ In synchronous mode (`synchronous_mode: true`), the bridge waits for all sensor Additionally you might set `synchronous_mode_wait_for_vehicle_control_command` to `true` to wait for a vehicle control command before executing the next tick. - -#### Control Synchronous Mode +##### Control Synchronous Mode It is possible to control the simulation execution: -- Pause/Play -- Execute single step +- Pause/Play +- Execute single step The following topic allows to control the stepping. -|Topic | Type | -|-------------------------------|------| +| Topic | Type | +| ---------------- | ---------------------------------------------------------- | | `/carla/control` | [carla_msgs.CarlaControl](carla_msgs/msg/CarlaControl.msg) | A [CARLA Control rqt plugin](rqt_carla_control/README.md) is available to publish to the topic. -# Available ROS Topics +## Available ROS Topics -## Ego Vehicle +### Ego Vehicle -### Sensors +#### Sensors -The ego vehicle sensors are provided via topics with prefix /carla/ego_vehicle/ +The ego vehicle sensors are provided via topics with prefix /carla/ego_vehicle/<sensor_topic> Currently the following sensors are supported: -#### Camera +##### Camera -|Topic | Type | -|--------------------------------------|------| -| `/carla//camera/rgb//image_color` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | +| Topic | Type | +| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | +| `/carla//camera/rgb//image_color` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | | `/carla//camera/rgb//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | -#### Lidar +##### Lidar -|Topic | Type | -|--------------------------------------|------| +| Topic | Type | +| --------------------------------------------------------- | ---------------------------------------------------------------------------------------- | | `/carla//lidar//point_cloud` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | -#### Radar +##### Radar -|Topic | Type | -|--------------------------------------|------| -| `/carla//radar//radar` | [ainstein_radar_msgs.RadarTargetArray](https://github.com/AinsteinAI/ainstein_radar/blob/master/ainstein_radar_msgs/msg/RadarTargetArray.msg) | +| Topic | Type | +| --------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | +| `/carla//radar//radar` | [ainstein_radar_msgs.RadarTargetArray](https://github.com/AinsteinAI/ainstein_radar/blob/master/ainstein_radar_msgs/msg/RadarTargetArray.msg) | Radar data can be visualized on rviz using [ainstein_radar_rviz_plugins](https://wiki.ros.org/ainstein_radar_rviz_plugins). -#### IMU +##### IMU -|Topic | Type | -|--------------------------------------|------| +| Topic | Type | +| ------------------------ | --------------------------------------------------------------------------------- | | `/carla//imu` | [sensor_msgs.Imu](https://docs.ros.org/melodic/api/sensor_msgs/html/msg/Imu.html) | -#### GNSS +##### GNSS -|Topic | Type | Description | -|--------------------------------------|------|-------------| +| Topic | Type | Description | +| ------------------------------------------------ | ------------------------------------------------------------------------------------ | --------------------- | | `/carla//gnss//fix` | [sensor_msgs.NavSatFix](http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html) | publish gnss location | -#### Collision Sensor +##### Collision Sensor -|Topic | Type | Description | -|-------------------------------|------|-------------| +| Topic | Type | Description | +| ------------------------------ | ------------------------------------------------------------------------ | ------------------------ | | `/carla//collision` | [carla_msgs.CarlaCollisionEvent](carla_msgs/msg/CarlaCollisionEvent.msg) | publish collision events | -#### Lane Invasion Sensor +##### Lane Invasion Sensor -|Topic | Type | Description | -|-------------------------------|------|-------------| +| Topic | Type | Description | +| ---------------------------------- | ------------------------------------------------------------------------------ | ------------------------------- | | `/carla//lane_invasion` | [carla_msgs.CarlaLaneInvasionEvent](carla_msgs/msg/CarlaLaneInvasionEvent.msg) | publish events on lane-invasion | -### Object Sensor +#### Object Sensor -|Topic | Type | Description | -|--------------|------|-------------| +| Topic | Type | Description | +| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | | `/carla//objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers, except the ego vehicle | -### Control +#### Control -|Topic | Type | -|--------------------------------------|------| -| `/carla//vehicle_control_cmd` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](carla_msgs/msg/CarlaEgoVehicleControl.msg) | -| `/carla//vehicle_control_cmd_manual` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](carla_msgs/msg/CarlaEgoVehicleControl.msg) | -| `/carla//vehicle_control_manual_override` (subscriber) | [std_msgs.Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html) | -| `/carla//vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](carla_msgs/msg/CarlaEgoVehicleStatus.msg) | -| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](carla_msgs/msg/CarlaEgoVehicleInfo.msg) | +| Topic | Type | +| ----------------------------------------------------------------- | ------------------------------------------------------------------------------ | +| `/carla//vehicle_control_cmd` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](carla_msgs/msg/CarlaEgoVehicleControl.msg) | +| `/carla//vehicle_control_cmd_manual` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](carla_msgs/msg/CarlaEgoVehicleControl.msg) | +| `/carla//vehicle_control_manual_override` (subscriber) | [std_msgs.Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html) | +| `/carla//vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](carla_msgs/msg/CarlaEgoVehicleStatus.msg) | +| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](carla_msgs/msg/CarlaEgoVehicleInfo.msg) | There are two modes to control the vehicle. -1. Normal Mode (reading commands from `/carla//vehicle_control_cmd`) -1. Manual Mode (reading commands from `/carla//vehicle_control_cmd_manual`) +1. Normal Mode (reading commands from `/carla//vehicle_control_cmd`) +2. Manual Mode (reading commands from `/carla//vehicle_control_cmd_manual`) This allows to manually override a Vehicle Control Commands published by a software stack. You can toggle between the two modes by publishing to `/carla//vehicle_control_manual_override`. [carla_manual_control](carla_manual_control/) makes use of this feature. - For testing purposes, you can stear the ego vehicle from the commandline by publishing to the topic `/carla//vehicle_control_cmd`. Examples for a ego vehicle with role_name 'ego_vehicle': @@ -200,19 +194,17 @@ Max forward throttle: rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 0.0}" -r 10 - Max forward throttle with max steering to the right: rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10 - The current status of the vehicle can be received via topic `/carla//vehicle_status`. Static information about the vehicle can be received via `/carla//vehicle_info` -#### Additional way of controlling +##### Additional way of controlling -|Topic | Type | -|--------------------------------------|------| +| Topic | Type | +| ------------------------------------------- | -------------------------------------------------------------------------------- | | `/carla//twist_cmd` (subscriber) | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | CAUTION: This control method does not respect the vehicle constraints. It allows movements impossible in the real world, like flying or rotating. @@ -221,46 +213,43 @@ You can also control the vehicle via publishing linear and angular velocity with Currently this method applies the complete linear vector, but only the yaw from angular vector. -#### Carla Ackermann Control +##### Carla Ackermann Control In certain cases, the [Carla Control Command](carla_msgs/msg/CarlaEgoVehicleControl.msg) is not ideal to connect to an AD stack. -Therefore a ROS-based node ```carla_ackermann_control``` is provided which reads [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) messages. +Therefore a ROS-based node `carla_ackermann_control` is provided which reads [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) messages. You can find further documentation [here](carla_ackermann_control/README.md). +### Other Topics -## Other Topics +#### Object information of other actors -### Object information of other actors +| Topic | Type | Description | +| ------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------- | +| `/carla/objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers | +| `/carla/marker` | [visualization_msgs.Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) | visualization of vehicles and walkers | +| `/carla/actor_list` | [carla_msgs.CarlaActorList](carla_msgs/msg/CarlaActorList.msg) | list of all carla actors | -|Topic | Type | Description | -|--------------|------|-------------| -| `/carla/objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers | -| `/carla/marker` | [visualization_msgs.Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) | visualization of vehicles and walkers | -| `/carla/actor_list` | [carla_msgs.CarlaActorList](carla_msgs/msg/CarlaActorList.msg) | list of all carla actors | +#### Status of CARLA - -### Status of CARLA - -|Topic | Type | Description | -|--------------|------|-------------| -| `/carla/status` | [carla_msgs.CarlaStatus](carla_msgs/msg/CarlaStatus.msg) | | +| Topic | Type | Description | +| ------------------- | -------------------------------------------------------------- | ------------------------------------------------------ | +| `/carla/status` | [carla_msgs.CarlaStatus](carla_msgs/msg/CarlaStatus.msg) | | | `/carla/world_info` | [carla_msgs.CarlaWorldInfo](carla_msgs/msg/CarlaWorldInfo.msg) | Info about the CARLA world/level (e.g. OPEN Drive map) | +### Walker -## Walker +| Topic | Type | Description | +| ---------------------------------------------------- | ---------------------------------------------------------------------------- | ------------------ | +| `/carla/walker//walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](carla_msgs/msg/CarlaWalkerControl.msg) | Control a walker | +| `/carla/walker//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of walker | -|Topic | Type | Description | -|--------------------------------------|------|-------------| -| `/carla/walker//walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](carla_msgs/msg/CarlaWalkerControl.msg) | Control a walker | -| `/carla/walker//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of walker | +### Other Vehicles -## Other Vehicles - -|Topic | Type | Description | -|--------------------------------------|------|-------------| +| Topic | Type | Description | +| ------------------------------ | ---------------------------------------------------------------------------- | ------------------- | | `/carla/vehicle//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of vehicle | -## Debug Marker +### Debug Marker It is possible to draw markers in CARLA. @@ -268,34 +257,30 @@ Caution: Markers might affect the data published by sensors. The following markers are supported in 'map'-frame: - - Arrow (specified by two points) - - Points - - Cube - - Line Strip +- Arrow (specified by two points) +- Points +- Cube +- Line Strip -|Topic | Type | Description | -|--------------------------------------|------|-------------| +| Topic | Type | Description | +| ---------------------------------- | ------------------------------------------------------------------------------------------------------ | --------------------------- | | `/carla/debug_marker` (subscriber) | [visualization_msgs.MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) | draw markers in CARLA world | - -# Carla Ego Vehicle +## Carla Ego Vehicle `carla_ego_vehicle` provides a generic way to spawn an ego vehicle and attach sensors to it. You can find further documentation [here](carla_ego_vehicle/README.md). - -# Carla Infrastructure Sensors +## Carla Infrastructure Sensors `carla_infrastructure` provides a generic way to spawn a set of infrastructure sensors defined in a config file. You can find further documentation [here](carla_infrastructure/README.md). - -# Waypoint calculation +## Waypoint calculation To make use of the Carla waypoint calculation a ROS Node is available to get waypoints. You can find further documentation [here](carla_waypoint_publisher/README.md). +## Troubleshooting -# Troubleshooting - -## ImportError: No module named carla +### ImportError: No module named carla You're missing Carla Python. Please execute: diff --git a/carla_ackermann_control/README.md b/carla_ackermann_control/README.md index a1be037e..71fc8464 100644 --- a/carla_ackermann_control/README.md +++ b/carla_ackermann_control/README.md @@ -2,32 +2,32 @@ ROS Node to convert [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) messages to [CarlaEgoVehicleControl](carla_ros_bridge/msg/CarlaEgoVehicleControl.msg). -* A PID controller is used to control the acceleration/velocity. -* Reads the Vehicle Info, required for controlling from Carla (via carla ros bridge) +- A PID controller is used to control the acceleration/velocity. +- Reads the Vehicle Info, required for controlling from Carla (via carla ros bridge) -# Prerequisites +## Prerequisites #install python simple-pid pip install --user simple-pid -## Configuration +### Configuration Initial parameters can be set via [configuration file](config/settings.yaml). It is possible to modify the parameters during runtime via ROS dynamic reconfigure. +## Available Topics -# Available Topics - -|Topic | Type | Description | -|--------------------------------------|------|-------------| -| `/carla//ackermann_cmd` (subscriber) | [ackermann_msgs.AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) | Subscriber for stearing commands | -| `/carla//ackermann_control/control_info` | [carla_ackermann_control.EgoVehicleControlInfo](msg/EgoVehicleControlInfo.msg) | The current values used within the controller (for debugging) | +| Topic | Type | Description | +| --------------------------------------------------- | ---------------------------------------------------------------------------------------------------- | ------------------------------------------------------------- | +| `/carla//ackermann_cmd` (subscriber) | [ackermann_msgs.AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) | Subscriber for stearing commands | +| `/carla//ackermann_control/control_info` | [carla_ackermann_control.EgoVehicleControlInfo](msg/EgoVehicleControlInfo.msg) | The current values used within the controller (for debugging) | The role name is specified within the configuration. -## Test control messages -You can send command to the car using the topic ```/carla//ackermann_cmd```. +### Test control messages + +You can send command to the car using the topic `/carla//ackermann_cmd`. Examples for a ego vehicle with role_name 'ego_vehicle': @@ -36,11 +36,9 @@ Forward movements, speed in in meters/sec. rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0.0, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10 - Forward with steering rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 1.22, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10 Info: the steering_angle is the driving angle (in radians) not the wheel angle. - diff --git a/carla_ackermann_control/setup.py b/carla_ackermann_control/setup.py index 310beb58..7fa6e39e 100644 --- a/carla_ackermann_control/setup.py +++ b/carla_ackermann_control/setup.py @@ -1,3 +1,7 @@ +""" +Setup for carla_ackermann_control +""" + from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup @@ -7,4 +11,3 @@ ) setup(**d) - diff --git a/carla_ego_vehicle/README.md b/carla_ego_vehicle/README.md index 3e4a6b20..bcad5ed5 100644 --- a/carla_ego_vehicle/README.md +++ b/carla_ego_vehicle/README.md @@ -6,8 +6,7 @@ Info: To be able to use `carla_manual_control` a camera with role-name 'view' an If no specific position is set, the ego vehicle is spawned at a random position. - -### Spawning at specific position +## Spawning at specific position It is possible to (re)spawn the ego vehicle at the specific location by publishing to `/carla//initialpose`. @@ -17,14 +16,14 @@ The preferred way of doing that is using RVIZ: Selecting a Pose with '2D Pose Estimate' will delete the current ego_vehicle and respawn it at the specified position. -### Re-use existing vehicle as ego-vehicle +## Re-use existing vehicle as ego-vehicle It is possible to re-use an existing vehicle as ego-vehicle, instead of spawning a new vehicle. In this case, the role_name is used to identify the vehicle among all CARLA actors through the rolename attribute. Upon success, the requested sensors are attached to this actor, and the actor becomes the new ego vehicle. To make use of this option, set the ROS parameter spawn_ego_vehicle to false. -### Create your own sensor setup +## Create your own sensor setup Sensors, attached to the ego vehicle can be defined via a json file. `carla_ego_vehicle` reads it from the file location defined via the private ros parameter `sensor_definition_file`. diff --git a/carla_ego_vehicle/setup.py b/carla_ego_vehicle/setup.py index 4a1a3605..4449d475 100644 --- a/carla_ego_vehicle/setup.py +++ b/carla_ego_vehicle/setup.py @@ -1,3 +1,7 @@ +""" +Setup for carla_ego_vehicle +""" + from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup @@ -7,4 +11,3 @@ ) setup(**d) - diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 90c0b6ce..a17ef783 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -30,6 +30,8 @@ import carla +secure_random = random.SystemRandom() + # ============================================================================== # -- CarlaEgoVehicle ------------------------------------------------------------ # ============================================================================== @@ -102,10 +104,11 @@ def restart(self): :return: """ # Get vehicle blueprint. - blueprint = random.choice(self.world.get_blueprint_library().filter(self.actor_filter)) + blueprint = secure_random.choice( + self.world.get_blueprint_library().filter(self.actor_filter)) blueprint.set_attribute('role_name', "{}".format(self.role_name)) if blueprint.has_attribute('color'): - color = random.choice(blueprint.get_attribute('color').recommended_values) + color = secure_random.choice(blueprint.get_attribute('color').recommended_values) blueprint.set_attribute('color', color) # Spawn the vehicle. if not rospy.get_param('~spawn_ego_vehicle'): @@ -148,7 +151,8 @@ def restart(self): self.player = self.world.try_spawn_actor(blueprint, spawn_point) while self.player is None: spawn_points = self.world.get_map().get_spawn_points() - spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform() + spawn_point = secure_random.choice( + spawn_points) if spawn_points else carla.Transform() self.player = self.world.try_spawn_actor(blueprint, spawn_point) # Read sensors from file diff --git a/carla_infrastructure/README.md b/carla_infrastructure/README.md index 54f26197..30af2b9f 100644 --- a/carla_infrastructure/README.md +++ b/carla_infrastructure/README.md @@ -1,4 +1,3 @@ # ROS Infrastructure The reference Carla client `carla_infrastructure` can be used to spawn infrastructure sensors. - diff --git a/carla_infrastructure/setup.py b/carla_infrastructure/setup.py index 82de40c8..611caca2 100644 --- a/carla_infrastructure/setup.py +++ b/carla_infrastructure/setup.py @@ -1,3 +1,7 @@ +""" +Setup for carla_infrastructure +""" + from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup @@ -7,4 +11,3 @@ ) setup(**d) - diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 285a5922..4bd98b63 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -11,15 +11,9 @@ from __future__ import print_function -from abc import abstractmethod - import os -import random -import math import json import rospy -from tf.transformations import euler_from_quaternion, quaternion_from_euler -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose from carla_msgs.msg import CarlaWorldInfo import carla @@ -163,7 +157,7 @@ def setup_sensors(self, sensors): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() - elif sensor_spec['type'].startswith('sensor.other.radar'): + elif sensor_spec['type'].startswith('sensor.other.radar'): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], diff --git a/carla_manual_control/README.md b/carla_manual_control/README.md index 466eff14..83807f3b 100644 --- a/carla_manual_control/README.md +++ b/carla_manual_control/README.md @@ -4,14 +4,14 @@ The node `carla_manual_control` is a ROS-only version of the Carla `manual_contr via ROS topics. ## Prerequistes + To be able to use `carla_manual_control`, some sensors need to be attached to the ego vehicle: -- to display an image: a camera with role-name 'view' and resolution 800x600 -- to display the current gnss position: a gnss sensor with role-name 'gnss1' -- to get a notification on lane invasions: a lane invasion sensor -- to get a notification on lane invasions: a collision sensor +- to display an image: a camera with role-name 'view' and resolution 800x600 +- to display the current gnss position: a gnss sensor with role-name 'gnss1' +- to get a notification on lane invasions: a lane invasion sensor +- to get a notification on lane invasions: a collision sensor ## Manual steering In order to steer manually, press 'B'. This will toggle manual-driving mode within carla_ros_bridge. - diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index f77026e1..2a8638ad 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -1,3 +1,7 @@ +""" +Setup for carla_manual_control +""" + from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup @@ -7,4 +11,3 @@ ) setup(**d) - diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 2da6f305..5b59ace7 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -86,11 +86,13 @@ def __init__(self, role_name, hud): self.hud = hud self.role_name = role_name self.image_subscriber = rospy.Subscriber( - "/carla/{}/camera/rgb/view/image_color".format(self.role_name), Image, self.on_view_image) + "/carla/{}/camera/rgb/view/image_color".format(self.role_name), + Image, self.on_view_image) self.collision_subscriber = rospy.Subscriber( "/carla/{}/collision".format(self.role_name), CarlaCollisionEvent, self.on_collision) self.lane_invasion_subscriber = rospy.Subscriber( - "/carla/{}/lane_invasion".format(self.role_name), CarlaLaneInvasionEvent, self.on_lane_invasion) + "/carla/{}/lane_invasion".format(self.role_name), + CarlaLaneInvasionEvent, self.on_lane_invasion) def on_collision(self, data): """ @@ -160,19 +162,21 @@ def __init__(self, role_name, hud): self._autopilot_enabled = False self._control = CarlaEgoVehicleControl() self._steer_cache = 0.0 - + self.vehicle_control_manual_override_publisher = rospy.Publisher( - "/carla/{}/vehicle_control_manual_override".format(self.role_name), Bool, queue_size=1, latch=True) + "/carla/{}/vehicle_control_manual_override".format(self.role_name), + Bool, queue_size=1, latch=True) self.vehicle_control_manual_override = False self.auto_pilot_enable_publisher = rospy.Publisher( "/carla/{}/enable_autopilot".format(self.role_name), Bool, queue_size=1) self.vehicle_control_publisher = rospy.Publisher( - "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), CarlaEgoVehicleControl, queue_size=1) + "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), + CarlaEgoVehicleControl, queue_size=1) self.carla_status_subscriber = rospy.Subscriber( "/carla/status", CarlaStatus, self._on_new_carla_frame) - + self.set_autopilot(self._autopilot_enabled) - + self.set_vehicle_control_manual_override( self.vehicle_control_manual_override) # disable manual override @@ -194,6 +198,7 @@ def set_autopilot(self, enable): """ self.auto_pilot_enable_publisher.publish(Bool(data=enable)) + # pylint: disable=too-many-branches def parse_events(self, clock): """ parse an input event @@ -234,7 +239,7 @@ def parse_events(self, clock): def _on_new_carla_frame(self, data): """ callback on new frame - + As CARLA only processes one vehicle control command per tick, send the current from within here (once per frame) """ @@ -292,17 +297,20 @@ def __init__(self, role_name, width, height): self.vehicle_status = CarlaEgoVehicleStatus() self.tf_listener = tf.TransformListener() self.vehicle_status_subscriber = rospy.Subscriber( - "/carla/{}/vehicle_status".format(self.role_name), CarlaEgoVehicleStatus, self.vehicle_status_updated) + "/carla/{}/vehicle_status".format(self.role_name), + CarlaEgoVehicleStatus, self.vehicle_status_updated) self.vehicle_info = CarlaEgoVehicleInfo() self.vehicle_info_subscriber = rospy.Subscriber( - "/carla/{}/vehicle_info".format(self.role_name), CarlaEgoVehicleInfo, self.vehicle_info_updated) + "/carla/{}/vehicle_info".format(self.role_name), + CarlaEgoVehicleInfo, self.vehicle_info_updated) self.latitude = 0 self.longitude = 0 self.manual_control = False self.gnss_subscriber = rospy.Subscriber( "/carla/{}/gnss/gnss1/fix".format(self.role_name), NavSatFix, self.gnss_updated) self.manual_control_subscriber = rospy.Subscriber( - "/carla/{}/vehicle_control_manual_override".format(self.role_name), Bool, self.manual_control_override_updated) + "/carla/{}/vehicle_control_manual_override".format(self.role_name), + Bool, self.manual_control_override_updated) self.carla_status = CarlaStatus() self.status_subscriber = rospy.Subscriber( @@ -380,7 +388,7 @@ def update_info_text(self): heading += 'W' if -0.5 > yaw > -179.5 else '' fps = 0 if self.carla_status.fixed_delta_seconds: - fps = 1/self.carla_status.fixed_delta_seconds + fps = 1 / self.carla_status.fixed_delta_seconds self._info_text = [ 'Frame: % 22s' % self.carla_status.frame, 'Simulation time: % 12s' % datetime.timedelta( diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index a1e5f51f..f4bdc1a1 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -1,3 +1,7 @@ +""" +Setup for carla_ros_bridge +""" + from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup @@ -7,4 +11,3 @@ ) setup(**d) - diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 04711a0e..07f174f2 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -171,7 +171,7 @@ def process_run_state(self): while not self.carla_control_queue.empty(): command = self.carla_control_queue.get() - while not command is None and not rospy.is_shutdown(): + while command is not None and not rospy.is_shutdown(): self.carla_run_state = command if self.carla_run_state == CarlaControl.PAUSE: diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 636b3b7a..4c9538b5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -39,7 +39,7 @@ def __init__(self, carla_actor, parent, communication, prefix=None): prefix = "vehicle/{:03}".format(carla_actor.id) self.classification = Object.CLASSIFICATION_CAR - if carla_actor.attributes.has_key('object_type'): + if 'object_type' in carla_actor.attributes: if carla_actor.attributes['object_type'] == 'car': self.classification = Object.CLASSIFICATION_CAR elif carla_actor.attributes['object_type'] == 'bike': diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 78e3b72b..01d68095 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -5,36 +5,58 @@ # This work is licensed under the terms of the MIT license. # For a copy, see . # -PKG = 'test_roslaunch' +""" +Class for testing nodes +""" + +import unittest import rospy import rostest -import unittest from std_msgs.msg import Header from rosgraph_msgs.msg import Clock from sensor_msgs.msg import CameraInfo, NavSatFix, Image, PointCloud2, Imu -from carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, CarlaActorList +from ainstein_radar_msgs.msg import RadarTargetArray from geometry_msgs.msg import Quaternion, Vector3, Pose from nav_msgs.msg import Odometry from derived_object_msgs.msg import ObjectArray from visualization_msgs.msg import Marker -from ainstein_radar_msgs.msg import RadarTargetArray +from carla_msgs.msg import (CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, + CarlaActorList) + +PKG = 'test_roslaunch' class TestClock(unittest.TestCase): + + """ + Handles testing of the all nodes + """ + def test_clock(self): + """ + Tests clock + """ rospy.init_node('test_node', anonymous=True) clock_msg = rospy.wait_for_message("/clock", Clock, timeout=15) self.assertNotEqual(Clock(), clock_msg) def test_vehicle_status(self): + """ + Tests vehicle_status + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus, timeout=15) - self.assertNotEqual(msg.header, Header()) #todo: check frame-id + msg = rospy.wait_for_message( + "/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus, timeout=15) + self.assertNotEqual(msg.header, Header()) # todo: check frame-id self.assertNotEqual(msg.orientation, Quaternion()) def test_vehicle_info(self): + """ + Tests vehicle_info + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/vehicle_info", CarlaEgoVehicleInfo, timeout=15) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/vehicle_info", CarlaEgoVehicleInfo, timeout=15) self.assertNotEqual(msg.id, 0) self.assertEqual(msg.type, "vehicle.tesla.model3") self.assertEqual(msg.rolename, "ego_vehicle") @@ -43,7 +65,8 @@ def test_vehicle_info(self): self.assertNotEqual(msg.moi, 0.0) self.assertNotEqual(msg.damping_rate_full_throttle, 0.0) self.assertNotEqual(msg.damping_rate_zero_throttle_clutch_engaged, 0.0) - self.assertNotEqual(msg.damping_rate_zero_throttle_clutch_disengaged, 0.0) + self.assertNotEqual( + msg.damping_rate_zero_throttle_clutch_disengaged, 0.0) self.assertTrue(msg.use_gear_autobox) self.assertNotEqual(msg.gear_switch_time, 0.0) self.assertNotEqual(msg.mass, 0.0) @@ -52,21 +75,32 @@ def test_vehicle_info(self): self.assertNotEqual(msg.center_of_mass, Vector3()) def test_odometry(self): + """ + Tests Odometry + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/odometry", Odometry, timeout=15) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/odometry", Odometry, timeout=15) self.assertEqual(msg.header.frame_id, "map") self.assertEqual(msg.child_frame_id, "ego_vehicle") self.assertNotEqual(msg.pose, Pose()) def test_gnss(self): + """ + Tests Gnss + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/gnss/gnss1/fix", NavSatFix, timeout=15) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/gnss/gnss1/fix", NavSatFix, timeout=15) self.assertEqual(msg.header.frame_id, "ego_vehicle/gnss/gnss1") self.assertNotEqual(msg.latitude, 0.0) self.assertNotEqual(msg.longitude, 0.0) self.assertNotEqual(msg.altitude, 0.0) def test_imu(self): + """ + Tests IMU sensor node + """ rospy.init_node('test_node', anonymous=True) print("testing for ros bridge") msg = rospy.wait_for_message("/carla/ego_vehicle/imu", Imu, timeout=15) @@ -76,43 +110,69 @@ def test_imu(self): self.assertNotEqual(msg.orientation, 0.0) def test_camera_info(self): + """ + Tests camera_info + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/camera/rgb/front/camera_info", CameraInfo, timeout=15) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/camera/rgb/front/camera_info", CameraInfo, timeout=15) self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/rgb/front") self.assertEqual(msg.height, 600) self.assertEqual(msg.width, 800) def test_camera_image(self): + """ + Tests camera_images + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/camera/rgb/front/image_color", Image, timeout=15) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/camera/rgb/front/image_color", Image, timeout=15) self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/rgb/front") self.assertEqual(msg.height, 600) self.assertEqual(msg.width, 800) self.assertEqual(msg.encoding, "bgra8") def test_lidar(self): + """ + Tests Lidar sensor node + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/lidar/lidar1/point_cloud", PointCloud2, timeout=15) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/lidar/lidar1/point_cloud", PointCloud2, timeout=15) self.assertEqual(msg.header.frame_id, "ego_vehicle/lidar/lidar1") def test_radar(self): + """ + Tests Radar sensor node + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/radar/front/radar", RadarTargetArray, timeout=15) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/radar/front/radar", RadarTargetArray, timeout=15) self.assertEqual(msg.header.frame_id, "ego_vehicle/radar/front") def test_ego_vehicle_objects(self): + """ + Tests objects node for ego_vehicle + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/ego_vehicle/objects", ObjectArray, timeout=15) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/objects", ObjectArray, timeout=15) self.assertEqual(msg.header.frame_id, "map") self.assertEqual(len(msg.objects), 0) def test_objects(self): + """ + Tests carla objects + """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message("/carla/objects", ObjectArray, timeout=15) self.assertEqual(msg.header.frame_id, "map") - self.assertEqual(len(msg.objects), 1) #only ego vehicle exists + self.assertEqual(len(msg.objects), 1) # only ego vehicle exists def test_marker(self): + """ + Tests marker + """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message("/carla/marker", Marker, timeout=15) self.assertEqual(msg.header.frame_id, "ego_vehicle") @@ -125,16 +185,24 @@ def test_marker(self): self.assertEqual(msg.color.b, 0.0) def test_world_info(self): + """ + Tests world_info + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=15) + msg = rospy.wait_for_message( + "/carla/world_info", CarlaWorldInfo, timeout=15) self.assertNotEqual(len(msg.map_name), 0) self.assertNotEqual(len(msg.opendrive), 0) def test_actor_list(self): + """ + Tests actor_list + """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/actor_list", CarlaActorList, timeout=15) + msg = rospy.wait_for_message( + "/carla/actor_list", CarlaActorList, timeout=15) self.assertNotEqual(len(msg.actors), 0) + if __name__ == '__main__': - import rostest rostest.rosrun(PKG, 'tests', TestClock) diff --git a/carla_waypoint_publisher/README.md b/carla_waypoint_publisher/README.md index 5c79a665..c8c47645 100644 --- a/carla_waypoint_publisher/README.md +++ b/carla_waypoint_publisher/README.md @@ -17,7 +17,6 @@ To run it: roslaunch carla_waypoint_publisher carla_waypoint_publisher.launch - ## Set a goal The goal is either read from the ROS topic `/carla//goal`, if available, or a fixed spawnpoint is used. @@ -26,11 +25,10 @@ The prefered way of setting a goal is to click '2D Nav Goal' in RVIZ. ![set goal](../docs/images/rviz_set_start_goal.png) -## Published waypoints +## Published waypoints The calculated route is published: -|Topic | Type | -|--------------|------| +| Topic | Type | +| ------------------------------------- | -------------------------------------------------------------------- | | `/carla//waypoints` | [nav_msgs.Path](http://docs.ros.org/api/nav_msgs/html/msg/Path.html) | - diff --git a/carla_waypoint_publisher/setup.py b/carla_waypoint_publisher/setup.py index ddb8a233..a2742691 100755 --- a/carla_waypoint_publisher/setup.py +++ b/carla_waypoint_publisher/setup.py @@ -1,4 +1,9 @@ # -*- coding: utf-8 -*- + +""" +Setup for carla_waypoint_publisher +""" + from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup diff --git a/pcl_recorder/README.md b/pcl_recorder/README.md index e77eb3fc..5334b7bd 100644 --- a/pcl_recorder/README.md +++ b/pcl_recorder/README.md @@ -25,7 +25,6 @@ Execute the Carla Simulator and the Pcl-Recorder. source /devel/setup.bash roslaunch pcl_recorder pcl_recorder.launch - When the capture drive is done, you can reduce the overall size of the point cloud. #create one point cloud file @@ -36,5 +35,3 @@ When the capture drive is done, you can reduce the overall size of the point clo #verify the result pcl_viewer map.pcd - - diff --git a/rqt_carla_control/README.md b/rqt_carla_control/README.md index 6c974893..44e6b43c 100644 --- a/rqt_carla_control/README.md +++ b/rqt_carla_control/README.md @@ -7,4 +7,3 @@ If `carla_ros_bridge` is configured in synchronous-mode, this plugin can be used You can start it e.g.: rqt --standalone rqt_carla_control - diff --git a/rqt_carla_control/setup.py b/rqt_carla_control/setup.py index 001ab7f7..7b519cfe 100755 --- a/rqt_carla_control/setup.py +++ b/rqt_carla_control/setup.py @@ -1,4 +1,9 @@ # -*- coding: utf-8 -*- + +""" +Setup for rqt_carla_control +""" + from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup From 3f6863e68811d42c0343dd962a4e5dd2009cee05 Mon Sep 17 00:00:00 2001 From: Vimal Date: Mon, 27 Jan 2020 11:12:36 +0530 Subject: [PATCH 012/627] Disable pylint warnings about similar lines in multiple files --- .pylintrc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.pylintrc b/.pylintrc index 3c916da6..931d3042 100644 --- a/.pylintrc +++ b/.pylintrc @@ -3,4 +3,4 @@ ignored-modules=numpy,carla,pygame,agents disable=logging-format-interpolation,locally-disabled,cyclic-import,too-many-instance-attributes,invalid-name,no-else-return,too-many-statements [SIMILARITIES] -min-similarity-lines=9 +min-similarity-lines=20 From fa06ae3ad3132a3f553c111370827490c5ce4549 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Wed, 22 Jan 2020 15:18:55 +0100 Subject: [PATCH 013/627] run rostest for sensor test file using all sensor types --- carla_ros_bridge/test/ros_bridge_client.test | 19 ++- carla_ros_bridge/test/test_sensors.json | 158 +++++++++++++++++++ 2 files changed, 170 insertions(+), 7 deletions(-) create mode 100644 carla_ros_bridge/test/test_sensors.json diff --git a/carla_ros_bridge/test/ros_bridge_client.test b/carla_ros_bridge/test/ros_bridge_client.test index c060a97e..a8740c08 100644 --- a/carla_ros_bridge/test/ros_bridge_client.test +++ b/carla_ros_bridge/test/ros_bridge_client.test @@ -1,11 +1,16 @@ - - - - - - + + + + + - + + + + + + + diff --git a/carla_ros_bridge/test/test_sensors.json b/carla_ros_bridge/test/test_sensors.json new file mode 100644 index 00000000..4fbc95f1 --- /dev/null +++ b/carla_ros_bridge/test/test_sensors.json @@ -0,0 +1,158 @@ +{ + "sensors": [ + { + "type": "sensor.camera.rgb", + "id": "front", + "x": 2.0, + "y": 0.0, + "z": 2.0, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "width": 800, + "height": 600, + "fov": 100, + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 60.0, + "iso": 1200.0, + "fstop": 1.4, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "manual", + "exposure_compensation": 3.0, + "exposure_min_bright": 0.1, + "exposure_max_bright": 2.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.depth", + "id": "front", + "x": 2.0, + "y": 0.0, + "z": 2.0, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "width": 800, + "height": 600, + "fov": 100, + "sensor_tick": 0.05 + }, + { + "type": "sensor.camera.semantic_segmentation", + "id": "front", + "x": 2.0, + "y": 0.0, + "z": 2.0, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "width": 800, + "height": 600, + "fov": 100, + "sensor_tick": 0.05 + }, + { + "type": "sensor.lidar.ray_cast", + "id": "lidar1", + "x": 0.0, + "y": 0.0, + "z": 2.4, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05 + }, + { + "type": "sensor.other.radar", + "id": "front", + "x": 2.0, + "y": 0.0, + "z": 1.5, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "horizontal_fov": 30.0, + "vertical_fov": 10.0, + "points_per_second": 1500, + "range": 100.0 + }, + { + "type": "sensor.other.gnss", + "id": "gnss1", + "x": 1.0, + "y": 0.0, + "z": 2.0, + "noise_alt_stddev": 0.1, + "noise_lat_stddev": 0.1, + "noise_lon_stddev": 0.1, + "noise_alt_bias": 0.0, + "noise_lat_bias": 0.0, + "noise_lon_bias": 0.0 + }, + { + "type": "sensor.other.imu", + "id": "imu1", + "x": 2.0, + "y": 0.0, + "z": 2.0, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "noise_accel_stddev_x": 0.1, + "noise_accel_stddev_y": 0.1, + "noise_accel_stddev_z": 0.1, + "noise_gyro_stddev_x": 0.01, + "noise_gyro_stddev_y": 0.01, + "noise_gyro_stddev_z": 0.01, + "noise_gyro_bias_x": 0.0, + "noise_gyro_bias_y": 0.0, + "noise_gyro_bias_z": 0.0 + }, + { + "type": "sensor.other.collision", + "id": "collision1", + "x": 0.0, + "y": 0.0, + "z": 0.0 + }, + { + "type": "sensor.other.lane_invasion", + "id": "laneinvasion1", + "x": 0.0, + "y": 0.0, + "z": 0.0 + } + ] +} From 83fbf1c6b7af5cdbdfdf58d1b7fa652dd2fbcfd1 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Wed, 22 Jan 2020 16:17:09 +0100 Subject: [PATCH 014/627] fix docker build --- docker/Dockerfile | 1 + 1 file changed, 1 insertion(+) diff --git a/docker/Dockerfile b/docker/Dockerfile index 49e024f0..9e5e54c5 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -17,6 +17,7 @@ RUN apt-get update \ ros-$ROS_VERSION-cv-bridge \ ros-$ROS_VERSION-pcl-conversions \ ros-$ROS_VERSION-pcl-ros \ + ros-$ROS_VERSION-ainstein-radar \ python-catkin-tools \ && rm -rf /var/lib/apt/lists/* From 8efa471aa3831d67d0054dbb3fa7a3bcb12b8386 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Fri, 24 Jan 2020 22:14:23 +0100 Subject: [PATCH 015/627] refactor travis --- .travis.yml | 111 +++++++++++++++++++++++++++++++--------------------- 1 file changed, 67 insertions(+), 44 deletions(-) diff --git a/.travis.yml b/.travis.yml index a24dfa0f..1ccb0633 100644 --- a/.travis.yml +++ b/.travis.yml @@ -6,59 +6,82 @@ # os: linux -dist: xenial -sudo: false -matrix: - include: +stages: + - check + - test + - docker - - env: TEST="Test installation with ROS Kinetic & pylint" - addons: - apt: - packages: - - python-pip - before_script: - - pip install --user simple-pid - - pip install --user pylint - - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' - - sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 - - sudo apt-get update - - sudo apt-get install ros-kinetic-desktop-full - script: - - mkdir ros-bridge/ - - shopt -s dotglob - - shopt -s extglob - - mv !(ros-bridge) ros-bridge/ - - mkdir -p catkin_ws/src - - cd catkin_ws/src - - ln -s ../../ros-bridge - - source /opt/ros/kinetic/setup.bash - - cd .. - - sudo rosdep init - - rosdep update - - rosdep install --from-paths src --ignore-src -r - - catkin_make install - - source install/setup.bash - - cd src/ros-bridge - - pylint --rcfile=.pylintrc carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ - after_failure: - - tail --lines=2000 build.log +cache: + - apt - - env: TEST="Check code formatting" - addons: - apt: - packages: - - pep8 - - python-autopep8 - - python-pep8 +addons: + apt: + packages: + - python-pip + +jobs: + include: + - name: "Check code formatting" + stage: check + before_install: skip + install: pip install --user pep8 autopep8 script: - autopep8 carla_ros_bridge/src/carla_ros_bridge/*.py --in-place --max-line-length=100 - autopep8 carla_ackermann_control/src/carla_ackermann_control/*.py --in-place --max-line-length=100 - autopep8 carla_ego_vehicle/src/carla_ego_vehicle/*.py --in-place --max-line-length=100 - autopep8 carla_waypoint_publisher/src/carla_waypoint_publisher/*.py --in-place --max-line-length=100 - git diff --quiet HEAD --; if [ ! $? -eq 0 ]; then echo "Code is not autopep8 compliant. Please run check.sh"; git diff HEAD --; exit 1; fi - after_failure: - - tail --lines=2000 build.log + - name: "Xenial Kinetic" + stage: test + dist: xenial + env: ROS_DISTRO=kinetic + - name: "Bionic Melodic" + dist: bionic + env: ROS_DISTRO=melodic + - name: "Docker Kinetic" + stage: docker + services: docker + before_install: skip + install: skip + script: cd docker && ./build.sh --build-arg ROS_VERSION=kinetic + - name: "Docker Melodic" + services: docker + before_install: skip + install: skip + script: cd docker && ./build.sh --build-arg ROS_VERSION=melodic + +before_install: + - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' + - sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 + - sudo apt update + - sudo apt install -y ros-$ROS_DISTRO-desktop-full python-catkin-tools python-catkin-pkg python-catkin-pkg-modules python-rosdep python-wstool + +install: + - pip install --user pylint simple-pid + - mkdir ros-bridge/ + - shopt -s dotglob + - shopt -s extglob + - mv !(ros-bridge) ros-bridge/ + - mkdir -p catkin_ws/src + - cd catkin_ws/src + - ln -s ../../ros-bridge + - cd .. + - source /opt/ros/$ROS_DISTRO/setup.bash + - sudo rosdep init + - rosdep update + - rosdep install --from-paths src --ignore-src -r + +script: + - catkin build + #- catkin test + - catkin config --install + - source devel/setup.bash + - cd src/ros-bridge + - pylint --rcfile=.pylintrc carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ + +after_failure: + - tail --lines=2000 build.log notifications: email: false From bae35cf49c6367091a187b779e8efb2c0034352d Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 28 Jan 2020 17:19:46 +0100 Subject: [PATCH 016/627] Add additional wheel information --- carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg | 6 +++++- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 11 ++++++++++- 2 files changed, 15 insertions(+), 2 deletions(-) diff --git a/carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg b/carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg index d7d00130..e9770d6c 100644 --- a/carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg +++ b/carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg @@ -1,5 +1,5 @@ # -# Copyright (c) 2019 Intel Corporation. +# Copyright (c) 2019-2020 Intel Corporation. # # This work is licensed under the terms of the MIT license. # For a copy, see . @@ -7,3 +7,7 @@ float32 tire_friction float32 damping_rate float32 max_steer_angle +float32 radius +float32 max_brake_torque +float32 max_handbrake_torque +geometry_msgs/Vector3 position diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index be07fed2..ca084ab8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -1,7 +1,7 @@ #!/usr/bin/env python # -# Copyright (c) 2018-2019 Intel Corporation +# Copyright (c) 2018-2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . @@ -127,6 +127,15 @@ def send_vehicle_msgs(self): wheel_info.tire_friction = wheel.tire_friction wheel_info.damping_rate = wheel.damping_rate wheel_info.max_steer_angle = math.radians(wheel.max_steer_angle) + wheel_info.radius = wheel.radius + wheel_info.max_brake_torque = wheel.max_brake_torque + wheel_info.max_handbrake_torque = wheel.max_handbrake_torque + wheel_info.position.x = (wheel.position.x/100.0) - \ + self.carla_actor.get_transform().location.x + wheel_info.position.y = -((wheel.position.y/100.0) - + self.carla_actor.get_transform().location.y) + wheel_info.position.z = (wheel.position.z/100.0) - \ + self.carla_actor.get_transform().location.z vehicle_info.wheels.append(wheel_info) vehicle_info.max_rpm = vehicle_physics.max_rpm From 489d0a7de2fe7c16303a79c8ec126e1f9f9838be Mon Sep 17 00:00:00 2001 From: Vimal Date: Fri, 31 Jan 2020 13:08:40 +0530 Subject: [PATCH 017/627] changed noise attributes for Gnss and Imu Sensor --- carla_ego_vehicle/config/sensors.json | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 3d09bd66..c0e8e0f7 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -113,15 +113,15 @@ "type": "sensor.other.gnss", "id": "gnss1", "x": 1.0, "y": 0.0, "z": 2.0, - "noise_alt_stddev": 0.1, "noise_lat_stddev": 0.1, "noise_lon_stddev": 0.1, + "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": "imu1", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "noise_accel_stddev_x": 0.1, "noise_accel_stddev_y": 0.1, "noise_accel_stddev_z": 0.1, - "noise_gyro_stddev_x": 0.01, "noise_gyro_stddev_y": 0.01, "noise_gyro_stddev_z": 0.01, + "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, "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 }, { From 20cf5da515d49c3d3e8efd26cd7322b2474b4439 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 30 Jan 2020 17:36:28 +0100 Subject: [PATCH 018/627] Add traffic lights sensor --- README.md | 1 + carla_msgs/CMakeLists.txt | 2 + carla_msgs/msg/CarlaTrafficLightStatus.msg | 15 +++++ .../msg/CarlaTrafficLightStatusList.msg | 7 +++ .../src/carla_ros_bridge/bridge.py | 8 ++- .../src/carla_ros_bridge/traffic.py | 21 +++++++ .../carla_ros_bridge/traffic_lights_sensor.py | 55 +++++++++++++++++++ 7 files changed, 108 insertions(+), 1 deletion(-) create mode 100644 carla_msgs/msg/CarlaTrafficLightStatus.msg create mode 100644 carla_msgs/msg/CarlaTrafficLightStatusList.msg create mode 100644 carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py diff --git a/README.md b/README.md index 94a3d485..a075a57b 100644 --- a/README.md +++ b/README.md @@ -228,6 +228,7 @@ You can find further documentation [here](carla_ackermann_control/README.md). | `/carla/objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers | | `/carla/marker` | [visualization_msgs.Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) | visualization of vehicles and walkers | | `/carla/actor_list` | [carla_msgs.CarlaActorList](carla_msgs/msg/CarlaActorList.msg) | list of all carla actors | +| `/carla/traffic_lights` | [carla_msgs.CarlaTrafficLightStatusList](carla_msgs/msg/CarlaTrafficLightStatusList.msg) | list of all traffic lights with their status | #### Status of CARLA diff --git a/carla_msgs/CMakeLists.txt b/carla_msgs/CMakeLists.txt index 40eaead2..09b17397 100644 --- a/carla_msgs/CMakeLists.txt +++ b/carla_msgs/CMakeLists.txt @@ -22,6 +22,8 @@ add_message_files( CarlaActorList.msg CarlaControl.msg CarlaStatus.msg + CarlaTrafficLightStatus.msg + CarlaTrafficLightStatusList.msg CarlaWalkerControl.msg ) diff --git a/carla_msgs/msg/CarlaTrafficLightStatus.msg b/carla_msgs/msg/CarlaTrafficLightStatus.msg new file mode 100644 index 00000000..d35beb78 --- /dev/null +++ b/carla_msgs/msg/CarlaTrafficLightStatus.msg @@ -0,0 +1,15 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +uint32 id + +uint8 RED=0 +uint8 YELLOW=1 +uint8 GREEN=2 +uint8 OFF=3 +uint8 UNKNOWN=4 + +uint8 state diff --git a/carla_msgs/msg/CarlaTrafficLightStatusList.msg b/carla_msgs/msg/CarlaTrafficLightStatusList.msg new file mode 100644 index 00000000..365df85e --- /dev/null +++ b/carla_msgs/msg/CarlaTrafficLightStatusList.msg @@ -0,0 +1,7 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +CarlaTrafficLightStatus[] traffic_lights diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 07f174f2..2b7b88b6 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -1,6 +1,6 @@ #!/usr/bin/env python # -# Copyright (c) 2018-2019 Intel Corporation +# Copyright (c) 2018-2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . @@ -42,6 +42,7 @@ from carla_ros_bridge.object_sensor import ObjectSensor from carla_ros_bridge.walker import Walker from carla_ros_bridge.debug_helper import DebugHelper +from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl @@ -143,6 +144,11 @@ def __init__(self, carla_world, params): filtered_id=None)) self.debug_helper = DebugHelper(carla_world.debug) + # add traffic light pseudo sensor + self.pseudo_actors.append(TrafficLightsSensor(parent=None, + communication=self.comm, + actor_list=self.actors)) + def destroy(self): """ Function to destroy this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 35984d72..9c6e6e7f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -11,6 +11,8 @@ """ from carla_ros_bridge.actor import Actor +from carla_msgs.msg import CarlaTrafficLightStatus +from carla import TrafficLightState class Traffic(Actor): @@ -57,3 +59,22 @@ def __init__(self, carla_actor, parent, communication): parent=parent, communication=communication, prefix='traffic.traffic_light') + + def get_status(self): + """ + Get the current state of the traffic light + """ + status = CarlaTrafficLightStatus() + status.id = self.get_id() + carla_state = self.carla_actor.get_state() + if carla_state == TrafficLightState.Red: + status.state = CarlaTrafficLightStatus.RED + elif carla_state == TrafficLightState.Yellow: + status.state = CarlaTrafficLightStatus.YELLOW + elif carla_state == TrafficLightState.Green: + status.state = CarlaTrafficLightStatus.GREEN + elif carla_state == TrafficLightState.Off: + status.state = CarlaTrafficLightStatus.OFF + else: + status.state = CarlaTrafficLightStatus.UNKNOWN + return status diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py new file mode 100644 index 00000000..25da32cd --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -0,0 +1,55 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +a sensor that reports the state of all traffic lights +""" + +from carla_msgs.msg import CarlaTrafficLightStatusList +from carla_ros_bridge.traffic import TrafficLight +from carla_ros_bridge.pseudo_actor import PseudoActor + + +class TrafficLightsSensor(PseudoActor): + """ + a sensor that reports the state of all traffic lights + """ + + def __init__(self, parent, communication, actor_list): + """ + Constructor + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param communication: communication-handle + :type communication: carla_ros_bridge.communication + :param actor_list: current list of actors + :type actor_list: map(carla-actor-id -> python-actor-object) + """ + + super(TrafficLightsSensor, self).__init__(parent=parent, + communication=communication, + prefix='traffic_lights') + self.actor_list = actor_list + + def destroy(self): + """ + Function to destroy this object. + :return: + """ + self.actor_list = None + super(TrafficLightsSensor, self).destroy() + + def update(self, frame, timestamp): + """ + Get the state of all known traffic lights + """ + traffic_lights = CarlaTrafficLightStatusList() + for actor_id in self.actor_list: + actor = self.actor_list[actor_id] + if isinstance(actor, TrafficLight): + traffic_lights.traffic_lights.append(actor.get_status()) + self.publish_message(self.get_topic_prefix(), traffic_lights) From a40e9668d8dd05ff9e42a2c162ab7100b15ac3e5 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 10 Feb 2020 14:47:47 +0100 Subject: [PATCH 019/627] carla_ros_bridge: Forward arguments in launch file --- .../carla_ros_bridge_with_example_ego_vehicle.launch | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index 3f5984ea..c40db57b 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -7,11 +7,18 @@ + + + + + + + From 13b68478001bdb0a2190bb66dfd78249722cf94b Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 10 Feb 2020 14:49:00 +0100 Subject: [PATCH 020/627] Fix sensor tf sending in synchronous mode --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 4 ++-- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 4 ++-- carla_ros_bridge/src/carla_ros_bridge/sensor.py | 12 +----------- 3 files changed, 5 insertions(+), 15 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 29e4c5bf..66695d5f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -111,7 +111,7 @@ def sensor_data_updated(self, carla_image): self.publish_message( self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) - def get_ros_sensor_transform(self, transform): + def get_ros_transform(self, transform): """ Function (override) to modify the tf messages sent by this camera. @@ -121,7 +121,7 @@ def get_ros_sensor_transform(self, transform): :return: the filled tf message :rtype: geometry_msgs.msg.TransformStamped """ - tf_msg = super(Camera, self).get_ros_sensor_transform(transform) + tf_msg = super(Camera, self).get_ros_transform(transform) rotation = tf_msg.transform.rotation quat = [rotation.x, rotation.y, rotation.z, rotation.w] quat_swap = tf.transformations.quaternion_from_matrix( diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index ffd6f0a0..391858d3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -43,7 +43,7 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): synchronous_mode=synchronous_mode, prefix='lidar/' + carla_actor.attributes.get('role_name')) - def get_ros_sensor_transform(self, transform): + def get_ros_transform(self, transform): """ Function (override) to modify the tf messages sent by this lidar. @@ -54,7 +54,7 @@ def get_ros_sensor_transform(self, transform): :return: the filled tf message :rtype: geometry_msgs.msg.TransformStamped """ - tf_msg = super(Lidar, self).get_ros_sensor_transform(transform) + tf_msg = super(Lidar, self).get_ros_transform(transform) rotation = tf_msg.transform.rotation quat = [rotation.x, rotation.y, rotation.z, rotation.w] diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 63270cc6..d4ff7782 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -99,7 +99,7 @@ def _callback_sensor_data(self, carla_sensor_data): float(self.sensor_tick_time) self.queue.put(carla_sensor_data) else: - self.publish_transform(self.get_ros_sensor_transform(carla_sensor_data.transform)) + self.publish_transform(self.get_ros_transform(carla_sensor_data.transform)) self.sensor_data_updated(carla_sensor_data) @abstractmethod @@ -114,16 +114,6 @@ def sensor_data_updated(self, carla_sensor_data): raise NotImplementedError( "This function has to be implemented by the derived classes") - def get_ros_sensor_transform(self, transform): - """ - Get sensor tf (override, if required) - - :param transform: carla sensor transform - :type transform: carla.Transform - """ - tf_msg = super(Sensor, self).get_ros_transform(transform) - return tf_msg - def _update_synchronous_event_sensor(self, frame): while True: try: From 474a7b09fc6ce6957f28e437daeabdc7dfe02f72 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 10 Feb 2020 14:50:43 +0100 Subject: [PATCH 021/627] Add node that converts a Twist to a carla vehicle control message --- .../src/carla_ros_bridge/camera.py | 2 +- .../src/carla_ros_bridge/lidar.py | 2 +- carla_twist_to_control/CMakeLists.txt | 25 +++++ .../launch/carla_twist_to_control.launch | 10 ++ carla_twist_to_control/package.xml | 17 ++++ carla_twist_to_control/setup.py | 13 +++ .../src/carla_twist_to_control/__init__.py | 0 .../carla_twist_to_control.py | 98 +++++++++++++++++++ 8 files changed, 165 insertions(+), 2 deletions(-) create mode 100644 carla_twist_to_control/CMakeLists.txt create mode 100644 carla_twist_to_control/launch/carla_twist_to_control.launch create mode 100644 carla_twist_to_control/package.xml create mode 100644 carla_twist_to_control/setup.py create mode 100644 carla_twist_to_control/src/carla_twist_to_control/__init__.py create mode 100755 carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 66695d5f..31ab843d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -111,7 +111,7 @@ def sensor_data_updated(self, carla_image): self.publish_message( self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) - def get_ros_transform(self, transform): + def get_ros_transform(self, transform=None): """ Function (override) to modify the tf messages sent by this camera. diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 391858d3..943746b3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -43,7 +43,7 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): synchronous_mode=synchronous_mode, prefix='lidar/' + carla_actor.attributes.get('role_name')) - def get_ros_transform(self, transform): + def get_ros_transform(self, transform=None): """ Function (override) to modify the tf messages sent by this lidar. diff --git a/carla_twist_to_control/CMakeLists.txt b/carla_twist_to_control/CMakeLists.txt new file mode 100644 index 00000000..f219cafc --- /dev/null +++ b/carla_twist_to_control/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_twist_to_control) + +find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch +) + +catkin_python_setup() + +roslaunch_add_file_check(launch) + +catkin_package( + CATKIN_DEPENDS + rospy +) + +catkin_install_python(PROGRAMS + src/carla_twist_to_control/carla_twist_to_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) diff --git a/carla_twist_to_control/launch/carla_twist_to_control.launch b/carla_twist_to_control/launch/carla_twist_to_control.launch new file mode 100644 index 00000000..d3694776 --- /dev/null +++ b/carla_twist_to_control/launch/carla_twist_to_control.launch @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/carla_twist_to_control/package.xml b/carla_twist_to_control/package.xml new file mode 100644 index 00000000..fc9890a7 --- /dev/null +++ b/carla_twist_to_control/package.xml @@ -0,0 +1,17 @@ + + + carla_twist_to_control + 0.0.0 + The carla_twist_to_control package + CARLA Simulator Team + MIT + catkin + rospy + roslaunch + rospy + rospy + carla_msgs + geometry_msgs + + + diff --git a/carla_twist_to_control/setup.py b/carla_twist_to_control/setup.py new file mode 100644 index 00000000..b62eb811 --- /dev/null +++ b/carla_twist_to_control/setup.py @@ -0,0 +1,13 @@ +""" +Setup for carla_twist_to_control +""" + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_twist_to_control'], + package_dir={'': 'src'} +) + +setup(**d) diff --git a/carla_twist_to_control/src/carla_twist_to_control/__init__.py b/carla_twist_to_control/src/carla_twist_to_control/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py new file mode 100755 index 00000000..8e8a14f3 --- /dev/null +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -0,0 +1,98 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +""" +receive geometry_nav_msgs::Twist and publish carla_msgs::CarlaEgoVehicleControl + +use max wheel steer angle +""" +import rospy +import sys +from geometry_msgs.msg import Twist +from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo + +class TwistToVehicleControl(object): + + MAX_LON_ACCELERATION = 10 + + def __init__(self, role_name): + """ + Constructor + """ + rospy.loginfo("Wait for vehicle info...") + vehicle_info=rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) + if not vehicle_info.wheels: + rospy.logerr("Cannot determine max steering angle: Vehicle has no wheels.") + sys.exit(1) + + self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle + if not self.max_steering_angle: + rospy.logerr("Cannot determine max steering angle: Value is %s", self.max_steering_angle) + sys.exit(1) + rospy.loginfo("Vehicle info received. Max steering angle=%s", self.max_steering_angle) + + rospy.Subscriber("/carla/{}/twist".format(role_name), Twist, self.twist_received) + + self.pub = rospy.Publisher("/carla/{}/vehicle_control_cmd".format(role_name), CarlaEgoVehicleControl, queue_size=1) + + def twist_received(self, twist): + control = CarlaEgoVehicleControl() + if twist == Twist(): + #stop + control.throttle = 0. + control.brake = 1. + control.steer = 0. + else: + if twist.linear.x > 0: + control.throttle = min(TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/TwistToVehicleControl.MAX_LON_ACCELERATION + else: + control.reverse = True + control.throttle = max(-TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/-TwistToVehicleControl.MAX_LON_ACCELERATION + + if twist.angular.z > 0: + control.steer = -min(self.max_steering_angle, twist.angular.z)/self.max_steering_angle + else: + control.steer = -max(-self.max_steering_angle, twist.angular.z)/self.max_steering_angle + + #invert steer for reverse case + if control.reverse: + control.steer = -control.steer + + self.pub.publish(control) + + def run(self): + """ + + Control loop + + :return: + """ + + rospy.spin() + + + +def main(): + """ + + main function + + :return: + """ + rospy.init_node('convert_twist_to_vehicle_control', anonymous=True) + role_name = rospy.get_param("/role_name", "ego_vehicle") + + twist_to_vehicle_control = TwistToVehicleControl(role_name) + try: + twist_to_vehicle_control.run() + finally: + del twist_to_vehicle_control + rospy.loginfo("Done") + + +if __name__ == "__main__": + main() + From 81e87ecb4f7b5e2a7e01dd60a57200a18427355c Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 10 Feb 2020 14:56:24 +0100 Subject: [PATCH 022/627] carla_twist_to_vehicle_control: Fix role name --- .../src/carla_twist_to_control/carla_twist_to_control.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index 8e8a14f3..b879ec42 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -39,6 +39,9 @@ def __init__(self, role_name): self.pub = rospy.Publisher("/carla/{}/vehicle_control_cmd".format(role_name), CarlaEgoVehicleControl, queue_size=1) def twist_received(self, twist): + """ + receive twist and convert to carla vehicle control + """ control = CarlaEgoVehicleControl() if twist == Twist(): #stop @@ -83,7 +86,7 @@ def main(): :return: """ rospy.init_node('convert_twist_to_vehicle_control', anonymous=True) - role_name = rospy.get_param("/role_name", "ego_vehicle") + role_name = rospy.get_param("~role_name", "ego_vehicle") twist_to_vehicle_control = TwistToVehicleControl(role_name) try: From 3336b694d8435d199b0b84c1f7fcb0a5bded9539 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 10 Feb 2020 15:00:26 +0100 Subject: [PATCH 023/627] Update changelog --- CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index fec62ea0..f3d4bbdb 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -3,6 +3,8 @@ * change Lidar range in meters * add new attributes for Gnss and Camera sensor * add IMU and Radar sensor +* Fix tf publishing in synchronous mode +* Add node to convert a twist to a vehicle control command ## CARLA-ROS-Bridge 0.9.6 From d5c8bf180b8f5aa141a07eac88a668920e3fbd76 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 12 Feb 2020 10:13:19 +0100 Subject: [PATCH 024/627] Cleanup --- .../carla_twist_to_control.py | 49 +++++++++---------- 1 file changed, 23 insertions(+), 26 deletions(-) diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index b879ec42..cb9bae89 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -9,12 +9,17 @@ use max wheel steer angle """ -import rospy import sys +import rospy from geometry_msgs.msg import Twist from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo class TwistToVehicleControl(object): + """ + receive geometry_nav_msgs::Twist and publish carla_msgs::CarlaEgoVehicleControl + + use max wheel steer angle + """ MAX_LON_ACCELERATION = 10 @@ -23,20 +28,24 @@ def __init__(self, role_name): Constructor """ rospy.loginfo("Wait for vehicle info...") - vehicle_info=rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) + vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), + CarlaEgoVehicleInfo) if not vehicle_info.wheels: rospy.logerr("Cannot determine max steering angle: Vehicle has no wheels.") sys.exit(1) self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle if not self.max_steering_angle: - rospy.logerr("Cannot determine max steering angle: Value is %s", self.max_steering_angle) + rospy.logerr("Cannot determine max steering angle: Value is %s", + self.max_steering_angle) sys.exit(1) - rospy.loginfo("Vehicle info received. Max steering angle=%s", self.max_steering_angle) + rospy.loginfo("Vehicle info received. Max steering angle=%s", + self.max_steering_angle) rospy.Subscriber("/carla/{}/twist".format(role_name), Twist, self.twist_received) - self.pub = rospy.Publisher("/carla/{}/vehicle_control_cmd".format(role_name), CarlaEgoVehicleControl, queue_size=1) + self.pub = rospy.Publisher("/carla/{}/vehicle_control_cmd".format(role_name), + CarlaEgoVehicleControl, queue_size=1) def twist_received(self, twist): """ @@ -50,37 +59,26 @@ def twist_received(self, twist): control.steer = 0. else: if twist.linear.x > 0: - control.throttle = min(TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/TwistToVehicleControl.MAX_LON_ACCELERATION + control.throttle = min(TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/ \ + TwistToVehicleControl.MAX_LON_ACCELERATION else: control.reverse = True - control.throttle = max(-TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/-TwistToVehicleControl.MAX_LON_ACCELERATION + control.throttle = max(-TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/ \ + -TwistToVehicleControl.MAX_LON_ACCELERATION if twist.angular.z > 0: - control.steer = -min(self.max_steering_angle, twist.angular.z)/self.max_steering_angle + control.steer = -min(self.max_steering_angle, twist.angular.z)/ \ + self.max_steering_angle else: - control.steer = -max(-self.max_steering_angle, twist.angular.z)/self.max_steering_angle - + control.steer = -max(-self.max_steering_angle, twist.angular.z)/ \ + self.max_steering_angle #invert steer for reverse case if control.reverse: control.steer = -control.steer - self.pub.publish(control) - def run(self): - """ - - Control loop - - :return: - """ - - rospy.spin() - - - def main(): """ - main function :return: @@ -90,12 +88,11 @@ def main(): twist_to_vehicle_control = TwistToVehicleControl(role_name) try: - twist_to_vehicle_control.run() + rospy.spin() finally: del twist_to_vehicle_control rospy.loginfo("Done") - if __name__ == "__main__": main() From cb0009966f34d35b67f1ea1e23461a78beadc70b Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 12 Feb 2020 11:00:42 +0100 Subject: [PATCH 025/627] Update/Add nodes --- CHANGELOG.md | 2 + carla_spectator_camera/CMakeLists.txt | 26 +++ carla_spectator_camera/README.md | 17 ++ .../launch/carla_spectator_camera.launch | 20 ++ carla_spectator_camera/package.xml | 17 ++ carla_spectator_camera/setup.py | 13 ++ .../src/carla_spectator_camera/__init__.py | 0 .../carla_spectator_camera.py | 193 ++++++++++++++++++ carla_waypoint_publisher/README.md | 12 +- carla_waypoint_publisher/package.xml | 1 + .../carla_waypoint_publisher.py | 83 +++++++- carla_waypoint_types/CMakeLists.txt | 23 +++ carla_waypoint_types/msg/CarlaWaypoint.msg | 12 ++ carla_waypoint_types/package.xml | 13 ++ carla_waypoint_types/srv/GetActorWaypoint.srv | 8 + carla_waypoint_types/srv/GetWaypoint.srv | 9 + 16 files changed, 445 insertions(+), 4 deletions(-) create mode 100644 carla_spectator_camera/CMakeLists.txt create mode 100644 carla_spectator_camera/README.md create mode 100644 carla_spectator_camera/launch/carla_spectator_camera.launch create mode 100644 carla_spectator_camera/package.xml create mode 100644 carla_spectator_camera/setup.py create mode 100644 carla_spectator_camera/src/carla_spectator_camera/__init__.py create mode 100755 carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py create mode 100644 carla_waypoint_types/CMakeLists.txt create mode 100644 carla_waypoint_types/msg/CarlaWaypoint.msg create mode 100644 carla_waypoint_types/package.xml create mode 100644 carla_waypoint_types/srv/GetActorWaypoint.srv create mode 100644 carla_waypoint_types/srv/GetWaypoint.srv diff --git a/CHANGELOG.md b/CHANGELOG.md index f3d4bbdb..9583ed44 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -5,6 +5,8 @@ * add IMU and Radar sensor * Fix tf publishing in synchronous mode * Add node to convert a twist to a vehicle control command +* Add node carla_spectator_camera +* Update carla_waypoint_publisher ## CARLA-ROS-Bridge 0.9.6 diff --git a/carla_spectator_camera/CMakeLists.txt b/carla_spectator_camera/CMakeLists.txt new file mode 100644 index 00000000..da537577 --- /dev/null +++ b/carla_spectator_camera/CMakeLists.txt @@ -0,0 +1,26 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_spectator_camera) + +find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch + geometry_msgs +) + +catkin_python_setup() + +roslaunch_add_file_check(launch) + +catkin_package( + CATKIN_DEPENDS + rospy +) + +catkin_install_python(PROGRAMS + src/carla_spectator_camera/carla_spectator_camera.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) diff --git a/carla_spectator_camera/README.md b/carla_spectator_camera/README.md new file mode 100644 index 00000000..356370f2 --- /dev/null +++ b/carla_spectator_camera/README.md @@ -0,0 +1,17 @@ +# Carla Spectator Camera + +This node allows to spawn a camera, attached to an ego vehicle and move its pose via a ros topic. + +## Startup + +To run it: + + roslaunch carla_spectator_camera carla_spectator_camera.launch + +## Set the camera pose + +The camera pose can be set by publishing to: + +| Topic | Type | +| ------------------------------------------ | -------------------------------------------------------------------------------------------- | +| `/carla//spectator_pose` | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | diff --git a/carla_spectator_camera/launch/carla_spectator_camera.launch b/carla_spectator_camera/launch/carla_spectator_camera.launch new file mode 100644 index 00000000..8213f154 --- /dev/null +++ b/carla_spectator_camera/launch/carla_spectator_camera.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/carla_spectator_camera/package.xml b/carla_spectator_camera/package.xml new file mode 100644 index 00000000..c30a4490 --- /dev/null +++ b/carla_spectator_camera/package.xml @@ -0,0 +1,17 @@ + + + carla_spectator_camera + 0.0.0 + The carla_spectator_camera package + CARLA Simulator Team + MIT + catkin + rospy + roslaunch + rospy + rospy + topic_tools + geometry_msgs + + + diff --git a/carla_spectator_camera/setup.py b/carla_spectator_camera/setup.py new file mode 100644 index 00000000..b0dae9aa --- /dev/null +++ b/carla_spectator_camera/setup.py @@ -0,0 +1,13 @@ +""" +Setup for carla_spectator_camera +""" + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_spectator_camera'], + package_dir={'': 'src'} +) + +setup(**d) diff --git a/carla_spectator_camera/src/carla_spectator_camera/__init__.py b/carla_spectator_camera/src/carla_spectator_camera/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py new file mode 100755 index 00000000..7877514c --- /dev/null +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -0,0 +1,193 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +""" +Spawns a camera, attached to an ego vehicle. + +The pose of the camera can be changed by publishing +to /carla//spectator_position. +""" + +import math +import rospy +from tf.transformations import euler_from_quaternion +import tf +from geometry_msgs.msg import PoseStamped +from carla_msgs.msg import CarlaWorldInfo + +import carla + +# ============================================================================== +# -- CarlaSpectatorCamera ------------------------------------------------------------ +# ============================================================================== + +class CarlaSpectatorCamera(object): + """ + Spawns a camera, attached to an ego vehicle. + + The pose of the camera can be changed by publishing + to /carla//spectator_position. + """ + + def __init__(self): + """ + Constructor + """ + rospy.init_node('spectator_camera', anonymous=True) + self.listener = tf.TransformListener() + self.role_name = rospy.get_param("/role_name", "ego_vehicle") + self.camera_resolution_x = rospy.get_param("~resolution_x", 800) + self.camera_resolution_y = rospy.get_param("~resolution_y", 600) + self.camera_fov = rospy.get_param("~fov", 50) + self.host = rospy.get_param('/carla/host', '127.0.0.1') + self.port = rospy.get_param('/carla/port', '2000') + self.world = None + self.pose = None + self.camera_actor = None + self.ego_vehicle = None + rospy.Subscriber("/carla/{}/spectator_pose".format(self.role_name), + PoseStamped, self.pose_received) + + def pose_received(self, pose): + """ + Move the camera + """ + if self.pose != pose: + rospy.logdebug("Camera pose changed. Updating carla camera") + self.pose = pose + transform = self.get_camera_transform() + if transform and self.camera_actor: + self.camera_actor.set_transform(transform) + + def get_camera_transform(self): + """ + Calculate the CARLA camera transform + """ + if not self.pose: + rospy.loginfo("no pose!") + return None + if self.pose.header.frame_id != self.role_name: + rospy.logwarn("Unsupported frame received. Supported {}, received {}".format( + self.role_name, self.pose.header.frame_id)) + return None + sensor_location = carla.Location(x=self.pose.pose.position.x, + y=-self.pose.pose.position.y, + z=self.pose.pose.position.z) + quaternion = ( + self.pose.pose.orientation.x, + self.pose.pose.orientation.y, + self.pose.pose.orientation.z, + self.pose.pose.orientation.w + ) + roll, pitch, yaw = euler_from_quaternion(quaternion) + #rotate to CARLA + sensor_rotation = carla.Rotation(pitch=math.degrees(roll)-90, + roll=math.degrees(pitch), + yaw=-math.degrees(yaw)-90) + return carla.Transform(sensor_location, sensor_rotation) + + def create_camera(self, ego_actor): + """ + Attach the camera to the ego vehicle + """ + bp_library = self.world.get_blueprint_library() + try: + bp = bp_library.find("sensor.camera.rgb") + bp.set_attribute('role_name', "spectator_view") + rospy.loginfo("Creating camera with resolution {}x{}, fov {}".format( + self.camera_resolution_x, + self.camera_resolution_y, + self.camera_fov)) + bp.set_attribute('image_size_x', str(self.camera_resolution_x)) + bp.set_attribute('image_size_y', str(self.camera_resolution_y)) + bp.set_attribute('fov', str(self.camera_fov)) + except KeyError as e: + rospy.logfatal("Camera could not be spawned: '{}'".format(e)) + transform = self.get_camera_transform() + if not transform: + transform = carla.Transform() + self.camera_actor = self.world.spawn_actor(bp, transform, + attach_to=ego_actor) + + def find_ego_vehicle_actor(self): + """ + Look for an carla actor with role name + """ + hero = None + for actor in self.world.get_actors(): + if actor.attributes.get('role_name') == self.role_name: + hero = actor + break + ego_vehicle_changed = False + if hero is None and self.ego_vehicle is not None: + ego_vehicle_changed = True + + if not ego_vehicle_changed and hero is not None and self.ego_vehicle is None: + ego_vehicle_changed = True + + if not ego_vehicle_changed and hero is not None and \ + self.ego_vehicle is not None and hero.id != self.ego_vehicle.id: + ego_vehicle_changed = True + + if ego_vehicle_changed: + self.destroy() + rospy.loginfo("Ego vehicle changed.") + self.ego_vehicle = hero + if self.ego_vehicle: + self.create_camera(self.ego_vehicle) + + def destroy(self): + """ + destroy the camera + """ + if self.camera_actor: + self.camera_actor.destroy() + self.camera_actor = None + + def run(self): + """ + main loop + """ + # wait for ros-bridge to set up CARLA world + rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") + try: + rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) + except rospy.ROSException as e: + rospy.logerr("Timeout while waiting for world info!") + raise e + rospy.loginfo("CARLA world available. Waiting for ego vehicle...") + + client = carla.Client(self.host, self.port) + client.set_timeout(2.0) + self.world = client.get_world() + + try: + r = rospy.Rate(10) # 10hz + while not rospy.is_shutdown(): + self.find_ego_vehicle_actor() + r.sleep() + except rospy.ROSInterruptException: + pass + +# ============================================================================== +# -- main() -------------------------------------------------------------------- +# ============================================================================== + + +def main(): + """ + main function + """ + carla_spectator_camera = CarlaSpectatorCamera() + try: + carla_spectator_camera.run() + finally: + if carla_spectator_camera is not None: + carla_spectator_camera.destroy() + + +if __name__ == '__main__': + main() diff --git a/carla_waypoint_publisher/README.md b/carla_waypoint_publisher/README.md index c8c47645..7419a7ce 100644 --- a/carla_waypoint_publisher/README.md +++ b/carla_waypoint_publisher/README.md @@ -4,7 +4,9 @@ Carla supports waypoint calculations. The node `carla_waypoint_publisher` makes this feature available in the ROS context. It uses the current pose of the ego vehicle with role-name "ego_vehicle" as starting point. If the -vehicle is respawned, the route is newly calculated. +vehicle is respawned or moved, the route is newly calculated. + +Additionally, services are provided to query CARLA waypoints. ## Startup @@ -32,3 +34,11 @@ The calculated route is published: | Topic | Type | | ------------------------------------- | -------------------------------------------------------------------- | | `/carla//waypoints` | [nav_msgs.Path](http://docs.ros.org/api/nav_msgs/html/msg/Path.html) | + + +## Available services + +| Service | Description | Type | +| ----------------------------------------------------------- | ----------- | -------------------------------------------------------------------- | +| `/carla_waypoint_publisher//get_waypoint` | Get the waypoint for a specific location | [carla_waypoint_types.GetWaypoint](../carla_waypoint_types/srv/GetWaypoint.msg) | +| `/carla_waypoint_publisher//get_actor_waypoint` | Get the waypoint for the ego vehicle | [carla_waypoint_types.GetActorWaypoint](../carla_waypoint_types/srv/GetActorWaypoint.msg) | diff --git a/carla_waypoint_publisher/package.xml b/carla_waypoint_publisher/package.xml index 857950f2..d744ffdd 100644 --- a/carla_waypoint_publisher/package.xml +++ b/carla_waypoint_publisher/package.xml @@ -9,6 +9,7 @@ roslaunch rospy nav_msgs + carla_waypoint_types rospy diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 44d34d75..915bc708 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -8,12 +8,14 @@ Generates a plan of waypoints to follow It uses the current pose of the ego vehicle as starting point. If the -vehicle is respawned, the route is newly calculated. +vehicle is respawned or move, the route is newly calculated. The goal is either read from the ROS topic `/carla//move_base_simple/goal`, if available -(e.g. published by RVIZ via '2D Nav Goal') or a fixed spawnpoint is used. +(e.g. published by RVIZ via '2D Nav Goal') or a fixed point is used. The calculated route is published on '/carla//waypoints' + +Additionally, services are provided to interface CARLA waypoints. """ import math import threading @@ -24,6 +26,8 @@ from nav_msgs.msg import Path from geometry_msgs.msg import PoseStamped from carla_msgs.msg import CarlaWorldInfo +from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint +from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint import carla @@ -43,13 +47,26 @@ class CarlaToRosWaypointConverter(object): WAYPOINT_DISTANCE = 2.0 def __init__(self, carla_world): + """ + Constructor + """ self.world = carla_world self.map = carla_world.get_map() self.ego_vehicle = None + self.ego_vehicle_location = None + self.on_tick = None self.role_name = rospy.get_param("~role_name", 'ego_vehicle') self.waypoint_publisher = rospy.Publisher( '/carla/{}/waypoints'.format(self.role_name), Path, queue_size=1, latch=True) + # initialize ros services + self.getWaypointService = rospy.Service( + '/carla_waypoint_publisher/{}/get_waypoint'.format(self.role_name), + GetWaypoint, self.get_waypoint) + self.getActorWaypointService = rospy.Service( + '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(self.role_name), + GetActorWaypoint, self.get_actor_waypoint) + # set initial goal self.goal = self.world.get_map().get_spawn_points()[0] @@ -61,7 +78,55 @@ def __init__(self, carla_world): # use callback to wait for ego vehicle rospy.loginfo("Waiting for ego vehicle...") - self.world.on_tick(self.find_ego_vehicle_actor) + self.on_tick = self.world.on_tick(self.find_ego_vehicle_actor) + + def destroy(self): + """ + Destructor + """ + self.ego_vehicle = None + if self.on_tick: + self.world.remove_on_tick(self.on_tick) + + def get_waypoint(self, req): + """ + Get the waypoint for a location + """ + carla_position = carla.Location() + carla_position.x = req.location.x + carla_position.y = -req.location.y + carla_position.z = req.location.z + + carla_waypoint = self.map.get_waypoint(carla_position) + + response = GetWaypointResponse() + response.waypoint.pose.position.x = carla_waypoint.transform.location.x + response.waypoint.pose.position.y = -carla_waypoint.transform.location.y + response.waypoint.pose.position.z = carla_waypoint.transform.location.z + response.waypoint.is_junction = carla_waypoint.is_junction + response.waypoint.road_id = carla_waypoint.road_id + response.waypoint.section_id = carla_waypoint.section_id + response.waypoint.lane_id = carla_waypoint.lane_id + #rospy.logwarn("Get waypoint {}".format(response.waypoint.pose.position)) + return response + + def get_actor_waypoint(self, _): + """ + Convenience method to get the waypoint for an actor + """ + response = GetActorWaypointResponse() + if self.ego_vehicle: + carla_waypoint = self.map.get_waypoint(self.ego_vehicle.get_location()) + response.waypoint.pose.position.x = carla_waypoint.transform.location.x + response.waypoint.pose.position.y = -carla_waypoint.transform.location.y + response.waypoint.pose.position.z = carla_waypoint.transform.location.z + response.waypoint.is_junction = carla_waypoint.is_junction + response.waypoint.road_id = carla_waypoint.road_id + response.waypoint.section_id = carla_waypoint.section_id + response.waypoint.lane_id = carla_waypoint.lane_id + else: + rospy.logwarn("get_actor_waypoint(): Ego vehicle not valid.") + return response def on_goal(self, goal): """ @@ -71,6 +136,7 @@ def on_goal(self, goal): :return: """ + rospy.loginfo("Received goal, trigger rerouting...") carla_goal = carla.Transform() carla_goal.location.x = goal.pose.position.x carla_goal.location.y = -goal.pose.position.y @@ -125,6 +191,16 @@ def find_ego_vehicle_actor(self, _): rospy.loginfo("Ego vehicle changed.") self.ego_vehicle = hero self.reroute() + elif self.ego_vehicle: + current_location = self.ego_vehicle.get_location() + if self.ego_vehicle_location: + dx = self.ego_vehicle_location.x - current_location.x + dy = self.ego_vehicle_location.y - current_location.y + distance = math.sqrt(dx * dx + dy * dy) + if distance > self.WAYPOINT_DISTANCE: + rospy.loginfo("Ego vehicle was repositioned.") + self.reroute() + self.ego_vehicle_location = current_location def calculate_route(self, goal): """ @@ -202,6 +278,7 @@ def main(): waypointConverter = CarlaToRosWaypointConverter(carla_world) rospy.spin() + waypointConverter.destroy() del waypointConverter del carla_world del carla_client diff --git a/carla_waypoint_types/CMakeLists.txt b/carla_waypoint_types/CMakeLists.txt new file mode 100644 index 00000000..6d0320d3 --- /dev/null +++ b/carla_waypoint_types/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_waypoint_types) + +find_package(catkin REQUIRED COMPONENTS + message_generation + nav_msgs +) + +add_service_files(DIRECTORY srv FILES + GetWaypoint.srv + GetActorWaypoint.srv +) + +add_message_files(DIRECTORY msg FILES + CarlaWaypoint.msg +) + +generate_messages(DEPENDENCIES nav_msgs) + +catkin_package( + CATKIN_DEPENDS + nav_msgs +) diff --git a/carla_waypoint_types/msg/CarlaWaypoint.msg b/carla_waypoint_types/msg/CarlaWaypoint.msg new file mode 100644 index 00000000..8e729d2a --- /dev/null +++ b/carla_waypoint_types/msg/CarlaWaypoint.msg @@ -0,0 +1,12 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +int32 road_id +int32 section_id +int32 lane_id +bool is_junction +geometry_msgs/Pose pose \ No newline at end of file diff --git a/carla_waypoint_types/package.xml b/carla_waypoint_types/package.xml new file mode 100644 index 00000000..76fa6b52 --- /dev/null +++ b/carla_waypoint_types/package.xml @@ -0,0 +1,13 @@ + + + carla_waypoint_types + 0.1.0 + The carla_waypoint_types package + CARLA Simulator Team + MIT + catkin + message_generation + nav_msgs + message_runtime + nav_msgs + diff --git a/carla_waypoint_types/srv/GetActorWaypoint.srv b/carla_waypoint_types/srv/GetActorWaypoint.srv new file mode 100644 index 00000000..f7e7dad5 --- /dev/null +++ b/carla_waypoint_types/srv/GetActorWaypoint.srv @@ -0,0 +1,8 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +--- +carla_waypoint_types/CarlaWaypoint waypoint \ No newline at end of file diff --git a/carla_waypoint_types/srv/GetWaypoint.srv b/carla_waypoint_types/srv/GetWaypoint.srv new file mode 100644 index 00000000..b3e22240 --- /dev/null +++ b/carla_waypoint_types/srv/GetWaypoint.srv @@ -0,0 +1,9 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +geometry_msgs/Point location +--- +carla_waypoint_types/CarlaWaypoint waypoint \ No newline at end of file From d968bc9bcbf328f4d2c4f0dcfdcb018f04721021 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 19 Feb 2020 17:09:01 +0100 Subject: [PATCH 026/627] Add multiple nodes - carla_ros_scenario_runner is a ros node, that is able to control the CARLA scenario runner. - scenarios can be executed via ros-service - carla_ad_agent is a ros node, that provides basic ad functionality - derived from carla planning - respects traffic lights - avoids crashs with other vehicles - rviz_carla_plugin is a rviz plugin with the following features: - provide a pose of the current view (used in carla_spectator_camera) - visualize the current vehicle control - allows manually overriding the vehicle control - execute a scenario - pause the simulation (if started in synchronous mode) - carla_ad_demo provides a demo setup (also including all of the above nodes) - modify carla_waypoint_publisher service to be able to provide waypoint for an actor id --- CHANGELOG.md | 4 + README.md | 38 +- carla_ad_agent/CMakeLists.txt | 32 ++ carla_ad_agent/README.md | 13 + carla_ad_agent/launch/carla_ad_agent.launch | 13 + carla_ad_agent/package.xml | 18 + carla_ad_agent/setup.py | 10 + carla_ad_agent/src/carla_ad_agent/__init__.py | 0 carla_ad_agent/src/carla_ad_agent/agent.py | 290 ++++++++++++ .../src/carla_ad_agent/basic_agent.py | 129 ++++++ .../src/carla_ad_agent/carla_ad_agent.py | 133 ++++++ .../src/carla_ad_agent/local_planner.py | 203 +++++++++ carla_ad_agent/src/carla_ad_agent/misc.py | 70 +++ .../carla_ad_agent/vehicle_pid_controller.py | 170 ++++++++ carla_ad_demo/CMakeLists.txt | 19 + carla_ad_demo/README.md | 36 ++ .../config/FollowLeadingVehicle.xosc | 270 ++++++++++++ carla_ad_demo/config/carla_ad_demo.rviz | 173 ++++++++ carla_ad_demo/config/sensors.json | 48 ++ carla_ad_demo/launch/carla_ad_demo.launch | 71 +++ .../launch/carla_ad_demo_with_rviz.launch | 84 ++++ carla_ad_demo/package.xml | 20 + carla_ros_scenario_runner/CMakeLists.txt | 23 + carla_ros_scenario_runner/README.md | 45 ++ .../launch/carla_ros_scenario_runner.launch | 16 + carla_ros_scenario_runner/package.xml | 19 + carla_ros_scenario_runner/setup.py | 13 + .../src/carla_ros_scenario_runner/__init__.py | 0 .../application_runner.py | 152 +++++++ .../carla_ros_scenario_runner.py | 169 +++++++ .../scenario_runner_runner.py | 33 ++ .../CMakeLists.txt | 21 + .../msg/CarlaScenario.msg | 11 + .../msg/CarlaScenarioList.msg | 8 + .../msg/CarlaScenarioRunnerStatus.msg | 14 + carla_ros_scenario_runner_types/package.xml | 14 + .../srv/ExecuteScenario.srv | 10 + .../carla_spectator_camera.py | 13 +- carla_twist_to_control/README.md | 17 + .../carla_twist_to_control.py | 33 +- carla_waypoint_publisher/README.md | 6 +- .../carla_waypoint_publisher.py | 11 +- carla_waypoint_types/srv/GetActorWaypoint.srv | 1 + check.sh | 7 +- docs/images/rviz_carla_plugin.png | Bin 0 -> 525827 bytes rviz_carla_plugin/CMakeLists.txt | 48 ++ rviz_carla_plugin/README.md | 64 +++ .../icons/classes/CarlaControl.png | Bin 0 -> 16301 bytes rviz_carla_plugin/icons/pause.png | Bin 0 -> 184 bytes rviz_carla_plugin/icons/play.png | Bin 0 -> 433 bytes rviz_carla_plugin/icons/step_once.png | Bin 0 -> 586 bytes rviz_carla_plugin/package.xml | 26 ++ rviz_carla_plugin/plugin_description.xml | 9 + rviz_carla_plugin/rviz_carla_plugin.qrc | 7 + rviz_carla_plugin/src/carla_control_panel.cpp | 411 ++++++++++++++++++ rviz_carla_plugin/src/carla_control_panel.h | 104 +++++ rviz_carla_plugin/src/drive_widget.cpp | 249 +++++++++++ rviz_carla_plugin/src/drive_widget.h | 91 ++++ rviz_carla_plugin/src/indicator_widget.cpp | 53 +++ rviz_carla_plugin/src/indicator_widget.h | 36 ++ 60 files changed, 3526 insertions(+), 52 deletions(-) create mode 100644 carla_ad_agent/CMakeLists.txt create mode 100644 carla_ad_agent/README.md create mode 100644 carla_ad_agent/launch/carla_ad_agent.launch create mode 100644 carla_ad_agent/package.xml create mode 100644 carla_ad_agent/setup.py create mode 100644 carla_ad_agent/src/carla_ad_agent/__init__.py create mode 100644 carla_ad_agent/src/carla_ad_agent/agent.py create mode 100644 carla_ad_agent/src/carla_ad_agent/basic_agent.py create mode 100755 carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py create mode 100644 carla_ad_agent/src/carla_ad_agent/local_planner.py create mode 100644 carla_ad_agent/src/carla_ad_agent/misc.py create mode 100644 carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py create mode 100644 carla_ad_demo/CMakeLists.txt create mode 100644 carla_ad_demo/README.md create mode 100644 carla_ad_demo/config/FollowLeadingVehicle.xosc create mode 100644 carla_ad_demo/config/carla_ad_demo.rviz create mode 100644 carla_ad_demo/config/sensors.json create mode 100644 carla_ad_demo/launch/carla_ad_demo.launch create mode 100644 carla_ad_demo/launch/carla_ad_demo_with_rviz.launch create mode 100644 carla_ad_demo/package.xml create mode 100644 carla_ros_scenario_runner/CMakeLists.txt create mode 100644 carla_ros_scenario_runner/README.md create mode 100644 carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch create mode 100644 carla_ros_scenario_runner/package.xml create mode 100644 carla_ros_scenario_runner/setup.py create mode 100644 carla_ros_scenario_runner/src/carla_ros_scenario_runner/__init__.py create mode 100755 carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py create mode 100755 carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py create mode 100755 carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py create mode 100644 carla_ros_scenario_runner_types/CMakeLists.txt create mode 100644 carla_ros_scenario_runner_types/msg/CarlaScenario.msg create mode 100644 carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg create mode 100644 carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg create mode 100644 carla_ros_scenario_runner_types/package.xml create mode 100644 carla_ros_scenario_runner_types/srv/ExecuteScenario.srv create mode 100644 carla_twist_to_control/README.md create mode 100644 docs/images/rviz_carla_plugin.png create mode 100644 rviz_carla_plugin/CMakeLists.txt create mode 100644 rviz_carla_plugin/README.md create mode 100644 rviz_carla_plugin/icons/classes/CarlaControl.png create mode 100644 rviz_carla_plugin/icons/pause.png create mode 100644 rviz_carla_plugin/icons/play.png create mode 100644 rviz_carla_plugin/icons/step_once.png create mode 100644 rviz_carla_plugin/package.xml create mode 100644 rviz_carla_plugin/plugin_description.xml create mode 100644 rviz_carla_plugin/rviz_carla_plugin.qrc create mode 100644 rviz_carla_plugin/src/carla_control_panel.cpp create mode 100644 rviz_carla_plugin/src/carla_control_panel.h create mode 100644 rviz_carla_plugin/src/drive_widget.cpp create mode 100644 rviz_carla_plugin/src/drive_widget.h create mode 100644 rviz_carla_plugin/src/indicator_widget.cpp create mode 100644 rviz_carla_plugin/src/indicator_widget.h diff --git a/CHANGELOG.md b/CHANGELOG.md index 9583ed44..79d65801 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -7,6 +7,10 @@ * Add node to convert a twist to a vehicle control command * Add node carla_spectator_camera * Update carla_waypoint_publisher +* Add carla_ros_scenario_runner +* Add rviz_carla_plugin +* Add carla_ad_agent +* Add carla_ad_demo ## CARLA-ROS-Bridge 0.9.6 diff --git a/README.md b/README.md index a075a57b..5f2dba4c 100644 --- a/README.md +++ b/README.md @@ -48,24 +48,18 @@ For more information about configuring a ROS environment see First run the simulator (see carla documentation: ) - ./CarlaUE4.sh -windowed -ResX=320 -ResY=240 + # run carla in background + SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl -Wait for the message: +Wait a few seconds, then start the ros bridge (choose one option): - Waiting for the client to connect... - -Then start the ros bridge (choose one option): - - export PYTHONPATH=$PYTHONPATH:/PythonAPI/ + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg source ~/carla-ros-bridge/catkin_ws/devel/setup.bash # Option 1: start the ros bridge roslaunch carla_ros_bridge carla_ros_bridge.launch - # Option 2: start the ros bridge together with RVIZ - roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch - - # Option 3: start the ros bridge together with an example ego vehicle + # Option 2: start the ros bridge together with an example ego vehicle roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch ## Settings @@ -267,17 +261,19 @@ The following markers are supported in 'map'-frame: | ---------------------------------- | ------------------------------------------------------------------------------------------------------ | --------------------------- | | `/carla/debug_marker` (subscriber) | [visualization_msgs.MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) | draw markers in CARLA world | -## Carla Ego Vehicle - -`carla_ego_vehicle` provides a generic way to spawn an ego vehicle and attach sensors to it. You can find further documentation [here](carla_ego_vehicle/README.md). - -## Carla Infrastructure Sensors - -`carla_infrastructure` provides a generic way to spawn a set of infrastructure sensors defined in a config file. You can find further documentation [here](carla_infrastructure/README.md). -## Waypoint calculation +## Additional Functionality -To make use of the Carla waypoint calculation a ROS Node is available to get waypoints. You can find further documentation [here](carla_waypoint_publisher/README.md). +| Name | Description | +| --------------------------------- | ------------------------------------------------------------------------------------------------------- | +| [Carla Ego Vehicle](carla_ego_vehicle/README.md) | Provides a generic way to spawn an ego vehicle and attach sensors to it. | +| [Carla Infrastructure](carla_infrastructure/README.md) | Provides a generic way to spawn a set of infrastructure sensors defined in a config file. | +| [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API | +| [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. | +| [Carla AD Agent](carla_ad_agent/README.md) | A basic AD agent, that can follow a route and avoid collisions with other vehicles and stop on red traffic lights. | +| [Carla AD Demo](carla_ad_demo/README.md) | A meta package that provides everything to launch a CARLA ROS environment with an AD vehicle. | +| [RVIZ Carla Plugin](rviz_carla_plugin/README.md) | A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. | +| [RQT Carla Plugin](rqt_carla_plugin/README.md) | A [RQT](http://wiki.ros.org/rqt) plugin to control CARLA. | ## Troubleshooting @@ -285,7 +281,7 @@ To make use of the Carla waypoint calculation a ROS Node is available to get way You're missing Carla Python. Please execute: - export PYTHONPATH=$PYTHONPATH:/PythonAPI/ + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/ Please note that you have to put in the complete path to the egg-file including the egg-file itself. Please use the one, that is supported by your Python version. diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt new file mode 100644 index 00000000..8f5a7216 --- /dev/null +++ b/carla_ad_agent/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_ad_agent) + +find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch +) + +catkin_python_setup() + +roslaunch_add_file_check(launch) + +catkin_package( + CATKIN_DEPENDS + rospy +) + +catkin_install_python(PROGRAMS + src/carla_ad_agent/carla_ad_agent.py + src/carla_ad_agent/basic_agent.py + src/carla_ad_agent/agent.py + src/carla_ad_agent/local_planner.py + src/carla_ad_agent/vehicle_pid_controller.py + src/carla_ad_agent/misc.py + src/carla_ad_agent/__init__.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + diff --git a/carla_ad_agent/README.md b/carla_ad_agent/README.md new file mode 100644 index 00000000..63ee8ffd --- /dev/null +++ b/carla_ad_agent/README.md @@ -0,0 +1,13 @@ +# CARLA AD Agent + +An AD agent that can follow a given route. + +It avoids crashs with other vehicles and respects the state of the traffic lights. + +For a more comprehensive solution, have a look at [Autoware](https://www.autoware.ai/). + +## Publications + +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | +| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) | Vehicle control command | diff --git a/carla_ad_agent/launch/carla_ad_agent.launch b/carla_ad_agent/launch/carla_ad_agent.launch new file mode 100644 index 00000000..209de6b8 --- /dev/null +++ b/carla_ad_agent/launch/carla_ad_agent.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/carla_ad_agent/package.xml b/carla_ad_agent/package.xml new file mode 100644 index 00000000..d2b3d2a5 --- /dev/null +++ b/carla_ad_agent/package.xml @@ -0,0 +1,18 @@ + + + carla_ad_agent + 0.0.1 + The carla_ad_agent package + CARLA Simulator Team + MIT + catkin + rospy + roslaunch + rospy + rospy + topic_tools + carla_waypoint_types + carla_msgs + + + diff --git a/carla_ad_agent/setup.py b/carla_ad_agent/setup.py new file mode 100644 index 00000000..0af8e3a7 --- /dev/null +++ b/carla_ad_agent/setup.py @@ -0,0 +1,10 @@ +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_ad_agent'], + package_dir={'': 'src'} +) + +setup(**d) + diff --git a/carla_ad_agent/src/carla_ad_agent/__init__.py b/carla_ad_agent/src/carla_ad_agent/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py new file mode 100644 index 00000000..c1cc8c55 --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -0,0 +1,290 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +Base class for agent +""" + +from enum import Enum +import math +import rospy +from tf.transformations import euler_from_quaternion +from misc import is_within_distance_ahead, compute_magnitude_angle +from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus,\ + CarlaTrafficLightStatusList, CarlaWorldInfo +from carla_waypoint_types.srv import GetWaypoint + + +class AgentState(Enum): + """ + AGENT_STATE represents the possible states of a roaming agent + """ + NAVIGATING = 1 + BLOCKED_BY_VEHICLE = 2 + BLOCKED_RED_LIGHT = 3 + + +class Agent(object): + """ + Base class for agent + """ + + def __init__(self, role_name, vehicle_id): + """ + """ + self._proximity_threshold = 10.0 # meters + self._local_planner = None + self._map_name = None + self._vehicle_location = None + self._vehicle_yaw = None + self._vehicle_id = vehicle_id + self._last_traffic_light = None + + rospy.wait_for_service('/carla_waypoint_publisher/{}/get_waypoint'.format(role_name)) + + self._get_waypoint_client = rospy.ServiceProxy( + '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) + + self._traffic_lights = [] + self._traffic_light_status_subscriber = rospy.Subscriber( + "/carla/traffic_lights", CarlaTrafficLightStatusList, self.traffic_lights_updated) + + self._world_info_subscriber = rospy.Subscriber( + "/carla/world_info", CarlaWorldInfo, self.world_info_updated) + + def traffic_lights_updated(self, traffic_lights): + """ + callback on new traffic light list + """ + self._traffic_lights = traffic_lights.traffic_lights + + def world_info_updated(self, world_info): + """ + callback on new world info + """ + self._map_name = world_info.map_name + + def odometry_updated(self, odo): + """ + callback on new odometry + """ + self._vehicle_location = odo.pose.pose.position + quaternion = ( + odo.pose.pose.orientation.x, + odo.pose.pose.orientation.y, + odo.pose.pose.orientation.z, + odo.pose.pose.orientation.w + ) + _, _, self._vehicle_yaw = euler_from_quaternion(quaternion) + + def run_step(self, target_speed): # pylint: disable=no-self-use,unused-argument + """ + Execute one step of navigation. + :return: control + """ + control = CarlaEgoVehicleControl() + return control + + def _is_light_red(self, lights_list): + """ + Method to check if there is a red light affecting us. This version of + the method is compatible with both European and US style traffic lights. + + :param lights_list: list containing TrafficLight objects + :return: a tuple given by (bool_flag, traffic_light), where + - bool_flag is True if there is a traffic light in RED + affecting us and False otherwise + - traffic_light is the object itself or None if there is no + red traffic light affecting us + """ + if self._map_name == 'Town01' or self._map_name == 'Town02': + return self._is_light_red_europe_style(lights_list) + else: + return self._is_light_red_us_style(lights_list) + + def _is_light_red_europe_style(self, lights_list): + """ + This method is specialized to check European style traffic lights. + + :param lights_list: list containing TrafficLight objects + :return: a tuple given by (bool_flag, traffic_light), where + - bool_flag is True if there is a traffic light in RED + affecting us and False otherwise + - traffic_light is the object itself or None if there is no + red traffic light affecting us + """ + ego_vehicle_location = self._vehicle_location + ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) + if not ego_vehicle_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for ego vehicle.") + return (False, None) + + for traffic_light in lights_list: + object_waypoint = traffic_light[1] + if object_waypoint.road_id != ego_vehicle_waypoint.road_id or \ + object_waypoint.lane_id != ego_vehicle_waypoint.lane_id: + continue + if is_within_distance_ahead(object_waypoint.pose.position, ego_vehicle_location, + math.degrees(self._vehicle_yaw), + self._proximity_threshold): + traffic_light_state = CarlaTrafficLightStatus.RED + for status in self._traffic_lights: + if status.id == traffic_light[0]: + traffic_light_state = status.state + break + if traffic_light_state == CarlaTrafficLightStatus.RED: + return (True, traffic_light[0]) + + return (False, None) + + def get_waypoint(self, location): + """ + Helper to get waypoint for location via ros service + """ + if rospy.is_shutdown(): + return None + try: + response = self._get_waypoint_client(location) + return response.waypoint + except (rospy.ServiceException, rospy.ROSInterruptException) as e: + if not rospy.is_shutdown(): + rospy.logwarn("Service call 'get_waypoint' failed: {}".format(e)) + + def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branches + """ + This method is specialized to check US style traffic lights. + + :param lights_list: list containing TrafficLight objects + :return: a tuple given by (bool_flag, traffic_light), where + - bool_flag is True if there is a traffic light in RED + affecting us and False otherwise + - traffic_light is the object itself or None if there is no + red traffic light affecting us + """ + ego_vehicle_location = self._vehicle_location + ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) + if not ego_vehicle_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for ego vehicle.") + return (False, None) + + if ego_vehicle_waypoint.is_junction: + # It is too late. Do not block the intersection! Keep going! + return (False, None) + + if self._local_planner.target_waypoint is not None: + if self._local_planner.target_waypoint.is_junction: + min_angle = 180.0 + sel_magnitude = 0.0 # pylint: disable=unused-variable + sel_traffic_light = None + for traffic_light in lights_list: + loc = traffic_light[1] + magnitude, angle = compute_magnitude_angle(loc.pose.position, + ego_vehicle_location, + math.degrees(self._vehicle_yaw)) + if magnitude < 60.0 and angle < min(25.0, min_angle): + sel_magnitude = magnitude + sel_traffic_light = traffic_light[0] + min_angle = angle + + if sel_traffic_light is not None: + # print('=== Magnitude = {} | Angle = {} | ID = {}'.format( + # sel_magnitude, min_angle, sel_traffic_light)) + + if self._last_traffic_light is None: + self._last_traffic_light = sel_traffic_light + + state = None + for status in self._traffic_lights: + if status.id == sel_traffic_light: + state = status.state + break + if state is None: + rospy.logwarn( + "Couldn't get state of traffic light {}".format( + sel_traffic_light)) + return (False, None) + + if state == CarlaTrafficLightStatus.RED: + return (True, self._last_traffic_light) + else: + self._last_traffic_light = None + + return (False, None) + + def _is_vehicle_hazard(self, vehicle_list, objects): + """ + Check if a given vehicle is an obstacle in our way. To this end we take + into account the road and lane the target vehicle is on and run a + geometry test to check if the target vehicle is under a certain distance + in front of our ego vehicle. + + WARNING: This method is an approximation that could fail for very large + vehicles, which center is actually on a different lane but their + extension falls within the ego vehicle lane. + + :param vehicle_list: list of potential obstacle to check + :return: a tuple given by (bool_flag, vehicle), where + - bool_flag is True if there is a vehicle ahead blocking us + and False otherwise + - vehicle is the blocker object itself + """ + + ego_vehicle_location = self._vehicle_location + + ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) + if not ego_vehicle_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for ego vehicle.") + return (False, None) + + for target_vehicle_id in vehicle_list: + # do not account for the ego vehicle + if target_vehicle_id == self._vehicle_id: + continue + + target_vehicle_location = None + for elem in objects: + if elem.id == target_vehicle_id: + target_vehicle_location = elem.pose + break + + if not target_vehicle_location: + rospy.logwarn("Location of vehicle {} not found".format(target_vehicle_id)) + continue + + # if the object is not in our lane it's not an obstacle + target_vehicle_waypoint = self.get_waypoint(target_vehicle_location.position) + if not target_vehicle_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for target vehicle.") + return (False, None) + if target_vehicle_waypoint.road_id != ego_vehicle_waypoint.road_id or \ + target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id: + #rospy.loginfo("Vehicle {} is not in our lane".format(target_vehicle_id)) + continue + + if is_within_distance_ahead(target_vehicle_location.position, self._vehicle_location, + math.degrees(self._vehicle_yaw), + self._proximity_threshold): + return (True, target_vehicle_id) + + return (False, None) + + def emergency_stop(self): # pylint: disable=no-self-use + """ + Send an emergency stop command to the vehicle + :return: + """ + control = CarlaEgoVehicleControl() + control.steer = 0.0 + control.throttle = 0.0 + control.brake = 1.0 + control.hand_brake = False + + return control diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py new file mode 100644 index 00000000..91ac8ee1 --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -0,0 +1,129 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +BasicAgent implements a basic agent that navigates scenes to reach a given +target destination. This agent respects traffic lights and other vehicles. +""" + +import rospy +from nav_msgs.msg import Odometry +from derived_object_msgs.msg import ObjectArray +from carla_msgs.msg import CarlaActorList +from agent import Agent, AgentState +from local_planner import LocalPlanner +from carla_waypoint_types.srv import GetActorWaypoint + + +class BasicAgent(Agent): + """ + BasicAgent implements a basic agent that navigates scenes to reach a given + target destination. This agent respects traffic lights and other vehicles. + """ + + def __init__(self, role_name, ego_vehicle_id, avoid_risk=True): + """ + """ + super(BasicAgent, self).__init__(role_name, ego_vehicle_id) + + self._proximity_threshold = 10.0 # meters + self._state = AgentState.NAVIGATING + self._avoid_risk = avoid_risk + args_lateral_dict = { + 'K_P': 0.9, + 'K_D': 0.0, + 'K_I': 0.1} + self._local_planner = LocalPlanner(role_name, + opt_dict={'lateral_control_dict': args_lateral_dict}) + + self._vehicle_id_list = [] + self._lights_id_list = [] + self._actors_subscriber = rospy.Subscriber( + "/carla/actor_list", CarlaActorList, self.actors_updated) + self._objects = [] + self._objects_subscriber = rospy.Subscriber( + "/carla/{}/objects".format(role_name), ObjectArray, self.objects_updated) + + self._odometry_subscriber = rospy.Subscriber( + "/carla/{}/odometry".format(role_name), Odometry, self.odometry_updated) + + self._get_actor_waypoint_client = rospy.ServiceProxy( + '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), GetActorWaypoint) + + def get_actor_waypoint(self, actor_id): + """ + helper method to get waypoint for actor via ros service + """ + try: + response = self._get_actor_waypoint_client(actor_id) + return response.waypoint + except (rospy.ServiceException, rospy.ROSInterruptException) as e: + if not rospy.is_shutdown: + rospy.logwarn("Service call failed: {}".format(e)) + + def odometry_updated(self, odo): + """ + callback on new odometry + """ + self._local_planner.odometry_updated(odo) + super(BasicAgent, self).odometry_updated(odo) + + def actors_updated(self, actors): + """ + callback on new actor list + """ + # retrieve relevant elements for safe navigation, i.e.: traffic lights + # and other vehicles + self._vehicle_id_list = [] + self._lights_id_list = [] + for actor in actors.actors: + if "vehicle" in actor.type: + self._vehicle_id_list.append(actor.id) + elif "traffic_light" in actor.type: + self._lights_id_list.append((actor.id, self.get_actor_waypoint(actor.id))) + + def objects_updated(self, objects): + """ + callback on new objects + """ + self._objects = objects.objects + + def run_step(self, target_speed): + """ + Execute one step of navigation. + :return: carla.VehicleControl + """ + + # is there an obstacle in front of us? + hazard_detected = False + + if self._avoid_risk: + # check possible obstacles + vehicle_state, vehicle = self._is_vehicle_hazard( # pylint: disable=unused-variable + self._vehicle_id_list, self._objects) + if vehicle_state: + #rospy.loginfo('=== Vehicle blocking ahead [{}])'.format(vehicle)) + self._state = AgentState.BLOCKED_BY_VEHICLE + hazard_detected = True + + # check for the state of the traffic lights + light_state, traffic_light = self._is_light_red( # pylint: disable=unused-variable + self._lights_id_list) + if light_state: + #rospy.loginfo('=== Red Light ahead [{}])'.format(traffic_light)) + + self._state = AgentState.BLOCKED_RED_LIGHT + hazard_detected = True + + if hazard_detected: + control = self.emergency_stop() + else: + self._state = AgentState.NAVIGATING + # standard local planner behavior + control = self._local_planner.run_step(target_speed) + + return control diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py new file mode 100755 index 00000000..9c3abff8 --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -0,0 +1,133 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +A basic AD agent using CARLA waypoints +""" +import rospy +from nav_msgs.msg import Path +from std_msgs.msg import Float64 +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl +from basic_agent import BasicAgent + + +class CarlaAdAgent(object): + """ + A basic AD agent using CARLA waypoints + """ + + def __init__(self, role_name, target_speed, avoid_risk): + """ + Constructor + """ + self._route_assigned = False + self._global_plan = None + self._agent = None + self._target_speed = target_speed + rospy.on_shutdown(self.on_shutdown) + + # wait for ego vehicle + vehicle_info = rospy.wait_for_message( + "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) + + self._route_subscriber = rospy.Subscriber( + "/carla/{}/waypoints".format(role_name), Path, self.path_updated) + + self._target_speed_subscriber = rospy.Subscriber( + "/carla/{}/target_speed".format(role_name), Float64, self.target_speed_updated) + + self.vehicle_control_publisher = rospy.Publisher( + "/carla/{}/vehicle_control_cmd".format(role_name), CarlaEgoVehicleControl, queue_size=1) + + self._agent = BasicAgent(role_name, vehicle_info.id, # pylint: disable=no-member + avoid_risk) + + def on_shutdown(self): + """ + callback on shutdown + """ + rospy.loginfo("Shutting down, stopping ego vehicle...") + if self._agent: + self.vehicle_control_publisher.publish(self._agent.emergency_stop()) + + def target_speed_updated(self, target_speed): + """ + callback on new target speed + """ + rospy.loginfo("New target speed received: {}".format(target_speed.data)) + self._target_speed = target_speed.data + + def path_updated(self, path): + """ + callback on new route + """ + rospy.loginfo("New plan with {} waypoints received.".format(len(path.poses))) + if self._agent: + self.vehicle_control_publisher.publish(self._agent.emergency_stop()) + self._global_plan = path + self._route_assigned = False + + def run_step(self): + """ + Execute one step of navigation. + """ + control = CarlaEgoVehicleControl() + control.steer = 0.0 + control.throttle = 0.0 + control.brake = 0.0 + control.hand_brake = False + + if not self._agent: + rospy.loginfo("Waiting for ego vehicle...") + return control + + if not self._route_assigned and self._global_plan: + rospy.loginfo("Assigning plan...") + self._agent._local_planner.set_global_plan( # pylint: disable=protected-access + self._global_plan.poses) + self._route_assigned = True + else: + control = self._agent.run_step(self._target_speed) + + return control + + def run(self): + """ + + Control loop + + :return: + """ + + while not rospy.is_shutdown(): + control = self.run_step() + if control: + control.steer = -control.steer + self.vehicle_control_publisher.publish(control) + + +def main(): + """ + + main function + + :return: + """ + rospy.init_node('carla_ad_agent', anonymous=True) + role_name = rospy.get_param("~role_name", "ego_vehicle") + target_speed = rospy.get_param("~target_speed", 20) + avoid_risk = rospy.get_param("~avoid_risk", True) + controller = CarlaAdAgent(role_name, target_speed, avoid_risk) + try: + controller.run() + finally: + del controller + rospy.loginfo("Done") + + +if __name__ == "__main__": + main() diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py new file mode 100644 index 00000000..ab14dfca --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -0,0 +1,203 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +This module contains a local planner to perform +low-level waypoint following based on PID controllers. +""" + +from collections import deque +import math +import rospy +from geometry_msgs.msg import PointStamped +from geometry_msgs.msg import Pose +from tf.transformations import euler_from_quaternion +from carla_waypoint_types.srv import GetWaypoint +from carla_msgs.msg import CarlaEgoVehicleControl +from vehicle_pid_controller import VehiclePIDController +from misc import distance_vehicle + + +class LocalPlanner(object): + """ + LocalPlanner implements the basic behavior of following a trajectory of waypoints that is + generated on-the-fly. The low-level motion of the vehicle is computed by using two PID + controllers, one is used for the lateral control and the other for the longitudinal + control (cruise speed). + + When multiple paths are available (intersections) this local planner makes a random choice. + """ + + # minimum distance to target waypoint as a percentage (e.g. within 90% of + # total distance) + MIN_DISTANCE_PERCENTAGE = 0.9 + + def __init__(self, role_name, opt_dict=None): + """ + :param vehicle: actor to apply to local planner logic onto + :param opt_dict: dictionary of arguments with the following semantics: + + target_speed -- desired cruise speed in Km/h + + sampling_radius -- search radius for next waypoints in seconds: e.g. 0.5 seconds ahead + + lateral_control_dict -- dictionary of arguments to setup the lateral PID controller + {'K_P':, 'K_D':, 'K_I'} + + longitudinal_control_dict -- dictionary of arguments to setup the longitudinal + PID controller + {'K_P':, 'K_D':, 'K_I'} + """ + self._current_waypoint = None + self.target_waypoint = None + self._vehicle_controller = None + self._global_plan = None + self._waypoints_queue = deque(maxlen=20000) + self._buffer_size = 5 + self._waypoint_buffer = deque(maxlen=self._buffer_size) + self._vehicle_yaw = None + self._current_speed = None + self._current_pose = None + + self._target_point_publisher = rospy.Publisher( + "/next_target", PointStamped, queue_size=1) + rospy.wait_for_service('/carla_waypoint_publisher/{}/get_waypoint'.format(role_name)) + + self._get_waypoint_client = rospy.ServiceProxy( + '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) + + # initializing controller + self._init_controller(opt_dict) + + def get_waypoint(self, location): + """ + Helper to get waypoint from a ros service + """ + try: + response = self._get_waypoint_client(location) + return response.waypoint + except (rospy.ServiceException, rospy.ROSInterruptException) as e: + if not rospy.is_shutdown: + rospy.logwarn("Service call failed: {}".format(e)) + + def odometry_updated(self, odo): + """ + Callback on new odometry + """ + self._current_speed = math.sqrt(odo.twist.twist.linear.x ** 2 + + odo.twist.twist.linear.y ** 2 + + odo.twist.twist.linear.z ** 2) * 3.6 + + self._current_pose = odo.pose.pose + quaternion = ( + odo.pose.pose.orientation.x, + odo.pose.pose.orientation.y, + odo.pose.pose.orientation.z, + odo.pose.pose.orientation.w + ) + _, _, self._vehicle_yaw = euler_from_quaternion(quaternion) + + def _init_controller(self, opt_dict): + """ + Controller initialization. + + :param opt_dict: dictionary of arguments. + :return: + """ + # default params + self._current_speed = 0.0 # Km/h + self._current_pose = Pose() + args_lateral_dict = { + 'K_P': 1.95, + 'K_D': 0.01, + 'K_I': 1.4} + args_longitudinal_dict = { + 'K_P': 0.2, + 'K_D': 0.05, + 'K_I': 0.1} + + # parameters overload + if opt_dict: + if 'lateral_control_dict' in opt_dict: + args_lateral_dict = opt_dict['lateral_control_dict'] + if 'longitudinal_control_dict' in opt_dict: + args_longitudinal_dict = opt_dict['longitudinal_control_dict'] + + self._current_waypoint = self.get_waypoint(self._current_pose.position) + self._vehicle_controller = VehiclePIDController(args_lateral=args_lateral_dict, + args_longitudinal=args_longitudinal_dict) + + self._global_plan = False + + def set_global_plan(self, current_plan): + """ + set a global plan to follow + """ + self._waypoints_queue.clear() + self._waypoint_buffer.clear() + for elem in current_plan: + self._waypoints_queue.append(elem.pose) + self._global_plan = True + + def run_step(self, target_speed): + """ + Execute one step of local planning which involves running the longitudinal + and lateral PID controllers to follow the waypoints trajectory. + """ + if not self._waypoints_queue: + control = CarlaEgoVehicleControl() + control.steer = 0.0 + control.throttle = 0.0 + control.brake = 1.0 + control.hand_brake = False + control.manual_gear_shift = False + + return control + + # Buffering the waypoints + if not self._waypoint_buffer: + for i in range(self._buffer_size): + if self._waypoints_queue: + self._waypoint_buffer.append( + self._waypoints_queue.popleft()) + else: + break + + # current vehicle waypoint + self._current_waypoint = self.get_waypoint(self._current_pose.position) + + # target waypoint + target_route_point = self._waypoint_buffer[0] + + # for us redlight-detection + self.target_waypoint = self.get_waypoint(target_route_point.position) + + target_point = PointStamped() + target_point.header.frame_id = "map" + target_point.point.x = target_route_point.position.x + target_point.point.y = target_route_point.position.y + target_point.point.z = target_route_point.position.z + self._target_point_publisher.publish(target_point) + # move using PID controllers + control = self._vehicle_controller.run_step( + target_speed, self._current_speed, self._current_pose, target_route_point) + + # purge the queue of obsolete waypoints + max_index = -1 + + sampling_radius = target_speed * 1 / 3.6 # 1 seconds horizon + min_distance = sampling_radius * self.MIN_DISTANCE_PERCENTAGE + + for i, route_point in enumerate(self._waypoint_buffer): + if distance_vehicle( + route_point, self._current_pose.position) < min_distance: + max_index = i + if max_index >= 0: + for i in range(max_index + 1): + self._waypoint_buffer.popleft() + + return control diff --git a/carla_ad_agent/src/carla_ad_agent/misc.py b/carla_ad_agent/src/carla_ad_agent/misc.py new file mode 100644 index 00000000..9495b815 --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/misc.py @@ -0,0 +1,70 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" This module contains helper functions """ + +import math +import numpy as np + + +def is_within_distance_ahead(target_location, current_location, orientation, max_distance): + """ + Check if a target object is within a certain distance in front of a reference object. + + :param target_location: location of the target object + :param current_location: location of the reference object + :param orientation: orientation of the reference object + :param max_distance: maximum allowed distance + :return: True if target object is within max_distance ahead of the reference object + """ + target_vector = np.array([target_location.x - current_location.x, + target_location.y - current_location.y]) + norm_target = np.linalg.norm(target_vector) + + # If the vector is too short, we can simply stop here + if norm_target < 0.001: + return True + + if norm_target > max_distance: + return False + + forward_vector = np.array( + [math.cos(math.radians(orientation)), math.sin(math.radians(orientation))]) + d_angle = math.degrees(math.acos(np.dot(forward_vector, target_vector) / norm_target)) + + return d_angle < 90.0 + + +def compute_magnitude_angle(target_location, current_location, orientation): + """ + Compute relative angle and distance between a target_location and a current_location + + :param target_location: location of the target object + :param current_location: location of the reference object + :param orientation: orientation of the reference object + :return: a tuple composed by the distance to the object and the angle between both objects + """ + target_vector = np.array([target_location.x - current_location.x, + target_location.y - current_location.y]) + norm_target = np.linalg.norm(target_vector) + + forward_vector = np.array([math.cos(math.radians(orientation)), + math.sin(math.radians(orientation))]) + d_angle = math.degrees( + math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.))) + + return (norm_target, d_angle) + + +def distance_vehicle(waypoint, vehicle_position): + """ + calculate distance between waypoint and vehicle position + """ + dx = waypoint.position.x - vehicle_position.x + dy = waypoint.position.y - vehicle_position.y + + return math.sqrt(dx * dx + dy * dy) diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py new file mode 100644 index 00000000..6d19936d --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -0,0 +1,170 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +""" This module contains PID controllers to perform lateral and longitudinal control. """ + +from collections import deque +import math +import numpy as np +import rospy +from tf.transformations import euler_from_quaternion +from geometry_msgs.msg import Point +from carla_msgs.msg import CarlaEgoVehicleControl + + +class VehiclePIDController(object): # pylint: disable=too-few-public-methods + """ + VehiclePIDController is the combination of two PID controllers (lateral and longitudinal) + to perform the low level control a vehicle from client side + """ + + def __init__(self, args_lateral=None, args_longitudinal=None): + """ + :param vehicle: actor to apply to local planner logic onto + :param args_lateral: dictionary of arguments to set the lateral PID controller using + the following semantics: + K_P -- Proportional term + K_D -- Differential term + K_I -- Integral term + :param args_longitudinal: dictionary of arguments to set the longitudinal PID + controller using the following semantics: + K_P -- Proportional term + K_D -- Differential term + K_I -- Integral term + """ + if not args_lateral: + args_lateral = {'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0} + if not args_longitudinal: + args_longitudinal = {'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0} + + self._lon_controller = PIDLongitudinalController(**args_longitudinal) + self._lat_controller = PIDLateralController(**args_lateral) + self._last_control_time = rospy.get_time() + + def run_step(self, target_speed, current_speed, current_pose, waypoint): + """ + Execute one step of control invoking both lateral and longitudinal + PID controllers to reach a target waypoint at a given target_speed. + + :param target_speed: desired vehicle speed + :param waypoint: target location encoded as a waypoint + :return: distance (in meters) to the waypoint + """ + current_time = rospy.get_time() + dt = current_time-self._last_control_time + if dt == 0.0: + dt = 0.000001 + control = CarlaEgoVehicleControl() + throttle = self._lon_controller.run_step(target_speed, current_speed, dt) + steering = self._lat_controller.run_step(current_pose, waypoint, dt) + self._last_control_time = current_time + control.steer = steering + control.throttle = throttle + control.brake = 0.0 + control.hand_brake = False + control.manual_gear_shift = False + + return control + + +class PIDLongitudinalController(object): # pylint: disable=too-few-public-methods + """ + PIDLongitudinalController implements longitudinal control using a PID. + """ + + def __init__(self, K_P=1.0, K_D=0.0, K_I=0.0): + """ + :param vehicle: actor to apply to local planner logic onto + :param K_P: Proportional term + :param K_D: Differential term + :param K_I: Integral term + """ + self._K_P = K_P + self._K_D = K_D + self._K_I = K_I + self._e_buffer = deque(maxlen=30) + + def run_step(self, target_speed, current_speed, dt): + """ + Estimate the throttle of the vehicle based on the PID equations + + :param target_speed: target speed in Km/h + :param current_speed: current speed of the vehicle in Km/h + :return: throttle control in the range [0, 1] + """ + _e = (target_speed - current_speed) + self._e_buffer.append(_e) + + if len(self._e_buffer) >= 2: + _de = (self._e_buffer[-1] - self._e_buffer[-2]) / dt + _ie = sum(self._e_buffer) * dt + else: + _de = 0.0 + _ie = 0.0 + + return np.clip((self._K_P * _e) + (self._K_D * _de / dt) + (self._K_I * _ie * dt), 0.0, 1.0) + + +class PIDLateralController(object): # pylint: disable=too-few-public-methods + """ + PIDLateralController implements lateral control using a PID. + """ + + def __init__(self, K_P=1.0, K_D=0.0, K_I=0.0): + """ + :param vehicle: actor to apply to local planner logic onto + :param K_P: Proportional term + :param K_D: Differential term + :param K_I: Integral term + """ + self._K_P = K_P + self._K_D = K_D + self._K_I = K_I + self._e_buffer = deque(maxlen=10) + + def run_step(self, current_pose, waypoint, dt): + """ + Estimate the steering angle of the vehicle based on the PID equations + + :param waypoint: target waypoint + :param current_pose: current pose of the vehicle + :return: steering control in the range [-1, 1] + """ + v_begin = current_pose.position + quaternion = ( + current_pose.orientation.x, + current_pose.orientation.y, + current_pose.orientation.z, + current_pose.orientation.w + ) + _, _, yaw = euler_from_quaternion(quaternion) + v_end = Point() + v_end.x = v_begin.x + math.cos(yaw) + v_end.y = v_begin.y + math.sin(yaw) + + v_vec = np.array([v_end.x - v_begin.x, v_end.y - v_begin.y, 0.0]) + w_vec = np.array([waypoint.position.x - + v_begin.x, waypoint.position.y - + v_begin.y, 0.0]) + _dot = math.acos(np.clip(np.dot(w_vec, v_vec) / + (np.linalg.norm(w_vec) * np.linalg.norm(v_vec)), -1.0, 1.0)) + + _cross = np.cross(v_vec, w_vec) + if _cross[2] < 0: + _dot *= -1.0 + + self._e_buffer.append(_dot) + if len(self._e_buffer) >= 2: + _de = (self._e_buffer[-1] - self._e_buffer[-2]) / dt + _ie = sum(self._e_buffer) * dt + else: + _de = 0.0 + _ie = 0.0 + + return np.clip((self._K_P * _dot) + (self._K_D * _de / + dt) + (self._K_I * _ie * dt), -1.0, 1.0) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt new file mode 100644 index 00000000..56b4a771 --- /dev/null +++ b/carla_ad_demo/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_ad_demo) + +find_package(catkin REQUIRED COMPONENTS + roslaunch +) + + +roslaunch_add_file_check(launch) + +catkin_package() + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + +install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config +) diff --git a/carla_ad_demo/README.md b/carla_ad_demo/README.md new file mode 100644 index 00000000..e6b17f51 --- /dev/null +++ b/carla_ad_demo/README.md @@ -0,0 +1,36 @@ +# CARLA AD Demo + +This meta package provides everything to launch a CARLA ROS environment with an AD vehicle. + + +![CARLA AD Demo](../docs/images/rviz_carla_plugin.png "rviz carla plugin") + + +## Startup + + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ + export SCENARIO_RUNNER_PATH:= + roslaunch carla_ad_demo carla_ad_demo_with_rviz.launch + +### Modes + +#### Following A Random Route + +On startup, an ego vehicle is spawned and follows a random route to a goal. + +You might want to spawn additional vehicles (or pedestrians) by manually executing: + + /PythonAPI/examples/spawn_npc.py + +You can modify start position and goal within the [launch file](launch/carla_ad_demo.launch). The route is currently randomly (regarding the left/right turns) calculated. + +#### Scenario Execution + +If you prefer to execute a predefined scenario, select to example scenario "FollowLeadingVehicle" within the RVIZ Carla Plugin and press "Execute". The ego vehicle gets repositioned and the scenario is processed. + +You can specify your own scenarios by publishing to `/carla/available_scenarios`. See the [launch file](launch/carla_ad_demo_with_rviz.launch) for an example. + + +## Troubleshooting + +If the example scenario fails, please analyze the ros log and follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working standalone. diff --git a/carla_ad_demo/config/FollowLeadingVehicle.xosc b/carla_ad_demo/config/FollowLeadingVehicle.xosc new file mode 100644 index 00000000..db33827d --- /dev/null +++ b/carla_ad_demo/config/FollowLeadingVehicle.xosc @@ -0,0 +1,270 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + + +
+ + + + + +
+ + + + + + + + + + + +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz new file mode 100644 index 00000000..35fd2f9d --- /dev/null +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -0,0 +1,173 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 78 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Camera + - Class: rviz_carla_plugin/CarlaControl + Name: CarlaControl +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /carla/ego_vehicle/waypoints + Unreliable: false + Value: true + - Class: rviz/Camera + Enabled: true + Image Rendering: background and overlay + Image Topic: /carla/ego_vehicle/camera/rgb/spectator_view/image_color + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Visibility: + Grid: true + Marker: true + Path: true + Value: true + Zoom Factor: 1 + - Class: rviz/Marker + Enabled: true + Marker Topic: /carla/marker + Name: Marker + Namespaces: + "": true + Queue Size: 100 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/ThirdPersonFollower + Distance: 13.610654830932617 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.49539870023727417 + Target Frame: ego_vehicle + Value: ThirdPersonFollower (rviz) + Yaw: 3.1504008769989014 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + CarlaControl: + collapsed: false + Displays: + collapsed: false + Height: 1050 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001fe00000367fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000046000000e6000000e600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002870000001a0000000000000000fb0000000a0049006d00610067006501000002a70000001a0000000000000000fb0000000a0049006d00610067006501000002c70000001a0000000000000000fb0000000c00430061006d0065007200610100000132000001960000001a00fffffffb00000018004300610072006c00610043006f006e00740072006f006c01000002ce000000df000000df00ffffff000000010000010f00000367fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004600000367000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077e00000044fc0100000002fb0000000800540069006d006501000000000000077e000002e400fffffffb0000000800540069006d00650100000000000004500000000000000000000004650000036700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1918 + X: 0 + Y: 27 diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json new file mode 100644 index 00000000..3d8fe104 --- /dev/null +++ b/carla_ad_demo/config/sensors.json @@ -0,0 +1,48 @@ +{ + "sensors": [ + { + "type": "sensor.camera.rgb", + "id": "view", + "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, + "width": 800, + "height": 600, + "fov": 100, + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 60.0, + "iso": 1200.0, + "fstop": 1.4, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "manual", + "exposure_compensation": 3.0, + "exposure_min_bright": 0.1, + "exposure_max_bright": 2.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + } + ] +} diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch new file mode 100644 index 00000000..c679c7bf --- /dev/null +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -0,0 +1,71 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch new file mode 100644 index 00000000..2efff80c --- /dev/null +++ b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch @@ -0,0 +1,84 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml new file mode 100644 index 00000000..4d354b9e --- /dev/null +++ b/carla_ad_demo/package.xml @@ -0,0 +1,20 @@ + + + carla_ad_demo + 0.0.1 + The carla_ad_demo package + CARLA Simulator Team + MIT + catkin + carla_ros_bridge + carla_ego_vehicle + carla_waypoint_publisher + carla_ad_agent + carla_manual_control + rviz_carla_plugin + carla_twist_to_control + carla_spectator_camera + carla_ros_scenario_runner + + + diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt new file mode 100644 index 00000000..877653c6 --- /dev/null +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_ros_scenario_runner) + +find_package(catkin REQUIRED COMPONENTS + roslaunch +) + +catkin_python_setup() + +roslaunch_add_file_check(launch) + +catkin_package() + +catkin_install_python(PROGRAMS + src/carla_ros_scenario_runner/carla_ros_scenario_runner.py + src/carla_ros_scenario_runner/application_runner.py + src/carla_ros_scenario_runner/scenario_runner_runner.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) diff --git a/carla_ros_scenario_runner/README.md b/carla_ros_scenario_runner/README.md new file mode 100644 index 00000000..ab803b35 --- /dev/null +++ b/carla_ros_scenario_runner/README.md @@ -0,0 +1,45 @@ +# ROS Scenario Runner + +This is a wrapper to execute OpenScenarios with the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) via ROS. + +It is best used from within the [rviz_carla_plugin](../rviz_carla_plugin). + +## Setup + +Please follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) and verify, that scenario_runner is working, if started manually. + +Additionally, please execute: + + sudo apt install python-pexpect + +## Startup + +The environment variables are forwarded to scenario_runner, therefore set them to: + + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ + +To run the ROS node: + + roslaunch carla_ros_scenario_runner carla_ros_scenario_runner.launch scenario_runner_path:= + +To run a scenario from commandline: + + rosservice call /scenario_runner/execute_scenario "{ 'scenario': { 'scenario_file': '', 'target_speed': 10.0, 'destination': { 'position': { 'x': 10, 'y': 10, 'z':0 } } } }" + + +## Available services + +| Service | Description | Type | +| ----------------------------------------------------------- | ----------- | -------------------------------------------------------------------- | +| `/scenario_runner/execute_scenario` | Execute a scenario. If another scenario is currently running, it gets stopped. | [carla_ros_scenario_runner_types.ExecuteScenario](../carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | + + +## Available topics + + +| Topic | Description | Type | +| ------------------------------------- | ----------- | -------------------------------------------------------------------- | +| `/carla//target_speed` | The ego vehicle target speed | [std_msgs.Float64](http://docs.ros.org/api/std_msgs/html/msg/Float64.html) | +| `/carla//goal` | The ego vehicle destination (e.g. used by [carla_waypoint_publisher](../carla_waypoint_publisher)) | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | +| `/scenario_runner/status` | The current status of the scenario runner execution (e.g. used by the [rviz_carla_plugin](../rviz_carla_plugin)) | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | + diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch new file mode 100644 index 00000000..def00183 --- /dev/null +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/carla_ros_scenario_runner/package.xml b/carla_ros_scenario_runner/package.xml new file mode 100644 index 00000000..a7701fe1 --- /dev/null +++ b/carla_ros_scenario_runner/package.xml @@ -0,0 +1,19 @@ + + + carla_ros_scenario_runner + 0.0.0 + The carla_ros_scenario_runner package + CARLA Simulator Team + MIT + catkin + rospy + roslaunch + rospy + rospy + carla_msgs + carla_ros_scenario_runner_types + std_msgs + + + + diff --git a/carla_ros_scenario_runner/setup.py b/carla_ros_scenario_runner/setup.py new file mode 100644 index 00000000..1204b037 --- /dev/null +++ b/carla_ros_scenario_runner/setup.py @@ -0,0 +1,13 @@ +""" +Setup for carla_ros_scenario_runner +""" + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_ros_scenario_runner'], + package_dir={'': 'src'} +) + +setup(**d) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/__init__.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py new file mode 100755 index 00000000..dcff47b1 --- /dev/null +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -0,0 +1,152 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +""" +Execute an application. +""" +import os +from enum import Enum +from threading import Thread, Event +from datetime import datetime, timedelta +import pexpect + + +class ApplicationStatus(Enum): + """ + States of an application + """ + STOPPED = 0 + STARTING = 1 + RUNNING = 2 + SHUTTINGDOWN = 3 + ERROR = 4 + + +class ApplicationRunner(object): + + """ + Execute application + """ + + def __init__(self, status_updated_fct, log_fct, ready_string=""): + """ + Constructor + """ + self._app_thread = None + self._status_updated_fct = status_updated_fct + self._log_fct = log_fct + self._shutdown_requested_event = Event() + self._ready_string = ready_string + + def execute(self, cmdline, env=None, cwd=None): + """ + Starts a thread to execute the application + """ + if self.is_running(): + self._log_fct("Application already running!") + return False + + self._shutdown_requested_event.clear() + self._app_thread = Thread(target=self.start_and_run, args=(cmdline, + env, + cwd, + self._shutdown_requested_event, + self._ready_string, + self._status_updated_fct, + self._log_fct,)) + self._app_thread.start() + + return True + + def start_and_run(self, cmdline, env, cwd, shutdown_requested_event, ready_string, # pylint: disable=too-many-arguments + status_updated_fct, log_fct): + """ + thread function + """ + status_updated_fct(ApplicationStatus.STARTING) + try: + process = self.start_process(cmdline, log_fct, env=env, cwd=cwd) + self.run(process, shutdown_requested_event, ready_string, status_updated_fct, log_fct) + except (KeyError, pexpect.ExceptionPexpect) as e: + self._log_fct("Error while starting process: {}".format(e)) + status_updated_fct(ApplicationStatus.ERROR) + + def is_running(self): + """ + returns if the application is still running + """ + if self._app_thread is None: + return False + + return self._app_thread.is_alive() + + def shutdown(self): + """ + Shut down the application thread + """ + if not self.is_running(): + return + self._log_fct("Requesting shutdown...") + self._status_updated_fct(ApplicationStatus.SHUTTINGDOWN) + self._shutdown_requested_event.set() + if self._app_thread: + self._app_thread.join() + self._log_fct("Shutdown finished.") + + def start_process(self, argument_list, log_fct, env=None, cwd=None): # pylint: disable=no-self-use + """ + Starts a process. + """ + if not argument_list: + raise KeyError("No arguments given!") + executable = argument_list[0] + if not os.path.isfile(executable): + raise KeyError("The executable {} does not exist".format(executable)) + log_fct("Executing: {}".format(" ".join(argument_list))) + process = pexpect.spawn(" ".join(argument_list), env=env, cwd=cwd) + #process.logfile_read = sys.stdout + return process + + def run(self, process, shutdown_requested_event, ready_string, status_updated_fct, log_fct): # pylint: disable=no-self-use,too-many-arguments + """ + Threaded application execution + + :return: + """ + shutting_down_trigger_time = None + signaled_running = False + while True: + if shutdown_requested_event.is_set(): + if shutting_down_trigger_time is None: + shutting_down_trigger_time = datetime.now() + log_fct("Shutdown requested while process is still \ + running. Sending SIGHUP/SIGINT...") + process.terminate(force=False) + else: + if (datetime.now() - shutting_down_trigger_time) > timedelta(seconds=8): + log_fct("Waited 8s for application to exit. Forcing Shutdown. \ + Sending SIGKILL") + process.terminate(force=True) + try: + process.expect(".*\n", timeout=0.1) + log_fct(process.after.strip()) + if not signaled_running: + if process.after.find(ready_string) != -1: + status_updated_fct(ApplicationStatus.RUNNING) + log_fct("Application is ready.") + signaled_running = True + except pexpect.EOF: + # application exited + log_fct(process.before.strip()) + log_fct("Application exited. Exiting run loop") + break + except pexpect.TIMEOUT: + # no output received + pass + + process.close() + if process.exitstatus == 0: + status_updated_fct(ApplicationStatus.STOPPED) + else: + status_updated_fct(ApplicationStatus.ERROR) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py new file mode 100755 index 00000000..77ae976e --- /dev/null +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -0,0 +1,169 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +Execute scenarios via ros service + +Internally, the CARLA scenario runner is executed +""" +import sys +import os +try: + import queue +except ImportError: + import Queue as queue +import rospy +from geometry_msgs.msg import PoseStamped +from std_msgs.msg import Float64 +from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse +from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus +from application_runner import ApplicationStatus +from scenario_runner_runner import ScenarioRunnerRunner + +# Check Python dependencies of scenario runner +try: + import carla # pylint: disable=unused-import +except ImportError: + print "ERROR: CARLA Python Egg not available. Please add \ + /PythonAPI/carla/dist/carla--\ + py-linux-x86_64.egg to your PYTHONPATH." + sys.exit(1) + +try: + from agents.navigation.local_planner import LocalPlanner # pylint: disable=unused-import +except ImportError: + print "ERROR: CARLA Python Agents not available. \ + Please add /PythonAPI/carla to your PYTHONPATH." + sys.exit(1) + + +class CarlaRosScenarioRunner(object): + """ + Execute scenarios via ros service + """ + + def __init__(self, role_name, host, scenario_runner_path): + """ + Constructor + """ + self._goal_publisher = rospy.Publisher( + "/carla/{}/goal".format(role_name), PoseStamped, queue_size=1, latch=True) + self._target_speed_publisher = rospy.Publisher( + "/carla/{}/target_speed".format(role_name), Float64, queue_size=1, latch=True) + self._status_publisher = rospy.Publisher( + "/scenario_runner/status", CarlaScenarioRunnerStatus, queue_size=1, latch=True) + self.scenario_runner_status_updated(ApplicationStatus.STOPPED) + self._scenario_runner = ScenarioRunnerRunner( + scenario_runner_path, + host, + self.scenario_runner_status_updated, + self.scenario_runner_log) + self._request_queue = queue.Queue() + self._execute_scenario_service = rospy.Service( + '/scenario_runner/execute_scenario', ExecuteScenario, self.execute_scenario) + + def scenario_runner_log(self, log): # pylint: disable=no-self-use + """ + Callback for application logs + """ + rospy.logwarn("[SC]{}".format(log)) + + def scenario_runner_status_updated(self, status): + """ + Executed from application runner whenever the status changed + """ + rospy.loginfo("Status updated to {}".format(status)) + val = CarlaScenarioRunnerStatus.STOPPED + if status == ApplicationStatus.STOPPED: + val = CarlaScenarioRunnerStatus.STOPPED + elif status == ApplicationStatus.STARTING: + val = CarlaScenarioRunnerStatus.STARTING + elif status == ApplicationStatus.RUNNING: + val = CarlaScenarioRunnerStatus.RUNNING + elif status == ApplicationStatus.SHUTTINGDOWN: + val = CarlaScenarioRunnerStatus.SHUTTINGDOWN + else: + val = CarlaScenarioRunnerStatus.ERROR + status = CarlaScenarioRunnerStatus() + status.status = val + self._status_publisher.publish(status) + + def execute_scenario(self, req): + """ + Execute a scenario + """ + rospy.loginfo("Scenario Execution requested...") + + response = ExecuteScenarioResponse() + response.result = True + if not os.path.isfile(req.scenario.scenario_file): + rospy.logwarn("Requested scenario file not existing {}".format( + req.scenario.scenario_file)) + response.result = False + else: + self._request_queue.put(req.scenario) + return response + + def run(self): + """ + Control loop + + :return: + """ + current_req = None + while not rospy.is_shutdown(): + if current_req: + if self._scenario_runner.is_running(): + rospy.loginfo("Scenario Runner currently running. Shutting down.") + self._scenario_runner.shutdown() + rospy.loginfo("Scenario Runner stopped.") + rospy.loginfo("Executing scenario {}...".format(current_req.name)) + # publish goal + goal = PoseStamped(pose=current_req.destination) + goal.header.stamp = rospy.get_rostime() + goal.header.frame_id = "map" + self._goal_publisher.publish(goal) + # publish target speed + self._target_speed_publisher.publish(Float64(data=current_req.target_speed)) + # execute scenario + scenario_executed = self._scenario_runner.execute_scenario( + current_req.scenario_file) + if not scenario_executed: + rospy.logwarn("Unable to execute scenario.") + current_req = None + else: + try: + current_req = self._request_queue.get(block=True, timeout=0.5) + except queue.Empty: + # no new request + pass + if self._scenario_runner.is_running(): + rospy.loginfo("Scenario Runner currently running. Shutting down.") + self._scenario_runner.shutdown() + + +def main(): + """ + + main function + + :return: + """ + rospy.init_node('carla_ros_scenario_runner', anonymous=True) + role_name = rospy.get_param("~role_name", "ego_vehicle") + scenario_runner_path = rospy.get_param("~scenario_runner_path", "") + host = rospy.get_param("~host", "localhost") + scenario_runner = CarlaRosScenarioRunner(role_name, host, scenario_runner_path) + try: + scenario_runner.run() + finally: + del scenario_runner + rospy.loginfo("Done.") + + +if __name__ == "__main__": + main() diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py new file mode 100755 index 00000000..9ff8da61 --- /dev/null +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +""" +Executes scenario runner +""" +import os +from application_runner import ApplicationRunner + + +class ScenarioRunnerRunner(ApplicationRunner): + """ + Executes scenario runner + """ + + def __init__(self, path, host, status_updated_fct, log_fct): + self._path = path + self._host = host + super(ScenarioRunnerRunner, self).__init__( + status_updated_fct, + log_fct, + "ScenarioManager: Running scenario OpenScenario") + + def execute_scenario(self, scenario_file): + """ + Executes scenario + """ + cmdline = ["/usr/bin/python", "{}/scenario_runner.py".format(self._path), + "--openscenario", "{}".format(scenario_file), + "--waitForEgo", + "--host", self._host] + return self.execute(cmdline, env=os.environ) diff --git a/carla_ros_scenario_runner_types/CMakeLists.txt b/carla_ros_scenario_runner_types/CMakeLists.txt new file mode 100644 index 00000000..8184efef --- /dev/null +++ b/carla_ros_scenario_runner_types/CMakeLists.txt @@ -0,0 +1,21 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_ros_scenario_runner_types) + +find_package(catkin REQUIRED COMPONENTS + message_generation + geometry_msgs +) + +add_service_files(DIRECTORY srv FILES + ExecuteScenario.srv +) + +add_message_files(DIRECTORY msg FILES + CarlaScenario.msg + CarlaScenarioList.msg + CarlaScenarioRunnerStatus.msg +) + +generate_messages(DEPENDENCIES geometry_msgs) + +catkin_package() diff --git a/carla_ros_scenario_runner_types/msg/CarlaScenario.msg b/carla_ros_scenario_runner_types/msg/CarlaScenario.msg new file mode 100644 index 00000000..bdb90fa3 --- /dev/null +++ b/carla_ros_scenario_runner_types/msg/CarlaScenario.msg @@ -0,0 +1,11 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +string name +string scenario_file +geometry_msgs/Pose destination +float64 target_speed + diff --git a/carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg b/carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg new file mode 100644 index 00000000..8b2df049 --- /dev/null +++ b/carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg @@ -0,0 +1,8 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +CarlaScenario[] scenarios + diff --git a/carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg b/carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg new file mode 100644 index 00000000..cf0039e3 --- /dev/null +++ b/carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg @@ -0,0 +1,14 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +uint8 STOPPED = 0 +uint8 STARTING = 1 +uint8 RUNNING = 2 +uint8 SHUTTINGDOWN = 3 +uint8 ERROR = 4 + +uint8 status + diff --git a/carla_ros_scenario_runner_types/package.xml b/carla_ros_scenario_runner_types/package.xml new file mode 100644 index 00000000..5df0ef5a --- /dev/null +++ b/carla_ros_scenario_runner_types/package.xml @@ -0,0 +1,14 @@ + + + carla_ros_scenario_runner_types + 0.1.0 + The carla_ros_scenario_runner_types package + CARLA Simulator Team + MIT + catkin + message_generation + geometry_msgs + message_runtime + geometry_msgs + + diff --git a/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv b/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv new file mode 100644 index 00000000..d342a73f --- /dev/null +++ b/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv @@ -0,0 +1,10 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +CarlaScenario scenario +--- +bool result + diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 7877514c..4d1c3201 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -24,6 +24,7 @@ # -- CarlaSpectatorCamera ------------------------------------------------------------ # ============================================================================== + class CarlaSpectatorCamera(object): """ Spawns a camera, attached to an ego vehicle. @@ -71,7 +72,7 @@ def get_camera_transform(self): return None if self.pose.header.frame_id != self.role_name: rospy.logwarn("Unsupported frame received. Supported {}, received {}".format( - self.role_name, self.pose.header.frame_id)) + self.role_name, self.pose.header.frame_id)) return None sensor_location = carla.Location(x=self.pose.pose.position.x, y=-self.pose.pose.position.y, @@ -83,7 +84,7 @@ def get_camera_transform(self): self.pose.pose.orientation.w ) roll, pitch, yaw = euler_from_quaternion(quaternion) - #rotate to CARLA + # rotate to CARLA sensor_rotation = carla.Rotation(pitch=math.degrees(roll)-90, roll=math.degrees(pitch), yaw=-math.degrees(yaw)-90) @@ -98,9 +99,9 @@ def create_camera(self, ego_actor): bp = bp_library.find("sensor.camera.rgb") bp.set_attribute('role_name', "spectator_view") rospy.loginfo("Creating camera with resolution {}x{}, fov {}".format( - self.camera_resolution_x, - self.camera_resolution_y, - self.camera_fov)) + self.camera_resolution_x, + self.camera_resolution_y, + self.camera_fov)) bp.set_attribute('image_size_x', str(self.camera_resolution_x)) bp.set_attribute('image_size_y', str(self.camera_resolution_y)) bp.set_attribute('fov', str(self.camera_fov)) @@ -165,7 +166,7 @@ def run(self): self.world = client.get_world() try: - r = rospy.Rate(10) # 10hz + r = rospy.Rate(10) # 10hz while not rospy.is_shutdown(): self.find_ego_vehicle_actor() r.sleep() diff --git a/carla_twist_to_control/README.md b/carla_twist_to_control/README.md new file mode 100644 index 00000000..4fcfd7d0 --- /dev/null +++ b/carla_twist_to_control/README.md @@ -0,0 +1,17 @@ +# Twist to Vehicle Control conversion + +This node converts a [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) to [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) + + +## Subscriptions + +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | +| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](../carla_msgs/msg/CarlaEgoVehicleInfo.msg) | Ego vehicle info, to receive max steering angle | +| `/carla//twist` | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | Twist to convert | + +## Publications + +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | +| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) | Converted vehicle control command | diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index cb9bae89..dea8861a 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -14,7 +14,8 @@ from geometry_msgs.msg import Twist from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo -class TwistToVehicleControl(object): + +class TwistToVehicleControl(object): # pylint: disable=too-few-public-methods """ receive geometry_nav_msgs::Twist and publish carla_msgs::CarlaEgoVehicleControl @@ -30,11 +31,11 @@ def __init__(self, role_name): rospy.loginfo("Wait for vehicle info...") vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) - if not vehicle_info.wheels: + if not vehicle_info.wheels: # pylint: disable=no-member rospy.logerr("Cannot determine max steering angle: Vehicle has no wheels.") sys.exit(1) - - self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle + + self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle # pylint: disable=no-member if not self.max_steering_angle: rospy.logerr("Cannot determine max steering angle: Value is %s", self.max_steering_angle) @@ -53,30 +54,28 @@ def twist_received(self, twist): """ control = CarlaEgoVehicleControl() if twist == Twist(): - #stop + # stop control.throttle = 0. control.brake = 1. control.steer = 0. else: if twist.linear.x > 0: - control.throttle = min(TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/ \ - TwistToVehicleControl.MAX_LON_ACCELERATION + control.throttle = min(TwistToVehicleControl.MAX_LON_ACCELERATION, + twist.linear.x) / TwistToVehicleControl.MAX_LON_ACCELERATION else: control.reverse = True - control.throttle = max(-TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/ \ - -TwistToVehicleControl.MAX_LON_ACCELERATION + control.throttle = max(-TwistToVehicleControl.MAX_LON_ACCELERATION, + twist.linear.x) / -TwistToVehicleControl.MAX_LON_ACCELERATION if twist.angular.z > 0: - control.steer = -min(self.max_steering_angle, twist.angular.z)/ \ - self.max_steering_angle + control.steer = -min(self.max_steering_angle, twist.angular.z) / \ + self.max_steering_angle else: - control.steer = -max(-self.max_steering_angle, twist.angular.z)/ \ - self.max_steering_angle - #invert steer for reverse case - if control.reverse: - control.steer = -control.steer + control.steer = -max(-self.max_steering_angle, twist.angular.z) / \ + self.max_steering_angle self.pub.publish(control) + def main(): """ main function @@ -93,6 +92,6 @@ def main(): del twist_to_vehicle_control rospy.loginfo("Done") + if __name__ == "__main__": main() - diff --git a/carla_waypoint_publisher/README.md b/carla_waypoint_publisher/README.md index 7419a7ce..a2b756dc 100644 --- a/carla_waypoint_publisher/README.md +++ b/carla_waypoint_publisher/README.md @@ -13,7 +13,7 @@ Additionally, services are provided to query CARLA waypoints. As the waypoint publisher requires some Carla PythonAPI functionality that is not part of the python egg-file, you have to extend your PYTHONPATH. - export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg:/PythonAPI/carla/ To run it: @@ -40,5 +40,5 @@ The calculated route is published: | Service | Description | Type | | ----------------------------------------------------------- | ----------- | -------------------------------------------------------------------- | -| `/carla_waypoint_publisher//get_waypoint` | Get the waypoint for a specific location | [carla_waypoint_types.GetWaypoint](../carla_waypoint_types/srv/GetWaypoint.msg) | -| `/carla_waypoint_publisher//get_actor_waypoint` | Get the waypoint for the ego vehicle | [carla_waypoint_types.GetActorWaypoint](../carla_waypoint_types/srv/GetActorWaypoint.msg) | +| `/carla_waypoint_publisher//get_waypoint` | Get the waypoint for a specific location | [carla_waypoint_types.GetWaypoint](../carla_waypoint_types/srv/GetWaypoint.srv) | +| `/carla_waypoint_publisher//get_actor_waypoint` | Get the waypoint for an actor id | [carla_waypoint_types.GetActorWaypoint](../carla_waypoint_types/srv/GetActorWaypoint.srv) | diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 915bc708..95191278 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -110,13 +110,16 @@ def get_waypoint(self, req): #rospy.logwarn("Get waypoint {}".format(response.waypoint.pose.position)) return response - def get_actor_waypoint(self, _): + def get_actor_waypoint(self, req): """ Convenience method to get the waypoint for an actor """ + rospy.loginfo("get_actor_waypoint(): Get waypoint of actor {}".format(req.id)) + actor = self.world.get_actors().find(req.id) + response = GetActorWaypointResponse() - if self.ego_vehicle: - carla_waypoint = self.map.get_waypoint(self.ego_vehicle.get_location()) + if actor: + carla_waypoint = self.map.get_waypoint(actor.get_location()) response.waypoint.pose.position.x = carla_waypoint.transform.location.x response.waypoint.pose.position.y = -carla_waypoint.transform.location.y response.waypoint.pose.position.z = carla_waypoint.transform.location.z @@ -125,7 +128,7 @@ def get_actor_waypoint(self, _): response.waypoint.section_id = carla_waypoint.section_id response.waypoint.lane_id = carla_waypoint.lane_id else: - rospy.logwarn("get_actor_waypoint(): Ego vehicle not valid.") + rospy.logwarn("get_actor_waypoint(): Actor {} not valid.".format(req.id)) return response def on_goal(self, goal): diff --git a/carla_waypoint_types/srv/GetActorWaypoint.srv b/carla_waypoint_types/srv/GetActorWaypoint.srv index f7e7dad5..7b9100db 100644 --- a/carla_waypoint_types/srv/GetActorWaypoint.srv +++ b/carla_waypoint_types/srv/GetActorWaypoint.srv @@ -4,5 +4,6 @@ # This work is licensed under the terms of the MIT license. # For a copy, see . # +uint32 id --- carla_waypoint_types/CarlaWaypoint waypoint \ No newline at end of file diff --git a/check.sh b/check.sh index dcf47bb6..b16ec844 100755 --- a/check.sh +++ b/check.sh @@ -4,5 +4,10 @@ autopep8 carla_ackermann_control/src/carla_ackermann_control/*.py --in-place --m autopep8 carla_ego_vehicle/src/carla_ego_vehicle/*.py --in-place --max-line-length=100 autopep8 carla_waypoint_publisher/src/carla_waypoint_publisher/*.py --in-place --max-line-length=100 autopep8 rqt_carla_control/src/rqt_carla_control/*.py --in-place --max-line-length=100 +autopep8 carla_ad_agent/src/carla_ad_agent/*.py --in-place --max-line-length=100 +autopep8 carla_ros_scenario_runner/src/carla_ros_scenario_runner/*.py --in-place --max-line-length=100 +autopep8 carla_twist_to_control/src/carla_twist_to_control/*.py --in-place --max-line-length=100 +autopep8 carla_spectator_camera/src/carla_spectator_camera/*.py --in-place --max-line-length=100 +autopep8 carla_infrastructure/src/carla_infrastructure/*.py --in-place --max-line-length=100 -pylint --rcfile=.pylintrc carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ +pylint --rcfile=.pylintrc carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ diff --git a/docs/images/rviz_carla_plugin.png b/docs/images/rviz_carla_plugin.png new file mode 100644 index 0000000000000000000000000000000000000000..f7e8208d7875e3c8439497cfc427536e0ce1daae GIT binary patch literal 525827 zcmbTdWmr{R7cRUIq(neKKpN>5r9%)2>5%S_?(QyWX^@g~(@1PKuxX@Qxs!9x zd3@gY{5)_eUJKXSbInoreUCB26yzkHq7$J50Ps}ugQyY!AWH!NQUdBD@CwAMlL7pJ zY$z=u3OxMz{?-VI2d|*neb8_OfG4V?-a3mlr(Xv?EKl0-$zKvFWxzWDwtkDj7{f)QVs`EwIGBYuKmzNRpr zlf0m6ED4B7nn3r&or+ygS8F=i{<;$w;P7imiixv!+ukd7@yAG4%E*Z@Tks%k`( zQlTn~9vhoH@Jfr>4_gG4GUz{l4I4>f8mz5v512dwue|K8V3C){>LgVC_kUn}+`4;s z0DjX}2*A5I`U%v(_hJ`0tS)GZ2n(}dVY%+s2mih2RIiheDo8Z^Z@pS48W3Gu z%g6a4@OMRwcg8x=*1QGtHdQlL@7}$;zxR3jcD$iMz|rw+dRn8Whk@H>PJt0GfF4^! zT``N9qJ_|rheWk_U}&h^=guQjSJ#FwW5jH1=cG&ro|KTVn*JocO(l+c+N#F?>`wE> z6UDv$YI|%;{N!olvZ%vgCldpD{v%Pq4=!FyZ{($~?svc@d=Kp6QgMFHc5lIT;5%Mz?|j3&A;#v-2(h4-&HiG%z8YGd!>CYOxC0*E z*zQFS#1`r*deCU0dT6YISC#tOv0qu4kx?^oEZwx5GbQSA(xdostBPsrPBa1e0$w&D zx<#qS!H&bRnvoiHv`#;r1OM@dYzaJpFGgB%pPr`%*gJP!_`B>g_+8CsIFuoy_9V8jS)_N%`}_DL zB&!=6$telSFA0DTm=aHEgqkJXV)({yIRm0U^qY(vF$+ViRyO9}6m*W{l?W7PP`SRy zH>;YqQk@mVlB-rPndYsFWcT0j_Y<>S=3VIP`&g(f&>PO?PR8hYvO5^BUAIMUAf|}2 zv9Be&vtO`2n5W%)`74&&g8TW@u51^xH@vlJi@cWd9~*KIy?7YzHawHVCZ6d z{9`uW6ZA+7!dJXC>kzCrzj(3nLz&57jJHwKP$6;Uu?BlyZ-OO6-|P z`*$pV6Xww^9W@g*JO*A+go1${#lFXs-2UATQ7HFN=5@2 z?zk(PJ^I;(vXMV_lwee8Z@=(+OO5x=#vZRzpjra?a*oWfyQf8M|CFHV$9H=lA(Emo z2G0yQo3HJ}`bQ$zf`Xw|qe~Y|ld1IB-?-9hWR>4PmKAhimZZ!}QX}Jb#i9{!_}7y| z**mFCVAFiA+bt>WRt~S|@;_jrV_`neMW{1RG1F2=+(t3exKa9x^#OY(qY<~W0I=?yNGD_2%0>@>7Sl_&^)|L zBF4U5oy|He(3zL*Kvx<%(7KsjXNpU5P2r3}X&7#HZfx1MLGN*MyqSyPntO{5?;#q7 zII)fx2ld(1T-C|+lRTc-Ce0*gf5kYJ*4LaWHQuo?Wqg;AykNjO%(4H_c375uuPJd3 z9ZgHRv*&q&6zX{ryOL?Kt=A_3(SOW9fO*hF5#nn8TvOU;sL8|b>=)<86Anfb_9EhQ zQr;4+Dq+{J@pdK~+faU6NgKwEZ&=X8k}rC&>qf3@mG!R-qcCEQoDOZv%}6o%AEjAd z)yE!7hpFV}iTBrbz1OQr<)!IUzZhPd30;l;yz&Zd9SRYQPqzFt*AgRiI`ZN|N6?MI zAAPL@7H$!=Fb8uwW5|SX8SfnF$y(r!7xomLRE%u&8pCm^N2D`qq2eA#L7=T{0_3W83;rSVps}$ z=bfmvy<*N~-`(iSaHVr(M{dtxdSObYI(*I)QCO(fsse#Y#n%R^MjBhGrGDe2=jWb{ z^KnMed)*TuH3yfypV%K7J0N@YOFueW>&HHZ%CBt^i9)>`obq`0vK%GK3W=a-o)&Z6 ztFFyLpAUzvGlOFYs~m9!kf28Uuab(e4UMzGGS7r>?z!MQ$Cd=@-?{D zmhaQ!Lh(@r+c?+F{-+xwz9h-`RW{bIQH00dk$Q$+&DeI(N!C<9F4w`_Kb_lb%?_Yk zpLA92%zKk4_io=fh=!6v5(ja~Et=}Pqi+^hjScw->!)!cH9|IC0lpfWoG-tzBp?w1 zOZ3eG%1e@oUU78)j3G#bfAKxcuYYgSICItid4b$4r#|2;1pgCuTs zLv7TMT{?~$vNv6o=2&)j^H4Lp7X%n_v@Ei5(j?M{y^rHlQ{zWJE^NmHw(!jd3xB%4 zvO|wCh~5$V9X-PM}JG+1wEZ& zS1OIq)UCY}VfUvBuju~sKNc3wE%Y$KI79w&6=pq$}5(XUHry=JlD!?&_^ExTiXQ&vqj+>uOUb-6ogZH`fk z*lyx8wh~779>!YV?F2)#QOFTNdRaKw!T*&L155EBg3B{F1jX)3Vo(e9f8BK2j-x;X)8&s&11eYph zvu3(A6^QUWoWDm#J|W8D%P#%8ZMMFM!p08m^*J9doIB6Zs>afBSPlsGxUkaG`=P@} zm{F`iUyyry{CVF3!{*<7fJxa>kT+^!&BZjw+bvIKqFycjGU!9x`{I#TQfNSKoN6(2 z+NwjN-^9_L)jf)u7Z8r4juLODU-QewDJ^|j-SU(EvEO%2fyJFk_w^*iz(4`+x$d;f zPhBR|Sws#9eo73&#ouvQgyxjzJc~sT9%rubhzR?f8XdWWHT*>Kcja4x+ke0&Au0J* z2$843Nlep>{;H4`c6s6EF0=TVf{n(0iUG?d_;>We$MkO#^lo3!tzecjHUWTI9lcS0 zy)8R@dYqNs*ardOk!%z^g^JNRV1CJqR+>B^u#(R>4}ya9Y>$*<2rKW99h+&qKjG z2yUx^Jg>Wc41@PU&+6$wz_tu68%~`pPYGr-Yp%!Sa{wrKYtsI`idM0em-EF!`GB8h zBm#D~P_y~^?cSttAr8$=M|-Fe|9OnrthW1liiC2ghu6FQWnA%h*~TU=$;YpD;eR=b zpa_QFYhy0Z zlW_bMoJ0x{C>pX_H6j01KONU@Dqi#CNj`7%ZF-vyPEL+X9g{{KiXB@Zu9#v1bs<+i^o8|lJolQWBB{uJi6FH;i0sIUG{)OO39%{9A+Ae+vd+$#oh?tftxFl z=$D48L76_Ry(UQ?i_pFYItTI<{eL!G{UG=&((m2zHU@O(jjN@iAJnKAfI0u?E z_bAhi#}qb8D$Em21tODudK>f(Vm9YI3SMfdTAY(Kc4Umt6zf?6_zzxYAJRSu$rgJw zyuIEO3l(AD+b>{*E0Ug_KPjF2=pwIok2Oy3j@%N#ymlC#maf^Au~;1)hAuX8DBL60 zNDSQ~q_D$`>u#OvALK-k=r<-=9b)Lb6&TEvfCw{>x@>fkzlDA>hj zFHyBomNX7-d!P{!F!>rCM7_wce-Tv}KpB)Gi{D8N64jkw`SAj4s*0=r?8qh{?T`Zc zX`fJv4w_V`qZt6AKDF77%`7kS6O@o!N>rIBgX~Bs(_5`nq!ONsp|Q?OY4|eOiq8Is zVt+v5JU08CP0vi&^KEuD#LhV`UK87eT-dyIT0lS_B0m!3TaSgeLxb!6dG}3-uv^y^F1bt0rD~Ig zqzGbg-B-feE2u=Mvb+|!{f4HTFUe^O(0DSiOt{Tw<-KYWxr|45&ysg3l!%`rZGm){1B5zN-n*BJ!G^bO5;ElT?$tZe5zz|=x z(D_!yfM;V1d@^XP`CL08VFu@_W!V}-~(>@s2 zrbn>G?3oBpU~9{f0IL(%K$O95|%AaQa8z9w39Xe6N zNK(jD>cIrmo<`fQJYDguwkfLS+#YpV*OQ>*8sl^!K=7mb&6%4>a0wSH+c&n$(JVbb zJ(ZG{R{8v!-11?r(wg|yt5jL^-~grd9j#FdC`bv_3T9BtyM-$DHgPF4uI1CnoVFcU z$30#|-#5@Q(4+;2U=i`R(Y;kGIG|JO&Jgritq34lHCg+h-8g8JCI8j6-1TZ*llS3hJP(V|s5YVE#M^6hy2EbjKW$+;mbcHqF6(!B~QEs1NDZ`qw}-QRPRuax2D#guJVDNqk>pTY?4Ic`yJoxw%%O zFs@j(H#yW69GR}WMP{w$G!Q(cdrfHWUBdld$lFG48{?Ows13ioJk*?Q`u1hh*tO=q z2Xa4t*R{X9>7uvx?jN;6VeKUn(!1{7-Z6{uIO=C2ywS%38zc*Hd2NSD6sRCveaU9m z!n^UCr;SilB8$1gKD1qqA>I)!-~%B9`*~>P)9i77UJ~G&q9yIA+1$@0gQ5PijrA*= z1Fqi4oqmJ3_slm{Bs zg&Qg<8G?dIFbW;cJ98nJ+XT%0JqpzJS2nTj2qZ(Gly;-$wzkdt6n9zvsqG+dNl3pI z0qzMZ7R7S{4YG)?u<%`PCN55oLQ^vZ&U&Y+V(l`r7Vs)Dt842K`quHWZBvh@iP^?* zw4eyd=XV}7YI>Q_(0%7F10-d zyAHm)`RJzj(Qu6Vq*QM*5PN~U;o*y2T~vow4wg2I_kszIg~9W@u3{?&H-iqkb?=l` zS{1F~?oW_kD<~0He_E_#=W(;F9sG@6BMPhZUx}%RM=F(`(ZRvNyGZ3Dqo@?aGAi2< z7@X*EEJApG8EKAmtK*B7MhmZ(@Y!x{Y(D@fl_u#Wa+(}B+}bzxLQ4mu3@ruyVILt^=r7W%Ge z{zpb$eHX1J4IE|0(g3`5CK7FN|Ph6!4_E6a4$W6ZEaqKr24&azNtvVZa* z>O5Wa3QZ`rqGq}7mpP+|FZ{@KuRBq@6vK4jE{Oz4!3C>4A`DftRtXjL&Vgtsk-vUx z1HufTY$D+o8x({D1PQ z={IkxBty>?bLj7P2A@EsIW^x-Gk#ljk`IYM!R$=CL?1d()|mYp)z}^+?8tx&wpiK# zEibiD^H-uMaZK|bwAIgvJ)fjxWmnwg3YDJ6DCQB&dEc zWOU2PMl(@L47H08s?IF_{@pu&&|$*RV*vzYhc4D=>|iBx*eniiynw(Ql&@5&5J}wc zRoZ~6K67_ppBnvh#{4*JOhN#!vx9@EG?8F^^{5od$P`+asqeZ{;O{U=^7~!Yb>4f( z=$3MTg8u78XC;?lwvSSz>Z$wdAB4M-2F^WP9F8ybE%CC zrQQ2I5QO}N zc9cO1&qJ13{yvXVIoQDMPnY5Uys3%-;lkgS#uiZ_{C~f7Dli0wN?Fx>RcRdY0YJsX z)T~)GwY4p0)S-%5R=nkB#Q*!Tn+Dj7nWxj)fj4i*yW9tgI4xlh(39?w&4h%pP@Ul) zCbEm3rZ0h4o&6>!QE4zP+j%kq*9!FUv#R$f65>I!SIy>wOmwnt?Iy6HjAqo?mw#Vj z*c*GF!CBLz6SjD#erxH|gaAy~&fRv0-;7jmnN&^B_7$7PlpQp1`piJ|sA*|dG(`Vy z-1SgB>@aE7E-&wUqWV=|TNeI9(=E6toE>j(%Se(Vs}=F5q;Yt}o-S)eLXnRjW2w)j zr;`M>ro_g+@Lk)MUmUVo5O~SXpn=!1JcMaJ!7(;FJFCyJD|C4AePA}c?|fx0SO@N8 zMMPv+H9eToe0Wo-Vp65y1C=i)6ZCXBIX;zu&-{O1uBl~Q7d<``@ zHnqZKzH{o$2HEzN*#xuG<~M%?g!`+jkUNxzg$84Oqki6Zc6P%k@r(D{X}m^V0(!+J z1Cjmx16noYf-WR!um5h)eOgdxwN8}goiBL<0j{IR(Lvuh<5?eD4oB5vZmKfAmvCScP^`q*@RoT6fRuifMz8?`;Y=(d;W zf0v~RHDLh+&O{Fu8a{Bfn92_*Cuk5H* z({p_9vOn~40!hqE8Pc|NfPZ@jyoZTqb!bbC3vx{8;~FblPO&!AId$Z3Q@;X2HGTd1H6kKnc)M1Y{7(`- zFFc^KvNDDw%4YamQ$s9W<|Y)h1K3G?z(%^ z|0_uExaYOpm;?n^;N%;;51OjIeEv{DL4ox<9*O(J6&~R5*lYN30&8(_)jbp2;bgs3 zWAXk=dfX#Gv(#j`9E zP1cDqkOM2+?wJ8Mqd6wcjB_~odVYRBVoQH{v)!N}R8t2Z3-EdH?#REq{GG^^)+k!p zccix9a}c;5yWHq`zBzdjM((3&w|^Uq!r;4w4%WWGe7?(z<GG_9GqXPFdFH#DG+Zj=<2%8N9$&p zau6Xtx{VfJG*)tvGVd>(O8Hn(9^-k{^R|)fRfF@S)Dz62`1p9w$pn9YghKORT>r=8 zh4D#AA+j(2Cb$RLx%V^su~Z`_Rad2G<=j>Z&6=E9Ay0QMwx{n5c0aQxWyI?=`v{7B z7Rh$=8AHw7IQSZ&RPTHoGkx@`$d<;JA%^);2alUM8*MwOtzg`OUioeTV* zwP6)sBvpJ{s$w(2@OA0VgDohhl2?%ZGYi0w=;6Ik0Y8hcw|zozciwhFwSNC<*05rK z+I8tLHurfC)cOW9qT^SU=OmcsDm1OZt?f%HXN{#Tkkem;TyIv-cm+~&o$r1XniL$1 zw_n?a+M0OZoVNIkzWw?Lc<~}N4QAt->abTIH55a#zoEuNM|T0E>HB?O_xXR8xeD(1 z$y1M#&qXhJcs8rdAGi&EdDhjrP5cx1l&4wi`|Iv&GtV)Zav0+vo&R>GMV^zU*IM-q z<*P+|9IZ)wluGvW{b}sx7ODWnMEYx{%?hQF!-)s3%VRdwJN;Aie}7?s{R6!yX=l<_ zKM&*Y)dIr7#=qj#pIVGz`}cRK*^C(NT7QEzZbW z;0?3>!GBlh{Qs*ui*&>*NmW%lsM*52=kD+16eW;B~ z`l?-(BvkYKzn=0@tX(Vh#g=nG0B`2T<5&W>M}U}Mh99h9g0=QshoIM78Zp&xQd{FkElKSf-L1bFbpW3pka(H2(<~lHc z*hg7QKt}fzent_qhfvkFpe0NQ7t|tTVr(MG%nfd3i^i6W`;quZZP^ss`6XoUyfdyw zpQ!%)k7+#w3dgoR(QFZnS_pG7E_2jXmy7f0`#bzVUD7=gtKQ7+r6bu}NxzC5G99sJ zKXMW=h|&Mrd)R1)tWC?|fL8oTppe)b6$ES%jge1U$Dg!g>_rP+VW@H7EBeS8_5>n{ z&`9}p9|>5|{Oe9JrRbqBdKQvK2|uMUDnMA>zNFyrVfMsM@H|~ysrQM(Ez$?Z7{yP) z8RPW-V^>wsBGrc@0m2MxJY{AMjL65QDnUFK4j$?4T4M3m>@Sm3R{%dHbRZI;>)91Z zk3^%LRcbFLpq7)sH{C{$siNUKjb?-Pfi&17L`y6(4pd7-${;fAzMdZsM^&do<~hpt zXCgt65PRs6Akm+2*jx-N-ZT|;KW1@X(lvNhV8@)5779s&hu$*fM=JG_tz^B7R9g4K z3zim>P^?8}AKMXB|qOg3C=CH_Ui= zF)+Dkp9Y;}mTsQpu##%9)PE{yxYERrmz975JVg}1Zy0~Z^q+*4Sk~4ETV*I9>~4e+ z8YQszrif%0DCUYs5pm+7iz#B27oB`m*1u9$KWa`8S#CJCo2-N3;NYwe=)H2?*UsE< z&&=X?-EX*h@&juU@vERG7d8zx+fo|BV##i>-4e0aVJpf7Ecu0=ujB4iMc1<1P?k`$ z{<4U#@5ATMpZ)yFp6BO=;O{K!&C;x5V@TvBGgSl2XPs1w{V#n?~o&-ba7v{ao; z70nS>+Rtt`lwbr>YwU0-4rmvCtr$}(j(!)1vHqxiUFtKI%|gT4oXjb!y&4P?-85^{3S z_5Q7?sfc9O{Jgy1D`8-`XG?79W~O)hA>=CmMjJ9)E(a)F-^5ZEq7SsOUMv_!DgsIz z3{4F z@ZSg0_(Bb%U((Yn*JC)7S#`kt=i}pJB;I^Uo@%r|qFwZ$C2n}FSh20O=D;*1T2(z+ zDZ^wTrTZyif2z*0D>_3ww?enEzP#bq0c0Cbk=u(`bipAm?BDzQWY3=6@4gwTg~Rzx z1$=)0yjXl_u}_!EM@K~^e7idhI-iPE#abi50}(zx*VM7G! zO$UNfad^16xX+)T+4AuV-5#z~7k(t>vZ5&0fO<@YPP=QLUA>HQ}Sp`jAW z$~(*LAx8qf$NPX z$&IKhz-;W+$gEF~R;+V!mdOxvcb^)7OGokkC5jjTvPK|#Zzbo22_XTern3oh-;!8r1`dwu zT}=-m4r-)uk$x;maq&*NET5T1Pgv}bAY{a>OuKG-XGcqg=$E{ZkMG`fDLQQ#0mG9zqDrQlCv#SPk5~t<;XNz(4bPrnu z*DfS2jPPq)1ggluN=T9`4@m$;B$(17*qX1su1yEow$83o-`@+WP$hqf=j_S~5$ zjUnMxx;?rWUT#-ZR6I(4ViZwPVX9iLn~|77ij95vD`f=Caw~K)w_9E0PJE;QSYS?m zcSOX~HaZ`#_9Pao5=V7{8&kp7NbQOrpAUf?Ojo(CbL&l(Xy5`Mm2GY&2ehR>sMkAb zXli~{DkR~w$kX;y(108v1!%ZuJ**^7em234@OwXaqHX80nl$w>LGp? z4W2;}Puw2vE)EJFv>R26ttUztfNlwvtfMnxuHEUXWcCTTYdHi3(`oScF#x7H-#hCg zFi8sv2rPW%F#uh-uC5N3w&^*Z^2VNIJmUs2vyntJ8L5y@+pb0xG6sp=<*>mYsmx}v zX+E9Tu``BT=mL_}i)L#d#3O;O^zoywR>S4>8S(!9{tyP~%y(Hl01pq3S+{cabW8mm zwm8@lY4W}y&?ULMiR;Lrf7CMPenQM?F_r6i0g4pb;D*`Ql!@oQU^lEiA*gcRnc%i1 zzchkzAsv^|cBk`HZ*D zr1si^doS`{ntSBN1&sHthe_9!=rMn9 zi^K;u!0WbS!n09Xnml^MO#6qOqDUL3l*YyWdSP9kSkq1*IU&V~neTcf=3c&3l}-E9QA#R2D{IkmrE|PUrOM&pzWgA);iWGzh69!E zqxcfXUv#eauB32#S6A{kCe;lj&&RL3vex;Udrumgn-{^id+R(y=XtTWGYKp2I{@{B z3(X1#<1$^nfiB2T7S>m<6yoy0NKKE9N~A8-ov%M=y20$SUz_`l&V~@}*n}j-vGRm~ zRlCl?xHGaG1XF^R>w3O>-Tl2@=KU$)iV34Sceu;+;7Lmd8{F&p?3SwKbq;41vU-bX zxSf59KXACKPphkgBYe1sFhG|Wuada%xx1c+TB-cr4GIm;&xah$G{WT%7HGJ%a*zkJ z_?vy&L;mDDALl{XVn|RB-bQclASm|rZDh%pD-0#?RM@YuO*M^x`rv>irn7aX+bSgQ&LcYj}Td6 z0ka<@A7+{#T7sVtbjJAN0wt$QeY)l{YNPG+O0EbT`(^(io*pqhK* z#cCUD>O7tkGFRSSV2uaIJxpuVb2MQ-TlwsvSme_cMi2^AEts{Z^<1&+R}S}6a`uRg zS;p*Hcrf>D@7K`c64LqTDxq|=X6mr-dEc+EC&tV;t{$HYj=YE+*q&>MH5)UfhmI#( zHOv&)$dZ$jN3VeRjsyqiC91%G7+q{IEd9MEO;hON{`60Js$r;BOl>XC6%!LsZ8h!C z8t^!P!b@N;K3_WdkzYd#Ve!7!8!DFkv2#CmbYO)}j_AC9I4X@xi#aKYMN2@)Vzt6( z1b(r*=6(;tzOLvO^973SA0hG&buQliBU9DpqXc?{`O1u-xE;7sySlmxKB7tJN+)_n zwM;W3Gc#M6F;wVA=43q<_>z#&V09Hv%xzl_hd1BP6!#^UkL{ct$oVwO>F;st`abpR zMr4i%a77BI?WBtY0IHIb)-e1CFN1NbQK(Jm!*vt&+X~&=OD!Jha#>W^rxn#f)pp^cEJgX6R z)l!SLoZvje);BrF@J1_+vs^Wty^#94i1rPM4dZ$HHa5qf$sqFLXZe-(O&zl3VU5WB;}_|kFPC* z<#2z#Ue?3XP*-=sGk)=4xG4|<=_(p8_PxC4=jMj}{P`1XDUVck+1t+7TMv)QH(&mK zl0)CbeRb#K4QBWmV{pnEBuHsKri6E`G|sQ$GC<76T_FKL{ z>|bCnNIID{5!05v69c(@!TZLm0nG6Y+6%u2Gx(De(r;I=77>M&9A1N|cJVjkuShMZ z)eBFfqa&pqJB3;PW zpnsDcc7U@nI9aL%i!SDdgM0l->d!V*P2ZkPF1opUoP%ZX)L3b2M9W%zCsIpo&3I+4 zYLHFEa$=h`n;kC5z_2w{vDqXqs3KR1OD8Xvac!@V!8iMGZMi?^u7}rgpPnJ;StHt> z^x*QVRBQ6_$;Nzx^G=n#kR|SOl^nGUFX^Gd!G$_Y*Y=R72ut9Hf%xEVcT~Pwb1!bu z_u&k-NE=ChkiK96%@lO?nJ7u+O0(XsmLJUIpR6!Kxr!Gq*A;wFBWGWUKQ@uwG=M|` zQ~7P&-?qw~<2SfyfR6&)MdMPhv=s(=!qVHO@g<&yuZ+>#jS{EIaaU?9?kB1sI$JyV z!kD<-1Ic{k2ilFxasmT5J~;tFUK)ov4hf0ZdjAVxs@d0fE6VGkJ?41Ja<10?;r@=< z#4%=n9)W^~r`EYxb)+i>1qmr#!2P(Gt(hM4WO~mfdF|-rT8eUnq6ZkF0hz<#kZ_1=6uuWJA3i%kee;mZAW zm8O?^Y$RA8XJOV^d}l_<C?{|>scm; z_r)Kki+)aLCm&mvF{~ix z7M~$2xi8sDMQ>u6_Acs?6iZkB`kX{kn0V192m0lTBL+K;#Ju zp{SI{StMeL7?_wzC^HG_Ulxz0k-}D+v^tnTC5H02p+J$_V(gV5XQ}yz56k!94ERTg zTxduL(&Y_;a91>`YKc0p+wf>)1t>wdvRrR&t!*u@Z6QPkhj8@t^?{Q_FdG`FxLng1 zu)Vo`++`!>|GaC95W5W^q&Y4>#?TJJc29B#+Wejm@#(eILoL_7bkSwWz_AG~PIAP+ zo^|?LZ$6L@9d(szLAQV9_kmRlp=EK%wmsyGwYcg1&G~GN_09~mFP2IIBIEu5hRE@C z`W(qdcLFR~&BsT#IEjUTO&2_tCQl*+Vt>bAk?hGG`K-5hGds53Yi#V0K-J=r9UZ5! zW^4kO_pD3c2)+D-vX_$s7BjHqrmMz5%sS*4N3Fq(AJK6lY*NL;vI^KHN{H)$?hfK=HbyG;Ia$C6rFmjtCDHQ@3MF5<&)*QRpQZY zAL8(y+21%e_aXN84PBfcd$>7jK1QC1hTFC3bAWj;I4HrT(*U;z}a+2QR56)EEu&Wi6Hl9{4b zc)$a7SR^a%x;_-<8c{VKXWJdQ8hsWy5ATh2ideDe1O>hK>d(y0&4YxMlwRjXVjpkO zfteG2UMgvOu{H16;&*SH@fbio#G+rQZPow6jR~L!=Y0G2O{q<*;&2GqqZYIsrup%7 zmEa@RN8)DH=RF0J8v~cuY3xSg$(#@+7Z;bUy6Uw$So&mbLq~8(NW;l_p3s9f+~Vvj zsFqEF@aWjqzS3CQ*Oe??UG5EQ_GNU}N&29ynj71)TPU^4YKUrVrAk;874d7gLlCSr zJ8j{pIdwT|Ac8`%PMw7_m~^Abg%+B0_%~QKo%r7S_$W5;TXm}Gfu)3wO=!`uB4xm2 zC`T(EbRk`zroO(sUu;@2E%gg5d~*Um-+o^Et?xAk5GThUwPStfu%4;z*P@+cEz%lM zz7rVQnVUPkZU6@sz%BsJQ(|Clem-JR+fDZi2~92;A_}G(sBvv@*73s1iR9(wrOe;? z7mg9@89egeAdOqGzx+J?s%0fU81}&Rra+zvn5yRQEU7k1vRcaENem5dj1QgzTq9cXd1BrAw;qUFAPgj*G5Bzed){ZhM-Vnu6*#m3(>f z!*`W1&p++nVVyRuH4Hf<$cyP#b1qAf&oMDWU|VE$%Tt;;FFzkdp6^CJ60R+ROJ6n4 zTp`6o$rZz${>bPX%j3E~$A2J;42Y+SWa}q9G6GMgKet^5;}U+p%R*28C6H1%4lH^C zf&vFAY7t7RW40pEpAZ1&a6P=oHLF*K8p}&!YKvuew>GX9W<*3Y92^|GhX#$hSb$Mi z)7a7Afylkhk1c7ckttuI|q&(YD5VxjV~fdSa< z%HXj#Z1F=l-dL%zo@qGl?PKL$D6n5yOlIxt?Pa`=-~&=*zH3yO_+GZ6JSFD(p;?;S z)v%h7+s_jX4!6QHH14Nl#wM_f$Lz-P-YZ$EAv$pOj z`T6c88ZJXVC@aZ>Ln^t&wP}5bkulA2#gmKf$&$JC|I7mXNPMv!N5^Rt$)b6B;)j4J z(AY2ovvob)thl}PYSx6#)L6&cz8Wjn^PL>bC{MBvUu*ej-_Q`KYy0`6S)kbbju0mZ%2K>6&=m$+9$SvS?M?x#I(Vcux~g?OZR8j;{7+c@sVB zZaYiU@-o`#E$y;rYAl+^#wLI)bYoCRi8h_aIyGy017)^ma_;-NRxu~jplyd@i0a&q;_z9t z5x>BOrj1`L?`>uZT&>1~Qd|)+ zN&k^R?&)JDw@iF3svL0&fp-m&dzFK2mN}| zF`eN{=qJEa;WlhI;?Ws?-Vu(o<5Z8&qUrT!rP$WQi}NJyg`U^FhJm=qYVf1@tuFVI zEVrDCoA^a<%il=umPDmoY;5H}<+5vuXEOebRrk^xM=D9`>L;*w?qBnCZ*FeB55>w7 za@D;*yRAD3#Uzi8j&8CXKM^1YmBC~^pS|Iu=oIN4)l!g%x~}y;@0GivC@e)<8IYBc z;Yb|-6d-aG012;0b%1OT_OBZ2v~kOOa9lRB;%6RpM2FH#S+I-??*aKD2Cq}W{*C*g z3$Jl6-qItc*F3SV#LbQyavPkIl9FIjppEab;yRdzvlYmZMz74kEMeBO=l%UMS4^tl z*AWoGi z_UB9T&+&KLx!P93|Bt=54vVtw+D9=SK~Vt#K}zY6Qc$EHM-dST=@5nnN$Ca^P#UE> zMY=nN5hSFgn;`_GyKArEdB5*{k7Ms&{IP$3?R_6SJ_9pz$8}%VTIV{~xz@e8ww69S zty?tIB7n~*%|fdOl*h(kxTohLfhJ|1w>)JhW_Y#sRu; zV0|4lE4tfN()z|LZShwMC=**LqouQ?BqVGfQTZ46hUOT@#et1c%+i!{s}xgx@ZIvY zfDK#=H{je1hH*VMV!bQ(;^Ueo7B*v|Evt#fh~R*!yzi_euxwlD7Ki} zxbH}Ae337=uQ26tu&=ud{mA}9Bd5HPjQPd8$gdz78!Q+pt12%qH@SS;Iqv#N{1t}_ zl_*cu&{n)`H?hFQr*9B=j5h@E=;Rc9KgfOk$Yk|KIh5(c3;aYIIw`SK{3~2{Sm+qe z-8e77UHe)3az@qW$vy1=h~=vde(Y`v)wMTOfsQ;y=t{x{~%eLM!&r~DfcKx2)PDK3n%a`R=2XI_Y&W<<%JMJAz zx59+$I5@s+n-fnx9={^7t&gW8JrT|@O3UfKb#=E5m3pL@en~Rq`Y=%rnec{d%?-k zi4{R5a3rtQ`fjAm!i1N?+S)HRHg;>vMizCPJ~_wLfyZ+26ar|kTh#l>4= z&O29c-G90~p4=g>)RI;2cg2WkZ8}Kwfyr>Ok@ieWnE2J(rT1+V4Gg}OmF;?dCbZp> z0`f-rW3KTn!o*yq3_1P1{4&wgBfrq!dL|}|5MGi}iagY*UxT>az0^h(zF1OX8^IY@ zWxG6FiyU+M36}nV(lH z{#nC(>ZAgHHAA7|KC^p$_F7`PI^apT%V}gPK3-*^q|_hXiGD6E4Fo9UZK;HvLJ8@( z^YtN5o2^>3s%I$3&wtHvGa&hR_(k>i&zETv+)o<5wZ|+kEip;st#52Bj8<&+?tX(V z2WUb4mXL$X*~)qG&r-%Jw_7LapFvun#GpMI^teEns+XGPs;31CWW2ol&x7b z+saiYz|W65?w7UYjN!XPpoW^=B%;T38Sz3iYn=Kb>=FS*vG#Ohj=F6an<941R!)8p ze7ebg^gOFCGY{vklOFPR0&55}D1eVgEYLlR+vbW{(oy#--t;gv$$<9ber-p`idSNy zXvhhBPgy;#a4}~`N6?PrqIw2QLH~2 zmEFtD#hIm#s3@@;xJrQ%z2V~BUT40yzqBNRsi>(b`HXq3>emXZ|IV)$odOkcM4rl* zxHvO&^YJ2a0y0BG+Nbj}eh2dl2#-tGzP*gMS=AjqZdjoN{=C}J??BDxKHEA0ue-bZ zoCmJBze^fKgD5A|)^}^3iYgwXiSIrkOc5vIPJXlPhHbGA4BGzOn5roIxH7!G>>HK@ z0nEZu0IWI^#8rpm65yl*$oB)oQuSqJWwo>t38%(yhqyog_1)6YU0CjO0+;76qmsuS zG&8AX!p=J?m8L_#SyzXL2QL;IC0%-EydQxyM}c3fsyh5hME_!RcN|xchklxE{980Z$}=Q-}QhG7x$APrHJ+K)4*fH1rn$R z%5py{U^F$EDlvKZ@FD#t)bh&8P9I;@KM;bR??5UJP&a z0tlzpk}hae?z;Rv?SekEQ|kXr`^1wFQVXR8r7PX3Je~d1Mx$Tnv1uHmE;`!!P*(Zb zjyUzH4+WV1cFHIwR}@%e@t~80h%$S~v!M@Hszh@&&HC8Zkd8ruY?<=W-qLS8YTA&! z9VMhWwPTJ>E=4=juIkEHXa%<178`1(-+UIgUU&J5ELjk+-V_(9%Wn`*AvVXOHFg>l z-B77>fBwR1qve;PMfLti^}bA*k+cgqviG)@d(!L^YV-rjY7PwyTb0ZhB!WG^KCkO( zog1yNhRLR6_=U@h!UE*?c{9HYS9ki@V#PFr86{XQc?jr!VPK$@MBqsTGpcq!M^K5_ zBrf_9ob2*Gn7o1bY&QADD_89pv=^uFpT#w5gbB{~>DJcvIHBScLY?tUVF7D=ir-yA zZq+>6d;f0ZNwta7iAJo{7fyu zf`k4FN}t=i%C+2+A!Ak8A4SDTl7uJ0vhYVl!j)C0K$VxYLDr3PZ{?8KOJPq*M2vMQ zBNgIZ21*h!JPEd?=2W4##*Pyb^Ft}P0kA_HobNxJ(rbOD%te{CscM;75wDzWGsdbI zB=9m`qu*C@JIi|#)@czUZhDP%Gl;RsX_qrz79%J5G4>t&Fm{{ieNwNEc;(5?>PzVR z`1wM%qWuNVl0XKABo@RygXc5B!;)ERo(*FiMqbLQdnX1Ze^-u_!ASk{-5>Sp$@!nc z2@$T%i3*RdzM`H>BaiT82-{s$>J3rwWcQTCB(X5ilI@5Rdv%2;waK?$fKhl3gl`HF z4$j~F%KZ+lb=~)QczSAUAIp8ZliBkoJ-TvBoH?cUmhUR zb=mqtC8f$pXeErBawz$LspoKnrg+$`C8w}aeSExT;N<1ow{NRsblxx|;U$5vhonaK zl~i#r8F4rUUrD#DiukR>)T%~1gY8sKRccq)E4RMP&Cq}L5vmTeeW7<#bYnV+2Yoy> zKQpb?tjHECqA3?zMV-t*drLC4iuTpMwS9gPorIP4Ku+EJaK!Tk^*ey4K+It~FIW65 zB}0B7A?@PX9ur5|OsZ46jMPdl`&N)p+tO~7_1Lr7rTi>3H8Yb(Jas z4Gk9#^c(S(7!PD9#?<5f^Tv$VOX%i@-M-rpS)BXlmFF8TLP7LF;71%Bp%Tr7q3wG? zzcOtpqhVBW99+cR4%Ufwl6P;OeHiB@`TGCtRb)65+!XFYc7B1uitifU`OwKlN_qIYjIBl0t4BmJ8T#GV|eE^D2Q-mbN3F)t12riE1U<1 zhepOOKFcOL@_sxSDn(Mj?4RQqb9V zpm7@*D1%%rML?t0uO1~h-ro(fh^MJN^SxUyQo8=M^Wz94|s} zX1TdxP#}JtW|WfDw#Izy0O6g79zPki4nS4AcoLFvK5cB!Xzu9fpKsH6{W|7>38zH& z0Mfz&1ih(}U97AF?d|RG$%X#yh?%J;tQMFWY9h;r!onPUd;`P7jTrR%m>B1$^+Td3 zdnxj1xsAq6LAQZwGwRDU)6uE(!v9icJ_eGGot^8z=9d%{Owz(+t4|!b>q{pg2b+^q zW%d{J&^8Q@l-uL@WESw-#>zS#@eWu+lzxY1)LAl3-rq62<7FDjWpvBQz5f1wO-&Jq zr;V%iLqD&H+t?^*X_-(`#()@lw9;0xQt?y;bi`#RTjbwBkdXYwPl}9+nzxy~emyWgUb9gO z68Q1);{f>0&1s-6$j7hBYE`HfX461fbU;7=oV`-cGbrj;>NlgLR3{@F*xP$lBCVtI zfxQ*9y-u$0lUXPNvU{RNhKCOh4#q~Pufl0;9h^^M@vYV3CI{9>Pqn4Fo%I(P9Cxh7 zbwrCBe0nmAlj}J%@W(g`R~dK5?@QCE%#cddQ)`#J1v+a~Hp}wW1L0wqMK!m`IZ=OX7#$9wQf6^M1 zXF;O5l~vA0&X&)c*_o0v{ucD2E@?aIf0bp_Ob__X+uz>?MrD3AFEd!b z;#CS0H0>)WDG{`sI)xN`bL0oofFHeX>J1;CfG+NIt4BLWiIRi_+SBZont24o2nh*! z5f0=s&d$s*F*7?lA7;+@Q{ydpmRVuF4nK2494@F@09c#R9UYw*eSQX`K__?FZ)fm zl^1(6l&6&L-ZgPQy#&7PaK|+vJ|0kQ@`_IO=PzH9`iwa^IQ*!2K=5m~>@+(&i}23Q z9%+<<<=@jINIPl#_;HPwS8A3?YO=C&j@mUO#u)Yi42?2STk+>{(w}cRp&$+y+dJ4t z{d$;gj;aLBCc@i(+>x11sID_FIvG!l#c7HI&N5M_oLE_CJX5_)Gv!TBOSv=f8!KfJ zudc#k^iBRfJNp`aVrXL%3I~gRU_zD^9vu8y_Ven*M0%Hzyj*T;p{c%pj(Mfic4kpg z7JMj%kB3X6QYGbCj?N)O2@=7f;o&-FW^r+G)HH6Tf0U3&bb_0}*MUV)j`VTr+OOy_ zG9&FRGxW^O-KL)z0JO@<;poIVuD_gIjb9YTp-{=>0(MIPy@ziNj=V{6hGZ^0-5#<{4>-e@rY zOIevr!51F{p4cloy1KqVWjnha4z-IERYrX|i!g}J2V1NG&lZ=Loh>@KAmpEmH=!c3 z1W^;Fy`6)C*I~9Ts;4n0Fi;wns)U65L!-59HGmB+E~7(5=*8{7z(_$YseBXnc^tOj zSfS(npWZh)E}UM;@9kO%W&m6$mi0i;e#gce^RBfJj-XHN1b8-|)x?+i!3p7zKHjpGYF<~e+ldQdc6XbNI#@-YVv;Sm+kXCh zWIfvkixHH`-#Q$&W#niK4Lxcy+Y-jJEQOCtGvUtNg+>_=$R%Ve`nR%U!x27fEYK9H&LHI~kOJ^q^`PP>&M1|~> zm?%6PhfH$M#>CIsXJ8{COgtxenj=n{?8g1(r+I8_3obA3Y9;dzKDPh-qE+XOU8t~W)fFSW7itvW;7z#G z({FxE@ep3dIU-Q7wT@s=4QGUSr@1^mw>9`kndr<`Mi$pql$}@mtLx_X)4yN81_25I ze7+};nxDZlePMR}do;LuBTm@!_pj?R{b$F(;nuEK|6ja%m-hU9&AVsVPqC3Ni#l!X ztWqnH?R378RKI|8q5;)-lauI*@}d5WasRWuvVHs=8p?dzf?CMV?qtP=w*G5}G{U`StI`RhSW%5p;<$s1-!-nh=|%U2+qKr zIiXR~VulKK#eYUxo@kh9j#M}<*KOR7@2~a1-CY_24Yu`SKZmokGZKjb)d!!&_z}kV z8#sH@;o`H%+U>X!w215L^YAWY+*%4(LG}t__2Vw_+ZkCvYb}qI!8SK};oa#iT=BH< zoRKbUg!H%9);otRfP8s12Mh3B(3)q3$AY#C3Jp^A)I$UW+c9y&Wntn=+u7Cy^EU-F zq(Ssf!MV~A{^^H&ACX@wH~H0`G#OFHjo)|ks_#R2CZLeEwzk#?F5r5P)XhS}!nSut zEEcy9&Rw{q0GjN?#ECMDn>rK&Rann4$;2OhAA_`MT5{IT&JMkJ;O}NEZUB@|MG>wzM4dioT|Qil?`EDSzbeG!iEhEuvWc9mms_+!(zW2%Uim8IN3xmfh! zTUMU8WL-CuoHgkSyN2SFAL&lKo-aRb9<4`Z9x~Jm_7?w~6E@Ec(cLsG+`oMR~c+^6>Wd0CMitrLzH)NyBXd>}`Iuw+=R|CM-${J%)5yBw4Bk?2! zl7Q|{x7{Mc!X5ytCK1BK>KhyzYf2TXqF`gQ1soEVADQn-!&KTXhRBFOEh7}Wd9k-5 zyg~gkGc(g3FFexUZwG?TB7^qfO53cI6kQ{uKOokQ;7~U(GovOWYkG1OXLob1)=`sy>jJBa7c)&i_6N`@9F7~&!4qkLuI}BKyDmi@{2Gwh!0@AsUH}J4kMS` z9-0pR0ueQ=!t^X2pjvyRDUhr9%3f`L9hZy+0@q!eDO1yn&2QRE?{0Xl#LG5DuU;E|ZjJRD-z3!=onXpR-Pil+d6{4@Gv8f$!~;S`Ox!r% zufq6B!BB!lDf@y7Sorgq&1VFQ81w@6$IBA)3slG);)-PZBQ&{jndPH93|3^BYs~2=PFMI6giu)Py5Tr)-~v3kawB$yub&l#{)#1l1bw z0gV>_jc4F1%5qk3Bm^(34-J)zjz_7~H{5-2C%et_~ z{{B9~J6Sc75Ro@P8R2Jk1MxflK-VhalR{MC`=H{AC>KPHT{_Br+DY@ns7Aj%EfPGm7@^a$)d!XYfc#Q~y?&E~A zaPgr-a|En;qVeFSaoZByn|!WX$f4L19XP;aRTsz*TOP@DrHO&*b?47FYMZt6^B+7s zKrE?l^9ys_3)+7z?$_mSYgKO0&}inUJ$4F9A67(*#p6snyrXqrnh)Daj z6i}R!l2sV)W}Sup96?wD>(fne7f;6T5S*E^3D))Bb3J3CY0F@ju766CURWYYh+SSb z&IptcqKX%=XiAkEk4mTD)_RwgHV0L74=u*2z-$AEB_gtf5p*_zNDxdnwip5oX>)Tk z(*1b*j{*O2{~{xGS18;xQ|ymT0^rJMv2VV6@~1r@NtB9XlN*uKZ>mR z!muiU{R3Y@{pjtThYxpP?IJ-o3^^!GFx}8lhB6Cwwf6n}1y)v8@WfZ}@ttSFlzS6% zU_nA5Sp*kST1JLz_=hB37ux+4vh%LT2iuSw@9OF*GVI)0Uw52XG5~}j3J3wzG(eL; z%`&KbU)lIGoDIfzd9gzos@_QLc8sfvtBg+7JHr>ZLR3P%yc#xUT7T5lU8j1K58e%O z)#~c%GBTZ@upLu(1hfu7^gV3qx9wc{o`J3GjUdEZX_T~ck>8Bat+1ZKZ1KYy@%-J*zWAVb~|6n}64 ztoh>uR8zhG^9%h03aR4V z^vGeV-Ukp)8mnw2B$#g?>n~3<3)ubsRfcw7S}@=KUQs4@V^!!RhFHDC{7DQJU<9rH zlo1tCIIeL$IC5I4e);1cB>bNg=AT01kcRSI-KtSTn?%%8jqmJC#B14=wixecJn zB0#;7?{G0S)$w|(=U3zY46)7m%W;NZ{}Cpb{P@aGSUr^9pr-wEz*U_uVTIgl&E zG->(QaLAs7Fh3uYq1O&h}$mr_m#Ky&89Hy_uN!z1?N(%~Dce+6Q8T-g`3huFC zd$cWtmj${_pnG%$=_+=0AP^raDjeY&0b)SLyf-8kI3Z=E>o$Osp}|3LiA9h#hAN8n zJoJgNzJ4Eow8Wy>&s|f2|S`(w?HQo zN+axK3U4j+X28EAAf6BoHxcIxm;Nc==QD!^wt2l9*iBX$y2hj$40T zl?($K%zIt2(afA+I$k~0-fjlcXP`TTyk&CWOR$o_tQmB~@&liF8*D3kD-`YQ{YeSp zd|jSzx2#qYos(k*M-c^~708V)UA)*9{ot;kp!(QWD;FA4^fq8i0mMM<^oHPSbx3IF z(;sImD4u2}YgftC)D*&vfGoHP+uPd@av{Gi6?I?#U~3-Y6)aFJf13n!2_YS54dDVc zDs5gZLNTmaXS^^rS^)>iAQAn@G8r%cp-xLED;H|3`&i^43*Llj*QXB&PN;o-hNsO< z4%K3ylGV@t_VG0W5Bw|KuZH@1az4~r9X>FL2yX~|K%GS{AG+0(HT@7n$aSs*8Z5gTqy-N3wX6v$OqR@}RE-L>DcE zOOumbP?84q5GB!ZaT;(reKT;%=7agP_wE(I*&w`ukcF5bT@*irS>|MaE@5|hB#q`Q z7xFIcaYc-?2@JiMvY#Rz9^N0gop3W?k?f9IcV>8jJI%<*XyiJDi(mLz4;f=HmKj6g zgmv&dn7FpAr(D%*bpYmaIYAzx>j)UwztuO{)60um#N`n`{}3!`m}4g=CyhB`A&(&Y z53X`LGb}7@SPTnC5#HKAK9UL>7#p(@Ovz^r>Q2KGX+%&6JQEWWcmTuT;2@+&;Qr8x ziXy3JqGMuAT=M%&C9$w%<*eLRk>V^Pv$n-zZ*37KLKK$F0zMA%m@p1^)dryy5teYD zO0wIjGKrW5i__5|^-xDgZhg?hZ@LI?Ag;{77kCheK;r#9dn>j;3?f|1Ebws{H6?Yc zkr%BO6=rB%5e?xd%ulipQ20z-*$-HlWGGdD*@N;;$F>E{Otjj=IdNF0cYVj_uz z3`8@)$1~o!lL(_?d>RdI;f2C>_xY^x& z@pLF;217B|9%B!#1DbDwZZJQe`&+p9JQxi2)C)u!smgV7ewIv}~<*!9r%N2DNr}LhyntHhN`hx&(0R5&=y$ z?7+4>JSAlsYTyB|f*F0JUFQjt4C0^7AnWUZv25+^04ha5EhZ^gKD(ts@kc+we0zNO z0G$g)!FvH-eD?IIkinmiSMmTZ5i`BSyLQbLB4TFg*hfac?%3PgPXlp^0hlEd$(@8m zyBYgu*=?NJlnGYa|3n36bkysvf$KuwAdp@H^&`a4yzH`V1@xb4j*oTEF#Su3>do=Q zfS`TL9JR8fcCgv+n(Tk4-M*dah7oaf6Smis{Be#+>J*_w~IdeSU zC!S*8{U7W--}jaUhS4Q1kmhM;Of5S*&7GaM`OIIxem!cEhuUf5>BOVW z)kH;yg#6g_#l25{6|l8=_g9~1DL%fwa`-So`)&i92@HiG;8XV#7uy~vz5?FrCg*FF z-0N6c5a;iqu)JCywVYCzijeNfQ7xJU3<#$SVOXa5!Au0Q(f?KtkRsQq1^j7*1w=%~ z_evbWrNIfPfkp|+lS(ZxnoE(uAGl10maR@f+~u|A0}*;K$$BZ;7#}0in|t%wt!;IG|AnlUt4<+e?O6 zh{p;l8&kxQK;*%1aBnDqYa`TwTL1@%dT6Ew%J9xu{vy5R;2ZXsDtilP$pSp0-Rig4 z*jPZQ2Zx8yW#eU59~RZsdlSJPAgO9Klto%4=XRCNAIQDiqHZogh&9B^85+)Yik`Z_ zwSdU3(sH^HY8L}SdR(DsYG&=986K*!?_2gyuo0wlO=EAbfDG1{6Jm;VKN|tCm*lE zHAP#JdDIfZW7vQ^nzr8tD@s7l{kKLOl=UQtxJtuX1pI=l`5fjh0C`VB#Y}}aK)^aU zl&e8(umc{uM9lBzg5uMsPh9}+H|#)?yWDO$dY#vI2<2=K=_8m-9PI3#gfK}(VdMj; z1$+0h{rh}1SlK@Q{P`2yExSf#@9=QtAa-iPqJmj^jq1@F08zM0fC8`K;c@4j(JVN! z$s42=FcKUp`G4bC!tevCm4fs9C)6WDP{BHZ7y(G0LUvI4!ghtWySp1gq{-D)pf1%*|v%l0_r@qxF&rkS&`!6$?ojgE!DaP^u~ z!(sT`yg#B9S+z`!ZuK}U{H`Q>s}!t^6)+afq)iQG2g#` z2a*HIGQ+LzV{HR)DFEg{zU>ZnufdP(aBnZ2o*0^V!TN#P27Um(pmv#QjUaRN(_wYm zS;FdsA;|!XIZo8w4VERN5+$z@_R8QMZbQIxcz7ro914TqXABaSelX!cUUx?E%(e4j zdW}l}!Ro824NG#N6qfMxvp=R`I~qe%zi>{C=+IC-ZEcXLq8KHyCYsf^5Dqr|+h*ps z>?jv@Y`#BXMXvY51nI+T1ec4oC{Q@wlNLk>O-vu%zi+j-HVGuqz<@nmI~dvpPOv!l z`1p`etZZzYi9#KNEmq|nzkz^A^gbP(4txyI2CUU}SQpTtsvLqX=obb2LmT83+?c^9 z#euDX+QM8UdK?bvxH${SAqD3U=q?AHjC29_g5kBcvB8GUupV2j-oqikFuVbV5B6sS zdj_Mz{4(;b#RH(LfRTWMSc1I(7)XqO&=&Z4tw$*3u6hr+3;Dc_nYc|0O=atD~W;*UZD0@}gt+@8||B#m{xyD-hx^A<1D zTyda-tf@j@`&eC_T(BM_B)0ifgL_YZ*U?D?<8N%13^yG&#Vh5E{F=qykZHkjr&B%b7K z^22p{UMB919Haz^ObsFCNyPXe`3Ep7IVFWu40=eo zESC%bQP7(MG;M<0!5amI(9~4@w{O?hCVxQ1?LQ&WcT~#&nE?So5Wp7-Wol~b({1@H z*RFx83u3=PFyhXuC^8BPHE3Zew}9omgcMn@#TgLdL(`2P7z`4xz?%C^wjUZ& zL4-8j7=RD02LUb^8!zDAcDW=W%3O9}_TZ;^A-R%Masw&GO9GQjtNZ2j>eg+Swf9O{8ijhzfUmp=Va?M(q6;`R z2rr?xLllI-y6yj4#MUr0*8t}5KFlO=IRFJsfRzIFIyJ$AK>|7>Bqsi?QBqX2I99a_ zwEzW{)6c*I0~);=M}_9(<>j5F0(Bex?}e9{4#{cc zmz7z7eiPDRmLX8E3p2rs(A?Y{d_|DAH#xu6SN2vK8XA~0_yh!JI!u5!;7de+cS3kW zY=I?u!Ia52d58T0wgF&UdrJ!t%yDXR5Q_jAn$Zdw?LDv!lB1U3rV8014pIx(S5_Y2 z!?^GOmVj0@&CNca2oT<OLZEq z*!DoI0`bKQp;RD3Rq?)npN7Ivn5OkjP2wD)5T^oe1 z(CAy-MtJx3Dok;tKMSPd*ZTghxVRX+A!@r{9q1X*kL5y1Jwt|y)O5&ItO0~_FyO#| zyctu^?V0y)g%vuC#o4!AKn8L_H5_n-`|*M8biYmrao9#-#plnT0hxsF5s6`=meSHv zaBzZdN9Ad0X=>y&G$PR z<3@$6-}pu|z-|M@39UMPlU;Vl>_H&m{Kq7G1~PV^yu8dXHNpTg9zL{#`330%c6~By z>rDtVX<#^-Zo4aV(n9ABTH42WmSB^B4sKB?`p@j!z~VMcQAlh%0wRZ^n~>mOn8{_( z1&T&6U8V!#A|T;D2M6Dvq^yDn4qz(0jZX_{QE2xDw+>4Q#|f0cThJOOJrDPGUIWUYf8GWdKhSb60ZUA?a|f_s zSz+NYcoQJ#AzcPxQDY#r`T-|!vk*b4mcPXkM-bq{6~R)0=luajgf#W78#j`b7Ke%q zpFXVz{{*PZLs;WjrXPrOMnS=mp`i+Pjm9-zxK?P#H3(V>Sm*FrXso&pHwtE= z0-m;+8CE3(`2z=_BmfUU7)}4oKe6Fm)0Y2f5k2O*Dn+Hy#^9;KW|o8pc0!YW?5)uK zl(8y(#fbE&I?m|@h`}1kNO1P%;92JBnK4x{Rmue$M@K?DMQEwg$T-(IZQKe>mg3^W zVt)Ag+Fsz%*7TFU)seJLNfdHY!xU(&=LOjM6r8{R`ul$h7nB}FtpI~(gg@bahkoIkk;JWQs=o;Uaj-#uoN38Xb6({Oi7Wj#QYa`q>a|D^?h56C|I zUrE!xqZ{*_+Lr`X8L_H1u(@?{^fsOY4iW|Zlu!j zGOU2&e}w}t1C{W)61C|m&NxC45qa18{Ie$hH&mf#ANXbWf0)_I-O_L@^ zJ{QQEKBH_?Qz+zM$S8g-_X;pipPEK86@GB~Qj3-VkH5~GjJ=~_0av6W0( z2;V04%kHlq@RhCYtQVD(q}aBQHfTZn!hN3gpnA`X1TuMY#^dE*GQu86cW}<$3@;u* zA8DxJH8|jsiXlHIM167FoW17kjJtA&k7#E9I`-nYY2E$Gy5;2cRpoP@5<0+i$cIIVFj zd`9ax9C5KuC^8(~pdJLuNu$>to<)f4L(ImV{yCAEEh$pLvcogDX{ zYIv6;tHVNE)8u9{FQGJp>&Nnb1%FM)#50yqdQ>t=AmltJm_(ACSv+O0sH@^_=dvP5 z#>Gp%kV-tigsL5CX52q0IdsjNy>3Oko`-piy<^{IEY_9G&Evghkkdx~=ajm*vs6Us z)z*Ai`b)(q_w&Zp?dRLtp*P5?efoLS_{+3buAk_`RO#o4d)GTykEWQLjqNYJ+9Rb5 za>v(Cxdkn=zkC7!3OT8)`f}sK=9VzzUz4oqvX&1BRZYLDsbBo+9fo%G*s{ z=5@iida81`{*czM2saj55^X9uw#y|yylb_pEseQ^yhir)R<*iThrC2tt+e^5XI7+$ zpcTX)%d=s$a{l))Ui#tsB>YAirY^*G_3G;>5$)v3lep{t^6jH>PP66%gkoPjWmm4- zvQrU=VZ4}aS651FSYl_zSuTmO`09N2gu+AVL;B09o+}P#6L17O0r%W@#)Sj|7i%_; zPgZg=$A4Y>j8l%oaBjtqB{!M9Io!0>@3(_rTtQs(%kU7r`;Mx!zhn6t=P7h0d>U&6MK6U*A4qoCp8)fCOLuYpdMSI%|o=Ymh z=MHx7UEP**UF<&|J8y~JJFZbC^xSW_I;1{Nia0petTQ2{nIIa96ss$V5Yh zIC6U1W}&29<8!$xI;qvbktjRqR=~6tl2*Nv#Sqx+PD;YhQC|I zR+C0G@`}a}AZ1qEHgs>F?)h6>yGC%lCN5&N5f)gP`DnGFQSO3FMoj?oDUV^=I z-V;Yh!FOK#duR+_wvJEzmKh&aNl(3LX1z`!0`eviA)%wR(`om%S;tPkRrli@{>pA` z1}5Re@(??v)tttSVKu^r*78U0wD%Jng%1t=_nX`gbl4-_PsRpjA_bKWx#v1ex0IJ%EIbmn)TYR zr0FIZoI7-#n^5FfYF>d-U^|{T(u-Yv9E#_bM?`XVM+q-#Yj!Q5!n}p9$p;tjuT$Bu z@w=ZK0Rk1`DzZ4OfuL&KCc}F3gl|r{?QuFypugtTT@} zbR72J|4~-6y|!Ftp_;E%i+$Naea-Ri)gPzZeC|cSl|gq#+tzTbgzWGX1TJptl1K{B zJJz`DqxTDL$4my#UHAMJDqtMgyG2U9K>49>%>DbT4FvtKyt&k8IgYou5;`v!Sy&+Z zN2*R|B6h3uccB!cBG-AQr7tbPaTa;}Q@o_VOPpqZM|786!|8B2=9~*0!);M`x7rGu zw$ow?nO{^d*e@NSllfEb>CG>&1S18iMVyO|v5jaT0zIrj{+xpX?7p$F2lwt-{#gTQ zA`xa6wAJQlS8EHIPEfv7?lwe3?ysIs;^VBij*K`tg@4p`fEx^C>n&XYK{9hp>GJk- zUK5JX#YF@>A#&GN8I4JD+P~m+3|>xENRq{oWxu&uar7fd2uR(Osw({NAa-cwx=mi~ zroq}b(gO^Ac9sos=KZewMxzm|05#xL= z$(wvLwiTLARH&D_TiL2!5GPyr4fG6g0Z*1{0OfjyW?xDPbeKuBZa~B4-@Om@jwN-VmhcF6ISm{Np`L}PS!YMZc_+ehwn+^C(L{Gxhk(+kCAK4x`TnxhUiiwT&`I=HM-^P%%vjfbt4RNSCx@P4~G zGJa_d-+5Q$q&{RhwR>!LbXlMSa(25buIs2(SAus#h8?f{{yii73``tLyyt<|Tz-dF-0qk&Mt#-M z&dtK1myS9ghzp78gMP*9+%&`a1KUO5LHfvlyjCs?mVXzu4@||tCEV4) z3f<;l#s-~&va}}KvFGDzLl`6r$?E|PlrcQ|v}-6vx={$olI?}>F#p4S8%!TonJp?| zcJnl;9q6B>?!ThLd8QFvlE2&@G*O((_t6b#=!x1V(5TIN5@F!BedI`II#S6P(+(Xr zrOM1G$jQ?c*eqE<%3PYw7tsnyLZ+B@JA2#h-Q5|h3b5oHfBulu-10%Z-ERqt6ST9j zwVU1Cha0||qhh%utx;xYW6FN@2ln3n$7;vbeQC0DlTS%McD%TTQ}$`iPwS-Jwxgf)L8JB< z)Qh{VJ8`QnbILUvVL|Rw)47X*0Rf6^VGm4{1~>)}4-P*+DntTdm|L}C?C4ipv|r-x zeg`3d@gcqNw9OQ0Jy&luZ}511Js^`MaMWnrALo4y&+gJr==3&}f(P7_mk%o~t@Fo) zZpp-5@Ru~S8?bi3Yrq02dSjWIl3A$O}!8D5>3VVP?AkD zr7`A^E1v(F(|!LgvZPd82`|1%n)>qx4!6HBa49%JVMl6j z{XWLyk>o|gTWx_m&n^lN;D4BSu$uQ0`nTyVJXU_uXQ4S@iQ}oAUJ~y*+g5^iDEO6@to}vOOm6e$f~jtwsBM$nzRN>@rXGtxeb3RBDP8|dCHT^RX<>Ut?9wO@l| zziAln*gu-x*&ppBYf$rjR?-je!$k9#%=Q+$>%j49o8JAf7u%Es!o00b7~9ihwX9;o z&4WhHg6Fy~!oD8kFAUcN5wVk8*{xa5!O?Wk=Hf}?#WT0Ca9U5RHhwDWEt7uxUhSQq33L_vj_prGJl8YMOLwyXP(gYEdadzL5{GT3TFdV>#z~TP<^=r*1B=4w)42}2Q4avn! zp{5=|YIemS=BhKhP|e5Pe%>VZ^)!oW^0^?wf#nf&85d5?s*JQ$KtK?(+UCu!yo^ST zl|IN|hb_rj!e0bV$BI~geE%!*$tMCz-R=a`TWG@IN0!DG_TFRwG#FTE`7IeD;Xf+* ziA6=5sji24*RF>%GhNEnpyZ0M-WMW*kcEd^F@s9Ps@Tni6Pe$yS?1w4djzUG*V;2MF9BAa1HJnHQv zR>7b0q& zNCTJEeJJol!3~0VVF6g|2ke?%<=>Hqobt?u69UW+UP5 zr>m!91L%`qn3FNg_Rh{xRl;!;<~R>6UO)eB+-BB_?WVQpmMxsu z7k=|K{!zE-@#cXBJI}iaqzJaTV&@zg$HI7ltGK#4ty8P@n4tZbKkwS&?X{B>27JsSOKIe#>Wr7 zfGdVPASPd1n9=nQ2>Hg#P}_s+#E?g0c!x-WR=u`)&I>&pr1df4ux3pIwYr~+L{tqO zliuc){1x&((ss73;y?VxnrnjFpIY3LliMe>P9S*>I{JkxdgEfrBV>9(t3tJ#b}6r6 zb(y*14Vh$vJaRf5HCDM6Ta<;{aqBMn@ck`Ox7prishF}ow=hb6&3WN-M!EXzF54zZ zND+d#+LrK&iNchZ0gCtFI zEqh$u67g4)I@dFU{{BWulk?9rW&`e_(aQJ+FK%3%<52j&DEsQ5xVH7n#t9PKArK(A z2PeT@g1b93?m-ePcyM>OhQ{3`xVr@j?hsr8%(?G(?|W~irfO=csQ#mYea_iu%lECl z*7{!X&7*#>>aJ+1;b1ixe0N8cI8PD@p!-jX{bsW{^{>d&$sFbVqNH0mda_voitRU^ zsM#oIt5D8nrO_^&Sn^Pvd8fYa6`ML z^~&QJSS_l+6&tO1l%LCfdSQ$IS9*+L+B1I)Eg+4>sWm{%yVkCAkLl|o!RW4e7d{NO zP1uP=^GWEqUS88x9wZF4Yc)#05v6MD7C8H|U^A_2YSKqU>12S+o|nN%qcWA2mY4hT z+BSVx6W*cpQSrYYsAG!BL1Ia_gkbJR3qF_K1xs7?kMSoX3pz^7Lv5r`6iLs9Oq`@HI-|3TDK_tDbow1}0XY8W)t98a$Fjgek_CZWOJg?dk z5eJ735|@@jClEyi;7PKWd$#|9bPPG4oY!Ys{~VX93Y_`KVZt-ie6;Y(p9J^GNfC!P_fdwcW;@s z42#Ayxru#1U#*LN6x^gTtZ1&lP4kYzF7g}QM6XMrwD1n~^%>KqB2wLJc5 zc46(TyKR=0K(zXln=rg{`Set#3Dti8Xgrd18@WcIH(v%&H1&nCc6nt>gEIANKF1@YV2l5=y?-MQeV2mf{|_|ySLDg& zi{%OQ`agdG;Ew~LZSVfZ4*wOJj_PV{GymuJ0GcI8bpg~z{|6HU+KB#twqYv11^`$8 zxy~*-rNgWLv_OG;iD!ZTf8Gc$sN-tKVNm$5O9@r^Tv3t7{L{p@`v|lDqXEL$#{a&; zH_z{by8nHJ9-pAM^B4d7H~q11|GFo8_JlkHvcifA1fmIr&hb%WtNwmk#0qrn5e}ul z|H0Abe04~7^k%<0FmYJzDN)~}O&w7g_~#VW^5ZkW@bUCOUxO(r?HRAOK?e$)2n!~U zW$<~(Aj^~D>Ew#jTg;(*|Gmx!gg_2^~r$j`T;$iH}@GI z%iN{e?T81FtJ9|Z11ASf?>}#(5d^)Mk6``y2#8x$J$^b33=W2}1E~d&Pb5%Mf@JA! zP5^!B%OkBXCpS$QEYMxXB2_4>P~Sq(Wq0=evhtIB0<<1TCW|eX09-H; zivZ}tH6>{$LBr6ChAe>pwcxgXk<TS;~G|a`1gzY0dU>c63ythXo-9hDp=co5`GgkJPcr_Bsp$g!#ao zxqGm}vIz>>%hUBT1B0V&iqJIAHw>tI@H|?p_*hT;KE(KLu#tSoj02D#{;V<%oL|}W3Vrf7Z@g|> z$*mmDLJa@})cDJs)7?1`U?LV36>+4F4kwoJ*taoz0Y=UD#f@z{SwKLn-zm7?0%TGXfO5bRGx5y+5%8HGtx0kCtglYA68BNJ>g3Xc#^%YoY`- zP?WP@0_MkRbyku89`%k9Y_)CIE1gd(%1)bq(b>*7M4*`f!QA(vG75zI6pieAG2*dW zK7~p!4%M16TxgiKg31*}0qn26%X@&gCiL>>y}tgcaxj5kvcWQ-lmXa1r%eE=(jE9X zktxt>Jp)j@P5@@j8X@^#Rx%VI8F3M{*4ukPkG8gE4!Sw^WI+pT?0ovV;1*3L@Bnc7 z1kbx3^%oEv0pcDU(#^X2N|GMS!u&jb@UP82IY4`U=()yNnXw48f#I_eq6=mQjzzxd zzB0AF+IaTpsBKq!X!X7GrbNTQz}h!_`OyhjbK8s<|1+saJ!Y?xUy})5MR~ND0vIG~ z$K592@~fE5_wmCAGiW=f9tlhOk*S3dXA_4?t9HcvGN3|>ibCKKFao@~PEN=wj;^n+ z@KJ&Q_Sl0iP;yVJ!B#@h5b!L~=T1L4JUl%!Oq?J{Vl@OHgN^=3EYQ}LDIA>UY10;S zp^7(4@_K_^$k`+CO+G$=rvYCBp2+5?1nvxlA0~90o!xYG)A#<8b)xq=Iy;Nzu^NL)Gea*h?>BR7%^Q7u{A> zN)x^kXL82%zVZE&edNII0#ssnv*+CGI=^^#xA=QYN=j0)yk0r^yIMXlt$t1uniAPA zeZ5Ry_u34jEn|X5d*Y?v!RG-; zYO?=q7nj!q_X^e8Hu|YmLsPC%rv6g2q$^wMBPhhp&A-(Os4aboI+i&dqywWz{{91;ZpKR<1PAUGuC;Zc*=^fl?C z!-^((IgDWtSmRC|w02!&UI2veQ7cl+_-x*CJ3S6-N_Fp?k58A~%u-yQhKA@B_;MWP} z%4VgL$bO7?;d>gqKH?c)EIDccYJ_LS(?(|sJ`LxJA%V7?ft`&Tw&`-b_2$g?;K=Z$ zW{Ve?6DMbe_pJL@z;gn1dt!mb;qmL-WgD=P046f>Lgh+y0Q@-+OZAt!DrU$GAZtBb zj672R&)c6%<8!|n{OHiy_|}LW4unOB=1zJ$+5P3~7>N46w$3Xt48il?1{z z%6EN#KZTqdja29%7Q-jnvhD2TEXMesd3u&v><$$4BzwuvzWY)7zF4QWaUR-!vb@o? z!${yz1fCn(TQ;BkYfa+|C5QZqt=`M>Oq+agAPQu%L1oUT{yV5@M1x*vcza82ufAc0 zOG&+_5g_~vChQ^Y6V=5>|7Re7rEs+HO%DzIktY6kjPbA4A|+p1=l?rABLxXvtG?U_ zJ>7Pm?CZ&cOp2LlC@t#l?6J~ra%9gMUc>q`U7{K2tGy(BjqRFhEE1!uADfdeGL*R$ z&ftW@9N4qtl>FxPLPSAvsMSVgHZsKw9Z&$FRW#!1+g};xm1I7IV(BO@%;M*}l~_=o zy14R=eK?#d&Bs@YWkeh5PB8HhZ5&Dax!svn9q%{>e+S)L=IIhkl{gU>*iH z*%SxuXPxzFstYpS-g@~JUW=bT%~RjQ4HP{pOS2O`C_IpSjO?dQ)qejW6p0}dL?oXNT)e#@4UqkQOyYoWeV5xVs^KS2jmK1%0S*Nny?ia1l z!$`LG%?3Q1gc`B;ujH@$dxx3#fkID_Y4uziLNA+V;?S3+{LXlGI;%qdpPG`iHn~q@ zNH2065`6r-3(rTDFoWG1IWcZ7MCwGBF4_bYknh2K(65&ZUt6zfGTcMB_35V^PRJf3 z^$TaKxX1SPf4@8-WwR_m*yvy<{pLZ##B3t$5j7mY{aHY(N{?c2a7}&)8!W@gZF+Cw z)zxf()3L)GeC#qdaZgtt5%yx4$FIz)gUwO%IWnF6>gY+#2Nm-HQ&Y~mZ<9y7{mI?y z8h23d*S&sCr9}@H&?^Gs32-teH zj_yXEZGWz})g1ll>rRYljc)hC67E+Y_UQj3OSlZSg5Z_ChosD972{s*e^zH~ih3=Y zPugCfRq`znldfS$l7XECfw zfoc8vdrexX7NfZ|eHWb{XSe!mVH&eed}5M-Fizg^EECv81Y~3w62ESx`Ran49CRW! z%$g}B@hZ|D{&_N@H;)k$KELzHi4qNw|BgnDzmDi$gSG{vd~iC3Fg_{ogrLr z;?jbXejQ?CRt3tMHlz42I_NDC-j=sO7WbzEoE5ix*oR zYsbXxluX5nBgXy2PKrgBc4U!|;aF*~i8ksEcA||}jxhFdyx(sJ7t)6he2=l{ab^Dtn9cIEN!8>omr!$F#F&MvL^Y`bZYG4pU zykOnKs^W8n%6qHL>Ki0NQ~U4HPrHrJRV5i5v%0MsYpwVCRPm;r%{DmGjiMachp;;l ztY@7Lk1JVTzg}6vfpn#NaPqizGi7vv7?|I zD`y{lzZeyKxL=?h?*UB?rZmCD4)4OwC!m{5q0r?cM%1uR66=T{nG+1AITxak$v79; z;<$~%`uoqDYZ83)7{%!KnX%Hg#)UBrAATHtAJTBm;-~y>;;00%Y?&Zwkf>qjvhsD8 zs%Bs*eOI-lHiG(yh3o!4cV_j;)T>-3n!2&Z=3$+krYQ9SeabcCcUTz#p^eO;vy z;f0thrtl&JBhl04#nW9^WIDNXxOGu)Vocv4e9SAc z!aC=z>^Ptx}$Qp{0EzCg(V)oXbv1_er6vIQ<m^{m*CLnl4MduFmS~_#O4@@OOyoZug=?_k6DP8X zOC~-s*cPaR@Jon6ofjURC}zfUi+6kC=oiNM z&Xp+B$-Eb2Y*qeFiBM~YBKi8_{yTb4&Y{$>B@~~oknH54z6%2lrY!k}iRt@Ui`UZ+ zB_d&M8&H+Zo78-)eotL2NK^Zw@PIt}2(|%B7BE92XtR z;JawzYG@v`vnXNV=2Y*VQzWX~!BehT%g)_U>f?~e$Bry2vz~$MVQVAIfSF0aS}Fv5 zE>DK#1DuQm)eI6T%Bv|!K7G;$dOSpwCY<~$`|^;Knu_<>#Xn>uU7X2yaI>jB!cG+A zNOX_3h!^^XZVwQGpqj%oyKmCoXA_%ek6oxT1v}Y@;vANK8T)9P(IJ6t`&vphKs_N7 z=@UXV`#s5lg&M)uGzu%bRw3k)uJA$Pq`}VlvJ7JF2xJ7QJPHba3 zapdI$)mMWPQ5b=y!e*ugjXW1av+rKEx&}^*$yop~kQl65#qyzebu5dN_r>?iFOLW! zOFri>eJnV^!&3}0471DHZB~|so)=*A@=cQ2$7~Jsa z(HKRLF($!wXAhzs8=5vt+ zm9H@>j`VAd$68#EQ*wpnjm~4YLOQNyHT}gAhk5Y|H$o=y84BqnkhHp{m_=QbkC2jB zv}ddPFG&kS(F4Fa`gRawt4IwBi8OU6e!$YT-h>ON;sK^BD?cDc0h3=_$_61oWjMtT zI%dh?QK|L3Ir%HE42DyU8;%Zczo{2ybCd~$C;^2*DEyVidx;u~Gvg;-I=e&nmX&R1 z|GJApr4-kQ>u@ILS8K_5^nKatMg0Xe+G})03G8iAICFM8B~^P|?FBvvTvucjg0- zWxKHlA#|EJ_ys@N*vxVhXe210Al|B~a84LmdabT1^D@6QpePw7=7w-kE{v|kHeW^c zFrf{oX?ZH@55qrjZDVMggwl{K{Pl3Tm+Yt70ab`=c`R5Y@drlqotG^}~9FVje{O0MsV+nZk zB_lRdkfL|Wv5*LkFgqOkUB-ExOeFA-Gk7>$_Lcg<1WZczS^1lEx(<2f6HJ#aN}P!5 zrHoeM#89Uw-T1T_pV---jIz#|N*-1!*FQ_@w$xP^iF|dqMobfAJ8bBcTQu0h?&#lV!$y_tlaT4$e}lm&_vRwJ)Yz|lSqNyHy1c}EiI z^u@KnrW+P>_^Z}%Q$`jHJP0RVH6)sxVSb0i)Wx$AR`+!P@5BI&5U3nlMi$5;34>a= z91$_^22EkW&`&Fe)1S=9fBm$~ zdeqaVLb|?-b%?sdF(u;BM8KUyl&7!+7)2vqfOx(HaS}x~yT$7QjV|xgHapF|9)#=1 z)7j=3OV-RUJ`<*F4Y>yN2!+n|RhyczGIh+lnx8pI5s>JRs;7&u1!N1+S0j>`tSl+m z8u-;o$jjhqM)&kgaP{;DTbpg?D-qz$Y7KH@D({W$@+?wUP&_;FAHMbtnQ?W06Jg1& zlvh`<>K~x3-|RSzx@A6lnBRHZBuwp$fT&?QO#LoA^b(pNX%sHmOK7Fatqz(b9`2H< zX&0pkRha;haao0X5^zO;%yae+Ysl|?i0IHWGkQQ(RZ7F9LDw)&jEGXS0U0O^^*Odm zqs`5e8s!J4gB9Z~Ef5avKk3X*6~*+Qawtt=$oYw)xt1o`a79sRMr>cvlz~VTO{H`x zR5HthQ1b0DEfZ>lt?E^bMhb9Y!UtjDo5G27Y^o4ey8O5XscgPe7AC-IBfYMDt0l)a z@0EqvH>4f4MOkG`=qFq;Li|Ii<1N&dt}pCw2+^@@PxJ=K}AgWglIvQrOOxhQ16IUR%oFmmS(c1Y_s2@mxM1 zXOJUDi(77{)HV~R1=A8LcQ3h9s|SV*OV?;r(B5^Z3AZ=c(2!TPNVt;*&AM@Lktvc! z2!2nkOQ#8Kg?ams2 z_!Kq4Fm;f9x>v~NHu>J{>?Nu)%vr%)RepW_?-&>RI%gs*o|%N`c2?O62N zeeBMc3mNx1+>F;BHP`E#yp{Vek@xlLnpVc#ZMqh*d`(90Knzt?44QDTYB?(r+Pts* zGBof^e}RSfm`DdAzTTm|#>f=(ZTP?rD#N7PrtB^}4Kx2$!V%CE55mpz*-0HYk& zaVC{O?m3U{xL-2yt9cb3CJPTorv^5zVEOz`^0co6Z4%~#ejOcEs4Rhp`O3VTJF_h- zHtu_n0GBd!F2Hu&jqJo4iW_QFUK#{235NEZDV)g)H{vu@>nC;6$C|SCbZpQEweklU zgy|_MN8IU+Rs${rTeUd?VFMcqyh-{jpRN^~_5cG1@<%HgR4omokx?}`!UEi&DtL1|9Dh#s zMaNl*;I|eEX~r`2nx&9yJZp(?Tv97jbes@l!gu(@Y;Z~15(i+kngY&HT#{ZhCXy~} znE5#Kdv$=s_OC$S9?vtv0@JlfPR^RV)NE{Zl0v0_ky9U9`bh!J@M9%g;ux=ACZUje znI1GLWd6*{;U{hy!!U0BuH>9zMH=eOv>Xo50sXW0M}^je*rT~;?YXsK z&0M?K)r8!yfqar$P-zI3<*M z(K0$^ROxB=!x}8m4t%bV23eUl)360TlTN&o0@UjwwiqLmoRsXFcENiB)@;Dk#uiZg z-u)Pyo!t)C8!&PMxAC*%KPdS*xIo^@@91?ofsIq(7*P0jdejrUU>)mdBo-<#01vF& z8OyBb#~d88MFxr`hMwhuvaqHtUa1LkgVn}{+V((^c}MDH+*KwcXAO1AZn~o$_{6Rx z^*nNkS9&PsHsQlTDm!3IT6t|-tqvoRYUcb*HZ+m&NT?b_Talo~fO`vESk6^(#AX!f z_7PyQX;~m>WaZau6zEZAj`3IE5F^Hm4LfCkhKH<7Z3!2B`d1q2TqX{b>Cnx?H3m=; z=FLI<30QKG5_sB9x%;KgWS#q zNwvDLW8D*q27TovI6CWLutN2$Fw4!kMY;;4<28nzrPE9v*=xc<(8YQq{G)%)x0~F6 zRM!HP27L2cu}p~6!HWPDH>JYW(cHu@r(G{(+WsooFqOE)=jLK)03a79LbQOg9c4U*T4fkhTWX=q&rgK`*s zqV}RR?~lpB$>w;)KWe$#ho5?RA4XpUS6bbA51B{2lk#QKw_NrNKRzEi3GdWEVAb>} z>X6Ym+?MEKYw}=u)aA${a}H-O4n9rqEF>F7)wv9n=I?MqKuogr zw1V;c8K{fd@6uVn$EcX?jVP?AMmWU!b`!f#+AAWfXWk`Nuw}=8Wx;`d`*Kc)8Lcx3XKM7I7ob$JSv zwoc`nM#Qq`|*K@wy4kyWn@abf&30U;TYx(F3J);9}nJ&*49|;FmtQ zx@axbiP33WBpF|#!yp^NP115ku|uVNXY%=c`n)jTPaOquo)}fw8eyk_dB3QjBdQ3G zsDY-V00m*@-T)o1z{z!(hJHLhOpQdg0dxD}hxJZlYif{PSX&?Tt2%mRb!wwP!PQL+ z&zQ&7u1a(8s@8G`lRBxCG+#aKrUL)lD3#SrdQ|9J;d)qGtM)O4(x@z}(Df?dJVOUpm zv91%QDEc#{27B6Ao5i$|?pg9KNlfu=S+z2C{-NflyPcH?1XK`rNNHK|Gk!hli1$}P z`#|N=2daFYH(yV)qtW%~7#d+wHFrphHy4Iu*W+MPRH?3Xx?ac1l?=eV*T)wdGC zTa*(wD9+csktJI#P@mYGJ{NcNX+p7aCPIfUlOZ4w>WU#R>Lkdk!GRGGce?PIH(HcX z>WLvRdIbJZLO4_B3Y|8yu)St9J)+KePGTCY+Vb#5j&g4aiIqDTHVvFa+I|?oZS-RM z$7EUH9wOs2<$gFY#WVq50tCz)+cq8(HMkO`Z!By%goCMm-ok zIyv>j<{v>70H86FJO7C=ScI8E35u^}N_z4=S}~UL#2QsBC!;KtD}=}MA1**$HH^`~ zNW3wj8bp0ys^X}rLQaQ~TeqbZLqR^#j@dn7flde1f|jtQ49rAg2|R0O?g~0IW+o$I zt`Hz>f|K@I{aHGW#~!#V{1di|^QKE_h5jRlNn3<~0;bT#}9zO*?O%s7m8 zk#n*lSi0uWdibLitDg9s&o-hqGQDw;4FYDnF^TzgCWSW3cZi4`XGk=IRxy+Th_U8y zz5eJKKmG-Meq2Apt9EMO5RyWWN1>1vS?o5GkcA=DxSO26+0$4Deh_Jzl_ zsiMPXSVhS1TA^SD;+8e>)*Mv+L*u6y_4bS)u{nSU>5vGSgg5Ru>mT3}%euQ~&)H{y z)XMVvzuA{8FXM}|>VLe>5b_+ORFl=V5yQzIaSrNUo`MH|vJkD!NMz^|Q$1A5cb3cT z3;qIj=Fp_04p2&nPFSv(sw&lZ0{4xe)#33^COn8=AJ$6hliAmx$d(VMeYnsqOqOJS zTd12wlfafH_oCt{3#DA+%&guq|M5%KJ8G^muw0XiJDl6oYd|H;=-{f#HI`z+mSX*I zs)DU{I?!5x4V&wgQLTJ~1wqZMR^dz|F@zefvRZX-^sMo;nK!;6D9LNqS^!i~6QiYMTXZmi^rGV{o0;2lPdlE zibzp))p>m7Ntbm zg?6P16tO?x``JPOg(GP(KKv*PRrwtk;s;=`Z+RNf97QHEiZB~#hRo&Q!&gme(`JuY zxM&NZLD@6=8g7|&u7bMDs*g)tm!iSg@oSVz`s^rrMjNokaWU%T%w;3}!fNK(L8?#mlL|I6DXr zKQTpP=IpA(_1ou)IY;Y#$VQBIym=J@iF0|rmW`66c_fY&!cGVqDWRCStyU{B{*QCg z3H4>--qEBKW0d@8s<6vztu{88^T&|o<^;pTNrnMJyZ2h{P0bxadAlwzlCnMExm zbhJsZad2zvjrxpGYZ|IMOaDzlVtcs{df7^j+Y~RPv^I72ac%N>t-4q0(=vPAp<*qw zJ&-=`Z~bX9*R1Sz@wA=)Yx`z&w8Bq1dA;iTAs=hc<_|<^B$H9-qNp~2FCv>dm$sDU z<;@08Hhn{-Zv9hxVN?(_PjQp?%}Sos_@Nsa)q$GX`0C;X255!RGCEuEqHp}vPEHdz z(QaXqDJ^YnT_K^egcK#Yv|S9M8t>>>o<-Rj71_!B$*f{hhU;;cdy!)Z4n3#Ruk(D1Lbj_9j%9!L>H zjk(y2MjM>YdsDni&J%4_HeMQ6-l!(DRgBl^<+goMU)9jI8}G(}a=+#?5tkU1&lum^ zV46G4u+^M)HCH`CuD$Mgu{=9zrUj$qxcL!B9}cMmCf2SQmQ=qSvAV~cDJKS?rPmyf zKc4`3!|%(6_La`|b?sU0^X`sUmpK(dM0Y#G)HyLDxf)e$=O4J(ZLx@X`FZ@qC0-L( zRCH~FCY(MDl+KCP9qEl3eZaP4g8ehK{`9t-xeP>vcd|)moH!o;f>SGkwMx|0Dw$=X=?O;luJfiq^UKRu8Vv9c11}9k zUo-13ul;KBs@Y_OLUV887L=KID=bXq><~1Ms(;H!3CJEm3}=RiyogNgjQC1YV{+@J zqiU=2SI0hoEp)%Xh&eix$UOPPa@1Tw4xhEhuXEoqv0Ob0=ww=D`?x+vyktKi z#-Ikv5;!rm|Ep-vGa3e|YZ=yvN)>$^gyqfGUK5mJ6CRoBCt zlcK7iIe#~0axr>xE`e=ItDE9lr^CZ{(Z<9T2v3#Qxerzi-T5%!#Ic0dl9)a+ zi_F3ql%yS0g^UaNfzSQz-M4u&GAZ*eC1Xr{j-`x&`4k<(;CUr!B1J~lUSe)eG{U~u z36w}xIN9(1q=$)i6vC`l-vLGBW=zj%; zIhqVE$QO0!vz5ltGwGtcH~%M@-xbiCSPP%Yhx~P@81ed%ru;sU1d>k+<(jM;hPE`p zP+F*sEc82MaI$=uem#44_pEab!0&#dLl_KHI~=%r2%TVugg})ww;Cd(l6jh5oqF^2 zo?z-!sT2!sj|8Ahs0!*J_&ufWG)+#58PLWcl+!+R*FX` zqu*X2-gsJV%)0wloGTDy_L5S2CN2s{R<`QIo$T3(v;vnK^l%z&$G-Zzbl7jaRq;)k zj7&Q9k`%3Ho{WQ|K3{9y8gWSeEPl8ZWI$Z5?iDmS`-80ftZM5kngGp1v>6_*j4Y+T zF@rzvQS8DH`xMl_L&@_J9uh0o^047`5v#~H|hU9f&-FMuJ%wr0bz?AhbIj`!J&_>U8V z7>Ihe@v^3&mV(72v5<0IQWXBM@NIQdOd@7bRwGaPy|BFWTn}1D*ZQsU^SJ2uFl#^dw0a=6J{$u<-wgp` zmgYndyuIYgzUKAfBVJ-#xtvF514#wfoFRK7I%aE6(1P*^-rgqTn=9}DUWFoQ8~CMV zYPJJLLbuD~%Y=UYvth&hmUFWH{L7;;=Z)Jp%KBaKbL6qVyG zj2aTIVHJPC54-Q?TKF{$HeDLK_D@Qq30l({8HF2fj~bp{oH6%y6H<$=ivg*Y2E1d8 zy->fPy@tTv#6*&J--^)vdGzz0V&}DeL`p$+VTC#To5iF#$E5+5bOTRqklc)&ssP-E zM0lyfgodK;^OdE|<@S-A1+%xAS{Ur_!Ib*T<_t76ao4cRmH@tLHxODXx-gQko08wu z_4HW?zXtV)4cRK=%cv#q2 zn=_lHw85q!>S0(A6-=rp%=3e-s(4UC7-jA*1CuICAub49<1c7BPA^%>|EX`xhEGV4 zOhXmx*HgRaLV@Rc+M{#x*PA~DGPy@OSOyrX^!3}vYp~SVgOl$5!V>xyXn0|boJ#)4qXooIGZoZaqj zLgklgj*4`g;ytMy#f%|-0_;D-aNi;#lA;B6M+$!%q#i|a()74BLG$}DnrWmihW7eh z6%qV4qyqHTZ?SK7EJvaqj1V85iXG9)_a1W){)Z0geQ?rA-OML}e}5Q)JKUz)>jfV% zfBoY3&AOMFV3#i0!0P;SJQTlh_IxtSg#4Z4MACIB#O=QF=^&mQdP$qFZX#{uuf|0+ zKL01)_YcPS_{FZZB^5})g>N~6-5I*GL_kjZ)7#_a{54BU-2M*iqYc}^&X3h=|3Jl# zyQ>+D=id)k@$K#KwL3Eyf`7W7c-9{;Yx_(By*lpBUpT+KJ!c8pG$^Z)*+J}SlswXB zkG7#ZK|F3Y_@YQ)7Cy8Zb}%gW!?kSkFe&?BKK-JeI&+;ymdAqAU}5PX`c0+p`R-ch z`|Qpq?69`rGW$yrFFcdSg~R+M?kN32RtKdwo!n%OwP*I~$1@78%kB-Eg)gI(QC)N5 zJ?Z*JK6b3_uzmXS-ak#s%eHqB=9b|N8^_D-K3q<(x(}`Gd*R}DkUf9q;`ojC6NM+k z{%Uw;-f$VUkyX)|X01aArmL4W+n0^3bM>mygFbFzeNEHEX~drY&lN%TmzS5jr5JMZ z&cx}3wf6OpnAZ<4$CYij>wh+CgN&7{&9n)Vl;}Xg^eTF0`u5J=q%aa)y}!4A9TN3l zXsp!JldbZJ7NCF(`X~uMd~9mn7vzKCrH9MF9AEI{r4QX_XrUCNw`w|qN#eAW9<%%O zG5f0$cPJQBf-%#C4#8riL^p{_)6boK@7*h!J{l=LA~h@obT*iB%%A(&%L$dq&=Z@X zaE&BhDMVN!;i(f!LL-BQ24o-pPiNN=m7UeTod+f{_vK$4U+B7s>I^W*Kl%{o*C_-T zdv<)#uZZx9QC?jrD|Mg(>en3=g+<`r>?+KBo4K3=6vt-GqwLX@y8ZgJ%G3FHVEJ-Jn{Ahu94f3_MPY(fJsUxnN3Zqu ztp4%rn4EOf+hVhapOPYFr74TLO8lT@e)XsFMR1|4EtNWRJ!HPaIxQizD+6{x2Psgo z*%4<>A66C9(ocrB3Exx}`={{C?&0sy4dIFgzI=pz(T!j^mTF^&j7lcQ+E!^6VetxVJa$_BZuW^K-(Kx!^l8SztrgLC9 zeIxAx5>{t35hj5VxIZR%v4sPru!L{;BD~K@cl~D2!%O+Lp}m*V<+}*NgwS*GfFe0i zgf>NU~En?yN@E)l#bsD{FqH+**t1HS**9yb41_eJ4&YsD-j3`%#&ymIO=Rzx7Xkb!lkC(WkK;Xu0mHhAf|YQ%~3VZ zmz*|n;yi6Q0NW3e_)(+zlM)RkbY;qaL{I6uXYn0svsE_%aAxO!5R`3`ZmehUQ1=3+Gu(X0z3pb~-g65Gmm$^C|TOa_<}QO`afChGu%l{_PwJ*r`UL3-y9$qq z?N2*J#NT(k-nf(!l%f0W0QE-CR@?KF(m4ptlX?cX!Szk*l}l|oiHpHBGBb`dD!5c+ zW%z-$>Q+GldhHs_g-y*65++SIKW*fadi=7}LtWIj-NJ~BSqrkmdB=DL8FPIyE~}hv z4%7anVb$o88e_D~a}2f86g2kfYzl6~7i{ui8u8KT@R(|IkJ=9hyz}%V-3?oD(!#ee+} zk06s;7`0-JP1JQ$Og1`Qc4(3O!NQwhc#)sZd*GgyxKSq}w+-K^5O%jIzR7s(fzW>k zas8r8EvY&2JHmT^vtb4gyH#BG>Vl@X((cy$2fnLBtG(H4!!^5S2EA*JX)ipl)|L?8 zJ~@My85l)3e(94BKV}CvGvVyT(a>Ge171-Mbo7bzl%ui_HG{b|CpC%RjQRyo_})G( z_}=n#T=1-|1uh35go(5TbJ-8LQDhI(rSbP@+QDgZnOD-mwGK{NoQnepXAVHNmggV0W9b;V5?ymMQc97&J2bTS4o7+Eby1Tl_@4ZCzebo@)p}iAwlnl zKXqr19S*Pbyx-xERE5r=JEF=v zx~RgI>tun`H_Po>8q5*nk3Cj*1N!I9Jh-^Af}!eT=QqbWB3DDUDvTvdMH$6n)g$*MqA+Bxcm( ztGm75ma$RhI5e5*=RH~}Z_$eu8}9=|L^-qllhUEvuT|m7@m1&OV5(H+M)Q#U%hNPv ze{54oZ)kCx)2v0pVP%dUSRS^Q5HV_nS3v(|FF#xJN1t%HD13SK#pjx1@VVS4qL`j}nUO{}w7 zuiWH>h4{d@{b6{sZ$PWTIn4IB6kiDcjhf4Qp_uMqVa@aGmu2+xzM|llyCyVsft>8( z{3nZflmNB&yA1Dfaxrsg<@9=be;b~d&hvUQ8vs@SW@Gvs^i=(V&ATWMd`L4{g(6Y|rGitR8G3FkX3jX6bkQB;zqjUqIf7?2hE=P3;7` z=C9K@pOc(ioGuXWvbMI{<1NoHel;9pr_e)mZj}17Y4qy?yQv(d)irxHT(M=H_jUSj zP2P^E+zi^5RC3A5?BPp7{%dIk5H-66@d-7TXu7qp6S$zcSd#Pma< z!>m@)w$PQ<9uBsn4|vPY5QBi{XM6F*NOI&wL+9AT+F^}pSARSnCyPA$$1YtJfE9@%NwS~D1j>V zno<;Y!I;#gLR>rwb91fjmH#76MF_`^bH_NnY;qhHZ?F?Fj@*hHyEMVKIn#7PWKhIs z3ioJ#F|^Xqd5C^1u@vI$VHHzEU-_%J*Z6kf1I2qIa}>%ceA0t`Aga5nH!02XGp8$E z|CNLZd>Oi*m$;ozRrm<|9$*70;b3P3acW()R7@N`gy0x+f82zkv@B8ey z+&h=ZoDM8;eAu{HN6HFwy{x&~nE=ROIQ5asm$)JiRSYqs?E~#l1^J<|(3~Q3UW3Zw zy)BHiU3&om3Zt~~;>&D|CmxI1d^@5lIAB}+d_z4(FmryF@kpEfwRK*VE2*ncE42Ry zHLvdmj2g!7BOe@7?L2_i)A zz4uO{_tCo`h~DeyBzlP+q76n5qxTwRh%h61ADtk2yFT~cZ+ZU%&ri=ed+&ADUM~U! zR66LMo#t1w)?-BS(x=EXwY7_ld0R4%87#L>uNzu(hi5fihf6%+VEz*`XPuQLexrDz z7DSpL<x z>t#ai)ZHLQGSTvqp5XxDE+x*zV!ZEru9^KUYl*vIWM5qG2GQ=N>0r%i-Pejk=8N59 z8$>yLMhCUZF;SV8Xz5$I(ne1whypll$E|e7z49%#=fc_To`67RmD9Da^Mis-J!iO* z6~&6QQ|LjJ-y0S2nks8!NH`@KJuw4$yTHjAIY&l*I4MOvmjM3(fHekc?eg*UyfzBJ zYtM)_O*|p8MaLO(VgcK@k>+$g|D$e6yM11>AzPZT-<^ zQ-WW1Jo0qiApIsYO+}sB^Xp{~DSEtippmokeA_BEAM7z9mF*oRIK&ZKj-KbVOM)J4 zR5jx7pV>`ozV$K;XO6kqLjV=V!7_b;I%Ae97w2+2G|4SA>fd zY*}FC^N&PNmwH}n68gUt!RM;l{V&)#zJ>j}(>p3-#1`>TrUGWhMzLFb5PWA|GI_*o zxcN!ymy58DQ^7y=KRE+72%{)Sg9@!{birF5&{;gsSp}fo0lx3cq^2W*=; zk?Ym)8Z|En9oz9wJHSF~tcF44cT;>jjDpd-52ZY;nlH_1YXfp|{W zvnA%$Z;o($SBkpYuT9hA+Jtq@HYiWxN0)UJk;>%JSBJ-0MZaO_LvI#+IQDM&3ppI<4T6i9 zS7*N5)>&JV#lXhKMxRAlv>`(6`}ODSbiMCBOI>O=WU49siZe;!@- zs!dX9<)FWuhUw!_s}i(?jry28a)@n_z0+5+Uq4Q#c&4f7LCJ> zrtGW1fB_82XBYakQE(H!fzNSthav9Wb7v$p$z&_*`QXH|cX)HOc$k^(Ub}UZ+I_XExUZ zd(#eXU5_FnjBC$KH3!RJ5XIZYh0J^j>r7vx!aUobZ5nc-oUtBuwtn6+7bm>c>h{J} zrUE1a`a%SLmnXqK(0gOVW;%T2*7yl2(F3(3?v5q}z6bC%wGiUF^o`Yg@#ra4^Cn7J z^p5MgzGpdToO5AjVrH*3f>WMms%F28t=x(0ds|Gfx(>eHzA!Xr1YJL&QF7~L79QUG}|xfu;P zae)y{FuW*VA(AssBJu)>9&azA$0sAfU3kmh236bfK(VF9glp?^EquWe`MRY_9pHW+ z4>F47K^;lg3Vqtjl5;s79XuDGxbqfIWF%Gkb5G?1q5NFxu4aa0Wr&gFV%bT9ZS)L-?UfWc8K?ba_g`LE-Zz+Eyur>CpL#+)X-rRcs$=o^Pco`dyaD zE_12xuntCmpR5`kaviMBt2kMQB*9s&2X?Xgcz#_kdGHmY7R|wF-SzQ9h61PL*UPObj8jgD74d**H;M80?3f<6^1?WhIbLIr}i2Vw5^mli;B$5JPmgm zIv_(A0>!UdznDw9BtLI<$voI0Mjhy2yu!DSJ)fUvS9?eJS^kwSkowq_?(dDKsF8P& zc~EG#Dq9)2ElBi47g8n}cot#vAr03wnMr6=6$k@D^)YBQoZ|4Zn?#L$@aXx_$uPBR zoEpHN*@hB1d{74%q$MOwIguY~A;U#`lz^Rb zj@a4!9L8v6Jbz6;e1eE5HgX%2M3RPbQknZL9ohn)N|hf)RsbKDJo-9B3FNjm(D^@w z`2K$i@g(eZtJiFEBkutkHtTRqm+<#(8|L&e`rf{`lfyDPptRw;_g7Cxc;bZkfSiFQ zd0pCCbieF8L&7)u^5atOGAd5=>W#VBYJ>44m5_kJ0}!%~ifRQV*r*`DxWgp6FV$*b zpZx6~rVl`X?Tz9AsSVoN)}CKgw^c+Vr_IYbllO|~&_On_4wElbl+vNMn-X;o(XQRv z)_8GWS;`=<0Kr{vC*zY+DL30K9{f$7a=@0KK4ZxC?w#4z@*wYea(*A$y?kXZ%(p&P z?>%Y~jK+r@kZUl&UN-oN0Cdaq_p!&r|7xYG^)niUVfjR}nN&^vCV62kn632qn;*zU zcomh_uX=1G-Ejcd*OQnfiS38}@5b%&&Fhzy3xjn>%OJPKLLXQQ#;<3Z+x~QmYJl$i z$NTx4(Zk)oLX0)ntnTuQoA}VssH_QfZ;3o*z=SvS{_y4$s~~pv@nY6H6v*Y{vRJ!) z!431^nGDt4PY-y4mUPvLuep}9j09oD$_L}XLr?qsI_4jpPdW>A+XK5SZB-3jj24ML z*V*gxte2a{W?0}{KVJNugMa(SQMlu6YaBYN>H$4;yx@(>fMv4|T5Lq3-JEiQeR*KI z;}$Hj{Co_Ud%g4fgK3JKD8TC6zB|TB1_UV!?xv{oLi6Xcj|h{OT)9Y@hkc2sWi6Qn z;W~09w0hLDTRE?*dWn5g!U;TCkC*sZ39_{KovX2aNn|u!98u1&^L_#w<#6L`YUGIt z$}fzVA~XVC>=>9XIvQFG)8W<13djY-Y$^FPS@}3z{BZ01-p~Hw>3;k@Yx`b24dNAU zSf4Bxpk!g_{Ty=gwKZ%rss=J;>coF!KPQYx2O`dM~ z8)eysdjKB~w#UsZ8%}LE9UGYy2S9zg4)DHnq_XIWx=!!(D)%9sE zW*XZcDrVfDXd%Wltr|qVqGb5Qs0+>cHP>6E`GwL`0l6@w+P9w-h8FRdnArB%+=moq zj`Dyk@u*+bhCH)cF9iD;-!ab?)4DE@+DR9DBOhW;Q|ujWv~1?r0|}s5d4>uKy^N>P~^&XVIwH-x+@|Nj~p#4;qZ4C9!%uLXGx1Ic;6P^cP zWO5raBh4@@)rPesr-E%~uY^COfxWyj{4P?&X2v3grbkvk^m0RMGIlCbAX@wW@c!`b zJwf*|z8C0mcm0#cTJ6jzkHTSYb4Td@Uubc|_(lLgU0=;2u`FH3S#HtXr|fAwhtRg` zcGOX-SvUEzXCJxaP)-wi2MXEA1D!)#R@xXH2|#Ce@k4p%kwNdTjxElrbz>oIYC)}M z(B;~JVne$ZZc^SiQ3nnEAg1**OY5U{2v>*GhmLO}gH`cIB6)T>W{C)kpf9*g@>69l zGb`VW-GR)}7}~;i?({fB17xh}=&EmDbTIk>ZEL>+-;%E=5n*b~c(4{&4Sqwyt{DnwiUvorNol0|yh;i6WF?AcR6j~RXRTNiDn=dI7VX7N`HQ_bo%~T@d$v2-n9kPG4`T`1Q-d$`JIYBmdLm;^*RdD@@J8mJi zOx;L#?9;;A6RN|KNt4u17W013l(xFq+->N|>+Tq%ShFp51CJ2^v6s9>s zuWE|-`8)h}&Zy*#KZFIg8O`wDhm-9_hXGOf3g#%UZ2)@P(<61YY1I)+&pm_nAmh1l#F=6DyB3LO0`cs9}=>=a;CU)Gw;E@_;7CbU1>uIH2-v~#Pi1UR_3O(*DnIGh1Z4%)KO^;f)cq`oN7xPwV+%W9;f<&(mT_(P?NMzc+NMI5^ys$`VL{bX_rHn=hL#`QVErNpRfL;v;~;WxaG_wg)#^D9FgkRxP4Lj*rWjUw;6yh+YDtbUL!<Iu!DR! z@inZQTo#ryJ@PlN@!v>QJ08J{-cwY&vF_6Dt)3s*G{+ZMY=Ha6$bl!ti-)=6Vc8Je zp1H1vh{&|YI_H&3v7q}k0T&}%YOme|N-pYdD=03QhjB44DIAE@<#Zp32 z%Cs%36DH8Y9zoKF;tuA@`bw;5-@>FPNrwO5g;Q_b>QJs zzO1G(5U!;;M-?2u|7XoC>iAIJ*>{x zuM?lEFOuh(BxerETt%JTAZH3`FM7Aj?C@NC^=2yxK5$uD39iFSHOKu&!w;sZp52G3S4>G6itG;+}Hh+dIo2@ z5M=d1(IBDX#}D~5b(!O7EO{4vn8>gghIilC4LE9s*#E9UnV&VfoAMB&sPDBgujNrQ z${W&B+8_-^)IYQic1#R5d5O|_S+bZswG>HfkTWw5o2qvfx7@~jWayZ&8Mk#`FP<-+ zOeb1b4jUUjT<|+qbQ?8JRl?5-4~$f+2kkOgR$YO!n7S$qb(6`Ug_8%9IhxK+g&I=$ z?csSLpvMcEuJL)hk>J@Jv1N_Jl;FV1U`v`=EJh0%L(cc6`c!~ zOkj1zc zau!c_me0OTWN(>tF2Vu!>BJ!8^usYFnK>5>+j1?7a_tp|9N1m@+rFb;cI_#4rX73O zpE^J^ax`y?h$CME%)7?iklb~`%a%gU=g7h=E;B`U5md3raJHS@YTi~99W|G${%RK+ z1P?eh8`$L-Iq;bfSBWo^zc4*rQ~+&azB(?h?OSc^O)&}5KQ)5K|22())0((Qjg z$}{`}8?V;^O&TOQ*}=+%F8_C9jaEGlo#+K8ZM7F>3fwBpG#n>-<7=WEnLL31xBZxP z6x(yu;!8|o5Er;3WU&m}MgULUGQgcef!8qdeX7Wn!}UFzzd#C61;FhcjVmo;cwp$W zs9WW01-w>&ZTDz#p7uSI@U<)aB>av^$U7W+=>*#vp)7HY8+SK@D$VqETQ>w$BYT)F z>K9lWGAs)L{1WC<997Z?*R{>V7S!0@@}@?kId0J)S)j-Tqp%JWW@~9pO&Ox4I>RqS z1=)^Z5~zqa(KLM&Hf&XV-`=PIBSgDC;cz9HQXV5lB~XEuoakMeZxD0tD?Mh^B2v@j zHb+Los^h`15(uy^@g4IEbaZ-uY(8GYKl|G(in%$JIL7Bo} zRwRA|BhE{{@9nO&%pRT%5CaJ0#%3B`JR|s-F-)~qk&rGdwi1vLubMKeXpd4cn_GTvDYB2KilNbr@gKOrLkz^xk?IYn8bzM0Wi|#W#Z)F_N)r z$D{aP9+o7Lg(MI4N%~Vm(8iMZg3QTD&cfhZ-@-h(GR#wI22&u8j1UupNtX|L8IJWP zmUsKsA0rDgw@)cisIC+wJ&lvL*&xZ;3%~NLUeqT*Gi{(p5rQg3+T`UIdszMtQ+S)B zqQOzUDn|2Kh*h4;&I8cZ0%!_QZ&4GW@16^OpDc4%dbD#F`~Kj3$KA~#c1rp&Gl$;_ z)gWV3cObz3bSvErbRiOYXCE@le5?#H9^utYgC2&@F-%>(Jv=!fnvUP*898(BX_G<7 zxzLi=khtW!W22Lvf%{=Eno@l$$`57=&DOZaZX~0Q?@tQ_1vTW|Rfh~&*~d;xC2xI0 zLqm5SqW!9|%K!!S_75*xnUz6_ zqTiUimy;a)%j>i6Ca+KlbD3XE@85r-V4>5mxuQ9I>KeLxx_e(3Do8QGe{Q&9JaPF3 z8{QzhF0VLCD3BhO@NE4Ch@5*6I4p8c9Ie6V+@NfCL32NXPY zU2F@_7HRI&J;*q4l47ksS-9Z+#x-Z|SALS7S2Nedhqw&e!-Br`BKs1CaWh zoA?MN*w#LadqL;5E;i}(d|G;rHjKYKg$$t0pB<_$^i^@`c(aNXt?bFTU)U!0lLE-S zsI@$63UrO|(%G|ZNleehw-gccgthSm1C5q8HbJLYT(QTfg*IP!mKo-x}A+$^__F$FgCj5e&=@b7L)Kfd!wo9 z)U;>&5q}WM_&8=y`$3?B=u{L5JE1^F$Dy*RzI|%AV(!W;GYnkmK-_k_iIlf#2yu&`rL_czH_kv93nqJ#-6-_yCO^%=do8Cz zUbvl%$!Zi0g1I3GK zhbioqRFxzA=EjvplRWDxDRxBZYN1x}dtcctBi9yz%*}Q3YUn?#y1TjMhf^$>Y6}&A z+Q;>t`@(17;;xz?)%-|M;hn_EJp%M^J^9HSbl2ec#wN^Gya{RGk(VXrBPG!D1-*;2 z;dbxp@ng%P0+dwJEmwTW?16rVQoeJkGpH?q{BKp&RZ<5igtO(&#N?co)HriN9+wBOD)Kyg&eqO?Pj$LJUxBt7JKS&y!dVr^7MUZd5Tb6z=tA}Ta&`Q`K@ArZ(hWE zKl97Fhw+1e0lWDsDBM4wJlM71k%Kwy5A`Q&EUPK$n;G35>vP0D_rS$#f`4Z%LRWS- z7;=e+%Ar1HV9O;`-ghO!k#pnnscnfnYcv4^u=pIfYs)iytn6wm5jtTlg#$K7c0 z(}&4tdTA_Z=eYj z#B!U@xLnVL8>o4IrUdJt?%#v)7p*LLfYJuVRofDk0L1}N{BT^)#f0m{6*i$aF~U|< zeLH2bH~X~$%}yD(x5uX-YIL@|Ot@Z2)MK29P@sebp`68r+WvW2ngV=#Mome9@zd`O zF&@$R?@P51#~;_*gY><1nOyu4MX$4`KMDNn=`k)UE;28uyW?(y<}HWjm~yqhy+bUx zisWpb1;b53?zbSqtFH7oB<_tF;yas7oex$5|3-1bvLI#K z=SNNjvdFU<{27~Un&;b5fNS*-C2 zp%R1?GFI#hPAyEpV(Ex7a2A0wrL7Xk>s?V9Te0RHLkG@&0tLD1tygGj&Iz}wqL9*oCuv_9wqnM(iUfQaYU0F z)I1!3(Rth`OSvmc>iFYrA2Mj0jO*q?7HE=20*-Ci%cMb$@8nBh&-CYAd#UyG67GT^BLpw^O&GX&b&j_6k0QPm83nTJal_a} ziJ(_wr~Q9<0kAZj8Hup*Np9no8$urrdgiwv^ZKo**lWL3$OrYKQ6h0P;*Zazg;IZF z6Q=zZ+~HJ*nKRbw3pLumYwD)TS{6KV`^BhSsEbR+?`Z3QncYgKq%+XawA-%va3jiT z0xt*qSQK#i($0lWrrvLJ4e~N?#B#Z3 zNUqQLkL2S}!f8K_cm5j)(~2*~4r^O}i!`s%W>hx**KE!0B6P{bL#)Ku&!#0)DXLrA zn_B$Y7FPw0;m0d~jHPeT3Z;vKomI3D+sQe|vY=G+gKaV+J?bZZS3JIy#-kAYL5=S= zya|)>B6A1JaF)gR_k%nRCr+@ImQ@Chs#Aiv3dBU3V4mZqW^o_25J*%;BID*|70*Lo z-j}@@c8>nw;3D76+4luI?SHuQa>1pj9BkHD&$~R zf`i$p0;mQG5)DdT-(KZlX9JOThbO3f9J@X0PXf^~8G8!+3S1Uoh_d=Ximk|| zO6cpy+g6l0#^a@7X8KwzMtUqiR@#IE|D~MK2mL&!#BdaJI(rntD04~@3}R;Na8w*I zxn)z9Pv#SCnj@UydW2;Aw#4AhjM{j*Kh`2uuV2z6d(92GQb_hLMNyy}YDWn0@yXJi zQiwBC5j0ZTV51MR+9UYfggIQCj-NdfAzcxX^75)Wgf`einYuNz?_3oURIP0E4E30A z)vNx8`}@CI5SCEt3&g?tV7Xzs#8ii2R)q7-zUAsCL-Sn{)X3g`7uR#$=n~&JV(4oW zRoPjUh08x&Wn5fUL9D3XPuk0;TnSWGL!fAmrZOlxz|D@D5s){?sR~iF`?x$ zPmisSejT$tnKVwm9g7+yv>`c}H{AKZ-7hw7v_SVIFy9$GZtIZ7yT3y)EM;we7yR!+ zjaG7~Y+r{J7XY=gu0z$}DZ;J+DARe z^Hr|V7MdrwQ&rYf`G;Gg*D9KbXrM}j&`AJ@)r;!!+oW(sQd(y5_Y1UiLJgc(71)KE zbSpyv$AfSO=aq-XfpE8k*WE?c$EYSfOA9_M4acG6C0Ql${|tpDd)N<)EsbZdV;F); zA`bk659@OZoTKyX&y@2s`t;3Q3_Q5ObnCnA+1$_W?0=On_lHxf13TYLc6i0Yz5$~~ zQzHJ^R%^twW9=z?fRnfAIWNp+ml+6Dtp;Dcw14ag{kxu$hC_4?dK6iicMatKwSl+W zF^m1tRh}*yn6Vn{eR_ZD`sTHwRB~ewic>zbLav6VP#n2gn!x|ty-#*SPhqga|UWOv>&(g%F(Oh|Ko!tG- zSq~~(T;%a_8zj!#Ty&CYjxyP(Zn#KoAs1m#1(t@*bS_fMrwmjZip+@m9>8hoD2!(e zI`#DgccM+%yrzqi6=>v0(L@xy&xi3D)@QHy{tDU=y8@M35lD;>a+?%K?it<5NdvYr z3L69`Cw`o}st)j5HpTOLjL;CEm3@G&Kjh1duJZF9W%!am^!0~z8v`{p9f+e<8f~q8 zYV@z42^xwWe7v&9A;i|I{Uc^Um}=;B=*%|sP2gwO*OI>4%mO8b3Lx1?Zw#ywA*2^+ z;8Oo}j5lhL8)-Xa?&s!~g)JgqDR-(bhnemiN0 zte1fZ0}*Nz(^zHD!T)I!K3fL$TtI5=5pBF-t2YFbJSP`bK%Opid2UK$T|!aMM#Le~ zS9pkBg@-Q5ak1S@E%Ml(z4nE{9Mg{E&ZdT#nbyvtfA=2plUI1|Zz-+dE&Dja5inyT<(b_vKtSeY$B z71(jt?FAaX{%AqvnsmyE0fzpK&vSeI?{RzX*)MqQ@N`?)zLWRRpPJRyd2#96xkTF_ zq1fMWJlSzE*K<=C{P&SS`f&{l#RY~lEgFN_(e+3>+=Fr3G`ytV^YH%ZgNRJ*JHf*@ zZ)+RyJqq4F%|Bfw_gpTX!~}ILbdqj|uhA-yGiF15a;y7@;!2#kGMB%2;2tXZ#a2!F zHf;d-)fo>~LaPoRsWQn^&<$kOR7lka8&fxT%PM_1S#Kpl^y?3>OB4Z`WG#!O`$8dY z_wMf7717YigyfDBuTP6G_YyB6rtG+E^w&M|_w&ANk4>0rL|(qm;-tps`!{H{9gB9g zYR)h&FkudGmNr!-jv8}gY;5M=Mwi|FaDY}9AcUOs*k7Ec@U8C?v#HqXV*Vy%5 z+I;oiku-%QPr~-EmB!BZa6&QP6sBgMI0?52M+tDBN?aylaDHN$7p(m{M~cmo{OOVh-ys$d*}><5u>Y9laL{;u0gDyy=)2~^cdMBz ze8%`0PRd-l51?$8_=teDLjBEMnGYnQ!oc>&Nth%^6iJRtX!qd?e=h|tr{6Oz1k!q3 zeWTV=#@qJ+VEZuU(&cFlI#?f|8(bVfmABSn06WeffgK@>E`?qlD_T6R<$lM7E+U(- z$G_*vg+L)38`lwq?iFe^=fy@kaxN%PLBP3oq8hSENMq(|`{K^FyFGVuq~YMVq*m&K zD0O)yca7QV^K5;R>{a>4bvXVUiVlH7grc_%I$NiF^W$H)bBC-?cX4BgPFOPEOSc6q zlplKr8Jx+l80)!Y>L&1Yo+E}lOlBp09(Zfhi$5Q>;_DU~m0LjC^2u(h%2`}u}C zIe}1wJ#%bjHSK`Y#~87e2RbZ3!i6uob^FTl#7ir3@}0qqwJArpgp~l{K};5{lHDR$ zI=(qo;Fhk~j~uQxSA&N%FXt5{kM~{_zo-D{e@>D$tDRpFsU`_?VQzq4R^`f4=8?|Puw&>z0W?0{81(uugGoVOI%;cAtf6k!Y4BfS5X z(=JlT4IxTdCeRFDv!oU=OdLM$n(n7l-J~yJi%L2GD+;C>Kpy}_I~P@%I_i#GMCL<3-iO~pQywD1W(4oU0dEOPf_Rb&Ri6zX3mqJWm!20yz$I+a6H$P@k2GV8Mm z=7~>3#mCF;{5`(Tq)6{0lZ^!L+iTb;t6=w!WCV@DQZd;y7z8FLMbRhwl4i6J4~zC> zh6Lb)lZNlcFTbMFows)UEayS zVrg`)@BL4qdzW`g4j%H602r|9@Ji;HRQP!hui;j;io0X^G5I+LtsYaAmW6CEX&S=? zbK|ckhJ|;HU*kvImng{nwV(OfKLUij0KbP^7ZZ|3u11bU!lpvN|Gr2!Ui}s5z?Ufr z3Gax?0<~)rxp8X+&wO~WOMU<|KBwoA)D1ZI9@iTR2s~t+JP^G=$gOmLa;Vbf!nR7i z-yLZd6le$=?B|a9dNrA7o%(Fw{ea}AVq@Gum|#TcL~H$x>xE)qE~S*xwC9k8`Hk~a zk&9Ftl#oQthf~m}w+BvY^dcuGU^TG$x-l7$Z_ue2y1Zla2X**k3ytLCZ~)K4`FL02 zQX~xBHEz9vwWvnnJ=?JfIQ`@(9sI^%^^uG5QW zNI2B&4O%4$eOuQu&%6yefYZz8yTQS&cR91|v-b?}Y~XT5B&yK=55L}=+~$SJn}}>j z3(uP73}Fo~!q3EtyTKAM6cc$SUjBMD@iyT?HE?;{3G7s*?_V5^vxkbHx%IiG7B9q9 zYwb1BMJ#JNYU5`zPSPF%k3^sajNUGxTgFC&44?}$&eUB_ zTtb?O{v6{P;`QYtx3?jRDcOQdN9shra$ZuN&ryOkIet04FslWOh_#4=Nks$6ZEI_U z>^2yG?3b_@yJl_rCs48IQ7|b9Wyxay{Gk3$ZWh+0ghNajCu`$c1I>>Yu7M-l!W_Ha zy1Fguvg44XLwxu?H_6Xle2xRcRlP)jLa|lC5_>iO_hiy_Iv4m-PQ;u_To5`?R8TG# zpT-a)`n5Vy2uaw_Pfoh{2@_`{Ja5fIa;Zhbr3SG-2{rH);1>o^re`?CMoQh4E&+cQ z){p=MH8}F!bkUFogj<{dIe7x1+IXo&OP&D9lgUy7m=H}3uyLOK4Y4!rIKKO8*;Jh_ zg(&l9>v#gOEQuq%v01F9N#pO}uf**?6Y{Ibg?O*R(fZ2N=sF^_P1Sz; zD7vB?ac>W^@lhGPiLTH1UHtK8t3K$YHQDa*`s~~4xxW;JiGTXCv*jk7^09RyB$@&~q?jTQ zg9;^`q|wat@8niMOMaHV(aT(&o85aG72ooc9}IuIAAj%1>1F-XI4eVY|7iV2>-V+0 zXvdZPgyU%J!GK>EOy2RGBRnEJzMq1ZEG9A{%4pd&}<3_xeVI-xFXA`w4U^n zZVpUsQtWvn^g7-0zKsO@OMb`)b`?u68Ixk-GN>HRuM@90naaotbVJx;T&nXG2}Va! zbP-0<*SEerM!Wi7B8;N@OusF`WiY$$nuMss) zZeqe3VA8NDSao~j`>I4;&GE_2Jnz+L3Sq7HTxdAl` zPE5&al{J;) zN27KeKaW_;nALhp%%87D@sPGiJmj(Bge-P=4wXGV8GirltU0g7vpMlUC;tD{BHSJy zADUhRYaE>gz_#mQf3p-)m2-5OC1bP2hd$OY>IlD?#5>@7JbZYq;YQ&9Put4hQ|LjW=K(P= zRk+-31m5JQZyLqzHt?kwEU6tLQ02+RMS4RH>7#yr7f9&rE6#2* z>P+}%#F7mo@2c4j6d@XCR{DrR7bEIztz2o8=k(2M-b%T1qk?{{7Wg%6}FlruetODzt?ei25V z)InYr%r}f}V=ozUHr=Ihh2B;%A@Sy2+f!RBWqaeR#SdDc*QX_Qoy$LMIpxzzbmFRo zz6knQL)4syK4d^%z3PCN^b#kZ3kGJT6THn>_?=K3*TB)U~bhy2+pOm2`%J3unXO%i`V|hPKQ1Haba}?>&Qb~bp z3G(haVR$3tz|s8d$rBMU86-)OZ7SBMujCqGH#Zt8N~K12_N<7wyjw|hyl8WAul?oB zf%v3^au_cfp!fZxBo&KXbo=+M%X7qN&y)`hvSF!AEHFPAsrhu9zPt8@sob~{)WWL?VC&1Lt{t6 z*T$lk(B^mABjV_clsv;Xf%BmIe(t&8HerDV`y^e@tyYWZr^Bj~;PcUV(7(-*FgiZm zpRc}!-IV2nj9GY;Wzl}n?Sn_UyYh|h7Xt5>AA?DBRZ+qSdoKPyx6&G!X3crC`sG8J zkUQI(eex55&As>#--8a>gymxj#UHnU5}5{xC`j5g#iSzDv zHEMu(#0t*mq0*`w$fLjobKFG}uA%F-6{Ne-WtmivZ&3I0C&SIOtW6L0HdmfW-IVSF zS3e2AQi|rP_1jDL+5TQ9sX>YZW2qHNGZWXTWHnMSp+d@qD6YbYJQUhNyE$afs#LzD zT6w&ypHv%0D~dzJ$1y_NNrz@B)z#&dKz>jIMc~NC(b~xCDd{-}b{m`L*G#r-Uhvo0 zWy|O6t5d-_iA4T*b5b$B^Zn!Vt<>Y^@3ZA@+_tuc(A~8-x{umkpM)90mYQhpLI)q+ z%{-5Ecjc{snvUWV<}|>>=o7MFeIX%{mYMngzS>3{l&zRp;#M_IFM~rWpVi~bz95nF z8hmHR-VRIY#ZMix(WHZU`puQB;LSKv3J+|RC=v%ZnrPHta7*9)Jw*r9A%3((NEcc94X_V$FCP-P{6HjNB_(1IzGsMa_fVT8Zqv8h zCauUAiwRX`{P@B}L&BT!L%|!ulQWs!?8{me^U+(n7pxd^5&du>LqSg;JkCjrWk!Ab zx>~=;oMTofC81K&3~R$dv}@tgie%^|j^uWP0E~#7Oi;b+E@huzQWlQkN){v z0Y$HXKx?>h3cjE_M+9J*`|aod>-eiH+lDd4LqN(O~rH`Gy&m5RFq4wf>GB*i^{;rs*)Rd9}~*Foyy!|`(^Azx@>=;SlTcC z@V#p}b&Wmy-wWZta+l}d6qlI^HEN2A2jW2dN`k8=r8=XPHJn#a+x z^=m)O>PQBPN-y$-PZhZ>4reR1Dk2_TsTEF<1$+=_+$>O7d!;b!^)`CZ;#E00d;fvvg@z{mOcZn-mKY_Q6QGxIgC%a~t> z#epxyFgITUI^XBx>82HER!*RR8?^1sfawg_73Qz*>Z)N&v($-j$|LJVIUGK(t=wy- z(Iq7kJNP^Rd0;5($R>*NxMB)+B8%EnWF60+0c@TP4?mzo4j`2hF%5_!4$+)1x zUdRpt0-7YRq95L6;$pdwNjwuMcUeUlsj`tBj#vy^F~rd}EL!gifTs-cTNQ3M$@tp` zMcqCwT+JeGCQx~dcIM_!_9(S0g6h~cNq0Z(V9#vr{}xQWIxd_<`IOd`!>9=C{PYT? z3k$k`;qlV^b2lyQ%9i~@%t91*K?-RqgMVls__6=FmvC&<+tFmdUR9kg%k$~zTy5=c zH6(`iW4oMe{}L&Wd%Dju9pgMXz`ymYK@)Z$8IF$VaDm7t7bj$ynl(=1XSGT~d!!7N
*bt#{&&vY*_oaFu)802cAojY&-;jOWPdx| zLK(S-mJ_~=Sz@Bt03A3d1`Unps))AvQ^{^bg@yqoiZK~Qz6a3@(It})Fan9|U!)G- zt7&0mo#*t=K1t;3j1~voRDDr{=OQkq`c?xzOP>4N)9%3f&iheV*PdK)O2ySvIJMiB z9}JK(I8Y0s^vGd;J5_C8+E%L@fo^X8x)x0?Dv2oudlGm&%}!r;MM(HYOlvX*Rk@%{ z+d;L5&Ox=Jf`*NXo)<8Z6`6vevhT_eViuHBa#h6_A&AfV$-^sY-W`jk5F6E?Gub4R z$=60R8nULH^c)&8xV_WmZ}StsUA?;I(IshrU?uuf5~>+fx|HmGe1=CI*X(Xm6}0}1 zUSPV+Hz~q9!mu9%L*y1(Z`ZjnypuK9mAts2#L;q86LK!Prh%7lPsYlsVLAqlDGy-2 zp2w-?#~R7U3CRbSr|hS7oMZ7@c2dT!Q=dHui|7QhIrx0C#H#G%u79-QE7v(~Gp_uq zJgJ*+1*dHLJD~O}G6y2*8M619)m0ooScOS+xdA}V*Qj`>)_fLk@k>aXk52CIw_~9P z%O`K{am&72%}p(cGQLk6_AofphE;fqI70)UHvD~z(xg!O|IPfsMn$*Bj1tTsdi(QJ zOS5rm5tr9Ovcw_dg*dl6>2;y9&vBVZ%qLU^Mchs;_6^4Oo^C!l=05EDywqu4&1#{{ zQC742e_gezh5G=)L>Wfd($?U-!-K2pUuc(6d8>|b6wb1Yg-OB&< zA1y#cKs99PHCJuhpDesU;>hzuXZtRLn%k~0Lu_b$Ico@ca(Nr%u{N>D!JH(_^_|X+ zIBjXpZ40GnVrPqJnq{YjjN!!LavS~vA;RgvP7RiR;S>wrSu3uhPaTA)i16!bK-%mo%Kp1kF)+uIS$hv%~vv!@0c1V^M+1%f}_w-Wg}0gFTm^ z&8pcsUfu*_huPOowpH_Pzr5R7qkGoPumJ4)R%Jr%H~$~&*}VKL%y`_Gq%r)oL$=H< zkpb_t=RY%STku(K0@vins*6WMv~Vq2DEk+PzAE-m?#m(p0@hKh z+Tv|!mc&sGvZ0!^`3LjN~)lN9rxXo>M{D3PBhnp>y>NT^D0b6uXDi>8vRO9xC! z@tipcoATYv6FNT46eQ5YuLAlYtLYu}wA=Nn`mcLqhH6O#CgfGbxLD`B%+lTQO4>Tb z=FU(Lbv(ZL>K16Prn;JI+&=WINuWMSuD5BJZi zu|<#*wt34FiP6K>(6J=@KmNb<740L0^d+>9Elt8t>#$>1`royY=#<(Q^T;8s)7d7; zZYpWrY-)$STfz!k?=Fn&W|DXL_6L-&t_x{_cBC3FK4)gZEjevZ2+{DBt8-aA(O+^1 z2*ryJ0EE&I9dD{7zWR#^m0wQ4R^ZSfuKDJsf{7d0vwdD^yE^i^#w`tF zqQ4k!>g{>o>iBPe@Ome7RYl;dVvP=s6$bfY&?3(YtJ`l$y^0Wgs#}hOFMYB1W&l>-DYA3{K>4l zxYIkXg=DbZXQORrTYN4+%> z3_HZ5hgOu1vE&^Z*8Yni6u#7~_$VmkDhnu;P*`VL)Ev(mB%~GJ<>rEYXT~;h6aP}p z(}zm3$Dl~8?QVZ!VW7(B`Lm-JmzqA7zHhCV5Xc@*7%d|IQe`2Ft(B}XlIz8V%={V$ z1092c5c6l21s`KG`r1%_9@l&g*Q8_sObX`p0)y0v?yB!A=t*0WNrJKPec4QS7dnL)uZu zT#dSWK0H@p7@K>){f2)2HTC*d)NM!f){U2B&mbVSD}ciLNdq1wyPgw2Bp=?EL-$K3 zwHVe=J!a=rHTMY(M{|Sm`Pku(1}CFRc~$D% z3kJK~(R=T>Xlr)f8gLbgG{sDLwg6TNi5V~(RQ_A$!u4u!7IL+7vu=Bb;h<36l(s?n z$C~@eXB1>P#_hP2*6&r9#qA#lKey8cULVd2oWPpof&(jpEiI89987ABoP*lf;MW?U z6h1!5aS!{Lh>XqI*a;;8g@}MS>OUHphL$Wk1^X+7(WMgECzXtSF?e#W zlSzDIw$_f+cB((sR<8UMox&<7{Xiq4@06pHm|egB`Qx0^SBA0n6~9lw{W+Z!P&eaU z>>2ps5zhRyZXP)XrOPBak)jK4>66tDpjVKS8xZF%rkE2b!_E$+cBKBRf&Vh;F-z9qVyU~1$QD1pPonW()cbt9TN*HtG=8$8r~vtjj7+kqbm&KRP9 zb0=<>WwZpYeYL=wNFuI=vwI3Uk+npaEvsypnSF2--by}h2JZ6zmBZ;n0W@7S)DHT#44HP5e7=A;S zoxPIwR*GfUxk;*FMUul%*E~|OB{gtwX2ee&6wd|TUEeHqh-kElQvkZ`=WG_b3smpd zJoN9-#nVS;Q%N$JSfX*zlw8fMi0EV(vOdNF$AQST>bIgRlboC)2mh?lGz%f?xn3kV z$vnJoWOKpBsN-}xnt~Un^McqAyGXxoMMyy!@+{aXe)DSwTK;H$M-%;6olpbOW{4Zi z*wjIO@!Y$6?yF?nqOr%T3tjd!fw;0s)-?hG&zcgdMRQLU!>fUs1^e; zd7siBg%2D}lz=ESI_vB=GU9&nOx8z(s8#ZbJHj+sjT_eM>kw_}*S+Q%AJz8%47=+J zOR0cmqWkJM*DIc|Bj*D_`=PVhQI~J8Qr|Rg#PxPo^lY@5nvn6a{N1FJze3pmusn)b zpG5<}C)KAFaYugDPU08-Y|O-ak3Y}iT)M3)d8mChpGmHas9&!hDtsd`uBNbANqDOf*AhQ(;(Z;ok zx&BfFpd;5ZSwkB2ThaXjF=12rlnSuAxbGm~UDa02tx386@Z3vLr1iNM2nUa57E*bu zW@0XruF3@JDKM{wr>_j|aKC-ojUzQRbi%1x`WeSWIOX{Q3D7&%FFpB|_A(_VnsqAp z#&GrF1O$7!I$EBh!X@kZ3{J)->H$R5zIGv+nW$2jASA%vfGb#H2%18OR8wJ(kPcX4^n08VKYprDl7&)`v^wGz}@Op~8SK_oLie?-EE1?h( z^)5pj8xOGzDzY&-XTwK+*9obqpuS`vI+oGHejxBA4cEy<5Z6BmTKdUEi4!{Iau z)|^*>ae!2K%sYlkbRrCfjY^4JV`CbktE;H)=S{w2wF((Jjdd%aAt;+=6P#R?DZd8d zUU^t!sYw{JTD*E-769Gdq0tEmZI1200P^U3jZo*~_*v?Zc9&ZdXTh+XRDteJF-p1~ zO+%&IEqlJpWm8x&_y2;46CbUmTPxwy`K#L*n|G_Ydlx&9{*}jFg6H`RR$czwE^wR7 z;hqJ}dz=jlZbq1LkEI4)PwCVck?nBeACzZCV8f*3fpV$ojlK<6lJkM5AlXRq;CfE5 z;T%D*XRt@A&>I9+j#^Lj5jHv9<@`Z^(PS)iN!+Le*fuLwk%PEX6W6jiK;GSKHNSl;6B#faZS0!iE=Td8?{bV8)?7lXMS3 z_uR3GQJhN6j(pN<2Zt97qij&e3)H^EBr7M>xXu1-TK6l3WPBWwCJq`84MO4YK_E6H zzpUNQyQR}7KL?25o6Fuj_hz75WB4I8J>wKW9pkLY2OCGpH_)wWT55#yc8@MH-sok` zz>1IW!4s7(*G&vGcde0i!KeF!SKY-XC#89fET)gwM+r|~K=U2f3;h>D>4T>g7B#ew zH+hd+EWzicE+z-sHRTtJ4SU;r-spqo#&W)yFsfS0s+8lWFcac5$_IOyIXi|S*_nnh zLmnL^X{Idpj;7CN7qP$iQmbE%m>ch8yc$Uzmc#cpFb91k48iRdb;EWmdi+z$qOd;u z)~Btd7=J%=4O(R+Fjr<@v63ykk(kv>{t1u1zSf~GXL`2r5m`$6l)N3b`ZP5eiGd!@ z(@UiB*LPMj;Aup2UmFb9wW)B$NSWd2*+L2U^HE~rm=v2s93_PI^6t@}T!*^r<6d;@ zz-XFi=jZ+U48xcfwFgJ1_5+%W%3pN=VVq6CX7}y&Z1CBZmEoc%+koR*g*i{GroBN$ zlzOQqUSN8)cOa`1rxV-7Nb=_lWlo!-WT8dc^lfc})3X~dgr~^@(1~hVcq?c)4yWCy z^OM0@eYLR#iNs-P@l3zlG-K5~(EW*ct_`Lw(UkEnKIde<@h z*R}*oj#D+Zk~We(tBDI(5@4}z0kwzCFQf1vH{SuQeQaDk!tQKbXdbVJOg{vTC1Law zREq6p2L_&=Bfgf>e!U&!UXeJ=N7msg|B9s^eF;d+d)!#>cyLRBHQz}-Cg)KD#+`(A zYpJ`RIp4OMm>!{JO&^E1MHa-0{ciMP`CjkHO!WxDw*gWlu zD#1sz${GLW8pys2!c9CayYy@W2!Mn;<)se_zL4y0EJ{1l6)eJ8Lm2$d(dF+BYCMQK z?9o&rpq3jV8+pZu6XsAMqg@_&3u#`t?97>Y=G`t?_F)N5QS@rE&&iXIcSEjF( zN9LSM+r>?FT7DN3V|6k8HDC}o z`poWZi_q1<*}?F8@58R(Z?#vt4nzQt<`G)oQ%Hk`J~5Vh*2<=XXX7`FOf8mrL=LhO`j1uJ3_%=aFr6kO8LuKtd%w8Cm% zYYPyb7Qtc$-oB%k`SFt}bYsrm`Y49Xf&RDRl1Atj(Q9-F)#NRrWgOSr1D{+)>_}*& zAECs41zOd`u8@r|6b1-u5A<1f_lft&)F-hUDK?kOs10Zc_#~6-yeYu0LG+1$bnr3U zRs(mouQ%`Z^pal<=AW&8JzM{%C*)P{2fURK@*(=kI9AW7!{-9V9^Y83>t4V$1rtCW zIh~r{fXgYo!@}jm3_NrvIyKbgI)KYR{HSi7)Aw75qf^c!H_eJ0mh%sQ>ZMi&-^;@> za6Xy=p>^ymti@k#kM~?)BDp{gnn8+9cL);+$W2@%M>H@zFkI1Nj{)!~!xFwdo}s zYkm-p&sNc=4EM+S9ilJi=kP51F}Fjycn{g87oxe|Qr-%Jg- z^KW88o9NDRGC;u`Ux&NpEZ_?R#LR}@lcBxt;Tc_+@YYNjM4^H=y?LF8R8bip77|a# z3`fzw=OF>u;2n%NG%ZHW13Losd4zCpTc~aMf}2fIQl`0V(Ejg&=D$}q_r_!`G}~1V zHp)k?50&w3$QMzl`Rlo;mv>LA2MJwX7n_pZ{Zjy`P>k&rULcW*@`13OfE(|bLY)#? zD2bwhL8QsQliBQxivvwk*gtbnm;fQewDB?6*vzz9kDku~M3v=(sj*kCagoHiO}XTZ15s`8pv=^4e55qUf9KO5|+(dX-VSU4jw zIS|;#oLIf{xxXVQa!|bU<&?fL*7YpehyTGeBF;`qUyE|qZ5A&u}DTK#3t|Yw3}n4^Kl=X5L_Q+f%z*TM23pthgKQT#UHepFGph*DK#v}^!8Dv_*3{~sC!{#%oWM^ zvvn~`3jDU+zd(Y|f_-Rfqv-}2~0SFW&}2s${Y zKfH0!`o&ArrI+*(+?pQIxs|=b*ZO*1#2zD#6`aL~-Y~HJ+hhHqd^=-;*%}eh#~1H9 zSZId(--giH6Mb>zBjxS0D;vO;nbv0L`$7EKirEEwlTd?$hHb=aUAO9-k!fnUkFIk4 z$6hV7CV@?4KZUsXUbDJ_^-FhqnyO3zOfruV+>bqPrD&W9EpUVj$>IR)ObSxiyLf*^ z>sa79jHMZ6Evf9#Fo7QWv%KK5!=XE?QumXWJULHy$6pTy5kMIP?8DliEH*mnIwRY7 zqo9smaq;i$0HrB4`X8tnZpxXKq0La#HS+NRUZWAajb3==V8KP_>`5^Lmu7Z znROZEw}h*B<7u?^uJ~oq*gk3FY|6Cr;T^r9fDTdGL)ZJ-y>UE#D!oq*&vS+!Tn5~c$$D;G!!F?`fXjXjw3W$$F$#R2-lS3p?nd|*eC5+QKs~=BS4r2e_NQd zyJa;mA?DP7cZiF%|0ajx!K#K-vfOwF2NMm9Z`(d}3`DP`c9nXwu!%<{(eFy*lEK72 zIaCvjo`I6{YFror1EG6oxB;pKQum{@FkEwVas9o$r~zM4YB^NHxz`8&hwJz+Xn3SK zdFR6E5~#$ExR7?Uor{xNHLsKH?=MAiOXQ*)`p-M@e95#CUrNb3%*1gB~epvKIjSAeUi3CSUHWAJ#HbTNO}mvL)c znDhRX7oAlI9BA=re$bmTOd+O709;tqqfsGJt6HCt>IxZt8Aa~M84+=z7}c(XXy197 ze^`|465GuS4iXchrNoT*&Y|@|WCE;Te0>^zK+S$?4f#9-5)c+0sm+Ibv9dNqlpYKy zsMtvt_3UZ1SQ0k;CJEtf&2z`4pH|MYY@x9O_WT$$yx6YA7YY>e-nVVSgoqi65``fD z-4P$v>RxLq?eiH*=Qb_BqqmL3j;(#ocehbh(~2R!)JXF{r+T&BFmdo_%1co(>sB_U zZLTN9fY~6;Yg=HyKgpo*qf;alib`UvY&irsTr7Zin~t@+KUo{RQ1|&ztz9qS_g+a8 zplWNoFut<#wAlZ+8hpLq-L=p`#~{w8CAUhI{t2CqVWM8o;ix9)64HGSS|z!Htfb;Z zZrYfx1bN*dZen+iJHMXBVekgZZk^fvTKRekp`J!z!nsn^v=&YiApO-W$9+XmQ}c^q zhvuFAWb@fM<%-xVbVFbtcO5=3c*x>6W zO2&ZSOBe-$w3sGpARcJ3(sc1$+f4egF=*Jl+QG|a<%eBx#;x3@wZ0+APhHuRM8_tt zu13FQhm(torgk`_gmIGf>r0RnA}fPy3$aeARPxJv2?bx@q(M^ZT5keP>=JRgw)G%C-rmKh>(@EU%EJ;vF{@em7H1 z0Y4RI@f5e_{7AZi0mKDPMFR?E%<**c<1O7{UP+ZQ$@W8H!zfK-^+zBc97#CQtK_#` zm(D)}023TiGw|bXe|O{;$T$juxTaCSArP8Ve`0XDk&ySnP6!rqCA-QLbn6+AljZHd zY-4UsXTw^II*0dwGKWXrByy#g0bYQ8%R*F(y1;@4|j2e6wt&yP~w;A5vDH^_=!V zg&vaWE7GWW(Eo7m$`SU`%mZb#hUTs%E!!B8%#nOIm}mGOEr20h0_|J2jW1WL4tuOs zbnOc>oZEv2RliiI6ESb-jdyTcu)b^0;={{)%V&C=+1gqMFC^l3=}S`P8ru=kRMJAO zk9ksb=3Iadowrh=itFGG3RaB|)2PZh%c>gX*?u@Zs=7xh#KkxK4y0e)6#c2t03rzJm7{8boiYWga$ocuJ-SXY@(SN;3f`M z>2dG@8%Iuh$JFdAO8s`5!Ecug1+bR#C&okN0-+w}UJ7cVFHKAL-(cO$%>XP4ko9VI zpE~K6zCJl0kq1s=a^FqIU)%(!-~F!EUee>k{KwFzD9oG42XK#et8U;BAhcBL{bP{U z^i9M3*}sKHGn@6QZLL2&R$__hg)P`ZD zvr4=Mb821HPGyf1;p!2BWol`niUy<^ZRk-+ufe8`PdvtfPq()s`q5J1T?Z4=1AYdR zNJxnvN{<{woEqVhc~=>0Ysdzwv@%wZc$|28lzc=!ZFDamR%^@gVC5IrF<%tbb6#HOzk<574c@HJRKFKAl&Atz=Z;L5duEAdmBl-3 z)MCk*nB$rr89hgtTskAy<0(#f5?K^~oM>qH8cN3?cU+DksAy8+?AYiEv(O@kndsq= zVsa*JcoWEJ&(Qb7T%d#87BRf5$NguQo{}ah`w+0MX_^KR-xre23-qeML)_?RS4K6R z4>StrIkJHbFeuhE>Enx0f7k(8u=-SI))bQ@XIK_7#S&lYGoOJ5HUHrJvgF6OAdYH=bF&{M<}^u;QwzG))*KgCo4ERS^iY z21kRbiZQ5TW(i8S^(oi%N(0*|Z7zRVCX0oHdJA*;nWN}og(7I+RtDpah1h>kHZFeKC`H=mL}a%yXwG3UFq_zMb)Bays6$N%sgAfAFj^NEAd zzQ>U%+B5&f)Dn|$ZbUO@=3h81*QX0b$+63L0P;oS z?&Y|Z!~69DNBnnue5%R05oPKo#(6@6<%kn7{N@#wE3~`EhJfrAd?Ir*cw?+;CAO6_ z0{{rMuM16-DUblz7K%-?hW~qi=6|5$#3viNP}Fg;eC#MBWJvgH>0HF4wC#I(v9T$q zT*i`Ny{13v3{c+${t8I5tn*R8*Q+EPpcPs z0s{=J)>PC}mv?B7VW%azTh#a4QWbcopJ@w@H+#>>#Q!Xs^|kB$mpT`9v=tp8+1Af0HVG*ekG5P|tl zs;_N(yMQCA*~@s%WTB`D!whHy>Txwvr3Y(#&r`c_4LJNO2kQ*M-D!>Z$LNTiuK-ES z$b1ht@jIatm-VHKC@&B|;vzrMBikyqS_6Efd<9rWJWaBR2?~3+l;E>5=>JSog+7Wk zTH_{0;~Rwkv#_@Yqw{Yya74%vzY0%whda8usEtqmIdl+85iBW|Cl`MA>g5uX#%HL1 zw@|>J!KoDy(gwIIl^T8&uexLom>SV84*jcq;hq!Ww=KUT?rGQY{_URjB~NLWg2+B{diRP!;&@Lr-vx$aVYrH z{bHV@Gqg>>Xf}pb2YJJvexSn2`qSDoU(?XdQD&LLdTB+?INgPDYTud=?(eAGv1sj} zO<48%72{7D_a8}#4xkFJsC-~HTW=2gDvw3!-+N4|t$_gq zSl53K4|CazxtunJov~#dupz)vyJ|hmHx4WA#k<-szNRMOP$mQMz6s66e3dt#l$O#} zwp=&g1$tTNZtJ>r=cy|%I{GVqun~oV5DX92gyz-@j)E$#u`-w?jJtIrJH>ZFcfS{a zFx@Xtf1im@t_`|R8^szng-R;Z8TbcD$bTRsPv=R6y&VsP*Npfhots#yqLB3@KMr$dt{oSfBR~{?z`9SDXt39^cZT_qmKJ0pY(}* z{0;9%-!k}*m&!R2x<^TjSz&BT*^=%1t53f7=iG>{i#Ob5^nEeXYhQiM$p3K zNu+RPs511<4Fas_oZ5zB(iATa7cDS*x*b2=ZTl)mp*gNvT% zXJ_{rIf9#S@}6K%+n-l%uQv~ll8v89@8HK+vCiqErffDz6|8d`R^0x^Exb#DF@ne1 zGW0m6@Yc}7`=@yn!27NTbA+5)tWy)i znq4_zKrNiuR{OG5iWwfb*k%D*eih3jp~u52EQ7Zgfh zym*cc!%sNqIG?AD$PDp|FZ*&EqR+OsJPZYw1176cE+Xa1{BxO9iU8Qh0xsxU{5_z3 z04rk3!+60v`}WxTIX>BRDd^^7jK6GPQ0__}+)^GbaRJln5|t((Wdk|o?BYPPJ(xkv z=oQ{$Ul=~n0JVNSvb}y0E|oql?D-zs;ZRUk*g6HHm@Q?>z-=7jQhA#lvZ zmlDD4PxC*E zm)uVm#}7snrpq*s8y9XG_n_mzwRj1|I*8s!r&6dFA}%2|;jOg~k?q1Gbcpr|5`6Ne zyp79>YAg6IR}x^9in1zre||#IHSthhD8P+JG5j54S7N@Gqu(%wy?VX3Vy!@s9i{E# zAHtqq->A%{`qq)j+a)LB&nY!*6QmhE?nZ%Y3hz8(B2POO((ixaeZ-@+xRcIv+9ITj z9$uPsQ}M^uB4$A4Nq{bNU*}4Si<#p-exd4mI7RN%ILAZoZGvxZj+TF>!Yqu_p3Y&C zUoXxSC)$>AxmQ0dt*ktUXX=9r4kT`_Kj=uWJ*UkS9+q|~3vo9ccVAJ3pI{S^O86wN zpZ-JPI}C{2QrWmZa8T7^$A1ZjV^ z?{6m)|L6QgtA#Z1kx8?%`oY+#XpksCoOb`+^q* ze1G-0Hn~O~`8CS{=CgVOWoJNj6;&PBqOqY*iUu3{M)MG5Rarf(KAM}>_egkxNX5i)KkY5xA+GT-4UwML=C&8`Mn z!|SfI_>1?;wcl#n`GCYa#rzufZ5u6mVK;Ke^sic8KV5`26DyUnd%;=`-;LZlt5I(B1y?a)~0bGfztU}sXqwGtc7gC-fLNe z=oJI1<#4BT^WOW~SyeSQ$>j8YGD^?7t)@j9eE5`$%?|vb80T346^2^xe;X_cQx6jK z{vu}{ZuWipb*@r2OoBy;(eg)F35RJ=7uOYjBn)(nhU*LuS(Q|&Nw~1eE16vrOuY!| z9V1m|`5i*h@4OP&^)pjb1T)4}~7km}vn>ywCE#+Mw*vJS12qpp~Q2;pYm=GmZ2 zgTP1e-1f;^T+4^UWj#H~m7w$9I|l>Fr~QH+J|0e|Ly8j+vYPevQdSZDrkjiXB%NFj zXU6dTDP02~FR!Rb|BqBpxg1`dg>TZgLax84Vq_aw(AGw+sY;aE_Zam`@$XbfetrWw z{ec2A(<5SZFnat#=yMNRUeGv`I@mqI)mIQ_o9Cim=ACY{D~{HMpPuz`r|=+!I@!|% z6DQLT?F+ceEqhwi)|cChcTdQt2i6chZo!ASz>~ARhyGK7pzA?`$9=?uO~2&BO2Bca zuRV>8DfxKj-cm1ts3|?2CNaIWwG1G~DEfvYnn#P6~4 zf}R)a;p@*f6&EpQ@u7oef~V6-Nioi&S;&z~&`#$JE2zO5dLWQ?j%>I`96yj7RNo=Y4OWA_FV-t|*v3^DP#L~`fPV^YZYBV9ehmV1*f>R_@W2{h z2s@pDz_W7Rg-m6HgVxDqACcHm=ozdw#Be&6T4o9FxnS@6y`%n`r-cC4f<~p-B0psn zG@BA|Q+r^5|E1%nHzpLUMh0J_&0aS%u?aa-D~3pE#ng+E8|+cNa-0}H|6{}}wzP~A z`HH+ju-QW8u~b{L}?I3_1X33!Ab<)57P;*BakPn)9u&03e~UF zK=kb9p~J$vo1cgGDHE?K@IIwOLjE_H(2N*HZL*2@nPo0|f3oh9EHGany{(mZi}+HO$1y&su#dw+>7Rfbc>Is746rK&41aA~#X29vwy4D2;3 z+vjKQRvG8?-bm~_h3x;-~BaEuS=UzsZ&m$?CO0t>-Cw~Sj`9E8rVYKC_Rb5iOp@sLj zaeY?td6En`o_?#GX0=oGAUs5apdk`MymgT%uP?8tpmnStREPy&NTV{@_My7VN3%1pD2N_;Kpqn-hG@tZ9lTw#*I)5A{09U)Jbd^F zu5T==8bPiNUQ8;?6x3JXIGI~j_%Fw|NFR_u5k1~C2MX>tTi<9Zb*Aq}JfBDjY-Ac0 z))-R&dR>p6V$0MOjhg?$LANts2;PKv(;x={L7QXQd4Y|q@q6ko4jw>-OIX6|?Xtz_{a|M(~XLh8)}TOlXIQ zG~aaxU781T&@vCt8`t4Oa0Y6}3XGOtr08eVsziX8XG0>VW#VF|B<^Pz*7|T87TPMh zl3tYk!6`Zj_>(bU^j$W&t}33>rlpQp{H4nL>XJId$fsv!T<>gGLO`}(ZJo1x{^8;D zr!xlRyVq|2!(;ICv2VY0__uNtFW&kpN;9jswT`n&1_gP;Xd3h@9;~i~v9)fdYR^f2 zec=tthHqy#-wpkIVT)JsxdK3eE7hw?EnKQ<=z%FB{i@wB=f&9VDkg0~O0pebs2OjZtXmn$iBiDDiCnxQc*dlzt_Aq&P28mS zVlVaACJz+3b?12CqBDEKsX6Vf1l5>ky5?QwPM!_T$0|}~0fYS{!>Wt*T9s0aH9s~h zR`8)PSn}>BDzMDg214MnQ``h!hodkvtdl5Jss_@~%do}~ts}zu0>9<$P0Pf74BPzT z<)&=L$!nNlaZ2bO8Vw+_Hu-*GAY`e=5NM(LK9zJG>B#xz(_23I6MtWTTo-Vzk^&Wl zCpSv9S`SBxNLp_Ei}llE&1y%N7-~!4`=G}&-IUc1$@>GzV63^tyKM*=Ox-z)u*UcN zVtMaz9lcV^_H?5}GB+*l&^7C7Py-ih5e*F=+3*KjxUVnxIdg#FwxT;A5V$~#E!nx8 zc}FbYyFqBKTV0%+mh^j)O754ie2Kzm0K0$)rcyaW`3SWXi|EgAWcRJ4>C?#wp23jw z*wj)*<}OF<-Kn!E)fkB74O6wbj3$wHMAv&d^9;iejSaF20|lH1!UJCCjDQwCKC1D7 zaO-hgo_>l$z`^bEXal(`kH=|(=a^x?XkTguxNap~ENwbtEz};5*4PxEE~RCxaI`U# zXWY04PI&n-sga>!sG8e@kF2(rI}gCswp$qcpA!tv<;Xi1ZEV^Mvxlv^-Dt=A%DXiv zYlwGQLQy?0&hL{Y3#>UqvMlfM@9cr8`1sJJPw-Vx`(Cri1s23fMXeW6YG@DPifr&Jth+8UlAxgMruLa)qwHm)1UYy8?}5=dayoe{xR50Uut*GF zen#mxbnL))V_fWFiz^vsteR;|S$GXk+4CKKX7hJOhSoHKe{8Mn18u1iqnv5C`QLz> zmU7GeKv26TxY{p$@Yg4ANpb4t&3}F1Kzp5l%*qcPc}``E+4Mg10d4+GR(5q&m!3JVRcqRh7}H zZNFJ@rm|w*3SmjT7Abws$tPRw$aUZY@I;Mz)hNG+3_aaPJo0mI#y1Ytn@P;d_JT2e zj=$P_FKi$U6GEOV=2^kWTQy)DaII1bsntKkc97~>Ez5H){}& zH?)ste3!DTAEues+}yv&y zzFcS_kCah1mrMr-4ytaP+^=Vao78ac=*iXR4lki|N3ped!CXWnKkmc9-CN!;-z;mz zb!YTbfr1!51$Q4Gk1(ugjphEZ5bRoFKrAlal3 zD=S*DfQ5xd9^^vUI(6q+4tcYYd=Ra#lnb{?M_$ZrOBhdHKqkFO&8yy@)~BRCOO)vt zZXadm<5c9KtlE1LL^)-;L|9TH!!z(#Le^5VAxo@(>Nt5h#rV(vpXowI06VBHVd zcasv!zXui%?$;~c>vdCtByVeIT*L*3#WJRp0>+7hmT(c61XdxZ^RcQGf+TmYlC(e% z0?Ze0S+k4$JrepI+1I+~;p%xVePQGWdFE6I^D4#kL26g);)~E05*RFUaXi=i7SI2fJ>(xhyC& zae2nR6@>o{5XC3ml3vti>b>ne6zrNqkq8PIXnJn(~^XLdL{k80? zG|e($@ao_QeEo2R6{24J!HrRetj0PpPjG?6r3I;F4Cn|5d_C0#vHE2|KM9^v*U^Lh%d4_1>3z*;5APZZrp2U>rD%ZQuvSv1r*T+nPW1wTv z+r&~r6%Ig|u*Rob!{Ceof^N(ajVw$60|8+8;JK@XnaOlDWV|*1LS4bH8%qw`C^vr) z&-j~2qwPMuE2^J|f|EH@h(`ed-`(c>Tl+wq*J04pBgJE{~4s>U{;qqRTAAUVfQSr$+W?>m%=|6O(* zU{)+CN0*TACB=#=^W5M#Ue)9s1Ge?to@1Xf^abrYWp6xYY9EAK^6~| z^&KqZ7Z04|cp#FuQ^nbKeM^ z@ZZ$JVTpiQA(03>U-Lp%d#sqp=&z`_q=WrMH>}=HFX|nx8{i4)Yn#4C$~iz{W#blr z2;*%ZVFf#`T<-wGq4U#}y6NK}qa`rHDd^&; z{wS*6<*F>y?bkb0qY5s>kXC!}>HPx1lh}yF?!Xao^c+ z3#mH`Df&@?c*b#~ImEMfKD!IeZH$#oKxr0|^u;%9o*s{uEB3~lv;iI671k}QFd?7q zn^;`X`y&1=eB?Ll;g|220eBixTjf|w@yV7OcsPG^qIb$P^Rv?7%4Jtk7+kc7?@^M< z?f8WvRru5)6?aileusvob}tUdl#H?R{|{GR71dVMZkyol?ohNXCAhmwai_Su6}RA4 zq|j2VXesXQ?gS|=!3o6z6!*&+YtJ>mDXBb=EBIErkd6jQ)IirZ zUTA-~mEd<6>`il}+jIe^hf+Z~ZK!rx7Hq)G;+q4S_KhP2XW=E^CEL42*!q{`*cx&! zaOu1k@)A9y=%*o6Gld4ZF>3S=+1s_rK~4-F#9cQJfEM?Au*C$ZDfembpx87~977Lf zk5Q)6HcN?dR~7hY0KB*$Q#!5~EBeOfACc!A@O8c$DS%DmKg)kJ`@r?3t%bXPLQ;g0 zNh+egHy(1DRO#>RJYru9J4VT)v#vUG8TkpjYq)GrM9a9Ud9RBVak#)gcW5yQ7Hn#! zG@6LBo~*p%;kcnX9(msp!4zMk=QGdn9yIkl9!4`P|7K+RhEFYv{^b7i`$oQ_?^O>t z{=w)*@!!733_SgaRFe@Lb!n#GE=ubT@LI!$x_HvuH&vDMnnzSP?(k;c95^dwxVr9* zf%=C`hH7np+cuY%?u$^KKaNoR3lVv~_-`$MVNa6Re8L~Bw}oMoNjsmKuv@@C@oE=5 zgx%oFQ3~)nG{Tt-One&5X30DWz<$o}KaZ~6?JxJFK9yfCI*_K{NBlbddoh*sW^)Tv zaRCH|-8mp#oT2&uv-&inSx#rebbSW<-PgP*4X(r|Ed3)WCjYnXQp8j|sLm5tCg$H% zcd)a~s)<$MTcO0(_mLTq%WoLMVln^~>#S)qibZp6@0H>Iytyj^qx}+Cq|hz;WCGIB ze6ZYFD5bKZKgA)CL8-N&r+XSzF5u;kpj*cxl=_Hdb0SpU5ne z(Gtk#MbhYo>@ah(*eDkCIlXVpdXOaFj7wJ!H52eG-P_8if~w)JtI7%+E5GP+5)DH>Med`z+P!tyY;rlYgY;m{)t=t&tV#JhjfDy4F~EC=z~vw+*LBfvhWmr? zq;Y#TkevnGbJ)yg4#TW_0zlMpTC^|-w9zH7fD1tsWl9?L)sX>C*0%88W2_eWaGr-%+*&^d9YEi3 zet^wgvn#00>tb1hCJmC_+28SA@W^GB>Cc@uW~-hnY)3~;Y2t77Y3URFqC;ug`9!1aUnuu6WhH4=6Uex{$$DjqBQ8~VzJ+iXitO%|4Yyhx$jZ1 zbzZMH>Ba2n{(zL5;I~F=L3$6WE~3zl)p#*A$nRxc3oeLv5c{HD3U~0m{TP;@A!AdG zwQKQSve3Ve81f9uvix%0d0f037Ky)+W47)DP|ewVS0r1EaR$~`$M%9Gk2mV(xgFi{I=;thYS`8A%?{29=sA+$KpGk|qlWhf%#U}It%jMA3BzkTMm3j9RFZxo)ohwlUgIPtnwhAL$TNv&-nq1|%Q9_YWTefk73 zE^mZEz92}NS(vgr0Ma7_879_5{YNb~I(@lTl5&HdodUf*zo#ZjM>o1-1u`4xr}`Wn zZ36HK876jo-_ptHD=7`IDXKcmr*OrH#(c{FO?~`DP%x*o4+SD|vMb-wzWfzesR42k zOQ%WtIf(r=taed%diaF^ewe@ryjzBxKJH@DT}RvhO)0BVXQNoCCuz;le}nb0ez7br z2a-T<{AS1Ohb5bVXKOTn>OR(=2QBP^6&2aG#G^kQvNHIP3C2F#m!-ItwZ)^iB9juk zwQ1RtEDnPfB3O4j)&w+kzdr1L5Sdnb6BUpg(;Bp2owF-o&K&aS^DoLdt*-RSW1eZhQzJrwOCOV}S|*Ahpyid{dk`I;DJ zRQ3R^tR(=uIlyl#VpKtmVFu24J)8W{c?pRaO%ap&qxsHzJZ@#~>$6#&m+_YaHJ@;J zaZ@||dJx2mbx+BW`+PP_38s5=^SPa^?lSn<(=Gy62Cm>h)k5yKhjTajY7u(7pAXyl zU6TSDs6QuNze)(kNt-EcK6pNjSFb-pR--+EG-s4kInKFGL}cv^l(T&&|1>uLKdbS2 za(p~nKzBB-t#G`gCPHn`J()_n;V^aaWRWv3O3;gqk^Cx?_#i9PcsLyNbnhzuX|LgA zV9B%_`f^*pn)`S;_*#ScZ;Rv9kH^u&AHot}GEEK`eJePAQS9r9 z3n(6KLqcM)wlUun@=^^B$=2GdFzf(wx#*DLQPEb7POa96qbZ8yw2iBqaJt!E#RBI>`B>RRe(Fabq8cJVgNrT?7Nj+Htl&K z8|Ja2uweMY9L>y%OINUHKmcnxnu^MRipt#0-A%~RMed{7fv5lVBXb}-+!XU_lv-vW zsfy`_&XDk{jEagnG574Rw__>>5gGb|vKHp3-v_m=OvbvOQ@exwMVSwhPLqM|KDB-h}@so%C!MC8yu46=M^VUs!TtV|Q__YRfO?{$`Y*i4TmY zlM-0i+?Pk4_s`OM!S`eUc_J~0q>~XLA*~_WL;GJNpv^1y_Rq}!wohgl$S}MLRg{ga z%V09<#Kg#<8GZe4!i)hn=CH04+l zsYniC^gIZ^RgJSzPzBQ3K*urB56el#vvaVbD}L7agf;0q{69jvQSZTih)VSjvmRnT z@z0YAJ~TC_z?6 zfR!z`va7hr%6q3S#Or>4DA}}k4~=)a5;s3Cz~&rgzOKd%7NtNz7O~YW&{SUuTz7N; zU_91h(M}{Q3!VSRmUli|KpSa$t6ynE&bkDw?q+|v>Arsro4fJ~y35krNzWCdgq}lh zhEKc1U4|ytLe8)3-=!cFw}DeSUp)YxmbX=E#nQ+iUP`%8gs5fgo;g6{{9lidntgr* z=?zRcCIuY#%v09=ko#Rd%k%YCM4#gAA-V9k{B}u$5u?D1Lo;MG)9Z(J56|xp8toN3 z>58{G`z0nLA4M@wlH%XED5Up<1<(CHlQ1&OFtpes2vSl<>1B{`yQxwu_yQI*(|=8j zQWlDR>w^vXguZWaVlEJ|p7Nd#@A9Wre8 ziun(FZYq_7co-?n<6TrYs2V<=)i@VW=G45*(+%qQvDd0sT2-{mESF4DSDZXmM@4Pr zg8fo^74nXBK~AjUMO5ngYx}>NaN@iN`?yhO14CY)&lSaWBFFDiFV*hlXd(uWwi9~Z z(Ft%!iC0OG+r2vpL(C?mg7kJ=U;Nq*Zn^~)H4bBVfqsSu$pA(yA=f|O4J|%+SImnt zuD^yjQ1zI5SW`8}{fQfgsJ86$EBDZc0508`h}@?~nifMXaMh<%fm190>6~!@&{oynO7l7+ zc_)mdic4#QrH3JhyZPv{2%?sO}rYf97S3fBl~$9f{1qdxIHk z;+d=IzJ{EQtL-mnNf*mZQqCqnFy!rB6P^Y9$JGdCJaph zIxc{S_(nemAD`&z?jU|EHprR}nr&G1lSzcle&^a0~4R)95qK>Lgt{QR^ zD6E+gxswWzKRUDq2pbzi8}RL%{frn(`CxWtEf1Q81eFMu*-8Qbb}@>GeUw{eKS%ld zWJk7(-2~YhqhX)E+=n-E5#GpqY|gK?Z>)97VCpe`pC>I0)8ZCbJ1GpsOmhBfw~f{^ zKV-(p?9;Po<6w!R4;#!}rVx_8l}FTyKrE>=kf}CYG^4v+iypMj+^6>hGA~^uNSqx) z3%-10G3}Zd^h>SdMVxUFe%#3wd-+j~lQfNQP?QbjkdPMiDfvk{XI)n2*t>Wrx!nk` za~T4IT3ZdkXeEtZf;nkbv{ugK6&yPp)`k@CiC)XR#vr{j-l-Ef=H&i&P z#6fF(XREz!vHB*w|3d*m=t*5+I}^gT7|&cXcd*{=&1D5wk){Atm4;7$rQt zkX#>tR;Ez9)Gul)X@T;S*-~KfGUAVa5r=~we-?2?aGRG;2^S%u84y2RknqjpP4KN1 zyFaS5WLey>Bp|5`n;SJd) z4O$lO*ULguwUC<&cj_)*p~*&nB@yqjve7hp`>g$b_xs}4T#Bm?Ay05$-e0C2f|ZCs z!~SPCsoKV6_d%<&x~@O4v-+o_|A_%U+&A_Zy$p8WZXX^jgz7$?+zeNDt*AvE8F%ru zzsN321CO-<$L1l|FI}|Wek(tWIqXKzEpw}Kc3-RG*f}}&Zq0SUsc>4=n|k2&acadx zJvq^;#)=b*S(qg7FU}GvmgtxhSf$4C`-z;H{-OeI^a_hp+kjmGRzZ8TCHH<*T|>3$ z$yPzw3G;V{G1kG2SM_h>0rjbOzZ;XA`fszk?Yd2##l#{(4=|z(6;c{tLIg#s9xP3` z$2<*^8RPPx$uc7X#D0-w%%&)U^i&3Pfao{U>wZ3hCXPZZE>-1+6-Up(HM+q)qLpKYVBsTBnas5nNi{ou&; z1*6F@hUxGBs+^?0IcUg+?FsODil_OD=zI(mzQjUN&=PX z{$f0A1V3ShK5~Ryve0%xlN{;4Vo(_N-|Al!CS3q0Pn)B}pUR^(T8<0|!Q2f-89yn> z%tEu;`?2S*$Nxd*ou_Q8DRPTPEAje+?^L~qchr$<+;}&-Io|1VOK3lbtUp2W{*}Mf zim5xIL`nd-CFpRA@92wPVDecm^>+lf+j|S4;(@KkN!RCH+@2;Ze}N5hZ+;@GPHfQ$ zr0;O*k0t)ddhRCaGF=%vsS-xc>&q>MkLL&bT!vf(-*4|-kGecQ)~{N#(ZX@)2tvs% zPexHSi`U;%O;rgK=lqcE3IDfc{!g{;P>vqUCdX!@JD|j1A66uUWI2h`V#)oR7kC82 z!SPv-c~j7esFFVZ#*9hRoLgT%&NI8NN_z~^9sV)P<_!-h5_#s{LLz0(VeGi19M`GH zP+#qRt$60W?gc#}%>6n44VG1hYBNAU(Ul!$s5dm=o%6Cpf~bW!=blJN3X5t~fMU7X zcsVBBU;@^t##S~J7uYBjkN|K0Ol(#hn=x-+2^KfF$o185cfV?rGj{!v?0#z4!vQ}N zylM&T7)Z=(I04M_NO^u|cgTWMvtPhfGnXcveoA#GS6d*&mX&Kk^mKAnH}mJ2V!fy2 zy2JZ#Lm#-8mYLYT=m8fLq^;ZNU~2^cK$F z?gR_@K@;`x@4m6pJ?STgjY?%86{R>%>4qE4<-I?TeCb_yPo*=@DNUMBNGAt4uCt57 zS`JSCg_#u-<-2{8@lcmp^LKkbBDz%?UmPG^Y(SKE-Lti+zwU+KYggJvr+9k5YOu)s z0-!!vq0(T3o2XzPdEDF~`stbP$_;B?PB8(C5VnxHsci_l&*WSDDXdy-n6{8vB&P9I zkbzur=kM0rfi+C`VnSXYWkm;xXd;;4-hGD!9+jhgRO|75KCeW99w)kW@1OKvr@mEt zyRvlc=4XE#TD}APl-gFWo>+$+HiZ!PdR=pw(Ezkf>F`O=&K)yx{R7O-Mq(_x%de^E9M^ld?e<7z$K_xBs7UWJpY0aTQO9=1TepobqE zE=Jr1jo{d@u$o}`#&6xX<<;HK@GWRQ^WKBctm)%+F#m5`@h2>BzsEH)Hg>oY_qRhk z-;3XUkF#oR<@6yT;x98V=fiu%04E-DED#TH;UKrJ>VkM*s*3w9K-H(QWRu3ONt5M) zcqzgLp@M(mb%YzliwGhEgf8tQCW&DDyMbGEG9{5Kj%@7fEvNuAYP;1M7qUy}nHaf2k zML?6+G;B>5)8+}$EXy}`ZObYTZYP&nf<)Eg;yR|uFxG~PSY*UgktB?SmDC(&Q1t|N zA2+#oDvnz){QGwRa}n=-I?(aSKC*XNY{yA_*hzUUIYm`Bx>S5WG9hDyeB394L$V;h zLCXzrPeMcF1lQcAJ6Yr0G>T(lcZqEg>#=d8FD)%^)xuaiBg505eq>uW>au^&$Y@zO z3`J6uA=%n@cmzy7v+a4A0U0J+W}uM<05GH$2ZbJG#g? zpLlR33?dQ>7?4n^JGjs^WXE=^smgOEO9{ACG+A?@QN_G1qZL+6`Q+l$uh#AB&3fWr z1>n->t|kqdELC<;{6LHRpA$eN*H@$W^E1oK=HUE?jZZgXyRYYGK3vmc+m@qwODuQg z)tcC0$ZzU6IRj>o(ty*H1$Tcsy`QZ;_7+X;@~s7y$UW|gZv@|~9j@v<WGIp)n`wKh)2 z%C78{tcN!0KS|vkZC!BQ*EbH%nJ3TlB47Nv4AVe5io)yK(=$=MlutM*}wb>zg0ui>`WC$?EJXG{{I5w9OTk!0@z|E8O|kvl%Js}aO79<@)^G*!cADaAiVR8dXO+4NGt9=w=Amiuez6OLnP_;G!M7b*E^xE&CuyRV~$~pN(1hHydQUu;T4YT zKhUYLA9OV)XjyPolN5Vkzva;Cmu3F0xclyZ7`5j-xa5*+vQ?GiX+saY&9^xvUwwB%d}np?z7ne6W*X zqu(s(`Oe6GzHR*e;zE7ai!`$GW{ocH!b)z?zv6p!ECtcK(fbEDJ7Hv{35~HI$#hLY zOVU@XP_l{14GN0i7AebFdOkM$ynZ)i0YpsREGSe3MC>uVfzXMJ#RGt988G63`~@(e zQXczv!f7o_4HChY)U1z15%b_CyEiCB~d;)JT2sAU5rMjOXc z@)+ISFhlnDRA&0Tps%a}+~B^g<99Xx8Yw4wkgQ!?)>U*EE3IZIvqO0&$RrMta4tsJ zYO9`Ee7ywPR2Qc0hexNhNct*5r=D3z()~P>l4gWWs;%&}Du*1gvq9;be;-_&+v?pc zY)Bkowt5tk-<=_gZ$f+Dy9tCtrXJJv2Y@lZK(0106GvmM42BefTxB={+y%(sUEkO? zfygicj%klZlkr9NhJ)O^Hm0up=c<%p0+Sc#RX@vu{(WA&8Uyp%{?1q4N&dHlI6W}H zbE)Wgf2K~Oik!qA@Nt^+#z2!mqb-oA4h69oEDIV8t9NxB{3x9ptZr(Zy077w4NP3&i55mp z7RE2^QdaQ@5jVa7?S7NBw2#%-8QX;z6K-rwDXu2q?C{~gxrvpjkhM=6R{gmKQOGVt zfDb}zKA5@|-|G~@ls`WvxfQIib64IN{s6CWLb zF-w9HNs?KT!d@bi`4MxDc21j1k!sqCOaZ|hB^G6S#*PQ$s?94mgB;gK-1anxM*#lS zkMa@GE}nNJF7Aul4Vq8)P0rMUVY?ysid#uqAi!g@p8PpWY!? z(Gc~%Rh7lZlOqnp6YkfLJVtiIjK~ZFjYE`bXd&r#T*L@ygCgnI`G|;LR}L4W3Kr6~ zP0E2(8CV5K?$MtoCce^9{c0Xn5hZi?TJicWpl^I7DwQV&D?=KyoC$Mh1tJw_issYc zNQ0WH(EG;>2y!CJ9e049}*nKTs z@XNvNsL5pu%LKAuJ$Ym*8YUoXDjzEW*t~*BLWLel2UmuEuE3v)`y+D%8C$vDu=na< zB9<&MID?@AMz(Rl^Ko4>!Ul&yvyz^UR2bX(ZIjYhL}4@C*nMrg+CvaRYXI`vp~xU1 zs2pBW)zuK`$Lk|6`R>9axi!*HgdrUfNUVNgh%Z%AVj>AFYU4PU{w9>9>!z*#EpMfV zE^a{rkyxb08JpJmvz*iINZ1|O)O$7uN9LLQ(@*U- zHGI$D$*I%nI@o518AJ5V<7LhaU?LC~M#Z4w$lUOZk|54oAOY=OM=nY&G}W)MEK0n*sr^Pklf1sonjblHQcJQ6gG0QQV>h z^FUT|B5iT?Sa6uK{ON`&1}zSX8JVs2`E^$XQMg(4EvadRk*)@dIJP%*miFa5YvVca zFog=olFh|8r2Z&CQ6_oB4pSWiNwb+h*kS%aDrbLzqJ<5C8W(nUG_VXIc0E<)Z*Nfg zw{35#{xN9HvpbHMtk@yd^Z1PpI#4DPDmmfCPyfLL!LzY%EpnGSUQ5FK=ixbM`{}Ee z=U61h@kWk7M7F%r&s0#p^1r)Oof$Dk7@_0)tr9*Ge<*=XuvRzKaPl=1^;Ts}eP#j*QzSAwll*d z)YYpz!7LG*^5fMZ&1ako3u1a@55f>&wegjZ@p4eWmBqF1H~<~hv7xN#{$nQ%p?wqSD}W=HgmxUTXVdR7*!KyO5=H%MX;+7zu6JJ~m3U3k3~{U*FB~0T3lA znOz(mA8nuAS)N?q0x#N5GW^ZR7=&nt$|J`pkFp%0^EiyGF$>^@E;iKt?Tes@}hX$SH^NufzYt!XMvzKHRp&o z6TQD+;H=dCc?DW1$NwPrUpKzEONZCW{?Fl6p63mpji+PVYVWDn+)Tfhi|$8Ip#22} z@e=T%Nyz!=YzCg$Un2iOfi6Ma6Q%3VUvc3< zWKjE^7*tWKwQP&ElGaOx;~fM+$Ko|$Ss$W*vyr5xXa6=a!v0cYeAfA9kaV%HqNH4` z4oE!N@&Lk$t{82u8#6G9fghGpwtN}>ckTTP41Ig`K8PW%pP<+NsNp zCocymz&7c1_A9jlmh`G`t$&RSlwx-MQ05Stp~3GhReA_VWaH*8Z1W_UdyA5|WnX4u z-i8INSeMc_F_KD#Y~h>WTLKv91=OicgRlHMm531P>9pyPzzD+w{Q^BVu9Rs_eZKl4s`J7TwK%zS?tF1kJlQplkdK~Bw%!Hr~4WjWAWN*P)d)s02W+Bks zca=RRZ+)eFq%#GK$J4w?4=6!gjxmHlMQmrOohR%Vzbpg5VR)OW$&oywpD2Z*qo~0S z$P{AX0fQ-iPIOLpr3pXp0+IgY6w7b8QC1~$%TOh9+5%(T0;n?l(v^m)*CCnbU;KgiFCK4rsV%*aq(`Sp@J^tbAWxXIO zqLH5a2{tl^05g`Q@=mh+yqs3{KORG$Mvy7$=*@Gf>8$!klQDWmqCQ74D}!w5Sspr; z&cWZOe+q#h)kKdm$cYjY^M+G6n*%jr5`cUm)@i@UsV{hVtY_IWS&J=@%|9_Ccam;I zo_H;Np$_w7#~YwJFr5rNzzx<@GSOS1$v6iFRL{La;EQBlJhU(1g74C13=!&%Pg&hh zZQ5_<7-QLX3jnBjx~KO7Uv|oE=}9ec28aM#=U41=qH_MNM_j+lc{|&$iuo^1O{yEs zs4A0Gq|C&8m&aIq=A;qu>r>0kOHmPjoC#J5aR2fgev~RqTjW5O3_5cb&F(Pu`*;2U zMATtl9Y(J7Sd>(l#Q|`rcbxe$eH#fCd6Ml#gWLTBB2BpR< z%)lLoDk9jybT3F{-ENNUD(_ER?2(3lWEDF*JWC5ga9Bf-rf3MsgpyW1=N9HAZXYK8 z`5-nNDBWWY!H#Uneq(C)i4n*fhr}wVlV5{$8`x|2opr)MGdf0JIiPL7qEaUzBIfoS zRWMrJldk|on}7safU!5RvWyr9MH#>s)m%u3;Ns1?>y>F%5b;ek-3?1u7uN zvTViaB5dK=%&zhdD?Ol{fC6s&yUG&BT#2;fKjAE&FDAA&uxByE`~JRKm3s*xISrK` zYbcJ~=G7C$Ve0L=uHr-M{L<_F24%D#4Q=|uAq!>6;YSnoP2@VYvJhQTR3T7dA|~6P z5*)Xd)g zq|;Y6j!oDk#PjC)DP3OA2cJd_N5_we@NqTi0ZuJ_=)L-~Szo?CwJ>Y9r_K5mGw9)j zdQB^if2xVVpg0V0G?KE2L%DJw@Z8*e6Br^?DZE14sdj(va(`aVqA*F&{c?@d<8vzZ zDOdHWOd3$FX=aL<6gn{`bmhV<)%*79-=o0`q`sYWLyN|}*t_1GinC&0X6dTl*GF$U z?ooaf7%jZQHDs}zOkjO|bd)aXs!9l^{%akFN1*exIwRq$+eCD@Cb9d=4hdi97f7bE z(-Bd1FfHsLi;Z7Fhls*uG3nyR>_|dX@;*nJ$Fs*}Y`P0UfqvhgVNf@+fAyrXi)3;e zRgZ4}Z1ujN9rQ+|1W~cuI^pi8_-Yy3FlT3NQiA*gvwos4TJ|-}d5I3`OcyaK1NK_6 zOgKrG#GUqg8|In$a)h_1vYr@6Z~t=6sq8OQdRnIgA90tK^VXT%H=lWeeR37iBo5EG zikyEKHl0A(LP99~=yf&z`n0|KJq?(s{hO57t9A0Ia%!u=SLW_gBp+en*FYA$53Qw67ys9c4s-u5@F8Obh#bFjPHior?B9>>R5hUOf zEiA)m`yDmf=)$N`Z<5L(rv`0mc}rDFdDl%9jW6dn97#=4f-!CevIXN-XZXGFwy|Le z5g@y*2J|5kjK(w4c@!*Y;qeSzkw9q?p;8R++gStocn(CBui2`@h~r5sy=)tQ2WGyB zPq5NK$X5UC0%1tWFe9I6;G7-lJ5d8?ptSW59|Iy-<=&=}%tHANc1<2H_9+=OZ!B>l zIJxw0X02|bAE&wYgS#X%>@u;yFy;THGV$MHw*nHCr%7io>l&SR1&+OJ-{cI)?CcKj zeD<0b^_%Iw{}dg*9x}a}w6p4pVaCqD4=Cp?X5SDw)%>FNHt6O)_$gFPOEs>4rjFcy z$c|e}S)$2Y4CREJrnTFfU{*ZgAC(L+miv;jqw?!qWL9 z0Mp>7JXbPSqdO!xY5PF83-&L|F)#EnTDj!JNH~sZQ2M#Y^@>BrtedI;B$Oe@RNG*jgNPuZn&#=C-KRmX!TAyCZ;&F5};pVVKa}7Mo(v^>FEx? zt>15NPO**;1XIv85TKI1*((h3PxF-^hu<02z|kVuwS?{4iEdi6OZ<%>gs2b^ zKl;u6=%%yzmx2$XX57&Za>Ye@M-!k)@qNL3Pl0pV&rg9VJb_@-O3HXrFt0dAnA*~U zCho@4LI<{AgOA_Ramd08uXM9K>a2GV{Fh$id`ff2_1G^sjqoaR?8;>{hb^fd?PH=DdvTtQSKKpt3k=M5D` zpj!3HjMHND0sk_<+5P>6-*b0?xhoaa(vm2Xuk z8xYP$c^Nj_4Jdt~)TUvPRlF_-Y6f=LuulG=_q zPg7Rp^9HL>4EPviPBx)iC7)IKgvhKe7Omrp-UC7nukql)IZU9%3*m2cGU~|qgRoTw zE+1}FG>VMS464Z_&zfl-_t)|0JXK^kP<+r?5j)C- zZhj_fUOm6sIO*+BBFkhc2fVJyI`}LkmFDa;*zX4R_c#NvxEgNcSmJI#@tZrY5 zJK9a`OZcm+{_z0+>YnrHFK}i5Yg3~KL?s6FKpeaju$E_R-SSqYTbJbk(Ymiq?NUqI z@UQH4)xK=Lg-g6>=w?V@r?ly!b)%|_j~_S|9RUVkBj^+)bSar3hX8Be^0l$Ucd@Ov zhK$m--t+)FCiiK4370Quph|}ipEPVu<&hCI&`P|5$IOX)R|RAdfdjmBJcc~P(xFIk zUsp8+vyj8xbUb-UNdPclk2VH95(5ymXKUGzjklszMndW=EuE(TuflK-tQp#)9Xh?R zsl{gwn181W4jH$%o$iBe_t}Z2q?m)9iR|`RCWguR-KsQ9#ADS*@Mub!6ioc4R=t=;FVQ4;&Ga zcZA(bemOhjHW2KaczZ|A#GiMItXNkPG62q?;MvX=14N!R`8zHz&qv9CGT9qiMMxGu4};nHLCP+-eoQIS$IUzPMD1mn~HlTp4h zE!F7jhD&J$dw8MHkI}`C+p>XQpWJH9YhErw{5t)6N604fmS~+=I{XJi&P+QEtM79k zWvX&V1zuqv1uk=}TJzquGx=%YL^Id6_WKRWv~MFKW+4P93Yt;s=JW4zg8pKg?kH=cNP@j6@QeZp01A;41tO4O^ zxgiG0WK!?kg7w{2OoM$sp##Z?-T^Nkjh@RnaHmWwTyO4dDCe{75>FvE7zmsb@40S{ z^y3P37nQ(3HV>n&mF<^#NNub zRyX!U2}zi>8**N1C|(8>5gg~>ATxl3dhu#;QfA}s1cj%9Bus#na-kFIbu{rfHB&DB zWb05;dMb>l08{JNL8qs|49Vjah#B@ixpohDvXz+09bO-)G_`4u4k*if-`a=D(3DR{E^mW5f#Zh@zdx(7r#r9%;@qbrH_+F!9)=vh}9PrLwuv|%%;w!nECM%aUF-V zxc-J$=Wg%$gH{9z8oJ;sHJ)PS1stUp#!9t>7(gP4iBe@X>{w2mLIh(D!^f(; z_*gR4h66kG4q=Bc`d1YOu?i8JjCF3rEM9~jix@~(7-Uq8=3OjkjC8JiZ>Oo0cca6~ zBmfac-=<=yOQcl3Ac=iMX7>pAVCp0C3#T(~Vp)Qrc<|R!@b?Hx5CH@I?b=v(O9L9f zOKMP*z)Nux4_!>_?;Q~#ooMDpg_q4$Oc#%hy|R*pqCy$}mtTi)y!>ou6y>T{1XV%+ z3-Fr6`!GvE8oty@K!d_U@O6+py1q7EA_h?4n}K;2AMoHY(UCxZZr?>7gD<fo}1|h#Cu^lE*LzI{7 zVQ-KXy@%ZgxtR_Ch&{F7bekD}#8hzc%(Voo_Glc#)0!)TQ3Bez)k_d?ynRl_$ImtndiFl8_YE^t}f(Kid z<^nu+k)4yN?~KG(aIk8xq5!+2`Ev-d07Hlhg7qzEMF|jFSsR3$xxD?QhwMx;i0LzQ znDN_uecGIlkpc>Uq8?e*d2a_Vpa6A~F>vRLkKQcB_Y~@1-WD+{rQ6v)oVB__lHp6RqO;9|BDAB?_A6ftj5wn9Q z>Vl>n(>{HOry%Jr{*eDSYaTx;P=qL5wHk0?hiaRJ>iGO!=n#b!I?H4-W>Te5?!r9c z^tDyEXMK_in4XdoIZP&wL5r_P@9TXSKs&d1uGEjMav=wRYZuFl@M)f2V5-KErW6AY zFP%>VLpxoFxj;gN(K%2On|{ul9dGOp*Sw}_)%B(eFA zyk`kl*xS-;x7L*vT-1)Mb3$?uu7pzw+OG2mGYQ9!X0kWJR2S+pfrdZC_pMTsh1he- zF(jZ{`iZq(ZS4{(cmK%G^ZbU_wj2~LSaLhfkfhu!&JTMC z0T+lX@iOe+9rx?4+&ma$==r1HcwM+KD0(_Ey!K0he%5`I^?A3`@hGGdPv_%#f?P+y2KI-9sX;b={mmNmKiD*5jGuGLpBm(dVcs-qYUD7M0ffH zP}K)NJ3M?|RhBu_^G0T9^Mi4YnLaJcmvpu$no+@zlfB54QM`|q2~w2t@xU9tZT=7R zxHZOo)0^=WTs`(9O$0)TIH>+)z7+dclgu+8=!fRGjTIwGX@+Jccu7#{Z_%=f2MD7I znLpH8+9*vdJ76#UsAEu>)sF9#M5}EamROQR04|ow;Tnq2UOwpqs8o}GIt%A49>AIQ z4~!FU>@Tcza0%b`O21er15spr6k`$m*#Cs4S5{x-NtrVmqPsSqgH*fk3Q5b!qS;=C zP2s43u7M+g^<7hCHwJ^6!)J!r_|SoPL8+uBMiN(8zWn#)`BZ}FSo zQiEARcn-V(oB4^p>;#ABFLDSl6)n1fk^KV?6bp3SGPFoMtoe$MqUH1v4)f}kyLf%a z!syNn3*_80#ELrSlry8!$z&!9ALU zhA@vfuuMQPz)LGNEF!y%S$fZKn+bjEGM@(k-ZREd0pDyg~rV zoV1hRskXl$AYvJWl0fB3Nfea(7%g3l5H1Zt(a2FLPo2 z&`QraZ&De`fSI2w&!?%?d^R3&@_MEMSaj5R;^N18l+P8`9~%@#QtA%Qrp zg6qr6nhgdOfW{VM5|;3qnLa+{=}=VO?b%QkN*g;j^{BW%#kLn}we1!@+hoYdg@rLT zxx$)^@jW8#^(B+}XxI=IEQg^fo`$oG8*_<`^Y9GUqtRqQl1XZ8nW6 z8z5goWUtVc5?w-TR}2(`L=1o~=N%6EKcb%}&14k65jFZ2el*945LdEChZnI1ashS= zM|oLe|J@&y;jk+Y7K*11O((S>7ES9ck__7x-lw{W37@aN_oPPDY4_~URfhi<{qO1X z(_70$vH+ytRzCEY6tm)WnnLVhGm5PEyT8W~Jjn&Y+VX0g*Hcm$A3Qs@-|Gks;H!|Fk>SNy zk(e&<_!QD<)(nqISR{P!`N5jd>(B=~a?9$6+gGJxtQ=>+sqfpRH6GF$>8Y%aTIvJ+ zzp}V@!KhQqp78ROW1X1{>H2Tz>b4T4=>bs%Jj-y!O4*q?o0M7=qG`qKJ2`TT!T(}J z%8VGj$x!GQ-cEb-@PzS+dnaKp%%#pc6jk-!2NUPFpXZft32$1fV07rlsVA|0)f|#* zy}YU-xTAH^;`Z%C#XkYk>_L-sw@$_$4c|+`BD9fAvjWq7!5K?K%SnqKf3p00MzF5% z?7;of-J4F0;uB%M*93Q6wJQ%`DYl9aoY7zrdt&i&lK~S9SaZMLIkMt5WPlH+(Y#Ve zb20k(o+rmgtZ2U5YC8kL>8Tr>@*wxGYjqL_>GC6^nMaT=>D4QR?6NWd0mumwN_sJU z2Dehjq^UkhW@vhYa)>7ApUPX?h3dJR<;wZ$4vos&^(%wfg)A8%0myb&XMM*fhtwKT z#vJ-gp?{Ua%wM~^I>69jjiD3Sw+(_LzUJc8ZSSD=KU#lPDM2*q)PN(o50G)kLm+P{ z(mjy3m;9=fNN=pC{NeYw2El`N5pxza8S?&c$vj_cSxgB~3Un)qbxw$p&9}533;ZZ690UA!(>7SSt_P-yz$ZBbu{Qa8*s2PRM z9NO>hkS=f!GmM#=1hrdwSR9Ja+PIZ0w$)-L@HvQe`T4i4?JYe$Z=_-j*M8Q+ouu-~ ze*AM`U(NKRz5Jmxr^UEBksF6Fp+A7vD+kXCEBSm)m`B1ib`u#B#)(&RtoSFaC{?RhgN+Qh9(mE z#TN15RA#L8tVjO&iR=rF`o=uG0EykEc7*67O5F-AS|G&wL_?KD7nmoFD*2VuW%l;a zi~B2c1VbQZ`9$#e`nL$=aS?-1b&IW^MAV2b1cbV3M(U|(R88t$sz*3NmUw$ZtS;}% zvL1HbeI1Rg{nRIZpi&FPWm96gU3I@)LX&oR?C)^g%eA*-`R>!z6%{~J`HjQd_RsO0 z=qKez(NZCpOjv4*qL0oG#XbM2}Cs*KZ=8K0S&+E&>Ef!f+O zxuBt?Cu*6$tDn9EIX3V7tjbNKhpuGaPQAD?f`3@@O_U>%c;shjdMI{Dt_ylOg1)<7 zq*e=n?>1l?XFn6$+l3YS*u*j}vT_9bd6HqF#rnl)hJ`l3>R2z5;cYU{ndYqic%f(0>SdL0h{&OBkO?L#)tF)RGVo8G{8^J=AjI)?N)4?fG-${ zm?`%DmU)}wC*_4#H%EZcUnF#N>{wiF{M}-p>4I=qx6W0=%H>}R{4%2a^40dJ#2ZQr zr{1HYd=AP>v5cSO<=cJ(%uxS7R~$i&%B!uHcCYanQJbgM?nXnX zsjIea6ykl<-U^1Xfd^A0qD%Pb(eGUQo(;hkmgbUlfQ1MZgz|L3TQ z>S<$tzT>$A@2Jj2W&R9~o6H6`rv^zCj}yRZPSX_P}gGXZ1NsKfMja`Fo^crci9}g5u^|SZqy>_vt|SVJh~OoA zouzoi2faXzyF`_Faab`CBb@ji%NR^u6L9-*L6SCPAM9r{Ln`#%u^x!HlKX8s^g-Go znr;w1!~{k;*znQOh+++=FP8#Na}4fb=@RRQh&esVC8w|nt-Kka-U{!^nA*mup3!i9 z9NbwbkNIg_2|j5KyoVktawu*@h*He&F&o6(SwLeFsen9nHA~so7$mx(7c1{8)6JEi zgxMx0w3C8UVRtmCz`%@sY$@S8JC@|~+tFv2t{u?}BN5Loy;P?NW>!81HrAS^Oclbp zzNXz6;W`^A1Ie3f$tJqz}ZwK5*i9#wuXy26ZnEeeW(kekXb2ah%J= zRzyUArst;>zG)&F0!V{f{-)_v2=E-6=mwjpuW5JX`+Yk-Ak8>I+pVs@1NW#rC{N* zaRL`g>XxxY#T5b^lJ<0;?@Rd9)YdmTR}I5n(fZ1=bdRXkihfUlerV7=OuPTFyoJC>@&AW zX(h_d)b;Rw{!&~j`pfAP37vwzC?Q{U&$;zi)8Fr412xmg#z}$U6 zx_!ZfBmr31^i-rpAQOyVHW|CDURE_2K8=~1D`7}I?gaI^dR!GdKiGNeOwsd16KafQ zy&kyxYEQRjXT3Wk=i5&%JSqG9uii5cwNI}rD{S4ZU>~6X$7#ihRj!!bVW;KmgID&K z!L`n{TP5lK?;oj<)F@l3w5UhLTfFA59N!Q4FFV8XBG~p-+Dx1-Ek@Onh|-vSBN-XC zbWR`b*Zl4_&bqo(m?DGm8O^b!c^esP_m_uv&h6%5?jLVN06%KfV}pMjtu1$vO@NKGRrtDJ+Ks<>B64s4^S%q%4U|+M z6}NWxXg0ok+33GG-FnBNHonE5sId^B++lcDd{UTN)~AOZTq#fyJcxYLBFWM=(1U_) zr(w^1RJ6NELP&ZS3u>_IEf7G<{%;3|chpX_QPR@P^ay3`#7$~`6sqtXl@WD|OY(2W zUtT|F&)BBQP)hIm-)6AsousqF{1Sv$wGcf@?2lSg2@t_&=7x&Tktz*+nW2!>&$A7tt|1-3?LWNc^oXNM^;siDJ?jDXb2dP4%3R5zF zo|N@OorW||#H3L%ir6fp?EgpcAo#T zCkkBn`{49;VEl4Dn3(BZi0OA9q&-RnTQ-|5>Lp3qRy8vHCE)PpJ(gCcg6o-HWJ;)* z*0H(d(AC=AJ>sRrG(?CsSvXV3sHQ`0O=pqoC8|eheP2GexQxuFoiX;IQvKQZ?fEIi zgk5KU(EY}_`CX|%O7A9xYdYkoDs)H87C@|-$>1oESJNtxiYV=*EX))hZ#We#82gsp z>2Z|6(q4Bpl3p8g?|kX4-oY7pmf^Ad49Ta5mzSgFuoWtbUCvvq zoJ;_+=Dd{Fy*--;5}>q|-7t=+SCi3f`^%@)(J~>ME_{C{e{T3{I!?2ARsbq8u8pQ?N4M9LnP4}; zFY8?~M{fP}T|0O{1q~fiT%pgg(Ue}AB(C7_dY5klNDcCCa$?fD%Ox3a)~q&-p*@a` zoTO=c%GdC&jX7+me&lrG0Z_@r;@W64g8;kY13ga%-#1Ogo zw|MK5HGmwR8$i|2K#!jm5U3fxveL+!rhxf7tsw1pEL_7^Bozh}oy#DGAkFPTS$JxC zP6VW%6$#?fva`3(W(Df$cq96wE=W3c{i4yHu$gaJ)BrLypSf)R3#fgw80m<&67}XO zpSB2=1iwwD^N2#$Lb8x}@kNw9rP06Ylr`Xgime_f?`Ye&tk-_A*Pt`M+YZHpM{gYS zVX0D8?ZDfI6+642_=C~OAkI*sPrZEp5Rctu*1&lcQ6(~I3Q5ec zn%r(^$(cK-Pon^H^05+{VjC-@BL`5|sVy}L&uQtYUWl|!t$Qd4=`pm9AfeIy`-`Gl z`$sX;-kH(bHEn>TLIUU)c&vd-yI$A_`IVaC~XA6eUg6T)yd-CDaHP15wJ5Xx?s!?*76TgI zJ|zE1we#CV!lc4nAE=Aou$jgoVJ?jYP|(=HQpLk=60635n&Ekou_GcMg_%cZ4acg7 zXd^Vt08+!$Nn~ZS0koDzu-anN`5LdWIkB#NOvQTT(=!tM(a9h46WJfkZqyqq=00>3 z{B&&0pQsTQNFOxzh;l^faL~ zby%ZWbxl?avARUxoVXcL?C_V(-OuhtuvfRYz3Ktq{#ewVaJiN0gL0%}%Rn|bV-^-Wwh&0w-b$R5c@ zyM4Xxw^XvO!46z6H*B{mL$iq-apsTr7lJ97Q7YCh?)?jl7or4Z{s(Sq;WuChINhfDcfKaPc%nCe*Sz1uT=1c>Yoj z(*gz3*u%TKVNtb-RMcHWSdiw&*Cbmwam|s_S+G));J`QzL136OZGJ4$05D8lf~s2e zZ0(dPSj1ecn();=gStxV<$b1K7(sW?-9I^cGJb9YRFRncVh8@ucoV4u~HdtTshZN-Qcjyok(YquaG_P-TA0x zAoIv~S}b3%mTf{%>Sy(4gW_SNmiE@XmfbEcED)7Gj!JVNV-aYM z=+0Io=`n)>HL)%ahYidu*miuf4SXtfPY%5^>tm$utTVbF9$0WA9VA%czB1_q0zafC zeK|_#*bec}e2N6A61ZTO<$?wfW0(}bXP%t$q-?U3ED&m4*=C6dRU#aIp=uO5T>H?4 zFk#)^S(-*OQ#ch70v!by-(caMxept>8;xV4y1@9`_|BX+IOU+(_Ki*_^A1m^@H0(OA!TIVs>#`Sr84`Hmmvu z^L?=dt-tt@3whNMW4x#0L^w1E%oUVyr9Jo65rN_%t+R}z8m`SL)u(Tp#cL%J*lyC0 zJ8;_)?>yO%(dhZDeHRolXwdbs!ZI@ZI@`Nz=^D z0r&XiU{BzxK-qUE>VG}&|1#p0)wv&a@*~h8k>rev+z?H}2_7ot{k_MEmT45_**=8^ z3+vLiBmd{@S3b(khgo=$D!3r~AC#2=-#j;Y%@b=v?65KVFdGck3xomf zR?4Fe7(4EKc0=d^;q2(;vJ=_97Y7Wdw^LU~4n`d!$GiS__465MP5LIi20i%t+$q{z zET&7Z{$21|s2QHbnRB2dayCh=U{aSkh@v=_t|7Zu+Oo7$$xph%9h9ot390*Qzf^>MjI{RnL2#y|yO{)y_x z73oC-)Fs2qjvCI=^pX{(da-OvQ{qbsK*U*rWJ>(OSNkoy<0gy}a{}8(J*ehkeYfcLPcVFkJMqo>_c^TWFxF+B}JqOoA&QJfyF5s}$SGWMDE+ z1rJer0JVHBRXZsJO@K5cRRU2NH+R^)l%WVa5cse7W`F6#*T?66BSmGewWE6_2(w%# zM6Quok_0DxY_x$9;DMsmXaTsp3$v!DuG0Ikd}z0VcVljJ9OP}?PViBeRe%N<@Btn9 ztF}w_^FF!_&zANT*nGB+b-$fIW*J&hK21$q!Y| zyqMvE?KmMCg|p5H$zJ}ki80n3Pu%sXh|caU)0}kcNsBh03}cUFdepz3DpMNzn*PK* zy@Rf-b%_DGMqXn}aTZT3>9MbWkOGD=r79Z7hm|N3Fmd=?jB!gtZ+Z;bI4$j_QS(Qy z{@LuwxF?2{jB}se2LdWM3V~8?eAr$hqG|u36t0ZnedfbV?_XhYY!vDrz?=7 z)p|Bh9qDp81Zxp!heP5llG-#XI_+EWq_(zPbV&2f|$$9((0G4$`fgS=9CN zaSUH_jGzgX;Y4mM7n91A^mgGS3bFljit&E|Gaj%GF%)Q|6m0C}YRPnYO}Nf>i+er1 zOALI^ve}~EE<(Dn5aW(tR4sa+;QVf#g-ZP&x1p1t0O0vgW@gXOI6wcVhhfL}ion|I zvv&1rM{9OG$LEYam?ETpfJu}o7cF23$ule79-t)7`E1$UZ5n}FL!N)VU>O{#hea9& zrM{?_<(uHm!3@;I#pucZ+zsYZi8Qg?MUJtc}D>I z5^?IRPHMpK@MutW{oS94slgqh8=oKHjD5w$;eVK?lEB4A!Sp$Oajb*j?5PUjv2$!h z{;~NC%i`(nM#h0Jc{y0zq0GP>^IKFE1q2?TH!#liS3QB7EcJjK-sI-lSwm)F$4oWV z8L?J$rZqOWb{wZtY>ud2UhZ>&ym>fITe#mpTYym{_}8IRlQy*-r}Y8qwsVS2m#R(K zqlmJH1>_%H9MtmAWOn@M&1k<17@}pESj5)h@_@KQBRFEo!`%m|(2`rz!a_%ZSg{G8 zS``1$;hV|2c{uw&dVWGQV&++`4ZcrC_cGhn7@Rxc9rz89?0Gp|U?6(*?4D@vSEB{| zi){FAHFl*TAfi_iUw~&DGRwXtHrFAUwH`2*6 z)QS%~*oqQQ?vj&I2A5AY#~MFcO+am*y3ni@S8$h&FR&L_&8ob)T14n6{o#}lDY$8E1XYkI`#huB2LS5QlaD4uvJ?NR zfSne`K_5}8Sc3ma?^C{9}uX0nPAZ z+9VC-zRw(Voa*9#+ojs}-|jq*M$T4n_xj0OWS90Gax;9}q#n=FNB}jo_pinC+2GdQ zaEiB`jGKDdwTJyF;XPaz$~B6fgly4P(_Q2*$WDY+s->G0;L8L5%i_n!v6Z*i6tUrP z_(mos^)TCvfu;9f##jDUxg7WAdN6spxft1#=3A!aR<&{axK0de8Q&KB#N%{#=S%h5 z6lOp@>dg-#<05E^wc5_^#m^;s&8SkV~rMl?bBC?Td%rC$Lw zx>6s^g?1bf&4*Tw_lb~6ZT|(1R&Ln*Lm;IFic>IIDhc@ny$mxy+`7^6ObiPHmr!Z# zi^|Bpr-L!mXAp8TvM?guDBhyP{B93luD7zgCG?^dr8Ywembi#}aQ0_=`H*y90JOO) zR@6id;_)+Fh;_mj*h_j$I%BwQuA75r?*3kX^-6%W=t ziJ=YvM!%0sOjC1+j=<}1T{3pfh8ik}?&sci4>-uNt~WMh!v}8Hx%vb*%VH^$O-uin zjNKfwfVoR(VI>PeN{?5lxp0ard5ufLvVKadwUmN8lEFKS+5ioGm#|O z7GDpk#k`b6Ptx!K){qzwsRYU%CA(&QqMx$PnH4M~T&Z26P@J;Rw%N@mY(1i0x6mqg z!-mP_oxtfJkmqQdKQwu7aw1@bVS4&cx)r3$9dD6^sZagH+fmdLmD7(@C#CbZ*LqnF1-IS|Aa0si@cA*j!%$k?y*X@f#|WkS%>|K-q+a0^3J zD6lhu7Urk!#2Gb&OOY2m*$vCz(#eQ6yg6@ft?_m%OGZ7&xZ}zqNQL#+DAJp@EyJ0j zQ1SZO!f>O+2vpiA5b7t`71X07>^NdU9>uGeqB>$Dd6j^8NO_m_{9(u~?55V1+AL4B za3)~@lSp2HM^g?aR2_?J5Vt?6oalq2urNguK4fk)&z0YLO+MOLcvPlD{4@fIGEz;n z>j$y}7utvT5YVsqPm_(jjp;TRVd`}vy9`pW$Zj3Xa#-*0RX#0!C;~o@>ObxjT!-8T$S0H zharImZQg>dUjQK3v1}X}P}8ax0ug)8KkM}O(MB&!?R-8IOP%)fskYxf|Hh7#Kp^)q z_9XW;th@D@^S|Rej_1*W0RxEE)}u{ce5fg{iL*&JBg`fP53_@__lYgr(EoDq1BaO3 zajtYMw^>^!%d8EpyfzG1LU=oNEqNU2uQdC2BM&skv$3Dv?ROI#xotgBG5>p2 zb+EmEq}*dZBQ98S9;czj=Tqfj{geBpamR}2Lk7Xx+dqSPZDUeAN$GfLV3l>r&j9f+ zowrP)6gyj8#&HR$icF1ppjt@~9Flz_XiQQX(yM|wK-``-6UtLXN4GxK{)60yV(X7u zBO_8ZMRolng!7veFS~aU?B7j(Km<@r1IWo93)X^(#q{P$*`e)e0&o&66ybAx_cY z%EehIt@S7~i{jn@hG-2>_IML#qgQC))gM`yZ}7OPBH3j-iu(7B>e#^k`_6 zpQEaMusa#;VL#O?5Dna+d*K~qN(f*(ypui71?VuQ$XQ_X>*h|jWg{Q>}5f+()v+T}Lg>+eI zO!#O41)#w)$Qbpw>{hBNnzr@*XWFo4nNFP^gW?(phoVEIhT9(Tug-@ZO8^*G-m8d~ zoG?JO6W#>D`|+zzC2Xokdp_H)ki(9FROFG{afk(7$uMJXuST8~PgNd9pgh>6twOHh zkDZ;br=0(d+5C5c9KedaOY5ufljlIGmQUrtLv5UKQK!K zI|N6Wdfqi+?*1Mgzh5t_aOEjEaU%y%LvaRE!{x-!%eHX^k<5p|(M)P7poG?XB8Ygf zxHMI;YD&&oD+>B7GYIWS^Ux%=L2o`%c;cP-ncV|*mdAdAm2{0Sp|EWK|18;j#wj;9 zbz?q$G}ER`sjIA28HE8hFi_A^bob-q`R<(PTV31=p7`v#)>D@Usf{LbL7B4Xx6^i5 z&&pZ-xF-JaP~|M68{-3C!Fwy&^qR3Ii7n9)m<}T@%(YWa2qq=<(b3!t3`oJ<#rN6Q z_rhJv|K?fn25Vf^hJ#ygUnzIkr2ZAqdnt6Sl?y_DFG%@)1y2`wUZNJ z<^wJOHSnP04qkoOJg@(Y5!vw_d42MnL=3_!rX0gRs&Xn4>|mtx8JdYoyAgGYLTLC5 z&mQfspE(Nvxngh5oRcf61x6Yu?~*0h*5$NHJ1MRJs)7+Sp5m^K+Eb20tVn4^C8N8q zFUws8i;4|cWe^NgPY4*4@t8C7AO`d-=GJXCAB&y5JFsEHYxdIuov_&xKOR@`#Ijg4 zqm9cx&DH;Q+z%6@uNkKo$=B@8E=135M<6s)FVOIMmc)lNVg~0>0Hl4oGH_P-)!4IU z=J0!0$2VMu93v%KjFDt*&l*XPwvET4G8|U6B7VsX5QSTfd;7Zr?(7QapPdi@?t+aR z5oyc@-Vf7fV!4>0jkVXOwT6GET6YD=ng|^;lRyw@WqJy-f&9F!!BhW*BY(P=0xl6% zaG9IdvdXQWG2`KfT1?J!KcPFrjy7`UoTAI#t(l_T4O7wD73UPN93?U^Tr!T2GjJ{_ zIuW74`BpXHoyMuD5*HR6bLKAVU1N)?gEE(oILQ#mLUt7Z=r3ciza1J0sq7MktK!#O2 z@akUK>SnxrIH@WIq@AK(`%YXshxSWAnGva`;f5q`@CQ}WG9$FZPf^9;T~V1m5kDri zYI#n9gw(P?Ng>dN=M3Y!P<$*Rhy_jtuG}|zizQ( zMUFG|6tiRPEdu}hAS<74u*cKw;0f6@`+)dVM?&v^$7T@`uvs9RupwY}is)ID~E|N3Goe~crn-}UKb&3{g&w{z)K96N;BW9ei& zr@RUU+j;cuy8CIP+}N($%j2%v@6rOwXCb9W&()N)Nhxea9@gMTD(2-3SM#$@Z`w1? zbeh3b_5Ky3n!Cs}=JQEfPDz^i-`R7JtcQPdwM-eWk(=o!`rM_0iEQC% z!_Jq7>vtK{TbKhn+O)9ooi-ONbvkb4)>Mf@vfE#oltF`d{Mb z4k1GE6Q-{`h%B=lmCY!!lvUJ~kFbEU>E8HwJo6(rY;Uj+#H4(up211o$a^P4o7pr2 zt@!h$<;1~-CMkm7U6!-WjRnX+2cRvE3NWm0Z(nJU--|lwOY#=a@DJ{pVK~TBrKC=; z7embhb;J)xA8CBYI^SIlY=Q?5Avu3rNFqWS^ZDuR_u*VE{)HVzGT-EwiQ;7il$v~1 z50`~<7dOmP62(3KFu3$$b*6&WY#R{saf^(o<*d}Jj-C*gC}{>EV*1Z#E&xqV+w}n7 zGJL?klr=o9weQy}eO#4`$JJ_W$YQ~=vat{9(N8&C`V|8#q{wN2gV*d0BeN%Lu!Qu$ z%o!LT5rPijNlK*N*+fT7%%J&ke8C{*d%d%#;&A4X?fsywM1s9_z)o$3crDA-MekFLkW` zd?9Mg8o&jB{a9MpF5t0Tq&bNndtCf;jh{daqB~YKc#q$?iH2Vlj4)S;G13BUQSUd3 zxz*EOim~KLy)i}N)}EDGhg&PSU4TfRYycbBTc-8r9snr)3clWBO}R*8MQ!)$%>oYC z4qRCb;)YSB53E}u1QA$T-bF+5y_Hu{0)c?!!j1}p;{d5!=n9!uMU;{x@EvS3m>Vm_ zfee;XQyYzozu?yL!zN04xsX9!myY8?r!p7IZ8hRRe4NswLP%+he%>`{4{8N zOSX14ZMLc^kH`5(OE0D?7h`rT8%L>G1h+RTEusVG(%5v zI#X;bb!i%Hm-2KNpAdj$wYjV$FM{9H82rk3gC!2X9gT{O28!jpzToJHN_yvcl@mFe z{*659>YlzdAe50ZF7g<$@XWAFtdaL!-4Ij6+O1w~p`aop}+#dC)y?7@9o#`H!k<%jNo4<(p}#H*pn!(5%*p{nyfwL zQpW?>cq}Y#xi|oc>?|`47xbz@Wqk9Ufsc$sZwVx*m08(2p`!E`UHMatTgR>6#S*ZU zX(ngrP0-{ha$Az!EwKT8lVRe;vw2`g2cAnF2t%Wg{%Nl|5V>m73OQuIEx=>l-h`u^iXK+Q5Tu^qpH~JrPL=o4485z=wxPh>nP`*^>~p zSoF+RY+@rsAtA)Sa}ZeaD+9 zJ~mq-X1&0VrHz0nV&aI)C*JdMq!5XLfDph==a~`I0{fTLQ7}1#A+thfWIxp92!9;E z^0v@HqGTryW%h5^X9^?!J?5wN{7k~><`i9b+J^Lw&!BZVlm|U={k{WyUx-;N;JK%H z@HYnNCz9pxT+supSW7eUa~;!_{lLl>i$S5rlhpv~KncX?SejiL@o12R8DbhcVh2M` zl3_p}BI<&0N(2#mALj&TP;+Z)0FhLrJ$$Go8@xsojt3Gp4d7kR4)X;S9ln5nIkwP{ zE`!rI&1i$2l*nGjBy!s?NzPXfX%rHWcI%T}|9;pzi3QM`$f?fSzIO(ukXv%t2_&&( zvMz-wy1M*5Qn(-l4(>3JU^j)M8-DjX==BTxHQ2+g^FaO3Oeq1z1<_;|u93O~`qb=k zW!QS!UXiMKX7PM&{BobD()IfOp?pB-ep_K!J1|e_dOTp89X%TC{4XAg+4BfmuhS|< zYWs94C0wCa`T2+4QR>7(!;|In_TCw%ql?cyj)8;ykl?}>3^zgYTfvjaT_m2C4d@=3 ze2pqdRR{$OAu})+L|Kp^{7^2n3TcjN2Vzjo+q0@v&3Wv+%(}5D3AUpY9AQ$CBvoc; zDwO1ERok^M@BXuDBDT6IP@z$jjq6^J`zl0zJ5x!Gm`e?dJ#@3Tb?+^D672Q&mYxLi ztKpemeM6a{8LSOB zh@}{~i1%*Q`s>oV^Z<}G;~t(X4XUuq;ENbMKLr4?eYv|9#)F=RV-KS2iDSnf>S{Gr8m|{b>4#g(i=cb zowz~=KNe7nD=Z7-&A;m-J>ajnB0cL6M-QdkM;}I9Sv#nNLsk;4i6kr|Hc_x#R9uGZ zLRlZ&j3_q1A@QbUcETnp1`!cF4}MlVZeO^ojg#K}J9&JC1&N}hh^lTEU#6!Z6vqXH z9F{buw-W(yWy2`J!NhQ8^nj0&)LA^1^R`#D?1~d_)e~z#?**C^ahznPc#7XS0=+OA zG{kNZcna>>pMed;SIEKchOnpu%DeehkQ&eE4}g&T5dWJ2urdV+why2wS)Ui>t^wg- zaA!7P&3f@~tebR`Om(~%VclYx&>p4=R7Q4)H|29=loj(6J-EkIQOha7rkHzYoFa?u z7xJYjf0JV@V^$;_&UjY!Ji?JF0QX{t3MM)jHt0NjtC0{z>7>&8=;|;;`j@G^{!%6f zvLf>^8-PTwFbUY90Ylk0&ting%cH4LLwyJNeVIJsoUVc#txjwKu1A2uBpjXDrBOl? z#~!yvU8-myWkJSC0RcJ`qyY&#{TJ~ZX(!4Zu76W;PVa^S^HRCZ;ZdY8UfQD8JFUlw zre};UaUe)IMf25Xp{9U%>>&;jANNLbZE*HnIS&?NylbBlX@Qo_`=iCyShZ%TRh z<4%_@IeD@On)Wj^#c6-P{o+rCgS!m-jGmf(C$1%k!zs@g3?>N=hX7z5Da##$msW&@ z6^ZvxR%VPDU@seedU}=Cgfx+Z(;Z)??w=93ULRk=Ow=~tHnLxPy_M|le7Z;2j8@)O z*4~+@;6K*!8j+tb6bLl_aGR%}Kh(>>g1@Iu=1uC;6GbInbWHH@bjQRSCQ+0h?2{c>Gg|;^V z+zHbiN({YC8RHFB&gien8VH4}o@6i%=>IWDZ4Ui_h+ju#x{J7tMZ={&Jop-aTlaIh!+ORNX#Swga{)S#@9Rn#G*L?J@)=I4LBhkq@sg7}?_=wix$ z5qxR;;_$k&MEm@wD&|{{?J6I>m$L<&q#JA?Cu-I1Rc~%#OrEV@I`Ver=lmkS(oGOx zM!a_;-BABcO;jR}F4?n-djxrz_xsNmT&5karM~`Pt2`Ici(i7v4eul{wd>DO*p~gJ z=H&^{D-~azZZ}burH)Z<&vnix-djPhM&hpTT*9Z7s# zptgYy%@6!rrzo9R6`LIy9gP?Go1Wznb);wI^!m}T=H7YYcFVa5N&M9j1wv(-8P7F2 zq}2oHST#j?-XKOE?^$8Zj=$aPdG>AU+Vg7CJ#ia4-|!Kzv_a??xvIf*^s4QTTDi~- zr2Rg0)B(8MaQwvyKy3j+PRdU#f==A)p|;ISLv2kQ)vj9(KK!U5_#>g`*pY&Cy^b$Nhwpz3R;E zkv_af&~l+VplD%Xw8lP|QLI2q4{?CGX|++g+P6Rr3HCBrbXRAcbFn9eiLST7u`34c zQ>{*|V4KbS!z-q@z;JSZZ?^V=Rs&3G0@XiRR`VM-ST&jedvuKg}!j0BieFV8f|7!#+ImaN!pP z=~|d|m=b|v`bL$iVToUf!VKv%OINydqiThFE92AZWjh(t?NA3T$i}Nl@i8UKh)WDm zbOk%OkiqJkic(+HktK}v>}Bz%&H)S|Q+yMq`Y?8;9&zly#dQy~!a#mP^(Pr|()G$k z&Pr#r(S?S7P!IrqEP3qagF=8_LX}1k?IF#eG%6;CYJ@;UeQw-Wbbyjc0&;bZw|fE> z)!)|~hqbfQQ}ny1+4klq62zIz5=%ARp^KXg#|i;i6(+xDUnxYULA^{wzVCu0TK|&; znC~x()B8dl)!?G`gqv+}M;2E8IVF!>JXp5;D_wW@T4$Ho>*EUgCRio)LZ4|+<@M|R zRJJg>!sL=L$qX65Ag(OGVeX-W76mC7xuka?WJ>uAc#2KDv?w27!n+rk?}br5tcR}opH=R+sQTq|9rm1q|$lc-Bf9gGWVgGoHSbFT7kEf?$9lmxi%+jTrArxjH5K;=!-k80TRMUE$y>j=7JMrh>`RD< zk_mp7WYGQ|0pcx;QJe~YQ>xj?X0D^Bv_zGUce7seA)YDKrI>r^*6Ta-&h%clApBQ; zfX+|FV!Oz&r{A=60-w=-aGf&Cj`|ztkp+U3Vd?~?-Xcbp8%O>=&iVh?daI~7gLYfD z8yaW`fo|NPaStvbK;wZxf@^ROuEAY8IKkZs?k>S0IDz2q1P|^U*4g_%>x?zlO zRrSqT^L-{Je`TTNefaF`r%b@jb!F85lBTH780TZ5TI3(twGw;9kXhrzCdd5?r%`PD zlg!hNP%m?MgxPQG#30>7`<%?1Edv!xBW2#lr=|Vdw7yBZM=QgAVWc>RvX3|QR;UzETzn)C6rUx zBhH`3k-0k!Lh`Age&}4O-{`q*i)W?H?ohe@B3rfE_Q%1up>R?QlL55d2*UYiGE zPJY{Y@7Si?)} z+LjBdM-&oEIR^floZER`uXeqfo2a%r6&t@+i`-rlWJSmwh~%*eSY)!UyX2C`{GBt!9paB4$OTWz<>w*ulB zyHB;lVbCGxwp2Lwzt!il#?||qzoIFwI~3*Ryigb6+uzqB)?W>m6mVfUnoY&qt*c&- zluu~!o#VEyluwtov%huhD#ta(@Dnk&C$GETnk#89TYr(@prWNS<+Z%TBHUREG4)dri&g>u)_5A5M^Vp5mzE_&y)E`WMe3D9Nw{ggfK! z^JY{Y_60Sbw6-{#8vY#bo=9VV`d3bgb%9N4h+P&u{C$YzKzXGs9iI!Jl#FCEe7C88 z@=}cvB?(u$1^1B!Is8j<#gVpgjXICd4_2W;qB z0&sS+q44(}mDN^6xz=fsiV0-SA)o)DA|pqVc6T)G`#w0#3M^Uw_)1yMPN6Y&T9Q56 z?sFr)>M`v7d~d!Pl~p#@-?}yhLJs&HgZO3jFg>90d@-K&^W5U`e$_qhbwR#y_udqb z0*T7vr4e{4Uv?n-d7z^?^%XnN`BZ#2jRc;EtH*P3Jp1=aO7L)PpsHm2`BbL#-19P0 zmg*_gZe{$e4n!M?F@*! z`Cpw%Qi+?mte!B)&+7~0}#d|k#??-0b7$4V^XS~u@LViIpmg8#rcp8b}Cld`= z!`Yayp%8HZt6f4q0vzUAnXqk;@7rn%zi*BjK{M2fes^*{&p!WMz0Z0|dOo-)?fn1m z?T_d9T{^qh`?Y5H_{$R;1my#y(HXcm>|?%11R((SF{Fw%@iXWKH6BRx3*Ues!0@VS z?o;NvEpvZP>5zqD;#ExpQ@K&Zo8yo)!q(l!6)Wd}miWt(&xDDcHlzoW9nV`&fwlFa z(VPV!DmoPIvl30*xnz(j2M$6(>Fq&KvR!KzQ386K{(+kFw_Qkwsq*VY!ACh1B#+0 zlO!~xHmC>*&;oR~z_yjJ1~4>WWB5mhVQC^KbFf=JLV16ivWfQt6tHeJ=!Tg}fXqQ* zzlb=Dg6I`O#~Ortmzl({Y`*kdSePM`(@B%C*NVYge& zE5Qu@ws!8d6@i6|Ol@D)c@M%=aWN$^vzbD&IgpU~Qn-Kg#^+)xO-0wJkcl|;I)%LrdH#OI%y-Y#D^>Q#BRDV5qn8Yw(7a^} zVDZYM;1M#6>)=O|?0cgu%Uqh*^SX!8l4-WKjd0|;M_`qj-*uN@%26DEifu{%X^Y_{bSQdz z@|5=c;Cn;)ygOxw{9iZhe_ys5K)dqt(qU@mF%4tiMPxTeC9c@YI;$TXBTXeZu5`1! zGX|72)akXK4SwV?qC+^gMPqhRem&o5Q2Ms_4s*A4FzpW|m<|roA}en66BMY;`}i#D zr#GWvtB+}co$?n6hnV>nVGhMATv&re{$g?@2`LI2`LN1t{BOyaa1kbD-TC3rNFc_5 zl?D|IL7yzpyEuo;h{0kV12N`O3Iw8WUyi#HHX`6{Ws7`{-)b?c%h;u(4YzQ{QNXEvS zLELsOx#sDp6e`mluo9!&cf+oM7@a(*9DhxcF>q;6>A>b<7(v2DN-YORdq|4XNV`N% zW{1eDjw4!67R*-NLEV!*wP&{cAp`&~xNqIi%8I;=?MK$%p$LDL^&<}8sSk}59>J}eewtSmkmFaBPVga=63@Y8btp2c;_WJeeobke3SJohU!3yW99 zbUlHO?v~<{=+Q|^0tdIMnz3AorrID>iy<)v`Ik7z3la8STI`M9if}u*T+r;QOLa70Xy!yWR4XO{IQ6}K`}f_*=NDO! zbYKbW(OY+mF2ySQ0%aV%J)S>r+Ony?4|nc2yuEJ;`bqg?*1T^fht>i18LDZo_Hp@) z^Lfv%rd$}hc<`qt2*cLjHS{Z9v>g$_)|NrJi+Bw>?ach^mU*)q!4{1ISLCIDVcC;S4oiTd6~su~q#80k;J;!&Z2 zOY+X8dz1#68&UV0=7+1r((u_C4ilX3Vo1M|hnm0WF8Mayg=B?wCl;W5{}zIose7&Q zMjY|<+iLfkvWB+MBv+Oyk7N@Mh=ApR;OOrMX&I>*LN?X|U62egu?IV=Z~)9E-mAs_ zNLvPgxCrh1pr52H=CR&3F!qDGIhUI@QsBk#MwPH04@zBYI!R!E4vuT^Wwu<=K)O`q z{F#$x>>WgHS{tbceU=4nt#9V5?kbIXw>JWRE&(qn%LUg@K~}_qvWhAE=qQiXL8!%47>UC0i@o!4#Iz-=tl!l6{-X?i{o4QQOpF1bpOl!^jqoG5=+LY}}3-LYe4M3CBE>CC$V>k6vNr#4-eP5|ZEf9X*+} z{pClZJUwKDqW1)Sa`nSd&Wti!T5{8%5%!yNl9K`XA$LQvcmvx+VC-Z0W^S-F> z>k#S2Ar`V-znTcUwqwm0WgI>xQyS&T{CIe;vTS<|y+6FG2sjd-c*=Mo6qz}dFWpPD z^^2OQNJF&uvP4`?Rvf9P6O`#iyMq@=-Axr0l+0s^!9<)KuO@_w^bwSwO=282)mC_E zcvW_5kBI&&%q(*oPIv9`@hU~dldO>f`($dt5CK|uvGjFVZf~t?G65$Z8JAj6w4R0R0xIOuk7CcR1>=JTbrJUdhgM%2?@pyNOlmAH zLM9Vw+ks6tt;J8nNTjue{qx)F3&>zj49H;UgUa#;hPxEkVl-Sv=6-}Np<~)=IbCG( zQBe4gvjknp#kv7TVBVK<9v@P+ zbk2m2vgrPqC7IrGXjQvdxEngk1h#gHkbK|QDh?yA|Q-Qu{ht40@kl@!2uI<`6*egqi-KPea zqE83FiL3|b7s7T|0f_%@?&C$@B^KvcdmIb{7a)l~@pYwsch~i>$y;za>PYUm8aZ36 z3oecX6XT`EVeBM`!ZaAc+qiPIAUx3#;Y>D!FIPl!LKUaSI12K+4s=gWjzbJKEA?RvWaRpvgX>dJtnG8dr&;<7uMq zR>u$_!D1AI4QMntT-O*Y(f@)QJ$9q@Zu`2?WWaOgu+v3WQnFX_H##yH7G|F)FL-S_ zZt(Hs%VTLq#BE`cc~!uPk@ncUDhkAMGeZ_L6O1l&^1v0VqZ5M|8HtgMcyF-L6Uog=v3AjfcLJXgF6$*=ux0VIQ|GV zrOaD<(yxLa7X=+jyTRCxceCtDd&_()e|k!sLzJ}$n7$zOhJR-!?#YHT8Tr+ODn*6^ zZNb&;Q5=b1Rj4HuO5l@QzgPd(UBv^e4DjB+Ex_X~crWSmCmuj&B9RclC~D!pD9>4p znoK;x#BranL=Cs^7O_CN(BobovM4UGK{@Vea}1PFId7?3^}Zhr{nV-p7TNRtho;|g zbf@p*dOe&i7*)I)X%8}lD!=d2Od^2)EjqX){iN=vS8u4hpv4VT;fin#wh!oQ$c~Y3IKHgMp!4N3Owee#5(!!sUx={Bt0t@BGYFZ#txUo z{Ox)%E+o9r+Ey&+&QNJTE5RC6NpCR862l=2LdN2G)dZqMvw?@saZiY&;=f2*B*IRG zUqp23Yy4Sd$VhEb6t20pXC^3Of*{l&Miky4&|y6I3qrYq3qS^^0@w*NQhvB;Uln+M zFuT6%nVx@aDgU7pN$LG(_K;6p-!s28dz|6+37aoxAbi=)rLllb&v~8Dw_um_tD)MQ zWWHtko#B^2z5v71>f&5%2-iE@l&`A`JetCf7v_M+wbsi%V?H6z#sZsC_-&U2AqN;& z;Nh5m{6rKzPWlAmn#bwva{q9bdK|Kz7R^UuzZl8M1ejJ$Qq}}czO=}$E}_RF+%MK5 z5DNuJE?H+|wEfBY-VYmBw$%N0ZSD@$mcQ)zF-31*nmT*dYgY$!$;XofG!CwHLqC{P zH%Wa~RdvYXS-qPpYxb_E;AAi{Wl}#MI+$b~ToRpBI^bQzcaW^VYOUsfWc%&5G}g&< z+~}3A{M^`tx16ca*KWs8_#=1cdkP>pA*al6 z&uH$S6yGEN1tpHQYbcgl)aZimz-~h?v0J@}>PPD?0!%o;ZXTM4qyZDl1wb5Y{0q!| zmG5A3Jowwq_mEON2Ra?USN#z3xz;@>xqU;$O~OFP=dq?G5n7e<^!9003xdK1gBiin z((!9ViS)_WA1l58;}0~jk%I5QWeVaSaeFn3gJ%+1$n)kp5Q)~PEUu<%6Ypv%06umm zRgaoof)QM}XlwmdB4Qz)*NEPj$4?bq_X{UAvQ54};y z7^o0!?MEBJr9NXdXA0wwdDV8&3)enZ(sxRI?8@hhP}{xwzx$3$AIpNOzLUpOa?!gQ z=8DW!5$_c{xdR~Der%*Rae7Kk%p@AeYrR!p@2N6tPyWyCZAaapPPAi*G7#jIL3`qW znwF-AgU}7E2?q1b9>_vYMcHS+b=_AQ;wkk1S%~&s$A*Jr;T~*Wo?Gzk8k|q2Ggz@QBYcbSl$ckKou;@X5s#DnF z=*|xwf%HhvKhyCMKpR9PV2!U=L95IUTobkCAhf1J*$M0<-Muu%z?jTt#Z$|Q+8gMU zRN7_h(8z-*SK>~zsjqbC`Zdr>rE==k1$v z{*ytg5$mUG(Yt0A8(o~_pZ}WN4r`U(+I)xg_wR1PqDGFsp1}*X$KAFIYDqcu?f%(W8e9x8*tC6az2!;ZTK!(S z{Y7{7>Z!ki#IvDTjh6Z6S15oEYBl)Lkf^(|a*2$=7vW?66|_dugyAP)rb7WW*j3to z`$x-=P-o2%Yi)QStv%eyG>655a@XcsoX{vyg%J<{h6hO*F zxMK<~AdcE=75U~NHfAsa$q$U+m?)A5A=BoC;QbzeP2t*C? zl@5KH+Oal8AR@j{8v|}Eai9YYjKm!M$?h%+7r&>*G0zw6MCgr`1L#pAvgjEo?;!q~ zg2%03G?3#5854E8OFdu(Kdt$xmrU1S}SGSG`4 z?aCqBQ?6o;Z+$#c0Hylk4@hHQ8b{HM#8|4K2r4ZRx6F>U^e@Zz?g=Yo%GPG{+Ma7D z&dwX1=oPLOOR-y97G&|kU$iYOR5^fK)%@*7KmzBvn}`%JKp-m9N(PD%9`lKrn&aqE z*2YI7iH+$$S%A}Aq%^`6pwu9y-)_ceLn~3OhZQ9Ub{qApw=Jjy2B6>c95ouy(}~!L zbYmxW!-)ge%H=LEd`Q3-_M!+3Kk3&s)+xb`%iA2q2bTAaUN=Q4Mu)ajQ_=63ngcT5 z<;YYfsU01=zQ|MoP6tB=2fG63^R%z>(}j6CGe!Dre`mC@+~1lyjUJGH3^XvvguK?Y zn%a7%{sR*oZ8cAU^X$okpXCoLX~Oy*``ax&Ws-p=QdGMiMDD4Icr{;6^HzTfRECD% zrANZPpP!3ssz(_NCM3e47}=~A+aSOCHc}Zf9~2mRo}g8%^{>9C zAKNINh6y`{vKeHIjy`pu_(HJg#kxP63hb_qiVmS`h0^!ZIbqa>IAG_b(r|C)8fbsa z6kPH7`%YJ9Wd6z%%kwaNq#!KxOcGFzU5=K{Gf;hv#@_#WL+@((zG<*nxxfW+owiXy zKF+RA*0X?9ET={S+dY(ncY*!k!FhPMD1XpnUg7$qI7;mjv8(&sVk!EYJFRXUOIApX z4h*bw2@x#+mhN2Xv)(A(Ie6Qh=U)f*J0!&qZmt`VG!=cV2ySJ+`k1=Sb%4!W?pHF> z!i;u9H)pjzd~Q?VN=6d|buvEbuAxd-Yk$Q!(xq1u&p~mK#TElwNLs%}>Pw|rbai?@ z3~KyutMtEI(@O9P7ep@3o(}OTZTprgDu5?hCXttmLidSP^5{ zawH9v`p_g(wn#a%5Z(u;(Y0KeP~8RO`mm~b*`nNtC#Nkbcmwt zb!`>x4_ecIx(z+?I^yIO+>HR@0)L%VW8u#J?T$0@RbS`$A;ak8ND&`39mxQc2y}g%D1yDYA>eZ39lrCC!g#9cV zrl>}eSPObEtmU~^K$kb5r$?&OoadGw4@LLkqh`ZR+ic49?&Jf+03w=@Y3D-Q#1h_oMJQk5)i;CB{}ndGQARkkD+DsjyB(w0&swmlG`Fbs2e< z$|%|F+eK)oNyTGq7YoZO<}g@rhwP z(qvSo+O_Eh#iY9Mq8v%k8qcsShR&f1>ua#mvQjyzCq1sQalWEccwFvvO}(q>Xm&6W z>rI4AYvCGUs93Zr#X?39e{B!T%5e$`nN~f#`+gHsQ?uu2IF%mzrQ__@%xs( zX`58TUE%PdB{tN_TFXck5W7xxbm!AVVLjopt~he!3Dz>cEW!VG+9Bg^^PyzcI$CP% z+pHI~T`oS+v2&YgKz%^aclixaFTAD1;p%jsoe(8=Fy+G5*ByuJR6Ahz`Ulj@V)vp{ zqjr}t_|I=|REmFP^pcLjPBTy>?iDx3%61>E81re87}gw9xry&kV0cX6?b5^82E|aT z)@1#b4Y`bS^P}jkQwrrKXDj(KOH67hX2aTAlQ>9GFf?MMHzNTwtgXs=0d_?K-;j~N zJ-H?i2N%(<%ChV3n7V&L@}mC?l(`c?+E?4vrbUfaMGwk0w-& zyg!@uq}{vnbaQIAN8fv<)#YD1KYuj;#Y5k+zSqpt#$D4x6v+>OS~o--VN8Xf9w}aQ zH(Yvikwaj=t{Fk9c&y5L1Rd{dX*!nXA4nND-*CWurVzYUTDK@~B8BjTX#!@T8`gG9 zqAWDQ1l7MohK|-HjEPkc{Cq?bXN%&Qj@KyQ~Qg_gQ9@$fDw$#IaC4m zA-gMH4Gvc2Yzy7R(j2eWIwbsI(yw-p5I%9((u)A}3>=;;dQ_a%dL`G+LC=lfu=5ie zp;iVAa(3L`Y2BaAz-qQjf^b{(!+HNi=gh6g!CZx$o#G8NX|<6kON0~8a>VTqCS_l* zk&D3?QEZ)d(glJ-6Fe`Pa=8J?{Bn(CkLk>vk zQjYp*WYiE5AH$K*w>fa#+UnC@VyGx!E@dF^Q{_+mXo5*hWcX?ZhXk>niv5L2WN$8>1&(pW=wLFMj#4d>q3aKIN1NS(VsLM{yvL{`S`wb z!bY)clz{(+dvC?5 z#ldnxML=2@2%Zeh5&SGH4Nm|kR@D@-3M#2P8foDDu&kE2(iSeh)6xIqni{hFIt6F> z$Qk+pIgZ-(QB@Ye3E-PksD_HeU)8muhYWQ~u^3|bH6MA<#uw1e*#a7Ha@5R!!n5z^O# zn;xj!&Me4&s%qVAR}xBW`;0FJeh=Tx8Ux&^ktYtowol&Ey0D7(QsW9)KT~;{_{kOe zoBIr4(uXN|QYudr;uQrz@;r=4WTtsQOFLDbr!~+KnAZ6f&06}_N6oR~b3pp=+mCLN z0%Q1L6xI6nM1b91O7i5|@LB){Cs?rtfJ3aNyBC$H!-iSM5%1lT7u|y;A~XDEsO+)T zh1>MiFz;9r_V7VcTql2UDcKk;mX)MH!@o9Z zch_o>{o#^<|IMNy(eKxBX#e%H^@dM*Mp^R=-jQ~OWO=Ghz#d{@VB63detvgVp)sv{ zGOTR7xXb}Mp~;3cxkLF0)3tK5Ehhy}1n%P;&87;S0s9EQvf!?_Md0AY1fj^-S3~ z?sJt<45ECT;XkR+zxtX-%=qzbh{P?4qtd413g%Zv5ZHY?B3Nk8h)*1apiq*7#M;mb z3dd(;A^9<3y>BO4JUe#b?ZzjmG5J_~c7G!3@g$|?<6Qe_GNgzNKx)&N#TCFHLSh-y z&e7mn`|Y8M^i?%d16Y7eoow=licd5UjM1fChV4LFmqDk!G(tIX$g7jxf5z#*7-M7Q z75pOcB;YE_>YfQ$^Hu1<@Ye=Xn6TJ*<|!h%%-@)}GjyCVW+SHhxEegQr5j1fU^;qC zm@~5acu`pZ_Rd}5eIw;Peyr<7>uM`u!uzF+*{5yt+G06Uo+}^mk5V~M&fEU(dYDxDk`CcSCNN!#|1 z_P2s*gmDCs6Cw61UH+P6%T@7cPXeuFkFg7aHOXEz>6yy=WPyAyRG#U6^>L4%{iFJ` z(3;@nm8rwNTR?LsJR!%UcCITHH&3PMBizFnvSt9&R=ZWyw)~hZFf(3knWdgr4{a5hLhb6Z=wYC2@#QGoI zcpJ9HW>`H#$5>0meSdFugnP#S(lP!}tN*w$CHfHk5`8-HCT9YgH69c)6&0rQO}hxy zzHdS7l~)S49Jo?P#0QyPhy=}HivVS(?;*UviF~GlTX$5{I`3xP@(&DUCH#x6IVZCR zYSOByIK&^(4=z*ZLcqoXCs~Ci)Dixi>B>moIkhli)r<#;dgzgo^M3kGw^*jW#>{-@ zgSkgZt5Bj82f;(l&TeY<`R&?cOVl=7^f&9_cc|#iaeG_mam&+j#dFdN$?Lx3d`B3H zv$AqLbY@NTBboX)PA~g@kB=$ok8Jr<6#ygvV|b0XBvIbfMwiKF;xmvK=oi9Nrs1q^ z-eZipk6KwXIVrntqBeBJ9*u;9na-{mTPhTI1qav?2Z-#Z(|p!ki$( zk2H>6k=|0mYAs_Ye}>%(2K3)pR1ABZR`u*w2YxpF_VY!wJd&D)YD~K|9O!Clw=4H) z*Q@RZg{Qtxr9ZOlB(SaJ?(X8wu~*zr|4r>a@9e(0nvP7E(<@}&N`_gB0W`!vQo)ZD zg)GZ|<=?*N&sR9g=CFeMw8M0|gaW?@K*wzWK79aXRnW5&MTiz{8s zjj5$CDNLS(@BoM2?c@2eoFt#7opdzZ=RRKyym`Kfs{#eQQD&ke(#+gEf>VKUF$`IZ zB2tW!>B&RvPue~wxf1<|u4p;T8lCKT$$H#arat705lhOCDV-7pvKM@{FED7JWTr;R z#-7Se3Ef4b*IX z9?p{v1QO^X16Pmi>!%#T45UF?%xa;_dxVkSb>`+>SH^{F*7N4rP5`UGsNHn2@%HNk zC&8~}sg%6z=`0=wuL&Ap8-O-I0};KqgV0B4+QP@6fHgIS$~Ub~wd{9fcTp2}_7mdb zWG0kn3DJiQuSB0OFBb+Md9Ah(IZbhq@sLx0$#e3`cyQ z)t#Q+nK7p5Tghg~xJHZxaGjhZ*W84E>cIHFIrjg11n5KCF3+}K`&nYxwLJwPuH4m` zh!rsWzC~~zaV$4v6b6B4%ZG9qF{n(hR0V!GZQ-krGE4FHZ{as^D$YTii5~C*QIA|D z5Euqz5=sbgD8yKv$+FA&XN{UJQnDBLqq25)?M{nCnMOhhj>=^GwyBA{922azX}&1= znH!faKbesZLX2!7*H1-X`z|&Dsz@!@PZWR?pK`4G*?LSxRZW4z?Y?~W1H;$HB9csz z$Bo8u(aX3T8#aNd$~J z8mg2xW~E}z^wC2d1Moq4#&ys2HalS~n5YmkB)(A-VOmJkRpvm=fkY+QvjvMUkNt#% z8uV+samC&F-`a!gB8-k847mERb}(}GcOa|qVbVNdv1}~UMZtz!^h>+ClRrtuD?TJt zq`Ba~k%xe@eX_PdcCF;cI@TrPq&1P zPyUT_k+Aj?~oRQ z_{L`4+r^06fD)GWMlPl4-M`wwFKK^Sz!wA&2jnIxD{7n#b=F{gCENXrkjyu)ntzFE1uP~1&P}A z6^8fav;E^?KR9&CCTi9FDr)8;44=$0BO(k>+C%Ja2Ns|ybQiCApl`73xwu2xX^c(~pFjOP zxnIYL;f?WCmj2nTX93u1s%ZCE#N3?WzP~WhyfT~v3`;fK3tr)4{6Si~@#3r@LFAkh zre%S3yH_KJGpS){0ApMzaX$|cOvoYP+S-Z=K*2s3UR=2P-a-q=n zINShRsB7-dHID#EOWAVk56k-7oD!Xk9Kgit4byWJbLFxqK&YgbbG6?a9^!8hR`SFT zg6_ZH&X$YlH&sGE&r@ln^v1~I`f1?;Fxk8&?3Iw&{H>_XC_&VK(H2e3)Hln6%7sq5 zJ2pNjEZLQUrE}U;jSkxw?r3xNC>myEGd*^%%3y>~;g$cSNp0$W|7W?-r&;lM?s*fE z2L$DG>pirh3CNMIIL3x~}JZ!>mt&8#f{o<7a)S395fXuT#Q*X_R;`8fPl)*X7 z!(zIqP{7Y~bacfr&mL>d-L6pcH)C{RGul=doazPj*15g3a?tG&ST;NRPO61sk|0L{ zF-g33rKQS{sh%L#H#OwPFXljPmz(!;7>bHabjosKbX0WYIoWumY2K#j=;$tL$d(*r z`Lx)SnV?vG@AK2WJAe8DJo-3?h;Mie^fk4$DESa199o!^W&0=2@5e`G9W@rucjni~ zHx@sb%U4KJ`juvH=O-%;jwpjvGd4H4Gyq3~3#6W%>CC#Hq zjKp+w6u61v7sf=5c7?8ob#Fs*pZZbkj&QEY9=w!m8+3D)n1u$v3~=|=H}Dl^g^^|-ZRP8Xsf9w zNhxWL9%|CS&0e{mZmEi6LWb@AE7-5KxGfW?Qj(T`HoS&g*(A$~eaGAn&>CRmq*G>O zrL@8S6h%5WoMgS@$0*4|JWH(vnsH>zV`uuD{dLx|<*Z*4h@|Ml`_i0ydsz=X9>PNk z@9!JhM|IdS3F7ViUi$u3BK!PIi_K`cN>R;~>-rE?pOWbNe?!<#C_2848b8=21zz{g zZ>vgJXI9c8jveluassU=z+zB3y#SX(;4ogfAv+xqj$LK@7Q1nE5&i~es^*1C)8?$&$ zzNhT4Fwa~h3B{c~AmKa*WUD&UDrH>@xh2WG=Y4P5Q)cc0TBamv?v^ktO1NEdFk8@u{D*QcR4cFZIkol9q_i zMU9giP*8Ckh!Yzh?0j&S19;#3>%&aJzY@EbbDO9;Pv%ojw(7$CvNRG7o)V5Me7EJ@ zq(if{<7gr^qtuKAT#TvwJv0|w{L_Nfjw+DNd-GZMjcCV-w9hc^D$Sbx_gwsHE+SkI91UdifwZa-7}HA8vSI z-r_&=doR5#8 zm7)ajQcV9c5A9u3u}2bDB3j-&%;)VmUs$<)u*BVHp*>iAy4LTwoQ!OLB%k3C77-Nf z0Bh51T$OsBP>Nz;S%2fLT=~xE%gI!4EKH_N2oht>V|VAOf}RC7R`}l8d$|78M5MP_ z0N*lRR+#|qt%7hsG4BMXg29PTlCPn*YRTK628KZI#0i}AEma@T9LYTwaUSOv;c0Rx?96OJH;NdvyhU0Z+F=#Xf`0gyf#Juc|3HoxEgM8R2!mZZ;UiZuW5a%yVK^` zatOnZ`jG=%>pt-8W0d~(TjpV_&J<84fdC44*I}L)v^vjm&ggL%cx)eNA@dNa5#u$u zJ5~8v)h3l|DLB5f6}RE*K)3$yTfXl1n^!9&m?i)0<;!5=OKHwm*I$jg>jP~H@JN3; z9ZV2alybptsZ!%-E^g*;XZ2gT+mo@;rU|h>H89lY*J<)$P$@Gp@x6`K;11ahH?!jU zvY;-eW%Ug&_B*W{P*JWp9*_ZMhFL1*x=`|{?vWdTP{g$~heaffk4$)m49Y^^Gri7t zT=@}?VRcT{7q5P##{^`8nM0ZA1WstbslPo5oB=2l3eWz^I(q0rbdH0U=@S6vIC)rRBM$GL|P@;DP}CX6fk+4O<_P3{->P&T4Ad7|W=@AiQd6$%l<#2?V|s z=yk8u!T&?mS4K4*hi#AUlm;nj=`P8Uf^>JcAl)F{-62Q|jAnF~Fc{K3N(805;obY3 zC%^nZ|IW_Y9oKyYh?V3MAVF%y$$Q3IgQ0xhTLMU)h0=I~If>jKpoGaY%8-^GyI;If zj)#b2seVuc*GHleC?+6ErG+UI$`K&&AS;EXl*Gj)F4kr;l=s)Vnyx*QN;cpXnH(iK z^O>B?|H*gl>1^)POO|Jq=f~PJtgbE`KU*DuD!iVR;jRDe^>TVH5bNh{tni}*qw+UC zJ-fn|VQa9yUOm1|(ZFDL_u$i7zs6Q!vpeQ74?uZq1Gu3!Djmdy{2BT4YVt5 z{aE9Zb)D6cDSOOTCTnByy)co)?ekRVMePtI-KE8!o6%`D=;+px;F3w6)2Dz3e^IcX zJd}8CLa1$P#<6M#U223c8Y%xv7E_p1R&H6_Ow+gNQmmPsno>eNzadn>pmSu4dXNpi zBMLvK_KI@U#}c#%jS(K_&bI$-{r@op{Qv%6Ue@wGQ|m`xE!)xd%O?#I9$}H#w{Xg4_*2`XR;iBey^Be?wkR{P+>0u`eVlg}B?C>O1 zEY_UKO2yl8BuABB6hWR+3c%>MOs`F-q1-4~c!`nblWQ-K#3RjW;+TkB0%Ka>VnOjE zDH}$ojbn*q5XiWI)z`fPSjGfxe@OMAYX(8@S<)D!>HH(eU{9lv#S948fV1ln?;Clk zS+55YoPSi#QvS`t<{epvjA66@aR&W@Syueh5>aja4Kt#qq%AKai%nwP$5L4~%u*J; z?3$7WFPE`he|;SQFwFxxg5T3pNE7F260Ni5Z*OJbxQ}Gcs7P6ss5vRqWsjN}OK;L2 zxc$d76-cXjKK;^WHub<0p!Kg~KQx zf=vqj@TEI`uOJarH+~pWEKt>S~T5q;VnT%Q#{BVD9hYds|g9z0xEVy0F;Uz!r z1=0dI``y(L*!#b`M$z{Vo8uTUk&vBZl*GpRo2OJVGl2LBfH4@-miP!w`;4MWQdl<# zYldh_AB$oZ0trxwtais`Vp3=^jpVL}^x8rKZ{N<{hs(Z{IB@P#rQm~VU+G`N(>P!wXF8-xLG5P6Lt~wX)I+r2}-e2bP+kp zs#U*bLxEOtL(j+Oi$7V|E1Sg>_=Y<3r_gj7eca3s34toBL^kf!Dckn^)Gn_teg3yc zo-cSIA+Fa=W`nAbjK(Ecd*E$Vj`m2`X}93|YPEt@nYJSZ#VW;QWq=&R%WLq<0c;L# z$SuvD4%0;OAhLk0$Sm~j5ns8xxH{``ZLB{3S*wqN7K!`4!1kxVO_@ynOAnay?=QDu zLS*oDD5Z_F(aP2~#MSszvEg{@2^&(vC#9#In%!foBK{CtQ(asCi^cc>0`SRAsF6za z=$S?r-L;W5SM~p}0FQd`wQ)1Lo-p$=9tqa8juOu9F@K-1w}VY4QaHYZUBi>AYt-L? zjF3Fg8#1dT=#Xlv9|l}k6rETv}3-;&{`(K z8(Mh=3mvP>eh?zMK6^GM8-cW2K9& zs=L{$Xtc=FldN=%(#rAW@q|`qB5YL#THq*n?m@m#@&nG5Ifl}r%N02*=tYgKJowyi zByM4!QEVT;qUm!AdtG@f;v#{BhZoM6r-b5%#r*Cs{Wqejlk$TO7(J`9}e zn47yV`AY&i?5v87lkuZDtY*goPs%y)vjXs_3%cC{e2g#V?6_{cM-0KvSrD)hm%HMmtq7QFRP6c~A^h3S6nvKGKYUEK~;;F5_ zefP6Fr9HBK&|kHR`T4vAVG=1yFTwCN!ds`NhBzXY(db7d&4x|{azU@YvPu`qx4^UD z1bn4AKQW)>Zy9zpLEZX-kllOH+?-}ZZ1%2$?tTQVm0a}}e%IZQZGC7rfIvi=9I(j8 z<+=g8UvTYtx|%s3XTHtUg)m8YHgyTTEE<`;?wmX;^xe@9Gw@Vs_B>L$a_q;`ydK5- zQR*?yKM(oT5I3RlylbIDEX*pwLPl2vA`akV(0+Wrtqu#k$use04M@ z1z+s`E`Go4do1Rn&*vjRj((nYcWck{tkCA~LB~J8cmF;IMEX>KN2Z3{yIb8(#{aH( zc5mHlR4hX0GqfC>{+M`ek#O3&{95z|QB?*=*D;S~61w>+0?EI!4Fe zH!;v%@cnJuyls7_Y#=k!PXH*&l$YialM1U-l(l$QuQ?Ur~+`klU@nH3=NQ~$aKJ!EdUyM|mWw)N={ zdEf6m#dqP6)II)w@toe+K43;3Vl^zfHtl=h0i?m+HM6T>Rq6Nz zkX?zw_^cV>B56&q8IQTr5^7#-7GWnbD^>$Zj6K4B16%Ga?u^XsT5C}FOB~UkA2FiM z)ia&yM{MU`8k<5RTWbnRkwRlpjE`nAd!Ftw*HZBja-w?6T#0466EN#iO_@HUd3)*A zNv_N5{n{*^AE1K+WolB3=&1;H5XfT-HtG7Fi(ga&ld(Pb(8MH)_Et@VllFP7w6`lq zy>-g}UiR%vUpvni&7O|OY)p)BLjQ%iZmu&*QJNT9<wSQ^QArVxpsMDhBbCp*enYrGy}QA+0^EJnr0{yNc)1$R<|sM?5EDUNJ-TN%Mh}z zDAPHe)K?;hbo96wnFK|L5LYz>h|L=-06dULuA}!~^6L}Lrr+hmZY49+&uQw$nx8B~ zt*EfI@I96o1y20nAA`ijoO{ddf{=%!-{v9F2Jyeo=ws}KYavaO?H^e?6Nu;$CP+vC zn*M)pu5UMAuXZeh+xzsgtM_1 za6?Lu%h9g_N3wy3lx-&aEO$or>)uewyVAaZ`@D^6r{SCNk*Das^Xkj<*ZV`R;gjtZC~KC5&kfWt3}farc^qTC+&Cf2kf{EpKTach{xopeL0IX z;n{ujXH6|fDH{~&G~@L7XnF$tKu-{VJhrFeEjX*jHs^Y~mctS$F*HsiBZ4+P&9t+_ zNN=PkP=~Max#s?HG~PX!lm6~|G+%t_Ht!spmHoLKJy)rUCV?w z)E4H-4*)ozhLRtY$!;?uKFS)YbE`B>=yfhm2cE1E0)Yf%^z^C`nMNrwhSGL?JxpaD0c8o<7guYzWYdqN2u%3OKeJQr_au-@r+c67foRoe4h z*fDIM5d3!(nA#+7^oQkd`Py2@jSn6aYG}`Hf=;j*60q4sQtUFQCfR4cwYZI}+(C5H z=A=osB$YA?7gpuMfNd8!OlVH7VnC)gFf(;ZI}7#s*s zXR_&aqx*^dygZ!S!;g%DPy3<8rs2+ z=QZD(B~;Gn$!gv)!*`&BPI;XW4WwQbuA6Mz9q<>|{{{2^2LRyj+46-UN)z$9YRm`Oph!YVrZlUlq22so6>l{t+ zGzaMsTZt~>0sAq`S=*{4$?AW`*s zIvTO(Uj$YVk#VE}BJho9zIl5xD28Q3#Ms8)^t`#v=gL%muav?Qe=-0JbD-XC^31UboiMboOyov7fb`od#CgHnE)d$cZ zeR||tcPU@13%WRR=KnEWG2^~Tm;@j)R!|{maNh^ie7j?D!Ir*sj8&nhWs(C*cLV5Y zXAd6J`peu;FlB&o_)npphrsrc?MF5`eKZh=;c=&Q`lRt_&ReK#hMS;sp(&3 z(I*1+xYhb2W((LG&e2Oh%F@T{(_SqixwDPdaL~}R2DbEJ?_X7?*)oKq(?qSoqStFA zQrS;uLAOR+3tp+woG)ifsVOasWh`_KnzgOJO*=A3;{WVUQx_E!@Xh#|waQd-K|LJ zOIy=djVF7&B?vgW@tVmAH3=6*JKY-3zB^@TdMSE~!>I9sZ;j9dM~99rUmsw<&HKKo zXeQ8)XDzq|eC$yypII|LI{6HL?CbSuusC}w7QrjSTyzY;7UAbL5%b^(j}F7$SFqvcc4voc zrcn!t{2@ZI04Ffi-k|h!YiTlPKf{v~Hu2aDD;G#R+@u(Eo&vECeQ(MQL#T1HlsDmX zUN`zbmqAEa+XZ{u%ONcQIxWTxdO1su9)qmMT!@%G-3?VfFWkLf;eRBh5goR0m>9hJ zNR_CW&RFdf&?1zi}8%TwyL= zyuO6IY;q18`!68lZ6%g&pS~`xx%NFj92*G%SgOD--)VX74~SFtHAY!re&rc>(m?FP z`1p~L5lhj0qoGkU6rd8&oGG?pkwgxGC6$FfE~eO9{(8x*x3`OLb%Wx4Pw>d)onj`? zn)vbPa9VeJ%J?uj!gfWs|Td$sVLm0v*LOSTbTOdDI&;HssY3-|qr z^|lP)VBnl8RFK!F8I{-a^1;F&Ge!4b6HVe0AZS6fAhP-S~_N2 zg(*zT`*{6%OtS0oIDc+|-Rt>F??Y@L2vCO5p>ngO zn2?Y0t2@T!k^LMo1}gIr012dvIldEH>6fI?0rCJPEHWy2ipaFYWseUZyXt$&@)v_{ zww5Vsq?@5Q@;3W}GxkrLL5H0@^64^|aOw1;U`j^WmDnbZ^55z$wcfz1(&TA*mF7?a zw-%$|(?Y!{;z}Y{Y8O)ZRL&F?Z-tu}VyQuMbw26z7FBcvu{QypEebV;?Ga_gguT3d zo?iXc;rx1F+I_a-;Zasqlzve3AKP;`J^{aDj{tDNi4RZIdZl%VF0(qP~$;~}%w{u1h zy>8$3U7np^)*YVk(8XX~l&V$YsGmPUd;0zb0@RlRTRu=M?uB(aK}s;CTFprIu(k#)6S-_V*8t`VQDk}s+Jn&d$S*jO}K@XG^J7FQP+ zIZU8uhG27*Y|eKeh_@e>lwOQ?rUlU3+2&1Fyq@TvccG}=Y~Rg#8to{&GW+*LpE$7J z50&3Yk&d9$s$^oDBY*yt#11h13VK1ZeV*YnY-|wM_+s6GO7=yZH}y*VCLkUk^4(!S zmCL}Wie0FV*(P_-##5l0x9%a1uI822<9?RP_6461ffN6f^r4tG!FwZU3<@Hz62b}R`#iIs;y@`iGM))|oNIv3i7`zwQ!cZP z*L5bTAVMgE^d>v%X%LZvXk~6@NfW!lA=FRFGPgVVF!*`Ua6eGFfvHuZ`#LdOHb%}M zRFQ!Zfrt0uz)qJbbRN@hZ}zDyLpiKWQ}YKku4bBwXz#00-`}pAp`sV-{ZS2psy7E` zZqosHu~A+!qKf~(cyz$n*$zOl7wB`L*KV9sRJ|lp&GGH-#UP5#WMeh&5X%7RzSDVG!^ZWFfJOMtL1VH%< z*@43k&5UBgG8zp`7MY`+zw-jUry_Cmp5uLltP@ChyaC4phjIGl8T_f7aRL|`>Oi)* zT3gYwYen@?#b!;m2V8ZGi@k8WAwnV)k^u~|dYVMZAonkOv?QT%VXeB@m{Mzz$<&ko z(!9q;?#2y7Oe&CPmERaRWzCJ;r}J%gUj1$%`>+|Xw*WqllUY)MlQcN3O}TEV&GeZd z5iAyD)0I=Zx=k~f3E-ipmN_A~2!G&crP;Bm)vLWSUPhCU6w_$AX?B!7S~FGU(62cX$WJgWl=vm61z&|nXxmREzn@Wvw6}@Exqn`$-3U-s>@qM& zl$-0PF7_VIVF*WLjQArHY7av7{J?+O+Zzxl`a1ILkUmDb)AV$BP>c)Od`syx*<*KU zwUl5?gGyzw;If(QG@p6={&)U@7gd;Cu<-MS?OPOly0Br{9g25fa4Bu4)+L{Rl7H3f zxd?342!4)SpolkY2QUV@0MI|{Ep+d;hA;{|Zovr)36P9$=IpZ3m$OhtYMNrkUcSYcY#?j@f{ z1U)9^+gQX_RVy#uH#N`=(|+-m*xXo|xWq_gDv}xH=AnLKP_zWe zW;E4iglURaC@RZosEEet|MA)Md!E_dJzT=gVWCA37GEaU9+}xT%^(W@og2ei?ytTf zy!v>LRI`10%dQ9^?6_94_#4jusK=3Zd%Ou$-J?bq9Ni{*L3N-SaFfSw}=gF(MDkCWtpD9Jy)vDlp25f$iLa6nF6}6$m$m4X6r-s;wVo`Gbowq;Iqd=F-_I@kgMmQm zX8jroJ!1l(LV&{t8G3kpeey|Y^b=cyyPK$yb56uFe zlYp^=vN36z35|z=32B5t2D%aaY}I!>2`RuimwqUh8hdagl8FwlMb3M z&z`z*OqN;A!R$PdId5z!u=7DY^6wC(^FqY}yng&$X~vqGm#4+#-y1RmGAK^gv8!j$ z4gy&e1C*jP3|xdM7ELwTCiW}iAE)7@L8SwhA?01(MY-) z)e}uLsh8#0bF*A}NEC8f#xU<=0pN3i6^VMQuwSF_@@9N-yg{XxL6)C;cnW>3>1~E~ zOq1tqrCJ{7N9}zbZWK?(O=ZT_$mNM6O5%(6I1C zx3paQ2F(Uh;<$9W@m;rI@a8LkhqGjexEtYV>-XyhOlYjw1h+~WwdCcaDe<$*w7gyV z5|^Jpl6vEjHp?ZXYO^{26lcCulTti%Mh0-)rcF_VMKwS>_ibbqDYLU+LqP5kBv^&f!o5%r~ zTb2@MaVKbPWOO7Kt8`&Yaryn{dYv2Yx$>u79olnc?q8AH?dG!5o)MFUv~8bJB6O+x z=>*X;cWn#Zx-I7o1zc>z$ZS=mHfc6*C#*L3&GriaZWuvSg}?kaDG7er2zEGIJbgL2 z9<@Kb zCj&Tx2G0po19PYzw#qB-1R4vk_K9f3rGwWFCrrrDcE2BuoU)T#gyQ{H&uzGLp_Uh? zFpZ^wzLSb+!$;+;tHOK*^)qRb%RM(?-%BSh0s_F22n(?lG7;-Y86KW@uOy59Wih7* z=n1d)cB-1aWpSmPxVx_%9mpncFiA-o=J73N6|4mWz+Oi-#;XdTS=gOHhX>Ao5(+;^ z7Rqf^(uhAT8rg|Z>FY7FjznQOq1fly=w!ta5lUtF$y*pWxg_M8PQtkvt+v)$YRXb< z6ZFl=#Q6t)k!8qLFr=&pb)yr!k7nCeQpyr{RK6K3JaVzDj1gpEc=Q_SpF4l?UrIj5 z7d_R4+>05q8ZGZN@i?_$l;>Kar_ufpY9?3Z+HCi3Y3t(qL7b-9ut;R{-5*O6@7Kl2 zZwBN_0A~c%HDR6j=ru!w)wHq~1tPEcU{fEOw zY2}kQ+mZCx~c z$7rN)$y=ewDi=#X%Wsl)Mf&=eCgfsfSI9Nt^_nJd|Mca2_w`KZmSZ@w;;VM?Wyj-O zA3ScwbpzmbV<|zU!v)O(|GKnU>SU4rv|lLrEFyqK)(Ccfx!J!hk|^TJI~kaZAK|4s z(y7DQe0mUYTBgv_wMih9ZGXM{&D`g^jGB=^!t3&z`E;|(&uX)YGY(NveHa;^C?lCi zE`t#%1DFw)r^qUE6Jv8rLRzNdhLdJJC}M`XZ*>@6Y%{o9IStw--ES7!d|=AEnNy>- zkbr1$X3qXH|L$WZ7WnsJvF}xlX8N52sN`pvwS8}p%i(SC?Gi{p%CV~`HiqXx@@dKr zX$Xr(2D|(Z;BgV^RVM6nCXrcg>Wdg5&`c6qeD3<1y(zrDNe~-yp?Avo73?2kT~s8t zIGl%w+`oHyGr78z#q9C=fVJY!&5?*fh%jCm60jETmGzWepAH3JZpJ_REJ`vq#rkHEq zyXOr))%#312fL}di1&tFZ4c|Pf6>G<-GsY}+Sp)3dgQbPWp~Gy61O0F>QJ(;5vR@m zd`EF%LMMu*{{fM$hLZGs%~yTgkGxEX-+oH#)j+ub4aNv#=pF7(EqS@Ve{oE;8s1m4 zkCqF{AI=WruaR}U4k=;N8QRnSSp+#Q^m`fXdO3*Wk~=4|eG~X@XH@eRqUdx?0oh#K zO7wI3Kcz+KOxLVZmZf$fE+&JC3?$%0pdpoJ4?<{Ej6sYo3H5<}O0yO@{5W<23DGK!=`ME)y|hIYU{y-FrosHQPFdundM+>_dt;_nj2<@aizlG7nVFScb)n zDTPUEoEmI9-O=*SmUsgQt(3P9bN$AO>Yt)CYsOuqXqaDeQ8z2(2#J#N~!3|2|mBm|TGBY3rZ*G}*3CY8P5{ z;1<7j2M=^P+0F?>tuD>_g0BxDPlfRDgW8^TM1G9cWFKzlS$*8ifMFVwVf&WR!HTVf zlL^imDEppv3m_sO$PsB;##iJnZ7 zEntB?W^T1cjg;mX(1c;`TMuzo6X0U!)P=y52Ynns~eYf%$k zEek9;Ox6)v9TTJS*p}qPOBv-z{7+DlX*198&V*P%?$nx?kdNA@=^AN=s67qr*ieO!t68>A;>#;AQ86>!OgZIUi{tL(wBGxP@0aK2bC*A` z5P~Lnrwi31KwpAHo%FS00O%U1NCA(3wu|dx=Rrsw|HBIz2PlJF)EVzB2r<#~^DV*R8+*h?jikK?VIvq5 z@DWGt#QE!ldIXV?9DLWeX$78hl39+U^5HmCaraxk)6 znG}hn@gsr6Of_dK<0j^{y-MmYOEtKrGbxZnExFWb5e}EbUs2Z za0fAT;-YtNt<9%q0@mZ>AL#z|Uz1=k{1$3}lT^Em`w^hEgxDYF0^-_uB5e3?9Rr-} z*r)CL9*+Pr2gpQa_^OSl2v9{v3A6cBhCIqrmf>iG99!E8`pJgtaz+=19~QW8!V!8m z&nb>9@w4b@=WF8c)obVWBiIBT+2AT~%Kly>DmUH?FMHG4dyn^kM$W13>uhHy8xo|U zsC6uP&Z|hX4_a6R2>WLw{?9Q*1ugfwA&#YB~y6twBd}Jp6(-!5$Xsq!>R(OES`KVTLtnirVV`Xf|J;j)lx7uH}^oHRE`A zoixq=z$3&0l36xEwjRCMZONmgb0UP`(IH~%%hSNi8_SiGlLRXw#jt-)$u08A4NC)J-r9=)2)up!_K4;P0bROc&S0$rpAk8hFjX@R zm?yUX0ykJW!V5X=qLbI81sOP%&s+YD(or%@r-zpt*2wK*io~cxa)1-CfJUa`y4w_I5tjxc12a6{3wy_TgIV^Tqr&>_hNnTb*iV1-?weMdu#b-0NfM zbW&7BEeF(^T3ia0u69z$nf2Lqf4B*pC)pl?x@A;E&96# z2vgx)I{EnO$FzLC_FSAIRaO4$7UF(kd9yWs1f2@9Jr*_7zmNbpG#&+HTXb51+je`wk`4p__*5&{UC7zTS-Yoo|ve<)&U zj=rU?es9y0GcMfye6lf@AKjtGFUHr*9x}@R=<_;}U%&oAM0DAzqGlz~%iG&q(zPUJ zjeK|@IALqM-GrkPH0Hg=SY(Z>QtgE$H7F{|uK7IZMF<$Jn@;OA7Okb@>aXRE(eG=p z^;OMS#0d9&9^gfD%yQ%YTmiaNeGj`;2TB%16cZzO&yC|(lam==A8G>MGF9*`zws z6WZ1C?g@9E)8NMy#!w-&A!+PKRV*9Ht*<^oX(g*(t6qC{G#m(JnujS3|M))>CJFTX zWYHWu0?Xay=QZFUUVff2Nk>#dX~bd4D_$_j0(%53Em)~>b~?4YxshYlJ4!FPJc{5aO$*qV&E$}i1oK#=X zJe(@07<}2>d^qd7%kTTePdD11P+IyN{@i2sv{>^PFf{JDEa*aDV@vQ((;KK_>&PuN zB_);c!u`pE#FiR&ZQIR!>3uFYeU1avKa)?)N5ITni?;Wi(ZrNvl_@F8Wkd)%x3c0a zPCbvK%y$Xjh&;$~S1Vk!l#4=M_AFa@;{G}ki$AN_9fEn8fnNOr;eEJoA1?0_lx6K<#XXo{z&eeK}A{G47G8}Y<>|cj z<#+B4^!09$q{d#8ro{Od*nSh*=#jc{SPv6%*y!9Ej_!NSmn2J8Sdu#4+Nw$4l|3!2 z?zx!dSc?)a^igTq^nd*u{@mQ%F7he?5yf0PEi zcF)bKxwv|A+LOG9w{Y!9L^7$I?<(VcJ${qD`qekt;3R*I0 zGxa~6=FAE?d0sO0yDy7P4J`_Kip)G&3O@UDzJ0a`g3CuA|Fyl|!M0!8aqhM#eYz4> zobQ{tsAaF*TxY>UAvg6QR}UMMCgA2vVuYGrV`EU|?)K&rgyt#z_0T7-*yUNc3el0u zm}O)Yd|&@s(1XJhT zRKBxCGw&5uGm)=W#0sUgJZKcMMT@|J&CX}e2*X6o-K=$5HRDW$yB|Q=n}PdY98H0D z#b&oA^)8gCR?!iL8`mHov;31p9h{D_i@}d<%T$M8G_m`UHdofWl|4r)Z+fQ&+;fNrX}uI125Nf zwk^i@-bJM%HUFqfuhTUMHMQn}nDhZcM<{-1zb@U|{F^Ar?;5#x#5E7&5+uBUC{U7&pLxitOtr>JXKnlFUqXNNn|p!SYkWFphk|#+wpU#B#gs zE<@)7!E|qk5!15hEu~KOj84~CM9OP%KNpt8Tq)UIax(Ya8uTT8pqDQ3Vab28Le_k~ zYsEqZP<0pEUjf=@>$Djjjs^Nnv_RU{0aHuA<4cz?I~v%}s0Na4G3-p9k9KPy2O`1l z+mxukuzA9QP7q*yt5UeZlUuR;L}2M8ua9aFFVe*Ky76UZ%5Itys-4WDF~R;w@{F_?*^sTf6W7I90ZN4g>Jb7|LARh~h54-{XlLZcDMAgVa`Y$Rp|Wt@ETlcpD_nY#QK`{u^VY=w##8t3=i*`AX=F@} zy>LP_nwG%xKlkVK>2Dhb2LVDiOk3LS#{?cnqr0g-#;H_-N#dvp1-D0^sZ_HMO-G`_ zQ{u(_z)w3GLiU9}K2;8J^&RPOWH;@%Lsq@+H-wTZ(`Tmg$9{9tNOZb|Vp5!*eE1f0 zac|ZCDe3l0+xo&Y`Vc+AM zgBd^gNp^5L=%)dU%f zem7H*2mXVx)^<$`Svv>%_K$7l0*Gb~Hk>_tzhLMy=Q4KGZiGoteHszjCxet7Y65I% ze^grvQ&Vk%FX$N5>v)1yvQ3hDBgfkJPP_enzt0mYG=a``zOVlB>(ebC$;IBD zJ0fi-rNV9<#O#A=e)#;2aBdpF20tHER3n{%P=`kHOxwBGh-a)_K9Bo|XpShk!g&O3 z#6YrK^Nl1GYbq%!+dlz`xFMZMeG+MyD@ZSv>a_WU?|DXT(`9>cv(^R+d~P|tbOb*g zK|GuT_IRqAV{Ljz>tA*@xOxi)x{z7r_#s|IUoPxw_R0@Fi+rgp^j>xN&rdI>Zw={~ z97^@iB#%^$n8J!0n@vGjx<492tOUc9+yyt7i6x7;IE=GgXLDrBijTpP%%G=wUhFj5 zMJ%67qyee%%h?h6@27SIRkE^F5#T029k07aN?I5pktq69gUiFb6WD@JU0&Y8c07#! z1Wm%7C^G}gk1RcP>Kn+md11u)`e;mfYaX1H1#pA&$H$`Fw*? zrBKL;7k!NKv5z6Uo@xSHp8Er6^Lc#4`7K=7H@szntvYv66nr5pdW*Fg{4BN^Tsi-f z*#nM`Z58n8Ul-(-9EuWH>`z|x_?R&bE;#dab%y2UyrrRT@RdwbgCI5DJg3SZXr{A_yzYogcWq-usY1K1-N!WEED8 zY-zVbI$~iW-jgspKCQWH(ID`ha=eKt=YICR)fVNix%}O}hbgh!-fkAlXtX!~kzlMfQhMMtM&r9%$rb+L8UN)C;Z4yHl(e@~DY*hqk4F)Z*er34=nLog4clQRn^pC8}4Ok6VR$C-BYXxiUFB`f<0{s3%a=@67sp z|D!7vVz6+`Ep-77TH_%ky6A(G6qfL$S><$Av-;4rebRCWTzg{W#@t*GLXfyL>xgNOs= zb!GEz@uSb@#Hgv~X$hW@+9kYcNG;w>{H^aE^tafiuUAOOte2CTe$j`+IEfEN&%ei; z4)J>e{`yMFgdFR^L`7hazvrT}_b*)-yFV(?nBd~{Jvm>Fb4T{l(pA3 zAq!u(KbdaL69WQ#e;D`+&)7WlT{RW&5#N6?E1N>JGLfs@Gdm3mIL+>R^?r(1?K?@y zwo9Itc)r?>3NZ->DR~Q zKbzy|SKuUNQ*{*&0l_@cFk7{w+`@u*DY?oAziF7*O~R+RYO?t^WB4*>v~2W-$}t1A zInt99r^_M)H6#t#Jg70nwBAVtx6mfxC@d(|G0JI=j($MvgMuxDV^Vb zPm6K6qBM|;OP7(7j1-cz67n)$4JY<@!V9>#Ysn85N2hD|CApayGog3yOeG8Q{R3c@ zyh)~Wf@?X&X95!ARZB=41tugWna2h^ME!PnBt=23)gPXx19IY-04A@8eHV+KyvCr% zbGQDal3O&i^o)<_C;uFI$XX_Uhrc`XonKt^WzyB^@63n_U*xH&Mz}7N$Rv9gLzSMF zyW02ECi$=+`Kmg0Ht>er9Qa9@6(0ahDwgk-{z&_`+4Tu+)6WO2|Et1^x`XKSd1H-P zb?r!1zVB(jce~(yIlf@ebLqB}PERu3gAXk59?s!>OY_Mr7-2A>R6 zaurp}_0MKh^lEz5_8?=VlD8h!Y(Wz$lS%(B_i_+~_jSr2z--0qP0V6lIXI}n`~?wP zH>2U|V~iLg*`-79>CwEpsuu1b>PSEMD;XY3@HJxVQu^*>x{o@KEIghrf~>$}Ems8~ zKRn6cNbgvYX}~lpbV5_Vz|<$@zgN z=B~?vpLyT5bO5^hgorfgy`lF;W2kT=)U^tWS<2|$h0gVk4oPwW(q>MZpw~jmLtLOf zmt8pb`BBy-gsF3{Gr6uzdvbATV208M?pz=)EWS>Iod;Rb+03rFfAHjz;ihh7tdv{& z5IE6C)a{ob4~kJ?9)dT6_K$vz#*)FEKiifdI$Wrsaa%jphlJYkRf5Op>otED0tKjX z3`T4Dkl(x8kx~#3K__8s}pIr zbXF@%fAybcx!*Fccd`1H&M-4;#tHvL>@Ishk5Q|j!n!JA87qT3G-pP{pMSsXtgxRZ z%O0-ZYxZ8>jE|q2V%ME^`WLTVv^s87(@7>D+=RA}s{z@h2z>A8AJdCVg3=J#H8~b8 zsv3v2QD^GS6ch9YuPy&B&{|Rf^kes@nN8T7bKj@o>4} z^!0yDHr@~ZTOj(#Z5{1++hQV}@EDQ>dUZ|rBWy=}&@qgq+EgF-PK;GvWfI!>Mk^*3 zla;E=P!G8u`S+INXlx*>5)nYm8zu(d7I?G}n=%Tpunmc@wK7Z8ud*1!(A8t|n5*eH z2;O5dJ&t_r{4Xv5(ZW_BT=4Px#*LdQVST95%%(CCD^>O<20=JsR4JKA!}$P=R#XiJ znvEL|dVGuV$DadI*VTEDX3wTy4;d?}EwPg#MLAoJAc-&D$l8(g@j{@C8d;tca}P>5 z)N_$ZHS%w@v0LM+XAY-kS$eiyJ3LSLw4FKu{(_y8`K0#RHw{SYeVA$S!j9%-#q51d zOh0c(oWVg$?RRYd!jCf`#DlN3He8^Lp&3wHhxQWY)2duegg}t~xM1c#?dN`^GBC*< z^CQn67y1RK_D38M!cZgD41%L|K>Cd1M!>1m+0ho2B@2Bc2GE)b)n-Tehq8ukoryV5 zRQ^~19LW`>SZKDONJQo7?CJR;W7v+yg(Az&zbs^@o{wo2@!;{0C-*)44N#Q}agz~=??}GvIh!#d zKqdt9yWaYpQfQ_3@fV;!K^vsmCHjH2gq2w<(^#9qPJ>v7!;Jv3IdR_MuE%&ea_({o3kSNQ&E$S%nn zGcWVML1aPd!APlC6qSzll$)29^ma`^KfL(o%~TJJ3r?kV{E8` z>>u`sd#)y@ioMmO>SrU#uldZm!>YF=TVUEp3Vj`Qo9bzgIaWGcKXuPU(!a@8G0Jak zk>mVBj_JHA(zFasOk=a+Yo5{{<7<%n{gMSQ&bMR8=`GV9N5pG5J1_QhlH6b-H1{pn z^_w5QC7{*pxd*p)$~!AwP)#pb)-uGz^ke6X-micuUx+p8&#X2+vq|>-Ual(Y zMnmRgUNlq5w{JI>>zgZgN3VmjAJev(kN`{OHGp8(_1>$AnIre}`~5Cbr2ocl;gHHz zYrm19cAV%R`sxzceL+)<1Lun0si6GZn=|M_RTi79PP(F0){(g1siT^ohKD>N(y#pt zWde;;GF+J7GMnI4*QEG;i?k-^nVL)Q&P#WpJbJjZNu5<3Wf4<+}x7Pc;&wlpa z&wf(AzWHMNMo8JVCrp=;fYDquw0N_{NG~B&j!?s-@YyJ%Bv_P!5}yDYBFu+($Uyvk zsGDfM)Y4A!nFzh!2v+E9GjE9!9dS;@?LQJmijO^jj3KeFBWSqVucz766vGV%o|;)H z8|CZ^AM&Jww7=4pRQ}?{Q}KV|wMa`$9`bYK)>9A-y(Np*ZkzCXxP8q_h`G)ySB-e+ zyN%FZTgeZ1%rcs?KqJvciR7gmOUM0|4ws*unyMTaWn_;C&nEbpQ`Ur{41JvjLzFW` znBAa8Ji;K~Q~G6lXhLgDhQpVW0%t(d*HVCDUw8vVc(AgN_mTFgJ@ZRilJ#6kv2YS9 z7~qS5$ruh)OzV?N9%E)^w6?}Ene^qAPrK(*fB{)|@sIYIZ3?nUU#W8Z0r%#cU#}Mi zFd15BzjCuB?6(;qFJHF$p6{&{Er?}vNcmllf@-hYV#Xc!ls2@2&i%;LOHxMWP`5Dm z!x2slBhqhcplVV+^=_iPwL{DA`8zEw;-D+R4`Kt>+StPD^TdXaQY7rdu^AQasEhrX zc*gz~`DBbtZm>R;N zLQd9zNjGsJRF)&kdBUSs{56n85s#E)ZQpFL(baUSL7g^n-AJqQyjZNwQ|W#49-cFP zXcSTV$rf+n+jdNHSGHOVQarux;Jfp}-}jeWyvig`ti&U^{JFmkI}9H0y-*T^g82u5_kZRl?@JHWB#%av zE)IjXIWY~m!Ec8L8&srhZTRWdCZP96cRl0UV|6*O~(Y^4fJh-?kAy zo+K+Uq*m$0f?qXs8Xu_Rh;_V0TIUk&& zAviu^kblR&+;Z}zhjT<A2?w#02a~nC4{_<=_s(7E$OMPvVej{Dwc9NsW3mB0|q3GABL$lIalL=uphfU z(N_fcdUxMA>An;MkxFWP2b=Vh#ppjJoB3hMXEfr1;=7Zd5%7huN7AVqOh;!B!Hzzq zmTSHJ-N%l-`ZoR$6bjBNKyQ9%cit2DvhoHpNsjK68)gl;r`%z$7ROn zUmfn=39-rN|9tOCnK36xE8;A|>)aHdiB)WBf1`-RFNV)r{PlXDl*z*eC;C&1==aaX z+#*7rAYef%xTtzPRSgt67ZVMK%zDYY3y?|*zuk6O7Jr_RB|%D-FrVhaDC!J^U@1~d z=>I4zMDd`!B!JLgy?1}_-_uGhcLaKPOEVD9Kb+)0jNL4M2*+m*yk0ro`idD5S+jl4 zxRn#*FwwvokwwQ?x9@=pyjlsRWcrkak)iMoiS$SQiHTf^Sift)G5~R@d&KdLn6F=H}O&}C9=@WEb__wrSB>b zQtM_xZhIY(+V7dsL@=1p2)E>Tk;+f7k|9E1d$ED9Ffrefx<;jL&uOAbu;au0z=Ura zY)AKds@H_2o+7xEE_?3$>+f5xl!ZlQu<%=Ni0&9qp_{e*!u6z^Y{X|JrKsM>%ydND z_(7lqZC#3cxP~zO(DQA+Ld0g)u*N{R(c!f@Fw%?@#sR?k@Lt@qLRY}9z#IF;cHo#i zqs;xDdwwi7#Q&qW#V{Dt>5z9EZ(*X3j>8AHd*wX+e+(*`IK5!Xob%e9k^1sFK46_% zX?3+5#~cuCDPX9bnx*~8m@|fKQdrbi4FD=sQ^Kdur2DgrRfe1PGBVVpUlsD_uC_9D zuRXw{L%LJ7qW40p4PK1ENjt%&oV0JJp4{)YEZja^VltPOIB7OBACqKpCgu_tfX#aR z^+QV8zE{bR-EmqwTeA@$E#NhFov*r&$L&g~2ypyip_$WFQb*vS_3LrK$1S;a6N>ks<=P&g&ap1XVBk4+H9WUAY2d=J&17YH7Wa989h;U|enGT(ytgaRh~^d;dfI1-e3N?VLv035iEPsTxsQr|Ciq z%r&^pORn`Pf#SB~-&>eyPgm{JZFnZWst|>qXoH52_-ijv z|InymYq~y)g=2{kzi@{MwDnt9uJjF=uVEJ?lxSdMwAOK6mIa#%6|OS#v^O&F#qX52 zpU3DA%V}N)?7MwYQk;6`!~arpAq`DD7_TOtSDm%Z!Oa86#DqJ*j0tnbEW%JwLG&|{+NAaY&f9ldSP$jc{rf1+W z7OH}(+=~0wJB%rU!c+!&q?x8imE=zjEsB!s_{ZS}ws?3qP~Di%rL?|6j38wNus8># z>enN{P~E^`2EJ>X_fBT6Cm`o>K)_Vo$lU!>pTq-0@L7N}1y+_IwKD~BZ*FeWwgw~( zm?`N2f=lUzbMwc8ZaMP@2J#sX6QjNjzc;U920{n3V+9ILZO1{hjFb%r6ciM~ShFrw zyVybt9X0$n{$H_|>SC9TZ?Lo-XRDi){hgoh zUQ=EJt;OFF6A!?OmGlIlgxX_8m{)ei(Bv7a!y~9zYiCJoC`$Ewr*`11ffP`wkKXxI z+@q+jIA>FDnhxIHuAK+|zPN(TF=u1@UT*BHuAfY0-?+BBBMvQMf8HBa*s zgMo5?cMgGzGJPk?P~dkqGP4E)W%Bh%N#{%bJ}-jy>BFYGhoLi%HB1EjYsK8ea&f1Q z0miqkRX9RwMM2dw<3_GVfai`nQdX_#X(AUU=gDP>mvo@{xDu^^8ocehtHOnQNLNCj zVt2(lq|2FNXj;#-;%2T*%2Wlr&}XT2C#~Y5#=(vv+@~#oyZZm76F;(1z2f64Bu=e; zpDT+MYWMxk;xl|O7YDFzGBc~}Txnjkt{d?V@&&w+Lkr+YdYW#)D0vv2iA?f1P&>HU z*x}1Q2^?;YzNi#bMH$#?udi^uCetG=`~9rSw~II@u4N_s0<<%d)%H~BG!ILpGKR;6 zi^iQb<4=oV^#-oFe(UE8Q_kwbx5=N+O!WucC$@F<8N_YOHkbTLc#3K<~2TH}6H8ho_8A-{CeHeTUxcxkOXv~(jU?CX)N6tmjK5dE3fQldSe zDOi!RZkkmV{@(I?L`S%yW7`5X30yFUM=A~N1hl>NMZzK9mOJeY_VQ+Q2 zcOrA$+IesB1$)B!d6T;@7cK`W&NjBNWplvxq>())Y#>`RN(1EMx(v%w5i;=nWaInq zlo9T8$XJxBHk=ZIRQuElb zz%%6<6a0R8D$^Xbu`mPSq639Rhc}2TSo^`&NPovd9BYVNfup&XMRq4d*QENL;1ia; ztIko`0HMO&gFt`FNgVUwhn%>~n4f1Q1lr-T07J!@-Mna3YSL&RE+#5HQy*DSL@6xf zIlHZ!THSWBnbQBmta9Y=c9oO+%kM}V{0*|4a7P#Q^-ZVaUgkhmb?vs>pRYlANLb&L z#G$EZ?e*TmfKn+SBO?d0&hkmAe)osZJBAJjD<_24vQ_x*a>)dgm%Ge-W1o(oUBrA{ zg0lN_C+VwOMDekYX5zvh&mDuG!6#PtMGsf`cdNEF*N6A3RfmUK1`YZ%EMS15$c4$Y zzDT;RqQICv^HPBKjju=bMRDkF2@1@FwGh4{^wS^LI4u3?Yk|$pEP-)V&BF8HySVIt z{SRNp(z$RZ9|H!}L4zTt=|2-?Bs+a7#S)`>ZLV&U0b>Dl#2*%3@%+fy-rc^IXvWs9 zPkklURqX2M5vYy@0D(D_0PmHw(XilwE`t!=ISimjilNP($j*mUBiXC=t#86ZuJI_U zT|+-QC7P~bbzQlCxZara{av0Xb@iuvt=1&()53iC%$aV3b$o&Scpeio=;kek2gReg zJ7eNY(r4>dI$R3AIK6axkv}eTf3$Q^)b&5S6&gor(L7}*D!LW89N;p_t(~~}oNq4g zLR@wyl~91{s7EX!2YmqRVry?=9&mqO9YOMN87%oT3bex|^m|%;r5k8V(N)&12vbC= zXRer6$Cs0LiSSV6JWVR)rW}2;Bpg>p*Bg=1w%+v#q)kb|HKd}h!~%O&94oL5qx!3N zphjkp!Omkb=1xIBB`c4cRGf?ys$`uX5rp#!g#m2yp{Wz9?X0@n9RYX9>pqiNmwXT)lH` zXV>+FS#x*?b*T16%G~XBznd1{vQy5^-^zkN&ydqEp8Dz|W{CEea`Mzfoc)wcS3NKc z{CRbMSEcF7G*+25N*RW+cJ+Pu@IiKE``8RDtfwnFCSkDsxinRG#v)ypqf*>B(}LY^ z%&#khfW=#6!G0_NZkAYI6<2zH)Rgd=@XPu}s^{2P%~QOf(AO`k00{4a{Xb8K8Y+wn z93L_= zQ0q}lHU=Mj%8K~|tFP3fYCf<6Kq6Fc^ox3u7q`EdB`SZT_oL!w(97=7hBh?c5Q4F* zS}PB)`KJ4l;!c%xlLgdfr(V3}n9{wbz3wReg~8x>Q=+(?=4a09MhMKrcV-MwaJl{L zfLAQ&BI<&K_`K}`e>@7mo(@t?L@yPxHj{Fk%>7 zSGRb?z(_d8Vd3`7mXGZ9%oz>!4~VCY*~k~*IzE1^!sl%#$4A3bpYeVIgE|Bjbg#CZ z5U`Gq=4brE^r(bRIE#OJ?6l9yq&&wH8WQHoReg{9xo=9`To(7W4+@?%G;w#YLxv`@ z%_^R6ml)A?9XIg0rTs(%c^nGM8E+JTeBy#h> z=fe=Hr}z-bZF6g-%qoFzp1fH^^PxTo;E-DuTrloXfHL4p)@v)#y{WSVcYJhge_x|2 ze@vI{EKui)*OtA={GZ2MMXTnt{?G71d-(ZOVxH6IME*gV50(p)ui8{v^I984&&1na zN}wZ|#R6s9ydsP_awSh~vgtkhPsaZ`4HYK6VpVHH#EN}E{{^1g!%swXUM&TF!RQKBK_7{=W zAlP6uI-JIhr1zDq_}y@veb}+pW>ql*rLC)Rz!2>6M+|+%Ev&_Y@|8d9P=Jx<=g#GS zV#Q>}#z&?bkmsj8cye_Ky7ZY27O9IurjHAhjwyrvVoH_p%pbX~Lv1L5ML1M=3DKu3a1JbR%xnM3&ccd}f zcJr!lYcnmMQHsdREm}WWHDw#9Hg0Ug0B%n%=mJTmHN4VKQ=dKI2Ca%Ue0{vk$CtgU4Aovz`JN5uEt zU!81#8L9|pNx0~@SoZ~T+PAsdy)g(HMk~*0`D^S;xziK%dem1E;KUY-9Na#P8Jq@R7GJWCE=2b=zwnaYGs^5_;`Fk-XLdfsF` zb_{%%BgXP&FJta%kyHG$?RV_zOo^nYm6ky7Hcbh|*=rSb3#%~C&};$z*QK=2XH|KH z-6q!l+=~jULWU4-2~~(%T*Upj_LujsVQ{;N}lx6mE1@w&#N>XCZW;ko-iT8DOzYM($U7qp9^{Lf)k`KNVI66@opyy_-!d6`h~cFSfbs^P7h- zF&!{J+4I`HAC$Sf-232tF*b}$`PSa5lsd+n=*pK9CXuS| z6;>mg8QsxV)caxP+%o5s>_o0X&W43u3ODm&z7n@TY@hjOozGXmbPtTaB?&R3N%wPw z=BjVqqaS)dzK&ijaKVj^mRvM9R#)SGk_}&#EAJR;Pl`YM9T5%dZJ+M%MU(>u#37^xA^$qCv&-)%js+`FK^;MXLq3e_#M&$G{-& z{wi@f-&Zd~pcFV3TvM2xvI`2Kin-$*Ot_*X6kH6fqRVNPXwoUUpGX4|ahO!{~wJgY4I zvs%U0J;oS$xi^Qhee$I3^ciE`Z#W%GC>G~4@GlstEwx7+QRRyaE}`JF$0UvwTjC~y z_JKRCePCkpkqn?Kh}OuvL4 zX&lHJm|I#tT;DAhlUn-!9SgtlX)|dBysK5e8XktLxkK_Pno`T_>2fI#8ngGEmX=!s zN@n0L`~S{|*VtIy7RZ@U8Ix_9MClvmk?!%_i!Kcid|_eFip{y&UFN$D8W&CQNI$6S z1hEh$m^)h-LeiXZ-G6nR+bFXP$_ivKxYhqK`M$;RIr5b?tUUi`&#lsv+U9X$rE@(* zV0Mg(RH#sv=}ffr9Um@$&++5U@UZ_<$(gP6ZmW@1U}mO%1w0GhoTy+pH7vJf=(Xdh zSMN@Xc4}lkznNTh6YQ6bW;M5T);Ey1F1*5EqqIfUsnMv<;rR70u`YHOkZ1cshjwcI z4a}*sns^9CyKA&8gI2XecLA$R_OErKT)OC?%nZ(6M)yaN2V({OPBXttFDyLQ%jP!t zv%5JRS?8&v;Vl7X@dm<1l5I0#(J)M+XNSJQ*#eRyQ8ewx+<_U;k8#)P{$Fo?`@=CI zRzNvaT*Bg!Us@6e+~Oi%YJr!OoJV~Gf9FjnZ(uZ4ksKlgM*xpVHkReL_Io||pkK=o zzn&6@2g#2UNo~`9w=12mUASE}kn3{E82!qvQYmh==6Ru~7*GDsa^yInOGlZ>Yx+MQ zfzYEgZG7a0tu?LKXrHwkB{weYI}S(;rstaQvZ;hc@l6z4UTX}gSl1i)L>Cy`hqU`> z4mV7YItx~#^nhjivgl9I%n4J!mQ%0KqKNT(OTBh(*EQT$R1cEN=rZ8N|5|TT&&FbU z7Qnj$8z7@7&>ZgD%FPV37&ULp3hiF;Ha{gbC8gMM34y&0#o{l0Z7r6bmi_H-l8eh; z;ZA)9FD3EQxA>kFhVYiT)i@-2KHO0Mh7w;}&kJZP;??-~orbf{rwn%d`7w3~qTBqN z%J2d@sB`&K1XWIC;M^w(CDw0OKjK1BzRi1sKQv|%oKN2W@-%2+!YDG`Pgk*fIr-GmKEjHZTUS5mZ z}GFymQVz>#A_O)mJMNl|yp+J9z?vp`t zI6T45rQJ|s)^yhx5pr|3_NE;!!B7Ab3JCJM``7;;7<~>Z1K&X*&!c4g#rjiiFMGC` z_dO+~rc7%)S^}1RxQkg*ZJpeHB9RH1p2NKv_JQ{B=ILzYxpynm;NC&AKF72ZK%;*f zuIL0+&$n%ffbVQE8V{*Cr&VeyZq-Tybt+s`75m=6)i z^Sl=sm%~%`>9Y$cTWRKhwf16eyVsu-TPS5TnntIYBz&may^Kp+lg<#|wKJ+Zm$kxW!SU$EKwhtRrBPEj>u+w~i$3-gk zEooxTsHd|+?_#LHSuNe-=ISZpl@zz;ab^BUaze?G23 zs})@2Z2A?9;{CF~ih-3bz6c#6>s4775C?=+0A`9r>*BlVhrCw&Zb;?9uiB$9%o?e} z8Z9(oTIu2);1wNFlR9K>FwB+S(*v!4qro>SbmF%>YdZLKU;^vS*0-5=tjMskFcX^% zQh8Eh@OPnSMxOGLb`(Ph21$3}wgPH{6L&t;G~@nrBRD)9M@Rk`v`%V*)NhaLi|^8f zd-K)v;H%5xiBHSfI`NT%eljBADXm}Ya+_iaAJwJwYkM4W(|A=_FC8kA&5?W&D)p=I znp7rkWA-?k0pV=1xX5MTZwWQR*#{``HT%>JP>gO_$QFwy?1U7}X8hk~$QacsOu5{I zrgSk;EQ2ndOf}_CRqLOt6;0o1!-oABw*xyfieMcoIW2kYd;iX%wZZ;g>#~I0UeB_< zSdaXhM|&;tcPT88q|Kd3P}(yX<#l@%TEv&xj_~Vz(})3+VSC)&AhYGe@x_wG=&!&2 z-5bG20abywd;T(M`S-UC-sULn;~9iwNbn(pD_?r8kOWfO`D*-O_{U@d(wiiz^}y$8 z*La=<+H#p^!pCOG2RiTdjM%P>9=j;DWg4ZMo0A#k{wBsUNuG2yX9OnQ`#C+X#q#{F zP%H3KIr!)d<*~X%nEg&VzhY*D)QMy-w@F{vZ*zIDk zb@~36N3%H}HCvmh!*J$mdb*K)34)Yba9Q%{mhP^2d}SI+rsIPs$gk$l(&ggFmMCa_ zJm`FcG#rk0X$&>N2&t6@R4@a1mV&fj9^TxsWhCpR^Wa!;4;(1#3om_CEb^*i2gISu zohd=qPnq5LbH!Bc5l0Cp!ZqkFZoJAh_+r!L3HQImFMi$e8KW_p zZSChf@En#Xp=6eBy7=O=v~w-6&8TP_KPpvIF+=eRuLs8?B=h0s;hgzltt$9&8X~(=DuLXizB@8R~fsif_T`Bb4MFb6so3yp`qgt;xU67&YVw7PsU3L}}^e;&DNV zOUY&XH1*~uI9<7nX{El(T_|8>X*i9P;9(~OL&&0IUb;I~J1xcgD!Os@FjRH^yUV|= zBKSA{@b@ry^(1kzM85I7A3BwPDEM+TP^krk{Z`fC7fJVd)u8rhIjyanQF(&z7IEG>o`B2_C~gwAa1 zTkwQ^p00V{2yQJA8&c8OkQsUzh}8a8sv8U|J4@@9?dv1YSiuKFpBOV*+j2gF2;&g| zycJvoAkfLby3q%fC`NTky+0oOd2pEx3Q2+ON+W zXSlr}eLd^@XUG%8uDwy~vUJDQN&ek==M`t?&8A@cYxTtZ#dj#dcJ~WRmfp>5XV63N z!#eX~Yc1BW%;n8+6z`i>_~{K_c}U&rYGn6;CPb?f;L}XTyk+VD7n17 z_HSi~#Izjyl#)t4a7DnjfU1qw|AtX$;b+UvCy6-*_4AcZ%{rS6fri{7mx|M0{N%GML%rY44 zQxgkWTwEHk>0BTtUTpW|z$B4m5LOr8yn_}^(<*RpZl)jb+q--D<3?pQYY-?hR)1=x zsA)x*RLsNHJ)cD#_0%pLa^t~FIi4d?@O9!ua<&mAmZF5d0CEFSK{=5(0Ew4}k0 zut*Mb&;dkZvkRO?X4O)yi#Px*)`BX+1IC7BB868HFPi=vym+xA9Nq{3eug27*ny(8 z)J9H8?Dzmzj*=m_s7!?aPGPH&=gqY1(n51}Dt!d)hRd7%jrDAIpbhoY(C8)u*)k&^ zF_iA~D4PeJn&hiAU9&Ti5EjZ*J#}?kSRc#QiWpLuF+pkFanZI|y7E3vwL^)ZY=ktmw>*LDqk1G7_{F zZ+_Op#A{kDsa%urlcpA`DPZZu@Ln_-5T z%i{PHQI)yg^HdUDnp>dv z23PN|UVq4~rzT>>)tT}MK99p#Ue9u+{C)4QdojT}y9k<#1C;Iq;-Rp$9i5k7kv?+f z@AdE8tSXYNM+zjtL3+I9J!Pylym{??aq7Q&U^nb-f8r2L*a2{*A8 z6#-Kh!+!!-CvZuSl(;tf;U*QYq*sB@svz2uO98xJ92=CucI!0pgJzpj%@WKVlR=Ha zx2HQrcr>*goJ|yA+GXz$IEj{iU0`H`K7vq~tc21IG`a!cdk+cAiCMIPgShLxE!Z&I zr#-~Z)J+tey85sF8ZG(R@f~)Y4IrTRf2aaaf8NENU@U`_K=19fjr(>_>_}D`)WX8P zhlJghZlO>z{z~!87EP6_Xst;jnwZYV?4{SUDigJ)!G))!s0lMFQfDBEh;Dcaaz(A@NuZaukPY)p(9M_oRc6?C<3-^l$_90~=yMSsog=lHDjkAN~8 zn54I`O_ewP%fGz<*Rb_@eKl4HDXW)5yQO+!Ni&Ses$)55Kj}I%8W0p%i-Qq%>y{Rs z8W*}F7ZktPRLL|+2Gj=~t)|FaEd>nvJo;}80n?dDmsud81x=*8I(OfYPS-%igsKXN zhZGxPT;WX_Y3|d@C0{GhVmI`N>zo_#rn0^iN>fZpG0m!v4CvY4I`_7c{A2+#MTBJh zRz(v(5>A*?MfH(c%SJ1#m7pt-FU=z|b#4~SPi zIE>2)7)~>l#6~jz4!hfA;~IK_xX4FKTtq$GmNCt1JAG2t5fb&ELU)8Gd} z({y)Fb`gP**{eMBJUcjXiI*0FG|V54Ry(g7gJ+6Z z`hrh=I%_QXgOB5^mL<$O?#|QM`q3_Xm1d+j*B%yDh<{!u8<^zL0)7X=r?4hRZz|mzj%-BwY{C|tms(;PTcdJ zE=`ta2=2&Nn3SGxs*7zeZeL4&k(8}S=$OmJf3wy6CV56(8L2UVT*C+J5-euScXMxW zEBTB|2z&AuZ89(5TiZ232JlD@K9p$rjE!I1w6_jYYUyEDFO%>=@IR6+^5fbRixQZA zT^DL#wEdo9oaru)Mwa6FIWIpEV+8DPfpRuS@*Ca8KRZL&^nc84OLB8rPY9PnG zbo`=oxL5jPe_M^6jr6pmL?}t8NtZ|aZJ*nDS^4tnqvzF{EFxYHKn?>vZ1V^#YYyjwB z=FGXZph$)&N^(Kn(TYv#{_=1Bhr|Eh)i5iWB<;@*8|cIe1FKAU;JJ2maqjdsH?y^B!h7TWM6QX@Qz za;<9>PQ;wY(ivI`Kl|J6b){C|@>%T?QjOnkhE`q`E2Mer^To~AtW9@)5#fM;w@}&v zNMioO;s^<|G$qv577A`}Z}+Z+-y^F!*Na^{?mtV^W#JNm4|1eR=}UYs4stouvoYgC zEY|hri_M$=F02c2T~-ypD`gJH`LVb@CboV=3oO*#QG|NFG*?*@B8?tiG+j=W zR5k4SNE?|b9dy5Ob+G0X)R5(6aeJ(_Y$f1N9V-X5Xf!_EMS;Dz`wL*sk|bRiMZqM2 zgJY>AN^p6$!}HAUXkm;jYPe6w3%fL&Ir7)BJK+qOP)h^TX1fE`ImuJpUjIE1_&LhN`fI zJe9A&DR3X{0rePl{xj6+Y?+txzZ%OptB>;8Ith~5m@8j!YHYQTe)-ob__TVr)%0ch z9SWsUn}D0VwfH_t!ZvA`3gxq&;nTXhxA(o9S{QE3=w9@R$USC5PQ{Q7<#i#7je8ZsdvCqAMWUd5tl z?OLPZLM6fvm>aW3O332kM1=ba2#!)ab0)w0x6t&++Mo($Yb)H8(VhKL0lDeMqE~OK zfr9gn4z;})sQJWDuPUGqgVZY|W7bXpDZwH}XP@h5vhb*Ma7i=bN8wotXgEygt6{~o zs_zgt5<@D51z%5DEe5+8A>>~x)0clTvp@1)9Hfe1<`>gaw~g2zSf@gbl5W((nNPi<%`#jcKPkB@7~eDB4qKu!D;fmaoA zC~!aRN8`fhv_gmL7%=eC#D`lI1f(IjK?AG45sEl`B0IXl8d5D8wv`Y=eFM*h{fqS^S20NfMmC||T)>B;g~X~VmkYa3$%TEm zSPH37G27LWTvl)i{uh|}bc#hN*8T1NH1%ueEl0welH5}kStz^DJYK3#H zRi#)6u-AB5PF`r_GsmvC29JWw)5B0lLiXqNyubD>mZHr@MhC!7 zKJz-6-bY=ha`edZ%RaIxQz}ya7!z&S-Zt;t@ODxe8)2#*!&q#JD5Awa_RhayGeAw# zf=VpL5CZJ0s%$J|Hvimd)wo>@aW&-Pb90zxRLfR3`m-g6LUfg_$0A7Iv{r3#tiY&} zqhG6Fs~I@+>-PY0Qvk&B6GOyeF(yx(cJYP+~334Y)eeAzU6;SlISF0YNc3*s_}dAHG>qlTv;MF4Hdf$5)te1V)l-0lNw~cJ|Ijn!rumV@2+db1Ye&~O=ta`F2>38|d zp^PVjc0DLN=I>$PO|D?j>Peq2ym(qIz9v;_>p~`IsmRSg==@KS6#5+>z$k0 zEWiP^Ehd(3w19NE%@yqA=377?9p2xOoUb?id0|@#>kDZ_OMtD*p>7o-eJYCNVKg{= zxL99}osml7Y{j;!cYJa$x8?WlFr}}7*r(B=vbdP)U|^Iyb0}J#dw@mQhc@FTl}&rN z=r~K@mCchAamsI$Fw`?cJsUESkqO{1AY|GSmxnaThT!&_kD#YW+oe>}*AbTH`(R56 z4#r4;?31Ox<3=y>VCeHvd{&`}@n0|rOxd=@=T@S2`5yN1Tg24V&}afA<2nx2LHd#S z{hAUYCtIgiUy<1SWhbVqe+1=#O$uWdn8v*Gti3w=W}iOp8g#*6#bR4LjOr)ak|YxX ztw%9ib)2rqXU4Dg+a6+}kZ1mGd%@r`J%= zAC}l}4ulxg-iBm)!&oD>^udJ?8ZqYG-+WHM#dh(RCj9rOHxGa3PLQ*m*H@TU=za~8 z0Qt@6AU|IK>;B&Ac4IvFw%e!k?&FP*pgdvg9dSq|Nw05UEBi%U+!QUgtk+D;5Ee?i zA~w82U>hUU=xkW0W{+CAh+k&VgI@pvW+N+)%`AC47{?L+n#zDP}iuqlZkY!jnn8@{5%rS>HiQV6C_sDgm#v>{j;8GNer2RuZ#Em zJx&?H$iiz#7d*4e0H%`ahbn2L7uIDp?7VEF+x_Oa!W%Tkj55y za7#yrL^@Oq_gIYIthUfzu~n(p}=;k0@NCRRgJdDq*G28@e| zA#!2DGnU+1NQj-YyDSQK3cVAYl|I|lG z>2R5A@YB3~#u<`qfFotd3vY(ew8l-H`E(o)kOW;GlpoHFe2iOws>u<6W>FuY&>mxc zqrMtSrW5h_`uHz&E=!Tj7wZ!r-)y1kvgC8I$jL(KBj{vz!Wag0uznDFl7L6w6tm(& z-8S$=ClDkD&(((JVBY>eOa<-93$r9*l1^*ujQMOqyJtJgx6BXj&E}&tBLX8m#dcnF}qxcLwwbi6`Tu zU~nGrL|NOyN`Cu15b zS@)5Z^$?!%d}+J*-QC8h7o96EW&FFlYp+3HF@J7@OIXLZR&TXQWwh&UdwDz-fh9vy z#EW^#wybm?7~f6fN%gJu$-(bHPX`>7tg5q}?nNWH{yhz(=Pqj9lOf7QdNHQ$IlVL4 ziRaGa%!Vx%>h4*;%%uIO=sib_0sEX8r|ylk6}V3Mh0IA>@3nVs9@m ze@;#*M--~}`fIM}+T!kPtvq~q_7xk2nTa2C%JX!s)n0VALmlq~(buC5n11F?iW#n| zG8{)&ZH=SJ`Q}+Btjivw%(M6YUeG^$p|vqeB(Xft{?R0LwK&xqFsIV_pD$u+OCZy? z3^QSn%tGsSFTN##9SAvxb2QN@s{`Mg&uKZG#$r!)e;mG(u@607RAYN0PZG5J&Z4eK zF*4REfN=cEJx&G$LgNmX`3*7SvmU)AVf$B_$l3b5VHWiHM&DuI=sIt=uZ}*K)T6|&|W^r}t&qaSY-vUxr-h`?e ze{0W4xX2uI+T@C_i6+jBi;lF^2apoQ^@NbWmZZjr3wPaPMg8sc2=O zP(FFKKxBR-09y1tPj*swhRs7KB9%vzx4O!WPiV;vYW?mL0-4*<;@&6d=w>l2!+(Tx z&Qb@_Bbrp~a3p4shrUiIvwIYy7P~Vx)mZ^Q3Kbe`D_QvY(cXik?;-rQo&7Nl#ze8Cx32Of!_Yq5&*{!JE^_n~svB93rL*R*sQJ76bkn9< zk=CeDL@~r`1fGD7 z+dBJqxJh7mOvKUfBQkCKzn$muh3L6o)^&wsHCnZ8;_K!Eyu8<|>H>B7px>4iNCf?> z+pZegj#uM&ZoCm%BU=6B9hBOF4PliS4}ZK9+w@Q8p_9vtHKfb zp~%la0>A!?bw4`{YCtges;qge4XTg53O67#k^V5=e_7;|kHyZaf!w|~%vNU)h^NTh zRjL3o<}KL!1?5hlQaF^P&tNI+KrufPHSRo=sA{6Mg7U>?q?I`2UH_0nJM|90X zkKSpjo8nHIX15B1U$E)o{iq`F@L{u^zEw%SDfha)tIIlvz&IJ?>_O#!DgdACkMBF~ z49HnXr-}bmU=azeMqrx+KIYTG1l5UwASKCxQk2Z@aU(amVy#>Js@82`RpU=~iHq4b z|LjWNvKu4{@r})JIS5+(>|Zyok~|p4QuCghnX-?$iQN#iHq((Ev1Zr9$T(JO?o`l35l;oZzwAc@eF?yvns$xRNn)Lc zC)#L)7(oF2Y=**qi7_^NiMsYtrS23`|Cb$pan%*7<7_}jFYRL(}*&ah%* zqRq!*KOB>--B~HXLw>nAEQURlt;%VXY8Q6p&UI4-gV zQPKoAXv$>UW{Ve~kh2noCi0Rj6IHc7l@Os$aSDVP28j(5B4u7jn543%-+7xW*T{&t z?I;Z^n{;S7-LiU%UTuzH%W?hk$aVb7@x>6w)ndzD*s1){Zg@lU5ROntn7Do^?qL5o z^icG=EIc%FClWJ?%e_Kv~qkJt2GkHU)e&n@h(5`Jhx4YWzbwG8L+`;*IrHoZdy+CP6~ zZWJfp1Y<|Pedp%>OW%?w{=Vt-C6d`lnw#rQF(Z)tK^Dw@5YMVg>(n$$-vB+P7R6+} z6)7HXwDYOL0bnhjs8Wq4ktba4Ha>5-ZW*JY)^3$UDzai0rZ|)Ek zw~EN9g!oJp<8!76SN*I!EWQmBRssSIXjQm>rx68!p}>Zuxt+^)e#6)+WE_=Y_@nVMw57^ zB1RP~l(4-Qf`?yBR%HH$vOc5bte2A{r+U4hwf1fHPJrG+{_KOYDPK?}eC+(fWMmz#5CBaCT}&MO!|gQXZ_!a`IJ!*1oG zj!8@FSH_4Jzw~d)wmZ6r*|WBZVG88HP18Q&_?6!!U25dl>0OJS;Tx50*KrgJno8&B zWt+(V2`OA8EeLN#uTv%4IBHf2a@91%u>KGiV8JcK4;npJN;1RJm7G0QC@J2>(Rx9t zc+`Jwra7)bUTtci8xqLOV8omV7LlFpE!H^kc*jG_4@qWp-n{A+7#&7v6-FIQ`OO^q zmaAC6V~B@wX?&*&fB`!15tpN*kjzt^tVS?3W<>igz?g+4!1B~CBAPMO$sU0q;nTiBFC(hv^HkE(M^mfr z^_R>{Iu>Id?b7GTc>XfYtx9R%(}IV;QIB9`@%7R)j=9!MPwHdDdjVW5Tt@;_6L^9Y zEC%pE3pm-73A-+Q9Qe9!-meFF$#50bmQr#woq&kH?x-g8CuY0oV`xc1Jco0m zar`~gc}LKu9GhAF+T2(h*vaZ-6)sT8FgqK6t6F6Jkv{%*UiqVTRJl@IQ%gc zRed%DM<5Ge`VLhUgYz-cbh3ef%$V}r9FVl%2JZw|P*mSIlF?xHY1g2^_(fI;WoJfB z+*j{w9b>XIL^K*^;v|lN3Nuz>jCFMu=ANtf^2&AMvS)`2__@6WB2>r34GVd{#ph*+ zQI)kCPK}v1^?~rA(q^%GzFUR_pRSbqfN$wOa61)}*HLCEw@+wvaTK8R`KEy82DfL9m#wA<1spd9YH*Rb}D%2c({N?GYse><#yY zA0H*cEI#pgP^b&WWT{a919$Dx5#0-d5}&-7fja3PicRHq{M0i64BV>9nHf28nucsA zsSB1AWU=X9CDUYbDxI##wTY# zR&lkW4&-9AF^KeH_Pke9{`m6ohx&AjT~E!?B!iZfMdY=YTO5imYfyFr`rUGuI@WGn zR`U7XHVdIXEwZSPjfrsV^Bi(rj<%lP!t;seYL?2Zv5Whk+Epm;z5eyTAB5-yVLpJa zuHSV62l6+_rTr#|rFK;N*)wZN=+XWvPC|>g&ld7$@Ye`{pUY6LJP4W$f@LKnKCRr` z-+>Cq1qQ%$*dlC{nOr5!qT+4?9~ZL`cRY!U8=26=HVm8T8pvr^8)tQkeHIO4b264u zFHRR3s$MT&6+e~L=eKivcmv9m@>H4<=mY|uG!a%4Hx~2pR=`PL2#_(*D4zpEuPueR8x`LOrJI}83JK|Tv#qKBtMqJcvZo{NgV{6;KfBz! zyu<@?-NH5QbnGUoKz(1^{>06^hAU!^58c|r*Yh=r8eET)E<=aRe_stMasCZR`}}oiXnVxS!azImLcuZ#t8rn5Up)3lG&Ca1nAq8B@g2Xtd7{%}9v z=;LGYmJ~zazw+e>@_W;@#{i1FjO*p%XY@&ocP1b17W$(rdzv7fii5%skH!>%l1$0E zQn7ysd+knj?dM7l0JUP`44Wri3#D|GxT(v_rCetDzf0Q}K6OaGw#MA~U^rp2);|~` z07xYf<^D8{xj}C1^eg7g?6;A-rXFt_FMhCm$5p>6`9l*i<1ECfmVI(D{Q#mJGv6+h zNnZ5PIqVzhR#qnNvkWo9YcFfI%(p%vq9D9mW z9(B)jsP?gLj8tPVfw>hf z3aydvR=+D1XfRPS!#%T6B|J`{BrJ8yv49zA?akwJNT6#k1fuG^JNQmu#t6pCJ{Qk* zQuYRZL+b;`!Vkxn9#6H)16*jf)6!9w%A8r78iY3~GC~AbZ!E5fXFd+KhQWkrm$tTM zJuH;2mnNqT*)LBxLX_5DV~!ergyp8BWR+f6Wh0)YaK*`s&wj%_6SO}HsO6)T36GJF zyf-AI>+|@cPU-QbfY*PY;{Q6&N?ZZD?Z5~PMu0@G=Wk0r<)R1uP2f9cnUR!tznf8+ zV$u-IaaIx>>7Vgo4&bn6I|ey@4Egefn~2=JqCN9y7z+6@HMqU3VfXa-@5^_}mF^!D z4By9KtYLSQb;vjeEw<8fj3InEu-Re1eB+^X5O0|mToYESsfXDuOW=xHk*<6kdc5Q_ z&E6_6dpg-sB6EjA=jA3R^a;n?b>)5tqqo*Z{!>@mjPn@}>pEN3CrmtGpmsldK?tZT zRVTw5CY`@F9zP>2#(e)|v>590jbj29{e4AFUYW$1kBjK5v5aQ4(+_qpKq%MjH=?Jp zclLo!OIRqP3O00!D?8OSxSnXc{4{upJ7vG#?&0v5=;}K-aFa&J5i2b=KOyDemMt}S zjUa`^JglrN->hg14?Ma2fu7n9aaf`m#kzOr;iQp5y|-L z*LbDtj6Jq|55tt6wo~2tkh8zAc|yis=xK1_t2(qdTgfg)nh;N)Usu8OvI#&L<) zH`bX`3GkL=e*EZR;>VZlB|8{gJQC+^SvjF*07%$R9T3aJJuP)ravfVs_Z`(nqn>US z+=a4C?eXzhl2MgY&fGTA@sR|icgN%gnn=?jTuqewpMrKNqJw=6`tEH`jo~gY58Voo zjeGFXnVCVl%cYR()q#zZ@-VBNm*TL#`RnPFg65VM`03x5@)VAX{kxk_y=vad_k`G2 z`;V^pD>gNCbS%uD9gEfpmXVp69?yvvrUU%DK2`Xq7SFj`d9u7BV0?$&k1PyTPHK%p zXZv`cj;;J6x0{uk2_{k7p(twcsHbH8i*c@w)PM)$V%!dP4%)8!uQITRL*!chJA*!S6M8#Cyiozlbm|DaKGZn=YxDi`JGCg1oUi)BtE}Wgn^+UyFxv_ zkf7P7$H~z4Q6&EE9d13xsou?LrPIZYgA(X>e4&`l1S0kfCK*PP0jhszZ(QR zd?pFeA}D@4m0{>%hX4W|Ukp*;f zva2M?Frdm^n%;Z#IY)dccFf0M79*Sa90lp@=4^$ZYB6zlVym{ccU{Y^mW_*L_8Q9N z9}~8Z0t-@-$2r3P5e47q%d4i8lsa_Y@5vv$l2ii<*g+|*nZDBX_IY--$o0?R@UCy} zbuci==arDed)07xC;y)M`+5~nZG@F+C8@l%zrn`;=i+C~vR<0lE7IEswVrD-@Vo(1 zyy?BM*y)lmyr9`$&jit0F7JIJm%Y6!w4`4RA4Tx;dsDLIu|_7=?xgY(KrR6e6U~-0AXpq+^y}R4j-HigmM=x$d;}jvmj6l3J``K5@ zQ23aPYklxTMh4bR`f+`@j0;t_{PjRJ$32Gmvnj)t(_MKv?V+4_?3f-{q+6(Sa8Xt% z{GiXp!2pvpdK^|)=r=W--PCew*NM8b>sIN?1YGKfqSV({V^@*|ukrl8XQtWH!x2vC zIyxE%zp@Fx-0^Ha8qsu^W-lyYBZhKrJA33NiXFIN#CI@fk(|y5xu+Vxi4_R5MfkUb zdvSmDiolhfXIfniZ^QS@!%a>$j>32a@GEulwDx+LfuL__%7zuO7 z;IT7`7r#ILkWCi*_g+g!ubUk_LRu!S|2_eUcYaM3P2Q1MoGIJs%VXhtmM)YCVleS6 zEzOOkjZoHOvX^t=Td`&QLhBL4+7SKOsygyk@$Qce8%m*>35o>}y~VtKty?0fk7==L z3d{=3#=|VWjTaO;?5$bzw@qPDC#yeRlh%5fW<7U+8{ND4PsSj*q~dpK9FLwdlk<}I z`=ZDs%Rdrt@+Qy?l`v|D+)lg9wu6o+*ZH*utaNF4htpz44oUcBu#2=DC%FK(+PuKd zZ+q)`suAM}GaO42F4Xd#kFd1OZ>!(_#}|QcUT=m)G$60YRa|N{_HkfuyfzPZZw1U{lv=FTw{_ISs7BAwWK)X zllR~cu$o92|5m2SQ2Cy4l?C^J58tE5Q&U)rt(UcswTWaw2$=7wmY8Jx4B_v~qhp4- zu&sm8y(dGDPrwP}gNedv2z~cldF(^z=1p5-^n4&$RPbPyFA8<Qif6Z+e?=K} zPm7Fbt@@9Vvr(U$4^!vPM+&hiAu-A?D z)fvTkX9PIAhxw=C?#w|utWO{Bx~-20xpF;6WgJl^m$dxUM+eeffhx5|g8BJ|8cw~i z!;izS9IoNl0lv*)dn5TysgGdwBn5I&2iJtZIq1g$UXAQ=x6iti@B^1EZN@lnt+o?% z+n{#)ivBEi(0mIk8iq$Y5X$)(cIV|Ew|sKzF3%K_Tg~+Cqm#f9DPi0gpi%bP7?*Q- z=?3?g+dCOOvZ%I}wg~kL!^yt|bq}JkmO*=doct_;<9fzGr;bn2<9a{YKmm-AIUuH4 zCAH>xeRdK`lwZlDUg0c7{dhxG2K2f4SUW{Rk&r~r_UFS&qx=F$;tgok7i z`-sxMnR`R`YI2Y5i{t+u+oyvHiq?CYnRRuvSsnTK{ZG9ZocDtB$w(BMAI90_+ql2i z@b^>wU@*EqEMh%69y0$LRk~T&k{5v#K~djOk-i~!pW+Xyw{_{5JOXE(yhm$g$#fjg zMkUNJgc7Qub;)?*)De}rq-`v#9{=9RJBT{!G_n`afN#ado-LH^+2t8d>7lpgW?Edy z7U8W&MJMLfGG0Lq9K@w1!$rU!grDjw4ShKC{~T|7^1wx5;Dyb-=py^J#O{MB&$ z8;7ZH_jtSSJy3iRzk;O;CRC-9QTcsMm*t&_X3OrxH-?xwOstchY=^`hh0PuzUqLk; zeWWMl873e;aCx9sg06N~YONT5L-_hj>Etd%)AdV%oOm88@I4L=@4d#oBtc-bLNRna*|bBhEq`0Y5FXKjW?%h!zAVewFQ!LqOcMNYlBG7c4hxQ3`Q*#Z=7 zS#7SKC&|&*NGWcE?yjg@&C7`QTFK*9Sp8;Aw^+a|*@rv!u%*)rNhHU(G6kL=ZZEdT z(_VBiDBb%y6MS`e7SJ;3(HcVh@V6JoFp%&+#`$~yGKk(EXC?qG<(D|gC>6!+E&wHK zaWt?PKzrX-!OfXseE;6ZSPr>0ebuv|ywq-AvIo{PldNt3N0&<^D%HCl})WH^K?f2c=G3z-r&lq`E z8EOtAKXTI(iYhm_3H{C<=kdr(nq{*tqrJ%v^9x(gw{J1ma=OxypBKQUE4VC1n|>%u zU$T-udT?MA5O8K|s6105)48hjI}-XiJFgBY&F{oQq};|$(fGt8T_62&v5eqB zUuj>sh4h=ceiu=P%89MIf>wgV)vfFO;pcLdx~u zYdNJh<5PJ}^fkdD3|?1QhfX7AH^y}AzeH8KN|P?04Q=#o+><0+5`Dbq8?}jcp=U!G zjfFEU4+;57XC{(`rP?-I!BCQ2kFTFTVICsgV3n>BpoAAn!$LfRoG)uZ^{#!lwJ`UY z_5CP5V;<5s=eZ?*Ge8S_Aoe+I)$G`_qqI-p(5=-QArb zP)?6$70ah$D;U@v*_u@0VGmB2c!TKzdY z^Ft$R>n2ltW_tg5RY4{au=Zwdg(ZiC!1C>n*6E9{+h|%=OP~Q<=K#q(==o)p2de{O(^C z5uiF558&HIupvha;Ys4Dw)_+4I@_^zLe7y}EOUa5}$9ga`+O9m3R9x94cq zyog~?(|edr^;(`MsqwT?jA>$;O15N@G)J~JFzZ;;*rm<9fP(eRtTatX0qkyEQo-2k z!V}-J*Xki5Ur88Qo=`hiSOId~%tjGU=1pQA0 zfReyN1oNKAGUN68Jj!hD6tr7*DjB`WQzeD1(md8m2Vg2G33ZI|M~r3%^&WqL8uRR8HudiIK}rH%94q zxUI4DtB=mu=I8VcDty!Ljp0VTWKH}|(LShapv5!D(Tv|8I(W!SK_y9SoU6yX+}OTP z)6uL;Y{T);HFn;zJSNG8CRZ5tbhHBMmX%Rq&fUrVp>(%^XRJ)x#a$mgE>xJ!A;gdHLa-m6o?RI3eR7h4SL@S7d?}pIE{4qX z%~njVd_)naXcJ#J9}BqXvBws8}Gu`xhpes=Os3SoZ7!O83X1wyEXAY0A5dHV5 z8t`GQq*c831uG=1q&KC&20%J5)stU5ORbcM4s||3??>7`&r=7HI4yM&G3EF?AK4jh zKV#>)HGd}+GLyn@->s^vtFg`k8qruieFwYks;V_Kddo9}@POp=cW71&w^VZg0GiHI z@*KBjjR$6zgFlypkzV8DzbyV`k^~%m?T2)0x1P*BW8hiD$r6Fpl)9~8xS@#%z;u>) zFjvQdCpC=K>oKKOSn%U=eZ-7=?pmomuIkjJ(p?GN!0@Ip=wf9kU!Gvb%dB(XDm}*r zX5zlvG3Kz;Q4tfDgM+SVL5Ne0;q{NbR>F$?kgLGP_L7?nc6w)XXm&Jw{Z{y{jndI* z4}Tf>M&#U(bTVnDG3o`eG~eY|$$U7CwOxNSv3GUu@UJ7Xmbiv4NC`V?Y{smsAFi$4 z{7oaOs%GmWT^QJtjX^sTYqQw%6TYXW#8+3TH|AR;duomo=EOkS)-pgV;v*`f(y zd{0eeWJxy#61#ZPp9+#kvKXk}Nn@hnmF8t^#}l4!Zu;}w9X3*LPne8{tdg~l-I)EV zNqh#{%w=%a5g|v*@@m>CyB_1{X6yIs z6BD9veC>d>67pwyT(`CsB4`?nD2k29VS*$%t*C49y_zxUUwB^3!bM9)3W7r;V`O|O z6STzcfL5#^_cd_}m%n%X8X6IDtHqb}GScYM%Jruwx3 z=v7u`XgF2eMEKU`Mh_@3L6xqLUJ@6F(7L&tH{ac}-U!Gvghk#b+G{#djMO#G7g zVCwFxfmDex58G$eu!f74QGJ^_uI@&}cNWiCedBb`doHt^22Vuu%0gjXr>b+~|4I_H8i;?pN5+*M1LVvsRHBmQh9 zK$12l>yr@xl^bMs%ZSO<3F;r%a6P&g?&IU5ko7U{mPWC~o@V{)H#5l2fIcUtqV)$| zBt+D^DD#hkf+_;=?`sHWH1Q2a<3AuTTTtSkl?V)v{(gv}|L;d3S+k#oG5s_var&hOU5U{L{QDlZGFW#lQHATj!GEz^G{*=m= zS`qjb6mR2xSEq0J;Nnl>^ys^x_tBd(pd=pOQ6jM$m#+T%e6@r}Jh8Emb!@Qp?2_5? z*}~tssE-vw3c2VWS(Zv_92#{LmaAgozV=g&`RwB2ccifde~t?eRJ(j=hfueh%@6lo zT0Z9N+&X@=nx}InSb=`T!Zhjtj z0tcbvniM}j0*pT53ACv(+ToPHN+*9&CB1~TAO!$4(OkWXtZo^@d7q=Epg${Z45T0e zY-=pEz5W?E47Ohn&=AMNE+EdSYGMMH4XNV9*h-+q@2`I=%+1-UDjOIev~GH!aNZct zLdB*KEQ&?MS>VlEoO$D28uHI?h*!PGhQ|5UFfJ5hCI~S9F^4|`wRbJ!Y*Gx5dR1+C z#J?ou7kE&zgVe!#D;|a6*M}Eh!wyzkK@a)AP8KUXXEZb+*Qx;I)rysHo>k@E1!t=O z;(6+Urm{JK&K_&LC7|Sd%3t3)jI^kkq)yy(VRV~tU`}bCgtUw#+1nNI?2nn{xCRW! zSQ-+I>Kse8%4$&L^P8^FO=s)KA{%rnpb6Q6zrwxCwu(1-`<#v#w!hT$RGBnE>*d_U zoYvfl@*kQiT8*gmDWX6i};T}+RR}JY*W0t zMxip#TRQYir{5vBOMhPZaph)Ch=~2$(4P4=#cg%Ria(h7C+==P1~o7O7^BYQ;D-C5 zHhE zE5j0cwkmTbcift{WZ#hs+_yZks2TZx%0U$U1yzR)vccnpV@l|*#-G1^Uw=fAzP4U$ zNtTUw6+AbG`|@<)Q}#TEV1i$*JcFv9BVVQ>7IzQKhPX8_w>$1!u{QHTRqHkAQi+XD zP*v%XR9yqF6M*NdJslp#0ce11#<;8HMsAI+2?t_zXoW~8D_LsH7J4L&`c8ta-#(jwB` zKt5IaXv!=_y&=IDeR4DqWi~BqjCo0>9!_CUe+br1ep=iinm03 zL;;G$qLrm&Zf;UY8JkG+ak22ZFtn38F>EeLGz3r1-`w}TMmf&L{P5W;*cTw-cOAQjVS19Q-(dL)a5C%b9IYc2 z4K<=kjoQVT-d8rSQ^)qGeqfon8ArOC74K0gPzcIvl+#L37DUT{L9>DD_ z@jXIY>;Z9&p#HF2)tm~!B-l{`9+*;;llpXnX^*T)L5*XQkhZaH832&tCR4`IClFJY9k7QeVY`4;ZNZx|A_~oG26b%ifm#9{34dCrP@ss=ADjA9e!2#ps%dq~?#NUCP9}96 zt2w1+!7E&ODHEs-5FIY1?vl)e)Ky@*s@pDCXsM{0?N{@7C1v34KNUib%h-9rj0Pzw zfMT8&)&~i%WFA26t2H4KjHl!jo2z!}3tr)Svpp%LkE$qkS=n!ZjsS0RJWp6)>SCjA zY((UEu(L~SB@YlCNBKy^rF54jG5+IaW`0{6OyhgA}Bc`H9Trt))2EiE}~AW9Iq9v z65$1NbJJn>-~|4`E~LqpkU?~K)H8###1?j|syxh)R)C?*F&6sOIqrlfNnWHi)7Xio zjUc5$yWL#;j~^l4IDq^-Zs6@FNVTv<^?Z$48sRQ;FwJk&$?}f1q9dq%?w`A2sLvx7 zmIbuooEZ1kMp67BohU9Zg9OM|Js_9x+)pv4L%Zv z%msF1-&)5to*U|Piv}P*FNhA)WFj*dOxlU!mQz>&{YwLV&6n*Xe3W4+_ zE%$^6yPKP_A(b8yl>^TzKg=wRP~SiYWtf@%^(n0bs-#hW`1hc6wbL`?%=meO_UcK1 zIcLcS;BYmIYNCtG4#DiSo%*bnBgDH|81=_PA_5B~Tfnx<&Q;9?Ze2a?4|;E6pqHn+ z+gkkzdj~*MIRVQu$OD3i@)7`95%SBlu}(FuP4zO`A#f|8X}67-2&N-=@zR+LY)Yq2 z#>U~fad@$`dFR7UP;+x`a*DZ}3#4A2d1%O8tb=lS#tcFx*j*QRXs5f8WC z$JfM5OCJrO2f|Ob+O|lqu!VgqO++SV$n;3e-VfPyxY2*S0r++IQ%`z_0$O9IHR&Z3(Eqei zUk#Z{t}*yu;>x=Ff>^VJjiqg$I+)qsi%&i8DabqKDW;GQW%dA9id8@GYyZXVSJ(#OcPvsVF_ z#lPGg%wq)>DXW9DaT}LDL05-|1EQxE6Xub@@MMF%s^k<3=p^lycnT@Mg{Mb$Q$n;) z7UP>wDv}B; zRRL`(F;^P1ln8nAK-PhpX@>*O(Poo(pK!UI>c5Y7rv_&(Ut$h!Jb%6j2BkPWY2MST+Ni$mBHSkdXr} zciN8MC$Hboc{10@-6?pZ2^|^`jbA;k@Qo1PGwlk;%R3ZjCZ1dc%W*ULQX_FwNve$7ibJvYxIu&;B;1czrq!BNAL= zqTKhsk2_bl*m?f0d$bpcGxp0OHnX~_xOEF3JI^93t~$uWq?{Lj&MDM#dGu_sqz}~X1L^h<4#$ThOopq zP7-0M(b?IE%+ai&BH5i)l&v`q`!2utz0b7u98*_ntSem7yL!I+s!d4=Symo)jprbA z>|KL7!HXUa!Pk`xbJzVpCX;g{zD)0gUAeR#+qB_tsY_W1qZAB0tp8gJAe5QYbz{7e zfwh<@f6d(Z{#|$`xbAv4{9?ZKaOf@(=dTb@*Yyl-L%M;ZFUMr&Ej}vYuUy*B<-`5I zi_V`Xz^@OgFSm(-;XCW)s4R&my9@&-=j#(hINAO7mV?Gx;Qf+_0C?ER73E&edGoa7 z$mFD6^nSgA`RV0SBD(3t)|yLGJ}P#70KJ7oPLJbpIAM@WQ;V3)URoa~G0e+pUZQ;r ziGeCAMvmv5BgneNH$g|wpFDX)PDNswm6bEDrVj9zA?sXx^+G0Pb9LnX@-EL`KA@^B96~XRffTfhfgE+0!_k zg>SCqurpBFK#IyuRX=+HK#Ym-y~^xzo+9`_ys4$6q~sBP`o$K(>m_n>r-SWaguyd~ z%#F1?S&!NQYMeq?;$G+NSu3DSI{ri5CIukw`~)hmTD0OX`$h>K{Bgn8m}>&QtIcGc zN?A=I67b>Rmt4>(gjh9|$yAf298_0c*8HP|4>+oVs1hCP?GV9=F3@$H_Erc z-9w-_&y=JOmfVQi< zg$v$FMh?8x-a?2TryYg?(yNOMuO!-S_QGJzpU3+t2V=&rYxvt@;nEX-erhz+%LZRr zYyUa8ji=6_%X~QVyjqSvbZnVp>*C|*l)CQZaMPREDTm;Jzp9G4(HB7tWz*g z!wF0g3T2L4zDXLy^Zw3jiiC zz5vYL>v+Kg9G?RtS+L4m(A~umMbb4AcnV06`e(FGA27noEcG*fwyy2!#B^ZNc0T9` z+smn}!)t!Cpwt>>^qweGT&)Q?+@PC*OWGI3)-|vIb7C}K4--7v=Fz9blpKahR_yKZ>BaeX0w z8h3>`CF;ZShKYf0sQb)Z8D?dHL0ee<7v0=3r%gwd4dV%xmP~ybI(y^6_@zz0t_i=E zMu%xAF`Tk&t>CuBM4eZ~G(~LiXAl*QNgdy)t)-16JNh?kmlMC+>~~BP{)|)-iGr3| zak$8HofLP3D~Ol>^KbUz%uEa}zRSu+it-AO$Pi$T%u&$;pgC1;x7Wz+ zO!)R1`p6)Bja5O9;gt4h{|9EgYc}+heqr_4-?vR<>!k12wAQW1Z%~m`$y(@s@6!E9 z(00VCZv5g%VT=XVs@mbh(yWZge897ytLCc}!&cw#NR7{#MH=)27s$3_ImYVYb2^q^ zP32iOZE&QxkBrt! z)!!=jGmDEdYs7{tiUeJE*F4y76X)TrUNZV=6%F4%|4h4@;h%USroM|?nh99N%kl!V z5_YxIITPu*_=ksXJ32el@>@Mgj3+T9>DSYYkRqj4ZRd_J4-TM!Xs2#>Fx^uYko9$x z=Z}cozL7(=#-sC8t5<-pTMA6d-uE6z-O+kO(^_UKo+)!*owMzr&R+fJ_+{8^5hW$Z z?%jy+li|me_leoXz&F`4TUa|KKFEVRA+CQEnRpdssU3ppm4Fgbb-0x9(~d~#uhBcQ z^?@N(MFhG%#;(5OlCzbx6Xywb*NmMH)q}QxJ6TZqzi1Zx!TsB@Ul;!by<6G254h*R z0pIbv@|%4{8N45OZ(Uf4^lBwe=H}=7s6$ZOpsgA7eIb5>VFCj`k||UYHZfWoZmSPk zo@5rjm}~O1vzt{2y?9=SoFRI)*Z$wrJFYo@-9Zc<^PL}V@>qisivl}z7Sbe!tL@|N zY;ngz{7c?`y*oa~$O&bc`#zL3S1C*f5HB3gAPGOUaS%4ihXt-z$_$+nec%Oa5;$!$ zg_?&cgMlc$;(q*WG6>w@;ST#>Y<+n+)bZQy3=>1bj3r7MLqcSkii#|aeaez4OR^7= zEy>QZf*W#14*syQ_J$dlqxx|fw|;N12LiU*edF`6Aih_5RiNWQ`2f~} z_xAQ;v!VLkG&t}GF1WySbZnT?fZyU1Gsl?{)Psm{sASP|_|{hbkS$qRrhkY&bpWs6|f z@@18}Us3GV?^14}u1vHmO7@WpUa{bCTR@t*`poUq;Y#UnC=l*LKx9}gR>)c!rRABN z5rOzHz+0V-4JyeGyK+mX7=TrKb3T{gU7mTjAor~M_{qgxV!^ct=JrXV`j)!GH0`Zy z`TMG&d{a@}*UAu@Mm6~spgHFT*T#bZawmPXTRf>^aW z>{p=yScxte8+#%njYGwN6vYuoegwH;ka1F{cx75QMonb&2MloD7`13tsbYv^+Qax@ zfX~W%dkKm4k|1kYu;_5Js{yl-?mOCgQTq{7{41IGFZb|!AC^Q)D68frdu3k@_*!1t z|Mps1#pasm+MRL=#AQ3Sm`@<`Jg}8x<((sc|3@W&X&tSHVi)9kq(@$ZR>fF@<~Xb^^+S4Zve9cc(ZZw>on$*vP+wO3#(%ue^3B z@Y1+9I6kyg>yuC=ME}1R_J3X7r;oRa;6QO6Gzxu8`d96fCW6;GpA_Exh@&I`;mqti zX@u{r_Dc@YPW(x{7QQ%@*_O2Yc>KZ$0LV_Pv$U@Nx$RTgkX3Z)y8+(mo^bkLk4Jh) z6uYo(S?4r1v^O+XdtnMzevJ<$udgF8EC#u$_3L5T;b4aYIz8m;PJdxUq=w>9BM|m^ zYW*z9{>UMAdxfQ`Iy5-O<9(*A{dT$szTYe03GwT#$#gf z=Hy-+pP)v3CpIh?0u&PB@C!nkKp>kaDN7MoL5OaP4Mf$fPK>aPJ&NdLJdO(RuuCQP zyl)W2Y%Xnt23ZRP?eDN^t6Ew`Gg>@SC-hQ%(p~0v`K|j1Q41lLDK1K>$B@AhAJ@{o zFW*1aV3YjeW;2KHwT^Oq9YKb|ds~@58k{Cs{2Xd(5bubelA&UwPZF(jMOa%8? zfpqx&q_22FoX+sS;q!w6`iwjnUz;TEwGy^lrkqyH@#jXeN4zc1wRk~cLCo&k# z&o}7%k=_KVj~UEA+0rUrzhUds4`WX)+{OHcSp4ok<7h|$YRUh_sIWX9&m*EA6Bn1Q zgNH$p+&}X!50j0g9&i0T)}4q$IrFBzoBbB*MNzF>md=>-F-{wGFO=`i0P4Zvm!-jL zO2Pwi(rSs*G(KGlmh16aq3_05(8dKiOg#dGJ14xyNIIR7vJN8?WI1NB9=F zIIVbWJ4Gk>!L*RM^7PuRnO}Bw*O}gRxVyeoKsj-1#q8iGixn9m*SKX1%*Gsi3y5j(Sgb#T1!<6fW+O{AmQM)lY}|7V%Ktk+P2AGAA8=rQ~vsR zLhd5d*K#whYfp_DinTHPOnG!iHJI}D*Vvlvfd8~@*o9mrZyNf@--JSYPPv7@#{aXk zzPomtNwIUEYse3S4_uulX~9L)z;~LELM<+2YgI z{ZE=AXpwYFg*1G71Kn;5tYm2lfvY5ord!UoUFBp;UcL`5Of6)VjYlez)zyinOe!Um zsh;3wuhh-rr#fY2`P#iP>{e8SYc|r8!K$gkQgwotEvNfqB=Q5DfsUd+Tdbc927MTL zL1X}oJe6%NehZJ58OG;fjZ}o{@&XYfsDR_LDmjD-Tz+gH8P+X?jhD{s;WQ@{PuRu9 zd0~YFqd&&|eifJEZ}6yDRTc*;Z?9cDrYyvPZVow+|j@kBATQDOolM>icSOCb$V< zoTSVRo|JL&34+C_v9?HGAA!;C&@$x9qZznPBn>6|8q^7b%Eb<|b2Sy``=0*tb^8OW zWA*0+{9AhfiBSXa`#mfPTFq~$g#qxW*uPS`AUKRhi_MPhMqG}8M+iyu4rF%5(1mp8 z60s+f1bIA1-`$)QPtV~IBoT40793*nWcL=pF07Zu5Ekosnp$DG=3z7c2s7B(uW@#UPxhQj*4mKzTQ&q>@$ z8{)hjcFbEl?fsk7JMZhc5tHe;PIo5w{deU2#*ELteDr?~ZP{Qi`)>=ETMe`S4A*Ga zlxjvi1d2{rS}{VttuV@R-AN(0vjJlWwdvw~Ra1-6BA47#=`^w?Ei?hyTUho%QtF&MZK`_ zVaGL_x^0JFCK10Z9BYJdAx45xvP~7 zFWzboWVQ)Zt9`4P478uz9PM|g_vu(O)y~wFnf|sDdpa^SBH-}k;pD14Z7)Ff%GH_U z>A0`9XHT?EeuhJMuz7KD;zRFUoiE(;rRwQaOuR5W^JO4xL(+DZKWJQrD@Q3mWYsw>kd9o8(xJO61h?tkhx+GuXk932ae!CP1 zR35=XU+7w`u>o>Tk zQWwu{4paTgZvjdwnn9C*tZoUMLOdY3yn(f~TXdgg^s$7n0XKQo(^6q1rS-rI?KW1x@cH|45CDG};jbX1*=g(qiPjJV52AYMON`Aqr*NJM3w(Wq9k77V$?Z4Uot$1PYLiREsMWCi`48jCzTq3g*OJIx$i0KBW)7O97qYZf25M*HaD6LkEA`O1 zpe%|FV6)$QgXvjRnJ8$$4`$jh}hX z3s{CdCW%$4kb6d0X(rHmbU|E3HqK(WPMAco9g?hvpOY+#H%cqO0d!u752J8T0Cmu_qX%%yV%a8g%L$k6z}_uct+Duj*{^a?)yb9!vdc50Y?LwX|-aKUl^NgL!h%huKHg=Xo_h^6c`sQ2EEeN}9B^RIQ8N^EYbE zK^zV*Ui#X3VURlAigHeP#as9+%QfU!nH38nxjI4o&-e_Jz=9|! z9@Eu(shcz(shTQ&43OwL2f78|7d&?qM;1aU0{lUFM%K{-DWITa)K6RompfnNhje~0 z8J!hsz~Pb##l@-c$jR$pfcN0D(@WAk9fV+=!@#CgdtgVKT_j_XIU*M4WN+AqHuqbO;@HI;}I^0YMG24}RrzeR6# zAX+k~A`Qvo7q)a#%?BDAE(X|;j?@g%&K9;!+j!?8b)Uc9vl3NF zh$n@F?f?R%WOAf>Sy}+6+u42sqHtlfXojWQCahEx_! z7qipr1z`)2I2VYSd(kTo8voE^;^yz*<#Vf51*<^;73k!xcFE@|lNBbTlwF#WyouST zpxuf%k{k9FydkUNi{IH_1FfXCmEk-*J}%hvUEn--n)>Ue>tZMrT=LRC(-inym?(d0 zu^W$KQJZ1hIWIGp?<^^lI7|>+@b%JlK|oy`X>1@!^6FBbi$2QH)%8T{@5c!sA>E`) z0Y~%i8<&uVaI#(vU$gQO5%29(1ah53oTWC`QWVizG+T2$UPJ)W092PIhH%r6sMI&& zd;>ocA2TO~ge>_~ek7x^28~YZ(o|h}^g~0N(y)C-6e)7_F3Bpi`ETrV-BWf^1&SX?r*g3ek`7e8z9X3?I`}wZdsDuEfZ6< zxBs$y>`4TI@31W~0nwaFIFBF>_+3>b_%gqJd;b8C=O}sjFSmU+S^IFSo)@8&WxPEx zOfZCcR9;zmQ)HruAN{sz8nwy{qF%|4unPl~d|nxQ>qD{S=W)7?yB4z9*Rk%qw|_W0 zvpX3?dg+e&f!Y7HIg4-GUNf_wnVvaM-EV0-oDi^OdU>^7^nGki^*z{Jb(4__T^09# zbXtakEc`<5mVA8GZNVq8?0qdn-i5T@FQgzd%wJaNnv+d_2zAHFj}BWl z1qEQ9*!kYTjeKGZ4Iz}^z4&(of{k*6iLoqKu|!EePZuK2I;m-KpjQ=4X8vjm;xa?) zC&e~?ka#IrDhH-r0k}ctki6%l>{h$$-yV%74mWyB=YSf0SfiB9KMNa;A0}2F2DZ`h z%0VaZ+1Z7Kf7g=K4GNT;xSVP@a}-cBExwZ!^7QBz!zXU#EwPGg_96i7{S~$jcID&S zUnOSBo0-2fSK7DQQV+LR!+F;+8il1m?-g{j)csKag${fbG&OQd9(GgDG9#@t{isN@ z=2hPb@(Dh4>8FKs7nsrJa};|y{ZbsN0qY$1&$>bFOoncFt6liD6YU}sO;VL` z04UEQXo4h^I-7U);hjZN;1Z!MA?ew(X5<59 z80-6Y=;0Pwxjl2Widgo%W#MJq#jdKY9om{<5B=X2oyh+k&-TQt8LI4|1(`IP& z>1o=jZ{KWSwpJIQh3&0EK(RoDZcBW&yij~H=&UvG7CrtlFpaL{#Y~78-F01`G5wDg z;Ck}%Zk@eJJy$WVmhFM4P>Ic>VnkV5X)I%jf}b}tAB|Wh<|W-eDS57wlqtURAmOQy zqleRoqZA_F>nT`c(pLAYZIymmMd%J~B10VYLLBcnu^YI=Kx#;crqxpfb?Z6z!lNz? z2gt~#rhI|xzo*zTe-KVLez2pTPq1}^F2G_!6OvU;Wm-zjWdSiJz^~+ZVMj1@SqY&F zsJf!|RiB|phWXy)k$;{u6`M!CS|Q_ZCLjg*4mkOKsC-?yGDp-%X1)M+-de8X8Y*p6VKDu$}8+Cr*~7^UL4*1NqqY)pYh-{ot}woPNL_yF!wyt`@H~6)7AUz zT5v3H<4#fXyf*hQTkP1z|A%?%FO2-X81;L!FzWBSpE4%;eM9z17~;C*aPp*| zZv=Ah+Rk^D_6{+U?F2Y;Krvfp;N#PqFL@Dy5ZE{yB%`@f)cNr`J;LkW;y2c9j!+OH zZ1$!4NXO;`Tk09oLM>FyWCMSI^Y4A^m^slSHE$;=ivRqq$-~1A_htx83?pc$OHnfe zF|C-GblX|wX|+&(!|18gYmi6|KXS5uBOUj-8eyDZEUvHpc@%SM%}+@mO%uYV)w9T; zVas~MmN1z{NeiQDv{Wj$EU+zR>Od9+mT z+-T!@h;3ZrG1d}F@wLjTkEiM{`ef;hvMD0D(}5kv__hu2;NV?T;4D(}_4b6}{6uUi zM{s%kwTD%Ac-~C@Dn0l48JQ_^q$;V>A!_TP!%*uYdz^S2qFTkv<1Ph#i#%fTil$iG zUlsMC1b|Z!AfoxJFOUt9FoEl5fjHyj${g~tfN19YM!D51LL1P0t!G1nLrRjTD1|Rs zl;S;ZoK&lJ=Hcge{&x&!-=E+#$H?-h)=M_+bz|94z5yArO{?;hHR5rL8RoN_2i*snfisb4@0?- z(Hw7LA)?j$By>p}D~xP9lE#x}f*<fD@M)pQV#-5tE4P z8ifLZKtYctq4dgN16e0N3k}VT7ZATEM?;Yq*y~=23vXa~ad4plGQda$Mw%uIKIUhqd5kE=GP^hW`$KzvY>619c9)}B!|N~#9}(NrDhf3xS5!N12lg1uOc z03YwVp4T*bb=05ZTX*iXn(-$q87#?JKgVFb@lv6lvc19v)hvT?zie_KC=oiDX>iGlbM zhc(C8)W_$^-KvXkeSHWgIT9Aq=5vmp8X#+G73YgUCDcbPb<$ON-)cUP$RnNQ6uc~P zJ4NB0w2Z*`bBLeXxB(U<0LnSxS~GVj!5=1lZufD+Ul-L=o*zS z3QCEc(YV1$qtT%9-Mujb@Si^L48fGX7rl-#8O8ukT8e)6DRG(NI1fIdhj9=gD8vA( z5_q%@WNif>>xq^ybOL2SAaF&+5=Z#=clV5n$!DQ{$DI;{K;kTKc5^U2En!R3p1l>1p5q>!t+PqAeCg$c&795nMj=t?-?M_PUmHF~%MM{us#Eo3f&QcE7hO)A#66(-vKmRG4Mr_m=d4lJLi@cJFOMtXVX_*J zcc-RHKhtR6wHEECR?FD@9<4PjWdF~?@jHbPk4qIf!1~0$unEhuM+lgfUx!a-rSSP% z@*h=-;_M7uTZ{>o3J?iLct8*gF7K!X<|raNiu(B(#f9*tahpWVb|Sk_us0NSK|HBa z5CQ|KtXGxk4>VrHb{gw&RK9PxsD_Be<&DzfG=yk;S@|JII3j~Ujr`_@A+pjh1Kt@S zg)IV(&w0yK8)7a)y2gE+Wnlu$Ul?*$PL+4-eC3%KsNc{JfK=Z2pU2_^43JuC;z$_d9Ne)e0Kb3hE^O{tg!G+cJ5h^Gwn6S*f57 z5)N0?b@ZzYNXJ^h071D5VjW4c<{wY4Z~Hy>K-v)s8KeS=8=6@t$T!d%Fwc zUElF^jK%$_Nn@*|_l7=gTW%}ET6+r{!|(qNFH>i>WrcEWY2j0pz^Q8of9p~s=ZQqR z_@LtA;w~yKjL8Ku1?uSoT)%s$y#jqEDKkZ*T>+26qWZC@cujrKQn49LNPLY9(wwC) z+7HHsOxIMYDbte5<=@jz zbdMuUojxQRw04ym|hVEcQ`3k9aNdYDGQwN2Dyzw=U8V=ZTn|7`fzt0eEu+b_+J z?9yVlk`6~lqEsjf`b{~OaXvoBq0hG(gl{+^0t80=O$=>iZZU!S6YRy2U++Zj0o*aN z^{k>4tl^7cbe_IP<@)2F$O~wZ32$b!4nxx)5xK&D1Quw30L1`BL_}nRSE)(ey9(cC z$2ED5suAqey+qO5elyIw_lm>a6!hc9i$9&wN|c9?>$US)Iixk=^yZ&NDF#0pl^TRi zHgQ!SLNDkH4*EjG(;O?QI9LHvZr?kv7R`*UjYl4n z0`-xoTdK!Ru4z-<`u3e@6EEH0GP&T+m{LlNPKnyY_GY9vhT+MOmwdl`<-4-rnAM#!SijVq|>7Cbkk;-P${C3!jAcCn&-p#2t+K2@ud^4w-Z z4+XS@g<^4pB)`!?a!;$b4};J^Q+yv3;MQ)#ACzzgtRSO*#^c{3#vBj&yI=CM(<`Hr z6?+@*UpH|;l300fc1ZmZlA)OOlR*Iv5rzABu*j!5J6U)pP@w#0uv~S6SV6FnOrCQI zUF}0?jIw;qDCv>l(;6j?7aSajSUAV;?p)JOtf+3AQwhHoGOmxy6$6Eb;uSQV0L2mt zZgFl}R&dZ6pu%??JM@|7Nz|gFVBhf*I?VHMd`S2`EzR!dM-c3-=!l@md(>w&?X+*= zUUkm98^xXIJNAJS|L538E)(d~76LQGVXNTPmEp>D&7sCA(&9!dYfFF|ZJ|Wj)f{Qa z(%u~}WTy*ko1$-c2yQU+vvF+tCe(oGJ^YolLNhD#X106ps?W5qU}!t@&qYrGqy3&8zd)*dGDWu+!MqleIu6k7N?fLuRS3@duwMSoxWm!H z?Jij1p0abpi$)u#34#+mxVj@=b$L3*!b|;vxw?2NySw2RK8?q5;h*qK_e^VP385qu z-DVmgs)=B(9~sp!8B=sxoO|7QWVhH73@v_#1E$Ggffk2hk_9u!=Av#f3TbV2aqJzV zmV5zDNNCDj4S7S*Q4YpgRR zf5Vq}B3JKg^{^uUrtGBs=oYY9opD$`@=NpcsKdd;J~Ls#?{kmZ;m#zx7^|n22V-@b z?|rr!h?uC!=hQG zF3E9rNT@XFS61#Y;A5QqR|icLQ9xt4l046QnQkUkYYnN~b+WL*4=k3JThHc7~}$!`rk?{x?@47B<92LRi~tvSy8) zmpxLNBe6*Ob!NAw=Wh>W34GVb>9whUfDr^Me!MOx53G8Z5ZCMm5-ZLy#t+5=)umz3 zwu`q_CX!#D>M6Rh?#OubH7UYZMuyCR)rr}tcWe5b1roRe)={YJPH$GH+MfFe;*z+) zrGt1_|3?gKL)OR3>F1?OHfeHO=0(debXXBY6#?fmBW_$`T<@5?vAz+AOo#UG|_<+Ub6cCoJ zYT>{cr}1ETN62E_CwOF@=FT1QHv6#zz;*V%_-_31g*Z(Jd^1P5_l#`LY&8G%(jkPL zE)v*ViWJAEK}tD!0%X~eBU$s87s%3?@wn~rk$YWmHSpe}X|?&9!=0Ifn!|D5nnJF( zEx#(O{&SQ$`nE-dVv2&y`fJ)Fg`y94I{uj*P!Ac8ZF6jgX7+m~XIeu>bVe;JpL}jr zT-R)4laqb{xjG1S0mNzn-iOgYuSy=Fwy$^-|I!Obn2kP*fisP#0C}I7vc0>MY3W&U zoqI_UmeviA0+g~f-b*3i(9Xt75bpD5`@+0F)Hm!OX+KY?6K)nP9)swX1~;iRyMsD~ zeZ*~KJqaX3BH&i20n9+0J3WVXMX<>2(Lt8Jjo1Y)iLUC>N)rqDYWP?MQ4-%wv^RMz z$Q8$PylVLmE*T7vO+ozbYWet=qR9!$YUX&b6x)7b;JfHskP7cPfQ9H8sOK=QGtQf; zH74C1`r}AcarXE)JA%h{hT?+<6r?WVG+3J}>LVCBSvit&KPdUFa@zB&t$@6Kb}27^ z9yRyLkf$7Ih(uzMIRkcFz(K!ewgpOq`@V_jKx8IN|wsS z_8_E@Nuq8~64*ZUrzCT^dy3l4+pggp6avI?NT-i~$+M6`v#A?KTH6r%fo7V_%< z@cX9ur$I;znKsn`ko2rE#Jhn^xC+4!j&RC+dvVhdHzhs&3^cyb0Fd4Bn zbxTZu`$Pmn;5dX@z2YM(#?_ibhQ-(@qu|qUuAyW+5+C2_!)y;E8vh!&pdjZbZh(Aa zmm*qNi_(9nvm2K;pf!BM^>2P@5Ou3SoF~t&&ha~LAjRj>10%sQx27$YCSVV;B#-BL zk1YLb;L@%NI^LRGIDRL3rP=Tf^cidU>R$V z3lWLwc$eHuiFy46F3;|qiUq@pEahy}@{F!+mmvS`N3=x>H~qJdw6YM_)}T1lf4bw~ z`?}fTufoIsqOWGQ7?JdyXG?X3Q53tGe0+WwY8{I2*q+~Yh}z!_zd~4SP-jxmAGE@d zUN1e(GeT@cmDDm$gfZtB__mYC^)q_oo45<<_eZ&7+E)5K6~gK;Z7chjg2X9l{)7+X z!!Hue7S}uN!d^988u>utHn-B9ChxWjI9mr5mQ~!BdQa|3i4J2YmkwF&G;&HysrU%R zMkom7$*DmaZr)NV@N8S%HRv7EJe?C#Sy@_c5{!IOj_NJ78ZyrrJq%b+76A$?(KxXP z$F~iDIhGL&)?MlWz>kuopkR$o~Vz zwBlp1W53TjOO>Y#%$ltn`Nan|~h(k0~_sXIz<&-=#l^FPRopskyBdqYD%s z1wX(T$yo5DWn2`3z6G0NlisVv#>7|s@n?!~xWOtpWW^3{a|Oc=dk~*jQd%2ARt;vm z$d7~IOPIw#ZD0Q6HyYD7AJ2unw&~gg`U$t4&n-NMV*J+L$TtQ@&H#hk2x z?`rSSd?VNMYdXRX_gX*De|M(XzG?naWHz!pPO7tf>%B^wX$ym6JIAlvB(az+FTZcT zQGoTMsf@QR@7bBD^Vy`c`reX^)-%kk^D?qf|8HlW$^=EAiUq$Kz|| zmM+|YAzN;zcYD_rC3Wt6nWPyR$Gx#loWoPUK?f@bguAVho6Xjdj)4C8Z*8gpi0iK^ zpMZvuN*El`@|#Zfu8K^?6zPL0)4X)%Uh1RrO>okyi( zEZ$hEIgN7SWX_y$yPpbp9rg$TcZNfbsA!%QG?Ih%cKY4ov^s)JmyIvxK0`8u8IYgq zU`uv2K%qH4E9uMOqSyG$ z)nsCEad=%xR=SuD(ZUrpo(l8%Z_PEk&5ruKNwI1W9VFAgjr)5O+Cri<3qCDk7S|01 zDBtplsXjiGQv+fmXITU{gE)kT?^9jcEfXiW0p;EI$q0qaZMjdcSDui;rfxt(WJ$;? zD_-|hN4Vw9&fy2dwV$kIh><7+iu9tjTou~;Gu-ilcuywoGW;Q|S@q*HvX~=NNA~<} zu0%NqkVZOg@%D=r{<6xIYivoexM-pu;v_mxP(%j&10RMEKsCVil6OWqWO~yj@P6DH zvwXMDjMNVeia^B3#p3;%<#vEq3WTYD&2k}zam5a54y>Cg)Ase&>dE1U|9)s~wik|g z+f&CqcNxQ;$amMQZ{`;7ar*57>UdOxEr*8S>I%D=5f9S#T0Xl49qJb4uUorMW)(o*^Ji2jXUo@DrVivm~N zT>s5_V@o7#P_Msa_9DmMt60eYkVMIpa(xafOy+p!Bc6WC3C*VeC3;`M;4+FXWSQP0 z^B|7Cqq1Y}gyOh9fNDIql=O5MC_39J-b$$&_dGscIu?h%NK13YBdd#sZPhu~gLPFs zH0V0ArS5zr5X`xvRCvONB`V4)5bX;0v}Uydjb3Frw}oLaR---dCCpAHBN^>0^kMjA z%Ph2Ua!a7#Cp&6m+t!Qvi~)K}*c}m>r+7W}4w=F@G&1?-ErNphoVS@w;----D)UoA zP7yJoRQPurS|O*sfcm?&$J2Za>~d@ ze~rM}kTB-&-y!Gs9{t%Gq2{l)+idOc|889sWzp>QZMW7Nc~XtFkwqGPxqFI5-I7j( zqXF{o8_vVy9haRveKZCr5x(|f44x-J%ADw|B^Sl>UU2v;^;=4@9R)>+WRynV*7}qZ z)MdjAAb3pkwriY_>Uv`kLv>vY2Z-(Ttn~|UaW4OI1&I6sKj33TDIMKRUkaFqqbRTl>PU-{QxjTG}=l8rkho8 z{KYYte#ELIFfGB?Ztc~n*Jb_fr-_7%bu)VhD^q*F_cvpGULAB!wCt@FilI-ZSty?u zS>p@msuuCsnOO_I0M4gbVw%Fgj z|9pBlzRynHe{n&|zCCvS;B>DyKi4X0^IH`4A~aBQ|6`N_aM zKO28mNHtS1Yzsc|zJZeH`gXjf@Vg$b&fX>Fn+XE4D{ z_!?@vx^$P-xeQw>#D?(>_Z&Y(uB=SLJWp~h!C69@3MZfP+(J8H(nH?fO0N)gTM8o* zdi<{t%GMdQ{$vv)+O0Sq;p2rj^@SbHUHS6FH0MNNmao@F4~xO>(A0M(;(j+BL2raP z;P9IqXQTv;C3(zc@-({eQYpvxG{ZnZR8NlynqyGRl?>7`&IP99KoGGK@X3w-IXwi> z=TvVZ?0Y?~Dg2m?gAi^qtcO{f7&z zO_k{)AiZEwoQK#>q<3OiPAta`*n7=mT3BpAiF@3ZUz|s9r_x<<3f>yo9=1!@8s=0H z(f70X-6l}i|1Hy`=RaBiMK0rSP=zZu5CA_|#(>Tb%(xZO#LHgaDBc_~w-#-&N*>kf zb`hMC7K5Q>^<;_u6Fv)L{DcUve*v3|#IcaP#Sm>XG3;(!IS0ROZJ+v| zJZYHR5pnp>C4cGk>Gr5ULc3ks@>t*JbKQyD?S*QsD&MNi|5MVTXo(SaWo#`xf8Q-w8_>wuly$ZXtLw&hLpBuEI9AJ z#cRnvN5pBsJJm-TtO$fK2Glvg_j*h#PaM@Iu0V2w<6qkr7MOJ${u(9)?XHl$lewlV z0p@OCswA2XYOs8BLslZ}hz9-dBZg+-eIE%Y3=05E>PbnI7h)UsPW0b=Y%yCTfEgdY2P- zWqrjyB(M$@*xqK(a-h-3k3Y#xV1@>fzSze9^vfe`(b+o4 z+aJC@wNi-RjJR6BZX){o=jr}YQIllFYKoeO$eRSxNoN+Lz}!MlZN0NMc~MQdzbt_2 zec4J>g5ha%zao?*j6ucI!#5Z->e-_j563wAD%`2w)NdDV1fUhhq~F-)eIP?4KJz8c zDuu-fi;mXP9}gj+I2r#bnZHJ|g=L;OzdS)04Cc%mZ!bnp)+arkWI=e!9fib%{Ct#K zMK2kj^?F>JU}pIR$%>=2e5E5!!lBZw3BVSi`;Jhkl0I&6Y1^&jr``M5Hjzyz9D|y1^=9)3h*k z@#JNeF5c(D3=kBSuGK?3V`;Uml49~Six za)OZDH*O`;wyOFRZ=0yy0HhF1pY^PMV2azZl~B z?5`c4ix-OCtd6-ETN=l7M0~jSUTx~GD*jJm zOXVhuD&G^r{8$9T5;Y4;C0l)if(Lvil^!Lf_Q5~!H?6W3JZ?^Fk!c2v_upm)dbNci z(JKrYxT5%+xVTHKD$m-$4=Z@8O6t6)_DiDb!kz5t>Wc^_`&W5rtrincYnxh7l2yyT zWre@oYUf3`Xi;hM@$P*oIEFviT6ALcll`wB(jDJi&VMjOUr`HxbU7Q3ck_J;Ccjcu zxe8kzbb&$VnLy{%+Gw!ETPTEsN>PKwRhFtVA+!@J3=?@y@$+yPI5&L)8q;K+5kGka zA833dEoH-uTVhFE68HBJ`bZue-q#4geVy(<8o5?iFMPM9MYy2X@x**xI`G8gv!Pr3 zKn{0}^Pd!;dr*Aaf5*eB4tj`0wpWfmt#ze>7om*SY9)<3@^Lbzwzztcym8`w72mdJ zcR<*J3ZSDol~&xG+IigolyY9sfnQxcRzZ*t_skB8vP5=u9?9gOsN%B0uGr+1@!A2P z3|-feGAg~?#;H3i(e>WXf-BP;7=x?&Nl$?|TF>;~*Z|4>x?pdlLS{)~p@wmS0doU+ zB^;OYepgG(5f=TL#@+=T4T5#E`E1?0R%f)>e)qm%tE{#Jywn59Nh+Cn!2w0QmN`>WNMrWU!H8=ZiSb!MOc} z@Qi33wOc$_&b_3mdmMSixBh02WA4Ne9U%OBkFO(uKms+r3R)^~Dy|djj>qc^Dk`gU zD^#mb-`sar01~K<@19m=#-RQeS!Ws#Wf;Hvu@Bh>iIQbV$d*x-?8Xv`WMm5?rffsR z*!P`C*@h5hC+pb8zC_HVlCg}jBqPb#VnR4`&gcBk`7iJ0^URy)&3!-j{kyK~dzHew zxi7fEue?FoKM1vdRQ!YYeX+8yDuv2v9^>&Y zp&Xn8d7ZR(pGr{^u6a7-@aDG%ruoiR7r|Pwa(7MmEa^@Z5tn zw-!zB%~3=+o%M85aB=R{I9Ey=CQHwt;~VSJB$?Bsbo8hDTEN6m9^iL(hdqMFI9@ZB zHT^d~h0_I`-u`VwNd7kC)0X}SJ?5Ci>&ppQZ7;byGXFS zbX@tl$~(fmhQ~cIa1QvRM*6{wfdv1@1*hte3lY56QIIb@T1P|9+YaMB^~P~m%z5xu z!@QY45oF3b_&X~IF3D}9s+%z}a?`H{YB0VarvWJPEUeBChI-jQ7xOBELn z!ilI2>l#|%z%m7q0DO$d!}KtjWmVh`ac#5EZLp#Kk>HLsI0w4^#HuUXKtS#ipaht> zFHAPOE_r>R5k(_Lh=E1v<>+%{OiH^)f_;dDBnM2^7|gTp74Ty$_2$bEK6(r0cyZ~k znV_=Drt(C4)cBv##sI+|WSqdG{FU{7@S`JfR%gb0^yu4A;iA_j-{A_5DzS=$tGcd8 zM%QNzORL>thD^KvUrD0sHFjVDz+Mc}43jwn$fsTEmGzYIq!XXf%M6VET$3{uGX zqMRyg625-{yW<9wjU9Y7d8@W2MaZ;}nqOIB2Z zx>`j1av$G10^DP3dLT3C4tZkH@l^ZgorXeiLU^ zx>FXQ{hqipUsMzd0XW>yipbMC{sULTwT*|N+P+y1ew}A|{Ilh~&tfrn=i>-hGKYg@WC zx%}2GKQse@#ZKE%!_UYCRG-Dd3OBoQbQIxe0R^uv`sMp(X$u;+c1Z;pF36yvj z>c+x^ouu8Tx#3Wnkj?U>(n@`IxxGkI2ZLf3uY#$bm zG(0m0UeioUjTBGM9Kj*y@7q6fDhP<|vb&iSlBYBVm;Y^`t*-E^q2o)m54kF<)H2SX z=3rrB17uv{;=U3s>Rg-lyJiBT9(IeW8Tw95tP%pzStf(7%+70&Ku~~cZ8BRU&lO#z zuv7~;eCOv6<2^;HuT(Re4pNZf8pB`C9~kTDnm z)018GyEO3DxC)~L;4!T)gZ{ALV3-N9rmIo3sJMs>-MIgyKi^0%&Z11kWk4A(0_GXA zP#jNM-~K!J+aC>%L1Tb);unW-60d1zB6VmMTQJHzCXxCHob`RV4zmzKyrtCIT|7Zl z*-EeQUu-?tJYGqid}p&M*lz#lY=U@1BY!!*v{t~?hPX>>Ir-Wh#OfdRPkhBPnHJL3 zHZX;RR-XNy(CT#%*M$w}+Z-Xq=Ol1B*ZIZbrRXwV!!&uf+q^>`K6VTIq49iiI3Q1;P1!pMT)Ho8ELV>qE4~4J5%we@&V*bqWZ;O z?WviAi8AL)nLzBWosa1cpYO8A{7eWl@q+v7x15%3}qus$(^pJD8=OATpqSj zA~XsoM($XZS1phf&>&-o)p;qAjP76Ba{wKtipO8w!hBo$^W-6%b(dbI@`;&9Fcb*# zAmF({PPqFW+TV_e1z;ufNu}w`hvV$#KAJ@t1x7sgQQAnNgFzNGytqYU{!^B8+_Om9 zOrJzstP3K!ww`hZ%*D3`Swh2g_EJ$7z9fy}7UV#Twf47)L;JEj_RF!I$5-MR)0m== zH<9OsEGwPp1EFvIE^_)Bz8qcU4h0X2x7O{G8ZE#OzoH7eitt4Y4LRNIrkD4ETevGY z5S3vn1593cOQoPKEc7sOp(qFyC@#r=*LBNK)Wws4UiFg|SVpIZFM>t&M8P~{9J^e; zAgQ~cva*BYg%+>X==|hMo#na$STQ#Iiq)VjD|3BiWv2yGC;$?}g>Jm1dJD6E+BV)w z=)S>NEyJ>(v;0ZsHDCYQ-uim`&9*`1I|jdMUlB^L@bVd(o1}Hj5xm~byc9A6-4#V; z81qjVXDr;Zk-o14&tV)hPBk9G0pqJ(2gJFfQeP^L>dRlM(DQ9KN?>4RP6Ftn7Q+=c zA&RXg*LQmV!jWkFn2IR<{~#9=;Bej%wxCXfz|UgB3Wh*9n0Mmas>SmR&NM zk$os5uc^Bv;?^DkNFLeqKz$An(12ZVjt}2ah&UZ~&^q~hYB6i86@2nVcYXSd)@OOV z*yFLS8zxfNpTah%kxMu!n;X$lDB}ZJX6s1DjQXGNY`-4;vx#ljykP!J(^m>l6N8N2Z43TO7X>{gYULhkA2%y#o19EXo+KV8 z#w0aULSzKBMnT)De4Roj?;D{K-HOIq zkfBgy#eUF2&*8yCRBvJKUT4{1&gmvNJeW)6#vl<%Y&FLa)E9-q9;zgq9HAoT@g3iSWx6p`yb=}&3euW? zXXLrI7tEVI+Q5#aWns9*HgrGnBNkZWMazCJ$dWv#R5B`7+pz9>lqjf?rwa zvd^8i@Ib0J!@1-q8=_@M;17)l{skt_fySMob+kgaD&{LSUK>axsfp?<3I2Bbs z*Jk74KLM!2bk0b1w-$;@gsWL<8F(^cuvP{1PSZ8~9xQ{)ayDntW5h||z+X`;+(kNk^6WM!#LqYIXdcj+Lg?1lAI3RF z>)ng1LbShgakZfjnky1N2!3f7_%zz`;&!i5@4a*Ak7no4W^)#jCPFXupXN`IY#(Ol zCiM-ICJyE8f}qwIuL#{s3+LIGRJo&!1a|vFpE8EzGw|U)>2`!~q?3C-odYGnMfqU? zD7~O9V@4gE!MWtFtSZK+QuaQ`7a^dWfibUpolpDY%I}%@qt3axP{#C(it)~%)RDa~ zTlR*L$*aJ!C^&O@ar;!o((<`&C7rfw+7El_>I>Yl&*|+uuqQ&H-iex@#_{hI5(n_4 zqy((fVoy)^?55}JCMR_TDP(%@9^ETRSa$S2dFp-twI6ED?LmVO^Dl7aRA4A_h@NJ+ zwTWl9wdxEl`6zwfSK^AShEnSGH1;D{-2dBG@w`^vt8>ku^^Qv$htW3T&e3COI-;$y zEIjnC;3uMv;__t6XWTKoz+7afw;9rBo;f^CrFNQKk!zxkQHBJ7Ns0!AL8V}M@kt(+VWaaNb!5;oKK$YIWLbX~jZC?rqB8gf zCsi%;`nKq=ZV14Y<~BIK*tO^}9PBvPHPhy_9WvBei|9%o2wga z6=RENe@oRexmRxYtnhhWW}dZjZ2!hTVN1e_H9nDETb2sfYwQ6+}900M6~hpGtYgs z^BnJ7AkA|OzSy2T+}#=EA*8Bxx}Y{ z+vmaOe2R){E+qqZ5Gnb&)(Ii#>7>d5Y$2f<_YLdzlH1nC$==lrD-E7}<1mps-uY*m zTJ7*P6OG5qF%>8f$N_hln_V@I>+%Ei%lAuTo@FqC;`QAu$}AM!e7CsA^xp6(-}Yan zk9i!V7n>I+U~KU&UYs|o@&K9H6TepfUk(%6OkKl3aFT_jf@ksC>VCmP``En86TjWv zTX$-Z{B%)xms$<8^FV(F>FeU3NlP>N9duI7Kwh1wRl|P3oBGRL2J|53Z13Nf7rZx) zt-#EKxR|Ds2XlP~{^WwdjWBB<6#^n1rhnEm~5G3OKFV-tJ06-%o{9cCZz{PUe(J=f>y2CxIVVt%bb#AYN?VhxOO*;^! zBKJBb)73R|ROgeRt{1`a;me_LIieXm|@xnd+S<5F` ze8LDxGr?f=G<%X1cyJImjhs|vACvv*T^Oh@?WbOdYxu;U+z5j5|Yl!pVz_tnCj$4Cm22U=H z^lui@;*VVT;pFkI9QX^ptgq8kns}UA^2a}AhZzoWpaBUYR3WC1o98aP;Rf;G8a80U zBBz?+dQyWU|Al+2#(rF2u!#u|dBZ6B|Czr3_o$Ay-(DCXniiZ)EZAvS#P887w+SS$ zDGEe0MOE{Bmb3FTuh}7#;OxP{qE=d0Gu(rLsGbrv~wF z3v5$qa`iezI3r_^*v9o&?R|b5P%LWgrwGE?(rfzLW8@xvN7U?1(SX<5{Z(hX)HCg? z4#h3;94ZXcYt)s3X&S#FQT|2e|Q063U=4Oaj_)0R4^s5Ax-Bm9~3MP)6$VQB^z$IhTr`TNY*gyAvc8#&7V!v znzv6Y7Eiqys>hs8cc(TtmDAl+2qixif7bV$cw9_;Dl|9usbT?tcP-eKycf(mqL>B$ zjA}@{t^NDYvvE}yl$6cUxz{h(_6^@$1Uxe*4-~LGe_=*L$dt~>rW!zRhLxsXl6>VY zu;iBfHPnCWy+IDfpgeTGyK|PHuIVDKfXN!wa3b%Obw}DnYFy-_9`8QrjqsnzxL=2L z7f6g@r&7eqat8iUNXH{1{t#_5?27y0c93km6KR1Rmg;BE4W9oQWt; zQNlnJ@NtH_tmhUA)s}cdN!&VHDgtS>^|WN?eISVvE1k#(m7*UVD%?A9H3f^mE8K-D zo<2iuJ;dJ&w>-Jni@=<-DG-&)MD{*6`IXj7Hl zt!?qnqyW6$k<=YYrHGuZ7e^jrw|b8$EAH#P|K`|o8G8|2Qxd$+$q@srEGahWz;MGuwG^RKY_*6Li8wIq~NG(_e^s zhpZ{P#f0!j0TS5u-;8W+4Gn}#tkZV!c`w%ctLdy@V7uuXkZWHK9*=3h7h(F3q{#o7 z^qVvKR4FP2CfdI|$9rQ#N7Tjrrr9mVo0Gb622Y?4{Q66$f$hD$>qv~Es9?`QpY_$P z{-ru|mX0rIXC1U!DKAzHAbp7=_N4^9Gj%3^5yOv~7-g?ai5GXR{GB-}i&1>y?d_h* zlJxMl&KGP)BC6Nn)0VbYQEtyor<{WW(qKa4O_%uf45w&!acj1jfAp>C3hWz`uFLp} zTX!OV42FnVYd<_QiraYnW!N0&S$#w+6ngMz$}S)>@0Ud;PA}XRHwjrTdQ(uU`7)Eg zaTdd9WfP*#WA+0I`Z(&nuLO+p8Vpm6WVW9vKXT?L)l!!(ydN1ecqZWbu=}2f`&^jx z4O1|ybKlDco<-6_n#&*%=aBz2*2MmZ4Dux3GO&rGr-OZIIv=ZjX>I`J;-#lw*gEDS$=|iMjh`Gh5z6NSf&&~ve1ygH*EZdFP3(N zE`>Q9ogHRq>j)+c+I$EXymq!fva*S%Or7XvMofvEt}yq>r_!U#(e-GeLLXQF4qe-Ir0Z{ZHn$cSo)7Q`NrT6mZf<0X?^&A;O%ooElanepczmlXqiXt=WP&E0%}Y8KF{jc7|v^2^o`ld^c^R znq(XG=O^vGFLDpPPUi!j8?g6Wj+RK^9tzo`0E|Y+y}WMVWT5}n7uISJuIs&=(v-ey z=-Nk|l>t;!gLfljGpF}I>*w0%y9}04Tf#l^Zv%*uTxfwV?;y|xewyWG+v3kL$_VuP zLrJw=1DZ=8-uFU(*^*XJ;{NcssRa?8^q?Mzw#m|Z{s%J!W``|{Ek*JA6r^2eFQeY2 zM~$1gSjsEbE&xa#_rHb(c-GXD=IPVi+!2ijLF$gU6WTU7cn)_o%XK`Tf>~dSr-U$c z{cYCLtt`gb2FXtxDKu2qAvQ9`S5)N7iF9=HI&_8ApZXY?wr4LKJB6L7xAyk}Juffa z^N@CPl#gb#FwQpum@UbreCU#^CvHS7H{hIy|&Fe`hs#rxUXC?WRbI_Ql6`p z2~SmC8Upb8Oxdb0%|(F^&gbb1@=s*D@^3y3XE|FQIXtj9E$BTWZ`3=TKM$5fz$k*r zEy$|8C~?K;z6q=CS1=9*1s|9*-4ea4z;*krq1R{}Upj7kspv_ofnM7!Lm2V}8{i%c zP(KE)mD!u0FSM10WO{Bfz{LDAs$UC&Shpvisuf*~8nlYonWB*_-aq+Lr|p!Nr1Vu2 z@)eh!s|NmMp@CCs8ASjtevr9>qO~*h+J8z-ELKPjP1C&R_A$X9ehMev2Fm znUeWh(6EXeX9k6S8qcSL%gYQ}&^>`&*#Ro%A`?<_;LhAo=*xyOkO3szUexU#{3Zke+)yQqH_>yK zn{h)^C7l<<2Rq%=`>K`i!k|3v1W!Q|Y0AA8KCwN(5)#yfJNLr-p{9$Yee+!$YtoBQ zS5YNX7+yk8G^e#_ZCDBBDwN=R^~a&#A;oFo(|8ldM}FrUm#V`eB4^B3h;56#k?Ku) z$uCrk6&QPPp7dag@>M^r%M+ekYm@4zYh&2(%Yiq*`L-a*m?Ro_f|u6(W=&7ys9t}c z4U^&-RAnz~uMn5_ywC6QVst0$=0>imeaNFXDV=vW!ApO+i>W+%D3!f)_jR&mWK<2GR#K^@mVmW0>>oFC?r zkc>~<{iWlX7`1+vQ;^*!vkF=apQnrZR@=?)b8xYkNP~3Kz*k({4C^`%JL%-uvgV{tLP!HXj|xpN6_e3Gw}1Za)CKIQVA* zN9GG0Fp6c>jIZ37W#_k=hwXgQXQfkjH|aH%0Np~Xl>lDvjrtW6AX_@T;?=PQQ}}a zI?}dRhis8Jp%vMEL*L$K%Y0-}Ga}4}Tz2d6!DRIW>7;44U*C>8-{gedYN?Z z2P?B)$7g)GJA|3j;L`y@nBXR#zEebV>tkmu~&f7jdK2aoKv4g5P zr89Sq6}Jc?MRzmI*A#lX7Pk_rn`*sxW<(D3k0y7%Y7{nhp4B*oH!j|3{jeT}%-Nfx z(eZkY3(nTCoLS&y#}xI-q_q1SBN4s#K?Efy`P^Xs_@)>z7`r-ugsfx?q6XYhO}i{J zmZ$K%vN8v&A|5rUoL$QAXu2cUOic^--;^{n-57wf^NVG!KKnS-d2`WPmWCS%_S%av z_JayaJX~|rwQPUoER@h%t7!*9j4fzJ-M&UY<^c7~rifK_V|3Sd)>)13&E9zg&L?i- z-)9ZrXgzIflN|-2KbmAS)%XOdkK{Vl_G5rQ7jB)SkrdF$tTOZ#8=GMre+ZK&%R$!J z5;xnv`#u7XrCFLFfd2F%!gnk7R!;+|Q@O=7gJf{8MxngVBJD6UI6_h^A~S)H8-JG{ z|+vr=;7|^zcq=Rzzt{+ zJ`UDa6rh^YT>1A74mYN!GwAA@5 zWbOkf5uLT5oxef9DUo~BUWSN-_eE|B+A(yhrSSJb2R4|3s?)ScP2Ou^zotT1F9|;; zdXOSbE+Wr77t)h+Pyb$+w4PGv(frmOc04{Y79nego5nwrE*Z?Z7Zv1b2ek?8SaaQ__@(r0@3NCqF$P|vA$Gi2~e=t9h-^h zp3MPfR4dQnz;EEw(GL@?Zi7*_m6G+oeY~1Y7OqNg|7wf9pP9bAuJ06CqYyp%f(Ca1 zSsMr=r65L@H@N7MB*m*z0J)cc9Mo@IpD4(c6^GFMF;;7vT5BF5J6#-UI`i<_2tgk| zaOws}p|#F_?<=PV2z@AlGTy|Rw4>ukjQwJFBeWVvzW!UG8hOqfFw(hS^#Mvf02Voc zSwz7y23a(prT8lY7kB%2*5avbG<1c_=jIE?+4QXeIG?z4l)Gr0P|;=U>i6X3du;xq zItEYvg*@I;851o2#32e;m=B~-HD?i+ULELDZsyHkQ;KG@~n75Rm6eUWh z?}|8}7)vbS=lx}y5-NNpUX)E4+l~@dN~g zTa{*m)kG)jq~Xo;(SpL{n_1O%+07~wDXV_7M<@CFfVh$YJt#ZKE`)L3zovHFP8n<) zYAecan zUE{Ex(!@na5Jzf*&GZd0G7x(bq0LuVC?b;H8+rUzv7YoPcOP+)vK8nQwv&<^Li^rV zsa!JPT8V-x#fswW46Neb+1e9&YHunq8%iss=_AkOX7UrHU{YYysfAKL*3WK5r1|{k zv?9*Wfi`&PmLarAI-WQmLX}fkr<21)(UN^&wsFOugR{m0$;Pe{*Hs|&P~-L_o}@fb zX1qzW;ZmBnLRn>!k8zybXItCn(J9S0rSRp^jdRRB$EV9}y@!MBw?1u>(dtvhGX(#G&keRMQ3X}>s-HOSccWFT zowaL5LJlX)LBkw&%N3WrRC@ZYZ!Si4iq)+XZ~b1~4ne8@cIusjm`bk(YNx!EVEz&x zhPl?Sp!$QP06|;5tot^I?Qmx3d zF-cLf16zdCSyf*>kdDqUF4sH{ROzh4TvrBc)rBBH%%)&8x2U0wMsCeHu_$Bi# z$bW;CVKY;M5h|M_BxTb4?+_nj+QHbfqnot#;kH#vPSTTZ`!>{;2(DI66FtyfP-fs7 zbl?+lIJ*@|wVK|=`NHP*=-*D~F6-@WKjVHZs>T2igNW-JYXl`hKRjL%2_7_OS1o## zZ0W={AoE!k>`WeVU1s;FL+vp(V8*#pqBp184p!&r_gCifr*3SY{PUNR2AjPY`28bx zM%3S?gz^5fEt1mEyghY%K9^81ym_YsON!OO#W6~0yjUkoe#>X|Z~F|6zw&lkCRv>m z!w*M9>BIq}x=+Nxxj4#T{*kvQGx+1Y%rzcHx-S-{TjBQ40`>wn>4E2>z~6y1jsnqc zQ%P=cQcaNqW|P(NWHZo%g5bXqht4y(H_?ETd!8qp*)hBi{)_|Ph9=!MfR2Jm46NV1 zDL3%X(U4b3*bZQ-MIHk&ul!@669W8IhGvdY$?aCmR17}1XSU?4`pwR!;nPN91{X3j zdI}d3wm(H$bDHlC4zO7ppCyjap3hwV@U*fH9V)+9Z31?%0*4h6HR{JbauKM+LZHY2 zjF)lZnY|s0-p$d391y6er}ak20U`5==i=!u7Y!nXODJhq( zG%k!mVrdOi>w;F?m@}cR@IEX-6jFyVLx9gSUEu~_Y0Gw)Ds>Z27PY#E5GyUcIQX;M z>A#8Z#lQubMUCA8fu!Hzlfm6avmDfouRFy>3#ZE@JYJQ9Aps5v{zK4wTbUJ2wM*^m z>@eDT8m2*7T>On%Q8lIq_^XO*3}`NNA3OJ#?Gm@NPw|Uq;|HHni90(ZZk>~~!p_}9 z)QC#G&nY?b5G(gcmGqpJ4d@)V1!Oy|dLjtHK%|#T^xFedUvPh;Ut~XKmTw zN2Q2RkH^$|+lKp3*0DRhGa*$KktH&w8X7n<5-0$$-b|%qJ0CrW+fwSh1<`PCR+kpV z>Cv;%l-op>Hxe=~@KTzF^-pok{|dqMS6#KZ9@-XD-IM~%!W4j>qSj1J*zLRTAfTlk zp&w2x?&29bc-N8OXN^4_pYQUs=wK>$4YAIZv{(Jr49zoWyUW;Ir^$*LeRUO>DF8I0 z7FH*+C}#d6QO$El%EX*co9HY!Wh{CYvz;Qsk7r4z6KDSl(v+zI-bh{WxQ5Rk*GPeQ zD9dc`Ty)9a?)LJE>Q5yVh|jp`tvoINZZ`LE7s~pqH-_1TJ7^OxuJYp%`H_c2T$_}* z%DJC=p>|G{f=e7xesW-$I@^uHz6}qv<)UPpnl71LO}aJ)$1M+37>BDh_dpE;MQ-=S z-$ly)1quH*uQ<_0<=p}kBPtuVvPT{UXp!kd_rsD>(le8q?O z(3~N2f)SD{wi5RL#al{^$S}}FDuTrmtRkIlAY$JdhE}2Mo$}*R-dxh!3a)R;s z$!VjaQp^#wpGA@HW16m-fx48Y~Rc6E&m+shmadjwuwTav*thk_nM`3QZ0Qfs; z8VOpsj1UG@WB4S?t4)l-(wMwkufIMLFv|Q%E1pAto}VVr)gom)mdp4AI*Aea3GR%` zUC)g8V2O~Y(59spoWXfkuw*&TCS>9r!nC>Pz4zysB*l#q_B=ISFgx0_t?plHd<;Ok-aLAcPAr}e{cKc27Wp|a!<;$nYNOi}Evjfu8 z#$nkI?ccvP@$DQ5f7}AbZDf<&J}X&1lg=_9c_cbLwbV$QZeaIyZAWWs-dVBmB-!m? z4_7rpRk?GADF@;VJ`_%}AUrV~zc$Qnc{!m(G0zs~?c^yDLaqDP$bYc(`%^5ZzAf>k zGru3pE7wxYc{=WnP`P+?-7P-&A=lYP0NdY>1T9~GgB6luOMedp>S}LvVaGjo>T%oB5Me-XYc)J5((k(eDAOLZweR@#b zI&yS$>NvvYTrKXLQNi@YpFwCb{45r|7_Oyt`ZsKKK1U7_gt~}YaU2PWY^%r23!^N8 zLsYeja#-`6^pYlWu61SkYN~jz<6RY=4qv$Qmj?Ppp#p?Prt5t?V4%whF5Qovg;I>- zN~N=gJAE|qvd+G-4<0d!mGQ{CYCaOBOAN4oWAyimbAi4I6L~@hT4qbME57U5Hte*( z@_?72L5IsNwGRCV%;b0DF;59M|HPkX^g=)h5EqouH^xSj6{s=YI5Pg$=aVRW;U6zu z1GkAZ&`X{b;n;1;SP}XI$o$k*bPvAycI;PU$m1L{-zj2aS7@&e6E}_O;mjoe6Q}x{ zIistkNT>4wlPQzp-AT=fk+di-2l-_YyI$>Y6$^lyRD?aT(|m%F?W%uXTiMz6vL(zT z`)TE%RbHL|Zm625^;qRxv}$fCS>9~LB3C%KZ16L#r1HgD?&@qD6F^kaG>&FB_@ra_ zfp9x#<_2z5f|uxstGnbFakSaEwp*Lv3_ef6FBx-!C==wmcX7O==tvP(2!OjfU9!?@ ziO%>rqb{omllV@_DoaXeY+!mzqS-@n+2t>gvhA>2E#3b@WSkbZJYk9*Dljn@*H%p7 zS{b&tM*)<1JC`u27mw3~7}!8HW0L3Ru@LU%()>)q=KA{X@`~(09r4}%{sz&#w?;;p z9T^eQ>AQ_rb+|jev-4;0cxBn5{HcIPb_^7(!+0K)Gm4~)(lV5Hf3!**e!t}JqKjOH z?gBGu#O3EOkGl77wk=y|m2fnAUGrTtQy90H8|V1n>wTy3w?m^~FTgUE)#YyOC@R3Hl;F{=UCb6EV_>3tAm^x| zFn-vS7rYgI%*Hsea>2&_YK&q+BOmNM#+WOWTN2ui8i$7P%Ne-8{@}avTU2jAbG|wB zF-USBNJA&V@V;YazLK#GvYX2*k36T%|LYyTBBt$NPX*g*+5{-MNqDw_Ek!Nv7Qj`~ z0`@zszYDN-$ZHk5t%sj+{B5gububnCvHCZYV{>QaDDrG=@$}b*PeO^8@dm{gP_+K_ zDKbx_=XABei5BvjT;C0{12|Xb6`#fLa4mM9Y@Hr0{$t*XI9^FC5X{^5t3ObcbBf%L zkM>FQb7vB6qpH+zZSik7RfPr7R{!0|EJsE~BFNj{FWfKS4r-;%srP8NnMkr3DWMk# z6bC2u5Al5&$i)~j#>_Tu3Rq{?;qnR%-jL$1Uxq z6Su@&8t-Q!%D|bm`K6n=?+c^x?>t!xIrxWYkz52`ghxe~!QbopHN!_)_Y~5kcOkq0u^Y&9l6=r}i9HJ<7fWlJAggK?g@|CTV7 zdW%bH57~PS!{%N!Oj{)|gL7YYg2ICGL~>52A}Z})*}@YUL^V{PbWiF)Um?k(*7w1T zvJi%a%Y4fqFkBdf;pgsLBSr9KM@gT97{myO=3yVRDbcx@WXwkxuP9t%U~y6tb5WFblOnr}JX z1ge2Xu2&w`@p{UgPi~b(N6f%X8eSA=Ud}LWgI_c-aqYztdxQOXkyebO0h{dfX< z9w8A0*tn{7l&Q3S9bsj8=b3HY4TgUfZV#T-#-qRL=fP+#JM>@W=H~4EAJaW)tBH?J zBY4>!Z+gqg2o?$&tiCj+64b#Vb6qx!IC1d6^>jY)P zA$pN2^67f>t-pNt4c#PbUjF`7I`dLW9z($XF;sZl_Sy0CrOGMpOZ1(?$d^m+TwsVM zzohN$WlqG}KNdMzu(Z3l&N(`n`Ne@{py-kcPF9|B`0rBQ=Yr@bQtIqwl_3b77&EG-LiruRn1A`(CixSh@EHj~_$yd+Ww+3T@pJZaIlPVaF({)9J5Yc#+?c2Z^B@ zs#?V~0}-_?at9T87WSbyY=3xq@#J&2QeB!?gaHy)x>776 zcSKGPXtBB@)O0TOD8wJhytI6J+B{u2uHY16^|!s?#z!w~AMA(ZlA zXGEm9?(k&!uXRoMFZyCH+rj7u$N2q-6+t`)D3J<@#dyeF!RI3V3(&9&r&akyy6nuu zb|ZuGAjZ3~iAxD45)sn~Ch?WPtUEbtmV|?vqw52$Y+~sth+@PpffDQw@Z|PslLoWv zJfA4k(V&_6mv#&>J6~fLB z=u~pQ#%Zv)=>g0}8|udHw>|RF`%~a{xC$=LU4P&dk)HeK@!4=MpWJBJzwJMNpJ^zZ zJX42EZV*pMn*nt&bOnACXW-hrc&=YOVqvcM;B+vNi)I`;+h20-?~?VZL{HJnL_J8u z|9f@JzF`Ar%2$(?zGl3k{Gy|-?zc(ZewxJaQ{DCSG#&Znl}_e2QA}yqO9g+~wuYJ*U&h`K?G5{v!JusaD1*Iko;Xh; zX}&}&?R)qch>gB^FsjBtC$&<+8&DcN(2Xb1D?V8B9K5ykX6NF(3|s}8iGOo{Y7NIh zXZH3Gi@Si16cqy3sT|wf9Woml^7k3Eh`)`V5UxYH#H}S(tSDyLnMgAMKvQ-Lz1T%- zcxeG~14ZRBpQu>;cW^=(o|COS}DzR+Id9&T%F0|%F!&i0Ioe!WnCc_=m05CPV@by59psiI6 z&zG;A*8IZNIb|wfuksRmp^3G3p9cm?r4kRnb@yL4p;ZMyUp+xShsF(eZGIpra||eF z=~{KF@cX?9)|N}z!vaiys+VY*F4JJf&g zD6kk^M@^)%)CIJORB|Rx)^g}na}F{mPTHQEE_E2AiNA11=#$F$xG?f$Rs7q1BnZQ9 zms7!lja2XMniY$QuW!|tR^rRlQFf9=zHc3s_z)ckkH_755RFKJ2(bVFpzh zM5~*rWnG7?%!i`IGL@+z@8%L~-5mo@HheN@*17mufL+Si)YO5~*~ZyX{prz0KUH;2SNXsT@5z0&In1jTD@s>S$i)3R3Tbykd8AoO#+0V>w|V6h%bcYWhu_@ zxG58RHYrN=fepnkO91t`-4SLNl%k%goOAiqupkE^56j-4hR#@7pyRd%g`In< zDh;}JH=c%B{&RSDcUXW}s@KI83H5LRFNjg_XD@$_yQy(=L`4OH$2_{LQuqW@^Dmu? z3b=5cJp8`i5R_9r`i*8oULak&szkrGxBGWl(fh*#h4(j!$;qJt^fk+Fn-&$|ZWWdG z(PJ4`i*a?`YMq^8)Omu>yjyGOp*`VDulhBc3BzKTd4G6MLQ;Y-z<`J_==4ntp0-9wfmFlk;5Dx?*)hDajaGAeb~S zJ3xAlHn5Vg-?;7U0`{ZcaFYgSS7yCTUg+MJ%m#47g*>D~UQf{IsL>WydvDUDU|n7nG+{RfYRIIVj?cn*ktnTpnh-Ok7%53g5C$U z5tJTTx~*E?wjT^OpW!uRLeuT2OpS1}dy44iJgDPV;NDv5bC-dK%kI_ti1AOGR@Xjq zlQ$WGMC?`OAO7$bZH~++A2S8GCbqGO5aE?Xzqf|ts)m7%tAf}mqBhsrt0C_L7aFOZ z`cs8v`&Rhg|J+7Kla~3z#i;j;(S3^Az}BqeG%65(?+-na*?X-=R&B7{^;5UA4?MUO zpI1TP?qiL;J^9BA2a?M}y_Y=KDX~4hzXk{T!T8!;4!|$`+4}hE*-;{Oq$5h=HfPDu zvdPKOSi z8q0_uzP=(kSodFo-9}e@U6mS+>GVUPt8P(7;6~S0osuj$7R3vJPW*)rNwW+AdYXWb z14`snZ^&Pl7OiF*v{SjM+B%H9y*|_IHlc5$u?|eV-rq8>nf`UE`b~z7o6>Fb^`y

JTON-AGs5A^Km6`zM2~u@l<%VpW&MMtrYgyC)H+BD zwE9lv{3xfDrAky?0CM<@to?S{&(H1Qe~k-XaPr4i{1X=jfqxrJRRt)b{hSkUQyOe${;Wc`iU#<83}h|_D|4e zWqq41z*MC2Td!o%A?@BoqQ`AdiLLOQa=3`57c)yd#IO+HUll13p9ChFzFdkIdVhv@ z)mhLm1I6^6Op6P;#C^J@*>*N(Q|9L8dV?31y>Y~0Z`AdaJ}-8#`UDg5)f{A&B0`3` zC5Z9Wbrr{io?|-TqXYSM$VLZ&6`#^m&V+-t$60^Hh9;I6Lhrhw&^1EpEaSlN!I!aeY7piFXR z{v2O*DuYm6#+TSHh_|zWuA6-gv^3`Qm>zpq0M;is-8BRbJde)2Rt2N&ZKf z{P#8CIyPL4srbRj?F<8=xeEk-3CNL}w@FL$;D1KxN&$iBN1Zy{uU;yzRHcl7@o!$9 z98aE04*lCbz&o9-o>vonGO>$36M@Pr7p(?f432ebMJBO-PfrS5F8}rOOtcbZhI2&3 z#p+Q<$?i#gf0%M+v)cJZX27|wiDn*qTnynNeeWWKbX|To_TTRN%<<}u+AKHVwzJm2#7!PUQ3JkVoKJIJPKjR^*~a^Kn&^Jd&A4qU zZ4%Q)Kl%0VzM{{I3vQ&P24&mismIq;{_Q~350uwLj|b21&+tE6|2DuEcz2OMrJ^bP+lJ` zx~i=}zv_2S!jT5C+2a|5O9w`Odw$G8Bv<(}GC$1mFyP0We7Bb3y2i)mo-JRXFq`?Dk&2tPMt zRJ+Y{X;OEhl={9`Z`}pLw@wd(GQXp?NJ@oy=ux99AID85*C7kU#L1GG*s`6EZ*%Cn z)g+2#vo6SvE$|i}+wEkU=_Pl(o~D^~unxH~{wPXGMTKj^sYa_6TPH&s%$eR&wDlV@ zOZ*r_e?Q}~8}NJi2c%eH<27}tD>xr`3aa#U&6`hhrbKW*(6_hzHv9gjVxymI@0abR3TAk zKli#z2A6#G^Nu3KYmm4c`z~N!8L$K@9zM}STM-R)=%x(@AkV9fjB^j7I0P977)k& zRx_Sb?WHy%+*8lS#`+Nx}h$RrJoT#w*Cs(tA4GHLGp?YMC^TUGZxldWEC7lA7Q&`*Xu ztoC5{q}~%Sgw}E918llYZ>Lg}O=i_kpW6tpf0zAPw`P6aaY3d2Mp1lMLAEpjUZ}w< zvnOI#3b>imJ1Hv1So?eRTQ}?aS|MG!=hp_ZIDK&QG%DhW*aoo+oiL@xpstq+FynIv z(pNANyZTfH1XvWL>%dg^N!9svpn^-*s+FBooD1(hbpCFgWF-wwXDS!3TpZ#)Ut~06 zt?Aobcoa;_#(R%mtcF9AbL1YsOb%m$V4S!iywxehkx~g5jDIKueHrw)-c5!KuG2$8 z(=&!sMBzo(F5lF@D2!Bg3#(4s4o~36?tAA>0GDPryk1cF~Z&AkfK!jcs+@E^%I` z!{6nRDNEjx);ugifQg%E>mE|2r@$(Sw%L@F zY>s)R*jucfWZv|U+R zfx-eTa2}um?dhj%c`KKzz-4UEjS6Af9D_99LuZ8kFQLH`o{lPhv~R7 zLKVPcAQB*u4UhweI}ux3&Gge4t8)HU+2Z}*xv$GvT)uV~YK**iP<(|dxrW7jj_7#% z;^AArrlv_CqBiQRy#Tk&lV9oA{chlgD#p8kF;44t+-z?TA<{{!Nar4jn+`d%mUO5$ zoUk6onO0Bw?Wc;Fg>DYbqFP5kq80sJPp~E~9YxOyNYT2Z%OP4Yy2a7nPdaB6qDA7! zkW!COZl}+uT4ieBCLzZwg(PR1JjTD?6wINwncpiX`R>RwQ$hYux~4}&n+Dv{)lyLA zJ@IjnjNOY>#Gsfn>^LitX_hK1E-sTWD53$^1$~#%4cpj1TFj2~(@{h<)$dUA5E&or zHm+}kEc2`Ubt$wg*rDsNh|9IjcKz6+)fB-C&L1K-%g^5Amj7HA^^ilp9II1rti+9Y zK2IQ-MwPSJPkxe7CsrPCYjUz=9s8~(#`(V2o9)nZ;>_nL@%;7pcAQC*n3aP8aZum? zke3znc1G8oW)>rC7=GOzD3>i2mCxwX;i6-e(#35S*DFx)=J2xd zt+4>9lFO5iGmY5+E_KBcWQlJ8WpBFG_Zn{(1IL&qUF0{`)XQ2~8dq9#&3dWoyV?gz z?z}u%SCh<9FBi;pnXY+1F5aPPmq{xSAwXt0QrE+mr^oT`@Z-gEN^y%b_qtC}dEavG znBEPW$l6vUO}nd;W>HQ#&RXFf(>yX2m@fxFoH3UFw)Wq-LMLRu< z(n@-5kTMfAcSp3Y+{fBnMn;CzkRyKzDpV@YtN;1mRo!zdcFOd0VY=t1Sb#J?3F}Uy zT2$D-!&QJnf^|)QKjKhowyDlVB$52tFKm^E4Sltn2b^OCU;ERU9J@L5b)xM)9uHAd zE5Y&<&|K`h&v(x&gZD5=f)KN(MLH}LYhe%%OD50RE&R~{#`l)rAYqCKwq)Ps7*Oqn zB6Ib+{eQ?T?0kcB(7FL_O0eGCzB=R49yzVzZ#ApSQd8^DWjY&+{jy!Yn9+WOtr^9Q z9HPez2m=v6#;?4#DtUW>hYs7dC@^cGwmC8vawZcEGPyM}GKgcUH z$`1rA`WVfVGwH#&>*CZ)^=1uMfr*DkVXm7cSGxuv{oU9UmiHV?8+10%sHHIsg?fIhb3A~691a4rup=-QHhajX;FFBKf^!eg z>jNHLfr4LKzjt>06~u>$eCtR;YR{5iwa1UlF$^(Q>|DOES8uZ?MPHtf*dKjzdXO@< z>NkA7isQi|_#)aVPMQQ}8LA1(JcyIJ8=_KC-XCoC7Sy6G-SRXYTMQ9x;wmaHr=|S5 zY&>ncUGUL4Zf`RietQbr^oYs>uEn2yR6_LFkJW8wL}mntW^E55&V7}OjZqP#0;JBI zvJ(#q!?F(w&Lht8d&^-62Cfti3M3r^*JSpuqDL?^d9qCbdMoFqKX>J=UPNx5yyfz& zQIh)TX0=|?Z5zM*!bZVQ?z#-Tj6V!dEOYQv>-9TeOS2F@v!$Cx+Un56=|69}H7@qT zyNG+&%Lfyr#;bb5r6uA|;Hie{g~C)*$V7f>Mn_kTe^bPUpwjdA@0f<)4Y)0}7s=dT z1D;U?m0vJ!8{S=M-_TOhl&gQp5HvO5R=kSKdCNN`aY(`*cX#8S8HZXGxaC1nT=AFs z9!lP9ZO@g+am09<6t4qC^b06iGfoC-@})UHoJ}_Cbvbz#tHg5&xe2Kyh2fswn6tGi z+X}P{%}o)sjF1s8ki6xyDFuETW6?pS3#I6@wiGOTkmBn@9O-jggi#Tb%iRl%X31}j z@lq^-U>uw}+o>i;gPKud#u^$YV7@mP`Yw(NpW1HB`ShYTD#$a2-OmJCH*LLIqDokG%RBMu8ta z-g=;UR2&>wfE&e2YMXbd++|SYh6e1DA^Z!!hA>E-QA`@leB-V07L+lyot>{xA!bkNubw$RT`<2(e&`v&1c9WJ7wmD3Deajfj zm_qtA+N&|k_L0ZPYsYj|p<=4HgJUyB;aBIAuNC893XoHbam-c70%x`f-ouww{X3d= zWB>}j#;)$PBgCeZ=BCmae-{k@V`4ct3kxeQnA}Q`H2Iz1J%|Xw{%3s>-HB=R>W3!IbRCRe2{$qfdbk?*(cPNFH8vZ==t;T<1VWT z+gr0``eJ6cA+p>#%VR*I)pm=PY{T}f zn4fCZ{sTE+e6uH%&lfGxSjW4v0%^4y|jGwF@-^tF_qo474v>{d3xm zjwJRkuagSX0HJrCGoChfqah#}%Z{3+U8^t|FjJ##U!V{(YRfv&`^bZn-yc%E1$)}F z^c@q^zf7kk0b;@q9V0m>KCWE^S=rl}jG0D)om{?d{XV?xKPP$`QWv7ZqTxn zxDQ5Vk|XsKzrW%rrnZtN0D2@S8pzuJkB#F0oC<#jUv|rYkxU+&@ZKwG;GAv}2s{T# zd{8)luLx=31lowOzx((V5~&BQIyq020ZPv)Md^qqq?RjX%^kcLj>d1gH!pK%O;(TL zyO)O|Ba}!LGTF3<=Xu9SDX95X2?_JhduEY}MZXYtOB4sbneWL`F_CamBgT#L?!KF% zecsZb)A+p(Jliz7$+efj{n-(qy7||lnBFMB6bK9{%?BmNfpf5Oe<0^ILt?PNoPsSh zBKXO_Jl}@WfR@s9@&{Tv(7fyyALvv?4LK-k$l65hy!>AlGSl0bjQ;)+8S%7{E!^km zP6?|5Urxu+K9~PgLupslf;pD)8mo4>P7xK@KG^%yXsl(y&$sDxY9Bo*y5R8(E4Sdm z3o^450cN$VdvswN3HT$~ZY;;>KDM#{J_D@DT>d!?{X~N5r{Jq2+Ei;wXNgafHXl0e zO~w{|R3Z_IuNmX1FpC(OXToa_IG(bl9BL%~dB^ABsv6xV`SA@vfgt z&!D`sS9Fw*obhp4FM=8LHF45)eZ=ZloTpjnPXLq?N%Aj+8nN~=>QP@HCpA;AQO6-i zTxBE_s#8a)hCFbJccv-2`<8vntcqC8l}dQXnn#zR-PHS;a-x6)faHYJfM9p;8o+n?{~6m<$NCPjT{)06{Y*HN^p}mQFGz z&PQ%JAj}Km?uS=&2OtR7_kM**;9FQu8A~f8Qkh7%Q(r=6mQMXi^kg{_ z399@0Ceo^q+0~k@jI=scHq?0zkJ!vt-5IPkhLllSF$uX zd_5a;GE+vs$p#;=$xH?>vQct4cTAEHhRqP55&OrN7r*@s;;v zB_ZqSe+$U$ELLy~xJHB`=KC+*LwQBlpDQi-1WZ<%!nJW24bBJX!TT-_U0hAFG=3A$ zy6JDy)Hf;FNbi|)OqyFfMcpYE(1e1@S@<^R!tZH)X&n-zUs*T{n|jJ)DZ%^sW!~ch zaV&KTjv+;>`Cp90DQU}Gdh34jv+j9^t2GpnZ9<&?>caLyqEsU`!mXi|p@H~gmK^h7 zqQkCl1?!IB74gqcrw#Z8??7D5pBx1ZpSp%y);bFB+GM%XA8%VlF!NdcBV|J!y4j~% zTP|W=GZz*#O?^CEJ)eA#$Al)y^IW3+T;s*cw&r4JQTc{A{g89nJ6Jtx`NWlL6M=(& zA=PG4ht}x1F6OUN`(PEp;%$O2<3}Z04dOasq>O7RhBucv*C(+p3Sp|Je=869_(@4x z4zZq5GLp7GGnIMk^(-x3Jy96(dg<@DB=cN~hB~b}*27Up2+jTH`)lpQCyfe4%lfsN zJjmw6q~l57d2!aLhkN@WVBeRAnYG(L_n*#~sQB&CCZ^onvCtQofN!NL9-OnOT%b%V zY2O{{_1*a>o*s&v;q!5}fr$C%Z^zpvlSEpQo|d{3cv4Su-X19(DQ_~F<+Is*;?|vb z*<&1~KH$ia7O`1hF>G;W4C z2S+@fLsNKngV;*N+BPcnV(K_@QKSF|8=Tvi7gUCv8wetp2irryuRr%Q6B~awiNrGV zMEEAYVYJc$bnFZA&z=$vR(EEF%BVPd_yC>uq%#}pEQ5!al|e}$KJDbPgqjj1@I-B0 zUE^S)Itj;Ma>}kZ^;jKR#!hf{bsbY z#D&fe@8{C4a#vMV<>n&_-cq;oa)>JA8oTFb>loNBX_LVIO<%&t!_kURy|unRcGRt= zO7i1HL?@5jf)f47sc#8&TrA;|5X?Sd!);9I?_ITe>Z_cU1osj_1}S`MEV0^6(Je7C z67BYVJ{iJU;6@DQ`*p2{4FBHvJ@8p3ERPBN3*pWSlDDr8VQTAWxL@b(9yYwk@>l(Yl< zygC0dk!%o(_vpIfnVtRT+3gXg$?GGFktyUVlD^>CADn4+JCDKKAIe_#`*eRk=3CPf z%j!?Pi;+1B>{SwfJo%tH5h~Xu zKB?M@>&?d3%*QlL77Z^GG+dgL=7kk{HMaHjyez6MIz1Z)=j{U<6?I=6aj>Whz?eq5 zv%)#KNh|^7qLhJ!xHs>kEQW?|7YN1Gw1n$PScY*L&nwnN^ zjfyh-R7F3N6ahf)4&IUU)I#V|NOS3v4UyxMr3FoYH`$f?h?Tmxol5Hmi)yj!#0Y7q zTRYaYsC@ij?KLR@45DLDhq_=X^f$Ql;R+cH!BoR*-d7WQU6`i|KlGkX-^ zf|b3P$}l%mj_}G#ex3?21=7%1q25+O#)}5xpr#G`63G%$DSxO(E5+KyMHL`p(b}#2 zYeDk>V8JM86qNLnKPl;BQrV&H=UY$-u9Y`WsTjL`^((o#;` zq|(AE;{q*vGUfBdr_r`fvtwczDIt;@o<^9<1ITDwFcn)D3h~8-0x2Mc4jKG|&-fA; zHEPHWnndJfD{Q{y=6LYJ3+v4B;!xhDWG)d>2&26~;a~iy10l?PD3|<;cdwHj&Hd5F zT&=ae9m;aJlyy*Psz45Cay&kOteBcVio_nQN@KG^Kj5+`@C~n<`D!PwGIqCzNx$ii zsW}bvOL4c3SoFoU@6Kdw;-gh{p5bqoQl z;76#2V3+)pw-Vryfa#1h#&?})6uB&|c2cARSz&F1Zw|FH<4O*kx~he-%BDWWokD{t z)$or+4i#^$?bh7tbEG${@~I!@Yv<>$=cY6=o?L%rIrK4h!I(g3?G3J(fS)`COO5Ed z3fQH;0-$y9hbJqSg?5FoHIaQivzWd+Hg<&>TX!0koJQU*ZbZPVC$XR1$12t{+=-s7 z)R&0PrN}*m6aVPC0zgE+(%0aN00c4wG$YMmB(np=>(;bTMjW3UG8mZHswros^pd>J zDkwk@zlCS*UJBI#pV-UP@lXtjk}an=huDFV-Zll&_g0#X$U|OtIIomnGL$x&Dj$wQ3Oqr(-{_EkbmTw4)zvyKtdw$N4w-pqH2vEm-$i;1avoXp zT5jdQx3~^6*jE%Oi40^2^}hSlSBw-W{pd!EGG}$h&L6F`YG%rKM(PTe5GciA(mCa} z?U&0wj~-QcTAd&x!#hn!tmr^3gbI*a%I3J@UwAJ2A}8(GpC%B5E>9Bxap}i%$>bk) z4;qorkeADpyonQQ@Qemo4*j}Tl3P~a6+i*PEJs?}RlDsoNUaT|(?2Xm&LYbP!oo%u zZm07x5)P*?e%RFhYBUP&5sr{NjwN)(m2^-oPd1Qaxq(x%p#bepivSbb=f(gk0mISV zZ{##d2;)ql*X1aH>;3&V!N?ky_%e<@>(FkPmz31H?C)MB-nw$pcsq%%LHSvW%^j8R zH_4%;L<6l#%Q3nQ_~c}usCA2-jFDTutr5cd)y&HbR>~rh>58M@eBD}D6FcE+!@y4g zY{c^Ol?^1jjL-_4=^OL&KGZM>2wk>C&w(cEFg1V~xXmQJ^RdVc!CEH(@hS^7qeLbu@bCZH`I(%p|6pdQxf6qzMn- zNo#4R=WF?Oik5Pu8HT89~bMW6W!JYeYu}I^5s|0pJHfGo8k#>>6s(ime19 zqwEY3`#0sfqccQx?0^5~;ft5uvFF{_8zxs9k7G|H3(T+VA`KEPdpb`CWAPv7RU?`} zyu4{ID`?`##LZ2LHPdN;jUlYeTOWtgPYTYbiz&fwu8HnKKUcK~AxDQCBe9qjQ>*}@c($4`DAZ+yG~>Yu#4EVlOZyT_9q&3RK3Mh?&^ zAH%s1vA+{ewRf|Zi?lgbXGH7bXh+9l?p*i{h6P+O+*@Ac8v1*I>fpMV(FK5~mz)eP zR`8*-epT|J$}rkWsH3%S zK%KDrg>yTAM7@%uF2C+>NxdkVdm&9#hcOQcxudOg1{y+{_W?(hhOqO4E9cWd39 zsu2@jRwOVIPb5}*r%!pvasWj z;Wu&7;fnOlTj91WY3G$9cr6FOP`r_)iT??bm!;g05kFnTG@AT?THiY@GEmB%CmVPa zFqluvN4nMZG<%7JLd48f^`1fC&pO{+x%9I97y5~(=nzzK4_efaaq`okj!YcYr^Ivt zn{LHc))=L4AIl|9S7OS{Uuun;{RQzpkhshjNGlFJ@QqZ^CCATfDAU|sWS2{uQfLVq z&*msV#q!#bDvy5e&@GqdgBO(37ZUQe-LXkGQ?mkXv&=dzMtek5oNM|xI#T=Y zNJ~E_EzbYMYc3)#IQGc&wdPCfj5fXRYru*oaUVFzt$6yR#4R~ob~|8nF>=n_T7e&N z-@rYd!|JJ9h_!+Y$I9rABM`PKD**a}0uXu9f*(_S3ehAE&(`0@uqdXC!773*dN&d{=dDE`-ysZvyr8?sVqd9zdt1U)D>*WC!|vt>d%`W z&YetRE_@cIQ1#BQkudZX&?vbyPxwf2(J_-oY%w7k$oj9zq+|CG%NK*o*Oz#X32XPa z!RY^bxfDOa;G(wXcrI4tW7hpHe>Gor#tzl|eSMs7ZH0HZ2vxiCKhI1ZQ(=Z@`7@F+ z3OVroY&&g1XVUiC3V{X??i087r&%nW)>hOhfPXsFb;5UR8zsu}Mx#VK`P2=^q?$sD zfxIB0%{)Vf)%$@O>*~@hfLlZNv(cLvh-4SC-~e?Mmbt`q;3XeAql}rQnG}WSYBu)xl@6m*|sV*kny5sqe~FJvMvKH*|xu?i!Sl9RX?!rsC`m4uIV zAC2zX!9xG~R}xRurd#j8qMc8bLtpRZm$54opJoHVmqpvj);o~8Rni~Uj;F!pz?ZOA zrk*SBCr9HO&dwm zWpCbOM*ngtWCk*;Gcro2j?hXV4Mq1KkkEwYnNK*u3p$;sN2B&tF469nKFocTkU@ zT?=&W;`rA4cqu;CJo7v%^tt{mu{~9d(tIZme1Lt(0CEc7E(@UgE|}tiTM-oZhSz(|7sK8C+IYVXc$@sgci_uTgrL2!Lb z@8uHi^2^=Wf9vypIJNUXR|=BdCM8WraE26=(|qjl>A^yHaj6k8s%cN#$(BSpk)i}X z?)ccFWOOilF(hiUmzrCiCd*)xW<@U5+uJWKYXwnH#D?ET-xvLcp|liYyZCvJTeOGd zyK`sXqtkqA#xby^vAiz^%tbDh_!2Ad%GC7}?I+iq_|LEC)1C$tnb zbSrCC7xHwtI!w5xlybvojZW*e&P&@xg0+&=LK%Tr*5(n@?YO-EV?W@l!FPjIR0YCj zq{q~J)%thZq2LT>D~Ybo2kN&sLMhQY9Cs7HESuPil2vS0At`uAnN+l_&o<^|m}Q=@ z>+i#f6>=4MNgvT$Um@tj0-5C$wa1D*mgNBB^Vm3dn1BfNR9em|H7|mnnN368$x!@U z)~zswng=9=uO#FM&No}vv<2Y+blSJtgULGkBSqccoWGeCH#B^@Blwt#hn<6iW{HvV zB~^9{t)Nf>z-1Lt2I-c&3w}v$;Lv(V>t9v;)m`2B{s5Dn5*;)ljZ8fk>De0N@<>Vm z*Yc}6T*HFvuYKzOcmZ%P=hKuGn2MUxNRN>PnSzi+gF}mHsc+wPcv5USr2ty4$+}>% zPO0~A9#-{>y)s$y{qySs1*xeMfe562pINSt+(aQ0;YlOn)72EAVHtn~UM-HiwBE$X ziigFIc)?s8P)#UMgH#Zh(`o)dBhA%*OXCKOyt_`a0S8s}s^0X}$TK?|9A~dMYH@x- zfn6mN-aJu8EC3<3Doky>14Jyybo(A1@0eQH5B5H0eZPrXNSR$;JlH(Dr8aQ6{Tl@X z3uty!AZ%$Z4LCL{&B|F&R8XmSjp;rP`Sp%kZDmL9O^D&xhY%)5Vph&@E(E^yX`73{ zaDI*%G8UzUmSp>8!3qmpY`tsv1EmpTfw6^(ywhm_jl`P;lBdMfZ%Q{q%E9*&)Z86S zBtwe7E;+bE@20`?eqey@qXlL_t0-gTx66Cb3}UZ975b#}WbP^FI&R*E`&g&KQ_DN=KLLS6HKAu$trmG{f%oG9^8A~ban>LVMk2K~KOxvB>tzl- ze?F@XeR(FcGBwnf4Zg0>6uXTDfkyX;BSX-%UZ{L1Y|TdZrxY{u@W2)CaKY*k&*if~ z0-6E;H5-5N0U=MA9E)0}vNBu7VM9uWhlYELhX{=YUcqglVAIA*b?I#`m$^&9jresb zHYa)pib6)XTxicM(mW`jgyM|ydQQ!^A06ixy$2&M;m1(0Ll&-9-N0e9vS!2yhR!5We4#Und@a?ItnGFh zt}!YMG7s^I!uj716c%Og^W`F)5R2b)Ru12E3WbP+0i;k_704hZi-4iyd>MT)AyJI? zEGVazL!yo8%{#ujX9lIE6eCf*Lk7zfb!YEg?gaQL$}NOn%?aAG_;S;dzt6M&*qm(U z!2rn~*z7C|AHBslPZsA#I?qUN7x(z#JHa^Dg!r2yr5^@_C5n^Wvck&ySi{Zhgv8ea zxajB>pN6X%0Y4gQ8bVe6ePU}65l_%f5C*#k(y_;oe(t8?<&H16dZ7MHN$2mz(Zuut z&1{EMOty6UvBuMPb>qJdbuj=dXPouts&|H!eTX`Gi{dB3IEHgy!;hn$^rh}yaZ(XQ zePiTOj&K6(u|3U<CYAkYQZFN&p`l?Z!ebF0-KKV`&T9Wyge_EvVi9a% zp1PTuH*t$YPxw7k9{L?MQz7PV9$><$(qO)e!fxpae(z^0mtJJo`;`q zn9(pTgPw(vPByYzBM3?J$GK_lq%=_1y|>!X^09(VY^!tQsL#%f>F(*8^9}==F0PJN z%Peoqmp+5)TSgj-xOlvwt_FE3{K3nQAZ>%aK%IsO7--CCA37?|CWI^>7oZNjX+{F2 z>J(<4%>b8Z$gP1$m)5z(k2FjnJJ>Ig9SsAQizI4s`pC1$NyaW9yK9b#= zM}K>?CSry;c^Dds;w6^`W>U?jF}{S4)y;3#BYB4Ze(H9xxA(@p%fD?vxw`p}npuVO z6#eg6(fUtjS2QXtZ1LudvkyDXONP);ACHgwzCZ7yQVtl|Cs9-@*aOVfXYsXjwJ(*mkl76o-`kGSh>bSj| z&>l^=W$#_}e)IRvYcZg!kb25xYs$P$qsym4Tix-kX53?(d2bgc>OOs2Ez!}4S%?HY zRX_76U@jRBJCeVeh&>}*EiDu4R8WO!pb(|XtW`m^=( zB#h2N)6rueW}E;GdF$@`;hA6MOiuo_eQOh{c9ysuU&t}_kb5t88dOxpq^M|p49(X~ z{$Mlg1d8yJb`@eAr>*d`w#@(*$F+ndrasewIdZunk+gw;UeISSI0uB3kqUq{jJXwi z4bh524!2>Q=nNm&CZ3@f*?8Y}X&_?mR?ImOI2^3}LfbXeN^YIecW=En5`e&-=MYG( z>=fk>fh%zdXvHbjZkb&6-DsSpn;xXMXsBqA^m>18{^`~JhfSXAl9GWT<$qd#YP z({se1HsEhzVdBXNB9uVrA9Er$R|TuybG)s;lL0@FHqy2tuEOa{y6)Y)S7Dsot7Fs^ zdg--r)JK?S-v7p$tF)T9IC{Rx+f#?5_u1(Jk}|SUG*p`W@ZkQW@=QCE`g}i5tkstB z*-mubA1o@y*DTNEG+%LoG?3SLiLG=63Dto$=`f5KeuDsnU&m?u5CVTRj`$wAQwP;cG@wB&Fd|JV)j0jgtd@zg)6f1SbHwwX5d{pZHebTHx}>*Ffv!5 z$SBk_KO76BIwh&pmf{0TxNP-u$AsJ#T*)WdxVJ9j8ZDYclE9d#2iFj{a&g6S6dxKo zF)=y(3^8;8GTvqag3B`^O0Dmf8wzMpX{XXbWu@5opiFc7W`&P$Qc=4;N)U8DfW2BF zKcx{0GLfR=H4%PC1%55XzxE;I4JvX}#VT(6S4+o<&q#FT0dYb?uAY0PDmppp)Ea}! zr!Lh&jsn9r2FS5YHylS_7LMTJ?f}xL!zdLFNslQ2tCaiKnHQC-x>L4zA6eKCX}n&J zp=_|L!f5tV7ni=G?d+kMK4Un!ps4`(rC3mQhw!lcE~IRFr%57vt_kHlHXv?6k9 zBo{ua2>|n}XQrkGbz3bDEn;%8WutrjwfP`q8#T%cU^6}3cW=3&?mjAS5B9TOnb zONdsmCe_+ou9M|c(B9iLi*e+yuLYYkt!^W>YMj}aedjmg(eN#Q?|M6X+BUhKb92ia z#Y{3VYBD?);!50(Z?%bo29E8aDiO)HS~{xxTXU_QA)fq|si_^X$#9)STO__=y{1k} zWMRe(isKFes?tA{;4hRYM+D2a+lMhG_mc!D+zSoO?!Oc-=NT*%h=-A4mnvxY$dVM9 z0Fllf7)*n%FDIiVk#uresn*-eIC}MizVTfdI^rMXA8|8(Rv&w!cDa1Ds&>H>d(Km2 zBKf~Hh!F5B{b*ODkxS^;x0s z5?M|hoJfwElYRA-HT$`_#93U_;KJa*VE(xKWLIm^Dj_??%+xDhqZ2747aF(cu`C6M zIt{r#nry}X>)ik1(qQ>$ifx50ygVa^iR*N*>1KrX1Gk4cGtk9 zHL&WnAJR4ymJpH!TlK8t-T4GS19wGtRPdzVgbltL*F=0Ghk{6vL`Se!R=sq~58^XU znoQxBXYGq=hEd5xw^!wvnh+LKHa5X1b|#KzeG!%VPjT)yMQhwV6UlgO<}3l|RqeR7 z4g)Gvz(9|P8EIC__+Vt5M3lHEaG`t}QX`7@#?0|Qd$>C$^ZeO;Uk+SG7@WuGq&?iM zh3U>C20<|@;3pDi9R*{H^Ve=KNo*D>0B9Z-l0$zfF+Q1_M-MHvk(+ECgdYS7@5Ch@ z)3niYR~%+XmK?MdqywlMck|(ACgYAH%S$8UpZWAomnDz8K8Z>Yt}jxD+y|1=icVqy z`ugN?wB&b748`NpBBDMlyvt)}JyVtY|JZu#s3@a0?006UA*8#zB!&*@5(Me)awtV$ zqy^~?5rm-;q=p9R8d8v`00V(PJc-K1bS?_n&`Dg$AtY@u#@4c`4y02eTwH8Pn za@ngBTc6@sSQ#tjG5nrg5Sat+RowuPuW9}g4^_btI!e-2pu8lx)qvVO%^w0Z*~xwh zt)Gu<4xR56sf&Fiqj2l>Z-_j`RXyH=GieGM>wc)9l#p#y6Qj}#CWk@(v?(t+c~wPV zcUR%uBCNd~B6?ouTPif6D(oU)US@WYc#m>c6vk6{QL`}NNIiY}`PRNH9HGs)FdDQY z{iM)!r_xfBBK;KeIYY^pKf&EL=1WXludIoIzaP7%S+Sd6&}b$GYE$v-$x){Z|GZMW z22MwGrLVG5L<;1j=~REFs{LY?Dhy&5*=Gi0MH3bq?r(Wh#|)!07||PcA3}D^5aC)y z>58Mhl{yX!?h@V&!&(;AM8giN1F zpa@t=5^xIXRtL%0KVkSd6t@yL zlSrk(TX5CC#hZ2*zdwRNlR))@i0XAnpj- zJj1llz(&%?HMbL z^_J6Z@bBkP+ePjMe~2GpRcd3nUx%O1I#7o1WN6O7lc@Za)cF@e*7{Y3%(`+4Matj= zV;uDBsPE_wQ5;1$_1`VOl0#H!VX~dkpZU!NUAgP6{n6(c4>v?M`>PC$2XyC2H`YC) z0pSXhA-K+(7p6O^G}uPcFYG`5`1#W&5sdq_uE@;%3yCSKlrqTS;_-%uHSy2S`AE{d zV8GR{lYUR;=y~yJhO$8`M_S#o@ILPNiXgtZ8c;QgBRs4JU;3l^w+oBtiXi=1zB-BL z8Z7pONeYFpuybfem1CdkiPZ2u89sp7`mC~aeZ5b#yG^}Q488K}Aii&E1q-d$nRQ%D z8m?&=sQ{9}VR521Pa`IUpH8_p1F17ZPYD2#F`=L&@C9*+`sFpPCgvwa#@1_8O1YN$ zGNJdcdk$O5_81d%SLQ@No;X#BVyke?bc==`RUNI5FMs&84J&bciS1lRzH*0tW9E<;?_Cez*IyarheFvbsq*u1JPFq=?*%sLrI=^;@h`&P8c*u&=F=KdASPc!$;AY7uGT`Q` z%k%p$7q-RmUkG`LZa8G4MwuhGyOvjFd9fcSV9`oX%{&3j3voSx6Er$%x*Bj86@mpPy^^Ew3IH|5>;5KifqgPgu*#1fTCJe%HhCzd!wV4Gma6 z^lAU?#w5d4QcDu0m8AW%~xJ$ppma@%tl)TV;zAo4~&;HqQ#-|mUTX!@w+ zvRpgQ4|nWd2%*ZmoQuaRM?EToYU+HWaGYP3IUw+6nvH+wzN^#!!sEf6sNjp4{B8H8 zN6@|Ct)uM!`YammyJzA*EYMsIuRP+7xoU%gpCvt<52P-Qa7my8Xe8X)I7D<#Y}M`T zNI))njsckQ#GxMbiEWwLWCktyU^6#T=x>)QpXptRUq7O#Kn3J9ZZ;&i_HjpzXG5%@ z5XoMXCaOsjajdF>0PB&sZvlF--aVe3(BMNSRd(XK!l+m{u7-vNvt7bw3*~8vOTfRc z7sZF${?_K6A50nTi(bgU=%s#ny-q&)x){?MEsTRj3XW)P?F?#fwt9cr6DgY#jV7Q# zdV&o7jY5AcJ+dUfe^2-;D=7@hQ;Qk_Tn%I$;n$QPl+O7p5} z8W+IrSt;+@zwzi?YREEesC09|o7PrcG%OUWr9eu5b`FWe&98dZdW9vdSGm?OL#k=|HSW*NoDz#tAuxlvbQ#2)pylybI8O=s0{C1>Sez$0feSaj zg&f)oM5(kN0sZ2+WBGfKIiAeMC0VyfITbk&-5|@Yzy{VxZs5DkgNzN$7EZMv!8y-A z>#;7s05T6bl0skf?6dqfqs3i=7;4SC_Sc zzRiI$V}~n^(3afYslAs>qj8qI2Ro2}PVySUv8g0xpd5X(I*hMmm&zevt_1R7ZUyKTJ z#wq@!Sgr={JnUx0nH*0>i$4*nYS!CuM z>qL3O=beMS&2sQ3=T2oDG8QRT@Lt9^m$PrL2=P-n0u|~g=_CxRpNTge-x$x=-`}14 zSuU@j8dm;s`dw{!3e-l^pc`L+*@~jzH^=jJe&HX^p%?4>k$5PEC~O?v=Xx=j7&3&) zj(l5L`W3F^Dt>+z0f*Mh5pbYAo-Lp9vunBS$f~3qhMTKP#%~ZyFii4-9!YA7 zAFD+k)BEnT>o;1c%g_sXDS&uIN*bVMn(Ly*L(h%Rmo)Z3f&5k+p#VlB({io687>F@J#b(yBYvc~iuUm1VU zli^$+vgv>|p73EWTiJX4AlRfLDpvsPdW z9Wy=T3ii_NlQDC)^0J)}BZ+wsJYOj`Y2q9CNedfmoLyg_=?l)_{gJsZd`VI*H&Djl%GqdQ*gznAQx1`;bUe+W-ma4 zG{!?Rclu>S^u$Fu8?(<(mP|YOTuJA0J`l@VZ6Y9msOU)y@qkQ*4CAnh&1Vz&*q~!;HsAn?kW?mtgIk|GP<>rAFN2& z#t+&HtL>cFvISeADC$oVnCZMEjY~jgrA?uBUNWkxgWV)!CU#w75|T&RbVlFYb!Hit zUFg;)XEL{P!Cgx$G=}F}L_8pIo`bI-ipk3tr`1)~A^ou>?MvdmcCrR=*>0Wb$ z@v*f}XdHHB4&zB)3a|E*VR%?=CQ_tM;nE{q)*t|88(|)uuh;G#+l$CdyM%ze5Ls^6 z9w^vYvCSzDCYye1YE}ho0b^LxcvQuvrS-c$*D_oC4g2$9h|Kan z%gZwGz<8LNO5b*MMz7yQ_jR8IzD*xl zhwD6v{YD>&LjYExt){zS91{a zG^xshzsc~g*4}HADA4VOX_z^HSh?D$?PJk-Gy2RZ1VT-09{CY>m>=Wm1_3^H42L>1 zbONAN4P+WNlga8GEz_&^Qxwg{pM0q$A(Uw`{%N#g>4L+i?sefQpNSQuaB0BfhZ&kl z=X_%k(n|Eu_?FRu=#i&csXv6aFplb#jgsC!^C2Rd7=ZJk863WU^LJWNwT+&Glh&s((Xu8N%3J1k$586Qn=o zi8(YrNE_p~5LsF-4UDk<+S2HllTEAP7*&Ks+J^UNb$YS2(5(^R_2(8WSmU+ODFYxw zYe06DEqYs!CQ29I>04%aEw&DVs~5Y2>%G9b`dGx6%S-)`++DYn1+nmor{Qz`OekB( zcd>Qa(-rS0AW`9bf)ML?t*wxKw7j?B+81MN1Pig61eUS$3IhjoUWqz+NRpJ0suJ_N z0w`f`nFB~!MWuhO-=mDyRRAz;I%*Fdu~rXimoHnY{j+?uP?16KtCcTmrMzqj;#+MV zhlSm@M(NOP`c9Z&2^}={tGFKWoQKSQW5-Z?v%~Vqh*7h3m36nJV1|&YG=&X+hU2>p z5{1b{Z=v&@zUVi*Z3Bh*r3S-ajU=+qTulXx-*^O;kj;rSb=NMAM~wSz;C+9!3te zi{ggPMj9U-E`hP3xY=i63pdmT`CCF5GCG+w0}KhoLt@iB8Llkp`kXl2F}WRMpKt!) zVS9}wwt0It|G!n?KlQ=)`-(I}=}fKY@ll62brDj}NRikcu$$PV&9C$d8oPkDz(|Qz z_(fRN_!+)zBnfaYsd_WSs-mK@vscQ5k|;_>2c|9rnM3?T)#VQwj3D8G z{2UR)N)TTYHaq)ZIddGON>YQAn#$JJ?5-k2LLsw-qX|CjIri>LT~%f*oK^`1RHza< zBQf~f;;=Ou@Y~gBe@e$1rF!9ioxP9az-LOB|GMkJXAWlvqof=&Gd=vZuQ6Q`1IW2b z=C?2(VejriJd!00v#MID~DDU(Nt?N@8aQds$ePqby}Z+3R|RUEe8C zyY>K0n=c8Coexe*FHO^@c}Mz2Vto z22d#*!=A6kD^5^q<0`Rg3F+z)@u{#s=A(x;&#utaGQ}k7S(%l|QercwS71ZHKuZRX zii5Hj{ULQRt*Os2oS3E(m-;xz6+V=-I6#;N3PqNm6(;%lkU^FM>|t-qTEdH{yiP)C zCY}$_!couW*V4zVX0#nUY= zsT)BdDcOiD%25MsT}_umrq=YLgf7{Nk6aCR?gAtGR#nduR2(%w4a3 z1q9JL*#}=4+@}(Kz+Z!Ww)6~uTX+8b7r%Y((}bd*BK|}V1}}{yfny*$7XKSX8l;vh2Al#iJoirx$t`ts{GNDmnU-5 zMI07uH_2iDP6#o}la0wpIccl)ej?0KED|y+mu*zRa^9WlEqP?jVy18(P$C?%vc`8_i;-5T~b<`|SY zc9uYw)K09{K{z~|W`HCU&$b%Cs=^RBV{HmfMYLks!{9f_p9x=C21UTDd=-o^xf$Vh zH7FYdZZ|WE40Yi@^~>wW40$hpDJi?8;W3vkChE3_j}30jkie&-cWoOl?xZCH9woqf zeDqDu8%S_L1-ei@Umx;{{b1fon)jF?^L8o(Z@GoEn6ZtOqM^p-=q=L7>?5#1FVb-G!TFERkDx!>y5%#&E+ciXsP=aan&>ibccN+HhP*5I#JF3Yh#R zzad=2dY{yLtDY?^M^YQarTF>7f_@)t-3Q9wZZO@g>u8qiEZs?Jx9{J(1YU0KZ;pTP zp3{6UjpF*VS8=)DPDEOqT5HK^lq@7FFZALMXuB1liv`c9z`_lTZbhhBt2P(C`D#$( zkQ+8xa#$)^o<99tYlwo!wEA+ucWJ5OzGB?OR-jl;=JmE`*W#(GJG7WQrPh@F(}W-? zJ(ODilXjQQSFOqt3|}sjskTpE^4CK8ev&J~QGKsdXx`KAHl+zTJew`eF`-AkcjS}8 zY(UEJQ&+sB`<2$Bh9}eom=0pjnKm^27R>wp(62Kl*T*-#n%2D^x~k^Rd*A|qxQRhWh&^k8>vD6k(Z@v0%u!wS zbz*Le(BigN4zO%gMJ}63?8jU(mUb-CoD7;omflBFEUJ^rUk+#OD>Er`D~Lch3PWAN zm>qj8=2opkf+V!3pWvru6#;v6?jdT8*+b|F=K9)E-nt%TCYK2}VuPxbY$&+aeB6kR zh;eLYnL$w!uZHT*X!W8!NQxdyX11P~^%IL1fqe;3IMwNr*TY%nS)A6;mbGOIm`vn? z0Mt%La`uIT2W{KCaqxt5^sJA2LxPbTa&U0Mr}iQh_%pRwtFNAl5-(*fWEoZn*li(*fE=5CT^-c|7*#Nt+N2 z_GR=TB&L8FA>!lru3cmBOC0|LtvM_CH_dwN#DW>JActp3rF=*)sYkic(#@#K+jsdh z0var-4Vx`@=4m^)**De3Vy$03jn{5d;A2?h1M^Nv&gdIx?QU&t`dC&Q?^}FqZ@*EU z!=N_+{T0oX`!?w(TItzCL$%g38zWNh#uMkv!1}4nVQgEW#$z#$D%-~;&*}Vv0B|7?h09@aZ1Xqb1bJ>!YRrt(U z`ZZNG6kDIgi+D|iUd0|vC?WfnPgn?_EGCv6GX(XmitW*#6YVS18F+Eu{gC>wpMT3` zBT}?cn_q@N?9b>6_%&)gY}?%L$5-qz-LH+FZT(nY?d;yOzt|ex=6k|RK>0ZAVEFni zv!lHi(r|q{R24+_croT}ir+VO`zBIeVN}o&*-^=>_f#GfQXV?-aeki#LK2NcHA`f- zF5rFq^tm=?k>fY?)s*tiB(*g;r>BaW~I2-f)suBD&zlNZ;2eF8oU#3Exf7;8Z zHD;Edz7~$I=+T|TrGAYG6S?S@%rX&KYvscQ47u7?A3U*{;q7o8L=gycBaM2(5b2=4 z+)P-Y%G&F6xMJG8G7QJ`NT~C-Kv>da=G~k9Wv9%|4h}rS=oXRCSowpvrv4`i7qI&t zJg9kSQZcD-sCKdOi5xKrV!>xjP=C)d3_SB5@p&Dkbu`8!0x)b)03=A#qAZ^s)XzqO zCxo-R_XDq5SqM&Goy`M1v~xs+FfqxS%%gFoFJ2rX64;ycW$Y)e1s)|0nr=d5p`ihs z`^{5J*;cdKKHtvNBsc|1de=8oxd=lrNPxeWlLueIRxtsj+B;arL?^BDzPK>)1j6YgBL%hT+-rO4pZd8$}8G}H$8pQ(<+^!@s zD66!Y!gxK@GGA&Pab`;TuDcK}SjxoLd1muiJ;MAcKQ*+G8-F(kR^G^sRL)SM`sO;? zINSD&-lxbob>*{sX%EvMEjGbZ2YeEPGt;>U3(( z>cyKXxtJJCTms?-k}@N5Trg`tAK&Q9kI4SXQIsqubba<;_%rY>;mmfpXUG_zV8LG7 z!`1k`D2w7+rS_E2c;cbKt&70fz}~1`+e7W@jJ_rh^tavZ`S!z{;6u^F5tEJ8o2?v! z7h1NY;UL}S!C6vLPOqcZZf8zbC^4to(akKYh;KuBD~l3FV2|C_WA?3Q{%ArbIN{{9 z@I$3+o78e7$Kb@pyP(eCyXyhTm-6?!@t!$NOUg#0ja!!8m#44F`L{}Vig_MWx2&IZ z{4t0DVn;@Ce{Lm4@Van7sq!nTsqpbg;|DX)XTe`;qHicltzL2sbbZwTI`Zqjo_(Y) zVR}lGtZiZEk@7ld{$}|nu7upZl%AU(4(0pgST)++&biTrV9`v5s?Cn#?<0}e25kGW&ccxd1?VPoa) z0R%&XNokT-%jnG1i=c=8t$2mQ*e<87H~uvJuJ{!W3!&D6j7LRueIHnWufdqj&;X{b zwePI>>)?Eu0=usDQF8QFfG?77wp#n0Zz3^^V3TA{UzZw^32NL4jJ;!osGpQ<4-&X- zc?3%5JrN7kj;GN=x^nhH-66yx3s*^FQo>*%%)i(hcn+%GR?HwubueY@%zKTmAyP!7 z&?&~R?waWfeC>TzVK_=YHV`_J9Go@BCVT1@wpSCw9?F(zHD-(4*qWZ_62vHy&`>|3 z%Fy9X4w}Qt71mqCuP2^5m}^~IdT1jDQGLil2`esqt%Q%o+lBVKx!i%jJ@4XK3Qa}D z?+IT$Oo&KLbpsVFK`K6`&BYsMk4)H-Zgo;lc9~vPu3t1sAODWK!PurK z)eK-dngd2+Y|ZQzI+h#+TG2?+f{VXhl_i`;PXesO|ZEn5 zxngQ1b-frRFsafW<*fN%`WWY6y>{E*IhxtH1|qJ*gswIX&11IhKMi3|{ks+`MPJH4 zoP3wR?6klAIuh-Hlzd5a$kZOQ?+*Gova~c{|0s=h-`!v1T&EV_$;;m?JbuLoq*7zj z_p=(C>F#lMrFWmc_gLrY**{ABL96AoBti{+npKIx1O3}?o^MT*S$7wYrDhc-N|H*^ zV~RNW1X=rGBG=9>NI^n95%GLFNuFd%uKUycOX%Ahk;+6hWlkayr zI}|xxR(~)IvCAg3y?MFplT{*wk;s>Lfb+%!US4P3>+HMZQ7-^Y>=mnT%R-s)w*E}GhwYAij;2+K zsp}gxb4R_Y!ZD=UhDy3s1>Lh)p*~^dagFCBTf3Mzbs<^9_~Fe?Jdo6zD-_PR_3I-o z&Sxj>#F%e#jvW+|JUFKsMNojU_H1IPGb>N^!kF5X(pL^ai&!sl9jyT?>aD1T&F_TI zsGfDwys;&X3e`uERhWsSZA! zk2FqxVs!%|;?->;BR{N;{@Xa^oZs%t-O)zr3Ag~mn(O(qJJ*IZb?qFO1__E(8Sd8E zX5MC>rZ_ZpP;6$bWeiPYrcC-mKOnFv{F%gySNXmWQmsph@WKR(qca0-vv!(Bop|B(9 z3j=QkuP`J7+-0lFl zaXuE;6@2$^H{fiiw8kMJ=mpCFc@d;80y{`sD6>3ED3qD`W8rT_^R_LyIf0@Fb*=-o**+wbT*yO;Rnt@4P zZAq%GWw*ZjkeP4()=xClP|U90JjBa8GF$4)lCPjI5a*UL8a(y25iQpIZakZ!ItKT@ ze(zsgB>N-2Pt6a^Uj3ZXex=?CK(GtP*b3r&5UYlkerd5P$ZU|HdpR(@R_-qiJ)hTE1W0uqL70a*F;Z5rhR1F zY%j-S#CU1+5MF)5vtyHi8!;e^mA*UXYBqCTl3;$Ko7-48&Hjh;gL2mOd|>X{t`D7` z$$J_wRlB7#}|R z#CY^6xubCp=y3oz=Rlj8Q{-ZICWoGR!-?(4X6F0L!G@k`cijpsdpF9oXJp`hOl+a~ z+nnmK9_mmPt49Ao$p^n-ZiqZiItr=v3;S*D*#!fZ=TLzLFbfhUwDh)$DaMvu z8@l%IGMi_luZrfU&Yh?MdW_m|)oqSeAj9$48%WFv;E%+hoAtD7|p3_lw0uO>rBC#V~y!Q@se-)T-s#;+)_F;BkW(2S^8DG zV?s-J-Zh$eF<0RMsabOh;e`mDsjrQ$bp$@9tAb$>qefsMT(*dN&xd!CS`{;#s$OES zXD>^!lPVkWG$-Rbz5go?{zoS4etJIJDxWiMdwvczeN4=?j}gMQ<6@-**2VO#3$OxOX(G@B9wJzQ z`A$eSf4uVOQUB#UA6=Q3IDq2Q6%)dK#UJqPayj(NR;Xhwl>k}Wx1dGB=uN7cxhp7E z$PjGti#yS&INm&^@8L?&)$p9Qd3izp<$3N;=tXdwxecx=loVIxYbEqWuhw#mrIVlT z(t8!nDO1fZVv&@lcvwTSYAG!4>r1I#^boa*R;bc2&A3a7h%!R<>Zp3}TCQsDsZj+& zVlLZ1PjhnLUH*6d(-(?Lg_SK&UmSMd)dntpkaA}RZFt5!O#x!V zNqw2Yj0HC#OlG3J65O34u2`mdC9!(APx&dz;uZi$4w;x&YS$Vb33u!Srksv|-kQ=a zMnD+tulBoR&Pa*DEik(WQ4)C(R=Hk%fKXu0mhfju*1wi~(ZiQM$JefxwlrbD4raz- zsCb3B5(PLQ4Mkbb*7%ewd=`_3Kl1IQ%?kR^_d%Onj@!lcu!2=i!? znYSGxK-L2jfUNFJ2Bvu2ipT~~?PEX8!QQ9r3s=rqX=13Pd`1_7hItWWc|Y0NW9bck z&HUK5Z=?8*US3RH=8cP`4aI-rKZ_D$fkvmiN=4!+>W;ZGi}>nlmWN_Bx`ILC?#j`G z$VS=_FyUWF1z}MGKh#}CS1juJ)`CoS?hC7etBJo!%=%ScBjP~k&4lqS8hMc>YL6D4 zI=>|aOm&Oa`a1@^T8ZT3Kbf7X&WzXoi{zmLmf00!+oH7avbNq#+)z0=QA3!$gA|eY ztjIw;%^;>k>8k#bN0L=<_VBXbD-YuE9wlS)-9dqVf@ny2ZU+6RE_$KIadLSnaF!-+ z9ORXQ|FOzI0}v4g6SI(*i-+4$h}X6(DWD=2w9uokfrR~7>I#i*%yMn23iLo*+jq;v zs7avK?JsW(0rwQ@m5_G?^J~FjPmpAMBsS}}q(N>?tf<}OSY!}`epMsY3JpewF08EO zjXk@)#8Ycvg}GauYBw>f@6%$fDRR?g*SyZr)iD1LIm=Iy%-vR_&+5lvb{pn<#}FMU z9dEoZI;>U+efB-bVA{Ft880dIHS-tz19r(wKHsNa129VsstopR_+8(TMfoo#DN%0lIJqAe&SGkRusuZGIz;nGb4%OG#-;*hCn34OP@`EW-i z|8Q2bN;oo*+;#h2jG*G|-?i(MuWU%yp%THH_mf)aSQMR=wOf$%-{6z+2Xmjp?(4~H zsv7q=0|p&<>BBA4-6TuK=KX1Q{@wdy92+*X$fVRkm#eGfz8XeCHCfS)vm6)jggv_ex}>&_?kDqmWRpm z@%it6c1qrE<@3Y)sNQxFr?|-cHu>NSyT*Y+kJKcDC45c9B%GvDTgd-HqhLev7V&ke zo%F2B3TImfTOWOPbV%*PC$i~KXcqQuopOKQ-|u&OExJ>w{)WY3o@*Gp6;f$sZreso^1rUC)2K)TiZ#wMPK*zU=#;G^ z`kFR$t0k=FUzVLuM+2(E+#D2N&h=&QjY@9kzl)b2e^!Q-1oY95USz=z4Fz5h+)8P~ zJuLomxdeF~Ugfj^g+xf{BS30QC8o`KyCm5}Qxq3ARW*GrH&E#{Ly%w3B?3?`lX&9T z^r&Ri!tire-3BW_qD-mA|>lV;l;p5N$*9-6mGg(B~ zm36F&)F}s!F+mny;JQm33cw?C_$Z_p1TWN)X7h>iO4vW$O z^(Dr#ooG~%9mJ?jMM-tX)>k;${4MIk>cg~%rFYvgtDj-7jKY;R6M9ZH4|Z+B6MF2^ zhbWhqv()7n8nq!YVIZ~&!LR~uB*nStUR)`23t=ZjNS#5&HVR`vlvYf~*owyVtM*H` zI%Yml;}(G($&eOpastp5ENY5nGNr)G>O;xu<^64w|@v-WljMf~06c)DPh&VO^5H^XT*;gp#oUFU+M&JC%_LBY2I1#pM%{ zaGd!+^CTb-=4qr9yW~BsI7t9R_boCVCx-jY=A~Dwzu$vs z;&=DSL!BZzs0g-O9(G_QHWuzKoM(|{&B*4d?6Omt-!jAsG(!s&J zg$lsa0uNI`%gLEiBv)e8GJg)6=0HU&r|n=gdwjLy>UB;@P1o%@`sU)XFIN+Mw|~>l z1?_0*?CM%L4f1U?y9g3Qv8dXy);{_;)Y%IM3Rjbs9`1DR4@MpimzKt@Z*9qJ(3K`Z z7Z<^&9Pl4GOshf7esP;4SG>!Z2@)<>;&N5S$(um+9VhvlOdhp_5BKsL$@l2v)K|YZ zl`X6Nfl-DFQn_nr!);IL7TR_kQrs*hOMw6-+2X@TvQD4S;fH^}54%6KYztX+i*jQ7 zE5B`xZx?A+e=$-|O`;A*^1ViE@pt~DeZ^GTVmj2b{K=N^F`zu^=B>ZA7J;yzMWEr- zpgSe*L2%a-J+LrA(CR=A{_m^Nvyr77`MtSR%5YgNgN~l|xzc^)i;@Ao3iv2Y<4;D^ z@4p<$Pj_C+ADmAa?$c)R+EPl#Cb&;EV+_LkUXLU(T_1@r{y3F&`FYJV{7exGpzWA> z74d!`#Ef(}I1k@10X6fM4NJSIqHi=I)bfW61yF(Xrc7gPQE<;Ew!O{97d@$+?#E|D z-`Q%E7y@WacT=e-ZZRG)h!(rH5-{LF$;{f@Zf()Ri4}$pWQStDnk6DF#d?CX7XVz; z3E>_WIfmpQ0G3>oBHRp!O;rHLJqbJh;yOsvkUmBhr@k$#AS%#KoXz%$+{8147`MTN zUBK2L9$>qW0v>;m${L=*HStDLe08S@v5T=JSFI|J(&{AjdF7sDjYoov=2?9=nXh+} z8ZeH@3_+Lyl3Xuf!3!Mmyu=>}xztEtWjC)EHJpjY03xq!N%}x?<<^3LwN1^X<;8jD z5tq=%sRECL+nfxq2;(&|j}zBPdt1ym6Mhpl`JBW?Q?9fz4BN)#ximh0KFKk-^nVTEo&3NIxm6}lBfZi!!t{RBH?ehqcR&eRi)WmN@-&?-o@wY9e)+N^Vp zu3{37wmUC!I-9Y#)qL==71GLaL&9q8zP39>bhD2AYwW^uh?)W7)#TA4nK`W`UDrKb zjiphY-iFWX9fY@OJV`aIpOe9tn@aGH@R}szuB0Ww^@EY6=gvcZ; zJh_AH>gtBnMT87=Sn!!MjX)bjX2?M#+x8A)85t(y)pPV5+pnXDdkY5^c2a-@EL+^m z;=;%Llta>+4 z*#sXKXE46@y^*l_aCSU3!ljdU|L3{<)y9Y*#`kAb+gw~Do0~-qQ&R*^DdcQInaM)^ zoW&PicfQ-DzWFkp0soxO&<}TgoL{i+7vztZwnwNpb~f0nexZ__jvd=u__jSiG21*2-|N@6_e_h;W(?3-+pZoTh3>;ZBO_QDnW2ik z!(aZk@xL4EoVI^$82|a)U7c?@zs~x$dH_YE%*YyDz0DYV3lWW0>SX=Vu~_D=E+hvi zf(>bU6QZ9UzFs2m&jCCn$9RM$HNSbElohaT1Psk>+XhQy)20AKN=sb84JBqxxhZ|O z+AB71ZjS`0}PLK9p{{1&L%)gZQ z(?d6PzYNH8M8(A;=^ZLR+eL9t-Pf65&?`6e`8SfHhENQ1EB6NWl!b)RB3Q9cCaULK z{IMD1;FtL_k_qv1IKrqWF;i@S=wb;cal9UF{!NE{KdT2v_3e0|H+EL~KegrpT@pBMfw$2|V0assuDFry z*eA64M%6-&f3Y;EJj;H3e892DNHE$iy_D*siqauv?$huU%mpo^M|dCz4VMttwi0O< zXyp*l22zj4FYygkn~wZpD7w-5Q||}_EGA{e)D!VvaxJk4FA~EGq6C}Tm);n(ntLpx zgnv3OW{2>Q01e8@RbM!xwm)lPwFFpT!lg*)w?HtK5c-23 zV`mKgz$zcogxEdTFDXL!;O4PD$fEo7sCJDHA#=8{t$R@*0Bdu5-XHkX$Yx~TG-7#x zSDv2Q3WHZB9*KFDrI&ql7h>o@SdLxI7B-_$!7`e)D0~TXhtm*@5!m60 zU19w+*Wkp~dXtrns-E0SDxrDlR_|@}IW}|m+G!wCh#qKZD_e<$nk2zz=1WnHq1R^T z0vWA3QR(i%pVeC!iuTg{0fy&>2AbkPw+W$1Zq1;CFzq@r_Kn0M>mW_Z3!Z3aOCTFIUQn{@dq~Tez@=kPc_tF_wyZ%QHA8`wT_Ubpy zOZz^}c8bq5&rU)t|M@Io#GuR?$MIrBxuaC)s4=3N+){OcAf*@rVeBm{Du?BZa95Vv zo<+D8|KL!+svZgtV9H}QL-kywWS+=>sJLa66%V2en&?lnXT7!mY0>`h4^QD@i7Q&3 z?|&+R^q-p175$mGq{mnY)zZGFMqE_Hp)t-%Ibu#81*Nacx z@0lLRn4;vI?v9h?1J3_m2d>_&yVJM%aE2bPw!=rWsx97GS+tJX+$>rsf|2kC#WDZR zmD|&i=Z7EOd*3;VSqFcP`pGc5dNqj8_59=&-9ypb>Q$g%(3?hcDhdAU)Zb1GTn*F3 zL@V95gA#|I=l&9XxQKqcO%*iw>C$|)d$FcE3SA`F?QGM5ChFtkkL*WrINL6_uNGhV zzYdu69DdAqxbOC-efZTA|9tg9e)i{Tz)nWHiO%ZPFix_sKS#~&AMa}&{TzNu{AOCa z@N$rC*n%V0Y+Iq(zIWT_UNOw=g9AQce#q<}$_7d?k;D{(^w|m7}k%2w>oB3c#cQOl2J_TJ1Y_oDM zV94Yoj?6$y*JAUDnY?pE5iZN{pY-^H7&?WaH1-UTLe?c_E6Ks!l1Y+I@Ykg$khp{c z4aeX2f3AQ(FRTKXP-JF* zAdBybe}LB2LMqoS{<`_bNIXVTyWvTU)0Zv<0DUm|sv0#0$z2qQ>U%u)xfMBoJ;J4wLREn;k@~qBxo~B~`u( z!6c_U(q2Q`Q)=d3q0H4}7P*T^_bLN^xZ7f#1(8& zwrQ-9;6Z}B2X}XOcW;6_jZ1LX;O_43E}?+{A-HRRAOV8I@Mh+{`*Htn{oOjJcI~tF z*;tJ=uP6d`<5P_N`v9l+S+eZpa zb=af~^B>4K7BuiE*p1E}YSWpl9_g9Y9LQp*b?|ihs{_s>pTtA4)rN=QSZ97lKLL*m zZ!=rSbEn^lGa`tawahFH!0r-bL=ghOv?F#b?E}8- z@HicR*%3V(P+6}fSjLgi9Y6!gjk&OnGJV3p+uRS~>)%fT(p@15dv+`v0(@DcIFB+C z1ZOw@nsTKET<31PRLFJb78|T^=_Fb6XBFD|@Hu!*`J9mG>YmIZ>1VQdO?6C090csv zXsq1`#gX>{h{jQOU6{aWR3&=p*A0K}$VbY)B~Ljvubll_$x{D*^Tg7`nr?D@@w2|~ zT4uVueIerdK3DHK_wZ6?Obn6O{m1`*y?k3W;PJDD&?>SqLwJCTa*gy`QWX)HH zq>7jH2xYe%<=Nax8Uop^as79j-Q64Kxsc7*v*!Fdo>O#@#~VaaKjeivyYtOnT_TU> zHlZvQb5yJnhpaNW7;nhwvpv(pqwVd(k%<5O1D=WC>D!Ho9|WPt-|4D$>$x>ej_Pxk zWN6^OgtyJ^{J>5lr@IL&({>ri=b2KKK4)BnA0_S{e6RU0<6EzPIeUH)S%_J7T6#!g zk+mpA(~mWnPzCPHnBzxWANV>2UYEb!2HuYMZ|3Iq_&#-CycOh&_}m>_B3`@=);_$L z_+O-(N5ipuO`CKGR1N|1n*eYfzef@wv_LjCIe2?)xwyVg383sG)KA_GBT{K&N3*&Z z+F=GptX!uG*U`?Z{0Od7rNyi~TwTuvVA9+ z4Fuyd!?D(lHsk6*DHoN2&t&)j)H7xcvrejnACN35mzNP=Rz?f@CfGD_Av1SG)-*v> zzDRc>o^A&m8?c;F%-2B~N3z)PF2pGF;zWKXd2Xw5Mi)<^G?(aiP4XKVFR~e`n5e*N zJ%Q-l)J`;?Nj#)4;E6w-^0H@#J(ihnW+?6EI|Bm>O3~E=_LiN(oHSXYlCw?GoT8KL zg89$k#l#G04>KS+TkVPF`n6L6z9XgW^p9;+@hnf^saH{@H`U1oge7G|K#JV&%V32?Cpw9sf+Sk1e}l>HGy6Md;y zVzqz$nFL~k%ZJfU&xIs5K$e`<1k^(KHUL-9^>rJLmhvv!dn`Ln8WMrc(HNY2Qi~Cj z$=^6EN``5X-o>n2Q%BlGfVrfbiLuB@h}|e5N>7#8j%1_&#*~LFSrG~0z5UiFpO7Cu zUQvx8{^};CBo32-fC~dx6lHDl#|sg*%CSb#FjMc)nMXsW0py}M(E4c0z*TUvO=$8V zR1_ad04EWS(urxGB_FnRiLwzFxtJq&0y$V%6T9sz$F*^>Fn2}&sC}qP>j`h_7$-?% zsl{fF5Ce#0qK~W?8b#HM3#MiZ(q|lz{ zseA#26vGp`pbG%&-X+EYN8&3TV}4UIBABzDuhT)TFkevv`JK|~WBE$h34;r_`8ywf z;GKA!9ZvV0%5zJsI7Aq2T|B;=_y|-*n-WE=oJA6lyVCz^GmBo~+m4h|k7lFsu-EQ( z+zi8!${5MwZc!>OtspS%j5R`SM1s?}b)jQC!vzl~x_zdX3U}b93`$jB^JJU6NBN{& z(^-plaq#9h(ciT7dQCg*BqIEnUcZg;`~BF_uZvfeu-|au{J&jd_l%h%-cOvFy%ff$nEw$uPPD?w?+jsR?{oa5t+&aF@ zMdZJ|Li)Bw-2>YE{@mhq*D25wGvksY&^Tq4In4Y0%F81T{PTxrY3&bfzTdx5yaeG6 z!@I4g$yZzd>cKUqepf%gpKZTu(@9g!*3tc2zF^_8KzSapZ#Y_riivoxubXcs5p}k_ zUsia+rSh#!d0N>|A_JBU=*hn3`}w5KGuCgu7K?P*?>@gO$b7jf7wLFD+;|lref4@c zxmUQ^Mi+kFGwB1JlSsJherVC`Y3$6_>Po{##tzHaHg3_3NF0EA*rAPRSYrk?XyT-I zFKGz`X~uM3!8Oqawe0(ZL&90TC@4^xD{SY!cAXt-Y%z>rSjc}7vR#7C*6@V52 zZUt^A`%JB|)pM_*w^MKa#%=z2(|L9$9`Lh-%?`+DMyCygZNcz4@#$Q<;sySaP8yL3 z-Scc)`0GNFvIoaa$k!D{GtG+{Ou28#9oV%+^B0p3XrKX82|%@i64?!@ZC6u}-kv_q z=VYGK5H0Sb0c9mei6uyg=ixZjh+K_u$v@mJ)b1VlG%(&1W#>~1s!0b ziWqR_h({vPEo6xIGLlOppRFfE{sVJh0^|S@T{6k${6-s2sNV=%1wXI=F+>LxS>c29 zbvQGA)k+u52?a}=x~uT~GWdF-DL}#64(-(gL>G6!4<&;dlp1Y-SR|qXch(klzwqr{ z@v(OTus?V`(QOLbW?+Ocb!B`lkp-@oFcVn9d9vkqMK2a>*Zc8)9TdY2t-i26N3Fu; z)uC05TL+=G(xQdR$RGteW#1rcqm0R2k}0#hxJby zj?f7rwT=$L)Tj@13mc#gju8Mkh8hmq$jKP%I_v9nVR)_$qACW=c3KA3+$T^xE}bLb z4(dQ3jKQAA$;-|y2KSz0h+u!R|8*^@8LN)SO&py_fZ_@bcaXUT@gG+)q98S#sKs%x z8gd59hYJfs3Zl3)0qE*V*MZ|%h=Ry|0FNWjizgA_7+{ly&o`DKel{(>O=k#Im>Frw zm@U|c?^aql!dg?8F2TwC!JQOLHaHn>pQTXW#+$W-YpZP#`g?!9rSdk}t#VTvXl|M& zdV>OX8r`zlz2GEP4ti>ByceAJxa>sZuh7?LL4ytQrU&#P*h}a}0Jdf5iO=)@CsMqn z^m1MO$j@J9q**sB2@<{KgUijS!2M|VBSciPwXjtG(e0;o~B@MWlvnKWbJ385v4QYOud)~}7P+Ewdm^1$ze6i8#^?MMd zmFFk=ux)RrkLT?ROW)&b|7*KNLO?si-uL&2a$~G~?kFDFt?!9Y&vfFAQIBZ%m@>%)*Ks~-IC|o&JloOW2M`DL_{gylht=3JU zk&%%@{xC^#5EaFKOkFBTL_bHtWIOuX z-k5>X#DR$}>m@gZwpk-2HGs%xsypYK*MwC+;oYg94HjmbkUV|J-uTZDhXA2<`DW|h z-;u!+Bc1M4NQtVQ3b%v63~x1+&s2Cv}ld>z{i;*3Yi*e@(6|n7x#yI}Bmh(OlW3bW#@euC(=TAigz-*G;4 z=qokPRSpb%Q&btM0sBH=LRoR~#Bs8a{=}GM(iY7ThlYM?3dt1HpN!j12W5A4zNt9a4%@kb0b^ilCc zTEeRUAw#_IKq5HUb+(Kql|lxDY6A-M>!U&ut`ES7Y{DQ>U=U~}_RFp}K_f3BJ4RDw z=SK;1Cp}TR^WaG+?1U^R%xTlN7=#%rCF=<&D8|*$*pUvEbKF#z+^{n+TsJrrJIO_H zvuvKLu`=J)wa9Cb`f?uUEzz?y&pLb-d(ZA%txYssKqeDokz_t2COt|p5tL;6IsF0# z;cP=xup>7lKMVW=sev10hGJ+La!E;y0y9($M0M8vNJvnMMEDN2+%pqGVdsuU++amG z>r(%LkO_O8)Qtg9-dn~h=e~V<;f*~irwt|qlgKc}m&uWr?rP^#ccQAszVK#y)B+mH z#e%{APb}Nts3@n#s1fH_rk)003Kx1>!sDi z$LC>DC!z0tw|cSpcAPZ8#c!UNC7q@BUfgzpcj`|Kx%65~bDcxhzvr`?^WN_I-iNLD-7Y_{0-uRYgtv#_2S?4CI9 zlk_$EC<|JdjEW#d!#HVkpsaYsRzELoNL0TwZPrmyXO#bV_b8JF6$i2WCfZAg`JAOk zmO!HLH&+`iOtE z*%+zz?u^VwM7*AHRv|V%gg5`ihd4YniXaX?%>s{4um)Gdgl0}`5(N!ZA1!9nO6T7m z9!OC3aFa5Y^+H<0$>_>v4QxZ!Fp&yQCT45__F|&F=B;B@GSY@l7@{&QZh$=2PE+St zI9~pHDar(dmsW${GcMR+>WRMXM~Y-*Ql3F!VH0+h3+o$lprC320zD;IOj9mdt>7og z5pqpJg;wQ~Pm$|l(XzqBGp4v4Ty3_fNGMw1{^6QUx{OK2X>?W{4IWQg3FL;8+<|cFXem@R z94!z6T|_mKH6gdmu`2xZp>RZ^?=;rc@kRiA{;05N}Rm zg>2fj1?Xd_?nB^Gvg7`-eo_PgaMbhqgmWZ4PG?Z$=;4!*HCbwP;88G+ZR*DR}GYUMSMa(}fc-u12 z2N)BDi!9AQDrhRzb&KGg@#`A>PmSoW?mhVUP4SiEk{es6NHA}l-?UD(XwspPQ1{w> zXtz@0pPyz!T_}N)pcA5t5d8csL!vVDTv>9X=d^1jw;Qj%=Xv+`#HV-lc{2ZX`()+u z_rZxzs~)tw*a~uYE){LF`7MJ2GmPxokvqE;QYig>`@dd*&u3wH=e^gr?b=JH7yfrI zGWmYD;|X;E7sWD8Ec4YDeXlbOcFj!P&VDZA<_uzNXv-Jb{^`^P99YdhE3r>5kyz~T zfaQdzgn$m83xjv+N$2xfa|EUIP8cry*n@qVdeista(cdl8f~1#F*kDx*6s&R5^Kjp zGI{c!VIo@fn_{uSdXc8KXtd%O(c0kjINB#eRcRI$;C0cA(~I;bR1cIY9$QX_u`{5hE`4AR7)GMaUw4xHe`qMjHW zt}BorG72~mlAXdYYI$;klmu|2rG-glj>f0-I5%pb-r$Rp@^59fXk@830#x+4xIT~d z;z4`AIBHb(2iEb`e=3L)7vRAy%Iv#jBRBDXS_Q17*-O z?nm9ZFc3-A`Jz+zn-QuRjNR(mC%kX~M1{yM)%?kpHf zJa%XI-=C+u^S+Wz9YL?n|;tZIK(ecFxfc}F&2Zevns2zhbmnI%_Awy%k-nQ-Y`kT zO*6mC647k-49ctVa6$3_i(H$9&h?X+NtYZ$vEq_trn%jnPc4AsQXCz}`E_Y4+~5)X zSic*yeIf8@Fa94G@0}v}g{vIvYcC(q8vV~aYsNPD;~p&UZ5{){4IeCiblrQVH5`$E z2`KPHFF2ClIl`aK3@VQAMsNq)VkkRN`Ebzoa{2fe>P&5>=^({mRpDbGZaBUHhWfVm z;)M=mb$xAL8@+=tVnBulQ3eiZ>|4p1egbMJw9RGx9=!}5rv9G)4cj}v>e%We`G6Hf zMLybb1yf9c9MN(2Og1)q4R8h~)B$J#V9Fm+H+7>9nBp$5g*uG!Va_f$`T!hLG0mV| zwB`}iWPOjbNZ_;JX#C!lTBm?hW>TmVak~;FRMx>^m`%XNpY8VtjD(fR+!3hkMhxEU z?LkdRSk2cZ3QsJb@PZwil95RRRohAuG-_^LMo~&UASDT({XJRlB4-i z@HOA!Ce)yd@FR!&&R+yj0FID^$Q%C6)f&sN%ubTjl^De7qavtoqrI53Bxxdq{7sE}YF5(=CW%C=w`T(&RlX z8N@XN8xofgi6|{$NGi{J$3IkyUl*~Xy{7rV&It#a0iF% zaj=8ZkgZ-C`nB7=L!gmXyz2Buvh%K>I9$RS9K!21%ajSWmh(+cC6F22p68N?w9g;9F{i*Ue`s*&Kah^Efzk&FIY-p!FGKDzeO ze{U;p0-M`yz0njsvJ;{lqMz4ATU4(l$Y{Xa9PM3A#|1|t-mZ`;uZ*ZUcukTQC6~r? z(}$n(MXO=^gkD|UdVjc-W$Pztx_vLsH+&&(Gc5f#roEej-NrA+5u{F@-Qy~G!hAyK zht0*KyEivfqd!V;)MME|*MAJ!KRa$|Gq%sFEM>p!(I(^zzJGG{I8OS!<7i;q&-)a& zORdeUddv;I+lWR=aBGvvEKdEFW6-W5dPbN2uO7?Xdr#UxqN*xG4A_2d0L*N zfwDvwL&4_ejzosgg9D!<1tqG0dedrq7V7^iIXbpgX&g!yWEF7vTr3dUS%F1V;A5R_ z6RGwU1Ej7HajWh4EVfHF0aDSm8ZM&nwu`bApO@b|4VPi19Z7MmMSE8#vj zEXIzc5^`K;*Gk4B6CNOXVf2qSaMIZ?gGhDB{QYxmSfb& zJnI#N#j(VJ59`}}M~E~GUdI8~JgqRYP=O^h!}X_RSUGgYa~L{NCvCN>1)X((GBoO# z!kN+aEi%D+H}oAk?df1Y7e3izlOcu{K6u(x_|XFqvl|b$%1X2Vx3eXZu;x(%fd@XM z6yYv)d)w^0K6^7Lq_d-QOYv39;8&TR^j8@g&HAsrvvLz{RWuEJWD>FNL(uFFi(-HVDhMjL?kGX7vSm6437J2qJAE&rH@XzSiAqwLIDA0hb{g@1^|s z-~{rv-*Ho7T|1Uu7muc>eLatTDw zQ=5%FG&x`eld+9ZVdQq4C{}SLNFsm0*+zD?z~V-XRkhFt8p{r0!~!rsuLKD!%M zH6S@D)g~!z}iYly9>IN zom}MlMwpzeN)Z2WghMrysy8X9;{k%!n5IS}91#0SiEOR_kipksCSKCG(G!q~#C=N* zgO6Wh|FJAw6xEbbB0C1O?XcGO_LonklD1O(!s+jDvPXgI(gFaOCt1;YS}Dfok!?P+4vY8#td$5BpLSfoYC_lK$# z0S;#WI$s#L-2p`k4ZS!xpr}@a+2waFH(tR|{I4SzQp!*$F?Ux|RXWUUfxTGK zFXw~y*m{0b?Q-oR5=k~%fi^$_E52h>FNy>f`@vv2QU7Tqapm)_UxfX34i)>IJp}K= zSE-$L66n&?jvt>L1*RJ6dg$-Mf0J?*AB=c)l#MW8gKHEi!z4?LRXdc?asSzGj);yp z&WymbE|Aq63c|BgzZ9ZD#FEU(v{EwZPLd1FA9bwF*cn@g>Fg~5WWYm0!)%nq2&9E^ z7&IIRHuE{TY<3Z@geO7Sq$WIXGKc22q%j2RXPhXI72b*w43-q%CrhU5MCC$G6;%~4 z1%eS7Q}6-*1|zaS)Y9~2;4)Yw_@t=m(y+)(%vILf0d=m(7{Z?$#Eru3#3z)Poe8HK z;h^9LQa@ik_FG@#JMY$oi-1lm#8`RyQiP*rAfm?mkzH1>LR?KlWf4Av5(_;I_NoFw z<|~^UAUe}b{8JWXmrikKpAA)Ejk63OR+Wej0VW5UiyxdBRV0h-Hip|!giD9h-s#-R zTOVPMCjToEE^VPqO@a*HnQyfZADH2cGa^{?)6+5c3QUxRLD>ut|JiV3Y#KQ5C1Jw?!kjo-}{y%V}AY_WwGCl=F9c(2w-ZEB@nRR=063|H72RoWiXZlBJyk2H z0(S~^b$=;dS=@q}%)aY>9WO^J;adTI?>7PN4K1&v9s?f#bscRP`=SgOijc0YxK|k6vG1$InD6%sln^p}OIdW3j=-u`RNa(iKRKrjoO+YSU2abl>ib{6 zzf;}j_R39!d|W*`jW7N=_5GW7U17$Jp`pe!+tFJqNmZUzo}HOhy#4j?`&J;^1z+T0 z-wpNZF5rGNg?9FQQ@>2=E^f)#Rx-XzuU+u_<(~!X?1=n&?x$*_i;c#X>44TWZ}sDc z>0wBN4xa3^>9&Fzt4lN*uc&nQ9pu=Zk- zL>Og0!K=6)10Pxs^=P*>7uP{0b%3)s^9!Xs=Bb&}zFYsT%_HvmX+J%^Z{I3tssR`@ zR9N8uj4|QybKD#!;--j;9Ju)&+_n2!~2pXLt9?Gm7P!i(G?^Wp?CVS*@!=H-oW#!)SpP|MaBK z+va1O4j#mjC9OL8SUKM;hlWE)_UW5W`_dXWcbg*2+s)2D?WBcI9(suzC%btg()z%V zZ>RQgok`IvgCmT)cIDQjCjGpTqRwY&OP zm;mUQ+aT0|)~AW^ufqTuQ`@Pe@g{nowpKB!@mMb4<=ce0_j?(H7`4*T02*EO>DSHANdxFnEK?iXG^j;qebw zwFtB!2%^e4#AW@VA*!udd7S*Iri*@&WL4yIWEJ;* zRMf+BYFT77tJP3h6a-Z1bfgmU?OZmnG*vd2M;x=kwWIgRgW*MP$Tb$0I0hUrC|y(( z=V0fgBmf&?y=B}b0Z-r)zq}~ql)O!?!$`!0D-+>&VBffLc$>E75a1`Q)?pL1!VvC= z9vSe4i6jPU*9<~3!D z;A%8Rh0EJebjB?L-sENNFRvc!N{5Ppbm#pE&|HB+QxrX7C=knH-5T}fw%8Lh5q8HR z_Vua=0sWA#vKN?BuadwO^-WnwL~&IOZ2C%9bz{8)66z(Cn?PdtkG{UE9O|YpY+CIg z(PW$jtcXOXx&ap9Hf|69j1&L~Y9k6`TO?0vjxWi}wdXaC)>2tibKblg~7 ze~b20OX2J`az#rMm(CtR{N8$H%B(l?RN z6lJc(?tIN093Bo)Jl(Ey1nu?o(yk1i38bV?KPt{j*b2w;qe5n8&T}??+s<(+Gp{vY zm*c?`X#BE&uB`z<1S42ni872~tAw?aA59$!l*&b90mKhbbu|CTMYL(2u58`f(dV zT%#)X2$?{}edVHR(L*a%vgT>|!b3^jdIfAG*vv^(bjT@^l$e7pexf}qqneNOZ|T__ z#|4UJIq3$D&Ph()+Sate4O!2Qv`h`x{K0=gi}P{hGpV8jhj7|BfSoqudVbuvm0aVX zN(F;!>Yw%T4U4Wwkcgy8;<;+8Df_iQG?|iiS7+~rfUWzi-p9k;;}&F7J7~}qKXqeT z$l|2>gkowi!gFmsh4pG@-Dh-K$NDzBxBcOxi1F9kr_*Yr^u3l9T;)}o@^ChyV3p4- zvzh2zuYN?rKX3GuDM8mT!T?G>AVe$?f9+R;oH1;=aNK_4{o1W5P&lV9Z{MBAw)I|R z%TQ!fQO;Q9>SVs1a#s07tkN10FcGWU6=K&SvYstGyny zqo4SKh!_zu&MVCO*T>?}xcfUN59@raa&n`4h#D4++$XDF4jzuZ&FCPAo0CJ%ry&LR zan;JiGE_M=sG2RFPS*gA**TyrJTZm6nW+d;*lYkoAPBQ9)v&(_HA73+BBMgFBPlw4eiclIZ;bocA z8#$8>(nNpPwgZB8W2zB?f8*gfH0S0Sk#n@uN7hn1%;?YPeg+IogtFow{t)2zJ+g0Y zK`2&N2XOFk%<WH=3yD||()u4pxm$8PJ$|MR`aqn6zTWcC(^; z7AXgyxDKZsj)N->BoL;81>q#q*9@FV^-F#Yd0M{T9lhpaMIHR=c2Ml#__;nHR=D|1 z(cML*cx%>p{*fn(1&n{Ez7+7UIsZS~fJo+F?X5ER_!PJ%7_ZZvH3Z+g$?l7-2hm-T z`%I_Jtsa-V!}FEHvzy1zg#q-k6Bp}Wn zNu9d_Z50_H_@sL+_b=BI%a6iezc7EjsC?6pFw@;I+3-I2#tODoc46Vx$J^7hI&~LJqBdj~wRE1R)UJ}^?c*b;w9p(gB{3B;Jj~8y z-YUq;$1Fh{PHl}pgF2KSXpOsBsNA63#=honz@m8ONqgFq3v*a1U%o1+s{n8u27`s1-vr1=O2z9bXL6%umm7Tzhrv1p3m)`UU;782I$O~pbePjy)3 zL^*z~KGo+=L#jagg8jkMS(7eHAGqfUln39kPp&oS4t#+}be@8}QzCcz7`XTE(N$n` zy`a{)gM=IN%L)zI)zxTA#>s-Y!gc-f;}@d-sq8_2I2aLbmhj0=fX-osi)K~ChB0)0 zxbfikpo@Q*i7*pH8?kS_$F<4lZLYadDJ|gClrB8PAjX40UJ}*YnbT0n;m+9LdbPfN zVQy~sp0})QdRn{I-l?qm^lEo<^tSo0AJ;eA>JT4SACxq0C-F33jUAEdJkg{y7&57O zAt#SbT}Z8g>aG5wILOokm4ZujrnHKOGE`IfbtYpZLnkK{+7FA4DKZiU8r?E+Q)?;BO+P zScD2G$QM~T^*VRN?l?M%vquF@$#z7Ts@ttB5rkNL=Q~_y*>=f_zNql53>Y_$7&t8v z`BV!#xXw>yVsF-f2Fn5R^jWsi;T695qkGO}IeehB7XNVbHSrUx74765fI&9)JNIFe zcK!ujS7)|0jo^CRdy0^HxuU!*#xV;3&Pa*R%hcG=Odf&*$z+D=MO&Y;@EpgTT&N^1 zW9l5IasZrz5des4dDd$f32oWrOtzU@`LDSwr|ujAbg>i4-yt1@?-zRX5qjxI+q&U+ z5RBqtBtqaIFxEDYI)zoUogAu0gDJ@Yq;sX>Kwd7??*r0YP4pmZ1QMc(ZSsnuZahiD zC5l>!*wd;8Phy;l6^JN*d9hKvSM3&kw&<$&uXKaycy-E)yD&C-zDB>}UkZ4AlhZHH zlo3c@P?>$6>iB%d5&NIQ{-2-w8E(R$Io#~mDCke$a^UsMLpNa4|L;NhY5DB0+1LGl zq=Bw)d-=Y9V}dpV?mgdxlYzuA13rib{sJ2danN+<%{%m zbv?73VA3Ua3BR&3W>V+TsePw}K(j_wV zy@sI+KR1vhIQ70d-fCIr$k8)`muo}}jNTNp^*f}ZHmm8rE5+4HoIVA2dUw!TBWrNW zy5F(pH}1PR9QyUF2VYuarkM9Z)jn0KJETi{(_+j*5nC*r3CkK=(7`3~wJ=v75#IlL~V*Wvbr zGYwq;+=7@XpzE?=aJzEYU@+BmW#11ZO}Cf;l*~@cml-rzCRD77b-qsmf?F`5v6q{l zE7euy*+PaLtuX(rEP}Hn|2{|=8;T9ZOflx8@c3QQZQN9xM|>SrclDt6I=4klNQ(;^ z&SGU7{%*SC-^pbM{e)&3dF;BcO0iE^*lB7C$Z|`t0OQGYKchy3a9)VMSzR*B5uvYn zt%h6Czj)9zQ-6O33>|5C1Qf8oS-~%ZaP*sSARO|esJIIE2t=#~Bj1%3vPPykYi(=Q z5L8&xcP!fej;heOSfLdppZA4XbKf;_8xAnC22o;)hrw0=wjD{f$JCJUfF#>3F>3F= znX9haCHPHpb2N+{k#o}h)3+0MQls_R{>qXtQpTKL{eK?J!(CWB{`|it{onN-vs31s z^|C9vM^9@v9dZe(QfScL)ZW5r3gm_O&Lr^dte1Z6yHWhLp7D5o2qHv|Bxvllh!3_o{OR?#Zyc zM@nR7t|SP`!~C4qvGjf2eF%ILdGj~DXL-GTv+M|@1I^5`2nRB6{n}7*Y~wi+xqr>? zdwa<4|GE%UZ!An2A;GLNC6*K3J>O(=V_nMJER`UGWM7*^(TQ)H8m)W}Wasex2_3Lx z-=JJSYEmpr32IW}pr5SaL83ZTwM4G~+hwSrODfmOf!ZVKthD5jAiwE)`#l+CqAfO= zo)N;Eh}Z@!8e|(C$0Z3DG$&|})@+6dFE+hzYi|dAv=BLI;LsC3N#~iac+3XGHyxa+ zq`{&&5wpDK;{-kqwhQ-n*_(7jZXWGqIN~S6Sozec+Ul9oONS!f8S-s1GBE<}2}8ta zayCU0xCqB!LEeh#6u|_xxhtA@~!S( z^rg5wv?x&tV?bd9oi*zq4xy&Dk2n1enPT8KLQ2n?nyB zQ%gg!7-&*r5IR0`HW!JF`lQgYDNRp9MT6pSxf``uaNB}tM}LNDQ$QD2_tmVxsQ?rd zLVeG3-8BBh5666luozNYxO===iEg~f##K?7C1cLz{5sLe6oR&qD`RQwrG~#WzWr2q z4SeyAi$%d zA#2!8fi$`hktCF3ci|dyo2c#Xf4UkmGMKb5yLqx2DQn1?{L&AOA}TiwLb)r1ql2Wf z>U6eWwr%7Li}ZB%IsP$1502CKV4GRr&_AS8noO$o2*L*pV|l`kB zMO<8e1_=i{ZVLI5fVOP~+FXER!^6Y+h+BNi4UB{@NEt$L0V2L~r!3khL&C!y|F;c) zFWL$DJ*^syC7cJH!1LSy8iXWcge)Z!|m?h z^q-XKh1{re#9yMGf8;1Oik&z+_r61}=qV;ryObrrd?wC;jc(qv^Yq5-dn&q_uj0z? zgPL*E_V^TG{+wc^OkNp{A61>5`Oi~!wVCZ?9B{zs6!`cXUF7L`XTh4~b-$Z5cF*0b z<1w>d7(aZJ_2+_y=ifQ=3h<`cG`9?TH}(f1tz~#Y#GdQXM@;U)ARM2#?0umnn`YCc zkJKKLnRHdHXNHXN8j|VX6eXj+0_~jx9*%Qw*F5;iR?**X4#oSgFV+K(MyK}zA2;8X z{}&e0m-N8v3;0>mxO^s_Qv*-;QknXlQvj2D>#OB*PskjVpP0dEU3_OHMhTcpKFB-6 z*ZS36KD(?E4}M@{QkB;0kE9UIG;`+IS#PwP`{$uvjk!gu>3~2+n^`&AyP7Ru@bJSmpZJ&)d-80wv)s6tsnDwq&LlofpKw?}a zGi$F#BcO{K{9!diCvrZ?wO3qBC<>uKnqHxDf6#T1vTE@fk4I&;ek<_e(T6DAu0JqP zkk>GEuZ=%y?bH{h^`D) ziwHsFC>#!eDipGBSwlm^ZmCl_N-K+I z>>9~fqtm8TMY5sdhiPeGG&gZaTo42E#t?;KsOioqw5S6~gI%7hQddr;d07lrEGu(z z83`sK^u z@J*gz?-O!a6dns!(=}tq1Mk5XeVpRu-=S!y{L}-Vi1E>*g*KRPQ)Zp(<9BHiO*2@8 zKCh;R10p{iQqY1}i>A^_dOBc~i(w^3r zWRMQ<@^ges_&DW{t=i6__8}|~!=fEKn<;*{R496@*X;b0%68hViA3?%si8<%)h`up z<TA1?3x zUT(Urw_XNc68c?UV*n(A-apJP1)Njnjz)?+)j#slqCI)mEg0KN+dtubt4(+PH8U2* zN4{W1ah*OL&BC|A(qAu7(U)kzS-IAOs$M(%ZmMzI>U(+YT{1E3>FDYSxClY-zs|iI zYkV1O@8d~z^=k0@)2f3Pzi0g z^QTflA?9;6cDKJIXvS@b+BHJ&G-*_=n{`cfnZmgXwxfhMiMIHZhCfh(DQd=`TbVCj$UT_;{M(&vh-?j%fLu_xYQVO&=*J!2pWWV2q!=S zGc`{5V>>N(z|F2-0JdSbb-hr1aRHTtI|ju&zSL;Gt!1f!cxjG1=Toh0q0!aZ$nL?O zenh}Jv`F+f8(bO{mr^`+?;tk$h}YY#0h)-v)y`bl$htjEbE0D#p3T7Df)3PLJ?pSR zTfxgGKP`^z@BhF8@x_V}9t5BG4l&AHN_Vo#K3jN4^kF88 zJ4Xm~Oq1MyWE-e$nNoUet64%>K>!XU7J8T%a!AragLZ9*qKQdH(l?2PAHQ6elfFw- z3wtRkI>`0zA+yD+tP{i$r#gNe$voG2_ZqNqL7iD&*fSy&$jsCe__73DZK730wa*=-#srTF z(I*V034AKx;kw`!2)w)(4)S+~tG(eBY1qw8$%+vE9shBFyEH zNzf3b8$DQRG6u>H*oj1M@l#^dxfdkekd;n=5Vqom*d5MGrZwsHHp9?#(I2Cs-cwP{ zTDXZs(q?LV;H<+>$SsaK4&72&-F5S=Ph5Omq%(`(WL>aK?8gn-Qo*0~fs8DaNM>+| zZa_H39$HFbW%iyM8BhxTA$_Hd9EaD&An!3&4fD=R%Z^8 z!@bEDihnKn*!|By2_e1|4PKsZ6pUX`_y3pn3Q_)Bmt>2P?3k#O<;9mu`3WfO1w#8{ zm7FzI7J7`&h%C@4CfFwyMB?%h_i-BSBZhlB#r`qIU+|6{ijYiko0vVw8DL@s0CAeb zbJO={VRHJQV1zYmLrHDJOjX{Hsgi#=%AB!!ot|t%pAWXHPQj#o1}xVKbI+oE&DXjl z=U~a0?5?2&?_IQSKPSHrhin67tx z)s`WB%B`r$8i9oPV65F?4o{W$=^~zfrElob5;55@B~rPo50hBt=yN5HT!Dn}4;&2L zs5Hv^R?an}|5k!8Y9L13yQ>qNJ$M`O+5Nkdwdcfk=g6avtLQc(^Xo$dA8HBmt0fB3q}8cW7mAJzYoxU!b!4ceRE#JjK+%#PHb%*f#| zj$!?M!IL%&+#610ZPjC|Gch$z-fuQ<)oZQezZ%=nR?5sI;UUyNv+&YFpWLnecZfSQ z2;=nfdRQf0oALWI%Ml;kz+m2qR2ENDRH?jYXdXU7q-A$!l7>C&#`oN&%ML2Se|!G+ zbkFy)Nx{1>l#H+*5rrBUV$-@2@f z*^Xb?HK6W z@VR7&c&F*xAS?(oQF<;OSD2E*9Gz-4<@1;|E7{oSlWZ>Q5Nxr2;}4z(VqT5N#nOV- z+DRcddqzE+zksh~227jfd^vu9;BvCz3^WcCp{=CS7@TFej@O#>yfP!_aI3#iFBvqK zOLu`PePH~NP-Isl)RS(5N3KjB>{Tq8Yw=AIu#XdK8K~ns{e0-YEHBN5O0T@6CWggu zm^ZrG9-cgqBSFV@jVtZ`t8T5+$f`&CH@11lyyx$+kF~2(*<1t6m>iHy%w2|3I%wV$ zS#t*0Wwh%mev(Pahk>V9>S?}+M%nNPO8(Pp6PtoR~E9mY=cp{Kh zn#B2Cx|11pb;c_WPg)Fx^^h96Nim9Ih{qbzjgKiciOcGDrIJSCrZ$T+M{=A$LkrMC z>D-jF4TXTs0~Mj~2No@=1QQxkVB?}~#9deZSmWoqXt=?F$)#@B3m`6T~0 zhL!)z?gquC9|ibhVFq#qFP9$-p;})~Zx5a`a;LVwbxJi}ikalJ9Lk<9pgNxF%Uovs zB75xnC<$oq!cugG4u7gO<$RL9%{ZjL0}XvXr6rxrk}Egd?wa{Mj}vaw?y}wIMG}>o zT5^_~n>%&i9()!eE+FLlzW1M?p{w-nc2(6R(@u{7JyZk)gc|LxfVxPvEWZ(S@n0H4 z0FzbH;@g5}U|zO%^Fx*9D%{+ruxuQ7^aJ;){f)c11(wefUE`*;=z)z4G|@N- zs)C6$3hCLd z7~RY0!uD0n-gt&`w|h8wG*Aiqs~10ivc@4l?F8dEFkGHqPW@uNkdv_?jT!n%s|Zz_ zugusHeG?_`JccCEzl#i)ax}zOiHL3&)hReRC{q0GTYYfZZ*0}C@$}{Y9Ya-PEEl< zO@W36OsJ5o!_#&Pc1K?fQs85!P|3}q+FdK-ugCJNfpMWe_xc?_u|PxwYCo(r9k|DP zLxAHQ!eJ8l!Ne?kC34pDx*U1oMus1bdHN&l8NHhFE

gqp#Rv5scd0e<3{P-2i z2DZBmkarLdQK>@te^I;jUq%+_H_y=>u#3@wjRV%8d}cxs?>fMK;tvn$X^ep zdWwca#{(6Tm!bH1wg3iOoe7hnQM0}2#wAll)lDz6-q|2?Sb+H`a8r36l2dLzc5tzf z>Xv6>Wc0r5@=@5DksNY$6^%i`PB7Wrys*)(0(sf9F09(KdJ%Tf9e|y=r&+i^!;TkA zSnvV*7Ts3M^O>KpPb#-#IuO zJdVrG1iyj8mzYT>JAAL#mkv)=`##?KZ{i<-dm(RcA&=v~S1d`yUmy4RLr#=O7xo@r zawW?tV|7>f&+fVq#6Ph~PE2PJ@Hz-t=pJm=rp^D*I=6M65W<=eA@u-g-9$Ep|J5WT zTM9ClK;kzndI23uR5`YN=pT9X;;#32OX(Qf)5comFKcmml+bH^v;S+)FqraHKPgeL zF>ys{GD>5FQ2cR61crUfa7!q@q$E9hX*6_N$wll%wVRLcyowe z+4zdjBA0RANIs6Kl}X<6r|_nkhplidjEid)mYMBo4Q5Rzuwt3v)2b?!6cHXaHswJU zwo3U!B>t|m4is(B^l=Vqiu&3Hn$QwEkeZSkE1LPzsCBs2g+9e>9dLUwqQP9S(IphR zOvf+Ia2ME3HX5wzw3yYJt@}W*iQdc7V68iUVXg}RoF2TApm_nEyAxz(GuB!guW#Ts|?pC`cqQTCE<;DS#!nQM^?4L z%lWS9(NiXOLO_+n|5!^P3RJ(8U(LgUa9n`ucQ2dh(t3pKY$1=oWy?F=F~y5d`?Njr z1o>5qM7+)_a^4!j~wIhnXS!M>8RVo7+LJ13-1a5~G6kuj>tM zM(;QjUYCn^7WAO#we>O@Xb#|Tem--HW%djS$5iY@HhVddTfgO3A~S$13YSgfj4~H@ zJn^soV2aR@{_DF!-gdhjv6u532-f}%c@9?<3we~?_PdhOheu1*>APhS0o1ApPOzi92s} zvyP6yz#z99;gCm!kFAh<+HfZs%FrnBS8)3~$i0cJ9cY>`!{025%|`+ViCmkw>8Oy^|Z*CL%Un&w+1pd+;>lbDgz5|W2>WYK7F_y9#8U> zt>;2CM@7Z@j2zI}Q{JSlY`8F1pAxC>u&p3}y7He9vbE1;Zr^2re2uM64jVEKoqYy0 z8mYgRGdsl)8AiCfqjF;`ey+cj2an zZ}0rv$_q0-vJNBa@4tc9@`2LM?nS7tQcQ?{WGo}T*3v5Ve#L`Ia9?dwUo)e!j>n`d z)t7>bs-xppi})0UJxcfO(Dlb#Z5v-JUm2k}m*G-%1QJkRh%;xgi4%l*h)lTJ#*6B# z6+Q`7<_?_lMj;&PSw5gCTSRguwC8NrVna~mk|&|P_e$i@)5|TVLRRn%9na$u3KlK< z5hM3C!q$~PA#})`RIq43f?t3u6k5F}BPADrlc045^_HoCWo?IV&&VI{zfg;}ifoBp zN}O;-WV<{VBX;vi`D|U^*4vRfE#_Cp;Gz|^!6`E&hPZR>;3+=WZm4`zK!vSa0skh~ z5jXjCfGyaK=?b7j`n!yWV>EZ!nV2A2r`X8J1+gO_rH;AC?t4^2#?}ubsfQwqa~Y&Q{e!Oy=sJ!2_h`*mhZ%p0Y-Aqp6MNLi}wtNtB!Nt9N;0^Q-&9|;}-lr@FzvnF^ z8V4Bt*J2Wq{V$^nTg$|IRT3cTV&#gH+Kjnqsd<%6->jIf{`$q<72f;;Ce(P`cH;eS zJB9f7tLc3ov5uFYxj{F~{nyV^B)=TN1y0~R6SDSYlV@2Wm*AuI(-AiQA_^spJ3DlW zY7|X&ZI)MtzSWa+GFH)$QSUB1pC{=egd<1#5I1nK2S25JjPq7mg$hDyixJCK;EiH- zPsqnsD*X{V8=KhsU_~;y=o4uB<9*QnaYERo7GpUY;cP#(M4B~zl-eG(EUJ5m6*q-M zY$=WuK)#*e5ec`F`*D=T`{R%kF)y#io%dH z!$J&e!VNtp6_pj!;G?VNhp`%mc^RnOT-l3ih;i2hblj97geqadFl;k3T?Wfkq!+r; zi3=VrnMoRxeIKXKybO7KU3kNLh_45^0RUL8?5j$PiaX*E#VsDOvBp8O0 zSta(eHK*?Prk*;{b4(Ke11DNMBB2o<*knRImYWszJ&d8Oo$0ayFuctlJ_7+UL5=n& z07Vnl*o>Wd_c%prX}69(pBKE%wEc~mr7kEQvrUV<`OrUbuS}n#2shiva$r&Tqe~X` zik<33@V^rAL2V)<@_6r-3ar~fOd$7txPDSR*mZ$OG0r?Q}zCpBzqlN!Gsz8uv9 zSNETm#+TJ7OQ~p{!6{b4DJ1XkqVS@CZ{<*%BAe-sT6(i;hwD1c3=&p+p(g$Y)Aq1d ziD(TON>)|Uj9=RpG2yG_%cLC07)+igB&-RBSV^xemg%Adv9p0GyVKxRF1c(eQ@8|b z%4jcGV@bNBu~|0XY$~ATO5l$}WXWuzASbttrv<< z2+YMkl!p(*3Qqm}Gxs7xLbrYj)SQWP-@&=rZ6Hmsqw>QdC0?ToD%~Ou4qX;U(MO<5 z^E_iV%{w zg1dr)`@}vj0zNPYwgVv^ZU`U#TR8KXHYaGgcF`DB#*8mjO@no5Sh^Kh(C*J@7`qnI z@_e{qvz}?#ahWp!T(XScv~w`7NM(d$7=pef+)th$^%>)bO+rsb$G})mdoYD~OV@7r zw>v)ep8hUW%xt~vlxUm|`uhb2db)eM9!*~?SrE0>t|)5aG%pT%7roh+p~TXdXRwL~ zehBwJfG&Gqz;DgEV37uU#|56g`h{KUq|9HWA$RGJ%;KfJ+a0L=f2!|mC}yOgqyBnz zlWU;6e><<^PfxxVPT{!($!ruR{od{ZMr`|~fp149Z|4gbV;2Hx(6;cIYI`{|b{Bhl z3r7phmxZWaf%oSNGh#utm(H#sYtF{|dvgo2>?VOH2cz*N`@;~8=o?#9PH?M8pSTR9 zBTx%m&oWTEoU=xGw?oLCN)E=_BBqt{)$`57=Vna7T=;Cl2L&vH!Ii970J!E>p0@@A zx*dv-tOKAWU0Q$!M&Ln%Aw}4V{Y3#g1;c*-4zZ39_YS?qzl%ZM)(jh*l2rUoLyKA2 z22v09=H=u^1ls@Yxu$@ySZAMmouBwk7 zMcEDqe@9W3B-}0;tTUVrHVjF3K(&@!?sYkfqq!Fi?r6#>mJTnEwcf5ARpMWNZb4Vq z4v6B#76;iVRZT_moD0(*`d(fgOyB0cyL&rq0kn?IdVWNDXRe+*F%pCt962Qc|G02l z2NKY!>pG-EkqITab<3>@7}V7mXxJh1+l7|D6=N@0Fi!N83eFUralw)}mR zlM-PVAqk&sW?8;T`BTcxhr2ccJj2QC2lF6uo)` zrA7;@;Ho<_gScGMm8Pt$=i}fn2&FUd5%vKmE3j_vBli!agoQhn_TA^HX^hhF3oR`5LNHRRN&`*?3gV}1y| z;?BqN8Fe3hr8O6H4&d)zo7%4Jfy0;(CM8ceHW6_BYPJE2k)-)z^*wYJL4(O3$+8~? z;E2a~8Lo10Wd<)RZEzl-zY0=h96^2b@w)+U{E(o5iW=)cggeY`={#hb!0j87e%a&g7H7xA$L{(b6*8*1&u6ktI_;QhdC$%UZT5 z-x->|g;Vr`_Fz7yYErwKN&a(Fha%+8yylP7*E235(ckvGL?X8Q&D6gg@-U7%nnKQA z!{hn;J~B-7Yd2DF;xC0*XRZdtA-NsL{jUM0{!ife;qljDjNs=tioRT&;0xUlr=8%D z79+M_VjqE-nv4oSSC<@RDao(F$U>0nRFu1ENv5(9#>~2w9C!3+l$HpUoUB0xWDlGS zu{UBO5k!c3UDZV*K@Iawu1QSJPQ7Y;Xo%VwDg2!G#qkoovolA3fk?km$Bhs1&x09K z#>jE)nUF%-X4hyJE}Uk%uUeoal%jq%yLc&o|J&|fv0+;MjfK4mp-wo@?$_+7G~z5? zcbR{vLui$y>JJ$jS6l5it0>Zn)KyD&G!l6BHSbnJZ#N1eVu2HzXO;xUl-_e+O#;=#5-I5 zeRM;SUhz|4wD}RS+d`cDpdeOekey0^>EYm%c1#tUQ4CN43^8&_5NX9_Yeb&Avg>qU zHg;-w!=jbrl%-LZ!GA7?y-WK;TBbR34#Te%j#|_bBwQ}+V<3gy zoJyCK-RyHUCZS?6y_l)ORg)>_`&DlQlpr)d-E1JyvZN z!`r}ERz>r0_5dz~{xE1RnfqWlN}c=*rg4U~Fo@ckV(Fh4TPjf?X^GyvGy$*n|KS-U zYr$e8H|rhz`13s0d7+v4UVf|{$x^Vj9I1{L?_H0DV>H8cwL4q|4d(%jk8FL7E1VN6v(Hr(~vqO;vo z^&d4Pdiiito3q7xw}Wfp;=%jECDqSM>~BHbqP-tGbI}wc{Dg_pIU{A&D*O&L2mvnv zP}%tK536;3C@GujwMNuOWYa+Pdcw;D31C7NBn%4XqeBVF2cV(7owJkW&rX09);Y1J zdAc1iu-G>GscmW&xe+IosgXqKG)X@Ov5bsJ=m^F{TWKhE!~>f*YtXTd%qtOVlQfxv zjDqYJlt_@fI+~q8_3s;|`0vezoYu7AL@{}J*hsWK6@%s2+qKc*<^VR=hEJ4U(L+F^ zy6`YF21&}#SlsN6!+uQp>E*4~7DJdfB{vxRbNnM zze7UlgOtMA4H&16QR4!`fgW>h`9Aq=4lJt66<*9Z`9KFb;o9i5JgMj9nZ0$%{Cq?; zm~KNi+=XN4NJ6y+D>lTajy z2X%QL8H_8Y0X=|@?(69I5ItQ?fIdhPl`otVmbw%5Dt@p~BN}b$zN$?n=T8xMw|cPQq-cQ-C2jgTn_PSn(bX90+>m5QFXjIYw13 z+bY6fhnH$vCt+`ZUP*wav25fY`xHAAmNqBrQ_k<@fao*GyLU5W9yt6(>!MEqg`yk> zYDK6=2quu*5TM>9!%w5-N0&|Sj+Wb%T(L;1=F;QY{80r1u}hsB|Fp+qFk@RJ>0>!I zFu(S@K0%QRJQ`O#O1&wWyVfmyiR4z{oyfwCru1Y)=o~;*Ys2V5dG*Y-O89-Bj0pDq2Ty z_4Vz5l%Dqn-$fD>2#XrCWKO<3P(U6KzuWI-!b)UqyKqHY8-vMwTw8_O%Q%sK;o3^1 zP?3b0_*?|Ho6f@)|GxI@jTd`nS38W#oc+VLZ^?RgYWKIxByZA=mr$)%H;J zeZ27PugmMud0ji7s%kEK$R2SL`7%b0h+LI}<);n<7k6GBU0FpFGu95pg3WH|pZJ}} z4PxxS>EoGo=h)_2D^C?_q*2~?U&Nsr>^ItsbM_#MJMdy-`}v^e*H%w(IRC}rNwX}Z zz44p^QhqSB-n6`J))9t(wT!0#eSt&>5B;$C9)S6%&g@xHJxG}c22onZY<)8c6Zr{W=y#w zYKJ1`M29NmC!{%|DJHpu%9P4=_6qJJS4Qv}O}!4)TOCh~%_3XY3$Zi6%nY^oI&o2C zn2${-LKv1vIvrXHYu1qYnPVkm$^w*qc3N7ig10l+p(dlfF!-8N;${aoR4%oKc`Rgc z$OOqTXTtjNS&`3Oo0k;;8yeA`B4D(%nYT)WJsN-YU20rjJ2H=w=6tjh8%Bz2Sbud_ zg>I;t_RR9JX~9$`5;mzTQ@Jq9cxtOU)s@ts-840CJ_ zK&ryhRNb1bo!7##yLF8WJKu7aY-?FI3bUr|K0WO`7_W{EB4*cCuB$-_elN{jxneLsvZ+@}6+=J@8G6?0*}YR$Ok>tx}}`LC^B%d)hZ znl?M3)}`u%f<(6k**x8E^A?Q;7}1v0Jj)^^EZwvopmgrFmP@j?gJQc@!=;d?m+jH` z4pBe5Yh(EDOk7}OR*L>@kkD#~r?IVbS|5e@mYyUi#EMEGc^w;N4Jeo)TNx5(o~CLsp3)@6|fCGfpqWE{rxKr ziT`HxR+o2vG#P2Qk?_w-LH$^!s2_-C-K!EtMnT+1Z#hCs%?lb8b7n>oYMk;g z-ZS+PN+p|&X5Pl(n-s<|u3cq+PT={2nn9+oiMCieS+ByQxE; zzwwIb$8fAN9V0$I@8?gb&iI+mC1ii<_`eZH$PavxDs~={g5^?WLFZ*hXHRS5$ZGj# zi_rQ-zo{w*UwdGHMGg_2Dh$?2-H&n6uJmEx%R#O4`07*-6l?Tg0=6U~I-jQW)!u$6 z?*t&b_=I}U1E5B%)2p#e;8Z=h3PkMC%Pc;Os)%o6Ze!}uJ1b|dLI8gal|sD7M}^-g zQqr*I@V2tB^o#PZfA*m#iX*sao_tq?(d!8IRXFYLcHPRQ0cqG}3S{MB7Hm)X_} z#Z;7^DAQRlMCt38*)a-w_H=`63L6E)2uuu|GUON7pQA=#p#~%>+t}HiEm8Qr5Fc@~{9w4O zDpcBCPTtqFJZ1WdTiC;@>n0N|E6L5puCK4x}KXXjV#$N&Ucbu>x>ZiK=L+)q@o zggArQY?@`61?(089|Cg^9a|SZ9t?*ZXZXsH%qIw_XTO+lS|f$$hqv)bt~%=nP#GS& zd${_4APhs(5~+H~E7zwOaOxsp)APGWGUhE#5slHX%-_)!9s8>RGMEPUxk7VOF~iUf zoktfzO2R12g#kNVu(kH6=<*S8X7lsVlvMmaFp65zw>pwgX6&Phh%j`qVtQWbIWL|R zJGAqKjVv5HxU_h?{?;&IS@}@>oP6B6QuLuX2|H%I%3tyW^5q!1>{_K(U{N#+3D1?r z+tlSJ;8{bzby&CqWEtTa&lR%tuo#5lkp($pVz9e&JAJBIU?bD}Fd~5Fkf_?`<2kpr z-z1-<(LaS5A>xXD2D?eYyHi_m#AJ~!xZzn-+~`|}3bN~*73(=qtQ7~fHI!wvX28%$ z5F&FtC#MU%Ay0lIt(7^Oiic|Az(obWS1(kr^avExjp)V@z0Hq|xK?J{i+I|pYh!v+ znQ(iRw{g3?DW4gw&K>(S=N8s2whnt;{4du3=z+UQ{ujI2)hW>^33h-Pe!|_(7)b;| z3j9W?pS&2;?{Z7b%rh>FP!*lt?*{alu+SdZP<#C$NzEkw_aF( z@9Fe=>n#+~tK-KAdEF`ue&}P%tWbsccXUGvQ1`rTf<*oAos)96vnlI^z8BKFs$E9HNO_dPuI$SKHHwPonPtvk|m*6BzI^ziw< zx_;U@czqmSvtZJsv69f9y1O2I@#o6B#K5pG%jkCY@C*!0M3VArgz5p>K-r}`sR?ez zW!vd0(5Noq_U5bY4^1$RZWzVEH;XXckQQJ^&meA@di9ziW!WFwPO}ZAMEsHd0)wWF z^0Ne5Wv&>Lhca$L3?6!~h!~yMi=Q=o;`hw<>c-1mxZ|kWpI9sP3e*lnCY-a)$uSgy zukGM2UTCIb!9)#X3Awx)`IXw-HlhR?1caH$Dh20q>(3^I#0DGp;= zS8cZqz9XA>CVA15I3h%(p%J87C(hg6ykZt)COB%K)@FVlPNHm;zOw><9%+-l+qce~ zZkf=RQT&#l>&I>Mwn(S9&FfBn^G5qGAA15-cB4*mPHU3n znx|XLc|ubtg$dZ3X=rLML`s>R`ZK8SsW^gz;{sR`jYFU4vO3`1!v zGj@I={;3Oh*0ze{Y=3xuAmu8B+s$kJjid#aj*8l)H}l>2Gb0(gng`9^2$GbbG|U_s zaOj+^PZ~MO8_W_hRL%iuJ$RFzf%VdY4UJq>pqa1?v%%-@fCJ2m#v*<-%70n@Vv{tA zdJ3j-v?>51#|RL`Ai}#5686%JLH%p--eI!uiO*Q#yXWG^YP(Q5EJO`gYSLgA|Pz^U)X*m3{VU(5P3ex6l{YkDu~0$zk*Vl(vlou zDMv3JIS6vo=DdoY8w zWadG+sWTxUBI7?RW9Wxn)--({RVp`gqoYfaxP(oOhr*(=c=&>=X43^LefJaCS3O?= zS;JhM8v)>_qhVDyfA@LMva|Keo~KMm^dvaY<^F0gI`!nhEJWzn>62sNXWdr)X?ZDl zZR!1MPoYl#Hzug}dG^AB{B#Y4Ig0+5)Q7Ftw#A$HQIcb|*`Ox^lL_sdgsAA>H;@iC zKQZN+`d z9!yNjWS=5`4=<=zc5+Cd7kl<~wCM9LAOTzJ=WPiGzp@hBSJ_jcr|PmpA1K+&P-4YG zf-u|$#^EU4&p3^sG!%eRi#0l^M@G`Ud7aSq0NA}Wy$C4ovpcfe6>GWFUVKz~fEBUs z!rZ_wBf;6?GEaMm=OmgW?gs8B=785(YiCr&pM0w&i;FYwr61UwHKF+kzSTwl^#bTn zi0HlU1pKx+%H986aUp$nV3$=rapuN5V|j~CjF1JS#r^y3O)|qFh(zoT=RHB%|2#1(GQ5c0A1(Y^8M>I4DYW|Zb!=Ve?mvf!6) zpNoD!HM2TehoaR>{CA`p0Kc?lF#(U+)J=fwkj^P68G8mio5u>*QY^ufS4IuT!$Tm% z{KZfuD9sN|WnHe<9aHB!N3G8lU(*FZPVe;v(50%WEQ!W`FEv4<&!XZqddXPT&}#BD zNQog)h_%hOvqceL)YP-2jL}KGmj&_CZ`MUYVxV5h-%|oeT#wS7TS0UY0ps!nD#-)Ul7hM&lsF zkDu>xX2UH^{02GIb7yol{1^D&rzZ@_$-I@eG)wZ@{+jmH;hk5VZAD+kyv$2*^WHYx zHONbc{u$cE^@i#&2(x5nD5`{>ro2;3!{#)*V#Oi14`!r^Y>$&ftkG>rh5J4>{uB1R z?%rndNip~c<#8`S_Y&t?Jm9I_#i^jbsn5SdNWd1oRGjpN{2yxnxx=P^)AK4VCgRO% z$mkaK!5l2UpW>E#4lt2w^Wn}ISv$s8-No>%U45j{FyTC%`0m50ek_PmrKD+YDkh8Y z1tI$9TcXVHO#gdle0+T2>v8_*8^ToczRy;$tE+&qsc6=8dFnL;`c=nVJ2;N=Bwfqb zJR#cAobTgJp`Tahx`^*b1;$oie~<0^gG&!>W&O-Qc4tSCY$dv3Hwz2Ylmr!7gQc6Z zR7vAu{E*k)g?MklqDAA?UEZgm5dS-e{s%Q-L-nwhy69SUlh~u`k~Gs z>JqqWl{wyvXd6|6$#^dtC>8eUw&I^!H(Mur04bOx%$i}*!h&y=CR~LLXb572X-sQo zJI+Lc^;*rx@Tlj z2rPMjB%1DmVR@!OAXM0l#os2NFeW=EH6La@p;qVVJvy}5rC3l^eO5w`Z@bJ&D;P}M zdjsawq7Zj{s|Ft41?rXMkzDc!LRu8|0IqT;C8Gylq`qb}*=5M`5uz_th7E&^(5%!d z2lto}HL1S1B~Fq@r1|od#Y;B}j#>%T+FAwr`v?96SQtU4m+o@N7i-D8X~PebT&}AO ziV$m8O?+w_9fvOy&bln?kt)yoa|pY$lf%x&SKilmTp)G=Y*jJ9Xsy=d9dLBtX*om{ zP|V6&3~(dvMNo~83I+mcSX9m{(+6PSX*-IuxDn?G5N!{VkXULDSiZEV|z6hqw2`$iKI4s14^bP zup(*7sPk$n{CJlU5Um>M9e``l5ULD|h+JBNj;;(})F0f%z0exCMwN_UDPB+0LJ0#6 zhpu)HORY|g3kZBWoRBh803P$8y8pmxpNEKhvV>U)N+n*O@>WOW{KbFCYH;AoQQ>Q+ z9_P^t4904FAnls_NYfppMYWFb`d&zM>+E`ao1aDTGj-Tzjy~HU_k!Y{EF-ehNp5@mAq3)==Zf?tb>U$=O#C^fcP$t4p(mvfj zf$TH_?+i|z+JAS{Q#!PZ{HZV~GYXi<=vtHWhrg@8Y7DQt$AK2xL%56MWJW|EI%Z^Z zK2Z#%mT%#I+*dtug4RwNm&5+}aQqse@&-{>G2e9H&`d6bDPq#fj(3bBf0i<1Z$b zC}Y>@m>apgtLaI1(S8ks7#33`vl|+}fOzvgA~dgzJR`n>Pnbcc>#zPvt)l$ceq0QV zy4q%yM>L&^idvC2bJ?E;Y$}e#@~*Dgo07X* zmm{1eoKDFKohKSVRY3wXjE?*S_)#jsTJnN)nuWqN>9{-i!z!_{u$Y#kwpPO1Hknke z#NH9VcO%md5RHMSIpD*TKt@Z-5(TAOVK|M=@For6 zm{>@5tC*Tca8h6Xe*|Q`R2dS@5BaFvL>> z0b&>3({*b?$Wi=1LixwwgyEo9a)XXuG0ezc`xe&5Gk(h6e>iqhATebdU-oh+hBDZe zmlRcsRaV#wMCV>~X()gGROv_&oQGnJ7^uV?PM@)iUNj%%?~VG7-(fy~{E&$Z?msz{ z>UcP3gZ4?jEI?IBlKrg;uL_Al{m-Nh3d>A31w$LpUC3dM+lxj-2~-2W>~rZ|o#yYg zN}(d+Gg#9n`=Uz#h%xE$!R8X`!z-!xU%4YXn;V2%=)E8A((!GG%#%_Xs%VPmQf=Ny zzAps2xS;n3zpc}oyhRA}O#xaB>M|xv_7_~44yU-YhMK$Ic^DmX*6gNB~W|^(P*ZWmy~Jl{O;0(n#ux>V>w2 z``#Dvj`u1odlCPBhmDkj&7QCJn@fq>@!7x2jfrGl@(^HnsHm8u*`^0$SIDMJZ&O2Bi-3v8Lrp%nt7wm6%+%*Oxx=0KFmxL-TNivZ)wg50)R<$BwA6+wh_`r~YD$p_euADM87`ZO->hdc#$e@1#S) zRhIad*b54~NJq%~Ud27&CQPuU+2XH7D;KSgMU+)^s755TCRfsV9gz@y`M920up2y~ zwl*&zzZ>tTKX^whd9-o=2xZ1NB*x8M#kxDxZmt;`8(;jJ=g!!t+4{+(tU@^%(X0s{ zsH^1dV_G<_M3MG!rG+?_pp9Jk=la5{Og940#@H#7RBBKgj-LRitA zN>s7gH}5*bIVS`!Njvpr1UTAxiqjeLoDZzqwViHQu3TEyIbAv5$ zXW;v(Fk#dn3lNCl2-J0wlQQMF^ar70z4A^-7tsiKJOSv89W7Cq9k~V;e=P2{yi^SI zgVyGbKPFf-i677w|6`R~4ip*gNbUL`u^h74CC3d%aIq-Xn{=OthMoRW>?jRwKKMmy zNJtq%jZYscqB;3Y%!QH|H9Y59`SKF2i|!2Sc|Sk)Z8ZqmpV<--6ciRVc3jS_(Y-%< zxp{KrB1Lsi*HpmzAVsy$NUOL>#` z>CY$EPk426Eo4l*pKEtr*_MhH0DscZdVjN4z8=DBQ)7+4jqfU|k?esca?yVAkE9V0 zaJT^WOP3R5l(c}KAY*l+`VP6>@}r$}`g094o0>HMA8CpwqOq9R9W@>^9l`@uBn?Pm zyLim0P)g>YJaJ)H(^SEy#29D^jd^`>)jfkkwo%;liN)DmBtv`P9D}B_yNz5C<0d|* z@&XniI}7D#m31)XDBB6Gl+#S-0=_1U*lCfZKo`jUAyW$f(W<=CrY*|r-tpC3-P7#n z3kO>OlB!B(>}MX?VWA_19-`|1!_-?pL=|>z+e3#)cXvq--Q6HHgfvnj4Bg!+9Rov% zATgvMEz&&$A|>4*E#2^OzxVgN@AJ$43-;RAzScU|ad5}vb~HNi@$5L^F8bt0K;q44 za5?|YlK(2BcL!VmQh%-eGSZL=@R9Bq5xX|33(HqZ?Zx1XhZhv+u?oS_72Z6Wdp_7U zwj0Yxci!wh&iIMvYhuh49?^_@AkJ?~Z$6lRiZejmEoK))_vpS>1-#-fmYHMl5$}O} zBD_bPNLdJb!SwDNFgM2Z<~QInFpkH0R01SFAF|AlJ57y4$N;)X$Authl$G-l3H%Ut z4Lwf}rf&G_0-`ki_yEO--1Kl0O!P)Q>~FuC8}Kz zj$$Kn3GrVyXwswb_cVV5>TY#n*#<8yRzv!xr|(gj*rPXbjFO8vTWa z0Kr|H;QXelPn46fZ01w`9L7Gv>CIl;VM2Tyvi5vdq&s!yqNl3`w?^;UeI^H9@+}S= z-qtzROaG0#JlylRDslXfLlXAB=4)~GX6-J(*>?h5erKXTd^f<2ihSXebCt|(k3LWO zmdJ*LzY%R``2D6$@SDJYKanStq>h&#^bWD3tDeVjJe4iEcbpc+>=nUI)PbV=x*D3M zY;$&BQjcl6;F`QeOZTTw61e}#;S+zJOSW9KJUXhm+7MOnlmCO5mTn+6=j2KoROFTa zR-YR6Q0{aCaj)?E2mPW#V9!$wK<uFeQ#dqZ(*8KRu5nEmKcjo(p6S z0`r}rzLa^#MVgp60}Z_?m!^HV4IFaqJa_bPy95@6tS_wS#O-ccv(jeuZ1K_I z*U}uX=HVpIY5^}*E~hd)oquf+h@&;*6;Bu$n+wtaT;>kE3rt9$Gn)*a@3gX1NQ%>J zEj&h#Rk_sqX}BWBh2==b z!?AVA{l2J^aQ%(!w8e$eOpmqSKZ($7=aVcuz6-r0;+0%9b?fz`Z*es@GOMWWP07{g zG)(YODo`~Zp6+zqx@OdZ=REoz8Im;}>fkF{i zgCP3D07V>_M}nw@`%yuCvf^;O^;TG#xL6NS21f#^93vla4fj)oJd#9(r2^PR{euLOXv_VG}AV-fWk)D1z#NZ|bP!la=3e!Xo z0?BuX>z`9abK{sww5Hz=6F;5_+Nl>tliWlS#Q-tx| zXFp&nD0a16;`V@TJr@@zFboK8qM`Q5c+zInho7|HZXIbbM| zPU^?yT2sbc?#=O}d7`S0Gi7do$O{OF_9{zMm^Ilkqi;#-E3q}Tki(ZTbmcG7#T77k zZh)UY01*f_QkNpVV|q*oU^ZCDTmAlrbe|-M#|+z6QILAtV(z6Aes@U~7P|iG1r>f! zJN2^d{*rKm&fFbXhBnSS4{r86Jq10x2~&K+!@Kqz=MtpGjW$*L@ND(GW<}S%D}C+x z_089hMo`4a3*gw}yu9oAHQ;FEcII&&K~^jI{2TEY*=JqgYA)fY8-><&LDfQOH8Ved zJOBJpb5h*!#+vE#ia6U@r4hTfcldq|JVvPm+K@`oOmwSdEym z$mlAosw&gXF4KwNEMUr*sHafHl$WIY325dwvBE0LpDo}_ZH)d**k}c%y7ssZ@NYeF zr?E32oYG_y&#O3ityJUd- zW6}6!`;gs82#>9kWGGmJTtq-&&ScITpS+JKlgr{9aCqG3)M_R)QCKrMvsp!Ngg#Tb zpWvf4x0sht-tcZ8W-`mfAB}0=CFH=!r~NjkO6h*BX5012sLrXx;;e~^XxpdBi8kma zxo1|x_Nu<!IgEdmQWUMq$ZM)OO8ZjvSt%fPxtPqlCFHtnS!*I43 z97xzOx=UXegDI(EZn|po^db0Xy9vmAJ|)1;ZYQ|VLGiFD8zXS2?L#l0vjS_!yn`0( z%zhOa7jg7;Ql95x*ydeVT!DBdcU0` z7%`^RBqKL7z7k%LxI<)(Q_~64%1d$irgQ0Y&$BK?!&Akl^<4WEeHcti=T>Wk%gw5>@!y0w)&lavXGa3JmhG=w_#b`sf%a08}fckfA zp!==d$E&ARWEouXIqCKncI3n9TVbE0{|ls}WAlFn0HP6$)n}ev{G<=1sjaHu!krPX<+wc0l?gDCJRk37Hx%?@QQ!jp=e7NrN&kODI1*taQ z*eXJTZ@XTmVy)H8YuVP%y@^CXSse5SH*ddI>7Y0ftkC1rk@tYEyB#CT73tQwl|a9z zUyYTc9EF6L7czYFDqYf^fyQSN`hV z3Sa4V4Cl!D_8Em8M_tZc}45(PW6qL%u$ccg(BVN)Hs(BW{|IVg%Uv_67PE}T)RvJ&FpT~V^ zyB;cIhc@jg`HNCcsA;szGE6`;Df{>3DxvpZ?~O#pTpykmCt#%9%EEK)G-^^Nn${#z zHFiFZk{#mlAbcB!+0q?zDpgXb&(!4zq51MJQG?CB!+#a@YXbP4txwoeH9`9pkPX3n zCj9+@(WPZC+vCkN5pNjhCx#+MWHEot9s%CMsIxhb;&3FCd+xDXJFRU@2uf|6mtf!? zS4L4#PCp~78}4-jq>^g;Rd`%3hbr^$+7qoNKlIpbSROI40{l(qhN>9~U(-TfX{UV0 z)9+;zs>m9Pj=llpmyc>DT+pOrdOFvY)9|SMd+UCC?fu`)?XedN%*Foc`ebQ>nb9`O znXZ0m`YOuQXU-0jOnjRz3y|V(&8CMvRQK+Jj5K8A6B29(phx0hFNkDm1g@e*QgU4b zu9F9X#aG_Zv4dYbRi>>O8O`mC5-TVn*bNzTpI&oXXkt+_(a~yKtu$A5R1OYlL0t26 zZEQfMb&Eb3V4jYF?W@t2%dME`1M$LTne{)=?{eJ?7aSD%SpC`7+GU1lqw4SLDjny( z4uGNuG?iqjmxyuGU~{PKNWto;iUfR`h;(tQEv+QwEm>ErV>tbnAeY>B)~^QG=p04@ zdE#*tTZ%l#ZdwIpdP8ccDEe+7k1)kA{{jO4m8PACp|5TRH}uHBqzVcFAHpztVL3H8%!+G6p)LI_0>nT zTFiyhd@vd}|6r<)*a;BI>QP-k6W@G;6j4(?+Dxo0Or+FLM?ZW1FW7U)#TIu&M|oyY zMWddUgomM8%RgMn6z7=HG}5ufo`-^#JFW4gTio`n%Sz`J&NA+>%3l`f)7kGaN%VS_ zJ?&pR+}+{wfXnE|AHAcu1P<#O_`a9?@H>SN?;6CLdtk}EE-?2uf*=`R4Bk=!I^CcC zy;N{?@Z~x$%G2!_FHK#_&Ou*wQWg&D@(u<@Pv6LhfQT5zZh~D^>0b-C;Iy`myRiM< zHQCWqR=;?c2x9=R<8C*V~Lcapnn(p0a6q%9p=i|sgYKS8H`30(puP`OEqTv;#yAp0hk!Yr=h9az4>_u zne+LovE7s4f1N2m&kvVpFlN00KOdrFecz_!l}UF53eX5K3=(9pk`JDLvwBlE>`bMC z(K!G30VpHMdOiRB+s``9<@lwh#egEK?Ab?;Ds!jM`$#tLXnO(w?VdLXTLH?Ml1XNf z`qQx3%`@#!;7gf5^#bv#nAoJ~msr7;L~Tr82%!|V{0muyd7{3Dsov|8Xlao#S>J`Jv=R<^B@XgrRE?b(!rhGSFfwI{3n^ z6j^awWdSX=#}-Rkln}mxSo^~&JJV|-Y;H-ha8=nDGAC8*QHs`SF;(x@v?zM3nyQ;0 z=3G1q+9I1E z`kAETM#`a@Fu5pgK+bi26~O~~1t5DUftKC+5u9r;3H z!rAoyWC1?#YkjlxHZZnA_4HBj;KS-S6T`$3qi4?3<0-a^fRPsDSffVj#dx=UUFQhP z07jx>wPnbT=(yW~`vFPhV(EWzUh&Nhr^SEwWWxMbZ`aOAn+BjDsoMXaeRE#I>dK#iiIREOZ{ovWZia{6jYF?I`6=!*i}r3?LZOn*hBw-D z0fIyA)8AQO)47FRELqTSCW(WgaDoXz-x|j}{T_~RgS?lIjgKd9y?bk$?w%m?2KB`v z!){t&SDe7npEcX@;YU06bQAkNvTs~euOHUWMF5iGp?<(lF*@^y^^rxo&WER6-k+-d zc)YajWD;`8FeEE`Ql58aJpR<=rfun;8VPe!Og_b#kVg^>FXO;JhpV8+R#A4K{C%JF zhp-_wQeDzX<&e`cKca7(}^Wd z*OkoEiP7rA7TtQ}>-I@o0hxSrOYXA9P5qv+lE_B%fPi17`EQjSst}E1VELRWQbYjD zBC|`o7N-ysB!cL1#>U!F zR-lt_Ug1ksA_EFd_3)zcviNI5g}6UOs~CwaOgmC~YBc6nvI=Q+=4GX%H&{-{IhTPA zXR_ReKWf4eCWzL!S{^u;O|Hd+&SiQ#<#%nMFUS*{Ayuajkt#9vsvCqTkbA)(fO$P4 zGX!1%H3oJZE0EeqFOPox(GvRl)AF)*_MjO<7NDEqv2Yo<9nr-%SZh4IJ#)!GU)uu1F@cLD(Is={4JwnSe94ymEL6-aq8@)O zSWk;mRGEMoUsOjBjsKM#BS)p1U6P^5EmF9G75a5MDMLjYJIh;X0JfUE0ExS|!#%5B_@~^2`AbA`g02V zb-HZ${J^wet}+1wKRY~4c3&3heQ}ls4=WE7JTP2=M5+$8Dt~*w$-j! z2ZuK;jG4*|0*%|H@vI(;EWJ|<6J0|>>pWi+4WR;hbF_0!|E0L!>ZZ1M^tD6VpcD=b z67VGSWN|qJS165w^#(pP(gevzw-}eCtsK?XV{h$WM+fDA4c-_J#+6yMlH&XfTBdeQ zdJ5NPKiet;tYtu(U5a|_`grRmUzeSKmX)1!X?11g?mx<1k-VvJ`3rdyW_1bX2P=QK zdP%=!OYfi;tLl5?kju&c{EUk(=Sxe58jmx)j@6JDf@Yjtv~9d#J@&YA>TMASEL(Q| zicEouLd+lM{jYn6bk3CW2`1Tn>Zv#333RK+GtNe@`BLYBrZj`&XzyLEzD)YzScw zjKw3#CK6Wv19zW*=O;g8Wu|v@L&C`mpoMDTskgIa=FgcTRkzlEE*OUY)~hjCSaJv6 zG=F4Kmn!HlJ8tJLN;bn9vD|Ko5vR?nAb?5)`Z=qj1ifUYNOk&#d@8eOrba~ zPSq}}?b^KSD8k7@<#!dmeJ6F&kV<2QFNqNj_!ivgDaT+4B+E!!#0A;415ip=B*Xx$c6J&?u)}0uhhD{ z)5@^H*~KUQq!q)n^fB_Du@Mx=o)wG~89HD9CMc<=Wp35X!XyE<%*6=I_2JE~#Hgkfa~ zSoV1n7?|4;+}g%$9`eH#g4)wmZG^^AOYl!gh;^I^X+djzu1cTEWmZ51XA~@<4I(tu znmf;YC}I_=ZvT)ND}yyT@OZeZ67>JbuSNAgzLo_S0pc(LM!bh?nGvx315et#RRnN@ zb4<>^TuW>~$zq|);=*ZL=3Vmh>_M0PXPg zajBx>T5(dnqXJC1!?448$sFMqhk-jt_XgQAEmJ+vR2lzQ|rVHaH^m)e! z>8^J>M_ZWf9P#6OdVCnB_Kt8AapFQRBdS2l51=paBt&!kr;8sKSZIU#lsbVUmfRlc zX!lon*JpA)(lc^9Q$JH#|1rAvZvJ)0xD}=!hylwj#OV!5y?u?pv`<4+uBjHB{t^-! zBfWgXWbM`G#-7}pLR=d|>Vq5FpRyuTXlE|JsxBuvl#JLnVU4{0i+YbUMsD!0utf^<>h75wQ;|0%i-TqYPbhA0J;_wN6O-y_PGUov| zyHG{d)n2Sw1)N?GC4YlK=O4lvkSoNA-{{S%Bj8|v*UZH=W}`h4wKU-e#I>1d-kOm!Ivi zyZ(iL>WkA3-@CSdf6T_V2jG!euH{iXi9Gf{A)t}W4kl#yKi3y}OfjZwc$pA;f7_^d zqlP}zf8V83b-%PzI<(nFfR#>U%3cwd#qC3VlCapXZ4ev7^k&GMOP*)4!J2;*>WRB| zCpfT%GG4jFSc~;F=0BFoX{MuW(&SyNSI8zFjK~TQ%+h_QksdS-hc$6BDaZ#m*&2+8 zwbFMr9osfQiTv~mSS2Mt^3c-78ajiIJPjv4`E=6y)|3fkwep@P_im=~XnSB^Vpa5c zseBbuU{HK^N>jV(C`hZ{NXXV5fw`myrefB?XVBL-YHe>v9XaIkO}&hfAB?c&GhM{n z)3>)C`^P<|j*lFXixpXbxm9L`t|`i=33$oaQxTbxR=mDtKqjEhm-2zf5#sFE9y?Qv zBy;UX2H12{b5TeAsXWmq9X3Hugj9*KM8C-&&IQsXIS&w{MGcfLfW@+S34!fY9Dg2&)vQHBjBK+?FYGe z(C&={ov_S9@Ad?;pWi9ISUvF15cavGrvo4?soK%SLRRAz4^J}y-(N03O!gOyaH1?y zKI80xqBW~ig1R5Rm7NH$_|+1F!v2oI;dY$5wZp8N|6N_xNf)oo4~DR50Wc-b4}sog zY(>#Lt3_WraLa^VK)Q6{_ne`tE9<+3nRD8Jt6j@Tb64Ri1!w^ZeCgVh9RDMv_>1TA z4rA}z+V-t+g4DZ%B(1oN1Mb>6ZVH$(9&2$j8{Y9;iF@+rvY#UKCi*HR-D$a^ZQiTT zPn&f?w;ClP7HRmbQ)>7OjP}~W*EfMOtv^kE2Av$Qzch;`2>{tTK~9DDqH>wROe>dI zylxu+n`|3fgJp9{fc#vfT9~Y}iYH^QU#2{LDxa_U$?;1T#bkOEl*9<{g<&spG~=>+ z?olCFxvBnqxZRPM?%^xI^JLkUKsNGf!DCuQoc(b#quz)F zi@-}cVafKkmNIZ>bFkUfk}{^z%9y=4Yy@WqY&$|>TqitsKCY=(r^w|j$6BJRKY(zm zIZ!g@IlA+Q8bRCYW}(|(>|%%pOPm7!z^M)LH{_1XC!XAy3sGAJ??wiWvp$^$P{5%s*AG=^5REEVQ zpG-3zcRCEQkTWQ=3K(^Br$I%E1%TFPw)M{SwvqfA`br?JuSYWw2pptu#mdC2aljo; zG76@DVPmIY+PE1BmoGJ`W=b`Ht-{5oGpX(0Ik9~~l|?j?)~W%k={T6$yO9kY0HtgF zvPD10bm;lu-eVkMul_XJTDpag%Nu-aM3R>R*fT+Pgb_g-p3M9*nL7JeF9Ee|4_i`a z`!7i=1H~f+(@5*i5?@YJH%I0KW6sw}_Vere3s)1;KV?Cm!ft=$ zYC0VSA{(QEqNqUk=Cef$w8j8to8ZO9)AqoF&q8IlY5`WYHzwJ7Ayd{f(mul1_BC`1$#3 zc^W39ZuflVfkBG-$@7G!6JyPYF8K01$I_-Ob~mMAGYYcQXddU2ZmE3c5dW#0<<(wc zWHy{jZY@)iM6nAR36#WcnMvQ`rGE(48Ew#1Q0!%?6llIw|A&CfBW-RlnAX@Y^TwtH-hVYCr9{25;`{?`+vVO%**} zY^_-h|IQ;V`AlHP?}?c~**%b&)wS^w@F0%^1u~wk*=~UWr;VQ0HfevmD<<2s$tBSl zJU}A&>>8ar+9(%pf$k?M#tX?P=TF?-KWSHo0(mOh1~Rry;7*o75s(`LiA&XFPXn?BQ4%q6qv;uRBZgv zS`2Rb9w4y&s|Tx1I~Brlt=kJP#z(?&V+(&H0EUmewyiBONfoat55xh?9YB7;mdKp|$kN-RW!8X!x9?E_F98OuQbg6iAaLz6H)_idEyQ^%WW zidlWD7dW^6`d@UBO&xLNWo{06d=V5eXjpMUV0{pOMt!0Lg@>$HmHoKv{*+Ha7;Z&g zS!EvJIbRyTZr-H5VZ5pQ|5UB`|GvJGakyGn$X&=S+N|8hU_ZBb;S$>Y z<9}UoW9~uV_l?1g-qMchx0TqttDEEP(>)&#-w+F-3D}(k+a=q1WXE+&?AtoLqPjOg zUb`!DYQvV!SZU`>^;QSJnlmS{j-ifL(hRD3ZnEl!U)4q|Z%xKHd(+6+192(bcY-Eg z*#>5E(I1ua=v+nydN{jk>R9Y3U(C4O;oC*?{oJ_G z%%PQD>LfVKV`4eFYeSC+Tye#%t}XZ+2e0QH;r3LiZ72AYs0%MN}%-L+bwQ``t%}ELBN~ z-_mla9nCWXV*l_$o=7}{&rXK`svEZA`i+P79^L8Y%{72O;OzRu z0mF{tmB);|@BG8<=B|d&>FXU1Z}Y`VmpV8h%JgCLsb-dvEHk`u@8WBRZ>{UgPq#AU zq_E)U!)RnRyRElc27iY>!%6DWm!(FOv}nYqN`sc|LnrlAv#^}^T6tRU#w+m-nrubQ zr@n8p4*cy7755h|CPMBzODPp=dG6+ah)Ij(QS)QbFI@%OpoA-$S&tto^B8;= z^J!uipqt_Jcnkt|d19In;Pf-vg7FnuZL0EydvQI1K88mH#rF6ym`O~6hU*QhlFzpO zeh!pQ*u;_JVlQ2+yjo!@Bj@IWqxP!2(KRg={uq2{kUT;&3NS51N26Unb$s`*)G6H# zv@dVe2R6<$bp3ppdRa<#490qc24GkjQ$EZpFH~iXQdoryLOu=E5=8 zS5srlR&l5{*LnwX^ggMo9w7Zz5VB~bRkoFSmcSBxt=UL5~S0_=3(hSA)hCSeBsgOi#lwH%~>ZdA4)Q)J-QH z`sm~lEZzPP+2qu|?^Ty=H%lVUMmqn2ML%XzrB;z$8bq zw-D8L_Z>Zr9%Dk0}y1&@>xD>f3 z4&7cHyUxR1XJOrTX=c%x`|;6O_Yj&YE&GkcAiVuOw#~S7g*K7-8>#$=*=1e zW7B?=3!LqHCk^p3P`Lf;X-A_w=S@+THGpdkgNgSoK*%$TFQ@_dZ4`%n7{mK zgHy1?gxl%Zsq3GJ^tnv%CEn!b@f)H_+o`6pl=)QpS4A;M4%K|;`p1ML>M-hx1cOGv|aC8Q&s&_eKeq+#8SY+2IAo!;ylw6b+u5uZtLL}YhnGk?dsvQWj zd)pgcpo$Q@uI*jc_elHF7U|LV#T~u<6*a1dhsS$9J%RL~I)D*9E1Pd*fF66a9(Jt~{AciTi9WhwlvwYm0_s%efF~cE20M8a zM~Tromdbze8rNqEpQS<6gr+K!I2n`B0az*>$YLj0d%j$^$lRLdZpDw%!_Eg^r?m+~ zilMfOs&_Ly`6QKqgf0x@V6H&*8S=?$w~K}C12hGN|Mt(T1(Mk86gYUu$he;~QJDvE zp5;Cc{kPQrkALv|*<@w3o;#DanZXZ}-ZMg1b=R+FLU9WhHBD1$q9zE0pGko8QVONf zv{k-6;^}u$!DWJyo)RpgUtL)U z#_EQ{wGpEWbXh!_nek|HUL?J>F03S+v)>!ZDBnD-fWdBq&~@;&oj5p%K%mQoD!iXp zO|G?bRrAgPUVeWp&CDz;XlI4qvi0U?(V(}9MJMI^+St0h`uZgUfEnF`+Zx$~6v{_`gc#(5cRKIi7B>@McfwvvcIciK_y zO($wswB3Q5G;#d%+u`cIbrCD0_$K zMQ{>GvV2qyH#tzFiXgET>wwuJKo&jZ1TSyE{)ov?7-xPrUzqH4o3C zgHM3?S4dPOg^gQ8r9W|dp!nEz(o;{*M*EStxmhiE{QiQ#GRXN7qVQ=%w?gH$XLS8? z@dddRD-hDY?d(4L34jlu8QU#-^*SFpY8Z$=u2I8n79Hu2+|8_AYY*T0$C-nYM-U&E z8jh0I7HDz_ZgcE`wp*w6X=QvQ9UXw%RH%c{(ssucL&CEh!!q7?AE=1-AUx`r^kwUq z72)=yF=k7DnYVV{J<&E8YTy*WvG7aC%_iR%rH$333{SuC$RP0accXav0YG1}5v5m( zW`*CKn@uwZYinVpgw_bMA}B|qYU!g4+KbU!yJU6Ze_Vw3^Ka8ymXdNYA_8aaEZ7S? z1$;@7J(Qh(0kCgi&T7-x?G>1sk?2`+d}vidwzqI+wt2{=Q(xk-m7&(eVB_tU46X-% z!pZc^mX$})EKP_Pzs#y)W}zHwS-Le>oshHk+4zJ{bo`I0di98pvCARu>L>5_CKpZG zfBbSx5N$cHvdb~N{mJkqj)pvBZd8Q6#rZ~v;H6SA%T&nlR&%=!{?$o8Y-1c%`3n2K z6=qX`DufxMe>O5~(nQMq;W)Kb0Nd3U4%@(@km@r@1=>1`i#^<&?f=7D$##`4QSX-B zxAc2%zL)V(Rswtud8DesGg@vr=I+{}Z<_m`EC9oqD{Wx`E#f%nIBlkw26WYr^1tT$6CUHh1l2o2U!f8M6%9JG@!hTh^U|!}gCq z^3IgAUG5sju0m*^@Kz-wpK4Z3%#fd#$sBgcup&m-?T3~s5)z?DWldvaT1CGR4K1Vq z1BNdg#Rq{Rfe$y4BesH+bH1}GT2q4F<|+GT*lejCz9&DP2H%K?yljCd=2(c|PoGYD zv_1UY2wG~6JvRZ;c6FbyO&q9moXD7YVnRF&G6|DZ-iM;>eE|T}&?!hgzfP zjTPgW8Wu zl?4N>I8Od|!ivbsg;5Nj*(dLzN-fr1o{~zO*&;|$1kByCHeJOb88l9bsVd%IBe_V0~z zt@}W~ylv_2nn}ay3{49IAd!-(5!iw zO^59`ivS`Qs*;1t#8uDjKG`Rb!t+OZdco*+T3<`kqNmM@?X6G&;gOa6Q8b-p^l8x} z-6qs*trYyZ9C2ue6bac$)VUU}ZAsZu3>e%r^HNTHP2DV58u-94s|5TgG`>>pVoDtO zeoRGGbfZ=#QOF-|w!Q)^`SiXWVpUXZG}E60ZS@^Hm+){imd24a+YYcXD}FR*d*I2> zm8%v)W&Hv6$q||!7M4ie;)9oF7~sj3+dQz~|GJP~hEPMYD~zN-pznC8AFE?F$OnGr z9N8`;e`H&bsdwrSO;dYhYKo1ao%~iZcCA(10p*>AR;+v5UXX~&S8fhu04hn;Pz&x{VXp9MO@u1D*s6nK;cSy@RvMOuQSqfrl4#s=0y zFW+LuGu4A)8GBFw5%ehKaWwKezT_#4oC{BPR|hv0_c`OVD=%*G^3^|v&1E-Db^&KS zzByzf!E+9wmQu7|FWXn0rLP^H;bV16v3Id_AvZ4vdE@N^hRh8E@eyJl+V#{l<6sdg z@c8dz*J+1TJMZ&Xndi0bd)J>=zx%qLa{4Tv-{?+hye<53cCiaDx8W3j>PvU} z9Q2#F&UD#_PNwtN04Z*|#GPn}zXk;A;F0@0XG*|jwAesWS(?lr<;F)hgkQy(za)mu zxOuv@nKGf@{`9!|+$UlY>h}EgzH#2GZNu~=OO>Sr*$J8$uUi`G5nD^pAPacLyN`mXtdp-l@|mu+7tK?*#kxNLBPh}@a|*T zRW`r3T)lA&h6YH?a+tAzrlplWg+3?E#8qC^L?Shk%hPPT4SMBZmDakfqPU$OKrgpF zF2^MjU7vPT&L?lCiu^waR2}fs(F$F%$KdN3Q)<#wM3L9Z>UlcE$h|(q@uygp@S)i-C8i0@3H7pgupk{*9w3D?&5=;HYINdD22f+DCEKpFzlp;7 z7+Jz7EWqNa{KX}SL6Km`W#2?VuTW3D)QT00p%3#DNtjRjPm}G$yQ~ghTy0!C!nTCq z#Xc;t&Bdd6)BD@5LK*pz=Pl?eGT(jE+;vUj|0u^_F8VUFc(`w9)G8Un?lgWAQEQxEqTn^+L3N7 zB7!9PV`>}t4Yns^Qp2~gr6tQaE>!0mQ2|V(gW}G`56q1TmAv`K!BU~-K z9y!7;fqp>_K77z|`@(99Pnuc~kpnJGP@H?)k|4r%*{9<4N+k5zfmS+Bk-M1e*ro)J z*5G<#BlIqJ&-LMaKJ>h)%2{NyMpE(+0Nn=$~=g+6SxT~6)wOcoHu5<%kE z@(^a*QwVYAX6LqC%7}021pH~xT{M2%b$N^5Mk2ddm7;BC=GAVx5^LbcjLQu>haJ}tBSw^~+!l+x@v8ZtAUC}^Enpsc zR2C8s7|@7{<J)XVH^S{#lmD&k7*(Ls~w4Iwe~Za#PH+hCH7y% zk(j0ESY~i$nR+Ya?m+*KGS6?lYh{}MZg57aEl|C>{(txTr`0jjemJ9>0|AJ8QNR6& zMNo+L&p#zk0^z0tBIYWK4od<80%&dzMbLc&N|oK;Zz`u_I382Ao|Cbyt4dC_wX3aj z&9NoVj>3V2urb)(@#)`@>de>_u+x_72$YJHLL8m@O zo*$1WH62mD7cRxxZsU(#AYGzCsE)k&aVQ4i${s`X9B!;Rr`p2oAL!Y5AV72hkEh82 zs{e#r)~fJAZ+otqrjF(dj!xHi>VF*bgz5iq>+fqDEo^N*g3&!#-CIi2!fx|fm6R_) zXEWSn&T)dhsR7I?O;6Et8)PyPV9KETqt(!>7w-?uR97(0Q}MO^ShJ}auh>7EwjXV6 z6rh>g+uQB!nSd!D1>C>Kd+Uhph7V2v$5W%wC*Gey&&PfO7QEm9A@BZnaq<+l61B(1 zBDx~#PhFRhMUSh6lE^E!mA9)i2Q>t^c-v+k=$>KguDLxz`% z6CUG8neL3tjF3BKoi`AvD!1{TGs_aP+a^wImHjq5KM#S^iS_Xp30Od9QP=M8YR*_QMFao8E67T#vK_JtYEmmZ7G56+}##OFq zkq^z)Y0dkIBL%{u7&(;jtb;ka3;HE}S*}4D0sC8Tewh}=s7258W zwlLl6?-##GMlgwW`su&YEG^SjgZf^Rc6&hQmJAxX3lWvKf<)D_{o(H&X!0Ap?X-`z zk)VN>Ti+#u_?8zsiP84WeN@+v%P<)gu~VTP8GRXT;gP9oQ(vd{J}f%@`AfSzAAD$X z*YvzSb9nRP;_L|Vsb^}!LRy@rF$Y8-?BhgXY(96HM~)yhe-+W*5GOCE9iEgYtp$ndPNNxTfK=_sI@6NaVNH9^8xIr0 z&pwt$T1``Qv!c46bz6nQ0+9j29`zk*6dJ>|b487K;$Eb_TrDWO6UY9^)RECO`Cu z7du3y^ero)X6s4>%a^LaO!4Y>@s@-{AFh710u!ICXk=;j?#5f$cR+2={WD~8q1DSN z+@yhQQ;0oAS{`{BX-8%F4{8y3I7ezxbg^4=tZKeQxgi9@Zs9$)j^g*XlIQ;)Rc{p#SD- zr1@+gX5ag`kZ0N%Ns!aMpm{i!*xzfhPXNr4+mbT&k$0B@RdQr71UOeKS;zGTV9`h!s#)50E5_Oh&&BZeRAdeR{x(*Cc$X@jucQevXRwzrNLe zTl;rj^LDZEzHcr_ z`z#SHoVb}jm@A{sj zq{s+e9a>SOTUq!EF{O06?bjB@^c8VqS|CN{`|4@<&YyC~xq^BJw7`~%{0&`V=VM20 zSShNmZhUA7xVfG0lZ6M|+|suR=7;Dkh3=F#I;9Dl;mOlISqME06b>27R2tY6xXf_c z{H;f~#VGKmDyet{ySUZ6h)M=&fY86N>?Z(C_%e4Emdvsw_K1e;+Kw;le(zcYgWahp zO?~YlLry9d(#2CsN#N(pp-S5nJd0S0{K}qXtxt3#WFZK`S1s)qzGs_d@n^nwF(2sw z+|uwdB{jmo*x-FTWa?#ooB{-Vlvg~K6^BhY%i;2gj+Z@ni9XNb0-31JRqztQzkX=Y zv9Tue1&-zmswa~7VT*^hCL%8iAhIIjy%v3vcj%D${GGs-n1sGILG~>XDh1XJXA``i zQ>B^4q|+@Xv0p60#_jP)}MKb&PCYKG>^$z zuJ0EwK>yR3*^l$tND1iQGUO;AZH03sz-Ul+>&KsOwRJucI&aiiv|MW?>f5XJ4K0O1 zMCSvNKgKtL*Z)&PKB`G>eS69baw_gd{fXIMgfoBi$+n1YtSJ{-R_3ocODgLJnW;KV z^|1*TYBuVY$G{9VHg@(tJTVkj83V0Rg`dLvE|si<*`rwqBca+{5h7NzM(aj3y-yAe zzahU#VqD2z77C{(=H|kxmxxF%I)sVYV5q#znAmq*fl*Uf{oQ|d!wVS{e{9j_xlY?JLN~yyO<%_sW35z$T>Fqn(p4#j)acMk)b5L3V|Zt zK*2?mmYn@p;jjP3J#U1COW=2wEXNgdmV9U$>{W%{{yt^~m!&$k-O;3Myg&h7 z$#w_oFXN7H>$jGqf=x~LiI%wp`ab6Wu21%~4GC6xydI=(N#9MLiY_`I*7ZQ!wLC`& zx}SiOI(-!7wWAy>dWabdPfy6Ya)5GKs!_|Tlpcm6>W13f(`FmcetmZVV!aMDWASxT zgUxJ1Jv^FJuZdu3I<=!4^mwvf#EAT_&aW;yQ{dk@%euG-z8ODCznQUb7*seCah3uU z`?s4<3G(PBDX>M5H_w{xGfjRsxtC3H$exk$k{qCyU3)IKwa^Z1~B|S~S#0pBf(@ayi4TgZ_9F=&p zmpWRotw+|v-zZsbQwBy?uazLDk>Ib4XSE$T@bFy}H-cZ*UKZzK@%!>4iy&c}RshnU zqPRta0E&~v=qUD35r-ZQqSP{(^P3y>Ovg5FUw=zKKWvEP%6Q5EUCgb^p~hIW%Fo0- zMTMVr#?4L3IxZOGwRnF;;mDWPZy_K{KD=s2tyEnAI+@DmA&V=ONN7|#00Sv#Ykyf; zk;=6m2OX}_yqdcfDKiL99>@6YZkF!XYsQGb* zLLeSEa)JB!_SWV7b?M2&z|o^OY`sBlHo&!D3)EKgoXbp zLPzcFDkeRtj2s=FTwS>wH37l6?N<-}tPB=PU(c|rv4c5kZII&M)!Bp%U1xYi45DLL zT2~;6Y|isPl$?`fkyi-y7DR(wwdX1a#g#SsLml|klNcYT4}}Yd8fLKH`qkh>uoP4?C}4SIX+s}fxQG#nMGTX6*^4nz8>Dy!9no{9^dLEEq%))LC&$qI1}t7N;(g0wS%d}}qJf4w~#R~DK^h0A@I zRKNKAeWkw=nYrT*m5BD*OB3yQYI!{@#$cx1Z-*FwAqgm+0cV_LuXr6)=>Z~lvia|6 zuJ>;j9LdS3Ve@POo29&dukl7+?S9l{4u0n|{09@7MtNf!kGGyC_WV~Hk2Vhx!gq&f z_YR7A{VL0-NlTu|aCBxmIEpZmKNiWL;tkt3hxQc-lyUq@k*x^grY*FSz`wf$=bEj) znNS{$((D|0`f-tLIPTY%_k0=FUIk+{!w!JOvPJ&rNMVTaGvlaZPB-e2$^N9_ zv}pfP7&0q*_J?qzSQZJ|YO45dyJ!tQ;$Hbj%-1nB@uRAG?xV)W_rZIdKN1X>Vz?|DbL!9a+cbm)jaGtBCH#;=+M|3%gRMDnMs;bg&I+ z3&k*KW=Rv2x;ebARlL|O3S3&cQ&yH6o5r63O{h^N8AZ8kET>bf%+xqSF(cP@& ze(2F(e}8LnwNMK1;S(w%**DfUg`K@=0>_3Or&o=QEDf`Zl`Gf;VYkDvSIglx;8&WV zELx8Fs;Q|Hhq;OQX;*=YL`@CaG!>ZpirvN+f2d@6)Bf-c_+lW{<{M0+SX?z zeJxE$Bl%p{a5)jmx4BOMTnQSape04DP(?o$FVW2C3$H@5a&CGll9opSf1Cr#MZP0JgJjoJKSWWyJ{?)CWFp*q9K!@ zs|~Wy<|j?#q5$=$fSE(>x&HrM4*pXUgw=g)hgM8nM-rNSUeUWy*F)$Q8{39y)NIJaNo24`cPm+oo>zb8K z83*W73i`o@L};A)wtLzF3>o++4O4%L3+*2^Dng9bGE&*_wYY`d_cF<-AY9oO3axP= zUPlfNsRkt|-NU)8y+`bS5H`_>=*XDyij#Y_0Eyt>zgeL^B7&Bkbd;qg_=3r1jzFip z3tCJtnBV1v2Gn;YM9lv?5`R@NG-1XN9IIsh0)lXG? zg!0mXU3|V6e1zOj-d{ZaUS=;OeYug|5~|qtWVBgW%MI8a-+E2!czt4@@P8Qhxv(?j z3%Jf+;Xi1KzbAE5balVz8S{xi`%(O;_EqfiNZHVA|KLsLB9}x08=$gDX!Q6LGtqvv zJ4o`rJD5xS+Edc_KImu^n!RE83^7tXyV(x7HuHUM*PD?#h#qnar-$q9wqgn0%pcLy zG(eC~!#)NqC-Xk=IqH76&7Hwcn$uIu16^S@Q;nBBh|f3oAx%~60LS*L^?;|u5|GsI zr4^sYp2rRj8>P_UlvbTD^aI~DirfwA)0JqFBgJ);`A>9l9 z?}Vgphw84p`p6UOEzUgI<1uwSo=)%L69U9k9dA!3X-tN#PFwn1nk&^6ADVq6eroZ| zk`oJA!K^#bMq(d_S`J~i+@?LoUgZqoFFq5-kdY(JC?PvwF4-*8VCBxuixWKz{l#aW z`okojB-k94*iw6WZEff(hZxIP;(eN+jGuik)jpCnV7rb1%ncrz9W@}d&ul#TIkk-y zAF!dG2GrxvNB=5S1Y@gDze!R16O0q%A@sXZ-hL;$F|1~RuupVk`9$<{0^;aep3_$; zXCGsFcX;@+uW)(?$H@c5`$HQLXXw12>3kOXct|cDg>rY#I!lnsm@ib;490<{bn} zDP%2WO!0No;4z7ER=Z%Sw7K)*vx8%U(UV}mBH2KcLIX?p?as}`>JAA&)CMSY#Wpk1L!vgdvh%Rz~b=fBBv-WMIM28Qp zS?#Yp?A~;Yha~#eWaGl3WR})Y9D)EPOO+*11@;SYA=7=9h}2i?1`*|ojJ02Bt8W~q z4xVPF4hO&edHKHvmGO14T%qB78uQsy@ZLH(W58>PKW)O_r_od}<97=QDGt$>Nd=S7d6zYS%}zs9J9G_V{PTHxLzkl7>&&` zVZ9(`1~yw(Cs;7xC9;4sdcBTfp!)ijjz=nNUazGjj4eaSS~`}5`7TIl*fV{Uk`Y7c z%o?6ww5#QTRGrL&JuV_Ng^`mpS0?3T1f0EmbGS;(U9We`XGxw<^N-vlIjF#1LWtEg zxl#}+vXn-icu5z+8h}of*I0xr6oJeQacYXQ^Y&)}%O7GYF^Xa6Y!SQxBSA7J&qq(U zWf4y&cRyD%aqe(jXrqlapDWsNVIBffMdAF(gU;9C@vv-=W9JvuoPb?Zca9H2qPCPu z=Aj48ud-SWTJY+ys4D5R$*TXmAb?`JyyL1$J8}9x;4TT|zt8hBd>zuO8=g;8-1!RG zDw@c8mosTv?_5F5_@uTn8`Avyx7GqDj6ua{U;=)$2u^`dq@*2A+`lDBhgw*6PEB?? z1n6-00pnm+yNBD}2L)nO8s%PKVS}vdI#xz3ZP4`O{%Md3J&{NyT+FM_j z6;{0`5C7XTXq_iJKKJoOH;u&SV7v+#J%Y=;%HQnc)g~x({8qE^{u(d*I%>53i~+jv z^u5mZ(PkFZ_{gJLZS{LTe`{Y`TN}HLYyJ9N49zpdR&Io07xNpM2fJn*E5iYCY3HoB zSqyk7F%7pXlpUMfbzJ|aWhPJk=H_%r*VB1ji}Me<>8t&)JzRYF=7U(8|C=e{r*F-ks#4Pwjk=-$Us3@8$x!N$c6diTUCqdgYlwj`LRkuQYIzk3^#MM z^Uuek_yu+jvYa9)Uo=1CQT<$*>Z2mxWmHs=BHvFY#rm7nT9yGV)(7`R1%sZ~LP4)$ z$hbNIeG^rZ!(=!7PgD%J9$~XuilTB`O0DaQL>5PUy{^Ce4>4F1a&8xRzA&}!unIo$ zNH(ZxjV-BhbDon(NUuxtw@z(UY%4tsSftZ!*(eb^n?RV>x+blsrqVBQ{{Lr&(b7Gd zm|ZUr(%bCYg#%e``SzR+KBcc#!gs(Z!QM;Gj9Omnf$l6nENeWypVu!v*_4N{(F5^A zM86cG9J^ThaC|_5U%9!Y+%@MlIduuyoQ=eSR<1Z!9ck2z&`#r;I#}R}SGRci<8H`U z3S!+Rtl9MN*0RwCta%dJ^YwMUISy*7bycr7w*D zQ-kz)*Bc~&=K84M35Yp~oDym?U}|gixP8gwUoa&esd6U52{CEsDp!-c=8bf^>=|Dl2coY+ zK++}IQjDJvJdFFoW!7w`#t{3$Ux~OIdx^e?6rN_Kn>HxNX%0SDXKn; zy88R$_-X|<7y;KJloISE2c$2-Xkf>Hiw(OT(lUl7K^d9qhX$0z88)*vx3=)&;SlUi9~zBPV`D#>ZT z8|@$K_WI>tIambF!o^{5?F|#}_!}|_uNQ|3GW)60H|vgS znaaMd^}~a$t^ygT_qOr+d4vMhRND}>w$91nsK;Q;n)e2unj(*Gs7h%$XkLMnS`jN8 z@3)8Bh5?arlNM0DElKP!rp3Lkx!i+6h)R4QF#^=CgJkB-{Q$lK~sxbq9^1HG8@RtpIVXI-qaRW3P zZQ?4Ffs!i^#y5N@J39xP>ha>^$?{k~L4NqBKsDIF5VbVD6`Wx)84fTv9GE-h*xPJV8T&t@oEkH76-umxM0i|S%FRf zkRwT$|El^%7>X~3snv;8d1F~9tZJY?b*TMcqjXSz@31Z?lq1ALU^zT{H-9+&IEL4IcQ;U5ZHgb^P8@?LMmJKBJ5Ry4^Gvq0 z=5t+|%P{&`XqUb#Cuz>?w@bAA6=FGed{!4G^zUZ+)O2?cR-#T%Wd*8=X{)$`_IyV9 zDctSNbc>PD!fV&i?(oW>cry$^@b?RxplbxYOMJICJG)9@AyuV6sydnu{sXZf*Eyzl zR!u>lzV+)%KUuoLX?eG1cE-eYOC4NtXWhECt@COmu>?AX(H;rQSoY%>^PBFb8w(Nz z?p)u1*L6ru+a2Ax!1MY|Qc8#Tb>!2^iT2m5!KcA>9oRnrOeFEG$WX3)&OBJ8JPFl8 zGdC32Ky-X#nYRlB1hG%#2=CqG_gUq*T&fO~=wF|s7&n-zBCq2GfiXZsAvcJOV*SJT z2|Vb2uxY&=aWf*|;W?wf?MxTy51{o&QH!tjz1!-`yrbVyM8IMF!-()r9P|5CZ`Zk- zeQ0aO_A>T6b#=!R*ZE9oBj}SP-Pn$Geay%BWZhHxSvS_Uc83%BgU_cwQre` zdV8AL*VZ>dSm}7NPfpYbSz>p$a07N};}^JN7jYuA;o{#8lOC$lE)>)txpxzc<6rV6 z>2f?>{$~ zGVxAf8Uz8e%1il}=;)2(7I*7^J|7abM8<&Cv@l6Dmdk>X`2O~7{`q*8fBAuoMhbzv zb&rhz_fMgXO63f%c5`9&L|o=Bqqgf;Y=!ea)pDpS9_x=}pt2LUcLx{hv-B?g;)2qF zv4^(~Z^FC}2ntu6*V{=Tx48Ih_$wv`d}Yn&g(f(K1Ts`^MeM&n%XpzI`p**)=Td@- zhgNE`?M{<%K_q9}81gLgHpBoN7ZJs%;7~FK+22hV5w;e&3eeF73aJ?$Lpowt*l?me4p~Orx3fh{e+(3GX9{nY z;~>)aI5A!eOe&G3$CkqPvrdI#EsM*Bgw=yDKPPsx%ODtGc$-i_n<}K320Fpshc#Jm zJI^D#y&sC5LpA3U;rkW?$(L0_GNlXi|pH@4UGh=x?uHkNPdG zi-x&Basv*0{Ho0okt<66M{E7)QO2Fu-c5+1wN}JgIn=Fa|q)NP~QI zH51wE;scU;#CDtQJ5r(U0jU=w=xT+5iBJKm{F&sd8+l66J3;00@y5c8(4K zy0wr9y6XrU`t43v6$twIy0OH?sn%N=2Hbn_pZy9XLtTLDoyx1O;5PDm7FQPbc>Qg= zu_iRv8yrZG*bTcb@_cy^GZO!o*}f(YEgrw$w9)A-oQq(XfK^}J@?#1t0#4DKa0Efo z;iX1=`mPuX^ACCE?Diw_<*P7hOWwtAwV++0Gv9r9Bhm@ye~V#p%CAMV9j`?JtXPlB z+8eP}6Gm$gU+WU=@D($(Y~}*&-;3+KP417F`n0aLm;qbAuh5Jj>S0qr%}}J6S?IId zL6YZ}6g25C0IP#JW4A@3*Yk@`m+^8P8+d5>eI(@s^cs7krLsLh>tz3Ysi6^}gQH_Q z2ry}i2y`}GZdI8QUHWqtTg(lbCLzHaLESz1y@h{xCI_G<4t zHod!qSLMu@ppg&|m3z3!>W3WW=%~JAD0MS^{f9TA-um3R;G%;U44;KJn4i7O0y4a2 zT>ZLQ-r}9st1oD&?8E+z1!4&=fDu)`S2~GV=vXc{TBh#$sgy37Of)o_iK+@&J-ete zv$flJ*zBvGG+<8=vBI>p!s^_S&j9B6$?A0?OX!u!nrttFQ;9P4bmI=qCZZH++OPNC0U3v%WFyD|`thC-So!tDZJnQCr>dZxj4 z5bwoxv>zi0nXFb^rpA8wOUoR@g3oRA)&K%v!?Zme^P>s+qUQ6rti?%%s7xD+53|h| z9h9IhnY(>>o=)xUUvoWysnY5a~ufuf=(XCf; zw~4jpFwv3G1%KPy>S;(_0tP08pcp4ONngU~ld8zFWQ_z({g2ACmrNe<*5QR$SB)*p z=(y1+@<#s^bl67Kt2g-stoB&KG} z5A4U6aa1yQa)D;A*L4&?-{Zl+2%_c@aAyo!#Sr@|lOKmXvk;zT0WTg8+dEporz+~L5g=A-Ps{{a+2O_EC{W2lkKt$RJk`2-?*dirfs zhfl5P2bTbh}^FIyet}3-ZA-VY4j4b!q z(ffRlFtbDJ6EANzw1{d1r(Hx9EmQ8hbmuEUG_R7aeOwl&iHk1*t|YY$Fn?+B>&nRq zA=(|B0)}K9PX5=rTzL`RL$_H@G&PK4Xn;znsToUj{_(bILaB9rdDHpo^LPcbkjvh2 zOMClwY;MQ3Ht#(f9gR^GZg(@(Q7;}=qeT*G^m;ItB8(Z3{oc184$kG$N$2O8$@S}; z^}a*S>$c1;1N8lF1>!T!4*BQe8rU0_wFxzja{SjGSz zK=nJaQVrUM>z`-|eOU?~l^z}_Qnrkp8|V>?UXDHtrC-<^!{%{9Y;WzYq%QY-F_!D; zZEycwLmayZU15%cH?IXMjWYKU1F9IzC1a{$ih)D3yf|>V_3)PM^!C!yCk>QCrx^}q zbKwSY!`F7G%c9rTCOA3K{lz!U#{5o&hB$nF_tXw4X)-iGVgB9%?17buOkDg)qh`J_ zNu;oCcP8L&V6&WzvuXT0VM|vBTO3$D{5SN~lcKAEmYeix5>8QC5&@y?Qg$JSNEyP< zJc!qG{+Jl5@!6`G3xR^_GXle`dz7eo7Om{2M76`|F6u}86P2Y2WR^EbwtnW~JdbFG zotCSy+#E+s6R4(6p~YYa=Z-Ha?9 zf$+)x6D?Od;{Srcn1egGr&Go!aB~9^{B8984u}GeNn^DpCjKjvcBZylILM}qt~4IC z{sQg{{jpuD z>Dr{&;g(a%1kN}|R3kY)u_XaBxHOTFXg*W%e0M#>r><~HyCSykTdG&@`Dk)Q+-gW@ zs-343muOpVh(4-BPD6n=-V&R0!jrBkf&$TZ6D|0=LA(_r<2)7PR(b5&e(N#m3=@3=C=jeYF- zC9wOAc@mD0TMKQU1Kh|0?31`!&#%4<+nj)GwJHO|+WK9M_@}+w&mVHeC^y8RM;noJ;4=KXAfioig;VRSfq$n~`Efu-;kE)#=kYzRfLbnnz$g|^T;%to%pO7TbRX#LU4 z`$I~A+MpN)t&x8NhTj7?BDdAU+7)EUQ|WQfRAYn^vgqr32CY5U`M$IE3fhpNCw5t6 zh{j&_BT9CCoJ^W{tHSrcZCP0UL{l<@dgt^0vNm+thHzV$t5biwea21tt3TxF$x|f^ z&lF>_@p?k=>0cKF-r3}PatNPYP8($teBo5DPv!;5>4e(z=#KIQsz)sCkMmzGKG$)* z?`Q8X4UnXrZ;or8FUz-6PB#;sPtOZALRaAU0B;aTI!O+lC!HE1%z$#8G^1`p^5X+o z8RcoIt(-xUU)TDZX6mR0#@Mr>u|Nv~X9A(n%Ye;>hLDqr$z*nY0tvSM7lw+m@|Itf z4icjj3<#J+skRmweD!D)pyK6jbvd%=kM%8xDH@t=Kh6$`dyE2H4*oGCrgWVea+Qxo zq*1kSrn}6CE1pmh|5^Att=hpp;?a)vqc?iCfB4zPYLYBuUC@Q z4CTJJ*|1kU+ts3*_x)qN6T-19YMi4094j~@F#2PlD#Jj9fClGm-+s!W7vZF7f`Nff z|FY|(rQx#oJ8ndqi*Igd$kb)_)b1j5D>!U(RN`7vm%)uq`Tin{%ax-wPe+ge{+0y? zGM2|wVJcGDSDq^BDA>RNE2nfVNhqf3BH(yzQ1!`~O3V2%lE2^v3_6gqOGtus%ZQZH?k;ak z=$;z6ce4QR>TF%uO;GRttIvH-e*co2>xg;YY00g9_e=cWwC1lP%~kc&Gj)E8O%y}V z&Qgi`mT{tQzDzeLtuul|}W~Q}~?)xJy z76U#o;6Gy@&|UE{>c_s&KQAorN-OMlKspkIcSd#DCSVT6wFnTa6y-t5R5&&vo{zq_ z?4;X9UiD2T-CT;Wshpu9OY5@t$Oj}(ahxZ7nOQ`x7hF=`FSKzqZ(W;)rvy+<2?Pa7 z`m^@!158-EKkqwTmo?tE_Q&1bZoN36T|-q1Z`do)+D<}xyD5swb+Ux5H`bP6omFup zC>VODO3Q85<~v_O{{F1CG&4tzuTPE+g0E96+#fmW`%PR6@VDL%|JWB6B5v>I@2Yd= z_XOB#K1cj6_h`&`f7y86^=wTyDM$xJPc0k&@cR5`txdky1NzTxZ<_S&@}aS>i?_hz zvAK|r!Z2-2g?}|bNjLP@p1D!DE8~i}E`scwz~dpMrcQ@X^ZVj@*jje>Pw8w@ESb5^ zr>dHbHQ^kyjzuOst7VV(x2am9)pj3{qhngwgi9K8`@^x>!pDR3R;Lq_l5VVQymw6a zE~mn{ejX@_cVSP9j9fCqpHkoT`( zR-;Ye6~bI#g=pj_MER9pj}&7#zrkf(XGea-cA<55t@=9!df^M{2rc19f14;>!be2; z`RA;Er=Oz1uNa~za625TOmpBx!NUMIG7376v3v7$f3x~z-*wG^@Z+oJ3MWNq zV$V*rYGpcO@90RsPgGhhW&ppA0m>d*X~d6>&+Pa0=5V}?6Dutn=2%APZ%x&t{{l;1 zBuTe8$7dggUv0xEy4)B-2qhYdjS`*+S_U7GetB&82`h#fyn9iOC%{XOHB=Xo-DC-V z;?!OEMTU^5hi0Wenwis{vLQ_lvzWEIX1u+f?b@WPq<_SmbtjnvT{~*8iI@GT570`i z{x3-qP}JTK;M8f)2R!~cfDY%*ON465FwB-J=@uxPN`pZqGvR3Dfo>fI9uA<Yl*v!^@S!OW;zJYqN!zPWvk^?v2JJhzs6bgJf2s#gRV?rK|+O|fqaznp+iMP0Jkxj9a@1C;lpZn$M+ z_lMco1DK3-kHV?L` zEjT+BXy;Aoj@X2b3QE<#dV;v}nU1v`&q>!IOZt4bYQPvB)i10A%KGiTi%Nz7l8%3e z#ykvGllaNRQbt}|{k;3`s?6BE4MAmG2HuzZaU~=^RJgl!dJXB!9gjW85Xj0kP|NX> z)PE=bPyNY4wY|Lq^ej$^%<1kSa@YVvyUAZzCkH(Bb?PxJL>ux@-yMqyUTafY_Q2qK z)a37|4&b1_v77H`K8`qM@*deoueMd~l-sdjFShIPCWoERDI9^) zPdZ%QfdXCOpL_qs7%wu1znbDz(Gu3Kh^&k`d`~bBDyYn-PW-v3Q6}HNtx_4(pK(#e zzvnv;xoFEMe9EJfOu%J#6C!z48KI}c{cWc&DmIeuKlw-gC*D-6ig5_X#&F;3*tRLM zzK_n|mdytBDy%7t0cuqc5~GOmaXulE7o|oOpr=RWm6OAQ(o6bX&h;@*rE{NH8jr=K z?B#m0G-OK|U=VuA!N)d+B}Gg>RG)_vek~-MRCL-e84U%p@OM$`$|F%DNRl{e4<0?d zRTX4#@bjCwAdxqN@iEDQyPzp+Wjq2}z^qs8$Oxj5vJ#jHj9CiPi@s#1dzW_Wx|9%Y z?+@pb_fP~dA-ntJ+Y4P_NIF=rLT33_a%#mFTrv+$PIwHlgtztMQx&w6z4I?LP8c$Y zOO|x<^l~I|^4yMEXTI}X-?GPlT#!nwN}^P(*CzK2L!r?IMPW4~NT7tXdri;JMn#Gh z(*{RzB0tZ2Rm3W+8DQ392lWrlanNJRh>)>SguAP1v0regQLst-k4{th9aP~1uq6>T z6KVp?MDNnecvtf>m7y~qh0QPK+wi>~j&Fg}g1PJoloTvkUm%XNe+C{UOUH&|WvQYoLxZHuM zF5F}921nko0J9|&0Mh&cfn#v({x9X>$nj zR|RCq8jqyVe8P!A6L{OST77=HW^U7+ApHuz3it$w?KI4vyIiQKkLQ+OgplfOn=N+E zQ5xSbQE&`XBOny9P|fDmZ4;POZ;a&NimbDHe3_kN-aj-IkgN~)`0`~Kpn*PYgWV+q zrT;>DA8y=r%H2_#i~lrC)bhX*Q;gDe(4vI4S9&h^72@=Ds6!6NQYaC_LCOCao7A&E$1e*EfGdD0H}z<7J;c%XzRXA{n`}wC0&Ugn zO}XZ?Lwr+sh`%a!yCE|vC@M&le0YA`gLTQIKw`s14UwjlfwVRwF?6JQE*scU;J zg4A1tbYAW@tX)1ErMJ)hS>9k$a?DxJ+2S^QxhrC=jwkWGABRxk^$j%~kFPD97ZISH zbKu%x5RAf){_{vlwO;z>E!oBVh8uv~k6psw`Oop~bgf>G1I*Q0&U$9zBc%6o?D#f7 zDs=y%{PJMr_qf9Ra>FoAtx`T*PN~^C*vQ98Mde%auRvDS5qze7GZ#B~ ze#O*c|Jb1Ofs_$6Ih4!7sC<#E(XN&0aBf`Qf6nF4>{%OEN?Z1BpDv(4JpIvbTSRMP z88V=}PfH(KSN^?fvR}a~Lm8Y05SxT5#{AtrI%DJ=D^(2Yb{ z@8tUuTZ>ARUvK3Mzjd5$C^4&(nP8^M)8xR~q9@0qtqYG#udY+K)s-lJU5D}sP#x+T zgBS{pfe0`)O^7T?e%|17;Uf2$CNj8Ag&kTY=Pdd`1`9Y}Z?qReAI%I3>SQ2;3w=B?%jgV{wDMtayR{r!lp-kSN%B zFTdrFeWtqc=1qCwxru__BR2{Woh+q? zvsogz&kK%5Qq1;bl>%noPZf_qs@n?Y!U`EVuRtwpm&U^RPHkgo&e#v&|uHbK~vHHqbf@4V9jF=};szUpr;C~X|*EiWG~ z$Gd??!V`c}T&tC-4vNwAI=Yh7Bj-TqvJ&~2R#u_Hu2pg%)jnIhnt<$>7Hd1 z)zo}boDhC-5jSs-r@b0MBUqFti`f3LXG?_dqZt=%kIV6X`|Q_yr{|{*T`4O~7ai|@ zq<^RDr1##+1(|qpSkg0P04lD2-?J*MEF8qPPiI`tS>jPua^*4T8_HGMKub06<|d|U zoDaJ8+SI1|o3;1T(FU2YB2-ksB?+4IVXmqxAu|X2)8H|DlndJ+-)vJL4*YN( z2e&%betNKOO>8}*f6OB$K2)^q0@x(IRvN$^XP_}46aTeAlRsBo8+tsGe!Fr%i; z{JOX?C2jAxZE86#EG^Z(1yIWkG2lja&9i!Hk1gG2iQtL|xDryvU?Ju!Mv3eykXhgc zW@`*7rd`u)Ohy-!me=`ALpL^_?0yLcXEtQU|EJN&?leBic)j6&I8tiAHSHzcEYetgjt^l7E;9ua0I%nE-iI~AnV|0@0~R2-H?gp4DC zj7?W}L@#upby$)op_4i?G=;Jn5R5cgpiv2{M&`0G{TG%}q-%{37Dj=Z#dz5Fh{j9z z;$nFZjxHS`T$Y{`lBl#lBKbVdKM0ysfVWmHsO)vhVS*8y{W3Y&_cq`T5$N!-2+%1> z>h1klca$lY>>Vw=jSNCt+`KStyKj^YFMI%A|2_af0hjuAWQg9**7}UwCG+&jNWblUV{zWaso9R{>>Ld`6;Rve+PIt3Qjx^xFK z;>MPRZ4_{}Zhkp-qHI+40_7^q(*h6p{&omYVqA~YP`!^D7o_VF$T6F9y50>Hc)#Jf zsA=T&y5}E6liz*Szu;iAlEsu(@3S{_etF{9;jwo$x8?MAmqX~2v)t9oH>1wxfUW5w zc~0&U=lRfO1LwVoybUj0#8tn zIxUq?Y9l{%9!m?%E}Ta*7_)f}o2r?zO5946YJo=u9&HyDIZ~YN*1Ev(zcz zf5IQ(g40-ytEB+-%bY?1fLQSrj8UHfDWg^_mQ`P&ippB6LE@45uB*;zA%$WB3V6Bu zRzD}_L9@c7?ux@^qFhE(u!{~AgMg))pa8O~SJeeMf9BBO=4XqNveTxZ{cyDomiUlFHbz z#3p|=%<+ER+n11$wYF!&0>Wp~!eP{Z;Bz;3#jcKJKuc}^2=dTMl;YV8e1vji;IK*# z5e7wguL5J?n2EyAg{4L%+j5%9HRpY)V}?Jdhkj_{3OywpTEF0s=!0U%x9u24n9u8!~9ZSlQVO6Z*D^p5*)$7Q#Q1ol9KJvu$TZT z^gM~~z(7hx7h&{@gz3LK zL_2r+V#^HOU#D|7Nq85-e~*^)Jg~6A+x-7Ab(T?aMa#Bs+&yRr9wfMh;1b*=xD#mH z-66OKcL@YYXe7A1OXKd^c;jxb&$;i8_x9ht$Nsn0sG9ZFoHv;X0o$IPw{zW2$H^*z zZKQb)I4bsY`YbP$ep{5HPA}W3gH zEW|bDkXke8v7#272p)AS!~*m=I`UOvPpCzEX00GQvoXXydC4Y4T|u&%QL(mznmuVyY`M1R5Ml*ApJlcG!J10Q;&Qs8AnU` zz0auc!TbpZ7>6X?!PjYa}_}G!45fP?gs!SJ&7Ks>pT56VlIycFoS!xe=Ko zckB4oa3x$&_Sc;GYbxkrHG6ZWmCN2UDt*Tr3vuyKe`94%^7MJ^`y zE?!N1xmH`K@KsZaC6Q+Jh>5~|?X50r@hmLdy~4p5iIMtHqONiyI5D*XakZ}5IWZQ= z4|QtEf@0*KDUm*3h48%5#03x-uKrih_>Zereu=;mZqu6f)Gr+@4uKeYJk4D!*u*`t#Db!?`i{$<6m~f+8VulSQes4~Dz*`rDyc_gUXMEU9Qj*+7 zl-3p5TFuj`CFI&@WkpXMG0|2X(3f{3a!E%G`CV-DND)gkkN=^S)RTqNE#vjZEkHm_ zNweO1*NE4ZY7{!n0=PnneGm|kgQZ%OO7kfQ`PYzA8WpNI3^1)3 za%W2xeh(M>rdv)q=QDv#VeRN|)$9wx?Apy_48jimg~^0$60~m;OKM|Po39|?Ygl{h zM;NaK2xd&7j^9OHuRf9zR8!m*D7KQ>gyZ||D75{WFZ^8#d9931a z9&bPSpKKMfd|-?=v$Wjrj&NXs#Q5HwZ8W>4XLjB`kMb4sK_g@+T0FL7`1wLOuF28(3X&7%#)G z{T<*cgXX5j)_P$woW=&vhQ`sU&*^*f!R1zhJ1>+*b$(<$abMbW{O$+7=Qq`PK1@6C zR*va;S~gHj^4t%0z7D=E$0ei_pAI>Epgj96#~SbDCeui)NxR{-Q$e%&_&N@o6v127 z9sWXL5xwstm;J52?NaXrS7&Bw^I* zdi+Sr+^4I7DD;C(AFvZ|>^0rFfoY1@+^%>d+9f`y!Kh`(W+=0lSi>P4F4CDK9LSjn zupF&2KxWA@mng+wdsoy}(F2rtsF7}}I_L;gR7}JitqhM2ihVKbBGpurm0DUp>{{}u zAQ)UAQ0Lm2i}hWQ?p3Q=;2ut+qtW&>&k{vJ49PWq!lrZNMZ;KRIgVhdt6%Hv%%WJc z+wu6*pv6JL?@j-vkdpDHX}A?shWNP&gon0oBp>GOvGz%UDBa$2I$uQv$3ZvnU4$=g z$w^IUH34I!{^*$ak1Ti&0+(G&G_f*mKNl{-_`Vh)h0Sl*7kv?IkwbnRkK1pLTtN{c zUjp`4?nH2_n6PoM7xB%yiL30>LnI5POj?TxP3+|Rpu15+6^@^jG>;QJ1Z@9T`h;8fPaMIGw(_)!3SZj)lRd8x*c@|{?OJvd1f7AZdq@-f zBp9}Pk!>2rlbRoaID{AkIRayZcp+ReQ5j7L3j8^-HMnX1iu{yG-{kt?@m5z|67)+3 z%_BKnQO$tVp*a*T5xp7TS$^A-@d=|$3yP`YF4h|Cc&ApBQW7U;lPJsVjhSa@fT9}!+GDeE(3 zFnI|4o}!kgopnXYp5biGrsnB^qH}Zfw1MSSzgb5PD-nC!^Z51dn0mF>eRqHNg;_wL zCW06eOYotaQ7V$a*s~dS8`oexeydnW152T}L^{#Chyqs^iB({;7fa^4I(P| zFHehHa`(5L0n5f|A*~%(b5tK`LTyrm5&wvh;O`TPlS=4Vyw?_^wR#Mq5#SMuGDCjTrzHa^T zY@43xzclY?dYTJ#sMU4m`q1g^=N;Wm{xpfs7>qYUfxH*upK=nES29!NeRYr*LB)d2 z;TkJdwUB?JSZUZ=Qc|LY(t)41VtSKsIuflJ|gFhYxCTvY~pDk`Q5 zHqP#Rq;z+m$p|7X-g*L1sUx5H-d+OtoHSZrpsn`uF%Oq_o%h)dJ!gSCK*s1~y^vuc+!cpAdbyo}mejRF~KNX@*ZDASBZEuTy16z@5R5PYHnrRefd63SPlXDJ+Za z16zHpR~OBT1^b(-2XJq*ww$lO&xrsS3E-GJsTd>Dq=9tVuhg+>YG$&Va*qZKH`J40 zn9|c|DwG*sAPM!6&}I%kxOJ4-YSKbT5C|+pgfS3k!v1(`raqL}C+mTLWm)(iBME^NV9v+kPgVn!(y&DavVtFEuNl^kS zqe?~gL84Y?O;TKbXSlqlibd7eM>dvBgY9le=@MecHWvuA^Q`MIR_%iaiHCL2F!S=ap3xZ97t&-3#JP zyt)`VRVso2^wn;+$|3WMp*4G~$&nN)CS4k;@OV#Beuvvl2COY^^MGAEM$nq?*RDy3$a z4kf%Ijn{Z|;YD--9ZK@h*bQ}N0GBuVXV~V%)qOtJtD2qNQ^Teo9>;Q8+MSxLx%i-7 zZ@Y#WQ#=o5%{k+c!P1$XTJM=GXW8J0qN$}NYfX47Eq8Ky*H6E=f~;|L@1RD)CQv)1V)?+&QBK=-k&2 zX8{Ht12eg-hAelP+S+Ut>MJY|?z`lWnQYI5qgrm^Oow)l#zy&GCJ%@nys!xdzS`|S zZ6z(!(t;$zU!~w9WewVfWcf+wO@VhQt|%4Xf%Hti+VuKmkF}z;b9G>|j_2*S2NXb7 z$xAy-rdACrWX$(E3C_(uZEqj8;)$jHrb#NnVGF2Bl4x)bBLR6m91%8wmTx;>TyJdL zU0fcI^WWyWZ_mevPd1wuV8*fo6>BdTQo@1T7bt8{hlEdmAA7gzP#2q>+&u%IriZs) zc6xU-Fqp7C_?88-@r#3T%v9c zgG_PU@uKN@i@G=M1Q49=t`9tX8&z?hi1Rk5-x&4V)x7s%+kn*Oxy>bBEoA zf3=#NtQjSs$_|o2*3)$c^|F5#5)u*cW;gR1>Ccs)oqyo!EC!PlX5Wm^C>2fo>u&;}l?9NWP$81VqvL7L zUiG7kRWVNT%u!u~Ffnsc_H}-U7$DvsO9MzKa)eN3fqa@5CzTFeZ$RYX5@MubiS&OEJWmTBng`0a$ zS#!IxzJfaoj>c}>$=$80cp2y)5{Wj#Lh5Q)@~_P|zzBr;v-PQ^W=gz||7WK0C>+fQ zCo>9KFky?bWq@OP@xG@?32?dm=)ug}5{6M8zix;y(2c$~`T@K(DY(R-A5tW6oP8%(m}B}9T9P7Pbw?fa(h5ccsm6(*G| zrbU~}P4r(wzO{{we0B(f%wXpeb0@}TMK(&+nh@Z8ynQCu`DU>547^PgIjG4L*l+>G^>d#rcn`Dmfcss2o;!F@7MO#uR~C^F-nk_+Z&=o(=sB z>nUS_$w^N1>$b8w#yXaYA;a<<ED!R1+oZX9tA(Y3%BqNg0J_-`^KE z$}_nxC+N})7Z?}+2Bht@7<#wcq`N9+dme_4M*F;&E`4Q8WNGZnYUWO%Gq?QvF&%)? zK(ASzRlC!od-AP!el3Zf3d3o=TwVSzBf@GXzifcy7H}A|Lz-P;an+@Kl^jCic*Dv{ zG~*#eK}b#hftS70%~(H1_(U;$rPV*EVc=z6JpfVwY1T}K=M>LaQ>4?e0lPI@{U~6; zh!6e%Z3wh}9tYP7dipzZMd>Se@-=j8CBV_1ISw|=&o0}{kB?{VaJTv|lo?fviXXHh zK0!fu0G8|$ly~?Nm{e8`Gag2Z@qp$^D6C$1bpc<$Vd%XYOYg(~d-Sb!^Y*?}xce-y z@E>O5zxc*OM|xvTClg5Vfil-D_3+G)*-Tpn0tlu%HrO|eI=_mgboZlM^r_vaNej(k z4}oEUmJLT77aw#!rJL><;sZS=hUuXxycwjJ1DMkW=@t&TImkd7&k2R8a@X$uMa8&G z@o@=T@OTCZ4NFpbAp}?k9bjQWnqTxX=O9YS1fM)(S#+qVX?c^DXOWv{tqK#{I zvsCSoV8(E`BHy_MV3-d|!jn`|xj}L6R*x*awYi=4eLoS@jue*Ic;}#@XYgZEpZAYy z8$I5RYQj7L8^C_i$h@E4u}*$w4eEV(#@usKm3!yNn_WsGi{!Fqih)E0;ES#ohe>I= zixLPtnQ|NOiMSsC%lC!{EA6H;@N-M0X<|(;uA|+Y$fbMZ+IV=@0OSV97wNu&BQP%j zX&DbU=wAa0`VVRg{Y?bDU^hf9CsHkqqytejPH#a{C7 zCOC{ioYC-%)cz@WdSX5YSH)C>$s9p$mK|T@v9z%2q+I^|s#@r2&u-iyz=3uy7)<8M z=5)H~RL;6tCbD!JwfKEZHxs$I-+`3KIj*Yudwl0K>g>`sY373tep5jd>1UrphN*3`R_|DGvDq|O(3n-P78xN3R$tMWqVQ-ui+ zMJ1=oZOE%)lMzV}9A05*{9xmP(5+7kqz`Wmoh+y*{w#=~>aANR73<85m287+y)wTV zMiOLW1~jFoLL8>C06N0$<^e*f>}`Y@NTbOAWD6i5)^cM2I0gS^g6e?-h>55@-httN zvq7!dWe7lNNv3)hGw6C@EN5ub+zQe5=vh$&rB~P53ocfgGHa7H=r?t9cF$AMm(@=Q zYU-yo3;+7d^FCB!{uAIr?63LctFQl2!B&rHf1Q7?go#-u z7*c!qDU>P^|DAG$wTZ_MNo-v1Gjtx7W)K18hn$DPbn~ThMV+!5KI3_J+3JW3tEZmS zyhL;b>R*`CfBJE2uXxY_Hsbd3(yKlSVlzBtT8%zu>r1zPwBrkV7?DxJ#Iz|XKqX7h z_xJS3J7t}O1n(Ra89yX)k`|jtj8eO^Y#AY_{OX6h6Bx0*$ zLkczu10>&OVgVjc}*V27KLs?QxpihgVfkCk6naSxlM;3q|A2F zC0sL#%k9trTU## z(v*%lP;Zar3L`_I5)C+F#n1#adP8h55qRWL|5Lz#&fc&R8-&g09Gr&jxxAeG13^AmsYTV^013bMZdLCCDcoCvjTaD)XC)v9j5I<@i-%>eO+ex;6BS6jw zlD-1ZGnLNx1<{`(-oL&+Yq06)C^^HcL|op*_!l<12v%!ud`qIeA>b&21uPG)#lG9I!;%x zpPtP#?pGua;Zu^gp+-hGfz*70<50*P`8^EI@&^6-T(cWdGBskMo7$H$7CEHo+iO-g zgJ4>16`ufHE;(FsaX0Yc#|cyN@c2Dj5B>?Zw*{@PLwZA!m$s~Y+5a>i&C@F}p+x}D z6m8&%=@H{?qQsb*>4k+W^(!<^hm+6iFipLF!8Su^rw<)8){R-xKw&1{Qy|)+Svub6 z5~}UhG=_H7I~wmZ*p@r-W40n#}{t=7KWNTqwqgbOXm&N z&{nIlb-{3o^e_+o-g=ZlFb2y08_3qe{fW($V6|G})(XAn^+2A1cEwB6Qv*lleV*nJGrX(|F z2j%BZsUSV3qg|~5Q}-TmH^;cFvg=om<&cEN6Mp!S;TnEoZiOI+nnBiYR|4g zNGNX(q@^^t^SZQjSXK#gsVh@UwVKlUsKpDp;t%q5U2UJOY5M@QDtjobf{*@RJOH$U1TmiL5gNIoLkPqzIz^NwEhUji+$f@UkJ? z_-!HimOp|%iAM3KnlE9cOGMQ~lO|kwcLc~(t-K%2KbFCZ3x}QpXCKV;mE;4tZ>$j_ zBm?=HmL6{g6^{ewi@_(xpiuk7>#=J_R@KHy#A+yO6fIqssvpwb##;03_57E+phAth zNRlPN`*pNB2Yhhr7*($xHnIdNjnf@SyV87c4QkGnJJIjZ6ZVg8@`sYJiQocY8K9Cef&JWPowrzwXcw6WY~P#ptHq*CC}@*y0>VD{rRXW z{V9FJ>$rl?#phyvD>WvBnV8+6)!9G4x00Tk0`n=%*s`Fy0{nAbT2q*D0H`nPtFWT7#+P+|s0Q+~DN z9aER#@Mgf-rcv_If6RnVw)Qj*+ivG4)U(^OOm5fS+B%MV!&ZcT7J$MBX_;g~UPL7lw& zW~F*M^3A{>IO0(q7C1)FVQap!5wo|RMN{$JU8@egdZn7DDk;o#b)McWDrq!MLD}kd z?xu%FYa5y5;rL=Hn-hb44-^FscShcM<GW=C*LPvnZ^1s zvDEP2-1TPv#^oNXgk*gi{8ro{I7|65sGO|XCS!LjmU;Xx5O}3Kih!l&5=@`mWSdO( zgTSgyIB(R&S%6iAVQ(ld$$i|6*=%UbLX+1uB#D4r1_d1>3x;1x9)<%9Wp7N8)=6XCy>x% zp^djmD*biL_ABu>0&*6~ck^CM+{cA}OO%P(Bx^9p;P6CY2=QH!^5+qJu|dBH=|8Y+ zHdHbBqvJ>EddWTx;$g1jR#3>8LEo=j8AZn5zai3V@Y7)K3Fg{Hu0a&tk8)*-=9%m9 z%FUySPgF^J%`|C4-d!myGN`0kA9QHowFD!AoKYW8EhTF+Nl_IQ&G8HAc}LI4oI=i< zcbMN^9#Qw|=w}80;zIv!>`WEFh1D{#YWXjScV^w+_P?~3C@HNdPn3W(+jZt~j5?iM zTs+QR+s`^)*;EmV=G@RturZNCFrF5|i>BIGAi#)f6yW+Y;qPG^ejOI7Us?GAg%wPf z$X*DnddNYt0NxP*;U>OOqq=lCmKLU0uEpQQLyeDh4r&AUryiaZ_P96@nMP4t`w~b zM6oF9FP*&H-1&XiTUK|eqMP32+!vdmS;==5JRvnrmnNhj7ha`#W7O!t z<1?Yx(YJF!&UbgEj!0`qA4LN81Q(<)pcbt>fd{$CJFo;g_P3k-$77YigAja#5KM>l z?uylgfkwZr?r(;YTte*s%oAhQ0Pl#Bj|6%TOwjScEY_DPKSD`#PKAL=MDKN*_8Q`_ z9(O&o^ayP{8r1}^4Xlo+Xf$X`X3MIl1d3S4Xv7gA1AS#SP)*I6>-hvkOl(g>jK`GP zKivp0$DHr6avC->OKw?7E&8!jvtt$7H)gRPT9tlBRtrik#*pZmPo5!IY0x;q>Wku( zq)fG6M4A>z>d}J*n~>fL7u(W(F~2_+*P6bg7Q%*O$FzoE+-2wfmv!Zx*;T)%wT-8q zM&K18J`n?xQhmQ0zwM781j2Tb(Z%&(buZPGan#8})u!=8G4(9&X?I_vr_ZJ(nYZcQn)3 z!izt04glI4KFsaYQ)biVq(W5pk{_Yt^dG8|7C)oMaPT_rt+VskGsO9JO8(v0KQI-=+DnN;^l-2HpQwo&~yt5 z`IYuIS+=A-@rQki;Ucw>f}rEpny(}`bE+8ufVyJf77?+ZZnJlHh#$;o{`F3ZLxmez zDvt>hO=S=n&h>2yX!_d94MZ>*itqM5)@c#QbM}TWC4Rw$5_U^K7(Ql2?C12j!mE*h24SKF_bqR1f zN<=Xi+K(g7LD!!NpL=yC@p{*2WY(joc9`jsQcy2$>^|diCRm$k%?5KKP{#jLOye*d zsF`PNAe9N+{v#OD3v$MGu&I9BIBX+dXD1TLM}S4Ld)0yqa;|3SlS`P2ufK}sE6ryo z6GJxyz6ilawlWiW1`cp_r|rN1AD1N8_crek;AO~6Hf55%^AzQrDdDNaSFRLzmf&oH z@Vw*@j<>Mr%pfb}-|dJ5zI0U-%vAGn;kR-L@C<$FE_=@gcp-BP9_1gMAOpO4R^GJv z{mWx<{1(7rEi(VnrXd|J785g++(UK{usgX-=!Q=1v}cPolY=IP!yLYT{@V+;F%@pn zZ05VFRWM-5Bph2dep|<2BROW}zBAt-@T!F}sN?-=`5)v(teFo|1wwc>p5ly+LxXOC zvl+ifS_g#ceRPlo;+$;d`hd9JTdx>U)j9n}m4`^w3=TAhf}K*RDe!oH%Y{?anqE>^$zB$_H$n9NaAgK$bi*F-g5pUW zk#bcqH2t=ET-E9PI@Ii3V2mY}G|O2lTYLJXsqfWe@vm{+YX?gC+ABkBnLe@p5_jhJ z7Lkzme3)-vx;?TD{r0z>poxB@C~ruUO!8(K-x7M2g+U*TJG5G+Q+M0WH5B>h;5^5k zI<&B@wXKiV-rKe!>p|0Xr^`=Rtv)t|HT74Qc#8BKLwU&|9$d~B6K;S8ttrWvFw)`= zfG%U_i-{wT1C>*@acz85l7=TGB_3wz} znKYrm`Ma-6%3!R&^~2Ir&5mQkV+6mtxQmxkvT{a((+JpmCmkmmjytY59a`pCgW%h4 z+Djv3Y9GXX-E12&8k_N|d=aR2>3Yl|N7yr}^8!(2L>gsNS1Cz!TOoU^Mr|!#Lf5(L z{?^jUK^*)+;wVH~eDKjsYWBkiPn9WLxx0tobgVdjA`Fbt(?F(>%^>TFA9=momkorH zc4j_;=c$^ksWpj#H24u^WIl@7z?nM$9VZ&*!MC~LZprYmtD@%CyM~E0Sk82SXAX0D z%oES!3oJYGf0E;iA{!&UW1T!Sid7KD^s#ctc4{RyO_0B66KJ7o(5Qp-V(y#2a?-fi zd=hrXg4D>zaY)N%>mu?ONt5Cc@HfNI_Fh#0hXN{i6&|3=q7#*2hNbA#Mb3nVN6@`$ zVh&MLi_}@^vnBb+8=R{y57e6loiTN|7<`NHf{PuFR(~ zp#6-8VW7`4D`Y0!*k|i#dpjf{@4A|mAI-Jc-vEu+h5^9r8tm`o#Q|_-ZG@ZWTB;m4 z_rfgz@D&80zU2a9$t$H%CZj#&36;Cyj<(OJe_~ym&Ee=6ng)DE33>(z3G;t>F?IC^ zb=p;}2iPA3Ag{ew^7Odcv>hJEUZd$em4=O(1cf#!~0N{~-Y6Lv&r7N9whiDslANF6xjCNiGzMiJ+ z0_y{gD`2S9)tY{3#GnjHqr;kju&@Ke>C~3XbORuhj2lg6;zQ&gdp-IV|NZgd!wU%T z>Ttpzvb4iM>HmDu*!lY6DRO_G8&Mgj^k~?ee0fnvt;ALvlB_b3 zZZY}x?AFXSQrn+@zgkKu@+cb|B2@b-F?tB`(ed>0T6Jj9*93fN=T^vUUvw1qd)tk; zOCa_-%Z=!~4dKh4rBLTCFOChQ|ASs|hz#8>UlCnB_E)Xlx0d)FI3{plh+YTQFo~0)WmJh{QWLHtgydg{=S(Xtu$u` zp72jf2Gd7AzNj?mXn9>*uAmOZaLrO+7Nsk?xNTLNy82d=or2&mISjoP?-?A6_GNN% z@PvrYN2-0Gh~XH0@&i5%zBXyNq_M>6;6KB{9Kr5P)gjWpSeu@AQBO!RGAN4KpxUiV z-9WE8#5-kx0V7I%^i@R$UW%B1sjMtkNDqIx1bo-GRjg3S-^jeQ$Y_w!TbEY<$03|} z$V@LQH{qOk90|V#J+2*s;!^;b$0jD;CmZLxu*eT595jpn-bnuCzdS=l1z&ey;jsU6 zxZli+JijHp6T1olcJkiV!rp6au>$4gq``e`Uu^4!PyrbWLM%Y7mE!W=uWEgB6$jY# z(K3Z<2k$B=fm*zC`wgvSway%(6CL>2f2HW`ktlx<(0!zj_RDd4FIDBY33GSC(Jvn8 zS&WSQV00B#Wc8Dj#(Z2)5kI&)1#E|sI@ZRvJFAG2_UX~dmG?WOT7xTZmPxC2j7k>& zbH*n*O>L}R02R%E2bxmZK#wE^V03Jaa1$L~oEjx&&u!OpE~WHmbALdgm9ASzm<-zi z&1!2u<`pR(FCVj~vC**Ep;MdFow6vV|Aw)Ff!*g9u+7bRQSIpQoX^^wf8t2N5u4X* zFS1F2O7fixg4h^YeP-&O&*-GwhN&uw(EQ>{SK`6?_hpG+m^`??6lgfQpW$=vUXp9) zzPs^dE-x47T*~f^ihp!Q=c9)4ociqb<@V+F_V)0MW#{#1;QrYw#54H1cw&w3tNg=( z(?#Y)+vi;6tQ;I1?AdQR4c70WJ8~-xwTGvNyX$K!#`l-RulM=){F<$8Z6^(DGL)i^ zqn+33d#f#!04wZ-{Xq>w^C|JbOXmEn35J=&>oCF5{)#8#=Zh)_wu#ml%Lx&mrd##( zq=Y;J@7~Aa;m7ZOTjN`Nq5&>0Jbd-WkHs4ut!=`hImSlDuc>EkOTTZOW_Ygl%o{SC zI=vr%%98O7>&iXytc&i#zj@e9oO=b7S+L|$=y4!|!7s#NW{6i1_gb56YU$8yu z%+lqsuS2QRNKF7w0muU1f608iV zdoAh;xV=&ldi(kN7^2diAX*RO^)qz~Wqktn zeQTe-yWBl_p%-s)AO5Gs$w;AD8y&$@I>SF|le|&!4U=p`fNC zrm+3Cz5IQM1#Sklgt~)D{SMayjX;czrUwcf!H#R_Tl-!{7REL_2$k{VtGTc+LHsV} zo`zHl8(O<)aID%92TWWfp*clHl2ZK|cjiNqyGQz1tdkGd`kTdt1huD-?3E&hx2!ps zao&pxeMMPkQHaQkq+g5*_?fSgjDMqE*(bCJ4^ZZa0+?h6Vq=bax3s`b8W^h-TW9Bl zHm*2`WZO0R+okJTFi_Y6y>-Zu_-C~nBz%`v0w-gXLWmF9(0yf<^2~=_5F=rZREt|_E+h-2lY7E%aW}5+@s%*S+i$0vC{u1)PJ;{FCd}4W?&vtCI8o6z`7Rcorl!;j|3f!yP7xZ-G zJt!UBGYqgM8Tq$PPOfH*ImfvDFHWE*c=&@5oGp z+-|M@Omv+0j2ZmjRG=qNr5VIi`J_VF1_fc?7)?~>YIXIgfc;iLb7&TLq4w95baqr@ zFGpy6RbCiuJV>QJr|#C)fS5^~_-%=?EEYpd)`Cf5&rsZaR})T;$A?`=-iQ{*`CC(S zW^;c(^@w?RQY8L%QptZc@ z3rCKyeyZ8m>Z`ldEG|PH>(7c=r290Of3@5!TxLN;1Q~4r#C@|PNV0C;*yYXM?cvuJ zf2R!`N(MZ77hc+*fN-vq8!!=4asxF3Gd04E+6}PBuJZTT=C71VCv?27TC}Zs2;@?4 ze7R^vsdLKg>rRcK?IM0@mswt0zJak_BlB5nyj&LA1cZr?zj6DY+}EcB_@@WFoI#rW zx0jpX%XHVrJ)v&+F6HU^eS`nB1OfXd$H@dgG46sUXe-oPlov5t|64y`Ul57$9*5g{ zo8A1%2rC5eS_=Ca>rKrrvZ7*Z5_fw%Y~Y%js%!9u5tNxSN*W=00;6P^WrXq*E)j9~ zs4<~sM}SBRx*XFDCB1s6I}Sf>*su#X z(KmOBVGHKCUXle37-w=9Y{pk0I4nQ>xcY^qYwzu^7S5H zwHzFb1VM1($ghi8db}jFD)2`M{`8xwUc4!f&4NFDrb;RJkm=teSEb{jOx5vTf;+pA z9jV8iZ8E%F5S&2BtcyGy!XF@BRr3i|`wBez8T&RI^JbLCp+EjyL=+ z=J^6|j;}&i9EI9@W;CCm54{YQjSl&KuiW_}LK#X)EW}rBU&cp&85;PIw%j~=Ir}!% z-~SlK$@Xjn9ru1#;+QjQOgjy{%YPX(crjBExI5aA7u?U_2V~p>%gHd zB3Ir%EzFpj+NyQYVJfWR3y$>>fv2KFjkd`dq`0Aj3$57c72nle8pVkG>s{oaJ{-$d z8s-)V#LPrqmWH3OeyXQtTT+IO0)uPtnaWa&kO|A~00j`1={hBOGvMFIzux<8!Y+Kd zcF^Gv(d&;CmuZoq{aZ|ULDnOlXCDL%z?D^e$JtPuxaWiMIk#M*;#}F08X>E{%c5)F zkR)>GoHva~sD48w+?<4byjN(rGLee@|DCEjw4;6&HUlZ)a%-*bd5I8!U7lvvW%td zJ%lln9gJZ$%kknG=VrPp12P{NPNNx9*+b7qW+ng7j}tJIO$VtKX4;qt;8AZEqIl9)TcC zey9!@7uUv=c9nV@M&dwxP8c|fRU;|^;SNlYMnulnsb&_x1E};VA%QR12Y@(T}P@ge_-dRSjMI=PO-7*v!un1-c6r ze4xr>m+ZBZ^)+H6|MO4WoVBeuUyTW73nPLeB{MdWYw-J{`Lm2Qm7 zm@O^hy643=@OuB1m%F{AV_rSHt$?$-`!! z1v>&8a}`PV>KWSiT0P{$7+?uc4{PaHTh6*0Zt0e558RA@A8K(#+Z1bSBUCCW1E{X{ zauI-7P6&J=w-2x1m7!&1xffMO9Yh{d43&BrGRh%O6s1E7ik5;tl?5=(RANY$1FAZt{#C{NsP?>>4iBT|yk2dLDx#fTYcud8Z#jRJ{(*{-AXB&PDlsRKrANlV9 zE+bN{8;_|t^5PCnf4Bzs(vu1j2P9EgsWK!Clg+8ER|b4$*4L~_W@lG9MP-|*8H_8~ z-XL$c1IPdlBxPeGHsdZA{t13H9SO9a9>|I0X84_#Ev&Q`-ZwBcTzv%*@2MD`eKdrf ze+s)7?C$xu{pX^dO5vmB|CIP|J^F%3(V0l}zj6(W=r^d;H?YDvA*;40&gBR)8<^a^ zb)ip=mN{?|8bM?wN(NZrf={%X?8F}aVQLI0;j$hx>hg5Xa1<2nSylag;Cv0Ti6SCSVO0txf!BM-6++upc(#4o}8F zWg-8GA;vFM@W8^FK67kKlU4b-I&(f7>``l2!58!3R=;f5ur_1Kw-VqKk~QbYHejVq z?)jz6)BXFv*ck<747Ey0V*}Q4mf&0kIWvlhVVvL162ar8=bX*6i#KI~YK4?L{td(Xq#c?w{g z#Okt%r(93FNuJ|}02_2BO!Fo;+o|Eyu6Z@Vskpqt(i4zOMba%~^MNV?ExZ?V2QHe)K6VITFAj;1e69j5{i2N6@ z9|>w-kF`LQx(svwH#s^7?mt9{@4ysrCGe>O)ex!fl#dH$SXB!uw7l-p?hb++^Dar8 zVRx%*q>MmlnhP@L>gJHr`-MdHk$;()nGB~%u0Jxf+{S1$7vvQ)l<1SpKRd3jjybSJ zfJ=-G7jFxPx$8YzbJ$&PSG)Y3G&~9EU9!Lod-F#}1~V=Ee!*b(f4?Zhc`{S7?FENn zf%A|uD7Jf~o;zb!wjg0Ge3AJ4+6acKSNmZXm9%G6T@LocNXnUrj)71+Y7cLAy;8EA zVm&S#o3e6zVU`YncVlq$Y+uGriwQhRiTm85QUnw8Z)XAyV1WovzxqZ|oq6*zJL~e|+ zUECia0nO&nqCz$zyq~=+n?FSF6ggejM970LmDPrcoKBO=IoxPq=om>pZG$L*btE6j z_k9ZOA;Rw43se&QT@QNZSXO7{R!rV6O+E(_&cIg2V-t(MyzCr}Xj~uK@dZ9ftGryC ztEHN={o2EZ#TzTnPdWnZpcVV;y{<=7w(x|g?R zLtK`Z0z_1ho5`3Danw4TfS-rCc@S0Ccw zptYaQmn>JCqoN^y^jM!Cs!519L3?dwdg zMfO+7A{Cuy*=sX%9VZ&7O!-8s5wgGrDGS`6SF0rLfQs<SwscU5Qo1jnp!UDfE0x+)dh*@EG0=63M3=T}*3l z*3`shMzJs}as7nL36H@mkP7gD^V+R#-+G^&M@*sBjN#(ie@VnL-L#3MQAD&j$RRw2PHRo-PAbzu`*EMeUaZOdi>W(CEj;-mN;Pe64b`2vo$~Uxh z8p?5SDDo0f96I{C7RVZC>E0|G#psI7lj1H=$A)hh_ZGxWN0JpwX8uZ%LPl=UMR8hm zNd2KuDb-=IG|ww7w+YD--0JjK0gW>iSIH7W;rRjcJxbxUkUnN}R#BEq)6>4E_~n8b zZZ6~igIbNrMa)D{oi04L0*r+A2eRbq_Py%bAEfSMzHWwd1Q9m>ucVDfC zhow;s1+M6JWGDR+v_oCbbv(6u11XT6yU^r@-NOs3J7YW$q})c8ww}BM=4U0xx4uwO zDiG5zS_AQ3?MhxaG_HybH`2*KB0O#hhl-D+;fSGwxm3k=O<+Awg%ylhn;os3fIcc3 zFm@jj%f|aI+UR>-a(i8@BY8YgvZqS9)#vh8wi|RLGAe}E;`~^5Z(w3V>Z$L9u-^_b z?;N_09$N}0+z_%#+c4)Aauv=`%aA3|I1Ta-S|A@qy-7iL)Ltc-XZZYj@91ONo}AA8 z(MgEq%#$J#(#p&3-dgYBuKV5o$c^2F@uE=LaAaib-`Vu6*nX=oo2N?a%~})XGma=3 zLV`e(hJK_B+Xm$J@{G142ZmB@)>RvO3j8iUe&+MoYrG61g1u4|Dnc$Hetj?4-19e@ zcA^VJ{@+<~_ie%BYXCUF$LG55y3@{%bmiqaSK9BQ(`uKydX{@d+ITb*ae#o@k}puk ztk^nyF;9t{YA>^s&bPFE;jeMG3>TL^iwPl&oY@ENjx-%Chg=-_c3&K=g!nz*B8GEL zcL^s~`1chl$>+<2<{y1i2?rr&Emq%0kAv6d&M@&HL9p+5rB zkjpB*&i#Yu_3oE`D37I#tz-w=X?d3olGKFd%7FiJ0EN;EFU-NR>DqPiy}zjM@xRu& zkF|a`*rXv;4o?z>N1M*G=8cq+h%+vgOCs)FM-Q!+l~m9cMYAZ>6E*clvQiB#D$sFW ztEs8c5w-~k3i4+;YBQ}f1jBIpl5>G#+4zu(SFt8T2xOF|tKuQg_JR6_akRrFC!J`i zJ%pw2AKnMnziM&vP$SMVy~ap7^^e-5Qv|Dh*TqKV3kKvoolQ;(;$b{PiP@ODo8IKl zlURT!&p8I|53c);P~9@m=c$*kigU{>&{SlsVg0Fdbv>sC{>5#agwFSMq9bt z`L?i;T{uh?+qxQD?^hvuu>}v}oapI7cqmynb86oY(Xt>wN1Ozn5Eem~M$4~b6ERttynbazIBwAmP5TlU zd|(Z?`#hLUu8qlR91F7^sby%1SuSp(i^i?YL8*F+4Ml3^y;$(o5FpD#wy`qQB_FU|Q9Fu_8hW+a*26UzL%h zOsE<^7z_9p*5{8KPU0>eVDH}Qw+_p=<}$iVV&_1JX9Th(o^S6lk34$9G>YzPyD~|p z%Vn_xqSsz}$hVnggtNz=49|9+AG<5Ish=2nWAfLpud9c6} zi99)IPXUn4#^v~1i4jT1szbN7^9 zwSM=sX{QQrxOdrjWIMK<2||k*^w>Q1VB@=Bek_0EDbLM}KK|{?hVkejAoA||Xfb!* z{op#E^cen>-PJA9{g}9NzfEz{adX|CR9#)2K+fNN{}*c{BBH2o%XTupm}w_{KriO! z?9hxM(ASyexWW zWJ5DF#K&)XYzN7z>Ry7DOK7$X)u1_c6OBTg$nY{o^RfH4EA3~z4@j|OYFExk$Xs=Z zER;%nj|hD6-X)W4IgV8xY-JtjLPcQA;CBFJ_5V7J8hXh05m5%aZBfAU$ zT@@pO2a=O=2X%G{tEkK4ZpISvR8~$SNgDjhKo~{k`j>+X5Gf=74V`tT)L}g&to-_k zr{0?`e!&3Yb}6e9pJ?M~(%>nHmQ|)Zk$1t<5;*Z*&P6=V_lNvDpd$w%8=DP1O>=9Z z^R~M^>jHE(x5`B=_=o6dfb~{!9c$z~Hp)j1J28Gro6dc8mtD8&am0G`oK1Mi*4zTO z`#Q9ffHX$Y?V67o^~i0^rD@e?@K5s&gZ*0v=6TDyk60WiP1{Op9M;k4#aRYB_H|tc z!ac(V+ z>jpq*O(yBwoHh-vV)dZ~M27Q(zBwyWJcK01)M=GEYK$8JCU8Y;7zhwVKd>)z$>xgzgqK^}mATdzDmSC zh-#gHfEE+#cOaLv#U_{ftr3dlLjDQD|klvnd&+clihxzWstjrsrm6WJt)cnz6vm0FO zY475~PIElubQ@3l@wDgw^m04DmA|pIw|BNTY~`9WTr4UkHp;q_7cZ(6?--Ua^bmKBXvxAF@LywI;QzJ?Opf95=4h9X(Q)a zo^i^gd&wM)Ik_~fbWjo=MQIvU=!}|`+mcJ~o#M`*(O=hiFwdHb&hvA0-0O0lwIdIp zqteS*!(Fp+%gkgYB_bgd;ZDR?CvsveqG3))sEnVt%E+M%OZ0ZrQS5C~mp0Z@M=Rgrp_wP$tPU#2s}rGjz$l7sk6 z6S6#hhI4uS%}c)JBi8@07ndwwT88CIt;d|8zt^twugdaW8DGM6%&U%zDmz7PAwI;v z&bc$vtHy*d;8!80 zatw>!KkGj(>kC1&Pipe9#{Y%BmIpWP*Z*y=-MuTD|F0Hc2Tx?#+S=OZ;_U{}ZzQYd ze#ctAHzJ$kxA-jK+SZkG_nY{11^Vt^Zrmt&OWqufevAis~br&6?k!6o)HUW{L3?PB;@K4&`0)6=Ot?^p$KP17+^Be&2=4KJy43V}L` zbJR&XhLJPpzRC}N?v8eeVoeQ#l?)Y0^ETM`sxuXHQ=7k|dg62sAxAra?#wXdas|87 zcCnkH0Pu#f0KNy?{B);lvRz#cVG$SXJ=78`pUCb*M5Mcos)P=p*Jo)7xibNa2LX-x zkpA+YTngwhY}eMP7i^4z$Rf%Qx5H^OU~x%@ni^gQ-XG-EV@RXhM1Z~@Vb))Y3#ZLFIUG8)=-ZGno|6OR`H{M z+4BU#iX$s8FAo9wrVuv$D^80(d@haY6Dq8PT|-Nh1*2az zHO)hhW)Qy$)d010bq%wsj=3zNp5x-?M^Z|y;c7?wFj`AytaA%p(oBjDTA8bo>8kCuyW%8 z*xWo5L(nX)-ofhZzU^6NV(xmlUa1O;&V*5lMbyXy9hSkXK zwMN>C_klRU7AmP}Ek)_?e`8ec0~vp@lre4AskxI{3+dLM(UAmK_tWKlvUXoF(m$$4>t0);Xx1J-p62px6$B;dIB5w9Z?Ve9 zFs+_^!CyFgteCOv_xrqly?NuA$TSMmcM~%Jn=<9UfOel;is1WeC^6ulfZrZJWO&pN zwwRD~zNS3I5y&8;Z)TWFC9`t#KQ#43-hs5t#Q6(Df!2+~<^L|Pm&ci-%*3Y~NqrDN zy1V-H*fN$?hYE56^`&=5AULZ=B^VY~de~;9&7o$}zGi8;Z1~n#|M?p%N}ZL&zOo zm_&i*PTB)JdBwl!a_4U|Cf6Tq7y9*jQvg{;LQvL!lyb6 zsbqKwZ`xKSa22(WguQaRCiE-;_-syb>D5y zZ#|rR7fb;1x~RK|AyhJ&nqNH^)fSjMtgZAZ?h7-eJpPK-p{ss}k``J;evnge_?Z;8 zh~&nc*zUw@MOD~z6lUrSh=>{0_(Lo);}}bC71rO0uP2Go!@zOOluCKL-N&=Ev?LL7 zez=!*Q8v!C67W#>UONmWyaDofUm*>8xK2PrLxaqFR=WH+ql+_f6#Y(%y6l6!c~y$^ zPhhJ56W<~}kHefP{dtYGwcZ~VB(OW5AeNw^^&VZ;Icm!0m_Fk6-$* z2k{jN)t;wu&SOdYrQEB4z+ivL%O+8q^jwGbes3?oAoTbzob;%lG_ZFjhR29aMEPT^ zAj{GG1b~3p`W8y)4t2hn^pkxSN#6Id#B9p};^%O0k0@4Po+hx2*X(<}j45@^0Mu2O7>?(3YcDsE&gNA1j7ec0zW`fp`E@Otv3kkcIBe&h|T6XPA6LFwO zvPqYNuT_`)Sk4P8FE?Jo!nYDh<xM7Bjq;6J^vFbj#_Q>0L@}B1*nV z!}^S_ngU&?f#-d@3sS-Fv4afT&gSI2S#efv?&KTzb7F?coU$~k>Y7#ho5)pXGC5r| zK$j_+h!Wm}vbX@)eaL`dD|~Hl&dAKHxcabM%%mR3BVPVHD5)7STd&0YztfN%i^I!; zql$?Wymh^W#v2}lMif!DB*~skav=u#^4cP|bl+JsI!5*7H+h6{EvQqH=2%ic7Plp+ z#k>MqS!*CA#F`cdxBzIDxa2%G@?V9A$H}9U^kCS6wFOxS4HzrR_4-}E@y0RK7$3X- z)1oApLlUgumD@i4?)7!Rv6k5@LjIpPk3tQ<{Mau$GaX6vhZ$&$Q6bg{+5A>}*8qSBND@jQX(wJSXQ~f82C;k2T#*r+{LXR=k<>@Z z9H_^WGc9U!G!hy%=;Zg*OcJUA?=u8n&srOexq3n*MV}~`o4>*}+KyB|WLF9w^&OD^ zknu)}My)^%6-Nk3<&?>BcdrH!*ps{QcM$0H&Ac{aWa^*l$#L1tYxDzpozg+y!fA6$(XCy8qW7|N?baa%>V1`MY54#($ z(sJj6W=)XHC6<$`F8v7OYJrG5nrd)>@L$RpSFI_lq3sO0A&%UwO7H;~%;RWPwASe0 zxIVe|SMF<(EBxxfx%6eX+kfxya0y<^M<@uY5d&)CY+s-@xcj+%7*qLi^~SeiZQY|; zO!u9Z;oQ7iTx+&6qz}bD2CYEiE5BgHL8kfK)u+E-^1jXax^Z3?^bMy$?C=^>ueY%R zr+p593C&FxqWMHAJ57pfHTREgja;sF;-Ov_SoE;_(8RW;wadl%u@%gY*D`|qUd6RZ zYRv7u@3VUZT&sd@xp;(yi8Qt+BxC*w$o8OkWei2p#sN64etFZ!crXOMIiUMpWOr;! zL&i&Msd9Gq&G~3(`zy30H-fG~Tx`#oh)~+G{QUs&KU$v$n=FA=dY!klot z?*0O~I)7q?Jg(%StGeaz791}8e+>=V8BiOEp}7{r`Xs;6z#CqZgwl?CYi_pOoiont zsFS)|7{_`>0tK&mK~g=>+s?0P@lXs8Ii@K}g2-0g?$CwN8gSEKRcE&*c1odH$BYqw z!AacG!|6P>O>#F+k}*(EKt(QW2hPYl@$3rnpxuYgXJ_l{&z#^KR4*EjR#(rGW*#tW zYH}GqIl}QeUolZKppR@VBL@*XBfbh37gW3d3Qf4eLg1i;f%WtAb3!8y5*J8Iz7DRm zvs?ggPj5N?v=he%4!g(%jA;g|Lw^owDJr}12tHl?;h^QNo`(mx=Z&`qL`tm7KTqer z=t;Wr+KqBA(Ja`iTzDx_wqGqa{% zDF!60;Vpuei8wqxljna~AK{i1mkN2joljbRK6}!n;sPE$P)i4TdIos6_-ghJdI-~ydm~YYUarwBs zj5L_w(b4vzvvkW~OL>AM72LSTov*VkA^mC{ZcufW zJ(*{^!`IZ##ECX=ZtR(-m)C&(d&&fnr6n?L6?+uEi#&cvttc;V3Vuaxj#$S>-vhdb z6571lgyfkN#49mtlgXP-k5WbfLk23rsDc(fJ1!Na{w25@a=~KM(aVxIS8N#K9C#|0 zGNj@&WA#yscYBVVZ)XpJJZ2AMXe^GKK>9aN_h>I`6W)9zBL*!z))neV%#=&{@n*LABeba_=N-2j=c(OhNIvJ>z38}5UWoYOohibk{hTLJQggE>O>4Mg4daOn zpv=0-P!g5@3jYn7sgiXE18*6=vU;6vKQ>un;g-415j~5FVl(w8lvkpGl{OlT3Q=G12H=ZI5zqQ#mEO+Q8TB?645)1Hfg zW1dQwnZ=C05i#uDKRg*6?>fWRTu2f(OI9*e+-pvNAM;wV1i9oFn+mpoevBdP7Gs9c z38P#swH6sd<70sYc?g8R{b?x?(YJzl3mT8c_Ft!5J|0Tn^*+kty=02NVD=blcB8Id zO~F*UW?C2&Yn;|(bsPo$JpNL$Sg<$xJhV4t&f1VDFSnbbWv85)%c?tU<%LFCO6~yq zbd|$zX=`IYjlPIJ;hB@Q5ykSR|6p4~DiwX@k?akDWfn_OvIojy-PfqODD9(T#QDTh zSMbAfr=j%oZCcs**Tp-{<@@D_@$cWSdrlq)bJc_Aui((4zRKa5>f+)z;oQiNO@ zpHNmSpw|OO#_DTL#YZP3Kp84x_Wt|F_r{7$L$ju>tGi7k$}ml`!7sRQ=s^Ro`bR)r=abfIK&u#KimBBh5>mF z?qDgkt}iP7@#&emqp_X8J#goAcl+ln+^?<*`4u@o{ghjKt|v7pn6`9A_m5pw`qwV? ze3|*sMyqSzo3NJ87~s7TZ?%~nXS4dNGCINh1B}84dc}a@=^mudoZ7P@B}R$-?c-R^ zg-kjUc>k~Q=Xw~3(?-wq8zH|P6lh*TEbQn@9sRxZ6E$D;kUq)`hzLE2G0I#YYH99! zl?-XE*~1_X6T4sMi6KZ%MOc2rhX_%B*Unx!8s(dr<*%=AuCFWOS-u{<|4#0x(jTXc z1H@(Gfs&MGp9DSjU0k6JHxiQXT2N13gNt-vST@(te`jUS!Q<#l%JCElxQn)83M#CB9(81sDNQl3b@ zKw1Ue87mzQEAuZ0fzRlzY#>ldDfP0nurMDBQSKkAH=>G5IvzplLJe~}{&DGlZgCj( zuvi8KVq);B1w_9_`O{WTRMNX~WC0IbE`QN~i3iXP+NtT&bKu``JXrH1l3S}$>3-{P zBL*zf5$Sx!r5tLQK5S?z|4F(fxMjzv+JGC!|9N6wJC70eB^eU6SZ(hzP2%PI$1`P& z%a@Rvvf!=z&aoHRe>Wy=3UbxfZURawptLZpHmndljnb6z_X~MGyAxd~{mxC&v(+Y^ zlo{aff4Aht-F5ogP=_r+sKjrB&<@k!OIjE&q?b6^X}8{G!D=WBiQ}8n?QIx1by4vl zVZd3c#%)C`Pf%Ul?IuH2BQDO%4AicgBS;gnHBVXsMtH!nYgRBP9sIeecnEEJ_+ugY z^fqm&-LEf?S#>X#9j+Ed^o>OI%bmAu#+Pi2!_+*E{l(bcSehU{U4BNbvA#hX%Iswo zu$a!eQg2$nPzFPCQZTxAB9!>sPaCLY(j|w%kL-baO8NMrn_2wUBWyONA*Un?U2T0% zHcOA%(ADG66X}P13GDgvo6ytiz2Sj>JHY34=wkO|le)et)+9D_i`r)%+t<7j^n{z~ z3fIiU9)8o}Uvf3v*}D*#wdl9(Edi5_QT=h%2KphQGN{O`JEc+;9BRT;>z+e#|vYe?}_CI+RKbhdMPxW=BIvU%#%DpjnwBtkz=VSbkN65MtpcV%FWQD(z zrw#Gkwi1SQMd+iT!w8@OZ?JY?#LBBjvqecfZ7N;A_k=W=MN0PF$=^qNv zfmSU|c{50*!TQwET?a9>3)j1fJ`IZF*=w>&5l_7O?+{&GMN5vy?WHWtE?7Kou;Qq>^SmPnYcY73!m{dDnnk zMvJ$hkQ)5iCIww#MgiVWX`SuVh9%O<&J;?`8y8!y_&0DkkeMXBwe9RzbF6K!j=rxc zk?prJMay)J9xRNGQg16@LArsJhIh*WNEVHwLtak|hxc`QW@M1?#V#Sc%;&+eMmpgH z{KtRgqUxd-xj25s{=I9qM5GZ(Cip(EA&iYgQQk{;ihtU%R>gU~j`@>pD_M+g{jS@h zj5P<;V+TYPcor#LFd*Czj~j^aM*7XVznC?wOqY=p*3s^++}5sUw_`0OE)FxOXnPyI zgy-MN-`!zqW?Jn-QYMU>K^?jjayromg4MJ?pVuREktWD5av*~98cXv9K~=ytCmdP@ zrMjg`GF<2fCb}YJ-nmEy)MPp5cwYX|g*KP{t@_S~CFtExB_g$V3Tr6Dac#sY)480q3zqv{?oO$ommz8dcn!>X< zm??%4F?w`Q{-q#CgGuPN6~Kq@@6!U2D>VvNR}15pNTS`<- zC}uKqa->PzpRVo$O}Sz)0?$^=%

@qVHX-+> z4eaGbUE>0supnc4jy-Qd68(0g!lI31j*Z)D;UY%6uq6kE3{jlL!~qAAblOoQsM*J7 zD9Hhje1q2rdB{5uVaaAvVxa~Z=oJ!T0iKxRp{9Qbfh;(_`mb5kIxFjM1 z%d#=QUl8tYoZ4MQv%kvaHOrRicR!b1DuICnB9YLN*R43B?$?3Ce(jK$HOj$JD zs)m8Ssyqk>Z0yyfeAHlqk&6!PkIVdK2+nf=Kwal4~Fz^{aD`MY+M|t2Hpx*v#h87aahs9_G4KeZ~gLefj)qGTLp(R+&Byp9kbK3314fRVFg=wjE37oT#hY zYOsfF(rE?~QiHoBdilSvckS9$G(&012qMDs=i^mWI6V7i+eH|SMBOrxbFoGy`-Z8N zOQNDa=et*t+S;sUPR*fl!Ek1GMC-~*CWQcP2$2y2;jdLi0sp1R-g5sgPu$oWUqJY7 z-g4B1&@)yA1zDBTrvH3#OLXxDOst?^aDlEBJipYxL%|CFxXyUQB@E3(ZNdVIHSK77$Nv#C>8GUtKQjN{|h zEz_#7W&d#jZoz^s7(%iJq!4d>b;$C>YbLgj?ccpLc^mnV3;=Hq1IKmt_C~TuxE*So zz{VFNc>+GZ$ygYGkjqCR56*w|pep)ckK%h>whI|b*29Mo2hIK*WX_4j}FG z@Ex{B$J0o4x~VBFgPR1QKOZTWz+uw={TI`m8E1`W%n;5wC#U)z8|O;|GaI~S^vp4> z*9{Gz`~VZ+;E(y3xpQZ8gFQHP`^M%M6dWgllFI`pbH@D9>tVTM%=wUci`NXB^>qhM zOOTl{Ilc|3)!=%xd+fN@lHQ|x61!Y+Dq2^1sMy>ey7(owR? zCLaff6Q*AByr1S(87T` zX@#1YjDvUluZ?>A$h9bZ3155n8gpdu!0VU%u{AAN{-KjkmJO^--ugF-f||F{#k9FZ z@!%vScHGEC*46-n;sNL4(L?^>j3VT3>iy3&10}gPZ{9%SDWg0?YIkJphUFN!RK6(W zApZLKGk0}ovD24Ra@Z(*IRk$op zgMI0ULa(L$QNCYB^4WOn&o42Ah{#AGS*W;2AqIv7aBc0e5{Dl?z-Bg%iAjs*%>`2Y z4V;@Ej-U`g0i)5!f92-#U*i@ICOu?V2N|g%{K^aZ$)wp^%M*Kl8Vko7puu*h=H>fT zq`$sZ#bPM6V#Ot9g9Du5D1<6~vZ{P)`XjEVaOsDcIM5KHrmF^%b-rDQh;dl>!D z52JX>GdfZf2d0$G5R*JGAK|bbJZu=qDd3GOZZ-ui4~yd$x(3pZq=<;6#54ZlXnXTr zfbp0g%dk6uB%t^85zRY_b&8U6@c6B>mX6}Y1`Yc?&n|ZKtYY`x6X(qwD8_xVVA-F@ zOTX9Fu6CHg7yzA<6b(6gzZe2hi81@Ny`3bAPw8EaSaS0?#btcF@!vwfT#lZEsR|@E zTukLoo;gDmoEMQ%{^pJMEBt#T61@df89XbTG8Qni9S$|^!WqsdJB=7KMSOdLt| z_4SPJ?K#1fmYH_L{PvRENDyx7IsoDLq$DTWu9Wqk=uwtL>TRTc6i6I&E}HMfw1W-q zB3P?fWuKbK;ICSvR{ z8;=J~yZm#(F(Zu<9C(Ig^bad)z zwBypo!aXr+*-mhHWG^_qi$EeV!8b$<$p*0CYS;=wk_kv0vH@0s zxcNkxJ9q3zPeHNo=0Bx&Jg)0Jf`x%I5wrb}(I3ZZr8d>DEn`9yh4?1*#tnY<)Xbv> zJRi@2V7t&^NaJ8n_3#MA)I%V?sp;$e&}6_9`n#(-ek6GpY|yJ$C!%=5Q64@HmquVsa>TclyKzWR2+s^-5?~+AAbW7%OoK zkcI%z(zPpxDZ%-4r9oC?OvBe`rLcV{7RGusjF*BeVz4XU1E9vpny|m=Xs%Z2*gh*D zzRjK6O&ROUQr0zdxHcRP`kOLkArAo(aHKAwAf=DRG=pf}*~K*OgsCPji5$t`G&sO% z@J+DmJP!0|C;43Qa^rQ}OUc?On6Z=W+qW-J5`xBRW*-`QHwzTW4>62S1aS;ZS`fhT zCnvTLl5T#C6p)xDk4#J{fKUTfTcGV4d$Vnc1T&9}TE_bPFA_M{WWMT&lOVjXRm;s+ z0q^;ZkQSn!&a-Q9mn3UtBML2+uBigmQVQ%oG(SYA>9W0`;NUOE7OCmzalf^F7g#AG z0ljyRrBV6Pn2!T3?b*0)|LB5yl7ss0-Fw~b=SJ%Fn>QQajfqP~q;R8iS3MK5Kn^$_ zRVFJ2ng!<*#B?zkkV7vmr_V_7aFl=$`;OaaLp~TD-cR~)E}__=^7Qj-4^Z{DtuSd5 z@E^-WAxV(go~+SQo}#ahdHM~~+QP!_jgO^ayOR(Ezi_Md$9fk^Ov&@-<@@swf$xdF z5vHx(ec#ghMQ%a^l38$%!rJM?05jvGK-6r}!t2L4Q@Ali)_>E}IbpEHdiL?gx`W<# z${d+{KxGTP58xtWG6vIIU0oRt8?X7kgp>hd_~ti)yGq*pX=^iy3AGQYXH0Kvn5{^E zI9y=GfOCI%oNyQ=CU08OtC^nc-YH@@4uuR2Q{Wr~dj|Lp5$@;Y|G1Q+2X|y!<0Wwn z%qHs7W~i^L>odXifLO5E!0i>BKy->g=%)USlXc-Br!+7~T1NG3zbYv4!iB)(W^u8x z(+>6!3X7?RG;Ou6X9>tqlG_{ThlnMnnc--pcdYX>9x!B-&1?@&uyGtS2uN7&M`AjZ zS^(~Iax7Z({8ztycgltg8+P?#$&=mhw=BT$4-pB?0on>jU3|t{7*$x1r-lvKQAVY z>{7Wb(URyuQ8ykinGv5NMe9)n3v=G1owP zCaxGO8c>q*DfrKTxx=aH+Oy}iW$C*E%D!(TYG8E?l8sIjZ5VcDtYB5_uAN8J^#lju zAabMs!>iC8ee{|DqnX9Xp`$obBBvhG+epTFxGwGzjvnh4}yoypd(z{k=_nR*8$LPXqZ`Ay7<}CkF+UI zo_y_d-;?adN3@FgfOj%8v9fA<^oViq0f*AbDx+E5^yobUAWdZZ7Lk$1?ZRZ<;oJz8 z@agMR2E(jJ;jZtvL3$g^XbjM2aHCj*N+){mPIp}J0;rk`8*EI^_TbS7 z&Ody3&VawuAL@9##OLCtPdO&?!+Pk=re(sL&EggcczXJDW8-)%7rhZZ(K;}0-QO{1 zNAc%?W}dWpHj$kGC`=Z;lChCywDZf~zxQdH{Wd8Szq4`vX3oi3RsEy<{j;%RtLk*m z$k{<$u4i`}JG+41nyl+e-agFL)H2c1jo(Eo#L6e%f%h?b{P-K}Ij8qK19AcK2vUY~ z+mGw>5D*5^Awmm*?LzLOwHPGFhNX9CvwHPHAhgg>g}#09#oNgK<)|f(qF3)u7J+3i zOQD0zmvuLyFoX4~Eyc~`ZlE&Dnfj%o@N6+hA?LRq1t7&Lg&S%Y8;~&ukJZo&x%3o7 zkR1DM?N17DU{!h}zNb#vt`3I31Wb1N)TvC8YE}6SV~=;AI0g+lj|=7%?@J{>0AL@b zf_Ko}pe4w@LogQ5XB>?Kn9bXO#~D4dXpu00Hn>Yy2SBha=}5WcnLls<$1~Z{w+p9E zu|Rj74q}Z8-%++_fdxqc)hHr&9vk(nFh%7YJQoo$X~~wlv3wZHVlXJ;n}ae)5j}pn zlh|>y1kmw9!d?&MgMG@!&sQA#$2f7pW5NdpHBf_surHqR^K zQWF|yl06Lg%N`Zc(#5M#t&sC2dr42X8<#Up814E;BHtSODUNOrl4YdjIoa8N zFc9QdPhcPrM{M$@TX&2xuCTNe9UL6^@h9N@o>~*eY(T?#Rhj_(RuJ( z;apL+&_YCE`|%^Ax2MW>-aCau;Rd4}C|pxg#EeT=nI^JC)+&5#aA)*rbSE9DHRkca zHwHWG-np~BEDHj-My~BHH7!eyWjf1oUVu~tLRfGZ+cb#bmxLXzycjheiIaswQQGHI zdGw6x(*5VQ`87Vy+25^=nqk>DrN+WLE* zJ9UHrh0}u7GQ|JJNVG1`Q zxL`ZHyjqk*zElzH*v=}3K>aYN){qM0g+v6Vu{FSZ&yA*GK4^M@@zyMGXr zZERw&Dl^!Fw;LpE8sdM(O|Clp``EL@2A4L7*yN`wLE*yQ9CeF8n@-3JfWn0UoByfw26 zsupV6CiHvVQ@3Z%4X(|S&I08y!*x&chJqs`Kgv_;cOI5veLQV3DTU07*H#k(02Y(zY#K?Aofxo1q{C^-I^FY0Bx#iHCGpbZQ%^S1O!)0muC$g8BQtmOGo>?3MkkER z2{sfTA}pn)dHmVk{U4uAl?6k%&8L@dg;j2_=jhR1-?~1&7;}hd^x)Ncp~;y&n-2}y z@bZcJ_k|DcUyfI-3O_9O`pp{+EQHt#50F)k963u>zUJp|x{cXK$GqohlZg!Q#>Kvi z0hmj4Yfw2=Z@4}a)dv0q*p*eLC!VLt!dzFg%JuB6t39ZlNrD)1=4R#D@m~RcIjFdl ztVXZ|%DiOzx5xZWARj_86iGs3OcyUX1KMyn9uYOGJPIB?itNr;x+MX&5ro@B%i#k< zjJKC4xY0PrE6iJtgOEz4a>l3XYSR*b4e6+eYQJ@3^@(Vv^w@F>3t>1%3go*TYn5!0 z1{(%rCV#UuozxABE5O7co_%@Y5<@jL>O79}w0d_^Eg{-lPqTvfLIIbj`2HjH+41o% z8@cI}u$%w#g|@ZIx$wm`)og#mssoDjWFG&6Zx>n^+np~ccC6l@5_q%cT1J26AS zdCmI8_c(T-aQz~Cz!sL}N`JEt6A=*iaU181+g+)`c@Cx6ECptqyn)r2M`JV<9mwyI z0avA`1^h5>_c;JUgBfcypDxuJka>{r4LU$8NmxP@RrQ`!uRy_vRMgL)~#gc=*L20WLv!c>&0-RUJ3 z(0!+Nb80PJ;`S5sTw>yT#nApQlRgHNf1{h8ghW|&*f7SH&ZdXO!)su{RqU_rj-3%j zPRG9E5p{~^RR47qZ<{>%)}TQnM(me+O^H4MZ}MNHRz!w=ii#$ej{&$*f}oGoVInm> zRGYhU274@rul+Nm^x6uqT62sEp#I%N2nW#^;Up+rhn}N^GnDWt&|-9nm;(S|BWa|i znb{=SnlE1*M(-wO@#Ohew%^|elY2!vKf;tdMDoSaTxDh4W!h$WP=q= zqlI*hZa7s0Gb2`TFB!%oSV@EHrkEU6pUNypwqL)fQsyT|6^my+4onJ|ui>*fpd`l+$QkfUT*miR_RhBTozj2r z6mtkjTZPfnh{FpZPnFehOUCx0(zGMz*9%X7g+p5H&)>Y~h{L}!a{`jOS)~mXe6$Wn z<7tK~>RC`y|2bbB#q4a!geDO4_<;l7J7^JmG2;%}-!9xczTKQ47MG`~3H9aMx2Plg z>*_A7uOZqns8R|}0=x2Bu|ma~7RagUL@Bv#(ikwF%e3LC=CIVD_Q+R^U5WoHYD);V z!k-f!P?G&462aLUoA-WPSO}N)Hk_vL^;+Y`xd1PMKM+5Kw@=EJv*hQ>HWVJTWS{}j zBXdQUK)tTl_@*-+lCmAnJla3Dmgz@iU9vpAt?|g$#ByyrzP74<= zzDZ4tw}E*lQ7F85Q-Er$LWb2$aSE0}`3f9iF@Js|51(q8O(f>5y$gX{bJjBPHFOxz zRr(IpHygHW5%@2=^jPn}Gt8Kz83upTI}kw-M>}V37XyC&M|!7;n4!wFY$;~|fLx8r z3E%-VmN8Up?`IeUfZMH`>AU1-q$4XTCN|cN=^nAM7VU^jc&jlh2mJVYUn+rBKd#KdfiHGCeeuiXLF;i45VJqfb740#LwN4V|v}X>+WBv&I-ba z$6yb6G|`k1Y=3m3kaGP^!gTs2S`w)8xURKNF6?mVy?H$-1K2NU5j^Fd=w`t*umUOX zNTC$go*{b#K~jqc526ii_>;jQ-g0VcY5+34xKR$bN=t7ZjH+Q7d`S6pGlZD9cZ%>d zhDpWr_trNLI1iHFOArv;6DX~4PZ&Rr$MdjZ3FxZIY9Mn0PLO9*T|KFQNnZE1yS(MP z`@-C)7ox`TE_v9WSb5N5S#ou)qSvjS4C~++BsSZ;`CH~D zyZc#Lvkz{lFbm4drYAvS9IYVn=Lol7M-H%Y!-ksL+G3zzGBMW@{G0!m6Ino`^V!(;-M+Vvt~K3UvHl?O47BmFy!m0E&~8*hIj8`KyrvP z2voe|*rT*UGGMzH;t^%PU3l<=ShxSU0NdYHRtnxU8N-!|%}GZoB?O_4O$<_i41{Bq z#pM5f`Jteoaj-V&{p258!L%!NYC1wBU~S$(K!UznYb?pY%m$C&UZ2Ds;I?o;i{D01 z@X8I<@_$BM(3-SO_G!LlgXX>YZX2w0NF04CFE^iK^PuBHykcQ840 z4Z;;|OKAb^hF@7Xc-Er2+_1s_ebPrWNDrJzsdhPiM;z7#n80uNXlQ7@Vp~b6WU^DU zRNyu=AUG~xtm4Kid*98$MIDscg{7sXOjJAQrGAC!S^0pB!Y;Oc)#2js zD_6c#B*y*d)z%J(DR$yb;W|AdtmW3v;PV_dj3NCCvRB_ zLv=Q-Q!Kp_8WnTk+Y|aWTz`(+x6_->a;yg7I7GN~arp_;N!S~Ztw!o%rJw7Uv78$< z`sjmt?J&-%xcHbCTdTNfdyn1dDXUDy=eK7M%HGJ@38q*ka!k2T0A-8tz2*#dN>(Ue; z{|ByHz~r1%Te2czGeD5@?~XVhyK7uJzucAPNY0$mq_iP77|Yhtxa zRs$LteaeC5LpmV*9QBzrZg1W)eU!9V$qhkkZ*ragqH>i;tK<`BUZqGYEW$*Hv zW;=?OlcyG*O>jOG{4$Q5IPp-BrpbX}E07sdHP!z35xdXt|H2qN8~6J9DnPD;9!BxU zfm*VmREcOwZ=ds#G>9-OdSRvgTEVRhp4U@IJ=(Ra8i|{LMTc>mLhvAoY~)U_(tT$5 zieJy&cUqz!%M73{^70qyWyqvg4jDX{ath1(c+JO|L`f=Jq?}W%92pk%7~C1uTJ@}! zyn)Til`OuPL4b^pnZ}$lW5@oE=nl5PS9~n2`mU{yT+y(M(CwC}wY`q5)VH^yt~MWX(&D#WG=Z0)>c%D2ps&`(iTLV*hHi zoWj4HT82&tFc#esF8z>L1D|hl&>cCCu!`2QOgBU51Y9vS0{jcMFBFv{u!YeOV_n>< z*Q=6Cjz;~1rc9fL1@2{f#pJW}Ypu|>(6wC8MHIG=*u*1;fdjYhEPP$7T4=#SW_<9V zaVMk5-D?g62L8IWB2fLa2{sHUYtst-A7iZOFgaI-)2b)X*C;V>RO>!m|URBJ&=< z@?O`jgbkf`xY2UT1D}ErQo+*u!Q0v4XuVOY^&z>F*hS(`!Vfz*)YJQ)d3-F2QSoA2 zYPZbqHEc9g>|hoFETGr7_tL3PX#7BmB*t2eze`L(v6V!LhgjIb1XFn|*XrEdy&P6> zG`3u!?QSm4zfNR!B+tT4RzL{}5SKFZ@-}k+n(9~2jy{afO8bscg+pX?w71Z_tmZ?J zdQwK>Q*UQCO|5Lg80lm0*Gw;*uImGqg+N-4j`67;+sN3MtAsv|M0h8VBy)~ww)@Ck z?zk)c6^IC(VEzQ>-8WQS_*8)Fg6L-1u*#?FI+BU9xta=bz6WajftuC)m6G%8;`^}> z!IvUzrIp)n)Y3`Rs$j2el!XNxz28YnO5QZWi;9a=GRhXAg5f5C_>?5BXnon1yTz4z z2g=kgO6&a0KfE`{qTV$K{18tel|iSJa&1>qi;-{XZ255H#`uPCah0EqMKfTXf$VHE zGkln04VU$S{jI5iu3u%JU({l0csLjw6CGGB+$tWvf@8n=S64avUT0kDh57SvrNHkvee0soMN=n3(~)~TNj z$)1VRZQ8Yi>=XcML#X*04~`hF>kJLCWy_Wi!gQ}@OlC?m@_AcK2{_^yT^2d7BZBVi zY_)OYjwYRaIaq#g?%Lnccau(iZ7ccYm-8MjIC8~BY3|nb+j~hOR0v^iG%le(5J3L2 z3O+_}2pSE3pJfy5I@NFpCKTji-dg{HV3ji`{1xIDl*ezd3_tA9l!b!K}WozxtCmBA5 z@wJ2MUE4+1)-MBs`LupqZZD3)&&yCz;HNslqv5$=%n39AQojoei~sRCW;EezbxLM7 zQVxP=A(aFQmf3UX`uqAqr;XC>sO-&$IJ59-HMtXuHDTV_V;JN@A1sNKH2B;pqw0eA z2F*`w)rI%VYA~z6ytsc5rx%8!YBl?pN8q4~-3YqTZCHG~68Y z;lb$iIYw##k@qs+GUCttQ$T6(r{>2Ei}FQC%BzK99)1Ae9P%qq{HnfS0jK*i*%C+JX=Yhn2p1t@do z%*^{4|F+)9X-D|MsKf)yY^vt`q9TtnTT0-Z_gBZ3+cK6KlYB;_Z-%mW%6$v7qkf@w z-d@i&&eK`ovI3VAAtG4lp`084s#N2j)~w0Sy?ZA^&YnXpd`T8E07H-Hl>9w?93xn4 zFqPRPzpvhHr!>&O!6qWO*d` zIL5jA1XnIGzt5b+oc9*@DF_%gUw<4FX7(_chfcXSrO3dH#q+gZ4E0QEO`!m#xoBpm zFN#-Gy$25&^0?oS3;GG>G~nG80_um}nA_lNmX>a1ZEf=HYNdzX(=}I62c4f7J}2?u zvq|;ePA*=>LgzhBXJP@m;rb$;mF*>-l9zI~n7EwKcOGJ5&Eh7EOn_xkQC{*t2bIIM zfYnYus6YiqO0&$)uIND~S%X@`6!)*?L1-LEN1U9T#+;91N9%bsh?W#hDzf3D;O|DN zBygaT07H24l(7yoFL z4en+Ixko6Kc-K7BL7Ib4!6AbgH1{4cNGwd&@6-#9im(Hrgg6SLZgXfU1D2+wO z@~_=Ja{TyA|1i(~D$-4nw3pb6c!j-pTyOia(p827Y z$EEHUC|ZXB$_*LfQnu5{$iQF^j0>mzCG{a6D=R8ykNH?QQvGE2!Uaa#0^g*0nFSY( z@uZ8}us?e7v`f9_RD3@B+E`&lU5#v6#A&H-g`mPE>Ge z3$Mpbj&2yAm1c+~zJb!({Vi!f!4cCGocASvtFy+(Bh^nKNT9cEXQw?v-CWI(4qewK z2FJ@kzzG}SUo;uV2J+bbjTv?&o-#UcX~@>h39e*pmX>#I)XCLp z@IV^k5TI0z=_bo(;&>u#(wdfO2V6DBceYhTGfCY6I@c_8Buk{bL{uk+_o+S9D4CAu zBJd~TqMuOAj-A)a%*cQ`{)W7p#`S@7Z)$&%3lX@^yhz24lvR4IU46wQ_M#UgL#L)Q zxqQ2}f@D(Fw~xj1(f2?B7m^5cz=KW`G?4@yTi#}>l%gWB7xIHYFf?(Eyhi!idr+PU zbDr^71Tv#bq_wW}IZ$45utW`{zo{bQF(lo!oHGY6k{Lodvt}0RJGKVc56eq1q;}1o zKmTxP0u-1!{C}9<4HZMkoza}4;Kt%4>G3Ue7pV}l$B(x$E;-4 zA{#N_Gc9f6WBVlNjVRu9|DFrK;n)ccJB_?^3oh+G*Pa$W%!fui)PON-;flHgGCB>| zvE`rlwQzA3%$akWVR4mNIXQ<-<<8Iq;YI$;SwgspuM6_5|j@y(Nwd=wlU}+YWe)2pIVk!l~u!8i+onMH~k4? z-_9f_KLgUZe}5Pw!=!urF}@Zw8L4j`N%!{46^NLFse?Ghd111;{muHZ-g0DrDTeD4 zq;znJJ>o5)p9K%1Em!~RSAOu0jOAx(QPZyGmNV74=NQ}e{$A4zisjqx;y&=Elv^(6 z@#sX1cRCSUX@wbN6bRC#OTw;RR5HrcZ^ulnrcLuXt)^A3PH20i z*auCE9A=LWk55w#34Ssu4&lYoeIMWj!!a<>|3Jk~b)LPBsUzH&L5w&e`f4A!De`Jg z0E#@v6LLB|e#gp1s9~Xmf#`d3K+z8$bdeO8BJ|`lu`zR98JG;1kLosW+$m;&|K%ED z>zv7b#G;OOK4K*W79~3BeFL;{>Jc?1y;aJIRgDs8kCu$`X8TjzLiZb8w0;mRKs@V) zsHvMd@wydgq{^|t@6-A=mJg_-b5BTsnl3kD zE>$=5&>&6&1qB9=K6+@!M7BjxuAzPKA4HRZOWM*=vTj$#a$^tOQ{5pa;76?tDsboN z)1$6l{bG1#8iWSiZWhTtH>EXkM{AulrhIA#hwcvPp+xV^O?RBJMM8 z(%070fPiy4{m$~}hNbxr!X3bHQAjrFXQ?3fbK1iIL(8%KPyJ?0eZP;_^vwYDDFz@v zd-fxSGxoj4$RA^(@0i5^AvDeCp<$k+>`gSx0J+26j|(i=Nv(JqNq{23!JIY(CwsWw zc6ttai_QnhZ3HbQ6a4k-*C*J1nkqYuRdF*F>`mwnnswt)Si?4;WI`1A?ba8A*d53g zpUH$|Euz#0jSw-{^bIE}yB!8r-=>)REYxf;!29`$=bd;?^!>e24x%6+<}Y4&$J?}x0C@dbPl6^nU;wNrK?aMse6zlC7;Qvu@!#m1 z&Y69B;(3j^b~sMH*&Gy9scv4TzWfVm7_YkWM9VV}jv*ktxV9mk=10lHZU0js0mM%n zI~K$efOAtIgwu~IoUedM5A7ftaR>)`k4I?B@E#1+E`o|)F>MePQ3!d}mt5W`m zq^qMqM8Ob?vO%&@aD}|4(cnDS-;d37fJg$(1tI#82xPusj=5#QCa^d)lLiVF->dVZa~Fv6{U%i`RW+)k9`N798FO_MQZ|^ieAe8iqf~MB z)XaM8Ox70|fWaQhXn+3>n%!0KhRJyHq62PPA)FJ-29Jl>4|@g^ ztyL+}x!0wa%#q)n3p{klcInbd;*tyL((dr_5zeI$3!029JP%iEr52+!M&a}Q)LqO^;Ki}7DUdW8k3rZerQel3`L4U=qrOgUj zk9O$VZeQj;)kBuSmQjXt%s%XqaSQZRj2avfF?eV5?xXte9IiC?(9jv@7nXLa&AIt2 zLTUTp_cga(TzK&Ohi1C@^9k>h&*H)aZHW@-S%)#qpCS;%L%gI4g*kCs{Z82aY}?pV zr-C;a3MYAeIl?&~e4x~8&}NAtC)a7;R%qXQbm_7Q_9HMSQ(DNdA27RdTkjf1&>_zU z56^n>!ULkq*@+h@zK}8U^^!$f>p9g}K70NB6}8tcdf%;GszM&hli(vq#yS)XMyMu) z{nl^`72E(gr~w!^7?CWXEzeVY5{`wz*OHtFy9nC# z2_zlhheMT>JNNBd+9CBL15Jo{P7t=)?P#EBPo6uG7#;_#0+*ra2)1X9oI3n6?hdS# ztX8L>vx?biJgn2hxZZQ$=#_G2;2(on4*SE@ZH18onNP+CtRo1qSdTM~B6Ppd7^CP$ zt}qDO!=HAnnFSzhy?Q-0K4`GSb8)`p3$g~$x9e3SHxvw?9F5hDjmCQalB zoNQn~aD(i%YT2?497O>8o9&u$JJ2+fPY6Z=(DpN@4^$d!(T{=qjWkr?L?oinxY3O_ zFIUMWRUv=<&Dq}>+vRNS7fsKWNDJ}l9miYwMo~hSKs#%*#YVM@KVxNYh5D2?LT7vB`!ir zvTAB);g7aw2FCCC3m1k~sw2)%!5fU;8&J!^TT2P0B#g1Y(uZS5to*d<_FZlfD}q&kh}Iws5+V)@btgPy5b0|w_ z`>|8boM>yZbftsm7WBD2eA36Qe<^vqi|osvw!-e+nIy*XBg7-D-$T(&;&AJfA0d|e z)>0p(FxXf{c{xS<88ozhV>l%`^&I6{d0NWRlhp6R%N68f%$Q3gI>-bzKN=1ZknCx0^Z z{7zceN7JEzZ-T*Mx>=2~4E!eI>{%>af4m5r`yUs;n1uB7YOct$)Q8E^{0`^e~@bdTn^R*%*I{FR8z#!yd(7t)*?R%+vSN3LIxBf|cifkRsoj3+f zF^zJU-)b@U0gWIbspqt#%(}Wl@dQhN9Z%|`2#dp47j(tm!Jz>rJ;%U@^@+JfN+RuE zG{Tww4R94b+o^XtOUkXulDBZvA(sitlJvSy?Einaue*1UpO|Oa5pRmh;HIbjvJoiA zlq;S#ZIFgWlJ7}>_M1qoKpbIi(rGZBJ1qXhnQPa^!oVSers+a6bJdzPebBBEYwk`d zV+IZnIQ|??TCT_GKQUKsC`lf?KJq?JQlR$83w=@0v-@crU~rkH_(>hRaF`tA=aAjB zov%@AP!W=U*lSq%RPDMcGmIAW(SU#)0Hw0mujRlkOSel+p(Gcx6@9g8iK-(I?CN3EdWweC}K|6djh8 z%1QsvQ_Fd#S`a*)bOeu{Dn25a#O2C38b;6uDCas)<6_HmX#F5GY#FLfh7QKkrKPg; z{4b0i5_RQ@R`myIV_H%^6`?R_9j%bQ^k}=Cmx+yu0cok`kcYdm#o0ObO6Z(ULE+(z zBxvkk#v5=IRz^nl%*Un-Wp^iCxnejEnu^stOUteJ4Uz&-qVnDAAjLsQpVMRN`mx6m z7jAWNLB3YWj1`9$O6_G<0AP#CoGSQO@p~?jWu0^PuG!qVj&^5rW0l2)l1w9UBplHU zjTINFg~X$%u#iLTC$~BNoWR4A+rX>>MugPJcm642RkhhE$K{Y5lQt9;Y2!!87rf}( zzbLuN&+y8fjQohqc>#VnVo@QLlbxW`|rE5;ieN?#GX5Nu4FG ziu?jDjQeS3Ef5i>gS66Ru)7^~w<`bv2^|<}3w=2{sW7k!=^ThkW#TL**P3&<2?mmc z(O$8m%;ibZTL19Xeg)VgwIC=dgW=K$xmctm?Q!$`dtytR)YP919yF*&-@bbGxe=y)egeA*5&VxI;eZ?jVppSC@oUpxt!KM; zp@it$w*la_zTTA%8krm~j{Br3J4}P9BJAx!wmFz|)RE2YqmEz`R5;axk)$}5^6LmV zsct`mvu%-V=`UH5mZgHpz@?<5@l1x&m1%r!Ox;nP&>}e{rFE-T8Mki>@xuEvl4Mf$ zL^@Bf%Md;@>GLWlKT^)w)&-45GiKoB&ERk#!=j?1bw9>Z-3de<(bCynwIZXt%<+Q%mx#Di=ouEZY1@{wyN#@DQ=)F)sk?7RC-qST5coct5?WCrbjo(?UvX~-sX zZK828gqnh#0F@fejEo81xfO6pu{?QvYmc(NoRiKUoFIF+DzO!)w-spH+NcW)IRCYXh_}wjjHi1F6mQojXZmA#j=)p^7uiWM=6;BTZWFxnpFI-^!%X9;S z*EHf3*Zt1y!90o&ABF=S6GwSu4|`t`89N>CwjDbT>~TU%UHuq5OA=5HNCsU!eysoE z2fKjVLA%Uca~+^tSeW8plT>$hK>TZvQveMD-P& z95)gzJsbE1f@rD~)M<}yJ>DUzB{C>d-YasBsB}dixt*S;1L4aN(G|3MZqY&Q3OHmP5^*|my_On1WW9#0xrdHKDT9lryGGvG`A?oSVpJWS5 z`dqnot*&+hspn2FFBlN?{J?YD>^uSq8^ha|+~7X=2y!@NF-67CZ_TSd3-{iCE6TB* zEr|WEUWuLq$racu5%-I}`~6JLI-nsKk!+47OI~m&VTSZ&)=!KbTk11@0Rabn`bVq? zw&MuInn%xmiyum|D6Q~ z20}Np^x?yEZzoWTF#FDK&6?-8dPU}>-z$(T(WdW6bm0MP9u?kElKTf%Hn0P}sC48F zq*-r_>XY6Jq5_05en5{?C$-4n93%A3}t9yNcC;0pI*xQE-{nmal!UT%(raz6^ zy?^p$mwX?K^^qP%I7(0GN;gAhu(^^|+)Ytj>95CB3$DmWlnbxr6J%X&$h5 z@6Q`X6wlmPuBUU$L>QW!n@Cc&yzbGvzC}l$E}c8SLebK*r@*u+>_}@!nS&~mZ|=;p zd3a)iE{-zn#_GEB?ovH3p-K#w8ZzYRzb9Z9f_xya1qJ%_GCKEtq_fID^C5bTcdHvU zbZFbgm}Z`(chl2XAatM`7bQR|&zl%|P!WE%@UuBNn)c+x7Z-=@ zHH4i@=ryx$>YGZwx)On)I#c@NEEFd1_?wyzP9rcU8CD^C6E=sl+k?J4(_f(=!E=e+ z5+Nr&{z@VEsFw(B*#Z|$ykKH}YO$F;``|J9p@m(Tkx||2Bg4Dnmi3i`m~-~YCA$D`?{cA^_{9-ZJI)x zo$JYGE?t_O)Y+;8LbQSmzyRwf=^`u@TG(msTGqr8GO2cYXnYMGp%Nyap+@8G4T$RxM zVPXkkxf)jyd3kjV+tp`jVcvgBu})io2m#^3Z9^cPXc*|racM@iL)K}zx|J24;h*S5 z;8Vkc$t@^YBvx~`VdygA&m~-@OG;XeSu{zx|3KeoS7+e{0)+{koEE3Tp&#w>a^uhf z3e(XW^0jqcN{5I61WA$4ic*TxIbs6wfvW~|nYvk-GdOh?Sv21RT1#=!%Ym-f0NLf3 zEK^ocTyR%yPR>SFY-+myzw{P zD;E|QW3})$Y_9Ux(QH>@0}Og}P?T2O){V~2Ol_&0>id2D_2+EZez2O+NfBkM54>nV zQ-|>{TB3UbVEA$ZsywGZKh_&P{GIo^8X}4sUE1bu=1ABt^;+L~>Z>GIp=Rq1N@zY< z$KD!yDy_J`t~v}Byq2VK-I|dWaxMK0v9wUv)C`-j?Fx|t6*mMH;Q7Y`q$&`}B#+x= zH5~jboo&2fN89FG$Dd%55q%6{gfY>hbg!|>bQ@b+{=2r4k`m(+SObKQ;^JS(iK-6R z&XHKF4j=BPBumxuC7s8fMqeMi8CYe|3UktZV9v&$IUfARLPoCxOzl*!@YZBY{TOu5(ZPo287ov6+6%i8 z@u}86XHf6Ejn~nE@}A-2Hk|@2dK`1vghnNuQ&dRcOV?S#4|^A~_fDU_S5)*PVMq?` zI>1tX#JR8__r1Ud&d}aM>RibEvfwU$pbGmYOBpQV$>19IAhAdG2W5^6Nxbn*A@y~ zCNFmENZ=rIKSDqtZQ_^W{uDQ&!^GxE_pqSkvHM-=eb%wIPiaZtoEJDdFtd0h9ev8G?2Rla?D8G{?a%tpWV z;>AQ|WpSA>777cu5bFS&0ne?|+#yM&a@V*)yLTI&Px;hjLocbnK-O^_FGy}M^te?& zlx*&2lHdZ!?(!CX%E7%N7JG9P-@c7+l#Z@0${h9(QJhctgR7--=A7u>rAt(@q38L8 z_;~E7zp-{Gh3`(Y*LX%nju%Ade*GGM|J;PRH8gnUnaH(Nrcfad7XIA}F2b;Q&vt+s z3rtF!X{k?>Lx{EG;&?Me{X+eF=8T_V)T0Wg0Rv)kI-yk>yX8YqkHtHcNM}paJSHx` zEepm)8buA(uH&za=Abp@PW2RpG)htB;0-$|>JbSJ?TJ?Xh#&$LB;-&&lksECPmR-< zv1yHINJw68uJo5rqV-4a0?Yp+T1AeQ`cEE>+epVafWZAhPd`ycx6~JtJh3AJsO+DU zaPy|H(P2Zq8Nz8H-!c(a7AqM7KB61A0FWjlYFAH$rLD+(LXHbsf>0yo8XK=-MSx|k z-?BxEG1CVQL?{3A{ThTP2$k#%3ghQ{CxpVe5*>QjSBOx)B<>3P&Z#*eUp+j{tK~^q(U|c!-304yJ@Ly=@c9mCcXeu5V$DbFU}kXwPzU{@2$+!!O;vr-v$aFN3|fq-gdI3Q$oVR4rfcGxu&)BNgvG= zNML`shq?)p@=h1jHUH^x9E&3+2Hn6>GD2GiJtFNLvPo%sCnDj3<#6}Fpa<$W)pqom zEawgM!3o0)ZXu;eVPWPksW6||xy{AZm5$n-{QOHQk1{6D@l6n~#!WE+AjU100iYN0c<{Xxhgq_+|R87`kWx4iIcD5rimHM&&L>SLdtwP6c z=zr+YZY`{FMd>apyT{)j<;GPeuWa5dny>SV7F2hmJf~FIz>l(@P=c-t)4hgE2!v*a z)2+7BUvhop08Pzqv-{W&i&kiM48^f1)30ra5~>e6cS+M$u8aY@;MCbx;@Y3ncF9*4 z3o+pnToUmA%^S{4fCsGmzG2GKOF<#OLQMGkuk4nTYp^sx1Q>DflDz$ycJn5J51c#N zlx{5RLp^qUREE3Y#E0Y?Y1j~2v5Kd@5!U*acjY5yIs7;oMIS>&mh!0$5U9f>C{Qk8@UQ>&hW5G0p&w@!ooANwvOdyQK3WZ6%NlL+FtkC z=IXjQWy}9z?M=YB-1oNctCCbgYKan}G%O(vR1^&~NVTffq>ND-D2gI;B!o0aXwt0G zK$B>|(m_XQ+$~i$^vKQ2>-lrA@lqQYzY}8b#oXkv|icpZ`kCln(y0 zl(NGiBDMF;Y<{~tD((8HgL?cAe2n9MHhi-~GX`$p>EUtNIS_CZOZA{}V(7IqQ291|zaPyw#QBpK%3zBLSO}bGP7ut9j+5Y$!!1+fx}WVJ7@JX|QI`Q3 zGEq&%e(=66=aez!MZ9HJU?`8h)c>b+ojO^C&_Z4lmtN5U-LTz3Dus;^orVZw=U%sw zA11anj|@o9#jJ40mUw6J&9`|nvcU#ZZY*VAdwPiFKhWI)ind3^UsuqL78F>vK7FdB zq{I;&K5Uq})FkdHA>L)Bfk1oXdn+neeANto=y0hSFV0d%A4CO%pH{7V|V5YPz}?Sf2t2!4J$U z!@K;1NEUq9ibfM+HfxF(32CKnq2XjnayM}1WQeAR#x=sMy z8cO+$332O%<9RD3Oo-=9Wk`9m(a4lzK4S(3v*P#)6hXn)hoS9pH#U)DgS9944Ur5q z@7zS7n$4b`fEce)cmldq-YjJY3Et*35*R1UTd-hiP+v-`lShtBqJtK4SJ!ylq=li$ zMo+zKy?Dy~)tFo|Z5NuX6wLu#YrUIxm`$Ia4g5)M{jQ?o<;H9JG$}|>_+8_8n|qc? z;{XmNicpb#-+dNz-l~G!OTt7>OJSy!mCyYhe}Lj9h}7&Rkyo2HZ#-ZFM7DU_eoIQ~ z>fF+`%1CR>HAwl#=dDB%1?xHGri!rTlsGu#1LhghrsETE-&TCsAzaA^Ps}0#0YR9p zjQ5fC<>mQrAgH|nPnnA*;*=yx$Tl}eRd9gyM~(7ooyPFUtXZr@;(861I&$-7OwRjm z-aEX?Ydd5g!|QNVxM{ypDf85f>m9_lR8&k= zd;td|s~g#T!xylhlG0|}eIaN-g=S;v3mL=#H*z_?hO_MlOirl-y9(sbwSy`kDo>RQ z+`IQBYKJU?GD^3%Z^~0<6W>2VeNi|Q5*eC)F;#3*mn>e)d^Cjir5{6|LOg-gTG1o4 zjPdB!fAFM@9R#BcL#NzX9Hd z4E7&R1>T0~e=&>PV)zNz+{)7OAtN~LA7}zHPnK*pcA-w`E%XVJJ^J2zQV+h5V#Y~cBt{rdSfI}5R>z3Ur7ZWs4@?ZGz1K2RC5ottsnA3S_->rf_#0nt z(Po8a9P!}Fb?e}k($EH5p~3oeotqu}&cy)eg2>5-1j2`M3JOTVgvmh$;DP(Ssn358 zM57v+|LSc3dzVNH^j-O{UoX4qF&B%S&lSIzgcYY@Nw3!?B<@FMP8mlfqV`6rzh6E(=b;*iF-Aw8j-OBjlbZ?a7n#7ndA>vc5Q>QI)b9a~R){XhuEq}_MViOqI1x-n^ z+sD7qgh3c-pS!TaTyvxtwbk$}XOwa)aRj!M#Zwa729cg+cgMxWaY5NG)S6?h3p53v z(bZp(YeZ$tBj!T_1dj#ZfAOQ{^Mv5V( zoRcMpj|0Rm?a}fjOAdPNF>bRWi7#@v{)1h)94qn~4#I!%JGEo~95BF!0h!+f_u6O3 zR>QAv`Qdb^W0Vj_f%EGIpnI6=#8!X`_y)0>&-ErSah5oZ$3^}kUXeY$D7`E!SnS52 z4OphMWPoMHWc-Z5)cEA)Mi%70dWEz+5tXKI611S^(uX`vhz&hMQFeV>M%*2cKVGiC z<4_QPot$ozmOSa-A`|1|L}~J}xZRVCe(rVL|Hxnu zA69|I>@GNkQQz+jMtykSAsJ81sxMzet6s>RuR8F+Ll_pFtbH`y^Q#w zCOx5uH69BdCaryaYayCJowQ~w{%+CFAxd)l;amg~K)bqf)ha5sE2mcEQ&DpWFjevE zrxG6!xh}9(w0|I0ft0k9)!zI@ur;#iqN{6^#3s`C8Y6fRqGdn_78Y>4Mz5~}(R_P5 zVpl(sH$}hr!`A%4P!eq!^&_KJe7rE(#5)V63dzdPufxO~it_j~XF~6XY}tpnh#F+W z`=NT(EbiLN;gbvGd~uCJLb5>>vVSDfoSr=2hm#k7=qB$Q4cc!gfSQlwK}Sc?F78mn zuZ3dv#`O$MqAKkLIgp@E*hHPe`iGj#v4U~&-)LsJ$Wc-0_IgD7Y@cjdnAofjQGtQ? z@a1-EeFfEvH06|bTD6F&?;13dC<7Bn)A0JmGlr*u#3&=~XJ%ge=x&r+Q$nZ~t%5eb zH<{??rct-rr>*50%YkTl@OKuQiTD<%5J*$XN0)h8e24nRj?cJGXg+C@k;KK>j>4>X zf>#Pp;>C}Spe|I*ycrP$B_C@dfqVX3s%uvus7MoiieKP1x(l@f+_@ikuEpK~m=1vvP831kZ zn7$T=13(FMIw)azY=FcsV`1`)U*T}hO(L7pfAA~VEB}>{N&SwDoQPbo77%~{NtRP0 zvw^noJh4vXLtu`wt@=w@CKD`x{+}B58{58^7YLfpR_%?H$iya&=jGNR7&y`Cf&DTL zDaJ$}TDF!xhaQa?ITG~r9(k`l)wBTi6L;x|5$CnHY~y-GXZK$7&wkD?zASQq(CxfR zn3}ZFG>rq>AFR0di@kXh^KeR0$G6JK2~UoEB1sR`2?hE2imR@Aqu#Bh+@ZD{5U0Wq z%9Z3I+qJD&xpMm;Q92p#Odb{8>hU7pzCCj9-gTQD#~k{CwKhLLY->?YPN?b8jkCq& z(c&Z{B}I5R8GkW?WlBpijXQ241Zt78_;7^zmAl5{8kTIu5K3 z<*>iMW=AnJX2b}pzl7_{v1~z2!^|Z3Hv|4V!^5%m9I30jpRKd>R(u7qkmx)~2d@UP z3`4_!Q(*&t0oRF_UOv)^%l<({gdlE71>Zd|(WjM8ktoOjPww}}^ejs**@wVlAf%)B zxqf}jhR&ZvT!3BOcnZ=><>k$#jXhIIb8;IM)!(0)5IU8RU{bS)u8k|mi+#Fs6z@J| zR(nkagZ<)^$sr1gbI>|^i1%Nfqm?0BRv+Gcz`Q~XJGQp+%F0^m>Q7JD@eSBmw_GwH z;r#icsqamE0*H_E0N20Q)tS$ptvYI@Tst;t1=Nd0RGd$%xS>NtseN@sJ<)Cjn?os(5-fAv)!U`)gT$9^RdW439Q7Hgbbjf=&#tdSDg)COy3r6vb-Ut?L>b zQlaqR7_SS)A@&CpE95P`4R#aMBfjHAO!I%Y4Ol|OBGlyQV zqlezo=7BF#VVl0af7|bO=EqEgRk1WcqOkVrsnx4jvy&O4ZJ^h;FPE}PZsw1=Iw~MM zu%7emCI<5C%m`nQ%_4700oI;dChr7oW?_hCbjX5cI8-Sn>+^T>T*L_V@9B*6(I-B- zjeEJFqwj>EocByz*C62G;16v_Y7SE$Gk-i0sO0p_fC(aiX<*R6Ux4h2qN10kc>_%b z#Z~i*KiW^*ko9b|v_eEfv=gO`-EV9Kg$CkBo4f2*-;G=#Tw91aef#yJilOiu!(VoF zj8jM9Lv2G#Z_$FLxb74)fE-Bg zqJ9qoqUpttAHp~S?<@o_&>!fycx#o2b+83T_}Q!=$%xrp3T`+I678w;$DaXUGB|Oy zspjiV&08m*pEqqxWk1T#2S57`OqsRA@W9X_-Bjg5Dmp7V}@!dcTZ>34s1 zX+;jJNk{_uf4FuK=J>BUh+D!U;>psbOTlGeBKWV%m*XNwJ(u6^X58NW^F3$rAIL(~ z;{0}g7M!16uf2HW2vQrb3Adr#_@E_V%q3Oa!p?zRhXVzlU2h@NXmQGAM)f_X;iEXY z*!1cecDbIRYh*t*n6SQz5zW<&s%NK+R+muyksom4Zl$q{{u zH-CD%pNKb)D~G~m1d6WcDlNAmMq!A!vZF98yEZOh_D@BRph#CH_ zU4NN9px^mcQ)2+a8fyX1w)NVhw;Kxz3*p(pD>$raDR((l=sEyfpB6|JZklyH?fK!b z3|CBdCvK`*gc|?_8CaLQMdA9bAIAzU1<2eP#O*VDi5vO0qWz!_i3i`*^%l#aW4n<=FjCF$Bd;al?iBAwQWc=@uu&{`T%qR1N4_^@Ci_1aq{}x3qTjiJw`7cEjBo}a( z^*qymVZWa#XN_r0fFH5tXJn_Oy!^6tdPi|~CbZ+qPcV(l3UGcgI_1$oqt{Yvp3?62 zrULcJc1T7%2^;1RR?xqk3p3sL?&h*%FsM-TaAHnhr?!G+ggEmL*4?9(2vjy28v zqC(=M^;wUO{ma*&a+_~X@kMAt_t3js0)G~*#Z@#9~5z;Ssjhd9+_-Ru2`3JsWb?>As&H7V-oVr?c1lhcAZL`<(2WW$dPDv+2f`%#AD51 zt0}%R*2%9C$cXYy>K&9sW*}TGqcPfBx@5_?v19vVu+~4AwcM*Q6`)|H1X-K-O0q@S zd->!xXd`i)L`7xiN)4fI6ZIjbE}dW^O|0+oh;|KL^@cP0ZdfOCW~XE z4KwA15?Wj6vs>sa=t6)q^;SI{c>2$dEB69rA+Tc;xldb@73?{Ykujc)P)CKuZNeLo z_~s9--ktEKZe#Vm%{R8AG=a$BXF2$`l!JCo>DZ5vSDOyH`J5_L<8*TuIi_C>_GY+7 zMMmP9G;H|ruOyCXVsThb`J3=^S#$*D&3fR_o_<6<}nw~ zHGDMIGecgW^yfgSN&N5xTq;gBnxM@gGB8>lNsyxk05pw`E>pGm+TLIq`l#xKG&D{S zwk}$;=4^7ZD^gelD&lyJ_w0=$A?6@$#HI7w4*wd?l#OWf!Zf_x+Q9R^Tp|rxT&OK{ zdx(#Zh-<3UkO<>NMRWWH;rnzAiIrzK>kMN* z!lp0o;oIoagHk+Yz8^ci#DeseWboa^m+YrA$by1{s$^oZUs~TEw6~%td-do~>{Qm# zNg}+t8pJRg+uvx*b4F8nim`eI!h#9adRf&{LljFir2OyOe!JGW&(Ml4tq0dc&+3xB zHa%Z8Rc1r<>qBdzyQ@dPEw}xr|HOIT%Oe}~^`@=EGdW7%T4Yk%G`3Y)PFpA2chrZ_ zF1rRyI&y!F`ovjTvz59%&QQgHS{xgIv!H?aUF6 z=QcYt~CPjznusbl>TtWv>4VPcU@>WC2V2MKBwuzjwpnmF58w-R*z!ccJ+%in)9 zFauBv{WkcJ9*xpVCb^m2iv95zh|dZ`oE8=kl8m5iy2po;}ak>fxmtb{Ia(&K6fmLV#mG0J z`R23{dU}_(oq08-d#`Uv)1T;E8T%-_py1VK@HaRf{?wV~=A!>T#dG#0+Fptg7*=u@ z2FZMhru&tL2pCJ_B+s2qMG(jJ<6i?c6Y-I*){=u!-Or6#H9%9bpSp%g`N70llEw6#OlHxB(n3s(JIEcO4IIB>^e1Y3>I~6* zizEkKMS$R*g!}tX$~2Rdo8r*au(eC}kO4{(1N-&*o*Y!}-m6jVHvuDY`+h^JaqAqW zhuR)x%^uRtRQ9cj%OKnIYRmMs-p?Z%+&kNEVCBqQW&;Wo%$2*Xi$0?g{nr1BWar7j z)U$+vIOp~d*v0quaHcJ}2!L&rr~u6Krv|@XQ%~4o+7Z#CMXOHAIglnGCy0 z-*=Fc7~$&^&=K@&;X<(>Mx+63BQ{zePC~ySnQDbQMmy9#KB*FzZU6o42>Gh%Uld!x2D_Lz5_}m#?nV0J%0Q}?7TK!9*35!*k2Xb(dGP9 z7Ku!Z+%638YHpaz+NpD9z{HDY&#tB>_^>YSv-ADvlh`7bP^>!LmfOT_y{aqVaZ^@ zx$a_Liu)y79O02ToG@R+prq5MIf}Th=QC4lA_t5E(29pW63lgt;p+T*%vBYn`NUO) zFXj=a2fxjDp&>P?=HMv(xzVei zM$cUP_4^oo1ZL5Pnzm5I=Y6aL3*t`GB2eEYV(lgR;}g?6hpu7_p}DbwOS@{->x^f{ zHI{Fd)I!E^PvLhVvoLH&zpxg(`uOo5&t^}=(`$@|hB$hPnsMj$?P^kV1_%xih(zgx zIojJJAcq>-TilOw?p)lF)any7y9(OzOyL4iHms2H&M)}s@Mls#!9W1qIQ zI9#$h+aa6_FR!2g7JBjM(K5Vi#=j4XcUJ48C(fm^2;MMp)r>iP2{ z*H31Hf_Fq@u@8%$1;G(ABg`eTJa4S} zPxpDzx|?8Z2Iv8ev7F5}OyzAWnbs%azmB!ZoKPnc(NimM!iV0!>|B2SOhVzfMe+;g z?h%P4oE1dLpnLV#ic<-DDAL*gOBP`F1;YJ{D{>ToV<=7JP|dNvkGW2n*OzB6Sg?_W zTZSrBEIK%Mn4e@yl8x$1KFm@{{kIli$&A}uE#$p!j~3CmFNtbU|3_ZT0;K^ z-9LA39$+gvN>t1DA3Q*u&3IY>XfY^yIm)0`6faG1y5QkU42s#mK>3581*s=kZM*28 z4V|fqO1Asx$S4yeSgon!QJeuzc{@&M&A#gLL&ANvje7d(r+0tfj7v9ecy_na`M&s` zPe0HDmZXMRuDq1}v+V`*;bEbYIRqxT`%@s^BY zEe20qZEYP11aTAZ{I@H z8{8HC>-_lx6&CS>CVn>+yx7zK^c9idjZcaz#^4R(1OnJ-Cf9w9a zn10QPP`2+edrB%b`7jN&;LTp4l0+lpeR@ z%a_>QyX~<$p|D06bJ^!}ZC2pB$_WwmyJlx7Y*F1c!i3%tM20@{dp6--l-U3``@|I6 zMw<87b>o{xi2d2fhg#jnXkvIF;(zRi0#IPc0Ui&`aOayXq`FFgZFH(|SLoe98jz$B z0IzsT_$Foi^E_AQ!lJX{;1eS&+wrGUWni6oB#*iebK6U?3H)f#_x`KR*|W)N4g^&6 zTX66;HiXGfaS?Od6L z`?4NiUUr)4bex^lL~3+_v-rQJibKvPwY%IF{iz741IpYOW*;Es-}dhCg$ue9#l=+Y zxNu?|pBfqrjg$9%z24Npifh*#N$u3Ra_f&zd#It(oMY6O2G~$q$PXMD5>0B9m*`1z zEEiZJ%Z9v}^zIY34aa}5kgNyEh6g<8Cc>JmKl&{>X;Nd})gPZ)JZl@hf)&mmj#to> zzo}_-^LfQ6{S7%*Nt*7{^HyGlWz*SNT;BNdYof_&r&h~ot6cEG<{WX7(_c-ZNxSy# z;w#g;&y%xi8dJWyv|~4?b)!DSA^9R=fZjz?K=G;7(X*w5JjQuJ)JIleYcd-0ijItV ziMZ1gyXbAlJbNQ=)qFw(;9oyr?m$+?1}QolJO2e(m-B&0NTrLp^dM~%m*n#04{q1d zYS0#fcy{cBUyU-DLI!!pCOxhQGbMz|43UYy_UNyiL1jb4SZ`(>M*8V6bVR zNtnw;TJ>~+uTxzID}-{5w>^7F22~5FDbMc3KyK3Vubj`1{mN)6#svESWdJWE4+9$7u*6w(h(cA77&8uPj+qR0N16 zq7p3oOS3cCawKmh{{YHjo2-rLd<4qdwoQ!~4Pi#s@7t#j!k!+3%~awi=vU=AqopFU zz%exEXWQ$+l|fX}gy0Di$0j0Ra}a(-MXA<(2v3P13BhGfmPh{X;axN#a?XDQsc!7P@QI^4$MZQ?lgd<19}C^ z@$NFggMz&sTK$J_({k?F^XC%1#=UNg1<{^nVZlPBZNrfykijsv!xKnLA@m=wFqct% zdpP{bc4h{CH&xhf-D+g+xQ1~{Cnwt^Sy_2%E9xxn0cX!3ZF5}1_dPvKfI_x&lIeMj zu(SuA0bI_@%`I`CQUWH;_mY;85v%-@H<*)5}^VpGbbNgdNL z&5$VV0mkg^?(S{IY+*(}6chACgmaqjCD1s#htA8dw1HZK8*j{1^?`{f=kG93-bn*7 zemMg>Bc`ISVj`1kzyLG79dPoK7dLO+q9hL&}7bqqKOi%?q}!M?5Iu_}@f zs8Mlkq}xDvoU)U;lieSCW^DcTuCw`Oj4|#YF~GnPGs@8W9R+a8JN2H<4KE@M^x2`t zQDX>%htG4IlmKsvaZ@6@CaqjK z#B16>dB9Di&a#fvs%HBHWFNmm$#dsG555m_7(^Me0z{otMC32!M#`SACNf^d!5Q2q zXlv^I#y^CoadZ$+5nsQqYsk&X=`NIf{rb4oe0ydYMCK#gi@;PsW2Mn99j#KND@(uR zX;prESs7&X3s($1!J4yGrND_nuJzdVB0(8b;+WEX^Z0gx+OT0eS{}l@br5K@I=%kJ z^cO3Qs46eEX}N|ZWKO8}$SPXQAx~Z6)BlHJbd>V2eSTk(R(!4Qv+qJ@2?;Rqrng6v zR3tk!KGVOGSE5o0V$neWWUtbhuPvG1dG(#Npcq*ggbu>|VS6w|Jz(y!b)V;IE$_A* zV~_KYY`iRfJ44=AE?%_hvz;X{`}Lg2?pl`HFp zJUdQLnof(b2AG?3!Oa4W-o%&=g$Z&wao0y$(kdcx*2=l_=9RsF5B@z03lJjBxA8G; zPw-RWa4|vCXtZw`(dq?ir>>)RLDmB3gP^9N2`bd~OkW`i#tfm%8Q(0{+ zCt)JlX|GKR{uD$2{(!Nds+&&zK|-Pg^YLjDhr+P-U>3JHU0upQY%5aMnh0hrbp?!E zY@rC~A2Eciuv`o5%gw8t83?V5@I{mLMGBv3Dg`H+$LF@$V@<{Wj!joMKW+T40jCiz@S4)F|$5Zs>A7#wI`MK`9^zFvlQf zl%cpE-&(3-ElsuFL14z^lGV2RFAzYaAK%t08SS~+#qhOGyYeRF$5<^R)7CR4-}M)~ z=b{O|;8)-N6pl^&Z6MOA$%bfrb~M{tP`dY1R=#O-SJFet6jsLAxP)heYKTg(vw*XN zcWbkf#r^Ih4-GI#O+0*9#Vfxuh=IqLmQ5QsvW%mX0MqEslc9y@AvUaLPdQTtE|?e7 z#N1{g6DV7EYoNL2p#uk2tzMlh>xrij(+V99$K5M+;pL0-Cex$|*MgAp(DtIWw_?G2 zI!hcDPiX$kD^rec9rx+maxu(Hukjh~>XTM7_ue{*y%PgHzlf5`duznj-K25 z)10!V+b(H;%9n;Pw?)Z9L! zYKBbN!ByS9-FM`-^ucLMuAWQlk@_Jv7-LeFgQweGq^Ur}h`S8Jhr6~H@n~Q8c;#4q z3Uo-94#J|POYt+Pd-dJec0UzTMEP(-6(aixJIQ?tzxtVfJ-7Z;+6#>amDS#(r?ooh zEA;LS$G)$4a>JSAs;IBx3-bRO&_U58YS;*{$rn%Xd$ z{PSn9&ubzUZbKvhDt36G(r7{g!vBx1lLg}lZ*eR-Iay@BuV2Stw`qcCX?Q0!=rt8R zc=ZF@i%37XvZW;@7nmIKDpQx-Whvav!SLGU)Y`-glc`YHw*911M;quI`^B;QH>({pY}geB(C5WVFa} z(tDqp?-X~A81Gb478EvQiuyOc6~~2_n~cScV9adM{rlp4GRpJwr%si+``RgOo3xoj z#~1p^6p+QiQC(ZrQO{{Dy;=n|MkRT2h-M-NjpTPa8kC%aaa=D>D}M6C8T}t~?6^!I z-i~RjgLy@fP2QpLr-or{25`~2Amtk+IzvvoE7M*1vTQ8J-LCENCis_9iL;%WJ7%2m z4t`AKxq?lyT3Q9g-S90cWbNNRg`lN&MYs;F z>G0wG<>e8u(#>x+v7lLy*VkKML?XY$s& z3oT4WCoKih^_xe+>uKJJM(~*Uqf%DT@Nxd=h4~NsinxZ(kb)Hm6-g}lMlp;PD=}~6 z#WFC710)V=TO|H$9A^0Fk-Z*m{m|Ysz+dc+L0MD zIf#jUhS%xuFIf6{#FQ9WPl;l?M@f=nYqqL(1QyE0&p z4gzkg#%f5NsHD%`zJ0hj0W_gTDb_+~*sv}53Zd};&_!9mc@GbN#LO-SgA(36a%#|G zTzN?D2um^UrME^}K*XefLw2K2nBO$|(ZwAWiM_6?3=doB&(fw%s5VWFI&@HO17!L`ut%F zX3p%c`Mf?g0|6-`KKbspb+58?!?J6F#~CtO(Xo1O^WR=9#6FSTv_Jc}7cU#X^I31izc(;TyTClwi47l?HR_zKG z`);2RiqhilAbFO}MonwR9~73z=XJQWWG4Y}KGwg(h74gpO%+xiF?kuGgD&jsE8NM* zPzS!!(-ZgK)ok#99fM626#!=!Pd=K*ZWlqY);rLt+E%U~GKo6H5hMsUW3Y*b7D`$& znPkit=K3H*xSnQ8S;4UYy*xyTNxG#t*_;fq3~E=&(u$yVD88(_ebz6_$fzj47keUmVs7GuJd{vb zgDXKiOGY_DCHHQ$lWWI~ds5`E*q0VSC=N zerV~^nQC$+PgoXRe;57a#fg_VNqoeO)Lr{Yg1iPF#(Py`}gRyD< z`PAn*-mQ&}yk2Un@8hW(}FyN1twyo3%!)kGu3z)q744y56XNF zTGi9AMOxx|q~dSt8vUcDd3`UR&JkeuTbfl;3XlA0#WtF`$xMGd)X=3XtOt6LWXA%%sR z(@%SCzgzn7(IZGI@Oadh+@|eQY*EVj`ug6y>4hYbm`2TZb>$CUr&o}QI;k{|QtO-n{US|EMxU0m=I8u74bB>%3S9@kjG zv$K52K+J(~X_z;!lfV=iF(eAY<=IDa0J>(%ldV^qUnmagO|3GIF;mLR(vVdY6BPUa z2>WNQv-Amg{o=*_<5#G4;8g2Vr{M5JHQ6qCDbVmp(ex}&?ee;8mXZba0njl$w#eUk zdX5)-O^q#pc$twwU1U_=3c{wT)9b|*l+B6M;L?s``}FMTcjY2*N$G{qkdXB8=J`s| zx{dOJ+R&k0b&i3XhwRwVQG^h1=oHNUh88#rM)R{rjp9#sa**WBOifu+-N9l31Gb6) zDf06E>DCSX`_nXDIDPIMa+No9oe-*oNF3g*shLVj;u8}yt8*heu%TYG@uN%@hYkPw z>j-=pP~+FH6FNRqhJJ=^+&<+UCz)3ayxM$;W#ndRay;JGs|n-01CUFCIm4}}8=(F8 z+>sAk`Bzll@e3DfC{rM}Di_55=%5f$xjAjJy>G9cF8YRcdNB#@p@lhFMv_gs+|Art zn(gW5GK^;;u6CVy$Z+#_x-S$XIn~>@*y6 zCMlEM1r0k&`fJD|Fp|yw9lZn0HLY%K8BH}-4D_Q{5BllySbN#ue+NMjYV8GXp*2zn zUB>T;v3tYrqGk21>)CNe+>@6IoN#7o578`xY)U$13Pf^OcBWVamEH|zSXG2WdoA9A zlI0-!edc9;t+r{%EI%`V4vFz7;2Ck1T>I?9?K_`0*X&Y>nihCqfgp(Sbk#w!C07$Q z1*1=1Qc0DV0U$DLg>}Al1EX6$%i-lIf5FjdeE4&S>06l1ynEr0ySOP$xP+c;z>$f+kWqT%mPN39akMWA3=^X76k+f#$@ zQhZAbzL{lo@L$<4<9U}()%8@Wl;Gm-J{ywv$&<>5CMb&STwO=r&@BZT8(aN&aCA0* zK^H+zighO|A>8y17$Q4D|8*`U#e+spR5SYw_ZcmT2Ad;fI%SH7hX*sL-Me-LEoJe- z2A!r?#nu~E4cFF|*$GKo&QAoVYIDMY0Dy16c(}gfa58m@o2k>i=UGoE*5!aL!o*!B z7+Vg;O_dK@BosA987^iX$gjKQOZ&mL-o2LpaZGti`pix06;f_|4`Lp5D)-0y;3(wC zIVf;3ZP1ksQhCMBlvKtUh?(%%yj zskVrE;vRD*VuMDmCnvcmSd}*unx5gev3wrBwBE1TF?kTVnq|;L-f-z~<*a-crcEg- z)7`Gqn$nc=t{8BlE`oU_({(`Xc7(}gRzOE&W`wQ)TY4DVx)pU>N}l%gG&l7=+43>zJ)IZLG3(^T5qV}XarH4W>L0Xr#R{s%|6u#n z{SzYeL2R9kq$L$c9x%U+0-6twjYz?0NWdL+EK}l-9JxdkCV^r_PXH_W=bvt4XdkF? zS?0~12}t+7Ry)9uQB-+q$X&Z^vEQcCp+VU*GsMlCK_9eNmB0=R0;P?-(o-m@u7(xv zqpbWeI$zFSZO#`{`!&QC+ISv2PourD2-JTZH!+Q{NgoB^`fa=d;2D+=3Xi9-3iv7X zqTmZ&hm`7UmekCV1d5%Pm)1v>_HM6Zdko&uVnN|*Y3b#AO|$kw@qkIk|03w{+kQ29 zgNSY*i`CS)d<~agXHE&5aXib?M^gT2$r4kKZIcq1Tj*M$gSzFemTAhJ+lL3UCE?7O zoW;I@BYoDZWhW7CIXhLslywX_QaTW%Q3_z;;JQLHIu-1MK9o&ov~Q}*E}NQO0ovr& zVZp&zU-;#aBSD#RD;8~7{Gp{;U+I(dOzrMf2lt7^>QYh=r6MI&mi?vB&>Y0t)SAAn zOLmT+GQWWem8z2E6uK;>r?;W0|2}X<HX8ZFCPjq|AY==X{fudBuESI-|17 zA?~o_C%=m-8anBi&b3>d7vX?*)JpILrX}Rlms7n~KB1$5J7jYzBdllw2FsH?cZj7U zB?-TczrkER>a2WmS^dAY0B6sND=_5cI|>9A5iOxD($Xql{zF$&(}8-JfVTL8H8+z# z9ijj+d&hl>);;k&i3B1Ci=gtyy0?YO&jpjHWhu#)rn1e&>i#VopWB(6ZaCS}!`Wvz zBC#83KSQUeAK1S?a@sKpUiOQKr3K17LenD#tff!DNd5eF)wy^ARE2hMy0MdfeV=4H zKN>~)rkI!l{tghBh;(Z_7T5$j8yaEHd)9=CF$ZZn=>~GcU7b1qVvPiZzVos_DY13K7IP8U*%uM4cb2t?YoVBr90Z1hd$}&yk*ZLkl zL4ztM!Fpb6Evv8#8YCDmU#_y%z)a45AOjF@t~pzw_hB}i(2uk6c-u2o8itHu(lRPy zXv;3YW5*!WPl!auKmTkf-Z3fRPT+k)2?K=baYV789D6;b^Hi*$3<)&tr%rX9shbg8 zv-h0MpC7}+TwwdxZ`hzNA3`7odj%8XN-(-22)c@4ghLko-Z`?B(2V{B{+6&wQQ$wa z9}gO2ZIr$~JfnY8SEn zr!GKY15Zj_Rr-svYbhNM&>6`orAh|}Ll#3YU$MDXvz^ePo#*UZ+WI;k-*2wjoN|&; zw1heNAsJP%@AbCCoLT>IyQ{gW$M4fGcGEdcog>uiUv(kGzkK<3!<8eMuWzbkzFjCA z;1?sUT(S~lrz=;eHuKk0QzA;ccKNa(P;!xwz*H!_O3omQC#socPYRH%?F-wuJ>A;W zV>yi#4uR_GqUN)BqH6bTldy9QXuM$<(!)ej>XCVP7#6A;hK62TwINq}!sM~PR}%+e z@_4fhQ0-jF3cX9AdVqyjj~;~~j*l1SDPp=nnWPX38C2qaA!|E35TLv8(Ec7!H-6W} zOcrK{u0!e8H8(>ORyUflli;rxGYN&tj&xD8_h%4I{`;1OYg{gvis*>B(ykib#u zgHxes1wV_B**jH2a9O@e#oH?Ov8PLS@Q({>2fk2izYnOIoJ?Ac%z zsk#^}9d96#1Ebi;=qjGXMYL)*OF{B6QOt)H8H+}&RKKOQwR(c&!nV&J_Qwfb7A^l6 zlD=r+!pv5!e-2OF!X=~=4$i4*+6i4aZbxJi8*p}ohIVfr^&L|wLGV1%l~%XD@B*GT zqC6lpl(iTq{yGH(JVCZLJjJV|%6al*Z~C)G4@52%mdz7{KeTth|QukfaaRLES`)@O6aC*P(*()T!^mgKsS?;oPOT-5aZ^ zVfehY?v>uppJ&Wo9z@j2dx-n;)1XLltD^M4ilQyO#ckmBvegt#9Ry&ts)c!R#U`H2 zcH_Jp6FhFvpcPDjX^c(kDYy_o5c;DVtsy!~Y_2aX_kH?-UzUA4a+KVIQJ2VXJa*@_1{`ixZ zI(|Qg1d^Frbpyv4w2uhB!66vWLxBbl!}yILz{4P*{@eN!%^&8q>%Q%k zYu9KYiQAY(qJ=>**||#>SDiLm>`OLxg9wvc37l;NV|x6Eh}jeg*v|qV3C0MlfJeby zxqZCFB zFKAKFniH&ukIbDKO``VL!=41HXvQ}%l%@NmUN>0UT3_})_$3TyW|`+;y^Qh=bXC8B zUkFAL74E@+Va%FeaDJ!iK&k|C`uXi!9_ogMzbRnE4RT1a$%5i$M6zpBQxk4VJ8Pm- zvm(wWB$OgcB?1qW7wrvc0$ZKZ2b5=ah}JTj6f|hxwuGDuYn+``@3lx<&Dy4XU3w-d zc$Dl=e`(gm4`WoBEKM~9iz?yZpf<5Dg&aqTt4~7% z|4bVXiN;}l!}spmwE0*#6aBv_xI6Eair|huD2)&>2qg@nIka#?ZfeE0023=3gj(dD~ z^4^*MKLsUH-vQ%+LZSDH0rLL^7BwbjfO)sHv>ZKh1P8~OmU9&U%FLufQhYF;6r}pg zI3#Q|FN${$KK}I8t4en*@#b_ovkeI3_pRyHH@v>F*733B1JZK0Z5>dp36L;we*(nKj+g4|HGVTHjq@TNup!pD{BwLU8kb7`Xml z3QLXLq6_~r0Yc55~IQ2JZONJ~Z%jN#eZ*l(S3 zPk0p;9xl3jaX}#X7)m5b6P6Qa9l{+kEq#?0wp~^?}nrfR!Rjcvo4Kv>bfEtq5&f#lE?x*`gKZZVs37 z1$udYU8p@m+GTcXm`bHn%SMT$o5`8>1B3rLezbLoN?p?+H8qZ8ljjdlnSi7R1$LuS zMvfSPB$m?Ow^B07Im2F$EDSw^Xx!1x&b78;7L8C;+$$-;z^C;lJ7L(#!T+3=Hk!7M z_Lzj{)_Z{00AI~hCJ*+L$Jr1`U^o)Ep0XTMzZkmx%F0SAj#{x{Z8%Chap}@7*PS2v zK_vqQK=`w&p>jXE@=R;pi7j=g?Ruw`O?_~X4w2K}Gh_-d4WI-Oil&K{Ob`^MMMGWS zZtJZkJ$i&ALu}VE9i?QaMC&9F)gk>49y&BuC%?Ot6cs2>vy<@aZDevWXAj9~y_A-b zQDI)5I8#jp%B6=aq3DI-LIHqN_X@UD0Qj<3^~SIw{xVz_lWAfR4r@2fJer5Rhr)&d z+pYrB2}uZ+;PUnKJ{dAALv=0kh$K%k5CMJ5>ie`+ZQltTA)%U`GFOG{D)iEj10 z#Eg0RfGH5^jT9?+rOB zr8!9YN8;}wR-%0u?y0@koGHi2$~=^wvZst!dHA>9$D+s z?n9>6A-EKW(U|Yqy6z7)&LgL%e4^E54nE!~iT%AVU-C$p1tXNDh^7ZHHfn0|U?VWq zPEKI4<7_eldoJ1;rNiIPaYi?i#5WWj<n$BcQ&?BcN% z`lzX>oe~i*mzPW5oc{&X0K0k5=Zh2nI)&7gMb1xha?1W1wkDsY?64^=ph&PFL{F6L zihpc78#xy(8H4E~H8cWR9&*@SH*CNyld}yTSo-xVv*-gnO1>1QO=S7$kRcx^3Ly8y z)jZw0W!PS%8WiN@)HiVe4%9PR(pj)^=1w~`W)LD9jGJPZ3qnamDe#XSw`ntNRf605OmbcvOqcLXw z*UBru#s_joe|e@s3zy7gOIa!y5Bo|Da$MVK1H42%c~cx_yn4Wsw z4h^eG1lxo^Bz1cmjOr^|uOQmNl(nN^erU{aef^&#GMFQymn@~Xy6(0Lpp=

*13d zwnn=i2u~hm9oMh^gFdcFfTid=lfPr38t7Qe7PKp5UVeJQ^peGku>fbV(Vk2T%2 z%(TAP20HffuM~c^Ax*AoNd4&&Ma|Op_cN(n=(mB0>3A;A^XwTId~&`MHej^){0>YY z&!0GPl{HbQ7D;DeHS+W5H@5b@E}i4o=Vr6!-Mu!iD?6&X+L-m{cMur_vDH_S79|KG z7s5ZBQ0e3A>c;HcH~g?CFWJT8GX$o1EHuTQoPQdJuB>JSSYR$EyKfC^R$l^BL&WjU z{Cr=xd3Q_bAUHBV>+35PY#bt?G?gD5wQ1?ur2nGL>G8PU7f2QT6tlo$B@GA)z{k-7 zCW^S8eMtplHGT+8${0*re*8R3?F=azj~%mr9xkcp(EQ;==g5o4u3Y)UqAuvKemy0W zX5#ZRpG`fOL$<4^oJpn^k{$E$Eu>eaRHj4b&%SGEN|=AZ1o}dILl-;ie);Ecj;I%iIk8KPadluWSCF3hI~7p4C#(gJNQt+xqXJ z22t;gsMd97SHalWINt2O%>Sp(N-Vf2Q1^bJ1l1rfgNazU*io8fUdE#z!7RGN1WPobIY%dbUVZLIFWAn7LJbkjN8;b z>fflsAOWWkhU1@y50OlaJz!3O9 zs9MOj>{*cYil(OgcKVdf1*aFo=x3R!p?ASfxOTjZm@mu^z-b3IBpr3z#yX(g6d=vbUOWQ9H!ZCV)xF9@Z^Ot{zG!k2 z5^U(yAlGmA4S*x`GiDh_@U|8v&^SD$+R@Vn!qFq12O|7NJC{jv_;)#ts6jo1wK7`)t=r~OfU|jeojK=_AFdAoT+i~7h&ufOC zm{=qufxPh{8Pc9p*f6DmAQ0qZe}+`z0fefi+kAq0Z=00;_;FC`N=|~7LJlA^jTR;N z0oF7>ESM_y6}>$oKN@Ice%!=2PoJ{d$AOdX{?!tn$h^^0d-F>5wuS&sr#h!ootn7{v-9AKek>fbk-42*OL3zF(8c&>yO$ zCHg6R{`{Fz+T&@-wDZQrl`)cD&O5H5QIN$K(9)6#z&q881`IQmh}pHRdg37h%h)p*-oeh3@I)>P@eYzbPuuu5z|=Gys?F^EY|kX z2M&mey3_*02(`O{DEmeUbdEO(E@x~kFwuonRB6~AoZ3{BmBU(724tO_vvg_B;}wD3 znfDO{AUCLXK#=`;+uPl(8~bbdOG_Ov2P}WYMu*X>6`HbnDL^1}q0?u~pweYuYI;*B zuZdAa_)2D&qi`$g+t+FB+VK0f5vY`fn(yCn2al$@lnG`OJ|AS1nTMVIYinx6z+c@1 zg?tS){bO%xSrOJovcN`e9MP4Oy6Rjt@@jB_<%k*C${-~rQp)w~yQaY!Y-dT`BQT0@7YikNFbMr7XzD?Pv70A1+2$PtAeGQ?N{&!fDQQQ z;JjJlv(mxS*~zIMB?z2SN?Ab|wr7TBbO%AVQr_j*RAgO?)I~cS1||h#^(Y*P1UijQ z3bO!v9d#9bHG+37J1<`(n{9isBs2&>QzQk36*Kxh#EJps3c5(^5uV!O zG#qRqbT*|h+16*Zbg>iAC%xrO@0M{wd~)*0apSJz?>=|#MRxA727;Akf-k%(;fQ|(J*XnYFfeVtLheuYXXKobQ(}~!2!Mc_h0Ma@Zga9c~!S@{X_4w z#v;C|OL=A_O9g~Pnn%vM`yv~8_j7Oxvgt6}PUW3HklL%!^ z;l$wd{O3JPOx5a@pVc^`F+A7nB)qwrFnx;2eDm`RhTgH()%BF5nZCG)M#;NNsG8m4 zcJY_SLmix@B|5VHX*D~4Vj6d5iQaYeJ#_#<1U+W(#E}b(qYknOhdEk({ov{0C-1av zpPDcStPv?Ba5v&Knhu}_2F_UXE|ol&U(p_H*X-MB0(+aB96bQ3WE1VS_t^zwqh^q8}ArKRGO@9(*2rHL!F(Q=_>qeTS$ClLp^op)3SJ$~j4i!$b- z`570x&e=KX=uwfH>d?WDa|on_jRQG+)_z^TYx<VoN9lP2u#9ixJ)&nnmgu$}|i-Bn1(0F1-GSg#%04nt2!W-upX_ zcO%}40?6E4-Ccvbv5U{ddl5AoSSjTonzVJRR*9Z!x3*j%7AO5Pt#&SIH zR5>B;D|F>blEf*0%NHDy(lZbz>$>w2Z4&xW7XGevW>SisOG@%#6{RQ=Kjx@y2P1>y zs$fh@hl6VDV{Tjc2Bn_%24Lna(F0lwNzPE03FcfdOi|_hr}nkd+nzsVmbY>~7mes# zp_dUy%R}IR_uJcs(ExIR`_@%%VX*4}bii6f?@w3wWF`0#f!5~8Bl7wydE&)nJtLfdqxEtQ`d6=AyZeIvs}zvCv=lYky{%UNlRjYPZ+$@UK6mib7z7$G zUJO!KhhT7Wa6sd5nYWD?;^OC@$t*7)&$h<$LZ!>B#Gw!4$RiD0HEsMPadyk^Gvlof z9}=9mP(1Txh-UoDw>P|>!FZ&1@PmHLor!vAKzd6{W!aqB6j=6*1G#Cpwh!kN$X>OHJsDIX8Zb z0b;_s7rlAZDy=qf;Jw=g$si)g)~IgzlZWl;me?rScEc__M>+)DacaaEzGep@W^5?2 zMDXSH2?7WzGXg`|j-XeOkRkRlaQ zhNMEIGDIOtB$`Jdy;4X>!b@gRh7ie6NK&LCAtX{XC_|mk&HMYWv(`ChooB6|<>#g6 zdG7mr?|toSU;Emaf(3tw^75@Y3(*`Br0!-fTIk6TJ4AjaeK@*$8%-{7 z@K|BiKp$+w^FiU#O6a02uakBO2Y?Gpj_j*+erkgqGlRRPI-^Y`0K}!AWwIEgvj5{Y za)juefqI^YFx>e6u0^FO@=KpwR~nbM z<-V>mOoZ$PoWrMpj>DdwMP&2X%Mg?wE-k+2r8W~Pnwkunlb$Ynmf;XJ#!+|248&+= zs?xsthDyT)v259e2DNJu|1x=X>(-%rd%57m!PuCX#+H_Byf$uL?bo!)Q-6!>_ItpW z)@@WVB9V>D$M^4BFm0kzeT6?cSEZx<=UFV@ZuXC!K?5e(cZTDOEa>9GUd_N2o&f-T zAsf4y4yNTOEgks@v)KQ7-uLm$O!JZqFS>PoqVV*-2I7%s4Z!EZ49zznJ*xw#8Q_23 zAP4wrVqD3_a6v}HVulR|A{fBg58v|P(Etjp%8T1nBO=gs%<_V51=}F9`cu5Bj@!+k z4#N2pC+;IGcRTe_FL4$O)8ogo5jo_ZoCS9U0=n%Vf?wVC#ZS2nLP3QA#J@0>z6uERZmh+XWWZ%k1dn9^Y|Cw zi9^9@Z{PUtfx@2A!e)%r)DeH|9bPhPL+|hA{Cz-t?Pg^PAoJF!d^f>})yWBxzNDZa z_CjCP!QgMf)MwXFi0pMaNaK5om?-F}!p=A*q!FW`yjMIB&Bzyqm`?buaGlwu2?JTB zD}61-+$(R{%9Y*MYCJECrF!Wi0%!CTVQJZ`Z{PLE4{5&w=U6}(WWQd+6Abb3~}df{Lrq zA8~rng*RSYDxqj7W~ioMaDvURNK@Nz$)MZt{*Q{`8m%s-D1@m`G@b&ztN4;f6)1W$ z>4DTq$^85GsqJ%gEO$P@rOaSIbuv}=Utmbwd0JVitEM&r>^H>z=*`=sc0StNFbUQD z^!4lrhFWLkOT@+vlZ3Id^D{RCF>-ECxs#2zeokk{BkrdT*&Q$VO_pc9Md;hRHZsU; zBdrhVy9+-1+%Ok$M)V~X0!=fQG(*RxJh>pvS~V@ zl#w^1nOlDGf@$7jVt7Hp=`&~kvC>31Nz0eyMR?>XK1=n?vocA21l54OJxDW&y#}1X zdWTe7ZAxLzm65WH=<%yfpWDs`^oKuj-zVPu?4n6^7ONv=o=)E_lW@D?ILUX5vN?u9 zgGj_9BoYCQutb4n1W)|I9Ty7OkNU9e6b-TMIy318k_UnJ6jgg38EuMD5i)UJ&(&mk zZVeA5F>GRy>HjZj-H9HLwwCEDBuUOHV?!}iGsX^GT{F{)zY_l!urp9$Sw5$ z13W2j0uanlJ(x~3_NmUJei&OJAwrV<|71yoHBBOtpgzyy-3j6eX|X(izJZ;^T$bxUwU~=(sWb7eqP>g_1`;+nBRMJQ3iPc}<`^9L*^E|ITg%R-x=)`_ovbCF)29c|lMU)aeqL^9670X0&6}4* zCscG0i5eJ%u*qmNoo9JDISlp?XOb%iKG7GlVfqO=xm5iP!5?`qDpH;#5*t)l8IR~| zyRjR#F(m=dDSTq==}`P`sBEW&FBCvb*cTiazwbk=M&7~H&z5fT0bk!lF(FLlRW(V( z?OU=1{sc;oP$4)?ZSz3kkKpY3T17gybiJ5Wdwyjb4_umbKW?@+HPZv^(;qzwMp6Zf zO6LTH5%>mC6n{6EVMt^U!S^<+x)$;H3RY1iB_vJaC;zvo$XtB~JSD6VRwu80=!KKb zVB;CWn?B~(Q5SkPl0L)6#ab>Y%pC8npJYen#a8e4iy5=Enl>$0Fc<9}cyD2L(AC;ddnR6<9ak6jetW}>poqfalOr0$ue_K0X z{^&&$rNU&bd{PwVHrn2v)mis#plfvk->ySVwYH%C0D9}aEgSD0NT(Z$UvmrNzg#)= zhatbdPNDHELOO&-+Isyy=(Mu*UTTrD{-?PtL`4eVL0mWhS#>phB&QIxM&F2aFlFWC zG8qFAb9i8&1fXDoqrp8T=-In_l&+W9=!$LP#v&<;>yk(N&r%r;7#O%cI&q^~Q~+WE4zlU;T%-ITYjtZbr?R%AD9q-EUUHqL@Bk%$2V>NY$Ba}xCmpkq!ATImi9~h%?XbCsE7rUkcqLIyYB61Y;YztLYHSPSD1@0cyg5MFL(TdX zD(S_NOfG4y(;r_A3OGd%NvHlkhTg+_PvO#Tw)+r%+X5vUuF$sP9`3oDi_u0ZX zDP4S_3_>0Tg{O)COesau0^%ZT{PN`sS(2$AVvUMN4|e?Sb|-BRxH5{Ti-_tc6swI7|l7U;^D- zdb+`^9YHE-?=1I2D1v6}8_jUwxiX=*hq^p{$-PHx?VdB|qI);Ac)wV6#OCGpQgx>af9GU=z8s*$z|bT>eGcr&V>$#n%Fe;z^FLa${!{j>o)pw8Y5Kjpu~MnQA4$qoRn#7Hm}JiC8<}JWYX`mqL&9BpmQ z);HoYbdE>s5A||I2)CzC@7N({vp0AxX8=wf>35HwJ?pdk)gY=z_k(fGM0k+Z^E;*b zMSip_`OX9j$_03l*a0TH3E;#a9&Z_3>uG)wgC0Bel9J%7a3MIR{K^X;2J;QTrv1PR zrQEiW9H1q;<U_{QrEbWrD(CMUwz>iO~=!-y809dn)_w`~`JdI{xfv~XK;2-*ZFTWNI zOeq|k@Qv3hdj#Y4DIx80-J&QvI0~d@ zs&uzQMa+~J{@_6AY07sKM(lYK4<8nEmgVIL3O>^WrDkQ>_qfgkSFYY;GeZAb$lder z;_1OMCQA>K0FCTZI7ZA0)7Z0f)~K}v`U)fFlq9T9VMQEGkx{5Mv0xe#xRHN{DftFO zT|NtZ(cSFZ=X9y>uT6P|)ep{Zr=F-&@i9_1O?mZNiYy0{z{{S#ZXFJBE1&V&ZPqE1X&dfQshS#W)$2y|kWg)xn+ z`rOP-o4O!mVCEX-*W#HoO7;mcY=qm}yFAuwkJttx&OR1HN-C>2HwZ{1=O9BJOr4)|gffoADV4i=J z3AWb0VSi6zs!J+hgW^M{uXrfI09eP96c%O<)k5Z=zD!84H#4KLe}l*C>77Hm8nRMI z0uWtnU}2{SH?0=Na4486zj%OO5VV%v2EkrKMx^^;Nx)^XHlHZ(FAwccKKNgyVBXa(yKw{XWeH%p)tcv9@ODy!Kht zf06Ma*A1ES9Tpyv*xJk4MZ7aL)8Nl0O}YvETKS^I)kwiOn0vE_v8DMWVnpHxV8lOQ2z=! z3(?JYJ^&*)G)My8inTRNVLF66p;NDN*x7Y-+$>_Z36K)yUUN$ecDJ8*C>5Eo z+!>{^a4FV)utD#@o*Z;5(JH}dhYwHmT`ukrZK%2Z9%Fg$ziuFiaH_#aZkO^H_F_1a zbGuseZG8M~y8wDcWC6GSRtC+jTMr%~o53XfDWAeQi#!vMC51P-N~I=Z*-svi*HoxD z)=%qu=T2d6AsnDV3D$!Y^5x&MKodxYD27#V=e#DLwVN|%G^h}83na^}sJQA>djHWQ zI!?~S4l?vrU$w|A2}%-I*8Lpei;x+wO%WbY`w3S#lB5KbuwHo= zp#b!%$d=XN00))`4W2=*xOj>`NOA4A#>PK^_b`^8>=~n6{u_B|F+{6O11AZgxAH~L z3BS%EVkf*M)|myny{)O)z%op(3ju2+Nd*8vV6CVKAa@{$pgDl$|9Hny{;|YQVgPWT zzW)hi#WQBCDoLBgJ=|xo6ux%!)2FF^w>~ry?Ae=?XHr-1mo>}h25&^8U}^MhTU**_ zZnZnE1?5K9U0R}H9cir9mfH%98dcX}IjCbZW>R3rK?!Ydf^duFkGtJ4YN z64W>#f*&lXzbIVHxDluWO-!873gzeHvl4G^d4AMk;-iaIsH{bhTuR{$jFQoDA~xlu zVd}~bgR-Nu=*QI7{<)O=Eo+1dKxEP(B>aXAtq<0tXIrG-4^`Ta*0=**)J0Qk zO1LTH&s`U=t0}?(hAYwZc+~6vX#oUdAwD>FygIj~&FY)L@}XB9yU&RaNfZIz(F(D| zkLWm}8o&JNb&*-!%I5DX`B<}Y;P%pXwT%_2pEwdjlV&Kh9rCbX6QQJ}L_s&l*7jiS zu*uG!XnUpvwIpEzClqv5rRA(pL{}{ce6Wc4;?g};Hw+l(4#Rxq+BN0=V}t-h|BOi- zD1zY&F2~i*w+&I1??$ueZzxYl03%@Z#$2tYxh48DqTe-_z7+ErJh_B%UVt~sUsxre z4W1*c_K@Cp_?JSqo`_O zvIGG6VA5|ibMbEK#9{7Q{;YEJFVg1Od$wraTfrV6o+N|u)?a20tbY1{qp)Mb!)m?W z-**4mrn%##I;}kx+H>J4I0+jhRdT}q{mP2RH6!9hW=98$g>G}`BuY9bA@V6)9b6&1 zl)G|!@rbsGR_(0}i-eg0NLAZL^p%nrH?Tgl!gbtbeoXCJ!gl5Wl!=!e*qHUcXvuk#=$+u%`#GhY3)wyRCC~ z3n||iiiL;pYX!>$4%@kVZNhWUi<)^1;PT4<(8$OR8WHZS&qKolQ9P`{W;%VbOsgg> zAg`xhB-}SOH0&{4{zM4vCr>hf{vYNs4J}x9!BOX%gB=HznKg4+=`Ok8ly_slop)pq zk)g``?!Y)JP2!@-x|%q)!iLPxpog?=?0Lsia7rj;MDzo^c^AU%xiL=*hF36Z6J4#jGV>b8Vbk zZXUOfC8+Y<1eByt7VaCveU=KZ@-`CDq3S7Ovk+a89Lq0drqkO}hN>;uAu?O0C1z%@ zdf!9)sfTvQXUDr;ux3Qu*5YcDTl7y&gP0*3weuHDjT4)ZpR3T{F}^^rqqy{GqjB|| ze6O@>wYH$0<1}wHi_C)WnS3@2PJF%5N=~HtYTh@Qq@7wJTl1pwQu^i><`0W|rAkbN z79wjAWq_GH3*TlOE&fQMPY&cr@f$aXS-o7?;HMEXG^={R#NT#gPUcpquhH|#A!iXE zCNw4JlQ11taU&$8r%tr(+?;h9wf$k|Z!No!E?_a0eWO;+fzoA`0xZ_t1Ber^s7Z@~k zvq;rv($#155L`Ep9_=F9GySOM1EX~{wnD~ONtqB_SB{sOI&0WGJcMVJcIAzL*`A~K zZF|Eo3o3F3zyNMavCEM22|JKi3p!GMW%T3l;fU*}G>w#PP^R%GfH7YDh6#_PRwBBa z!%ljZ#lh7XZi`z1O!P;9RuJ4;)>CS;RU^|T-PKBUjFj}(ijeq>xgpbA|)!g;fweeb6eclcC$q!v#I?(>xWb1DS<6j&*QaWg3^yeJw zqto)|B*)7RRkYE%aKdfft`|vxYVYd%*S?~ZhlCTyToeXPdVq0;kAPAM^*Cj)FU(ZYg3S!>_nX=BtcY^y&00YE`@ zNe~yQ>Kz>%v5mTte$N2iH{jor2@b4oB5fj9AkyHc$A5wh+>7N?aO+<f^;zb8 zMG#&*f&>C^S`TUIrWB?Og6=H%Y%1^pU@!y^Y>2+5)ki@gL2W42Jc+w|_wEMbQ#YBT zi>+*ErK*QT<^`IE&_+z;_HYf*#K=`j?Zma`GaBxcy%-Q59^Z6CqAbboo9&bOxcTuT zULBDcKg9L3*^uR1yVm`1&A!~fUan_a{tmqdv$}JT7^9+h-a@|R{jqZmnS^@p}N%F9nl_-Fvf)6 zJmaB%(IGlD1>HbaLx+JrV86b71)TInyS)z$QXXc_oNNFn`YN=f){av^-#}%I{CR=F zdBFfJUk>i-5`mp#zRCCnEhoRW{lZ64sO)G@;3Kg!aqhDc2llWLA2=vJo?}FhJq!VA z2sfFnN6lmK0-D;>&8;NZxX!6}w8aPDFPQawV~}7 z{geYnYZl}63)BzVo_Q1#fohmQY$6Qt_&zXCE>%}xcq(?p_Gi6}sjv}KKyzP&*>*-8 z;OuOjr49*eFYvBWbklSfr&BE}!Ky~qn^TN1O3&!rbl-H+g}((EobDJb{XCs#2hAgR zER1+R;=_^%m;cDH0OG_`8z6{10)EcDcSf5YWnaAJ z+ZiTWiZiCY@wsA=8khSzuJ`i%e^$En&g9CIJhqISy6H*0V1qd-^V2825lLmHrhZ8e z)kx&y26`dQG*nte^kuB0HmPYMrUBT4P=O*jtbtX;;c{KgWB703vKJTITU#HOTw%s_ z_;C`5hhYOExZfzwX`$&ySRtJI901!$Z4m<{?lmnLR=ka8|k6#&TKK|!;7cz9sNf2s9=ma!c6#0aN(Z00~ zWKdMf|I6oUwVda7@88Fp3q=kC+YsICGv|z1?=GSv|Ell@Ggf!mG|dGS46T%vf1Q7D z6I_#|p(!3!SI;U;3OiDD{($U$mVsBxjc;plTk@sxlhjc>zVr4llNZ>isY^Y-p%NZ` zv!cIEN|!;sMF&}EOJ|THMd~QOvev!lcQNQyREnz^3=ItY1(aj!S6OjUX=&+$2h-TW zJ~+l)xR_aJ{tHqjyn6n;6|xZ_&G?I}gMzM8X7eL?ZnkG`os_mxV1rg5T_RrspYVJ% z_`_)XS=-pG_wkuJeL4a&_@I(zwn6{Q-UcoTGPGaM7V|i4Q1sckQ1C#YvR}GK3k{Eu@@)Q?Pel-g6_2 z(p=XdV(A$CXK7HdMz87Sp#{2gHG5tETqYAc@YT!1Q}kE%^}gc$O|!Lae8rx`#7p!t zkbfYh5(Wlw8SXwea3T=G?*L9rwhj);5Oj3$*-Dif4FWPL&K)L9U8n%>(w(V zz$ZA!YHJ~5f!!!IJjV30>gCRbK9c3gGrW^g8(*tQJJ&BXF^|<=H0sG@FW4YRuT&Ud%{sLD_Pbk8 z{`LN%e9BSG#4mjRiwku`IoIGeVdDZm6&GM3y6szs(rjw{KeYLPQw)Zd>^-e)1a zcO7n!kM@p2AzZ_^!t-kUHGgymq)2W8HYEWYmPcmEl340@9XNoPIfNw~BqLBWKw1M$ z3k413xSg}qk3y;jBvLMGE>n0Qo@rdS@6AWWbMa~vz&+QLY3T8*@%hw-R2QpR#jeW!?k0eYU1V;X9e|^T=^|XxRQfBCxLjMY8_(+NlAZ z!&L>>BE;3a$j=x*+L)V%)gJP9SU*}q!pvMud3?7z6M?7@I}h?M=t{)1GmT1ujA>{tMG7L(<<{%mgQtFV9Mde$f`rL( zFC2)LvG)GwNtlHyuElZy3hv(`4^Sl3A1x`K5TlwdfS?XRmYqL11qlO_S^g~f9q($k zWQkz#fk~97r_Mz?%ikiN4ZUXIXa_3^325U}7EO^#Jz%)z%_P1iEm;6TCsvA5o-uW? zOc62v&|$+;Un;sAJgTX#KJub{oH}>DDV(54;YuJK!AF=o*N=rqB-6F)*B{N&{SOR` zVTUGfQJr}nhqP<9yDbkZ_UmW$W*Z)*U>P`b!mkGW1jaw@GpoLK zc59P;KLd&2jseEkR9K~O@@zI+FOo+rxl0#K$csb1?jnUD?50@>516=j?^M}H2BJtY z*czdu|I@Kd)y;kT756=1zJXgqlwlWh+J}|&2+7+^(;Z<3u&^2LDzb2v0rZc7Y0xKw zVb??aJAS6KTBLF5^XJ;~-6pHcB|fNYkY}0lmPvZqk@w!RzNw}39w>|;EV!961gzKP zJs?nolX#WZs9vOE`W_?QACcYz?@jz)X14q``VV1-uAjq=v^`;-C8rLRx9*UE+{PPd z&+rQfCIS-<5Sa*Dfl!&TpL(5MlH8`h@u+q_&+oX?lkO^->|db%b{m<|=)$`mtOXTT z5iy4a+sU^e0@Iys#x+DgVDvbDiHeIk3a;w{TSz6ipZX$j64IEwe91m{voW}ZlPdX# zcki0gA<4{q3SPN)&mGQ%`Uu9)NK=vz_{x_@k%enSNo8if4sSO-bYdHf234xwph0&L zfSyp2t(^~(c)bW!Cq_$7P+345YN*uq!w~madK>Kr10v;uAP{;>HuT=2bC<7P4WII- zw1;0ox>q9{Bjl}EOE|(=JpR;kWUsk%>zn>TtCMUqm(Cgd zkn#2H%e26p=o&6l2=J94pK!)~b7NrY?~lvA@rE%VF9Eka+Xhuf4f67<7W`K2S&2^O z4h|)xKjd{BT%b8q3npN#{kqYAF1~Gux_md1p5}){&9xIKpsODWzIF!|_;>FVCanLU z9_Hr>pn}KaQM3OJTPdfDH+K)$_Z_M{K}P!SjRSq8B=AIjmE}uM-qYJ#Fu<<-*)j9} zhem=Oq!+lE070XOZ^+_MhR7+B5v4q;X_%}YnPtNtW2!^@_0p^0X}-fd=B4NkY@Qov z8iL0HKx`jgzsM7`KkxTJ7SCN2ZZ^MjcpCaQ0{SAOfGle&k%owG2mt`~0)>y+23Dx%iHz7mW{{1(~5`hkSwy5n_Yrcgbf`?lbbbrdROdP=vF#j_h+PK3;f@X9oVks@LgSg#{>JV?S)nq zdrhA|mtvoVz0a94;W*#zlF%f?Yo(Yw%=(p}TjTq0!seB!0mRkcQo0E_o`9Ww2D{$j z!)N%Ueg?9(1!hAG@|0>mf`8;cnfv}5)X!X&xHtdOYQgY<5g>#Z-`{+kQ&O31BHK@j zLAWo<*NiHUvfe-db8MqY$mdEYvunpSzkKVYL!3HpJzi3R(LW+szyzi@pFbMWo}~er z{Vh|qB#5e$cZTO<6U9~K!8FeyO-TpmGcq3Dzh9f~dv(&WI|O!m>NFT4%F7>z_UYaG zf=3baO!q0R1XrwEQqxwr#(8R}zB$~MmXs&#%~-I&mldw=6Z{tWSp->A`7qi#-JG>anLe897?dKQnmhR{p_;oVQfK)t=I)lcb&%5Aws^u!} z7eTS}XcVSP>`W0Cp+wc#=C&VbCD!3XiO}?gIM0B&U|)mR2B1yP@!UfG07rz{tiQp~ zqCT=-}6%?b8eJkdU;Nyvm3!BvFVdktz zK&UWaLU14sk94>YfewtigNHOf^5LULx-5@PY&vWHmlxKhCLv-1#$H`sqahSP{^5=~ z%Py1=v?-e1;&!mAl&DJTW=W|=su&YxVbV`~uvRzz5+?L3RIcU5_+Lfd&Znuhg8rlKh-LDaAy7KhTPzqii6 zKX3-*$c>>Pz^l5ZC)6SaGL+%G824nDg3spr?{8a<2(=n+DmCmtXD0{P0m0f5sZK5R z(Faul8HLWl{BzEh`6CY%O@K*Klhj$FHd!_lZ_1Py%5^}(IbRS;!uZCUU`1Pf8SEW3R zHLfkb(=FZc8bX)trav~9FGd5yd;rmo!KAMf*Oqh$jJ__NEXJPf7cF|tV=Tamk~?&e z8&j5CDC5q7{W-SrQW_CCY-}M=)_K8i@$Ar>I&h$7Hh(qW>rl1Rkc|-M=Ix&>xPWX8 zXzk2|;!{b?c8oVPEVQ!PY^(h_Zl&k;KQJq9h|q`w5V>q6u%($m5AJ8q4oMxID7C@1 zl3lvsDl^Mj;V+D@nXvFeS^UbSn84fEpxU=%#`xSh)tS1u2xI#8x9km>Ln44CL(t5h z31}VE<}kM;I^9uLR@9>hrS3MBS8b*!Cz!Up8t|Q+4)uUDRBQnk@1B|K;$qXXF0i3W z44WD$38Dl%DOiv=!RyYTgK0PXf3>D#Da2ybtStXT<%S;O;a=BQQx3seuqb1nyX>nM zAydb!U#aD>5Tk16^u>1|M6d`w2SB3in&q_JN^>vY^KZsjxOlO}su5DYl0w*sb0bjXY57s#F8;FHas#pxr2O>nif&_oPi@Y>-g?0jS~>aG1XVWEW| zglFu}E?{|1#W>+xePI}wuuf4e4D0<7G$AR<>sq=vy%pA9(3+h*$uz2-lLe835(ngb zXM|8eWc7*89Sc>5u9POZCliQ*k4WSD*HZoeg6JPY+Zq4~zl?5_XOkD=0Ui_z6O_$- za(<m!n4Cir4yI;eG3YO*;PqgMOr8nJGQQ zyjHCuw#=A1mDTUCJ2c&Q+iDA{gQRtuf3>XYC8L1RKZTVVY@HA>F_u9Q%17p+!y*PY zgahgKctZ(in#*}=i4GX7?1UOWTH=i}TIF{LFX3G=#P(r1$P z?VI*SkggLN9TK-`18FQa4al!RuT4IM)nlrKGr?$NYO0_f#@+jRi!HE-?@47^6Ly|b zyT^1vev6R<4c_I39qFoxFQ^{Bt(^XXs z6_o0_LXi^1h*U-f&-k70gJf&pq3fnS=@$9`o+wX;n5;i~G~1C9{Jf{@`=16;&?3ic zS#Wf{yymdI-{-0S(*khA;S6;8CKN)^PWy6+oebl7wkaf9JOu{*2hwGnGj7nLAbyr1 z$l+P1wXgUtVzR7-Uh!iQRYLJGv%_NMpmXN@2jhMXy~rwkEoDrcWJrR@+sT%(%h2b;4MG{HqA1BAds}7!axfyWUTR` z0!p6K+HJs-t#vA-8E`CiC0>Aapgi;|_?G)#pT?GMK;<=ZGg@yTGEeDD-^qn9nB-^N zjF!r8b}f>vQ&$U36eqj~*K@-VAA^yF1oA^6T$Ocq(4`#&EBI96H1#aGoG0<#2Q=GX zBSK1MgFsOVL3KbD9w46qzUN%6T`SFG^ueTfUgw*G@}4~^t3Z+DZQms zwWVZ~LvNZH1@?0(YTowX9ZNJK=X5y_G6{gRo%p)r!s5c`1yxbhd zKU!sWy;vxJOG?(E!4-B)*J720{)T+#^5Vkr;~#0u0T6`HK76=Vu`1O%_h3N0+JH_W z$=Tj#@u8>o9WY)N3C!`*9W~LoPjSDKW>sG|U;u_nL|CRsLt*md&gQb@ z!S?ocm^{Y6keEN$l1JEEK_~DRYVdysj{kwmhk+I779Au%knM+|*B-Cje5a~L3I$dF zpJ(fO54Kn{LUXWqdt<|dAv%#)*1oR1URpoacc|vzh^^g@9LtSS`8m}(>|ZS_)8Y5? zL{3h7Ob6(?b`hOBAO6|%=ExmHrb=7j!u^~=l*DG1N*(?BiC;261TFns(7aPL~*D(Wo4I4cjOA#oM2P5Z1G}t!|VqA_e`5G zgKB}m!|N~5M~w`R=C*L}FWK8ym*_2CDQkuy)-a7*PI z4R9cK4PARQl`B&e0#{|F7b~oH{J!++^+N|*rfuV5aV)7NKpfQAY z&)AuXE4Obx?D85Cop&Lb{F@~k*~Ku`mW3WF7^=}%ViQDpIos6gK7PEiD7OpDEx7Vm zwA`V{ty}LC`i1@?WA+H;*g~{;F{(TO&CS=|JRVq^Oo>%`hiyewmHxp;IS>;5D}kQ^ z_W?_dBn@dM`XNMp$921@H60CZ>-^+N)%{)nR3z#}ckNwO>T2>)XS2)EQ__QGblOqV z9B}k#`0*jz2KI0b6uY!Kr}gXEvR5~&%Dw_PQcHVviy}nFj}VA^FoJ|R!gqLkULheN zuuqJ*Ojm05;W2{R9KYrb-0D)KdDMW%&v@KSGVZfKdC?o6QEIkTkxXP?X#NQ_wiu?F?ROAD2iSLo+lMNTATC4^7Ar zwB>+)hq+C9o}()mKrAU~VsfjstErOIIX{isJ~Wu{EjivM%i8c+gLO4K3tILwWHd~)-hH&g|TJ@A4m!)%6g$-oM}wQ$*08SBW+dc9)q2*wTG zRX6$Q;2GA37+nLzgS>pEoMA`edjAzZjOyQIhVh_d3$u(h17$h@Ni=F-hGQI zMmt{U;$djyC(~Cabjdv|%R`0-eUNEw3)`>!;#$|1mUDq)_m35?ztK~&XLxLnaT`1J z9(?QQjB_4x)$ejHy$avb^<0^)qg1p^Sn`1VbxLJB2jOmMJFAnE`DD^ zFOFt$LDNT(Xn}5IR9J>##zhN%0{G$C#zpvrWrAbe((mhm9DcG*rLK> z1fwi3Pg_&djk5|{>!2{od&{JA8%KJUbz-9a>)VF%j%LJbOy@1gT9;o?u!?Gm*4>vK z1_65Es_Y9>Ie%K?I6i!Wol)MRbyS69CSFDzV$GqbkC8dE0wgk!DV>Gx?xmP)tSCtn zbi?SPPn@U)G7$XN87Dt@$0q}$gtWa&gjl6|28WXo7_q54W`PJ3oQ}H;?6#<;DT-cj z=K1sSr+%J)Dbb0C`mM?7dk-JN+>K+H2w836hpShvtTEb;5SpVVa?D)u6d+5-d6ez1MsQ2sg{s-^=={F+$-dnV`eN7`JdG>qK!+Fqx@Aw+do z;NgBcnM4(TWo+uH7y0Yc_t-jUJ}gKXZ#Y7&JmtrVj)n_`n?HYc|9^~9i~q6 zdu6ShCq2(n1Km@&p-#oSU0+v3a{zYrV(eAG1Mz663S-rHkDc7=nCV| zo-tAc<(3`v6VoYt4j4b0+T$cH5?WH{e@RAZ_=4^74k1%0zAKKM)yolL!ZoQ)tTc$+n1o!!n2Lw)g$Nz2-@S zJ`lUfcrhHHU^HR4yjNL|tchAuzO|H})!JiSU0?B-oOtkYznN;kk;}FrI&HfU`&blq zy}w*Do9erU3xW(`3`Pus{4>^M6BwKF@i`AzV+<%IC53e}!u;dEY9)d`n2{}kzTs{V z|AoJeE|$J1K={w8-rR}O7!sc?n~@ZpY%oAZI3y`FLbmqs&YfoVy}NZc*?9l4?9icv z@~Wt1Vexc)Zk<~+z_s5%ncjoL|JAClHgg`J->>ju>C>=OH3^BE>FiOexJVdYXM9#~ zSoc$>U*A(%l;2AfN}6a{rL8B~rw{4l{)0tD>Y~u`0ipSkp(0f&{gDxG7JIA;DzNC= zH*R0|88giOdGq2@&pD^VLq+-{!p`aQ4~L(2AGP1K$J!4Twz8hDWE$$1ZLLlmv~f&E zMriKF7E9lnE6ZS!;W@Tg%3j1p$;;&dbY8;C=6FN=zH)cVNQj-^19 z51{c0AZ-8fNe>~BKnzWwu)E4~Y&386FRmOubH)_;522o+#<$+GB{u{!|1n-XJ)_mt zJBbF(Jb=#V4F!a~z_X?v0JK09U*~`9N$TA@fw;y~uvsmC803IK_wL%-B2yKQjF43d zG3K-6`bnpy;Zu?I^|6|fkHnKF#$$bsb-hLsEY;;Nu3FV^WS7-1YcHRd-5z+u3rOahpCEe8Ak$L@^@_eV)nWbk+pIHQ( z8jk6hu$sj2b(%?8U~`|(uX+Z2zcocAY+uE+!?7aZ+Vm6|YwLywdgqo%dR9tL_$_hZ zz(SAKj?DP@s>9o>2nrwVi~?F#^;Mq`_pDf4S3z{}oUG=6<@qzMu3lT(b|>cC`r+eJ zmUR)q5kE{qPjvI*D(7o`Ikc5CwdDnaf4~GUNN29_gbA)XeUZr^Uf?z}cak*Ska6M7 zwTow!{zpRMJw`y>&1!RWCU0lEUEjY`9)fs7z(g~Vk@2mwH@L57L!NT2X%J9vuxoXC za2$S+@IudiH@7URzy4itUFPLBjibgr)cnkx<*tzSHWo_@ZjUE~{X7uVD1vENr4R0G zAqpLyW$VX=3)tqDq#N3E>;(jF$(@iCLdY1Q-UzgmW4a$D+TdwuhqHmC2e zW`$D=%G!MDuS-tbjYos+ysoc;zMr^tbh_C1@y|25cInw=<;vDyYd3TRIcCWRx3_it ze3;yQ)vBrwk`zui3M?`+MWXC%TYK?KUK1zX?kJAc(keXgW9E?~X4-)tFDxGM`9;@| z-_2)ZM=raW=z6Q@u&lE5(4ifx#uCVbY@$aLBQ8U$akR(-kvKUTMo4Y!a=f79TeilC zY+nuT8-sS@7dk9BoQEkBCSVYU-lF!<<9$BsyY%h8TQ|x&Vd0%_&#&~Zu6F4dO5=qG zlfBQLWKXI`wpg})xmqu5&g3ZcCbS@L;Z-*V*Yt!Xr}B4T@=`={r0Nn}6>y|kNL~0g zgdy0(9XZ>Z@m1)K7eqVNHo0FIP19dwLGw8}TJq`S>n>JSc?{vuLw;LdKND5TEYVSA z;=$lkpCwOzDA7K^O$7?ic6O+hCM?)oR_gL3(7lLuHwmh6b#CN+(Oj&dkXP9L%mlkR zVL%Fk3tAjx0ON2di$PC|dag-5u?8ar8mms{-SQ!`(`QOs{O)HS8q;0BU&HrT9pzu% zbm}BFF8J5ygz}HYukZJP6@33Fs=@pDHO1Q6s%OI+zKS_HC1pzK#)A)Dd%^0trCs!h-Lfu9V3i|Y_4}D)@(ro&4Obvefy$Xt+6@c35FkB`6 zbpz$(7Qxp6Z6KY83>_+v&S@3z-ruSz(qG=|SA)3rP>Z!APc7&=VubgnzI*nJs~D_T zAM*L7pQHVU3dx3j1nW0$SG^t9Wc;&Y@`64q`^fzsvi1Cn!`f+PFQwF42ct)cyE&2lBxgPp{#O;AuM#R>TP*f6vB`YS4X#`KI&$SG4i zbf_w%LwwjU?=@i`i^FUrCrr2;q9WgC(S3QT9-U{;etzMDvu)vn?$@s0nR0o(Z&ZD@ zxZn3>-G&W|IH%8lds&b$IOkd4NmnZ-P076*yKq&H9XlFo(`I@9GP2$Ad6S9y z$Gb1D<`nmiw16%T46J;oSLXTrVh@*VqA64262yId9WTkq_X&Ft6(`&Jb&4qTdO+$K znP+DuMN(bGTwT#wz0@!MR5}rm{Ic8NnHCQ65BI1A8!708UmDZUCflpiw8VCkjwf1D zUBlc9%_esak9hq+Z&BgE);4!h=(`7tDz9}YfBXG2F0Ns<^rtIp7d_M2WAJZMF$gQ| zC6KuEtZTy2ZPfwXTU7D5JRrS0ZY1z&41j0EOnyQ)HsqA+jdnVRC=H>x;9Iw646{fX zsv(};F|hJlScK%FFE4sJeTO>aaA&Xm@DCd#Kw)(7ibsz+gLPFD@`Axe!L7k4R|J@bN>HDmF+BvS&qqgP14(1t))FmXLX z+0=ULp6RkbzrJo{mL>n)u%UaeO;Z*1J((ZysWvos`M1j26=}zpe{&h#U$bfO=~MD5 z3+zg!DCp!&IcsHQnp+SbIB4H&d-11FhtId0+&SxcNX)ly2UEX_J>X;JALMm;RHSWb?qYK{O)9LHSz^)R+1XX^nimzO55M=$;zn>o?d*|- z`KvNC;#Yt6>{zM6^Lh}UdFv7J&$hv%^I#JWXj=@Lp_uQ765!$OgCxcFhFoD2#{f7* z$eT6463!gC*!S6)sNX+xUJj5M==nZ2Y7%x^V-~m37Q>(djezqJQpY$HQ&o`gWHH?|69ptmGj3z;w&T6$^Aro^37k z+*7^MaQR%P?hDSePR~~~{}{ikbJv;9-MSq-Q(1jIUc)1Pt@GZ!4QtBEmn~TpKV(SI zlgDu>drWo)+9UIl!pZ3uOdM&M*4A6$dSwa!9e9GF~()d7+v*-jyk=-3Uc` zt!naEw#?Eu5C(MT>fg|>TM&y2hA1fR0n&;}N{^7kGeN+Z&66{qA|U=NVfujatgVP! zKU~T>>2{@(RAv%49I>HZp8>`EkbKG|^lAsjZB&1mV@`r%T5{5%SkyY`U@=x;jsf#m z+P&Yuf0qoU3}i+V^Q#2Q!^neC0o<&tY(IOWopsZcnTZ3@vEao*!H863MaQM3_PKpX z;9BxXhLV|(Ma$970##TqcJ5KjKLqM2(sA(e>Oil-*d(@A0UI}t%6j+wxg+CNx`_fq z2K@xA6jYtG6nW^N=Kk^PxiIH{T7d1_J7|T_-{DPz5pQGC#^t5EAue*%nM1P)NhSV! za7hsn!g6FB`=Tsf>)rT;wPRdzGW)Hr13oo1HGlEhh>nc9z>l&UbnM1&M{s+AIm07} ze}&o%PDA^3KZL{kPEgNk;L>~?y$P=qCj|4#+NUS;XRK((jO5gUE8j>12yvLv`oQ-b zaxo}r9>aryiTn^%>>asno;ivZcL8 zkKVqq7p;q*t=61S>S1q~zO$!c(TFoelajNHwY3e;e>(bOQs7j_b7g(kNvR$8c%GZN z=tO+(aby3cn@J;IFVGFRzcXs>hco&kKNWejo?kRHgH6C%=k6S6oE#(HO>OXpS66SV zA6R^~cTC*q{$p2-EiyVG-Zl&UWdJjt%+74`gR>_? zZ*BHRB{nG55)Tn|73GEZrbOBfzVprp?Y}Qi8xvJgg&(NkN->8|8NF(+1tq0%1P30v zp^(j*hhwG0=$F{3$x6Xbjznt!A+@|T+_n_0Hz@ZCT?QVpY3bY0R3l0z$7Ef(!b~f< zo9UnZ#=cY8zPMb4 zfTvJh(z2=E%*GAqK?VnTC=pbnWqSAJiz&08q&kmz-zOp9N{t7-f3JP|iT+$kNWo!!Q|s(UPVm?CAG*kT@{{8e z!X2~|Fd++>d0by>RP_8kKQydX#r+s&{X0`ju4VVOOaEl;c{tr@V=t<_DN|}H6m}0^ znOrbvaKy=B+Cy(0w{N(kaQZ?)&vLnF@kNVd`=T}QR?~5LadD|IV6mVzFqm=UQFqr- z*!%lu*=jSu@%iaVh2{6HEMoEIid&za)|)$BesPr(dTQ>XF!o3yc~euJ(ltzUaaBZ| zthaB}l6z)zzb_g6jZqyAD6H!mF&Sp0) zz|oY2Fj+8$4EW-Uku>ty`SW(o_FWWzyFoB9!76Cj zwr-tDPn`pV1-+G?b(onfS}D{}Pp%iT`jdx;W+vZ^<*!hX;v$xv@NImn?oCd1X6*9Pr7b`lyOH&{J12jxNy#`k)3SN+QM-7D=p{wcT2EicPj$2#u7CX59*%JB3hSsLD_4d+ z_+6+x)O*OYc^9(YEsiL-7KoA9KXjz!ELG9=$5zr4`Cm$j88-y zV-2QL`r;^{aJNw}M70^07wGQtW5=f6(4qGW3$Y8LuZwaZ{QD9YWb84M2U1({Vw{JY z+b|Dpcorf|K`skSA_k$FBR#AjiZQqGsgu`$B^h$5o4nmtXm%DRea5aG1UJ3HnY&Jt zBCE(!#9j+VkCZm%3WISXEIMqy;L_9B)TCL=0v<+yso7ASQ$1Y!u4121da2j>)tsd; zR4X*+Xirtw)g|xSH%u0RQ7!0;wjb_@9~qdlt~?J<^;gslvjQF<;bgKm-A6$&Jk0n5 zi{iTC^^OdB=+I809y`**P_%Rw9odoEFFmmdDuVA_FmUIdqeGYHXE`MEeHy=ipNW8T z{VoLCx{l{=zIrtQ?eNf{Q=6=g=Z?_Vx0*RqGE`VRZe(OwjsQ0LYBCIc4-r++(f$;n z5$si!>Dd!L{RTM&fec#SjN4gn54HSzu%X_l1o_^iIO@AYp*@ySW zY%fl?bPOf>fTFXb|gCpIsW6z2t2%IO$z*k;% zfldG|?bWMuzK@TS=DKmVxk+tTxRTyM9?KA2}b`xpl#-@I9@D~^zXR4LH1;Z1n6{Tzlf*#{{( znT_>}B}zRa&Shv#4C<-MFz)e!MrNcuNEcaq4XgrM{or5)~OjlUJ}$*AfbR_{OD zcykvn?}sPXQ#TdwAMNGaKI%D15c79jc_*~0f09NaTLA{->e_Yd6Mbd7{U9PchZwCN zfg<(8ciYSg;&$M#uZxUR9A)ku#=wL1#Kl^pfJ6Pk3x-p{SN_cuv4@V5p$}-sBb&F) z7&UtI3>>FH-pQSmDXGJIuP`|Vo)o-(eU9td1q8NAD3HGfGLr{eONM5U z-T5qAHrd7o9NXG$3`uKO(d|70r}_Q(P~Af36ABnPsNM)uARmzItF-1J#SPdq7QwMd zcBAcwz2ov{Hje%HophvaB}yI) z9XD8w- zt4{I)usdl6o$K1Y=SAi&0rKc>m$kO(-tlLCgKg48)%Ks;74)v%dZRUV5hyT6Fm`Vr znFkK!&ASJQqZTDYb2*W)+gKk;2u(izl17od}L3q{>1C*JSTh?te$21&F$_@DQcK`8pz& z4{i;L4A!WxUriQUQ{yHK#J)`gFDpy{=J8&RtN3SFF>w_)ZaEgZ-lu0amrMhtDfuOu zR0f#Y)Vj}_W!?R_?x-ofwvR^YI$+{@YfSd z*?hly@W9Bd12f|07cEw?xR!phh4I%%HGno{@G}nWG*hBzelKxB!7xv|@ifMI{OwaZQy?!i*Nu7-UW2>n=%(MD#}aHn>SB zxU{?3RmOC0$*&gE2sa(D{l+>@H%?P>ULxFUXbj-3Nc#Q*=%9Tc2x)s7fr@M4jcqb) zN1EA%dGJrPihnM0F09F2!m%9+DyH3RDcf{_`BeC|H@M24mKQ{!fiek+fnD7Qki7pI)XV^FfGs84zkmOJ{TLaU8Xwi+;qnMKGmn(m%wx{*xWE&RarS|pxNKT zmZD`B5rh3;xI>Q!OXHM{jBF>DUbpTSH0BMoWr=uBLF>dfcl+0kjwigeY+<8 z{Erv)m)#GY(mo*>5wq{R-?EGs^`S}A4dPa7zZf&dV(x&v{1-Bx9pd)7xuvBc5^6D? za{R>Bur7^_msMpB`X8vOLWSJ_k}7&c1B~e4wZ+AKCFiio-A%ramNSCGRa@#_XWuH8aV6%TVvnI;Mp{d3E zF-{8dN!Nef(x^=NM~C}vr{Ax?{i32Is%<1EVO0RH5L=m#03RJ)=tyK98k4pm=bTb_ zFVHe0iWf15m?>3h>HMQ~PtZ^UpM)FR|!L@MU14c^6j+)2e_x zvB}*RXzkez6OiiDFM#5#3R6(|9zg>ael<(&Xq@Br8})5%Z9rqbtZl)|B=7F8nUE+^ zdj-SwnLRYrO&{>OX483ss_lu6BmQUCYFZ!(4wq8Eaw1nEvi#_v5hM2eYvPEDg@6lP zy}C(SHBvL&NmWC6a>d-Zj2CvMaUn|#wmg(j{NR~u7ngN1J6P$6_TZ^ylY%2}Yv$)$ z%u%NCWG_8)=HJm4wT~OS-IkZNv~9{BruF#1C>&nSpP$Xy%#(lcAR5CT{5mgODA^R` z{5x|^6h{^BdTl@epENtZ?7nzVP;h%6P|8i6PoC-iIy=?Yw((i+Q8&dC)yt~T<8aKr%W0H-Dx-9y`p1my9lz!YWZ`MP>F?sS5 z(zZ&7nK@G}ECiYuicjKX6!#V#{g*^7%X4OO{Hm1I;7cgkkG8zxC!|Zf zbUe#QXR!8ow)_Xl1x&qR&1>9*0ZqjEQupEizw{cGEsONKT)!*2<#e@T?aKchJy(R7 zfLNw<0YXC*L6zm@*cFab)>ae296*8nf9($3{GqRFYPym9g2EkhCstV3&73vuZEYQ` zkEX#kN^t5bupm~hY%vM?B#34}n8>i0I{?gY2jS(xgQB38L*co4HpS7|YZ+ts|E2e_ zej8iv%H_+%Nm2nY{^5FhK@^+FlKPv5JguoQHZ}b#{2>mSqL5!?x|lpd%rsbdyQgSr z)5%?GA9>2;8WegLSSz^R^0s0hA(Qf_;6zOgeTRGJBXvOmIStlUcNvwe6DNLSqQ!Ku z=#eKUG+lnW{0D0Vwt~K%9z*s7cQ)M83<3+1G0eVO=)94{b7}f{LF+q77FB9SiVe>a=A2sv}5_ z%Fa~FC%_WRx{K%(T!Twjfi|zUA{37)!>8UB*K`=jz7Vd~Ry;+%*J-UiBRANxk8V8G zAj2u+_zDcd%v-OKB6DVXpdtY5fgsN2q92(0ZA7mLU zVx^77x=P_+q&Bq7;VKZwS?kD6g=`c~EgBgFv^;k~XavYjzQxg@&^+Vms$1~5&;IGM zIWe&sb3@zX!O#n#pn!6^|bav_Qajii~{B35}8gc?{_el2wR6d>QZZ z^4l+hc4CP2a!fl(eTCXks8vfJKBQO-<){x=v2D3cCcxrnDbpbANwGwOz&ik(aLpO{ z2Ln1T1TCClB5$IHSBLOH3I9+xFy+P9l5}t3f(0U`Z6Z3|W;G<)_y%ZQ4=E{{e2kOV zI^6#Ms;{AQa8|`uJj}3cW64lu^QdX~B+|hEf1($dZjs4Mst?R#GAI!61DI_qy}Zhs z%*q&I2kh*Qlm?<-Q0VwZFy9-bh<9 ztg1YC>~Q|0LQEzqXmoy_XkMUtxamNd+}&&r+ArWcG@lfj@9vmmQ?;6;4H^D;vTjaM z9OruU?Ag&@fAi$#m!CZ0_IP`%>vp%<pSFpr%f1e zdj6xy20-<=PTcVtiI+{|5VQo^Z*7Z^-{B5DO!%#WwC!UYoR%%;$G9Z$)0 zMdlMT@hiOR_xM?r;hct{`s5rwC!js$r#~+ z-E<|e*^Px37KYQrE?UcA4_^pT*nRvjQ2!jQH9&odOH190zkCh8EEqGiyyyfT5S>97 z#e~<^mKXCZWwdMYJ+m7U)BMyU&@!bim(&ox>Ss0iY;`?JGKS{ycU4nC&+-)LIxL zNeM%LqL#v@Y{{(FSe@Pzzh_)~`ZTG`n zVNk-8TMJ4hfzA)6dCiY5s7=3=5G9R;Lj7U{3sr^D$u9rMk$@%3|i9KTMz; zG~Y@q+*p`~aqg#WU93lcM?a9w*zufT8OxmKPae`@YZ+68m%$2woS>uQqo!o(a4b7J z`1d?&L)w}R-^6+Q)bp+HA8q$mW+)gm_$<#g5?G+UYHB*LZ(jhYK~Afkj^zr87qhLJ zw>*3&jN@|4lce37pG)oJu;1VfuNlZx4Ydo~f@r~PYU<`JPd8+zFJT_kt||g#0V?GB zome%0==+x(EEw%^z4veD$e`97M>XuD^!N_l0bmlFSN`yg#6>`SYZ5tvjvm$94=^E) zBYAYRK1j)_Q;4#?P1l`vvb>l5@2YJmQ;?95s9f!IkM&!oUdp}ApkKNfkXdw%EI?## zs6E!VY7on;uMXSrGjBF`u>)u@Onw`i?mp9prgyK<5*LAn+DHT@uKHnR_cXR~ycqK4 z=ll|k=}KYvW3QzyORJu~!|=J6+jw$E9aA(T#{_JnHOS@?Xj1+AgOIK#@rAD$Q&_sF zs7lZG|JcX~Q%s$8_QK8pe}C!|RsHTFI;@D=w~(9Dv!Q~tQLWfsfcZ299<55^M&-3@ z<{$q+RBhhV)9sI3lzh@uud|zPg~2Gj8gG$zELle<=3vi#`<$G`hRxR6Vyl)CR6Fok zi?MOqsoJ)nsaLhaYb2s<6x6)hX)@NYx%AoeZX@yS%^SR{$9i28_1Etju!{DL08n7n zz%fYD>X>2-`$fAs!$~RYu=u+N*R$--ELYanEq<0;p1b73@;OKdtE+?PwKJ6q$COp8 zSHJ%^nSV(A`&qePfGcuodM{jYN?IDWaY5P|woQwjo#m9J3-j{!-d`M^nLUU8X|q5jLEgeP-xsJM85&JqB#f@YMuXoVSRjH& z3OX~!tqE=J2M2eK2zIIlgdnIW(IDNsm!Ei3Uw;-WG!hW|!ki~1|A$70zuW(9qr<=; zdad-Bf{dpdk&l5MUi8RWDj`khf9TK;uU`Z2ex)#M!TbxgGk|K_ z%)EZM@{z!b3~L~4!aA4@ZMns{WAZ-R>KvTt?9gnhF1zE9LNQ*7RKJk_#$(zFH}ArV z=Yb8SazIsh5cvj3^}bIpm@4;Y^YfpzK`#X7E=R|lin!9GUYwKOwtM%OoRAM8g{JU! z#m9!uG()V`LHgm8-E^mW#k<$=g2=3C8GHigMpjpO!exYy3utlU4XE4ae{4Thytq?O zh6zJc-){0d=NfaM$5dU0%@&@hchtE#@R+Rj{%hxTp%Td6H7E-H5|;N(Z;lPf51{=$ zgAB)`2v^y$u(v2xQ&EJ%Zs&wL?AfR3)r1LNpS_YsOLXrQ-ncZ$l< zuMq61z<6`GYvdk1`i?%`8L@s%m)-h>A^O(|9SD;JgVp#lZH21)$hUlpT+M7nF|r}c zgX0Sf28JGjrUhNV_6ex&4v1cF-r&CpEs$?*I%-dklz-z|!B>0WMaMB-SG2u8ORS%p({uUhKvPKb1+`64zuP86c+vj zl+ZtoxkKRmYf$Qb9u`yH94L;k1Un`Pd+kc_I$Lyp$XWI&~Sc*%?qY1`n`LY$Z)BC@ciOGR3qz zZ*_OVpaE~FGDj?6HGxJ21C<2}U=2?a$kL6-u0Ftafm2u%@If*1R#R=EfQ=GJlc~yH zU!9RX8sUi9roSQlQ0Jc)ofK%ws;a23R}*-U)nGHeH!xs@ALt1b4D@&km-eTmFp{OT zeih&G4bu@!d_X~Q|8gQP#dYG=0>T~6ba>kX?KJRrSj5=k-zzJl@|d}G7s(+>3=z!0 zbVKIQoH@C->5kRlDRv5K3Ir+88;afJgoGcgGzLI2mxx+YaI+km@5GH-@O8rYsg+Rv_3Qn4+u;~L0(^r?*#XP>{u3`+9+?%c!xWXLV_LJ< z@o4-c3=#Qg+#`swkgtyS@tsUZv2WG1u5|6vCC@DHzJcYbhR(me-#$bc zj6KBs8#Ufa-mOVw*08w88ygc4?$y?+ZGA5pD$DeW@1g7j?Xl068*RVA+paR)euJD; zUBP=}=6rb)@i_mzvavH+^&ERF0?=1zy!2L)f>G~AdYjNb%?@87-^Zt5(`$aqDtwwyGHI3V^Cx7$@gL3&$F6?i0q zfEL&QAdF@MH0%1t#z9!EGid>9o`kCzWZkz&$gM_bE_dCEM1tcD`9)U|>|s!NZj;^v&7N(&?<1VXj>S>!0JBqIi@f{v$?=qBWfTpX)4~Edw zk&;U9bsi&F-i%0=1}B&jXCKD9A_xwlEEkv%WJR#9#|VI7Ol+(&MHq)Fl?S&2bg^er zmvkFY1~tgsSZx#LhZ6`~vbLdcTgY&eO z+QcH$e*HEd8sO#BBR%l;>n{eh@7Xj5M+pk9iB}2=R74z%#B1sysHH{u5d}$Xc$Sq3 zBg)D45Tk!-ZDo-s1Ufgab@AwV=+NhqfrOtk>(;8y9SD9I&vH6s5`?ckdY*N>?5c}8 zlIcdpZ`O?Ok5zNuGOKgXmixl9W74i-r1cSEB{NJ*4dcri)?6Y&$e(BOM;coLJc)Hh zmd$w2BVy)kaojkEiA37{2P4Gzds=I!UFDrEH7au=rm~QyJM+?r*^jQ-r%Yke${r?!FLx)DHEG}SjR^6UaE0!#o zT*Mw%%H5rP0ud6a(2Jnvng9+5v98@&zl+&@Prpk9^oLxoEVZnvtV$#ky|p-Z-Gl-E`lND%Gwzf~8Qy7IwZ~9bd$75I zjLf;s+6JYszu3N=W~ef#HglPxkC#-7LIPfMSv$u`EsYzHp#ALFe<7C@MFzss!oNBr zl_2XqpH#{~qj{m_Kq4|s?PjV5mOMg{g1oyH*||ugeci#V;J+*;ARn=jZ4!!Kfon}d zW=1$gdP4Z;u2yPtKKHtoXs^L}rJn4AYb zhb9eyd*_3jjB{|}{k~~w>7;agfY_LpG1+oWUxCZHBD>n8qg8FKDi+Ud?u zcdvgon;e_@@f zsu(Fm0y_6#0VMn@=w%R@3EPrmGLQF|eR`YLWUns^BzsHDdTjJ!A;&VPJq z1i28U-u!vpSvS*zpi%&a61Olpf=^{%*gxEOtdMo&QS`uef&9{+Nm=^aN?r@aEgOO! zg}sAADC|(?UtR9K#ks}gIZx>6)0dKivj>Nmn$g^C7ikf12M^x4d&Wr$0wA}4OHOYJ zFOG7>Cf{ZKLY8|{-SWW5Ihardhlp5*D&aeieRXNlVutV)78LL_u*qwR98r|^mZ438 zNcqf25nAGU>I3T*>+D*|h+>#gC+A*q8`Q_ICa(IyuCe*L^|NQFBo2@@SC-VYx+vVOw`Skiq<+=Y2pHEsdlH*LG7sM;&p zaeGI|%P)UD=gyfE@^sl*pV6bQxxCAcg4YD5QBky;?MdYB@^5?`x)A0l*;Vu$oA4bh zv}Wo){s5u{An%`FzZSoh%Z|TuKLYQ^Uu%&mfBp&o4Q>MR$d7=Y)Skiu0_ZErt*S4kMMAerz~hDUJT8p$ml2+EL2#rUU}!Sc zQAjGF$?z=vH$D6>PyCn1-gB#5il?2OREpz>L4#v13r5Nv24kZK?H#Mcmmuwyxjy-jyHDD^S-ti5_SzFStfY}TdmFNX$H4g0F^ zJF8C=YRdyF85oS80$ z>hq4Y2hk6=$H=1R9z5eE*v`YFo4_zR5`Y@!T@H2zX2mOx)KuVyUF{)sk`oBAqqtXI zCs6{j((IZyNMA9T&fiD6!^**8=rn8wjjAn-%{v~Dx>V0>$ajIn3nLr`FJEyo*WBY> zTwX3Xaus~n5+U_r$O+mDGqcog$_!US3=sm00dlZc4Pnx#x9?&j;1!dlB7Jx4LHJ$%Qw4!Cw@&-M1(3Lfp+d(_I{3u#MPbrDH9bP?H2 zoql(#?G)%U5~A!`oIIsob`2#W5gpC4cdl&W)U{{&rt81vb%B_Gm-X)1(*w4Ye6%;+ z49NgbZLz@`-R8JT?%UU?|6*yEbMw{Z1B_)Pk~aSOs*`-byAZ2}+_KeW$(G(_ny39` zUKWZ}oK3KL+P6|cK|fh7G%}~uM5u=wZxQ|$26@9h z;D23bXD%_=&$M13Gqh zleeE1_e)#R&U&QXp}21PWk+n|7|*;-JDHbFE>&2!($I3c3!NDVo3I_R*+C@4BDDJ# zYn8Mcm@K2C<21d?;ltOwL|eslbgp?_F2qjd@L~1#^`6$^t(^0cJ$qieCgNW=yY-a0 zUM@S;;rcaEPZ=?@u5tQI0{+qLethskUIOX=r8^buki5Z}4CgY^vS`e#y}HTFz~C!( zS=5Ri=e&2)eOXu1H9cpzu?k6+SXW%U8tXib$KV-!`{qq3aZQj>spsG*aB(_U9_t>u zk>AcPOWeQz5?mgi>PlbNVNZ@;)_BqDT^7}j;ZpPLC{zpRPVvO015|VCmbI`=#|SUn zR3%C{;%TZwFBN2VPI~BBFx=89$s%ip2mm4f3^4t+pOn4G)o=e`1`y6Ssbq(cSzgEzG?fxtl?$5yth`J?mB1snpxVvvvJGo{!#bp zEu>RfDU6^g02&ZX3jZ87h!tcVva7iN<=rA>-vF{gHlf`vv>>-{-%cIJY3Q`1xZd1n za37_s_7f8lES)O~+ZOr^E?>&J_%1)&raP~mL_6yG(|#<6n+={Sad#~4+_nE6Tp$bk ziGIeHI=GLVyzu4)?7$7wl+zOYo9+l$qr3aU7k=TUo*bL(c`GX`D%r-0%s+qr2o&p6 zq2)_-bj07@!&Y|3t}gHA_DO~5rJ%4DKnYk0Q8dsuS+hHP;lP;m=pp~l!U~x2PyBwb zFd+vjLT}6yPHxX`B>U|*#7b|HPnY?AUgn!oFZ;A=X|=ay>yb<22Mw9hVrzVcRA9)hBt$4EJ@)Oh zuDdTx!ajReuaHWSSE<>GuV)iK&WB+X8xvjD9GL1o! zfz4scqhFS5lt13LcogJA3M|O?h%~UyL**{SbF>O&8(JjgK-NMD&h#)%LuZh*aQqCP z`ZfO*S_96V^yNQObChH4z+sqo3+ zJ|2X#g>JXcm;6DNE2I!C?L#sj_~FS43Ob4^bW9pmKJaV|A4?-H@dFF~^5u)#kET4E z*qgJYm2_`>Jnu7c1+(j!CGZnkP1cvWlgN<&qR+3nG$h=#m-40LyKm09o+MHzM$RG> zIK)dCY(HT4cE^gz+%jvKS_#DxsanfKgZQ4`qcv=+29wqkuewt+KYa>0LDDRE5-?Bs zGYPd1AHQejSQ-9(I#R+eb4%k6NtxGsGRBua)c6a&11@x|;&53v$mb$*3>X#$d4|dh z3#jIU#icD*V9o;i_6JY^^^2f9MYzJNrzFb4a&c(bnv_7kLA z2x#ENXmv+{ZQ=xho3AC|x#qCO``oi<=YYvBi*g;LrS+&-d)|jn7oynk6cd{kyv%ZV zXm?`fQ%lNXTA27_Eiw5hZCA^(Bc-Mt&NPQVbQPyiEEkwkEYA+44@>N)^GR`JFU0A| zv7pH*y@`w9(GX+@-G9dzbxMF==BhX)~SaF*wqO&12KwMOnE{{QeG~5`rD-Gt<+1x zT=b^&R&CP`*My+M?`ptdG{FKV+u6dFE{a?rcDc+u6~{=_V!r#$!*Ef=El zmK1z>{lKp9uqrGwCXuPjN`CI^pXkEGU!V$-D-ezk2%Jut_z$qm9!wMV6lPExp$CjZ z9g!zZt>nRjV)*F?HZwRYC(0Wh`P;Wh1>Ynk_4D1a1hj(oIZy!ug*^)%XDr5~Wg{vN z@)ecmJb~5l8rYlQN;%otZEurTq6eP9B=L~mN}&(%GNIPn7urYKB4O`dJmim*ZqK1n zL46HW3qDJGj0=#8yq0}SVmy6+y#(q`7JMHJ36Hzyk(@hzx>w-$%y4&AroX!%wv*Ro`!m zbu8*_@hs-d&)J(^WehsMtE>2u)%h=P?_ALL>}=~ZgWN8RTQ;sl^?FBm8+5+>0 z5C)fd^x}KiH=LthEf^GTe0s)Fa1LfFj9zl>-tH#faBV$3hQ4;+8oPIImM}#5=L?Lv z1tI~eOzeP*24NM*^5oR+inGdnQX$$Blw>*$k5fI|{oPp$ey>l3Wj~4UnnKLm9 z4EFR?Tc>9sORCB#$f6`e#dDmZoUGc3K6}L@_~iN?7tf$41hH$_t4RLtM#rD+%3Pvy zHyQ6hrmYWyP{mDyx6=UOw%&dFg$8Zc?%m!7`@vikMy>zsSKw^5B%;L1N&-C+T{&t= z{PWq(9JTQbPO@3xW^x?)8mt%A07nXCGzwJ2ohFc^Nq30l0C;p#`GJLi?X$nuX`=k# zqn*ym5=Pt$8nq5_SD{oGv&?tdGN=iqAIgL=Fi?Xi;DlMxp&REpm%#Rnfb$r6t4FV1 zfk8n>3;Kr_>2|Yh)-yI%5ut;|xMSTmi@%`w_K zIutKp!`Z|8<$GFMhOwqGxO{1cR8&hcBPZt*Sr{}-)&?0NJ>RxGP3L9cfv~0bJCO^6{iPk=uM`T7%;dcJ}Ig3-Mb||K2jo5TN-9$2qC7aO$FtN z*WP`DYRB?3m$d>*L1FcQ?xN{$D3qejpFgh(Q%72Wi*8vckDjEHXvP{Q=NI$hUV)5| zm7PWxTNfJt`0KTVX8CSsy{>mz^TQ%c-6l%qFm9d*BxP^%CfLlBgHmBaB`G@TmcL7V z2e+HFe?P+xcTNbuQO`d?_bBgnd}`tQ#a=R!s^LD>Is0x`&UK;55AlsA01reA)2X?u zE~e#b+MIrtl=md&bJC7R($3d3f+4J!{~a`Xbo@d8Nv+NR!RVMoWU+lQw>x;Sryvv* z%#h)&aqnU;pRc^yx97}d);)|XYermS+lZ;7m>p>ajavRsR@#HDC9ef}G`)7pAJ$fe zu$GMl@?06i))8^fblHN-3ZG3p-G-AI?ml>RlVa-6u|`I5&(uiBD3_^arX06U9R@v< zjsd@nu*7a!{^JpZD7Y{j=zJrSIG}pGoUyySgeDR=FrFpG94(x6c-b6GNnt~jO|ui3 zGYFdjKFkA*R2+_Pi|W?vf=vRB(2pZB_0uvkikV|B;x`krF;~_IAN1|xv(bG1-iN;W z6dE1r`uvLL^tp2n5#iq5R2WseBgWi8CU&3o&0BIVr{%ZzR!BCIlU9%$eH5hV58+RcB+{7T5e;PxB)&L z5M~}g;$sBoGLl7lG9lla_PsQ4rh1H}^8fGw`iVYMK3~0(@7p)xtX{b3>`7hg-%Z{T zsSvNHkn&^UPCy2{Lbu#o!*~OF@zVr_x36zTfqvB%o*x?2(zVKzAM#T_uzY#@>`~%K z*+6{i<-1*f_l<>nI4i3(l%|_l8VO6=sE8Nd`GIMx1PYMf_|RGGbPHL8ntDeyv?Vo1 zjgk{}?>%6u>`k1(x`$MJh`Jnq0Yf-Qt?8~jIEpkqL{ci&9+z;_I|&PmuDo+#!xdAKMH4TEBc7o=bF2g z|L9flW`wzq&oOFE^$@0}%>HU#^$Y9}6$+C-aYK7OZ)5nNEz(vQfxzc-48DO$kA1Ra zKo8P#Tyq&qNz@<;0uygyULfa#yStK|rR4%pldE(QAwVb&cWaF}VVye7-Q7fA-;Y#? z*Kv@{BR3U5k#TW?v=@aM>G1NXWU$r}Z_aB> z`n)yL)&J!1=JV&ng*g{!Vg(urokctwH}!XbQto%4K`XxYwp%?*H`T1$$5FBD3|h$*|a$ky#lOA3NA(#@*>orEv)lGY3y0W(k^RWh-%${8h_YQl zVX5lfO@3}E$RSS_mSM*RNlL%mTSR{`wh`QCy3JKyn{CR2o0w-V&R^2Skv~`h0xf*eEF?yl4C# zs-u(7v{cd_MCABW(RX1X?8>pYcvJws4jnj9vqnNLQ*Y}3Sgzh52#jF^rA)hbX3v+a zlM#^|b^Fu)a;YRozLT@_m#<%IU`xVx!G0Ub8SDhpwsAY$JoKxPnL;^Z`N733udY6d zr*hHknI%J=f7ZWwbNKY>J@%TKt^01zk+JEiSiA8CMA;}=txq3(GrEcBeSjPIj8DcC2Qra_|JforNU{QRd_vri3{f9+3MLhKtzo$-T97bdDaHI8jIYhsa9I zyNhAj9eEp@@U30z-`WhD=h#hLPD8_LW}nz3+YXa_8Ot5((UXywaGUg0NL7^dJ+3{{ zl*~`u)nmc!o|aR0yA~bHK9N~)p!Ygd99S(-S+e!n*Hj;{UN*gax4hN{D_VLJ-rm~l z)(U6+XIhR48_;9lM3doBzW=ge%H?^%?&fU{Pd4;k{v?M{8JHd9eqYyZMhT7Msn*tu zu(N}WC@Cqa-f5;eI-2}5?9U|+ebH{!v7feH!DWDV?E&YD#$Y%5g^}6ma|R~Y_VJ&6 zvr($$iQA<6x5+7Cv5M3=z82XH?5|jV)W+(n)oz>Ipz@YK;>0p%%FHic))8^&z}K0m zXMej$q09bZUWZpp#NI-gv={ZY%Z3Q`+ye$|>aT}0HPoc8xdYE)TRT1twG7e7g8 zdpGd7y-zY}RZNU5YCVn}HZTN3rdF{(rh6*24|AsPnD@FCWfAl36V-RzzHLL-TYxQ=EkOPuVg#Sj z^@+6Fx^Jd~f8p@!|2#*k;lgzrD8~|rdT&E?xa_`6W{j$WoLUF7TtzSG4h*+%e|aWv zRPCSzhCBdRnr^BxVi@I+TVojv6p~RmcZH<_M`C>$@J66yrZI{7mw`6i34v%mErTaprL*FJWZ^95aM8jZ4mQp?GcM! zy~JIAeDn8$#deOCCpb|3d7lXL87!r?}9E4D0sxana~ zF9{XZ7oU!$k;bPTd)85ypxD@W?f2g#D)}Z52lfO)Fk*Yo*WNjlfpAV(R*(q#_ac4s#u-C!hcWgabZOPdCQGJHN&r-Fy2Ovg zp!C$K6;#atj3CX^nKDwpN_c#_x<|6IaM=O@J;nN^Mp-lNAZ)}(?^}VJIl-l`*0cC& z<#D!5)m0GHZAe2i4n~qz3)V`1liu2Yh?ph}CU{Y#CB!0B3)n!E5=yXK#Y5m2dQRe> zhQ{?bYXlE>nlS?ho<4k7TtqQLJ{`4lCv|^^R|&Wfme?JC{*>LVx2k54`TfPY0{8Fm zL9BAHC42@P4cu6~LG_P}RYg2!8q`HBS#;`Z0`TF~;%S;H4fpqRY;e%bf4)i~S_IUk2UW zaZ}oqHuIUXPM^jnWfQgf!*(@mH6(WPk#ay46@eog*Ev0*_7By3qUOX|fgIPkB|UgqJHl zVweRf7&NcpOtZuwTxbZ0h}KcSDr`V-i`xMWg~F7{N-W-@fUw6fcSkbaF)MzU@e{Yg zjKp&JQ75`_M1IJe{noN^=*`z(ct{B9;oaqXm&G|}+CX@hc9a5Z!0V&1uuxFsL7ky) z75??rdSlh)J&umyg(meM?E8eTnA2EpNA%z+K(g(s!03@L5Bh9%~940?mQ2x z%mn%FjJb3F)^!z2n^Q>apgaJVtEjB}3fZ<}3Ef-D+QI!hkXBvwe=lz#%Lj#fD6n+@ z<2N2aZ(p!y&WBnaNM7Dde;Hm7g|*i6?>~NksR<5R>()L#K8s`Ctg~bEy0vuffrnbu zt|Tn1JeU5{R7umgO%S?|8wUr56qOS};EFTBi(`{#aY~IUnR3WXY%@H0fB#m9^rh7u zoO&bhFQHwy&W`CN&+Vs7v6`SI{D~+VL0`*Hnwy*F&J)ci72#y@`#n0WD2c-nK0Adg zQxez2%21qbSvxi(a209+(mmQgcW~(v4o)8Qh!67`KE7p|*0Ez!B3Qdo;iM@v z7KF6N^SeaMH&ewv<{M2L-ZD9;;f;l#{+VZtGVu8HymtMMZfa`fkHwAET3gNCRq=)K zdl?zp8o(ik1eA93O}k_*TdvWsli&@}L1MAZR0@-Al5NmiPfdiw z8r>kWZix6~5L!$8CTDN`{HsHNyXitwn;{++<`2i|*prhHn$l0JB;Oa>Nfb7JVY5=p z0dgQ4E$=5FtUOlwbm_-?CHOa&l1#WuxWRaG7=lbJ5H ze=m9r8npT3Ft6O?m3tGf)=r+S*yx{DvDr~VEAxVCLr~YQvPwtux=IFY=KDd`n$UI; zMmPeQG$XKa->hB~6rMeMmbiT)I?tDH#GhZ-y1VCN@z5bC(8)XC{-CogxqTbf-LsmS zXaT$~jb(keRd)~F%i=rbS$Lj^(AH(KZv6N~cLenFNwj=y6=XlWaaX<@Qt?|bAO}4O zvl}Y+20oAgEi~tz`JUkh?ve)De{(qkx>!sF$#W0CTmnt(j9<>w*ibF z;Q`Eu`1ITOml4`o0`n5dG(fNz6+ut?38blK=N2`Dg-UAp($~!x4ohyX-ry2 z`hu9xpw6F;Be}u;>euQI-Yx?e0*mxEooTan4P<>qwVa`qf0o_pa&o%VEh`{LiULhCd{!# z!6@>=4gwa@zV`)E>%$97=mtK7YJY(9l{73qau8-y(CClgoo~=@H(120R|{a15_GT% zcSd*CR9WtF3bKQtVJjUjj&JAztvko>=F}&P9CX(&E&}tpAIA?F~uSf zFG+&8T#2&hARO%`0JZZSIhZN&y=_ZKu4OH2XR#t?OQSaJXic`sl+xU-O?&P7)DzkC z^)bB|7&2@~7t?`&nkqAAy%=4a87tTLeoL12<52U)e;Gcf=S~dz@T-1bN1&@0 zp0_g*94Lb!$j_Ds($Xc*MD5ApFs!5X^rI>N&NyRV^pcWNMg#NsO-OTF$X|eHTv1#- zJT8a)T0`gga+X56W3NY1jk&8Xd4Tm$U;$#y5Tt{-l9o|)8Q-lMN6JFLgoxAjKsmq& z{>5`JH9UvFUwGBHZt_-a0-Pn&FVM4n{puC|fXXz)l9DhPJu-FwtG92rjhZ|K$`L&m zdp9>K>_=?l!vdxTu{01KPHDpeiUzN(W!_(dCx~M9?HfY?F*4HC+D%iCi`;wM=sQZ+ zUjNUd>DRBA)Xo<+^Xs37YU|)$^}h}$o_mq$QlEg-m>x|H03o1qWarp+K6v+yWVo4n zp{Z%tjPL4II)+BY4^qy|?;7$`jd_Q)E7Ok=aA}fpQTAXJ|1Ed|B+1+TQT(s}`6=qz z7<~MvQtEV4oKmV`u#887?!gxl>H1>ABSbX0fZpdYMY54dA>T+1d-$&8)-Cc4QkYz5 zd_BhqvsQRq^z&i{EjRkjsRPIgE`$>Y(zz!8GY3~*x5mE=DglIIxSOw4oYer zrAO5zR+sW6wnKACh~Ze~pdL5bTp<3n@)O4=xnog5K@D{XA(anxv12H|Enbg1b($r< zsY6U(f2PZ$`Q#<&J=)n?P_Y@;f`tBVX=y7lVN>T{8pw@AMQFB2jUO+qyLN7J_(_BbLfXw|rb5U>v)J$l;xLUfZ`jRO&c zm1g$q^MjGPDe2wCEV5&-dl58a(r>ef4}flXs#p%Bf#iwh8tMaD4a^L|0xW65I)jaA zTb-8N@HV(nT#S7f7Cgs}y(jqc;V4=tx@%`6tz;SE&eU7Yn7*LDaANZq+lAtmuEXNN zx2bGlYzX)_LoQY%EI{h_=ir{5PVXwpMYnFPjE^q1_dI%Z(yYhNL-+3Mlr}NCYpPkL z$UU0`H0^y^>4yNG%k5|KXPNZVQ)l%Z=GkM(!>~l9ZsM?;9*YNzgfNAWmAl{-+%73W zBhG|m7%HtFs`vCXsd@H{y5#ku0VIxyHx;&Ce|m0_J-3bf8(_I$>%b&T$Bhu3Z8}Y=i8BmbL1+07DLf1ICs7;Po?vAIyPsU?+BDDSE+p4vRvaEdfS0&w{LhEp+d`HC zVXE%v-}4%pDv7n^`6AM0P1l)jXVNn>w^pACO}TTIhumYyz}#HS?1&M6Mzjn%7+UqH ztDW8P6O(6ZNs^l%@;I$Kc5F5CpuhpR=dlI`83l&nP8)j2MCjOWcHI8xX!<-e($O#? z72Wege*~HX2N+5*SO)|;@LDdq*f)BY$yv_31ZIVfpA%iEnsG$Mr~XgT@y_A0O*TRb zlLE@a-v0LLmh^Gy_qw>!V0;35|NF1rWG{NyN8aw^X>$I#1-pj;O<-{Uy8ziuqZ_jYP$p+LvmVW`f*1>R>} z!-g#ca-_d65|F8;CLl;7X#;`K=xNf_rKw5XtTScjfU?v7c&MM=oeSSF%V~=}rf9)#hR69ZY19p&;DRlqrZZM)@xyKC?dNUWBBT29!)0C8 zxQ?!_>88IOdQ!=OuCR;-Tf*%Z79c3Wq84ZzrHFq}BEOVul7;^lMazuUvZ%*=`+wO&GU#Wy6hQGrWAK1X!eqlJ9TSg`6l7 zDn3CT2(8&U_W#TG(dn3b(hwbkWV4peDnxg@BKmwm@3VQrm%vPj2~b} z(x6ByNccofSD(DHh%A#@%B66Em+B1v<~l!#Uvckm_fm@=k>IC2DGE6Ts4SB=Q$d8b zsZ>-SDJW>C5`m}&>73llIQh`6$ox9 z%=?CJfXo>PiG%~gYezud^dDQ^+q4d5K~W3{W1iQ(b3DH6y)G>%65XemUn^3UH~_eLU}W zCCPR_fA{ql;`z_^@5{c*1-8@;cRiyuZX5?i37?NU)k~D^A_`L{z%f0GmJOOUl6zWo zQ03Lv_f7vlae7FJyKg3G!$;vG5Gn&xmY(WvPz#7E414(b$rI>}RwwWA+pi9icr2G7 z8gZiU>^CuZ?3_Uvxy1{=`h+Ttda0HoED;jRY4-My9zRZD#`@gM-9>9?bkkv=y;=gN zK>(x4WCg>!rVQ#4XHU;i>QH2yWVGwotvfaEYEk^W^%Zu8Mn-}qJ8M)Jpa~*IcOzTi zg^>`sQnW8va-~X;E#`v?%}k1 ze2cv41c8M0&|hBuEA4qAENKfuB6rLignilElYKb@#_|f(3TQGfK3P(zE@?S!+Dafe zvUDCJKtFH-8hSYe1rsJU(fkGO#H|AISX;owNbm}N?$2@@x}oN`;_=hsU_v_QJC2$R%|j0LM!oneX$e&`s} z_2|(~R?N5MgVlmiqsbvnL(nE>zIyc+oLX6@xJz4=$c169clk0dKNgF3^I5rV!D3f# zOw4;5DqiNP0gb@%eNa~i%oaVtW7@Pm0xMx_P<+IxF;&Z_nx1MoB{R<7wIH_Vn7NEX z1xT4Zc?pZJpRZN+ewxw(tjfaY7{A)_^)Bhs=YLc!Q=DiZv$){j@cYrWRZ|wcGMgm_ zvVR06GmWeM{VD!D{)^mB)lSsHTx2%}rLMDQ+k66^?agwbNFq8BgignM#V)HKp(uUe zfJo%M=*676104pVyYAlPpAC?NM*57sh?j?L_8ro8-4pKX1t&$WxvAM zaHJ9-rv=aoUeiDQQx9Qj>{b~w#nSQ>%%hn~l@5&OdwA zB`Qm{qOyeSp^}}F$i8RGzVB+ zg8CbZK=cNfpYahT9v&#nDj~Nwg@hGdR}MOPz(@Ym_D7H2_xC>z*Fly+83hT51`+0o z|Et=o{G0YUrKK-o z77T7ZdebqFA9Qh6%4t$~cyQKC;eTMa0K-UPcf^Y$&KfDg1H;0S57ZP%mssht^77gS zT9%HWGyt#weKdd}Pkf6MVGIlss!*`ISyhSMrB>dP)X(h0!4#!A(L@jF2H(1>}glc>cV?^#=tB zO%RS4kVKk3u-%>_4Q zBqw9;Tm_zIp6gO|PkQT=+ zK3+AI%;efTV&~!U23w7Bz>zE1ZjkN{1v%PZ#88NmXn7PlNhpKKlwH)^4tOY^e!2JF zqes0!({bA2$6@w5O7A~QUqwnOKE`eGDlK)x=i9<{>|vbvHahAM4Am|#AhQ=kbP+x< zvoz$yIHB@JB@0Y%XSd4qeKbuDv%Nxy+QO0|LO^l7dq(ri%&7wQPhzOP;XeM#E(DNu}c*S=T1AUBMVev!21alqgtDCH9)ej%q zO2@qECWfz}umh+IIt`5lmi@%Thp@FnvAOfgvFT)ula+0v(lz5`F@M`dL%Og2k*Em?DFR0Uy4yEx@GC9BuG z^)a@g;p6k#(Q!u<5Ef2kX66W-*);Po72{QOG&b^9`uX_4u=EX3$uuh6md0c>cut3v zshpUh6$Cv2@MPC6q96gF0lEf%ldKjLUi0b!;~#5d7K+>XA3hj^Gy>m1G%YCl5k-m# zoI;C4dLId`<8PGlLveuOfs$iZ`UiAvjZV+rO_x(j+Y|w~1MLay)DZFQyzw2VM2!k< zAxs44`2+VIRV1>5h!cf0L3tb{3reO5qLwD{y6IVWqb`!UHq3$)MGVY@$k{X7S9<9@ zbQ(69iJ%|QF>-IlNtC*9D-hw9XffbC=T>mG1?YBuhw9<|(F(}rq`04h0?xc8N(&xl zJnHh0DX~E`jhS00(=osJe=OXvBV!8JF3T(ABs}_fLa_V8(S&m(T;v4$B@8{ou3%l} zb+%}a$m)7;vazd8^}j{%bnC>ugWcT;$vqxP>hfH)bRS>Qaqq!db?lfodd9js7-8jQ zWr_Lq03h$Z8UiSutQkjp)VJ#17I6>R3`06HGB2?}#R!1!2#iB$&YogF-UsNij*KFS z<}Zjoz`Yac{SZi+wZd>$+uHiDRS~A!vjdyG&qjldLNJ#TI#~iV-mwGa9X>!i0J1nA z_qF#v=+vQ-l$ag|uR_2&=)$6^XimOs0ue_tMy)l`hQEapMOIw=8$nWuC0OR@qKd*Z zh|Uy_`w7?Eit%Ghf}`%ndCvI6Af`q<;pc^gGnhIP4n1T6^vigt@XAmJLx-?cDFYA# z?9q_13TZ4OI(L&7@~9|J&O%LtRe>!lE+WDKH3&n0XMJ42&ch$yU$O!Hq2Z!Q`q1-d zy{V(u9si1u!O%*fNyXSV=>CG)Bq@xF_Vf15W1x{K>d|+7_E54DuFRK`h24C-PR8c55kq&%N zU-fC5#nj{^7C~4U@~6QxgwCmhE=GR+O*t#}py#h%1&ZYF>ZL|bNG#XjP`SgNcm`W( z@h2O%Q=h*L;s}jrn3#HS*!^DO$9H0;<3&ak6rBc2G)VISD-28$vJr@)2Rb`@&p-4E>6Ws*Hu96SOt@vAZZm6$4;A;jTfyg0m(b(=4uB;q$A(FrHB8 zN5aFkp_#=Z!iI-Kr0L(7KFt?BkeWaJrzYH|F#)I<9VH3`!3b*7!r@LptuT~z+CgfF z_yv&IIKL5pj*t-??GflhAcsS(jc{l)Jl6kt_RgO>2VFhXhaYa1K!uzEa5W@kpu2k$ z2@o~`sMXfyn@d+?Pzp9sPtOfZIGwyN1=VEU&=}8e@&3p%sXUc?a;e^0Nk| z3fBwdAEJ&0l8d{CBvOO?tJ~TwHdfFnfb+tc+oWe-=7&zJL+;uL00_z6Z&rxwLcep> z%E}c!L)4Y&Es4r_>!9GV+u?vl@$ygi%&5YX2%!l~`!yd~SXsk)E{6UP3m-%5XybcS zvbYPd!ZlSTp>{+;AEbs!Q_p*5u<`dUZQ|=qoSoy_Gj(lLLV@G4W@GccR?WTpwva*} zksG|ovy)f7Wm*gjOggklTz{9?$>{K^y~cDS>mNayp|a=;DHi{cJ1d?A zn;Vn(m1v@lOngTdg#HB^yxD{nb|GXr;Y5Zw5tZ!2Ll8$pwf14F1(lOM^6~CdYkYzpl1c00WB~D={zsc%wcUIdyJ@Fu{R+&0NES#9MYQCEdhR_ zAb>Jx7g8(HdtY7a-aGC}edrG%Sn__6V6S%{i%c$&o#f)~P6S&L5x{vCbcAcb8e1|rR^HP~2hzhJX|xU218X*dAV9UZk|3e2U*V z3uGDv^EJ(`0@E_C6nOph^`XbfFWAumFPXTM6de^6<6quKAx-Lioz$?cLhtY!g#k7q zK)~mte-Hvs$N{gQjz@b?KR|(Er!yMI%vn^mSOb`X_Fx~%1ZumjtRWO6Jc>BVz>p+& zf$hNMV~^+W!-yo}Uv!8*XJLXXFPC@s7Hbc4tEGzSi(FAOlEreK{X40^$s3}`T4WDRMpkr#zW5Q+`ps)4+nga7};o%hkmi~ zD^g>sZS2weCVO^WJt&WE&&&)BaHo@{v|8FKUJh}}aU&#-VA(t3ke9Q#;sHDq_&mHP zA8Y*Pj3+qx1el(4bg4g~recel!PzT-l95@ALvDMKjrepD{-Kdt0{y=|!J)#lR z)s2wSB_(y?$dQk55MildMT*9is!?eLw`}qBT>dKa_`nu=9*V?s%4sy10{iydA%ckK zz;4cWE1~NudZ2^sr+|5>B_rVp7sg*<_wdLJ{-@hRHL!C7uDcY-Lh(s~@21@;olet_GI7)K$nNLH7iyz;%L0`s z7oVxK@%2tp?FxBoq$wD>V5k2YU@hIj;XQ@BA3v867EZ@M5kEDaeWeB;-Ehu1D!!j9 zNlC`-oL8;y`A;ry{U0sBctiEjlUeIdOB@Q@Q@D{Wi;WlBB3#e|0Hi881EpnSV=}4& zERmiW_~y*$2_|vlmCCdOb{jz4!kDQ97#Z_RJimY164G$)?Ah$RJV=y@d_D?#PT&g~ zPEV*3Ujtf7%LH7Uj91z8%q~5 z9?;)dK(kD40xWIW-3L~v7> zPIna?0&rhwUWO2D0(mm36y&*rQw5dCgdKKEv>yL?U5h_#7W#j{#1o+XN_qjx3J%XJ z&|cv5!`@Cy`ro{+rD6Z?yso)t39su!&!7D!Rb}d>+em0yr68%o9)^9#POi)v^*L4^ zT!>EVYpxHaiD2wa6SjdVsFtgJjrFfbG>lURhhw(ZxpVvu0rv)zt_Nu029L$@dslGx z^@TneS`(4k0qP%4n5w~@$nB^lM{Y|it)`~(sjq(-enAa`1O%dQ$5+6`aTvjoH(`DW z<$zHxvG#I=g^h;}$lju76@|+Fh+*6;2IUg7hR`CTQAWGm(qfv2xL*YrD-eW%I($SO z<3ip%J1#zuj8X{=)DvHUDdi(n)R0-@gaP{}xO;aP2ebmDPIyXj=iurIcQ|-SR~Lix z&Ke-2M}g4ry+VRMW(g95kCICny-OcslfbJL-}w*(1AtVbgaq&h5OR9r+#^2kr$G6> z|M+1lz7w40kt0X&PtWW0wo}~$vxWG@XpHZJ!4CR=Y;{LfRB$w&MzB6?zc7gc!$55T zMm{X8Yj7|PuRA#zhC||n0b+-fl>ii~yvV>?j3MI;PnP#N$9)XoJul=rlMyN~Y~?6P zN#brlr?FB|cOiiT!Y$Ma4zdW{iNt3E?V>Bb4d*_7L1A7VGXF6xmWPDyoPq5?3hcAc z3;&EC0y={a6BQ32Dhks72aG(~k)MRhrV%B2R~KYzf$zU`6QnEV4%^( zaPRBwCGu(kp-}T}4r~h##Nq#z5`7nTUqA{}o_l1-CB@({Xc}*_hD;*Vm!h%#PK={~ zPQmFjei@>?V!7wEH=XM#a#d%J5LDbiK7-@s%Rj+NzaJc2uH5+B(bPo!!U|=+DlLWR zWvYYh&lKtY{?Rg^`;&`K0cxtIMt->gQ`|OqEuQ!i5&yR$;3Vts7o2j#-r0+)9Lruu z2d3tUE$5d#d1gnkd*G&_4J39oz+@2-2qhzdy{N&)gD3&~3Frx|E5XZ{Y*Ts94Es(D zq$`*nhsJUbPNW2wqf06FM{{s-K@Ybd1E9vg!$0{2rwL$VEEJ*#x?Kv*8QN$?AYrQu zm1DW)*vzQ=wim=;a{>r)U6vCJAv`D>P&5M%f&qdE({cn%i4rmV2Tk|Yd;n_9a(1#6S$W#&==^ed}CXiSPUh$0#96>X15 z5<%Ea{b<_KjJu726(1%_3HR|C7a0O|r6ze?8q?>vK5aOoMsmT2h)%S0h}=(8@COKA zWFEdjlUVdDiV4eQz^i34Y9kQ4&zLRdplgaBkvfiwxx@)&y;?G$I_Qj#gUIYt$5J`* zDEg>2lfWK4auyyQSY_wUCymIp$Pz^OCBskiSlP^(S-o6Zq0t8ndqG$9u@nurB00Q^ z-^rd`r40jSv86>H&`VfY15RxKcQgY|R#A(jI!fFct!Oqh>;_5H*e&+Jun6SzGLY8>1C z@N$Rj*uK5aSp4GvEtFp%U&a>}#2TZV ztU!80C?YWK2+1iaAvyWzx(58K&=^b*X$5eDp;6U{yK8s#D(}LcvFfer95Gh^r!A8F z9PL&P%rHky4#gUXqNX$Vd>MG?NjS<#*i`op_MjOdH41H4g&^q?BGy7e&fx7LG!Hm5 z!JZ88j+`T*$AS>|TFHI5c>l2`D-#t((jVS;ps@q|EP>4lTRlL3mCKi(%?2pyz@H7n ziLY-xq_N_|58y46OarTknM}xS#Og!=59-(3KKvb^FVtxOmY{mTpSX~1w|oTEITS@W zb)gD9W`{fv+BIj@&*t=oQY?cNj|QeoQ8bo|$U%5u^_xh0CNOH>pUz=W^ytU3v~(7eo{)*G0dh>vK;2=)_f z?o-jTY=4IP1_l8AV1)r%#6)m_;t_gktbvHjpdz9{v5(-wAtSyX4RL9o56)IY0;)i$ z*9}Ajfs@w4r0Ljb-d-2f9zf#V-B$r}It}Mrz32Y{nQ?tnlMrfD*uOB8h{!6XqCyNv z_;hphPiR#yBeoRszKJ&U&m@gAXBHq^$~z3R?2A(|&gk2ApNtBflP&5ZjFEQOGVq)s z?dV(SU3~nPFMB}kgF$LIz5_8Y;LI5YDk|L~J1$bFRw3G6)Z{lk(an+=%SENE05qUl zL!3onQ4xUyD(N2Oa2JMysGuK(R>Zf*q$+ei5%DiyH&$1F#G=J1h`P2Ca+c_dOOIM6 zgE?eg=j40`=zeWQN)6}6a2f&$TPC5|{P={WDF}gs2NHD+4E8mOZ5^|XI!8_dJOp9a z;`#Vbm7uI(OG*Vn#Cd_mmg@Bgl4W~WaLf>{3e=|Z@_+DyJrpZZpy3x|XXQdr)Pq;q zgSHT899UScZcNVH_aTPc`|K3oetJbkac9xiIJ(=b_u_e$mz4)916ZAS@yl=^2n z;|H6~=AeYeRb2dd1QpBahJTti@aW0N{6 z=|(yPC)yEc+p5O#<6Se3D0@+CVk*dyP%RknhCgjnNn?Wmi2?jNe*7{H>NLz2J&jyN zV%{aJ2Iw*Mpz2PK&#LzVk-iNeFTWvY^fp!(EQ(H z@Aplxoyp1J7$2&sA#7J*Gf16_hl;2c4rl9?;Vc0Li2muvZ;T8;6@<)%OBEij&{+dA z17(lT-iHUXNWLR`1JycYGt#+Sk1F%%~VJ`~vuSX{V={B_PD9e!Khajq?Aj{$z$Aq4-k{3DKZr)sPQLr#S z;v)Oz4qZ?XX+e!UGoxylUGo&#p4Tc=T8+c(+=||@3RlL}s2Kbr_Egt;&ptgH-3M+T z6$EowF?4cb--U0zi02RRog<2PXT3b8c?+e98wHbcWGz@NW zMjrwVI^svg`+RtN^#Hyc_E-*uAW-2JBK~W^xx9b>zO5~2^h=Kdj$ddV%u!sR=tdPj zIvO{7Q?U;7xQTOOxiYTF423d`EZ|{1z%8N9=A@rO*fR1aP)6X+VN48cYKA2@cVn*j z+OkCKX&!mUt0({@~yaF6J-o#*39}yc18{#K~u_NNk zBbx%vuyhPQZ`J)2r(X0Bh|qrE%BZEgXMO^MgrE12V5U_5)vjG1r#6uYEy&?>C{f>b zoRk6I&4xkBqYCzvgVOYkbYdo zSSNo(6w!`iVwO3o!Q&YAGDM4G2Q86G;#mPOX4{Vogk$|s^dnXT4G89@wW)dZ|Eqk% zPl4`*fAx=`Sz>+vkSd-uLvu*OKpYV{IUK$DXy0r*3AH53eh4%14)SNd2UGEpKe7|( zaDu=EIf}sM!QvqYn57bt$cAk+z5D|)!qcciv~m=C-|eL# zOOO`W-(Yt^EEe(*$p}G_c{7Xjw4|xEbtw)sL^xqK7yj`d=;Wa4!C?ex1%hR4JUmrk z;JySB+e3_{z(!nJnlPK;-flGp0)_y9F}zw#<|O-o2=omk3lf8bVFB2*3|bB^{1>RG zVfU;hMI3PHIlCa}8eUNCDJ)-7kOE|l+HU=O1J9yVex<@KLKC%6u}UOQEv{ytLaZxv z8=s&qCdBd6m#Fwsu9@A(q+jv4v*qNKgAd;GZ1OVTG}(3(`-^j>H>zO(*Z32(KO%BkxN_xO55)npgNg&| z1QZX7XuNp@is9)cqnkL6U(AL|hG@Z5g0NnJKmfyr#g_y5kv3W7gg7HK{n#!nXNjC) zolESp^v%uLg|BH9nk!13eeMbG_I6}3H`mRhAS3(sy*jJ%ZMSyUmTld#c)~TlnbN}=<7ghzMRInwDaY8Hy~(LRaNNkly3id(aWv3qa`_EtnMj(cjyT~o@Ru~$A^BB-yf$4ZXJ%XFS$Vgpigq) z5+OD~QN(ycerEe&25TPM9jf9MP`n8H#`E|mYxZjAu5H~tVd3|tuh!O{r?aO+a?{0& zeQE`T1wKJ^zp~V*T$|p$6*r~G&CPa|wCK3#DCM317@H}pgPE&BwIm8Q$loyHEFCoyNQ~-7}8K>A8A5;r}4(aJgcQK`524iC#3hSc9c__S#CG8 zj=x}hOQqQ`oNlZjyW(CcV#A86-lKHZsT zNXs|iz-M!!P-DF5_0dM{`?)9Cb4Ll9|0C{1H-&~kID_Ky2Xw#K zLt)eC7^B-%-YmWUuzy)Ue&Tn=+JwrXThzhYZG2pYI1^o6OU~{UMSmeChD5_Jnzxxh`G5Iyg#XOXJVVC8 zCbyv>k0_VW*s^Fk!8$jI+C1jpX^{%HYrFR4?VyIrkUkRyBhG`2kotc)9S8LF^ ziUIFPUsrc;X;l>FO6LVOJl>gI5#jRYslg$6xx24jPyqDS1ulQs{3sGrg&%UgnzqKh zWK@x7!v5lRgL4Xl%25fxpCwYts&eTl+=uXH-rY=zo=!In^F;k2RygZu;2l~xg}sD0 zRZ!tx%rg8sHKo2|Ax20^$rFY>oWkv`t%O3^$EOa%mLQgG|FrF^zWV5rMJb3d5EXL3eqt??Ar1HwpsR21Vebcvv|XlV4NvmvBG3)!Xz zDH+n)IKoO!i;C?HWXM%m*HaF45;&_6*BI`TQS_EQFmEtv?Ner9An_i%nFN@c@W#;l zyFvC2j)9td6UaA6{pip&!jX?IIbi=;2?3^*)C+VLZTCVLcvOV9kRuRFz zpr{h?4lVt@g49*_-zMDxw(lsInN@cj`}gxD&X$Jt5`z;VodZoU2gwKCOUjmw!GmU9MNdHGV5-txP@nUmAl zo`I55RzB(69#tJpD%W4n6#POIRb1tqzf_ei2$!<|Q_RwPVW%_%4CaB&4R39`0TtiA zdp_)h0s?S5ij0aM?FuZ`0^V;N0c-)x2cQY5abieF2YLbk{Vi%10^a!tU!Et5STNnt zDnTVLRQl|x0F!@FQIW1_#f@=aoIXh{d?|-9X95K(G<%^PqRoPM!*MU)`|S#8zyLBr zYJksSU_eG(yz{ni!+6dVx*L2vdZA%$&$F_!RQ_%dDzAyjFbx4%u#JzN26+_OF@=55 z6&Y1Hy`X=CB3P)jURp?rhno6=k?5)}#>M#hM!G_mk>1N6WPOV2V!NQ$%(Af`|q;wgs!9 ztAMflBIIgF)e-;%l5hv}@n9xQ%SnK!GK(81p_Jj*-j~cl?=^`fu8Mb70<{QY{Ai>Q zX9g{yD}XCZ+r%s)1%;jxA6D!-a*qpajpw|{H3Udi;}_^H_Hn!$uG<2PkB_T!<;U_g zKg$l&akbXC%>QHW85YCdQ~DPtB!Ia)ixbpAcU6Ze|2rq)!c0w_1RTA$SA)vxHimJb zZhnty9BLh`+&w69K(b<;3YG3x8O{S=0*xMs{_EJ#174>#102Dj2<`3xC^%IIR2pAl z0-?;*6Kqhq{;+J~KjMPEAL)K~m3b>4pnQZq5f^-5_!A56i$V-kAgDiKk;MlRFuecY z&8lbI>H~QR6{=1;I%G;9X05~{sS6x=*B0lqCKB9AueU1XelWEbmZi70&dyEOlyBA! zk(N$y=W-@RM6h<@z0pH^}jv--cE7o`FkSq5z@HgT{5BCu^dg;47kU|qO(h*U9b zr7+?M^=cSu1YOyRCmm`zO#Os4g^C=dC642N9pU$tHDDzxad!onj^DVE<6&cxql@ZC zPfu_CIC6Yq06}&Q4B!`GwO{#5F@w1ImoM3N?!>N|okLGYOFQV}Dt(0Qr}Ql3B%nu? z@U-Ed01H4ko4E5AU4UBHyfju1V%4MYR997fQprB`*hhs3_JI`$QihYB5ux-CI;NoI z$XPRSc3uKLIrNhNDf9A%^1XirY$id7A|)YlWel*po=c9}%`PNysJZOH)}s*<6%kRB z`w*=WYMn?80i4Wm<+C5W+6hYtByKDQyf5`#<-)_$oxbm6qlSn6;6Y1*Xox&e65v_C?g`ZAP?vV{?E z22(0KFEohKr9=&hKtq$yn0u2vC#e@iz%@8VN!RU32Q9g%*2nC#T~0; z#Har_IVa}^M#lqrBM4Ru9>;IMg%U;j2<67BmsqKwWxy|B`tieKy8s^yLYxYb0e`&f zZtsIe0Pzq-gamU?XqnTONXBq70HeeFKbWRLJ$kqI7F_xtEx;R(U18IpFaWnMj^*X% z#vO7E2QLn)$Xt_m8249}rvn2Bn?h8ao4Dm>Vi2Z3vOVkX*uQ0G9>MBN| zx`7x#=N1^)l3EDkt+z;)@2m0+iKu-w^Y2}z zxV{W;`Lk_3DL3!NY%6VOno~1LlGsB#dZ+l#S>Y7j(601!0lGq&S zkvFszaLvPq=NC1ptQDWe<;!tqTFcFc1e+jH|2$uq)6=dr!s%S)D9|j4i=qd;h5w{##Fmtxajb=m| z%y*{-Vz0%t0(AFgN7SUj38te@uA(FE1C^CIP#`35;cxKF;IJlWv~%YikiQE=ZfS`) zJc4FB4UY?GoO~sh{;S3>^h9F%R-3t}$(L@;QOKLBYv{8u-D6NX22AnVTXmlDiH|cI zE0mNByTlnu`;F>9R7+VF-{CSeB#GZS^tq!Ul&|el?2A1VbZqafbsrYcaNND&bZicx5)8}u2 zXCNA1phiWbZkW|~sw*|DpPw}lw}jBR;{xrBFCcL2?gpGg0(pk07=1mxCZ;=J8Z%;Q zfNlZ%-CMfGih#)~CJNDOygc7qo14Q=q>`}10F(L}KZEw8yu2Lrnkx79)U>o|91b8Q zF<0##(g#4luFRJ$1hY#8?6+s^_JFj7FseB^=5H!fN3ZJS;4lZ*HO!AJ7dG<+L7Wr$ z-_eI*I)b_`5~v2C%4maiyjDI4Q}%GjB2rU#$5@OZQcLBdDsg5pCZ2U!7(Ej{gTUQ*Y)cdHkQpG56F_Ejr0IjL&BzrWMVN3~!-_xq8~lDs4lLGOe2&OV3~ z$#D{)V5sj+5~lwUwr)xppZGT`y+@9!IHvL{Z2M*d>DWAf%V_m{6Zb_SC* zKOJ>1Nf)(IfF3@VCmecy{L1EFo`%N~@J)Iwf27HHohqYlXdx&nYHW{Ul+@T>zq&Bq z&P7fM3S>03x!L&2-8GM1w#l?|PwO{E1ye=Y%7%vTGyA@+E}$vml=t>$Cga^pC23*2 z>a6)>am`$x@?EO5w8n8VQgF>ok8Uwzb2HV}dwD;8=wDqY3ylecQE*uTNp5e}-OSlM z|N3m95oT!oeD$U)o#*wqLw8GD`w|p7EMaLuGZYUGXo`rpKt{u!dvGZ);g zsz{=`XI(G%>3G&qTGup`WQ3`$|K#<~-v?Mz3Iq6va{!1f&?caop}w%$VA|e8A9frs z=tv1@QfAEKTzRB@D_;OFYarZ`$adl1wF|%(pnF8b*81AwN91{2?7;4YhjYr@9!C`7kKY11yC+2BhZa&lYgyd}Dk!k&3Z|R9m;o!^NI@G8zjO zGgucO)W-GcQ_^%dmDMYVDsXf(JY<9N%1*T}+oUc4xaYj=<^O5FiHuU zjjP|9?FCZv78~iv$TO$fMnOn|aNKE@r!W(Xsuy)7vXl1VU~!s@(hz{t`Nz_dg?~MW zz8+U$Z64|L0*@UbIXQcU$l`*m_l?z=hHyv9?LlexdHr_lQ=i8>J-%TT{*KQg8`{CLJ%GyDGzg(xdMk*N$ z434Qv73Q_}4{^Fm74DX2fBkx=41GheRQ~x8Zo2ZApb@1Y+f$<)_8%6_S+-yJReEcJ zN?SYI!_{=4Z>zQaIxJh)|(A~_8g(IV&3~+ z!y4N;&LlLep-D7+DRuzK32+bXIW`O|4KUK`iS@yd8!v-U1bYUKjgYDb1#R~~2FMg( z6A)ye4)`Kt?8xn*4gHBa7^bpQOjT4=P`!Yjgd@XS#mYNWSdmoBEw#)y)gJKjFy1Ij~^a6N5HHFi% z$<6ZT;v$yAIme(Bx|Y_A{yI}l&B?TWQfq7apIc@x)!F-=hU$19yT_&QZ8ADLuO{wr zWOFTL^2_;PuGlufpq)1>6~?Xs>+ zru7G%4Kfqj+cv(+VEz4?`#u@{YyYw~y_adjxB0TcH*6=P`@heQd76$C3l@&7EgBwt zzjKG*YlFnpzS_P%p(&S?4iSngLMQ;@&tY* z&mortL~ohYKESyF&gjwTCKdJ$w9DvI;DN{-`N-LD18|B6Ru~NpA_=V8E<^+;Bl#D& zH=bk2r-V9?o(l1`^yZKT)5BuKo^%E?zUKON3i}eRwfCVj&d$;;2S(BJVGXM!0uui( zWTFT7527Z}xO7Q{JD(I#adW${5iBJ1AVB3JD=F<&O?U2aTL1q22`>Bi0>Ym?lykT~ zxm9t6oI^TcrIPK@Bi^v8cKVVMjWd3Ue540;I}eZ#ysoZGwGe;M(cnvW_M)$bciP_K zQj^IOJK2H9JW~wv+)ypykc$MV;z%StYT^!RHe5XKDX^W zkYW)dH7Z6bvLDbAu-T`;0sDI8hVa;Y#qGJYrD?6@)y-bWdr)R}|=2R`XC3NmQxv8m(>xFqgd4|GaO6AQBX14{;)EjwzZ07<3(`kEZ z`Dasfk*WH7_oI3x^A;R~l1}q7!ADQiEz?U3)=fjtS+ zU;#Q5NmR89V>p8d|1I!=xjCe{+_|fqFkPw<7^)!vat=b89@Ich`*XmeLm+n*sv8vF z?#Po%q7is@UN|TuWCP3``8M~|99M3MPs6!M)5s;ZOt=b3K|yZ4)0T8_bcg4TpE^5Yr8 z4+8~k_InMj9#%X9UK3s- zfB}O33tA3(7XvM=#A){9eo^rq?aC1Kkrl-74Y8bzPFDsRb+@x?o z-CC7ae=$gHC8aG?ixpi{)y#@l3asjs529*L~8b3ZsS@Y+9N= zTC}A$Iv*;Da>N zjb4|^S<&!>N5A?JqKX|qAO<0Oo#N_2g?HWLvEM@qwJ zV{>}Zknit@U;2iP^z z?6BGf)gVq_E=dd8kcQ2jzyXg(2*PDDhaDZDPgh@Z!Cn#4VAIy20YeRj>|*ZQ zrE5Vcx8Zm$cba28DbXIUGzRDtz}J*sJRyDqj1IR3F^@C-!YkbX2|OeMOhTpCiQPSP zDLFg)8%Rm4`=wvMP;`>xL_sW40qnKFfIBNkC${6(rlw$d-gs9CcQt{AB*qx69l+gWdxmOhKz z-mpLM;m+#GDTm9Mj{GfaOY5i#-w!vUoIiWQ5A$KL*3SI{}z zInpK}HA$L(5ik4lQDA_zt>y_<{+`~6jLZ_fykc+f=4k6T=8FtN`L^4Y{??L>{G7RP zt-q*@Sd;Zh#+(go91g?7bbZfaT5c~=zesvZ_AJZZyjJ|sn_$}!2&Yz0sI6a5H#j31 zk~AD6W@=vdBu3}-z^&{)-NL)3xr%XdQgd0EP4N}%lYN66bTazx-`OXOB2ScLh}wOq zN_R|-=XsIQnj;ygrNvq0>LzWS>NNYVNZ8?!HOsBZ6MZM?I5p^a(sKWBEPJ(d^jASS zb?x*k`UW+_8-&8Ey**CC)E5OOm(G)UI+GmC1;SL=m_!hr8Cj=P8o^b7c+0-? z_YX3M^4r-fmp{=!{{pzc@oR*RT!w{w*lmIxy14eLuxJoru*j4q|q@}ZSsvm5- za3)tP^PILYWnpkg!xKrOZIqJI)w>XE2@t$gU#64qjK+^AG2;uB+gQA}(0rKi{xv6Y zYybK4PY0jgC9`O+Exab{OndrtcEOeqod(;)L=vy3&$Uio63`ct^<}@0-@pBw`Jwav zvGkm%uUo6>GV}5q|WrXI;5MM#9`TuT=BNlfuGj zKQ=7~+O@wncr3?E!wUC{?O1TVQMt$b-gm#kGEG`{it2hjemo`CtsIss^S+nm#tk|t z6I+Cxin~j%tzDmGsaW2m;QXO~UvcTK1G&K~9J2rIj%kV}5^;(?A!jCQ)VOU=$qL5C zZe#Tw)P;&*;gHx|kB+JR!I3XCTG}d8?cmLFY1Fa#1wTD(L3>b&%y_!O+`K+Q?1qfQZiwks@1Rk_u#@y@6%9WmY2SoBf!Jzf zZ)~cI2Q zw4y{C1(I$EdniPh7_uPY{ACbJ9iwAKN?VsSu`fc6(9l4sj7I>BFG_2K5q*cQhKhU> z)OrJk?rr~YMq;2nGL*F)%f0tLjEft^Pn&|13<0YckQHV49$7aiYk$Ms5HjD-OKg_} zE{O}o{j+DHF<=!)Q1YQ9u(PxrfRzOLAE$-U_rQhVNx(zZ<@2vi&bLIYf=qk~Qr$5` zsiI;XRl6d*YdH7d;Z5Z{3?%fZL?Uc?~yu!~= zD99OcpVD-}(A(!@kj!lC3!lR8sWNaVlBmc#`|H%BVYpUM&?jb~Rac|?eCtg;ItuLO_j9FI4L=hz z?>m1xvy2M%&}_n{fgL6RIPA(2d>tht?QvXY9gBQ-Nf%0}GvfZ|^kLqix! z$2=L%^{DL=iM)76=c3y0`ES4K{F%iM+_U{A5d2DdBjHG~BlU|jI_BZrN)%`Jjg0IB za;RZ=I;Q9O5z%^m`wQ1jGi#(S&nsLmKKr%l)>vJVDu`E)U)vp>y7KnCt;xBvnV#qM z7s`3SL$$~;vAEVg+oxN`iUy^V58z|PpY)O$wTm$t!rqonIMRgP0*VwUZLr-Qnei@iD&-E-V5+T7&SpC1aN61kXg zYa!iaR$*|0!HdGers|Op`Yxrv-fWV_78k#!F5UzhZPoL1{rF2QLprg!qXsn-P3S9C zwrfu8)^XNxp=1XGq2| zZyB^e;`AjA1xTQsAq<2>3!KS|{QO>QSYu-w<-bRhgKLL(W4lCh1`&CIRRJyqX`(!L zmam97K2kN5;%tCr0ouVkG_oQ<7n^0#02}AT`M~SIZOttYK{ypp^9?Ax3PTcXdVgL&R_*6@M?5N&>2Zr;0n| z1@Oydl(k4B^}Pw2437yEGpYBBEg78(xeBAv;^WD@1ewg1~?1BZ)ifQg_!7o1IHr^FAE#{(M*jkvEG7#bV&?fT=Gn!%mJ!_)nAFJDGRwkTzM>`=~T=v4T8>A@&BHmf*GW1@DrcAhlaTsAiGgWktBF*D1`@rlxod4`m` z=iJ0l&-CQs{DY2P16~_^|8|8dE11L2bG^Db^074Ci_;(Hvclp+@+>7hWG@?R;|N?^ zYu56gYCEb%aqr&jppw*RmV97-wz7rb@>=tEpSHH|6UVt0SZu88X(6C7Fd)e~ZMClq zDtDJ~5NvMw_~qdv7BIKIbVqGP?M7?6k~@2BfJPW}fCHM_n||A6q|DEU=KHe5>3B6j zzi0YyWtV?f>m%!|vh`z-`B_+B_c605A?cnMX?f*{>Xy`0DjHx?gV|)5u>7}YkEh2b zso!cfZPIJiu76kzN~`KAgoG}fiHaWISZ82kll9nX z7P*EI_ZgWYAv~@`xy<=rzjl2kw)0=TOrOd@O}fr$iFhi+1KAJds&*BGI-g{g?6e3s$$f(mUV0MbDVX4~YN^ZF@b+y|`JDi;@X&@-JY#2gLS$>W zWgNn{pd!MBhe}KxuEt-5dt3P7Rp8jUlQ2v7nD6l;9ikC!F4E)Qs(1OaXqW~9A0a(& zIRTpcgh2RPOPIuQnK9@kZ1uuOHk=nog~TO)Yu*-svYp*1luej#fit1&@IE|sc!crP z?d!#lQ3ZAkr4TFv!z!@^#vZfRLuTvdHndyDsZNNTLN zJAYA*SEPan_3p2B*H7ek{uUf)DZaYRmwt;EHvKUEvlrEDMM2is4w6XBg2wZgY1tsQ zC#zUz|GiMtMkg%X*;kiqepaWUJ@&B-1F1i&;YB>CKoNCU!wSxm(Yts_*Z@gNYhHSJ zK;#CC7~T~D({+3INaNez-?{}`Apox*DS^Q(ICHRsS>$3>*Eap4U57Yr`i(nzGcNlp ztylGDk{}4*d5~&#>B8Y>isiZE%Aeys#c%BwV9GEG2~m3Ornr}CZUCIsRjVs)?4UA| zlCsUH?MA%|rPuyKGWqitnQ>jfbNk?MrawQcy{R8OJf^j+@Y>NLJG|twTQ#k;Gc!^} zzdxVy*f<=_N#^DHL)^)_&G05OvxJjyQqqS>pRez5_D}cM5!DE^zHk zeXYy1l$2Mk-*#=|@uW33PkD~Py|0!+DwPWDvzG46%;|{SoV&=W;G24q%=n`UUURI% z_d3KLtxPR{=IE83>{v9bub=LrBzdcd8U#p~3LD-2Nre(Jlo1eZ2Lp$6Rc%UQjnyyf zt5$tEJx@JYe0=c{e}89B5;vndco1cPloTyjz)a7pExYCp4KB^ADk~RkPN*2V_&VeF zHFNS!Uq<|2>1<=(%*B`K#($|511E^4F<_A z*Bu<7vPdb1SwqQl-2=)=gz&-CK_i7s^Xd#Wo%bnRVJA`v^MB=?+y6z}Lt1}wHY2Rp z82}|z{!f2BErc;rX4K_q*Y>az5In(}h3g+phiNaHF*_RrTJliT;R0(54hYI0%xA-S z3@r_!ehgoJ;YYYk4r1_)zAlIs>O#*^DH_rM&oeHQce_oEjn67HVn};x+O-UZ_zuJa zHbUAm2GId@Ahumw2|V9@h(SPCLRhGF507DwvW&mY%Efif z$W)x6`#Ay>k3r^ETMMB}wm(!gCsL7wbpe(_C@uhE?%1(oXu3P#b@adIe7w1}_05k~ zkURi%d*QD9`W1x&a$XM|I)p5^I4i7b zA-KNE0HC}@fl1{-64(_|6^aUQrl3h6JG4?l?TohW1|VJto8aknb#c**mG2uH8$*O1 zX#A+iXV2EU)OnB`Xb!a^1e#EZXgjJ-M6$B8BM_?|@a)R!>cU`7^3l5VVOCaGO;165 zn22CfoopVAT_%A`IvhoH5Xjwu1KnUwpf|#W?hX*ze@q8dS$rBR^fZ_fP8r z3Ojk2#`*t3L$JGpQ)Ti;<#cv0i~li{P56&{S+ULNPf2f#5^8p6BPYc%fg(%X7fK{4CyTtg;LTL_FLtaJ)DNofBY!A{Gc= zCInb*wtBpbgYVuUtJq&&-Tr7Z#OUGS6ZaqD;M#PTL;{cVQB^OhYiMX?JFU#W=G2js zvjKQ@j_5e_wnT^~#=t#){uxG>j~}~;(LS)ul$F8nEmW$lqJffEU=KeZnZLh=<}qz1 zCT5YJD^4w(2Wu*L7aV`X#Y$s%xzO8s*fkOq3CSSOewfl3< zSv(1lc~jyhV!i$S`xo|EwfBRLdEP@a|h^KNG6oIPFvEhf1QFs8Wf|USC z3z!L12uZ1!Aetg%=}8AWj7s8x&G=o5X9xlh#dxEO7wc72PJyGq>@+K5V+^3(Pjdp+ zR~*U!%di&k1xjAz$+K@$;|@{Zksl`l;0ah1bXK_V1x!+6Vhmm|aN=HJYanJH7rWocQY1^wY*4$5az- zbpCYpj^bYZ`dV~jmIW-@Gdbg_yoFI1?{v%A+uH;72Q#V=`|275!0;%yw6>;*WTiC0 z!uEf$xsoZ^{!sH)i5N+2wUy$X<_aA}eoTm*=w8}7iaV+7Npgv1Smz_i&1 zy-EA@>C?t)r4fG zJTHI}=u$D|HXHAWX>Q=Tk)RCq*5;8q_#%;gmvd>S_y4?3139x0^H z99DJt2T2YeT#+@!>NQ1K2VA5ugB!~gQZWpLg(|`P4B!ZQ z5Mj8@PSQIW8Ly)QMO8dtmq};k!l7?;{rWcu9PwdvV2Z`Sjd_3mlpxS&aK4m*5Xa(2 zv*xg|ejC&uOw{x9iWqPLZ9T3$X(tIj%un^>xg&dLtr*Mwi(d&M3(!1PBFpJ>{u>01 z5}~HMcl+FVB(ycY%+DW*(;-k)NQI;K$3nLn(k5WlKQ8B*t;o}L!lJ8K}aTpVistNHd+bkqi7{) zX+0p1hH>cksQW%H8~&{4&@tm9#89edN}h2I;{`tn(e4g*b~ivff};8tFIpgzJ3iiM zYM}zML}<}g9LGUAp-rj8VJ@$a;nWz>f;b+Vp337KqiR0*XgOfQz#v0BN@;VVFpO%y zJgBI+4qg*GHwHtwVnFz@T{%Fj78luNuO}e>1s#6(D>pi{nj1JhO(8OS`t(vzXlZ)- zEJoIPu1rP?%CyVdUB+gFP~fKqLROD(;^QqsS5GIoFY<&?%YS=K01$Nuo8f!hA1H}5 zbbz9m^@UM=Kk+%^xf5;ID3@eXndJ}T-Ir-GA@RT1dJ||a+qY}@hYZP_keP%ON~UBk zQz28x6e2Q|j1fghkttD#%#oD2kRq8vl6i_U6iNdsLwWb*exLVS-&)UaJx~ApzE_Fs zI?rR+$3FI!U{DtzIXl z+i~OhmJ1${^Yz9~!w58az!5D}ys^jM2W1PNyvI0xg7%gc+sr0lzrUbp-{r#`{z3i? z)TMwZC@PLX#dTZX=gG-(oF0gOOS}IdC{~S)y}xUYp-NL89cb^dSTF)+5Vd4yRTh=pIivD~#xzV*X+#^=|V=`pEW@Z!iy z$4mfGfd?%X5OO|SwCol~=K43-ZG!`NsNm*pGxfvD z4CKQUgH~Wwo^eLppt_`J0Ph@o{YZ$rRP?khh2piba|NjyPH-q$Sin{u1tbKgchK0N zF*^bc?k-C5I%rdZYjpC{Q81T=fW4>op-Fud9o>OP4;`bC8?)LnpwxlgkM!|!#}7ImEWw`PIhM}9tKjGE167_` z`7|JA+MNoWAKm?8Aiobh|A#XEz1q1L+=PSx5Kj>C@V)v%Mflj&+S;t$P^|%Nci%1O z$AM7wd17KKGxLY(X^_!d3a|Yyt1mJzdLL_Qnno$&lGY2PRvH>?Ae(|^a}aR{I}d>1 zKxKe1_ByDf5Xtw&aRX@z>x2x==ee7=v9o`}V7K+=&MyM#Q}B4$iYEcPhg6RPIRbJ8Z(ILDwIQ9t_h+I5tXM$!(WI70Wp0J zOO6eehEB%nnI4$cp*92q8_$;m!5&UegqsX}VPqg_f_e*y6ME_pvsc1K8F)n)PmiGo zLBxUTMPyNmqb|Ndvxnw(PENPsHH^^?1~*TiK81q?#KVXWE)xC>WNT^>6|l!X^(4OY z)473SHKZva7N8DL=!F^&q+5!gr&xYZqslQVfRrYRJrF7fvvv!Hl|x?s7IaPV!3AVv zCp5pI{EW{H^fs+$mTrHozD~>riQ-4n6JS z^4h`@dV5F<=un7Vo)?$bk@4l82~?zh{BZ#n`AKQ%(2L72z+uLzBM3J?Cv_kZjMEF) z`V-3!fr2bLiIBa)$H4N(P7c6FC=9?pk5#4E59jYUBUyjlLlBj{DI1qRp`?BzM0 z`sU{Q8012_GU#hXKPYUA6W{=S`qWlw$j^lG>KO)spe9hoB_vFI{n`<55(J)nuLaB5 zv`eSKtU%I7m_IXvnWTjtbamiO2Elx|@-i_qLx;W(KMXkEP<`&i{90fqVSEGjPvH-h z`1Ew%d!6UhU2#64nSo`0b4a=z6)Qdjb0aYNlbjLL(aoVn!ZUVK({ytBgef*aZ=J40 zmJQ}a3YrQBwI&2BOxH`yAEMwvC?Xh|^Msu=7SAB|pka1|MnE#-AzgBE;vtK+=N~`v zv%-6wYR{erxo}hcFpmCHqhC)UCz5vLX-J(ax8k+C+!rp`&YJvLZ9t2gxRD~C2_Z5) zMTZHBJLE8wmnXM^;%>8fPtOIYMBp?)uL&{7C_i2r3y3hw5r-qXPZI;IBqCw=4T2{G z{79$?;p>-a(4x>x949sjEBQ0;a!@+=aqPADCy+Y5u#DP;REa_aON|HvFiT~u(9BD^ zjGdGFD7WujTA6{{GhEI~Dl7ZCyH6GA%0$W{5$+8;W^3{4(3VNQ=js?f>cQ8uiFp zZGH4+p8(5;HGfQ-wuFB(K1B7cLLp)OfFIexpP6{brRP=tuC3wSL*{+p zPM$;SGpM5OF)!v97M`w(BBZP#ApvJ7)LwNMj8ByXl`=-5S4I!CHKjUmS&B56uM1cP zgME?*XyI5}L#7yt?)ejjHd^-G)?h++J^Uqjdbq}@MWY(+mo;YR_6SHzvwB{ns>@Id zB^5ssvu=vHB6Hl?qg?jjffiZvp%*8B99X4xl5v~JIk&b}%pSZ7#@jMPA zawSw*ARUg{ciUW#R!PIH4TL040gMDq4GqGz98!dRGTGQKoJ%3J!5;b%+7BBSxhSML zG=f@D@qy9_8x(ym{>|gIubM;CCT%Gy49PQxvdO*@$YTEVnuh&dP7YFUi~3zsj?u28zI{aU z#MGHM!y@+rf4*4%`#Ao1i7bSOP;0$Rw>uc&sAuzWTJAk~7ubOAeTM~cQS6&Z&3$yl zt~s(Es$~^a5=bh9p%-#NEjEU~JzI#uL5gDg4)W;FfK5J&+7>Zasor1W!oaIk zDlBY#Qs>KHXoaiYDPw$#^_a(aC;oT2iL5RLSO!fjKuTow@=D}OG@B&`*?27=4ZuWK z7E2kzH)^%7p#yyZk-?49_c65Qv*s|I;SNS++%I>?#)g*!gFMB#94H1A6c&1M1CcWs zGs0t|8lRh69U;dCKjDjxJc4Dh&lm}>VzWPm`x^o*4h7&*i0*qJ6qv3dX`{_Y7{a|E zcKC7nE8U=WjN(ms^-CGm&^^#0{;Uty{C=7@yUsX%ZlK9_@4(Y@RvM}jF0?k^Q+Bzq zpF891;yiZb!MVTB9P&=&`RmMC`uBfXEz%XIFV}4pl{`&XX`JU6$e zw&nTXmiZ4Ke!=c45Ez&4BK|Oi6qH=}`OpOaPS+Mvz<~yr9sR=kx6A85!hT5BE@F2$ zVJKf*Ftq*;?8&e^?f2uO28#zW?xlR0&)(H2m^)MD9$&oV2i(=Bb`JQzeF+DGuMM69 zFcD@TY3%I%dCY{g8RT$jOvH`@w*fB_sUPJsBp6lsNhAp56TFD|(ThMmayR$-D4VHIqcL-OJCPVK=!?n$@F{V$qqKM?jhP;{?RW&|AdthTmcx zD5X?Xv|V(*vzILWGVhRM*2V&VX0yGP;jJQ9RoU-Atb?$b1yP$jXXb>Va7vI*a0gMq z!9sWQR$(C_A;rIo-E?c7YypZ0+sw?&h{=B@6OIjeAHt!4i{QzirNrfQgg7AKwKm5% zW9Ctjq0&bmk<&dx(2}QapM>`yA?=39S#+W-ud?zN`UC7Mx#4cX-}Jbp^3&G=RaTX zMiE@)GiR!)*@XTBTGzm-0P%H5e#D+H_F-v5k(y25g_jb-Lce>zp{UnQaPdt@BncR4DcsD9&7?V z^#vvmP}ripkyKJjYqW=tq&x7LW6H}8mTpHSZmTR$CJYV^Dx`r=en3DVb1IeqJ9a;Q z=7}tYmG;W~qC;JCOMqWwo413I2=Sg7?*LS*U#yX9p8Rux1Sk6Np=6uKP!R8c@LOxE z!02}1?CyIxU}cP<0P>!R32PNF1HrLc$W`>572C}v8vqCL5K;?QU3xkbH(h-_6RU&8 z=PrsXSLzxY`+TzX^NX2qz)m%fFP_Qhw)^9O1IEG<-1)@Eaii_;sPjJMci7Mb^drnr zl>aUoTlQZWGWGXg&O8*Mo!|AJY&RVCisnJZhamnCFk1uuSNNmWgv>s1Rx!0 zVX2Ah9HtZ)+7PV}4koD>Ra#hB7~H<#{K!js4h<`UrU#jLVd2xjYq3u&mF$M!NzCJr z!AW}{vxp)e9qR=|2a+w=g~&(O6Lr%;7@2y2LKRECcM}truvmH8!J*jvA-+7I_JQ8s zZ6t(4M3Kw$BOuF1fQJp`fj3Zi#?HaH+9fv9L+hGf>;Jy3W5J*Xp_06=)UnO4i)CJL{KSgeagXZtq-nkC!6QVV;P*O3owpPLp7ycl6)#&Z}^U#2x@PX8P zt`V&45CrabZ>PHoGCJ@-NK(f(6FTxxlk6-9AmBP0pg@zRkBZDGX1`61uU?U9!m;{O z;^l@;dSM2BZ+D)&oO*E3IrEpIa9X}em_gf&cQqW9fGa?j0phI4Fo-lorbq90gKVko zs`>8rJ|Us7tKAv!yNt-`QZ;{0?#J7|dq)R&K+bf*nmFzo7&TUk2h~NOzWN=Zt3HwmEw`ss;oJutW)0FdWCB>bnxV!PP@G zC(0Ud@uJF`0O(~xp}rDqdo*nT<|>ALxd?pqfafHprhPX9@HJ4IT*B9Y!1ktc-Nrq<5Y}3^Y30;`8YKN zHwi@E9Dp^#@trZtuTei& zeKNf7%(@Y?y8GemE|@A1%cEF-fmsc@a}|}7_qzv&hkt+W3YB(*CeX2sMMI(VMu9K` zr~6&OsveKqvJGgqZOda4@>dCMqvU1$6L|LnXT>!OdJ+A)l2gDPO-!#mmb}5UWvhsK zprS`rr33@fq|kInk9H$Y-h>VbBC;j>6^j$VxG``6CINVCeteveR>v)6x496~Xg^pj z-Lq7L0sw;Q7&#EHwN<*qy=cdMuA=s_TL6fNwS+x+ThU(z;n9QTPC!#CJz>S4?eOPT zAbyUnKlX(fLe=Nb11}lNEYH^@0i@W@#zu_o+4`W<{q55yGw_8cx3(PmYS`@L?@`SW zuf4d`e-gtAOjc2{MlC)J8b~xTGb5fNsurY7ILu6WRtY`%^!2N?k+JEB%YL2{`fO?A&`@w8y4bJGM&Q1aeu39fDpQNk~iqToUy<&hrWcl;R z&`UcSpPd#(aM8FI$Q*8!a3Bw<$JUm=RSI0s!x|b(@DJ);O+#@!TfBGa8gD{9iCt3N zf-@(#zPHfUi8_?J;pus(2GDVk2Ie;Ks>&-fO=lt1`o6#aH^3L0V%v}+SGA&SR0}Zj z73yiR-3vvFgt)l9?nBan-&iWja66Zy<=$gvG=v_ZtW$ZoFBLq*JwPD}3ma6HB!aW@ z(f>(UR^I6Rge-dwNLA&d{3tLo%#kIad@~~E3gr>k4-tb!HKWZ1%>jzlQy0VB;Bdi% z#xvoVGW?TLQAA)Uw+e!Nofb5JfD;9R=7@J=x0eG=20lc_#_$?M+YZ;$dpTkajLx2& zCluRokcfsp(*T=hqWkv!$h~djIcLkqieixft$tb~u~UWCgG-3c2pbUm=QVXB`NJO0 z4LPyK794*b)vMf`lXld-3WyHOY+=5ecl@eAPXRR7N1g|z>Wb@G?1w0j5o@D^6mlKB z@V0N;rtt`Yu~>44I!$I1@#xj`=+~A-?#h#$Ib&c%E+Mhkg;n=14fxHcj%9C<92Y$h z0Kam}d+?(hd-$*&l!LyCjAqaWVtAEOFe6S%(#-AxqJV6kr=Lc6mCU^}_`Q=Y3Z`RF zvs8JLBIAnVg+uEcRfK{I&jTf*GFh;hjlUxlywLu*m%vAb$Y{W15Y!}2lsaJU3e=8x zA!wC{P>aKb-eR|FFL8TNZq+;sPJKs5mfim;-- z-A2g$1g$J0cveQgNkjGn=7H>W=k8rP5;2+ol;(%+_hEZWaS$Ocpv1y;#%*5$%HUEl z)Yv$6T_pWlEhgZ!HTwm_Eb`m#87k)exI5ujAn@HUUb8u^|nE2;@npaM6&wl zu#pES5g(nCnx%9k>`jAA3zeuGnN#SXAhb_^Q52CVfbLGfVf>{uh*#IQLQEjTKvkRO zRr8@h#T$H#@NM`nUX7CQqo$!cKz|JCXFw!aX~ThD;I?3*q>OGI1v&5ln5`|JC_4@4 z0%;|o;e+|5JEMO>rZoeShTS~}P&*^zfL2tQgVZ^x1ip;p4=J);pG$=4b!5fqX3%?9-_-}Py28UK%h6&JLlGRqZM#ho04qB4!qq?Y z*5H*GSX#E(?!_bqex}5;bQ>s!52aVl5gZUvo)0%(zHVDYDT`hGSEtLc&0-m?d1yXI z^!4jPJFkcLvZT!@4h%9~KMeZ7Gyu?+qs#Eq;k;KX?YEfG_(^E`)Vm)?-SsDo5^UET&NQW^KJvGsqy@l)Lwjm#1aSN}o$E5yEb%B7ARaZ>!CW_`m% ztTt%XcZ0Ke7Wo9>3xTuTLLB@(Vpd38mf7B@J)0;gKd>7j!B#LP(ndyRJO!aXlq~Cb#1s0+Ds$1mEW) z&?B9uPrO`AR20(E@7%dC^?IA7S(pM-X#IB_5mcpABxJ!~VCxK5XPtfJERCrJiVkDe z-0m58;3VF;<1Ed&D{=*OF=-r_39AOsU&xmy-1y)jkM6tASsJIvw#1x7Y>feidiHC` z6{H+i4Kh_+?-Q3NsAb92aGc1h*cRVeyIA4rk#XVLD!5GUU+F_q$}re$Hs% zj93bRul2571?YUUyKw62F?WFv78HmO_JqSxq@(hK8VC9#5n*9dGqWd+rcejN@Eaup zRK3P0CMZbKoVc-K;K|^Rp&h8`o!v$ZO|+|8-qH`9`9(KT719qRRL`kxpl z-5jLar)tuY+LtDq%;Xoz(BXcdspHe?Z#$f0fAe!N|dT(1~D-v+BDnvj_njSI(pj( zP75N7Sn6S#bxh42orX3a( zP{G(sMZ-`tn?OqGs6ubd^cJ#{r2j;?EnoNaVk{rQF+?SX7Yl%DavIYD1iQ0;1x&JI z%Pol*JGQ2_iXkwWEixZ{p9lKFrjztQt?w*_ewmu0Bw-6(mNOa?D9@^ARfpUi|4tgD z_RmaAG&o2VeY>?Z_J*1-kVK47run`OmQj-kkWARM@_8)JJ=4O`=Rq}4Kz#DV4~>$w zmDRt6d+WGbmi-zyUcf7mx>o=Ei5r_Zb+c^>Kfq}D85jv<`P-b~jg>=@iUR_Fql9)M zs62}C(6pO!^v2JTb8v@-A-*LN6Fa+>(&yf{k<4D=XA^JC^3Z4a~(*9!Pzwb@R{5I>d`R_Ke~=!ntxmJEKGW~fM9lDp#>(>7&#{P>BnU2`we zfHPRmOObAHA7CLNX})#nV6154VLCHnZe_KGghq#I2?OOtn)Df>_HpV+ zfkGPcXJteRTS8Vo9$p%1Wi+Aac7%6r#WWlI5m>ak5;Zn8L;25GR)H`J4K4ZX;-6Bu z1_KC!IeB@gE*lA39PEzJ6Co_C%J>#_y4anQZ^1l9%g)7E?76t-#GpZF*~1vC2iwFC zZ1XQKtB)9^RgYB_VgU!6uzj&KC@>+_oi0NOj!(M(bTZ`@Hkfn+LWyelFi`D49D~Gt z$G&9a{6KMk!GEyYl<0zeG%I7w zvVH-BIp^f`8#9f8YNnn&6&895GNprVxR~z>O0W$`q*H}S&t>eE@UXLk7x`&+Rspyu zo|SFG4T*=46h;-tsdDLAXedQ!JqkT_3b21L~Rc(&+1+@+80mg;t? zz-Bf^>yy(U8<34dSTR})z!>0_Q0&wXe$P{rSkgdMPr?K?;`XHlRX6 zT+cs7V~#Oo`l4K=hZe;3$!u|w>HEH8C{t#>XX@|%0uH*XO@3F2Y?@X zMGU=ODJtg)C?8|c@o{i;Oun3BT1Ylt^(o!8beekp6g7cc*}tN}5d{rqusZ29qW7!r zZZO(QGcxK{v}s0k8Kjh<(I>10zgjN_4YbYHvgzzR)G60?^UB zj4}!X!e;?XF7MdChCIHC5ES{-S#m1rpzG9ULveYLGl5CHc1PWR8YXexi!XE^DF-3{HbxRt8Jx^*%wg8fWdNUX&;1GNps@RP^Vtj)m+qMxg zgxovWqF{GT zFOO;Obo?g`fm&rCboz2K3BKOmLVPr!fXAQMpy7-+7%sM;$prsf?ev)(QTXX>CV|4$ z&Q}Fy5+638v+}Q9qd~CpbONs3Rz{l87#(nvzX_)ihA>E0H#YWSBh8sA-?>~q_6Eo*9N~|t z$gG1#$4J7Yb6}&23MDAf_}dv6pjln+BhF}mc4X_;iMcsq+SsImvSYM9Nq&Vo>)}Qbm@XWy|VCOCy z;>K5m9nsjvYA`d?^T@jAb)tz83+kQlFax@#parYuCZo-pd)AhFuF{)$O8HFD?qo9f z({Uw6S1cE%h)I(7KThnDlcNo`mnx_aEqF4Phul`}6ZLXo7xATKnq#s=RYwoO0bp6R zr!Sm;YiPX(I27m@xes_A2E?&lN(cxNb|pJM4OdHt4e3B(0c?;M?gKyZSg`Q{woaEH z+$9?NdNY%ywU+z#1ND~aC=3xqK<{u4%PPU*s(v}yWgU@)SgzMyjbFgYsG z4mjO{<%Nde^CRr5f~$0QY%Q}rT`9HWG=Yguo(6ae67;PjQwU99?VFxBv5V!p@BGLa zCntFAPI~%VSfrTmL8O6FGbBk_?sf9*vp)=g0)FvT^!F`_PM4TtK^aUj(%VUj+j~y1 zY~Oz7{aLRD>`o`o6>l(}2yW27@lZzIKTPnCJ6#5`T~&T(JEcJ7%P8m}2lN1jgI@N} zm-;NpL&m{Uqwj;mEvf>Tw46lKh>Se~40Oki353VKPy4)meIeD$&7k$TAM{YrTfdCG zc+q;OsMjUc^78*3NQun;e*>vS^s@k`+o`pROd%Jf4LbJoz`_20b`tm$=!6o1rFPFO zHp!fPcA-S(-)A=nzYzo-Ge*cnUvMgW zG;`g{GB2p_>^vsQ`g#h`9Ms2gky<1ypQ~CP2oOIY;*Z{W&t-O=s-6g?AaHc-F^7T+ z1F9Z!a`Keb!tsUWV@gZ6ri#(*{zHAT+w|cbpg1^6kgYYgw8S3G3+SUJb)5D~MtK)W zM|B9`Ye+bda8NQu6OWKQyuH6*=m*1D)TFIG`1-JdI+`wxV=T}!E5y>h*q3B%ZDyis z$QhhO)-=u{Wntd3OF(?e_xcWRuK(^2OI*O_5 z#EffJ-tF$A!(WM&Xp#r`Sb&&Ckw3ukM$AsQP6?kFVv19@eKYgy5E>cG7ttah5jNYG zkoZMKodIQ@4E)gu+|ooWv1rR-dbssKwHBB=R8B$^Q>#EUz(@jxBF>XbQPG_m$3U>9 z2n+xL2Vx~(?SE*p#x`Thl8W<$auA`&7a6v_T{l^`&w|o>CrF#vy+O&8D zNe`Tzu)}?QR8X*w5hKpbsg7x0BU95~I1LHp#2gJ-LAjW>G;?ur5oi{M3JB=ONhq8yU{oyDOOGUIgNnSdYajEckMVQSL8*>Q@d8Yd7ocJXrn}}1j(A`f&|Hbu z>~_?@@OB4g(}08t{v&<|fQ-NG`#VuR9+a1lQ?Ugx0Bk8tEeJaA<@MDuTo71;op(8d z0G)4aP>_F@TTDE9Wo#W~K*8;kc}+JmUpDO0YQFfDHz=qegrcCpnCM74m9u|+&3Qe@|SVf`Fr1qSX6C^2h#I&g8)A2&XP z^a2NT>nim$c{Lst{hcDlHGalurtbx57FlYETOScOSKYbOaK96gY$jVx0u_;hqB%8C zrj(SJtp797zBco6O7{Fd6=NCy%&z%pIy&hh5y6+`KL^ZR+Bv$}M2_X1ZqK-RGoNxx ze(uo%danFvt^(_tdV5s0b@ zFaeuWua*Q7gy#gb9>6y0b42u=pfd;y$s#HVIfB=(;pXnG(9Iz! zIldskPg+|G?u@8Y9bc#)<6HY%-`ktl>t{wwX;npjTe6|IFfMuX@^VH$MZ#u7!?!hZ zi!&5KtLpcZgZF>PjL0<#IZV#7Svxn6^7Z#CcJah{Bd!dbf87>j%!@_9eF8RFL6pH`_Q+{>w|CXeo0tn^mMFWfKQ z=3pyLPRj2!fXS_`^cCIHE4y}?OHe1$&d#Zcg|7q{6n;~BKt@eH?wR`ZX^q@@k*K9Q ziW^Mo?!*M}ifQ50!tzlV8C8216uHj$-q3`q2s(rP&jNOAbJ^IYy2pZe&Hi%bR*zEV=hLMss9Bvt97LtCY#Za zds%*i0t3tj^fpCRS|6e=S~l#sF?0$J<`0UpxL9-2J2)LOWpg+CcP+M8+wYkYY zt&(}Bb2G|HVlPLUXWqpkwp*`PKgRm_@W-pVf2}=qSYrC3$%ECtI(xEM>gUh%4nKV& z_va5Omiqnsx`~ijM)?DS&SOmKqeQO~PRzJbdSXmLMuv%AZq42ZPRKq1rqs?q59H)e zl9GCCgY912LIKXXdN%?r44_Ht*H=IepXrxf>7PG%T-v2Z*ThG zp&g|K(_bd0@lT(c;f}0_jkDo-a`hHM5gtQXH_$$?4um(_1>anIlv@PBK1%Yr^PB}j zcv%YE(}+5!$nrO4Bo{ASAk|^03kFR$`b3bH2CEgq-tM@mEtF$-86FOfaV3u)F_1oc z2dJv5#%f}*(cM~}pfo7#tXO&8lkNDcq?DyaYmR|o{6p8_U;BhMk&_447cVJ$pOKNt zyR)P9;Pm7jg<<~yb@PGRqt2pX;dT^n^mWDD1&hs%DeQj)$?0r4bVZ+~;4`2q}IJ?|;#iB?8w;Lbe z=eu^{o>2&}d_%L&2*Vak?C|S`Qvi@LUk{IBpAYW(g7I;hvD3b>Npc+x+TExujt(iw zn!{lC8$&Z~X3X`hdqk0w&1wpgPicQhW-{vfgTdfNnJ*PA%Z{4aJ-5eI&<}SF@GNGnQy86}PUKfpqM%-;`zxg|l78WvdHZ2B_u+&Jy z_=4S+ZcAte|G1~SwfApR%Zrkg+H4OBxlXgWy6C=8d)f8F#;vP+tD@4kQR$Pa8 zyEt*uUpxHUD0bU6eilffm>dsLB~49bbd!85mH~5mX+b+p;9w5Fn9|JD5^dXpyh;xn}|2avpHOy#cK~b zw%xmT=qQJ%s^;aDK6&zcX^F5c28#FdCw4o~mf(Y$Ymygl%tGX@k$PcoWTQRS*3rGO zfw*1bAF{ZMHLB4e2QCy~C9A3izj$#O&ku$(n`JEY-$&5o8l6C^2*B9T5X7eT2s0s; z<0d8un*mYhD2Y|b^?c4fPyds}x^Q8fb(W?goX|81XSV@&@mh3rg^zgbQBl^b5fNaq zH={79^bsd2eRX#Y!T3A(8TMZ8*dr-Q z3bfp0F%Z)`)#BDqKV2m(=dW1zJJvEvpISrX_Y@D99=BC}d@&vS{+k-S(k*0U94bLp zM!T*x{+6*4DruxTq3OlIK{DTCY}?gVc)dOA_U$v!JoLR7&YRffeB{#YB=s}9ZY8Se zY=++1iNV^uSSyK5n^X;$Hc_g@^5)TaYSY*rWDYZ+z)f4ZgdYSA1{4799xoG*GngQT zv%pP3tOOAa)euZwNARA)IHfqFLF&fQ1cI3pZWp>IVgJ;?fJsL>z~5h~FY_?lr00R_2T~Sdg!IK&uD4v7 z`bJ68ZtCLpb@Qx;Bo+M&+iPzdu#pEgHOy_l?|3ZmKeQ_4FPpurtVY0?Q2{ii_1^mw z7*TIolQi+8 zuD_qPY6m+X-}l8$Y;Ad~Z|BP`x?jCYN??_+#{FSSe zC!GAq(QjLn+1OLldC7t`L+k1;ikmew2uQOAERxpF39657N3wg427S)EdV>}aClMY7 zNt&^Hw{Nq|N}H^E8l#v}ec^=G z(iIhJhyW!&D8Eu~8)xg7P;wM2SQ|by$KFZCMW>A%ys@$p@RJ>ETuWo)Lu@Ucp_D&= z@Tz5Zp)BHqoewMVf-88^XKEAs1?&^ zQaY)X`97UEODVM-RuH%NPZv6`Mnr`;x(5%8he3nomC6Msuc_h)iO!fH%$ea|%+z z=K1-$srNN;sq^!B*>>}l*X~(lXc?IKJsxzq^nAwXI3-E-{vm_7T|c#d#@N|`N9$c( z6s1X1u|-$T_qf^>%JQt>J$^K80kBm|*y?qz9a z8y1+jR8&8Io?dP(&1fu^Xi?Pn(~v%00?82~N*!|IT&e(U-#JT5+;%;8E;engnxe|; zJwMs53jTQQJ?CU;8d3I0Yb)V5m3|XkHe1kxUit=jRl-F(+d`lLA3sXrKv64`0S)lS zya@qevH1cQJR|I(1t2 z&-O<9ecLA{Cl9}jLSlB9B?-bR;zdk2@$MI$dt5{%<#Kt$U#?1Q+xFYuNnbzDH&*DU zwtC#Zf8!GrWMuNW=XU28Qh-v>AXR1l{#L7MW^i@&#e}aGSzUF#+eSv}-oN*DccSKI zAdy1JBqT^AeSKBsUG`;s+`U<%#xIU#GdoBH*L(nmH>@okOmf~90t&+OjsQ{j71NJir3&M=d_7I{TE zh+ly-;5YP&>b|`d=-FvkT@po5lGp!!y9@ygJE`gOU@HhA9*T&7;n+4db{QoqNX|3@ z4u=4K4$)OvNyKYUdRBduc;{PwzQGW2@TMRB-2n_lym)BbV!m-R)S(2(CFbzMbmnO_q>KF8D1_rE?{Aa)?_~XyyO(X@L0XJKzkVYwp!;(i)>I!?v*Ew7%^NPB8i^j*?XxHSY zhOfhMiIjtbacT68jjD#@lbZ|;nRw{Cy58PrJglK+5Le`?K~q6R+!=&GrxJ6V!>FPy zGq*s!CtPJv;$v_K*i?C;eLrE^trQ@wpAw3I-wl{Z=!@v>wp^ovmsc=H-{MkXA(kkX zcm$Jn%?HRxM|vk|p`5ByXo#DDWfV8rmsv`9In8{aER6tkp1Ll+@TO?^*HGiHaa%D7=griCVAt!rPvTfE=h>L3+b|JIh=Z+EKg zUJj@|>gm7H&+f8KBY}@$fTJKr~Ul$H&6* z5l)ZTnFJe%Hx?}@;D*@d1{#n-(O}#^?S$TXd~ORA50z8}&t%PNw!x&QjBp1ytiw|aU)_E&e|#KjA$>;LkO>e4|**P)Nbha9lm z?qM{nfS=Lgv}nC(sm3WoU5ydn6fjZ@bufQDs;zwi*fsbdMMsH7r<$DQ^25SHSBZc5 zM9~-x(TlkyWJKG&Ee=wc`QUT%GkS#a2{)+6n);WgKF7gk!cX%-&r>8Bup7|kuEMWY%jlTAfzD}p*< z^SEE`A2SZe+!EMP%F3Vxw&Gr`5El+9SY_xcu@(Wg*|o!hH{+wRWCUg$2t3Q|54vaI zp}e{@rzQO2-{Vrc zvZ>{Sxz{8n)*j$mqML*OSjX`2K|HK3*^S$#9}&im&J~5)@#BferPmLmBFBN|XS&lF z2gmxrz`$p3Z0^%X9;@fDwzR;Kv0iEsD->qk2TuZ=txW&xK#;^RnLd^}E9 zh@_os6q%*X$wJa*Wg!W%Y$nA~C6H76zBr$wzO3n4=@*m3+hrD<~y%l(f>j~!FS1e?Z zib4OtY_4t6x$W!Ni_2K{pFZ}xRa1QZ$acCW=u7|vG%`0Ql!SogUFrZMnEMy%)u_gg zxZuqPdU6~ugnEc*7y>ZGJW}`AG1#V;8x=T6C0i6>dRP_vY@^okQ3cGZ)~Rv*usRze zYWuPVH8s!?Mv2>PpB6%|T)9fO-Tv%z?dh9MPbxQF#@ihp9>I00#ZsBt6VGFF)GPuN zP{A&5nIRw%ktTqhB4wp zgWbU1YtiBPqIFgDOtUl~Y&)XA#ZK)!h|`r4IiZlLLVgj-)WnnkT{y_3-hh|BF2t)4 zhr(h@RHNX57p9$hm3LA8w@po_f=KBsebez>$;~}-pXGEu-f6detW}3bqsM>(j z&H2EUd|YHv;Q|MgLs#htuHM5Nis;#}*9e4l{S}~fb*0n9awHaq#^+B2fpUmDh_(;Z zF%82>vxi;IcXaar6->BoA)fqKU5VS!DMrk<{AKkJXbLT%ahQ~Vy{Chz2PHMNv@j9u z8}WyOY5&&L5C84KTaJ5%wAG$lF+1ww)3Et*>r!ta&_<2M+IafBTG>zht>jI7*iDJ9 z->Y|8$%%m!Y{Lk#5+tv9vhCZykNRbFheS}*ae9Bdvd*m4VoE%7M0@POO~s4M%soJ> zWd!d&BO};o_<^&5W-@`{wyCm}79KcLX^dv}iPO8?@05L!dLJ-Xgepbu`B;6uT466x zXD{OaKfU?dl}&xG^T~Uvcai1g(jjsCNjd1@3)9V|jRDnlCgl2O{TwLDe2S(_x5)%y!$&MfAXGuO?^W1wg zf$Dvj|NW}|4a2iqIHv^$)%UYMdluYGfsXeVl``M6XLZ9|&gH(t;$a5;TKC7;eIGuK znCsWmX%1Q)pNJ(RsUNcYY``H)ca=W0MZ5UP6ZcjcpB;cGN}=R%ACnAOIY~P|jCL=A zwawz4@t2uQiuyq)CT-5of$6oA#s+ifTj`Fx4I1-3Ry$UST*_pbw#GDk6C4TS1>)CiJQ z#{`xE!GD2#ry>YD&z^xC#c5|eyzydd$dIo>{l7WGY?_! zl0%;9?p-$v33Y4ht$f?FBr>3Z28tzy{NJW)xpuO&;z;6rA|->agmqlCNCdvDenoWO>cF8?%K6_TZ}i@SXqk)zeEg$9m$1RsJ@p|l!=K6GSy6j zHE_^DJ%7P2Zm~#Hv)*G&G`v{&BzOp{8Z+JsyF;N@4^`0mtmUmwwg)PYb#^jdOd{|b zJp%M@u=jE&(qo5+2mtw{$HkLN{XfG8Iy+-Qt@GW03NV@vNQqLpNqIv>Fl;EqhEeVu z#@KlfV=2OkdfBJ9YZ6e4nl z|H5hHacRy}MNU-xSQ^0GocI(K$(-B@uqLVdBzZ9A_jqm*5fPBoiHM*+AuDPA-tDoH zCjPpiI9=iWFQocp)#o2Sd{`b>g>015kOklj?KXb9;}%Uq(GHfX@Av$7MR>Ln0qyI< zoK4^^Y+)b&a-!u873uRZdwL*?X7m;29d!*2eM@LwZL3RMXJP3EN;bibnNuG^t%co; zQB7}z>E%2wM~Bj7Wx`WES!;!&d&SYGXb^lJp;km0SuqG z4K%5y`ev+<%+9*B={jJlHPu!5z^}j}Qi+)tj)rQ{{!MpuiIrrW&aDs=2}V zSjheRMRSMpyI*>rV#kIcbSC}L?}MWbX5p_4)52qS<>PPO^!)r*AX;-PhQ!zxL;vu! zstU`78)0A*$pD2ekZ*w2_!YP{6HORfd!_oVy#%ZuA)lZ`JI1wkEh`^z+anK<2swTdHe?vw!T=cJkIe z7J1u7zd13?O&rwNI0ZDB)TK96Oiiz7J5)bq`3D31mDiFrHePO+!NCM=U1RHnDF12K1y3KDk-ul9NWs|?LESb9 zQB!&O~ZIX3&)GL5T}y zoHOp}VH|B73GA@~k;^hI#1Q-cQN=g1WE6pOhcrUWYoP<=fb1^qtLLjmgd3s)l|h}$ z4%RfI0Qcx+ z@cxxNJV4dLya$C36rbNSR455oSd2Q%mQ?BHy!knLk|dm=4~UpbNw()W?!y}7?%huj`qaCRwb+))N=yG9NBZn_{(IT;{_l9p`rJ_Y`lLA zGWSopP8T6 zpN@rh+0K4IxDJEO&6t#^T-t{+b=ourv`B)+CgaMMy{uz(x-*^N{9^?a0qfI`C-48^ z8v_>*&;(r5&N<3)?d71eE1;zwZj(R5l_3c$wkDeaIpfWZ3qB%kR{FA+$((pn4 zKhW?hD1^kv%ggKhd4aa+$_!vJ$905Q5Y~Z-7#A890PmW1>ZdAV)460QoNz+cbQ1{x zJ4OKSy!yXhn!dQFAqoTpUEyxi8W1S{i}-QsL>0)EnpewqU3JfMzp@9k4+_-^p2?+S zJ=)j(0A*za^@R%~mfydV*4{{}r)k(_7GzHFT@KczQshOHe061Hp_m+-kfDgWcx;Z=~R6-4gWwcBx$~ z+25t`UdTt3KpV{WG@Xs%5U@lPW`gn3=?79qFb8yDkdRkU@T{`hKt$eUP-4m&48Xzi zHntlu6G26yvhq0_RrB!huqB^lLMv?I*;!c^!7Mzepit@KUlf&KJZS*5JSYfSwJL@okiqMI_8b<6wDtJu>undGc&FEbI;T{qcx?* zCX+j)GFzrRxtiHp%j{RbZH)GbuqfvubFDFNe20!wB=J90J$>qW^yXKU@7|r?$s=wY zJNa?`Y&GAD4^alqc6;lhx$<%*lJ{ry9|CxDHKrlrkkjfbip;)Znic$pjEPxBJY8ye*Qq~jna!-Iq*;Bp$LoI%MLXsuq=%70Ss6L?BC-4enrKeYow#DB9<6g9xbH9 z?5B9qiD)Qv(4I@9A= z(*`Jrf0M70Rkywg^vR_Hm*jpore+lu*1(?(L_u~p5$koSnB0|*$%`USe4TyhePJ&- z$D>KDZY(c_-CbLyA{t8EjE;UBnyycqk0SdoMGA!NiN9XV)qZ(&T#zZaakzoxcfXVhlu)s}L+XetZfl3v(9L@^cXu{7g6aRNmX}1>Lyq z^$`nsI)R?P9v7d4Rt-;aOv%qvdo46JwQAs+aBvJ%{k$yh4YDTiJY~qK0Gj>Esz#sP z^%VFrvgR7nB$gA4eGYuiY@PZESQDAKx>_Mxb4Nleq62T*q#3Y5@=2)@9=96 z@-+r)hmaiZJ;+vz^E8Z&B#SpSeLJv8ktWk@;me7?&w8;byL0E;+JjKGm}m;Q?_}H% zvy%nRWU}rr56pGV(Pwj6MjRH*JfZZUuyBT6d?ik4f&MA}gCi;UQVl&M*LRZY0&9x? ze6KYT6HmAp{E;$V8$RG7Pf7@7->j?}^*UL-e`F*oDyo!}6aX30b>TYH_6`o%gVKxw z1GdXVQ2PG0>(@6g6a{bv8A>D`0nL`s<5|ZkfR?><{&_H%BYD(lYIVT6{R@^cuKg0>J!UN<6f`VBi8e zZ@@>Gk+|vVwu8CAtBBd|H$K=%xV!T}33q;;frJJM7CB(KbzsA_rG;k879_nIlr+#= zK&0}*Wr1WQK7ygH|25BAOulE96)4EB+Y*v_%~&zp$UBcUQgye-}3Rrhi=E8ReEm8;O?f z-~XZOJ;1r{`@i9z5h7(2*{dX3$tZ*nl9jzTr=3Jgg^(nBkBUTQHd!GNkv%g?k&%W- z8hBp6&g;7W_j5n@ANFN6I^qABh@H%(a+AB`_5N7+u4zdK4x)wcM1cpt)C=h8 zH^HimiJ_mQR}lU02`Up+D5%;mA zuZi?Z#kaLBIrePp>+|{{GQapNng^~TnyKV#Ywog}-nU}?0Y*+J|?1d#pno}MDKt{BDE zqVF2`9Zq*ei(UzVrf_GFgt;UEM!*L_%oG$v^qBsm>!2>f>OV_00`w?Y8Bm3`AnYFA zKA!&;|B#{syMFub9Vr1MD{Vxb!bd?=bZ+IRQl{9xeGX^=uq=qON0jPFsU|eRXI3yl z{_?knj~{n~fdR)+ptm5TEr0t4Ur{uUD8#l<0KuhG-@;<)?OVt+K*&dW0bC)lo1sV} z5U^e$IbB+LCFR^GcunF`#KefW_e)=Gz4tQT-Hicx`bwc_87#2j&>8H3D>0-&R(@ z&r5L}YkUVQAjn7YfH1Fqg9$ zEbEv3bxqGz#EoC9+UZ{iym_^c)p=(B{yGk;r;$z~wFh$qHP+sxUY^l$xqFu9Lt%6) zIn~PtbFul?QbLb8-XAikjmcA6Q00H3yP%p~WEgUDS}@{OHd{(u;5{Di%!ab%r#>mC zirdrM{=2k$%?s+;scAAxN_f7OK6$bkYAOO=QEbv$|8QbdkO3=s$NRuV6SCkbtDirS z>eknXPqVYVS(KW|1S=~s_q_t-?4Sf*U7=OaMl6!8t(gCHwTiu&On!9_*kHkxx#PnH zajj70m3O|^_N zkZsxY!0!Nx06@@iK?694<7$iswoNd(!RdNXP|(}g_b%)m;}7bK< zM>W6UPD2xpw~6%ul?lOrJ~ z(Pr0{8vy=QE)fFcoYlzR1ys462MThiYFHXhYFs=hB9hqP*!}z~Y}+6xL=yGL%a^yG z`T#SA*E{sl?r)yn&Axbh2vrIHfdfZ8;w&9qs`8UyTr);_Vy!n~r({xR0*$$Wq=k2@ ziA?sYfDqr!UN!_Ts9d-=k6f0TSzHhwRvr`;y?VclYa=-&YfloQgsle}_sNFgEXI{| zPr+Xv@*UtWueH)2W?HIe_hY6g4<|-62_S0&Cg7Ol4Ng^-+Rs^kD}X%3;$jymZB{UI z%9_IuJEmm9QC5@fqW3@`;%|?&)6kRHZk@JfAflnSlQARD0Or(YQ?gEb9S?s|PqTZ< z5W~TXm84*i;2F=M?8H|T+SVzq|9Iely31w$X!`&3$WU+wPCOjFJzy(+PR~7CK}w4I zeAcea>XW{b7IhTNB28oE(edPRoG{$5vU>Z8R@BooD2va*X;}39QL%Hp>@wu}a|cy& z$@_&{RCXZ(7u=RT;eFz%uuCmmx6(bUpPxm0&?>hdH1txcaXxN1rT z$IME#r2#*Tm@+!s_EafTS86ER;;XZn8EeELNADy1_V0)J-U7}hK&p7j=u}tnhAZ)G zA;4cr4Mbf8ts|&p?GyDNxNiZWfxL`pfCi^@kt9Euco86*$=WtJG=%nojA)Sn{@DSo z{Q_ztJKCQ=hw$^hNU=%j10YLsa`jK1B!6I!ojf_zcm(q%O2Sx)9GGqdXlf|@KwS5@ zQf}BVIM3bAS=*OsRH!oKC26T2d85}YGe2KLO6g1j@kAO>?i*G4H3Doe&FyBX?f99GJw6 z>_itAuW3@1lg(w0$cTef0?I|_sBA3UpAfA~E zI^v_uTnS4`0umC4waVBS+AVw_xGY2jcJC-rt1tV5N2@5r^q*AQu0*0@9B!-TFcg3{ zDn^)~#;CWfW1fb#L%8lNKw$_qF`Q{Q3!cu{`(UEC4(Ms{IoW?YksVs}uul(tp(zKT z+9!-ElaS$Rws>J+^@Q_FUDRjhp2Z(%lL~X#w`E2WhjfJ)ji`HOK6zr|xo8Lo4WtNc zaV@ROa`&(TQN1M#OUPDcXFG;&F$V61djjV3#7PCwdIXp*(0va?Hy-}sQFrR}>2Vm) zqerFK#d#G(or`a-RcD#q=uOkW_mO&Crhn3k$XWUKw9m|OR%L(KuNke$?r>ecUH4%a1q8R-DeRHF6rq6?aeIegRs62icB4+FzDXkz;{#c*q&U4OUo z6FIM#v_o0p^9IutVnGBFp^)0@@-lsRE2euS0XdI)mRDEN;@fFz?qHluPDt2Bc-6jn zvJQ4h1=-mrscgTENa+kvW*$^Vq3#Y7R$1B1{OQ<3ZT$zc)m%;`(c58_oWXH|4*=+E zN=U<75itS|Z6}fUn%$5{4b+BR-XLP!db->gT?T%mwN!#hgBt5pIcvoK@ zRav_~7s;QX0qX%yXxzbJi;YzZVnriEqG)cOcIx$k@SHxSv%8ek0m)stA`@{QHIRdy z)q;T?NJbJ}eM3VDBIuFdZ`cRRBmlnjs+j4=u zQ`2L1&u?MZ?E{CMn~o?j{`YBMLIB4@SWh}Y7lq_O6r)cpJfVg|Bw+H^2uN3;_+!|K zXpYj-bJz#)bVfN2dJ{QmGa5YnCs2pfm>2|jrZhRj)qmC--yeSoZf-Cv)x`)Ker+h- z2+&h(p&o!cNY}lMq$-uF*Pt>IGerah+7YB9BZH7R_?EWfzTuK|HNYUzP}1Bm3cQiu z++v}gFLf~@K;${7yV3^_c1%ri5)5cZV9&s9ekWVsLd1AkpvY@6qgwIg$q;t~JN&5l zw?Xz~_s7oElx0$cxvVfJ2PcLD>|^m6;^5UAnVCFs7tY}LFjDhns%#`KQ>+!zG=8_uMJm z>WqwHN66~=0$*!s?;IT?IjxeM!=Ie`tVbazR83ZjCevx*?R*>Bal}U)KtZ!_A92L{YJ=n3_!ue(sni{8 zZ4u#e1U3>*e4#B6uYGxhtONkdXm_9-ZtLq?M%!CpRCGHkYGhy_P42R{mzS8<%QVz_ z?qg+`%i)1x9t&|)a!N`_XsD=V?QUWo0!U>SftbUGfnb8FA5vzJfI&-x5j%{jo}!)b zn0Qi(NifzcW}PGfV1*#S<_WxLaS#wqlZZB1XxfEMN&;G@-7$DU-wc3P&)8U6Ow0uT z$7!K>^?gJiNB_+gt}#~;eqTS7$LlDRsXN!4om7BnB~chpJC{*5UbY_T3tV&kj)_io=gI zunBI)@GHUr1ph|-VVBFZ|29kwFzp2rfzdY+;=$dekPCnA%!e)`b58rI;(}{aUN@w%2+;DZ^ z15GPtA6R-IyOJql$0w`5z{U0y7Wo{Ldbq)I8R@A*05E`orokMnWDEaqY^Qw3R%#dd zlOjn4Nc4adCy92)j@9qq_ar%<7lD!4+86mNr*Us%Ep32C2R6d1_V(W4VNNj{xNnl- z)d8w$om;`*O4UP75ABBA3fu$HU^bk4e^XZg8hG69auI2NFqs2of#@}Y8c=iMUoY$b zJhrn@`GWh;MTdmwnwW4=n;IB23bEDL+YoYcY;2eH$oEm4xWEt@sjENG7vX&4on3BG z!W#kUg@fmZ;S*4LnBpi*ablKTw{BEkCKf-Nu%`fp`U0RMz*3k4z;e71j{!Z57koYN zfs@(W+jT&S`*}NJ0#@hG*x9}N+fLWSrKbxeXcQF|VuCP-$Q1}6pYLyV5OIjmq|Ys)_x<8+`XH}}%!AEFnm ztu3O@{${Kr9Bmv!acF0Th78x}aJsGBVL9@l`)(a7cj<#oh_} zU)7%U*li`yVt&i^st)lDUIsDFULA5gT^8uMWqoY1P zb$#YIpJT;9Nvo5El{6W#2wmkmI0jz>a)*{ zqoWSN60bu^f83IWni_}!bSl6ZmZql4(MIckI=_!**ytyJ-Mup*=y(@55|qISB_;Y?I%=f1AU; zcWlh})9WF?EBg9zvx+D{h-ozVVL{yvjci~=6NK##Y_hbZ#QD^5V3at8ASTB26-IoM zk>eLYtbnW>N^)9+^;9&W4gp_?H~}-1tZ>j|EvgTD<@{ase@aLUL3i!AvE=poHNvFD z+>F$!$udU<#>&4I`!{&|WU0DwSn>IMNXliszq|89_kCB7(kgFVvPUea9QZEqM_~A`BU<7P!M$!-*)?nkDFj-~$j0Ue`v!30ajg>7aWK%} zQ@!Kdan*{-_X&6yzs4{)$u_jDSQy|6`6@63ycs_rpEx=HCtANe(gqX5YP%u7E z%IFh9=W2>bbar2R7;a&wDyGu9|{93KH+**&z{4;$-gcy|0L#?`M$`J{;T``&qG|z(M#B_ zcOl%4Uwv#T>UJj+(^sbh6HOBlRFx_#-qKP>YQgzg0;GmU7lWV&NS8v%MRd=`<0`== z^D37%Q~NWHaANomdO0|lWa}*;=m*@r51&32;V|pdQbzYmPb&ZcWieVxJcET@P)$QM z3)UjeHWl78DBAFJgoU#Ulrl@IsuEMIjNowDYL^(TLJ<2KhWs$*mc<YBiuNs9h19 zmDCBd1qmssoC0LZ0rc@XArf3Vd2<`jss_Fy=9j`kNOf=A%4_&FkOQ3Qh=c^38?Fv< z+&}Iog>481K2*rN*pGfSym&Sf;{wFB07yXOT&|&@yIr(J0atZI#XmmwoiFyu%KBk# zfEU7Y;`ZLj|NSy@eUJ}~iDOUFn*gfzMOTw@3b-e9HK9>~C-a!@}Y`Ffy3!F3itsrXM{A9|(ZHZG~o3 zJkKNB=zqsbzh)L@9F5k=5|p9UO+T3!G-o}v=3k& z&ST72*rnV@vBT%yzaO}xkt!@M?hTkmBK>h$nKxE0fIK-)QN;P7AA~E>F#;w^Kply& zHzs`OMudbwTm1yp_upyFhc0k5(8uBjyB8g817k+>ns<@J!cY#g@$aZd&>(5L5e?qZ z)w=)=>cv3=LW^?fPQ3iyh~Q`(S`a%x9|P@0^Z@;_nW zvq=1E;o;_xw7_Nrbr`lX46DfrLVQ~=DEa;C*V@Msz!8W+#5*&vw!VMOhFBu5CT8id zy%cHB1F18vflp8wt~Ut@EPMAlySfSrH%)uRZ(dU`{y{=0Uj4VCbd|ES^zwGyw-mLX z^jlxn2sf!7cfi@FfhA%{Ivp+yyr82MKxa2FI1z!~2%b+kV*(Vp;i0+T~FoVaN^5hu|}9@rt-?ZO8zew zpxV{ly=&U*wPP-wQgJoHU(h4{#A4Ua(R8t*1&4@5{^}(sr<|Z592?-ZBg+Ku3G)jatiYiFSp4+| zn2Q885^V%5SF!zJELMZyBAlCJy8~{^%3u1b`1uK;1jIRbu%PNCny~s{Y=`HW)QJlH z`;Q;YQ~*lPg0>EGrjziw#3B6uKN4~5xw4m)brBE(+S(|hR>YkbohkClZ5qkH3ALYzw+)$!ctuZ!i z;OmOSs%*rL#1lo?2!Iy6w?D`pfPW{%02aVw;Ogwia+#Sq31~GjJO^ptiy-ORBj_~0 zvB;1AuN3+d>T~Rx{(e0f5+$$?LA|*)h|u`{&a13JCXmtp8921BC zg~DVSy3@(Nt$FMfBM?v$E-u=?lq%US3i-)%=0ER>%8gnc6c{nbIr~yC42wm|uOldePBwe}iq) zpPYqV3uni?l*i_ka|jKyO-gX0gUEj~hlM`5o=T!BZPTd={DPc%U}Jy)Hu~@X)H+Mi zYdn5^6m8E5;7Rb1gSv;6iD`IA1B6$cr^HM&R7p<84D|G+*yXtK?jJn|U0wdzcZt6L zH3k6=N9<)lG>nhm4eW^!t-cSYA8AL=@xH45$HU{e@1lW{Iu1%4CPwDwGz1ie`}b!9 zm|TnD9GjOhlzqu5EiZ3%PX03jd7<;$_-MU#J2Dd2`S9Q%j(H@w%%Nrkcd-Ujc93_F zhT?P!>-59>_eA+29$@*Zu@KWmNOaMDL)64Z_%o-lm4fsV{Hsh}D`sIxbTA@8`p6M1 zB0JBvBX=EHj*r<1QO0sGw#GbEer1twZfXio)qYBf84W>gvB~(0Dvy)H!#knC1dy|! zwLzTm{QeDtGHl+*LVRa!ZO`cH!rs*i{zibzF+e|64d|y(Fx0L9W|F<|Zh5^4Kp}XRh}4<)E4+ z4rUb;{07Ui&m}d@vIBJh9Egq}=M>lN4?w;c54)a_h^Rcdza+8x z%Kuu}5u#sh%`Gf!CrD)T(qO|N6$mwn4Cb#>Q}S4%SWHVE(QpP!PD{g8eu&A2<+$nJ zMUzOOi>(h@L%vz3(vU1~sJv5?3d1EBKO-qNCkM`#fr~LvW&NLHo$>i5Vw;m|NT)SySB)jYv2B-HdW|N7W# z)+ZKpREm}jJf3=j+X$C7*-1%lS}4~4oHwc3;qLyrY>tX&$biBISmrAvcV}eS04;~A zmV;p+IyDuqJT)$E;90RSY^Z>1!6_Ij7FB5}SFq+$1`*AT)TC#8pUry1`hD)>$2#;w z*k|yCL^1emXs9x4Jfzn=H09GRQ{8m>yo!o=x@U3&I{G~QO((!0G%}(Pz4!jn%Hihl z;v$zs6#`sMaVHi_lrtO|r>CXPJQJk(Ss9li(uHw*Vpc%NsHRJfr;vET6Za>8U-n^L zZ-(-(wBfPZ_mBsjy$7fhq#fjqm>b%d4qU!;32|7NAqnUSu;gWlc{$KRLP!k#8){H< zlSg`XrRx~p;vmQ_kT4TLX@(=wdq04}{~6)*UQSO_Ux@U60T)$x*fEBwl$l;e7&A^} zv_$AKu;l==-b+obg?ix1Csq3|K%@a5IbQ|`fZ+Vnat+4H?h{WABY_yQGvcs@%|n^d z@1^*aG6N2EsA3~ejk`>lpW0$At*(CLzb%jT=l^Z$H2N*@FS8wD#r}F`gk+GDp0KjI zr^uZ_BavJBxz)e}FU*_g9DsLklJi|kY#VofGCg?HQzEyPbz6luCR{PWQb0rmD$?!c zC)W=0fx!T@h<~aNH}LD%sTA@kOK}svOZ#hl5j@3-yU%gkQXJ3FP{Z!;>de$MJfgc8 z7&0;l-(c$VFta{#r?Xq*?n!leII6`bG(Wa1Ie$R&F17X5KK{E(RHgcylY2QiKY#i1 zWp)-wgru9>#|xf}d?>?b+GB+MdE*duGf`8%pRuRG5GCi0<-@P+ZEQ-w(gZsM^!fsn zxG0l}ZWFS&J}VE^SOk5l*EKTY&+h4ypk+KKkoHj5a|oyBtf6kAz?sq=cW>4B-rNf? zh33!KmR-Qd-HIORPGQE0(*#)u{kq?s&{@ghV!L!{9fdt8*Rc9{Ngh}E0Q;3-)2|FS z;NPf=K!R4-T<3eW8{qO!__M-t7{I@p5Yyk<$!bBtC|mX=M^evRxXJ@uW0aJX1HwSV ziAgy~MT1!~XdNK8)FO4&9DU^+DtCOZWZRCHFG&e#EmhNi>OTSdAI$-Nwk4EF5mlLC z$Nye$`8$Dm?vv#gZl3l^eoJxkmEWQ8+qVf#ot*_GCDD#EAiU7AvlC-ZpqMzH{ap5Qa&dQLot4ux-b8vsE3_XFWs$RkD}=My+)=i(A(eY9Q` z^Xh-;E2(-<^7C)s<3aD=g+bLR)Px9LIVCL~f*Kk~G-f9F!Vb&`98S)ks8rW|7zXjYcrH%$kW9VE_PZz)s7j8|Z04fU2CP9sRPvnS$BJ|P&X*t}YMVW0IY zbQJ4XuLJ!q7`#bGQ)1_p6wL6{Rg=fj-Cc7l{EUUoy=#wXG;b(7oxn}RPix17N3n3RvWqlsJ=)a9 zo6D|{2ME($Ab4|VF#kn;jPgnzK72kg@du{|A~)OrQ@PW=P+kGi2YiU))wm2G4467tQy^E|{+@f~5HMlKH^>4W!HNfc?-yl1bb#;> zLCbT1Dcn@m%Gz2%R(5=J^a;peU0qlM;OLwjYN}eAAs&TR_5cgug@{=Yn4tKK56pEz zqekCY5rFz0@Mus_5Kx7`0+PG<1%!`4OYuB5ILUajfxh6n!z>7W89q=?Lqr1j4kNXD zaPUIhXE?qf-UeKnWWkt$R{5N__XC=;pH*+%LwDlL1FtD01fC!SuLXu3TvN?O8d}?o zjc?rv4x*gyQ6M46uM-9bGis5$XtQwzM@d7PgfrcxD>w3wHH=zcGnBo6m?d}w)yjbM zVrHgDWnirADk$ei(Q_}b;o2eg*%w?qVs!oeP0z`z+yhgNu#qlY_>4qI#nUuZ9zmw% z22$dJ)SeRo%p`N)SUKWm9H?kRO2po-WM00=udhG7WJ*PKDa6vCGQaP0MLAQ|qZ|tS z^?B!8QIv){e|)=po(hGLKmEh-=TFmcRaP1?WQ#y>>I#TEaAHX7>`uzTq0GlSckEEy zhjeq>9!|`K-|+LUsvh-Y+Wam`M8Y-d4scBpgQ{R~kKnSNk&)^Iw)NXY5-lVv=zns$ zjt=hz!1UVG#^x<<;bO}=V#s`?CrvDxH{&yBnhVA01D8Y(Gcq>zpY957|7v%`p1>W9 z^IDL}=7ND?#^vND`Adhli(5LqqXO=btiCOKTXKX?zr)xznX_d}q>S?ILcJaFj?BaY zel7m~eH3v1Xe{v>tL^UiVT)1j*xP&i)H}#biOB)%>|Jv!m^Ki}{DMQc8NmjFTdi%& z&BJV%;XQF3%10JEl(A^qi6{F3@@FkAWMpI*a1w_c=vIh1Paj8mFi!*2^S4dM0sjNY za_URJ`+^EY(P^H*{ z7wOag&r6&r@X|$IM69mB1VnT|XfPDde*D-IHzR_IKlCK1!i5DUMXF2z%jMQSefBs&ay4YwG93-f|4uzM zX94};Uq%*yud)8~Cx`si(Km0n2t-XJ#$fPUZkMvh|Np;cm9Yi?K)Z&1G0sm7Qvp;| z&VP6Z+R9;-1q44oZ zWtqG*OMUeRhl)zmp;vOni`U#MWVQBPv}-Stvg{n!x1_DA(zPh8zp4FuEJW2LwRst>_({j zBA}i}lqxE77WMh825;=E(SJ-2nPQ@ymoj>z?~lJvH#;rNr@O78L*b1i^Xyz z^3l+SgJE?=Nr_Zzdz*^1;OEf-V^Krl7)WqG8tCiOY~OxHU%#NJ=o&`uSop+MU{wm- zXB@`>sy6^sSTi_-HAkcMG&&0wQN{lkDg9lE+W^vb{O|vSDgpdP-ns?2^6W1~uqyw* z+;|H^t~7ZgEG+c&`_Y%d<7Ou!U|oj1K27()?1`)JK zJbKP}Tr#|U#;5Gem9O41O*(w824f786g_4k&RW0Q8uh665Q+gTxldOX1y!iNt|`q#l*#} z;HJQx{`|R0ZFFKH1p& z66xDV{hzj^CdH7*%R{Z`;fJtgeQ8g{YR}%=%+2La&ASwue!OY<^OKfsWu;*lN1N zLdQ&5SRI2cUkU#^J-vVy5?Wfi@Dt{22ml`xSbs|f5xB!6`u^dzdDY<5;yn-8K<$tK zB?xXOJ~+j`v#kqK@u0`SI4~8o5KKK0frVl;iv8HLX)i>XVQkE{XOAR=SU|Pl1B&7r zwFO!o6eC1pIW)DMou~IP5MgYLm+^Hc%KwSNYI66ooUI*xr^U1<0K;`#UCQr zU>vi3`*z4dz)!d;Zw>3t;NY(GV=L%Dh*OHAUN#mM>HVAethsQ-#*HJR3!kCMNz1>h z9NodfWZe&pe^TOzqe~x2Sy^+#a#Jf(LhA|8%dh@fFYT{>%JPqmTg{d4`Hvp`1ELAk zVs;ipl8CQw<%DX@?tplARt3{8_U1AaJg9OfRI@v_9OgJY^}QEF>bLm^edHXjY&_}6lK!Q600Rrf?W-) ztfq(?{7vJ1T)^lmVq^78O}7)6n3yE~g!jxrky{H1Cg@}7d**%P!BD_}J2v(kHV2Ux zGBZ6=TAk^Z!-_x+`iq^wS$88Mw+y2&gHQ&Xh7BXy-L@tS=imO85=i!_oAY4wPe({ z9tEP0_-EQ5U!>jtEFQvHJXF9oR-N^LZF}JL4V!1=qfbhIzA(JXWj@MLLv4QjUWJQ~ z{oJ3W0`YUaqoazKE@2W5MaGrHL|rp#TpUTvSHF_%*qb39B(5sWJIGK(H~9oB5$Pys z+=kCi9;yW@3m9!1X&~?gG#;2oq{PO)TUy#dU{NAwF`$Anni#k+%%cL!Wp%E}&W`+q^O<|Zb)ckf=BtQ+a+ z`GV>jJIkV`@Q0|r5Xek#4t@F#C>0|ZfoeY=pH&P8oM}>|2Z1F6%%SL!Jex84dvvvw zG=$BmtU&0M(RVQOXxi~o5x* zHH#6UJbjFsp8)N_`djz{WSSVo;e$iM*Ec)H>Z*LB@5&9n!8|0ofD{Ud7$4AW5S@Wg z73$^1zj*&0y%T^Ua0iGfb0dIPyV?8v7I$mj+d%+#{mnJX#6()r*4E}c{jZ&(IQC8_ zJMWJVManeWvh-012$K zz>}Kh20t-RcJ~P?BO^LSvbk=QS+ElA>$CBorKf-U*~))@s9<_QfBpN&FTaSiV zwYzWJVC83q@d1o&mhIKm3HJ7*4QyA|+#hbt&LY#x)m7J=W*3)I&po=`EXlC_jVdTMvGEty{oNF%vW&f%`Ux#)5T>5*Vo+nIFk6r z&nW>ALdU>$-T6|QlJfMh@LTWcULKoo$LO97%Vx{}qUydMs<0VwCW}CLsORMy;x-b{ zaq59j@bt;A>57DK=9cW!-zOJFbUKm^jGld-jE*Ih=EIw^@zayhTOt>%VFF zwS&{7ZF{*1&WmByHYDS}+xt0AYV`QmQ1AI@T+7_~wxmLBNYT)+`PX;u-8VwEsqe#; zADxgbR~s{1UYvh@jnQN|2o#1t1`-lPifb3k(eo6KtwR?Ec#fk8f7`*hUsCt?kCrmW z=-7VO^JM@nT<^J!Wcd4Eiurzv_U|rz74AvS`yK^7Kr&Rz53_{LDx8URI|hGj1duBd z5}_RiJA{}x1t_?-Wo~7*R@I8Uzw}GH(&O&wmQb<)T>*zGa5@PAp`nyKGicK#Tp<#< z4j4Sb=&^~FVKH!49QkAMOfQS1?6JGrl}gPLt0doN=j>7ng_N8u0I0pMk20Da94V^U zns2?10w(jUQ-;GC0-EbSEglH&{h5kd3$#IyY=r2jUaxv_Jjl&$@9DwB{FIv7Kkd;x zC{ZwHwE5?W__cD_E@FD|>s1q44$N!D`hr*jKBG4%)d>gTzdA|MGECa!NLxv~V=Zkjj1ypyX$$Qxt zKU{boyI(~uG(Le|N!@TyX~jNKPluRVnRg4PsCatrGm?>!Dk>?dJMsUVrX*FQ*jXsb zpTHn1`)xpnR+yX{N@|hF^y8m|@aApm zcT1X5o`r8ta&vcgKko>O2YumI`H|`6Me9`Yklv4-|MXB1Y&|nNL^>N@>K*fYv4=$9 zXGdp&|M#@Bw`ye$3i1X=7nyG-Y^QR5NRn?+uTE&sJ@dWb%o&H*6-m?rkzSXN@dSVU zNgm)nswgh5uDOGRJBacS3u9^W4lZq{SG;-$d4k#HH3{kl@v+SYzTC$Ka_D!4-fE>a zPxXEm(>A4+___Uz?`Ef=Ky|*4XkxRiOH_YgegPjDWo(ap!JEz1gMGc+LO;k7uCJLc z{-Y4MN8xC`_Q}A2i6 z-7QgVJyX^fk$=H~$Jm`Xruq7HTG{C|kpg&!O*-;1Zsz!$(7wUJJGX8*S6r|8mVX6p zIOu~1n7<3aHqu<6?sa{jYeiIkg|Cl2nDi~5CTa$HdrR(E`TXUVWnS35XHRx!COrc~ ze~#KQ@BuJp%>SpUoOBkP+GuBoS&!Q9n3?~)cWED7m6~dV~O+*eSL71K(IuN&@={Y zz_ny*18J#g;FPLjd6y8q{C;~}PxDv`f$oEyXAdW-VvhFy;AqP_b%%XC!Rpx$-HadP znOcA7<0Dmk*7DJ~p&=}gBy-CQ%MoE#Ff;z9*PD>Nzi;@l_0y{|8aZ z+_`IOpSRz7_^5Gk-Ml(Jn4qdwUb)pNx}DJR$|HAX{tT(&a3TJk=g*TWu6^FGckuFh z2~Tb0enIUEG=8%}9LD?ncIU;<%*JFYvprzL_f2KZjH*9=70WW?M1-_r!u1U*Ld`{( zQME)NbX8V=yh|FKhWzFr?B~^@#WsOueMLK?@LF=!*4I=Ro9fg?X_Z@y;VsP5Ix~OjBiGWP52*tHQ7IShU>v%!aa-kO2ox zrNznvHf-6Z=4M+^Qo$mJWg?s21Ddub}u9oa&1`m{+Ysf6Um>N~94 z^bYop>-)6T((|#N4G=6aCL=73k}NDlr@ zO38A_SyJ8g9F7-^aYx21DmS0Ky!Q@Wl5cu@xLzq{Qrl+I&~FM5B%&m`q(+ zTY}M8((iZ8>6o@-!~C`@O{RPB=n(?Hm8c+;0hrroqqpO5OsWQ1#0S|F?>yit(=$e&`)eBDns1|i|wWn-m^XMs^0|bXv z=PGfb(Wnr!2YbAwNdsbH`k=~D;q3!^2%N~*0uN(D)c5@Y84^t0Hg_z6)5y?3XZHoi z;E=I37-d&sur9&;7B=LL7_4H!0n$WfN)pHz=zZUysZ>>^AQW2Ee1n>Y5Pk37Q_o2m z0+@rNus?=Yn!|uL0#=9ebmSI1H5TXbRxDIREL>HFO0a?gc7(VS9-rv2k*0o9|^{(6h37ihBnG zF#;7ebv{7-cZy*u4~n1uq9%aMf8ooNrLpmg{uen>dk9d7UxT44KrS=P#?g0Uk_*n1 zp_y6j**Efrucj*9lJb+Ncy0%Q)Bbq1m*X912#_8emXthx@pC$KVw6?nC=Qh7J%~ml zpl3zEoJd?ewp(m;7&>@Zm1sE(xK$k98Tx*D`W(I$z5%Fmpwj^TH8D2_oGU9Rn4c5Y zaroa>!v{Ad@Fxy2n*j6`aA6N^8N1|50KJ;(%NStu zySjqk_$P@DuacRX2iZLva7w=<^o38>aIVoJ#Jd33#JjicdXlL=l1Ql<7Z)#T2gi+;n4JOQKV;Y+UF7L>0iDe9$u3B znFKT1j<{Lr&6Qm~A1O#kzRuI9E4;b1A))WRl9O<4$Ubu|L*fH8GFMmo)PM`)=0`c} zY&)@E>1-4bC2S_|qva|V(k%+0M#dnh?7VudGe-s&Pb(jklYppyoGN2=f|FhHf^SP5J=?UKRx*LL8kJ}vnD0l}y zsbiEmpAbVo?bXiZAN~GCSjaXK?rKkZr?p~XbE?pR=<se~0r&AG9q@&msw14zUH#rs z{*P$HzH12$-i92;@kwd~^&}BdkHW|Nhm4|i6j11ErKyiRp4r-rN>|YFoZyb)8u=05 zKq92VYv-i;p*!JCxA-$DDe?fZAD0V@wi7asgmy%pGGoPIOK^Bj#lWO`<3{^~li$zg zs;dyF?ixnUDtdqDIl#X2Ouh8@eAtUk`7$3hoW$0Tm1+#L{WiWQy=*=+#A!(8yCskF zJSS)7&t+bQm~iH>Odb;Mg@tdQ{@Ge8ucsF}Q1XuQ(ZT!M#-4snUiX~Z#%L`z%yb5}xjqjaHc z5zH`&vWD5^OHg$~Rxm&R;jh0`gKzToyzwIyF^j`RkXyF#E{EM~GF_(N#k=f;USwhDW)5VSu){f4+%BR^66|o~pgd zgEmv$))wv7j=hTS-nCCPfL8S9qcyGmhdoTO35VDgk6le}mtRsnn?)KeY_4v~GFJZR zy6>3ygU8w;)}8{FKQg6A7jF*rC>%f;-MB$)&I*e<0?DvCV@}jJY>!eaENp)kf&}d4 zHDiNlNw@Y;uGj!VnG@|;MVMIiIzj!-Q-^UWaeE3Dg?kSlZ4qt3h6jJHk^JeLists~ zj9!?csjQ5wt*rWtSik(rVZ#F7JtIAq#%>?o6RONSLe_jMcB-7SEkXd!7*8;{y84s? z=bae(8@#p?_rt?K&dl8TogPf+_%RVx2nKH}^B%{giG%M~9IdbNlvgI)J$@*zBfq9P zCt}3s?IB~M&6#hDhGWTx#T9chc~;gEX*q@1q%?;gMRh$_p=f{lo0!uiVx4Ge-l)Ep zAbz^@c5FQRUGI-0o%szyrHd?y8jkR@YQ4@Znz)_3%wt^8^ZI5@VMfNcW0(J!NL?zq z)0r?f-pM4ISbG0;F!|VnlY7EHO$i?o$X(7XocZO;!d>T+_wDMej@`?Yn+RdzBu_LeYUaIzB1Y6lugCjq`xUunAqOiEX|JVzz&dtrb)Me#_ttI2S zYqL6U^A(PkvEIAg+FC}-COCZeh}zm$+g9y@Nz(IQGc-@1UTd?Wf{Rw};>Hi_U*kd7 z78YL;Qi6iqTZvN5*4TK@LT1Z4{MPNQ&oeXaPCbv4H@}@``T8!Yki9N{pOEI-3$C)U zaz{9avK(n{?jr1mkauiO0cDYS~=aFPEIwn4FS)>)d-f&c{#7SamN*{aR~{U@NIIx_EGgw(dM7gyK`jbw_q9 zvEEbQVS8+>fpb#8`g^Cu-4 z#bDV(lO4>=4i5Da`f8M6VI|f6ht=*`$X(f8?u3Fb{dl;>hJdS`!b3}zui z1q8DA_^-DHbd=;bP(^JbOAFj0L=ZX4z26B&N)fclsD8hfNz&3rw54nNaZF83K}VPG zuYN{YM&YGo*owZ9Q5A@-_%?9enFYCGn3iF|+gk}kAX16G>b0~h8ya`^LMcy9Zu8lq z!gU*AdU~{WkK4$z7iyEOlJN(0N?aJ9ZgEC%m+DN#cWHLr4JV^iY;mtIyK&=n(m|nM z1G7$XQW96^_&+xU$MQ6;z0Kbr11Fh8$A@~mnTE@D5IBq1_8JwP6Ct#=3LGkMOo?T< zrBW%RZ*=qBJF~=tqLlZoJH>Mw)vCh!M?wQn2zSoU58f*n=)WPj#d)r#QqT_p2^^%JkCGN=_NVx7ay%@|VX)qdzM;5j}@EIBvC;R6Ji@ z7%dOIB0U_$ctGr$3|t|Ztq03y^7Pxg+upT`zDki}Ib>whnaF%(Ph9vBr?>0p+$U}g z6_&B3KTCC+zN~Ob`AA1f> z2Iwrw$$S5e7SYB)WMstnKc``ZE{1qedNn{+1t6E$^H13!A|M>Ib(mU6gx$PF9C?Du z1?0^K+(|eOBB~zDl1pIKfCbQ3JfIN&7qMH!Xa}S+aO8g>Q3)WL_2g_lIH*%#&tN8f z#86&G|3sYnqlVPPxG6tL;ZJ|$V5QfUd>AMmCNfvEl5F-c+Yj)&za}S?J56Ur^=7?D z8#mu@Tl_vEsKE7cnCIwT7MA(J?Q3fw`V2f8xtHSX#K3s&gJ$d3iC~uplh5)kRRvpT zJ0WC$cYecZLZ~QkS5cVW{#V1Ji7vtWCHq>W4+qM$@$wEOi*I|RW2`Oh>Xuc{PC>C( zmI(^5Oy$fX+T+KsZXM5NvraO&?Kv5pcr$dDt=sQ@%k1p+pZ{p48I_vMbw9bvayu(G zF`>DS-qBHA>srjJp{59R$ow$vnKSF}ckN(XvujQ5k9hy$eUdeITwX19Evv|6JI+cr zX-^!Kiy&J7eMEg2gv4pNOJ4y5x_DXjyCby0il{(r4aaDkIG3)j_QxcZUpt*Bp!7{5 zrV7yYKfnvqN*3dhl3K$T!Y0qAzCPV5Upok&DhG6C3 zt)14^mI6+Wkh=fyN5QVLw6yeP#?UgD?i;bER*hiw#rJNzKwqZG56U9Z5(daUSf;XH z>fg`LUjq1p3juPeS0MY~Zva9(JCGA$Ac(UhPlXrJc0OKSNMXk%wu=H3i`~?CpA)DP zaE5`F0LAk`;;LGQQ|0V_$mZwZx$|Rnm0S#e2a*+tc2bg)mr%B0AEB&(y41YN{U<6# zdH835oj^l=19hZMs)P%8Q$&ObA}zicb+B0z8pj*KUBEwL6AV$nMkF}Oh@=x(M4UQB zE7VYp=Yp#aN}e5TQibTb;F(}o08qD-%-EZM+51Xy4oBb5%d;y3U%|r%L&&Ib6ds;0 z+#_{w%}w{S=85mkHQ5oEk?6R1PE1#xYj(C$DC?z7M*j0>i*91NDLdq>ggX^0n-vXN zXez_{hl;LAco|ZV4fO`}>-vQJV%;&=OLyhUfBw#$kYCh6fy2)SD|oFR1jo?3UVEXG zP^xQq*#Un$0Ryyq!4Kl|~sxZtWitrEtA;_~**{FE_bM1TwNh^U%$W+VC zP_Rh5`5w`%T2KK^fL}a#o74CWNMMOTBP{M< zaOP)^rr{69M%ZLd$5-4vJpLcHzB?Yv|9$&bLP|wel$~U?tn6fEBzt8P$xL=unuL%| zCCMlwn~KnqD9IjWL^88C={c_Y{C>|L&vU(A-}~cRx!tbo{XXC4d7Q^_oclBqIHGHj zGvQIgeUEg>+q)W(Y-k7_{$(+SW;@ZRM$v$b3}~)UY}y2_oFj;l$Z!$8p~?nQgb;`Z z>T?7^Y%Z|k@S&k1>6iia?mp7&nZb{^7g^R8XA3&IyNT1i3LUvCz(wsL*vAalQ#u>f zCozZ(%4dQb2Jea`Z#DJHeQKZ6`p>F)Dh>^`evT;f!_Xhh^ZoppEptMFU!?KEnR<^z zik>9?*T?=I1F&?2UqV7#)3rbf9y$q$zHYBWei9TkJ}yb5bk@z@d-CEgwB+`3!E6tG z0u*Y@B=r5j@v#XmK;DnAj`?py5)BH{Kkkn|s)aGH$s145RKYPo481HvPKkUHsS4UE zXgc7&N?u-D0xJ{W*?d3!HL6Xl*wks%-E*T}Rhv5w~@E?lTYZ&Y@9v?{;-4x17U- z0{l>05Z6hFXB&ysXaX6{-9uIs_twXY8lZ87p~M}Gwl*>0zbwnVZ%e^`WmbVqyXw2& z%Duo8$?IAVC#F-QW~AM{TN>{rMm}ZgT(OBmM1=mzSsYF<*~&ThkPZ)-u$BR_osNzU z5*0|Da85mZNufO8Ju9rPj$Cp$YYX4eXnr0GR(5!(y z^l!F)=jTI}?f0b&8w#iyO8dLZUd{yo$7Fz2j4fgA*5j}Tn(DDWuX4b2+2 zV?l+XRucCc@c$n!00lYu9PTC>u3dBQDgHexkf%%Snlt`O-cgG{(?6Q~gavcsSn!J? zm%MwdOgj>X3LJ@%+mlT#uMrRCr8m@OF=lV!#`1G$s2zn0o)!MQ8(QG*dE#VBQv%Bw zQ~3^8vkktqDYt&CQBxPF z?0tTfRXqO^6pf&^U0O6Nwr`y}N7tkvdMZxc(C`@!CoDZn@l6|EBNi^AQ$vJALBVmj z4=_>R#Cn0^20#PW0gM&rAb*;hb5zQsOq;+05=M23V-*n+%)4vXHlPJK(bUoc#`Mfy zoWNsq6P(0jp|ZO~yf>zTL7WOuq7*lP(1{xArQ*;A85nNqaWtFT*FZn~>mc#!DhcvU za7_cCX~#V!W@kDw%c4@a&`{#s+e4I$dv_8K#d`(hF~}}Fkmf13Hr)%0`3+KO{yl8^ zDz~ANFk67T{HLx-INYfyD-%PeVSIA7;1WnxB>LXm9DOrG{7xwD5#osvWA}E#MF}>Y zFh7WmkC*eF;eoZt+qcJE7@*le%CS#E!stPdx~Ar)SL;-IpP}hM6CT1X2&JIi$|<2> zh%l*5)SI?+=sKK~Ecxrn8G?t1cz}PS?e+I&aHeJUPrn*UeM04Tx!Um9>rlG|eIug+ z=2bdsIKnyJ%Xykwa7dABX;rs4@(xA%YsrpGL#!dR(GcZfXp1civN~RGC~#gecxqA` z9S(~ycr)P=u|61yK!h2=xO`UT>_7xXL_!0UtKqP{EuU|ogS~w?tM~-$L+qZM{TJZ6 z-__I*u?%@TW@QirYnZf_31r>WQ`LN% zDSBP#*%^Zwgv<)MHw;EjZm5ENC$wGXll|k8lKh80?*SVe`-^w)-p%A2mi4(H!$nGu z(N2dB(aLKI)T!*vO~dSA*gbM`o`Jm|Tq`|6OvTE9?G0{JAzEs<3wb6bb*T1{JEGA7 z^D;<&dFX&5h1CoY{}lETuTbO=s}2fS{lLl-YHF@tUSRzF#@#Y@paH8N0yaO{WSTig zG}sdpYqwcogla-UM`vgHf$L(-?*p%?YHIVY0e z-_J68OR&nw$+3W6m?S_qqG|ewso%!b28i;Voi8-+iQ$j2xnbNxP)5Msd2T;oxe3AwXbA@~F`8wR zgGitiZe@WIQ;9t|S-JWdLMrS@l!!WBN?FuYR3JF3z*M*YqO;H`{EQ_xSXx+LAAC_( z=7|gjB|H)eTv(eqC0mJi`yj9*v>H$2PZb6jBh9Es!>W4_b_`GmZK9-H9BbE-oyF-2 zAPuKwZc55`9IDW_INRG(qxHEFkrE*Y$KE7PV?adhC^;}30#9&b0)jGl42bhEjem}m z3U9ChMd~8GG?ZnQ@bl z+=T6sGT_(&LHIPFEd;Ko@JT8tn1)fQd#u-C?I}QrPmPO|3(~Sg5m)U2M}ok%F(1`3 z0SV&M5)&z=0C^EvB@AHj^ClOXItdu1pSt>2&p7HSD)HhB^|!^aCGC^>P@Ft52D z1y6?-^}q0WQjv?E{^b(?{>*bH&DrYe_?;Ck*eNK!v{S~fHW{`i&KzxPd*Y$^#D6v4 z`ov&lW=Tm(%GF5j>FJs~i}vl!sqWmIdAY{vtl9b?j^ILaf~Srq@ziM@9Xi(Q$8iI3 zP+}{OdO??>>_Ntr3D&sCfddDQ9MN50Dhvh-1=0V_5Sg!V{MgE2c-Db9f_$a=DFZ#d zBa&kvrzHD2342@Htt=w8D3l=5z-9v^=e)xFFU~w&@>?fVdB3{O+1M?LZWNILb$0bLrrDNYBu?JL?dGU@^!W3Y#~U}sOG6KrCwDPZf)-oI7i0Eb0!|K+>N^20h|?96#7GuIeK8H;g=5C zL%wt8&YCb*CN?(n2r2umNI7kQLZNy12fkXpK)w+o!k7;!bTj;ehy?`$jda-xx;oAp zFg~ccXnyK8Pgav@M3yPLGw4ajA*Z%}APDDAV2? ztQZABaa>?Zk@b19V@ctx>y$A>6%KVHB-j5Qc_N{f$FTeeMQDV2)>q-<()ki%- zIz{DB01$J}2N)O`3n#(Qiv2lt3H6t>XX&5-)_uP1eyOkMonn8XQIF+`G!_^BWS;d1 zg3tsG7o>4dA$rhX5(Q~c07IdQi!Vu=W0q_G`E1xQVR|w?7SfIN&MX+AqGYifmnI6L zJ3jkj)j;zo$74c;4~@me>JSFl6L%|Bl;MP)8*86LEW|Oa=Ov`6eBr_bA}oB-;E%W) zMI9|IoODR9;2c3?Rlg#I5YNBMBa+xVLSJCJ+m>s#u*ywJg1?RT)7fLcVz0p=D&k01 zw#rYSG>n2qkOA^;mq3!Ufbf;=d8Q6-i+G442|zym09)asAzYc1dp?EK9f=ktkv^4_ z{03{P#Y}al!KqU_XlbYWUT<6wCtyzU4P+!l-KbA8YlE3$9-@Ipvg~gf|HH&*-_hjW%A%7avhTq5bLV2kVF|8- z$B1L+OOs9wS+=RmA-K$im}-|r-f2HJ@?Jdm;Y0aD^B;z0mAE3Mx1bm|LS#IBT5$WO zx_v*UUmK?S^kQb7f#^+RR$WV)e8wFZ=QB1uOz4ls#t_;d%wuL|&fg3ixB4aT78m{u z=6mlR2LpaZy+P#aNVqXD9#-05E#~%@!6!)YCtrgUZq9~-qN1@8*1zD94B2#lzrykR zM5%D&Nk583WDjLHe^K02Vc;&xITRtzz-ne+Q?dj1e}~C^-6bMB4<`!3eS^rTg@xf0 zD=a*Ln}r`q7fgNy)Ule6aD|1gu*FQ2IG}r;W48qWvV>?bw9p)k z8z{e8^td_6@p*8-WA4s#*TE1F_K`fD|CBI|CYA0a>F*Np4cVpG>MLNN|M(79{1$cf zFC|BvH~d9BVlFstFmh82R@8w>_rvGUpXcOgu$>Uxzn?Z(G1g!|js{`j+_L?+slTdz zgXn>tW~>eW$gW+qDMxH>2S0xNo;~2zn@6(S3L7zw@((I1!n|R}j(m7@8}@7)+snOO z3h+6+%t>G!V?sMo>miEa71!KcOLKE}75Co?({2WQx(ZO-u)KZIZ$Vab;c~JFT=IOq zy(@k%d=1*RN5@O39@eCBDr|#z@?xdaTvr=LFSK~n5ohgcXVXdD$2V{K)XI$>fG2Pg+`>K&lM=nWo&)t@zt zX2g+=i#WSCF$(=SdjM~lHUjryqP$3XtK4#?c_tCkwucWnP$^4Fnk>Trwir zizj)qj9oa`ocVh6@ha_!1CVX6q#!eG&e&;9Q-iZ?)0Le&K$rv^r2E(UJg!BkT zs{R-smv(5&fpNi;a>fmC07mr$geM2E#|U!b@#M2GG*R}L^hIqer4Ar2& z9z5;~m=dWjJ-oGZi)ovO;9uK89{&-y2fFG@nycUpGlW+EH_e`PBbqv5e0;!@f@hgzdp1PQu0ASGIVhPKes(xuU_ z-L^<$GSbrce(vd1^zkWEshsW_cJZua9V5~4_XJ@=RIcdHo8f-#$PVr$p z7|yZS4WTnOA+eHz0BLas{h^Qw8w9o=vG!Py5C6Uc6FPE9dCJ|cxo}dlqUxt72xgWFJm+3c1s27 zJ|u4grO zMe_@Ns+|^w$pQi#zb^1E(kYk-R&Ra8U%{ZRcIwordQUyaRK8@pGh}An6mlj_BLAIw z$}?p=bf4}8S=C&e;;?Bj@Ddd|0U>(-r8XpB$bEG(=^KKIVFeT`?vutCL4*-I1q4U< zf1m>G|NgxI*&WKy;wM$s@Bjlq2>~PackYCVYBy4%xjFYZFYCw}Y?#00n7g;^aU?qk z^f*-Dj)@g!O{69h0|QF7505*e#$^PQ zkWwtF`UY|~49=`k%V%xBe(%nmi)glE${=C( z1)o`il z`*Z`V#~hzcy@DkNymv^SlL6*;Jln3D@ua+P2#F{AoXB_tL-fxii6yw!=bDa_=Fhh|4JqcPiwvPOil_>shbt=2dMq9O)jT&NqTAxd) z3t&BvPNzTe)b@h;vv*rLJ(Nb270fBqSx?B^sm;GEBj)(Z(Be$Dq=#YiHE1$XpyEu% zD$WTR{ml&>I*t9L`q<9JP0l5oFJwSu)jAc~&|p2*m6b3Nf{ZX)Cw6OJ5^;JhQx zz@a;ud$VPG%Bh6^Eme@{q5MGIoPoL$QQg`at02F6D-F%BU%yZpG7LnZ)#ITz@hmK>dg%Dc9`y8BPsNfuCzLTj=QW zUDHiI`kdrF-dlMq1mx~d^%iAgD;~QgZ!|w{)ib_6wV>?o9u|C@hUSttC;w=AqR#%} z;#20~W#;5reij-!bkKc-v3h)UZPnrC>Kh6wuyR>&OcK|(*h{Oxf{Ci>Vj&?%++4Fp z4huAJ@b4OX(WJ4B(tV!X&aub6Oq=iBQ`7vCn_)C2B|f^ooQh^R{zmH;d#!q;HIl=R z2g$!x5n+Q32=-V(13GGeOfmA3EWfZYYTur(#dZTo{YFRCoP~%gRZ$3iK-ATK7$WEE zyNbF=Gg-D`Z^SUl3T*R3HlGp@@3P7nn|2_zLWeCoOwI;rb$onLHDaIfr$#&hbnlQi z;1zoscqP8Z7Z^=fb{w+WEf|cW#HD@aOo}`Q28S#Cy%bXNu>|2e*KK<06bD@}x<;sR zB5I<=b#o;9kC2c{iQu^1 zO(0W1i^=^)iRk#arPW4L(~hn;bs;m-X(K7_+?iTK4OUG&TUoI1Qf8Kf(o*nX_U+wU zkd`Vvj{=1n)0DoVp$}Usc#}Nvaep!XIoUsWf5cs zxMH66#jAIy4GGLuWSi_Y!F06$GX-==MhX4m6drh#1@ybGPnUhkc(Zq zOmiLO>DWhXa?R@tbn_^I;lrSM$rw=c>Q18ShU+PwE~d@n71$UiQ_6*X>N(+0S+y%rOP%MNT=;AUC~qi1C2(sU40^ zF5^a`1N2%CZtFgt>LZi%(D9^iW#p#s|8|s|lKbc`DNoCFzaK*bkCQF!f*AxZ&hiQh z;%yIjn&@DpBrR*GO2n)0mhHkzOB_7pLk$CK-ZuizHu3QA_BV3>_@P%M#gM%+u>D+( zFx{DXdn)q$LIv-mm)B@BGxHu?&|9bC?=&olr6jkUx4$R>DJA80gMjyIYkK_i$pKRf zUyTaMr97`RsK}E9jI#a?ut67_=O9u~Pm?G6S<+EJ5 z7I~+m^j4ZGLK5Wj>*&FZcNS zWAsxCy^T%ZMgELI3;m(|>f!CCO;IQ`U-i{z*h0IsY^Ma0maV;l`j(80hY@F0b+t`G zu5C~gk6PKu7)ZEDAK*! z$tnZ+G@6+1BRXzwv&is3Uw!$)A8Mhuy}bd*S3S&7I8VS0UtLS<&(C|#B))Z<|4U&m zEX-;!v1kxrx3g-K(DKl27fj~A@sble0e(MgsDyEt5%clDXwk{lKFJk{`66&iScMy$ zzL!v10X$t1hJohb6&bYP42*-bC5kk@`*`C!@rlq8OKg9Lm^*G>cZ^O!wd9iY0}O#c z(i^P!7rd#;$+;cYCrD3i?5NF0&!552c>_)lq3G$_Kl?Q3YJ9K}l?9L`Y@c~uYfhyj zM~(niK`t&F|B=^7wGlfD@gH5zo@~1iFm;GpYv)deDwqM| zFmQZ%RtmSZy>3hv&1NH}hkvT0!wl;^2|DnYy;!EV8l}U0&}?w*0)Chv%V{%G_i`wxNI+ z)Iv~vJ$OJmcpIT ztky`d4{6>>S1XXg8Y_3LyIkO_q2~4r=`sc~RxU0F4`o)ih&kZaNA8NI<7aCm6T<3<`Jf@Vb;IrUZ8jr^T9|=b0opt3~>K~M@R9iEx%d! zA>ey?E#d&D=x9gYFC#6Dkr-2TrnV@hb#$WoorzJ2Hv$8}#VnAe&JoWGNDDhPaI_VR zr#?g1vB)oLht4GIJ6Lw?K!lTn8B-2=PBTAh=L{9~39?-NnYYlccfoMcqg~-HknDI2 zAVI)G&mZ zb@}GO__AgIwP@j!N7!Y2e3speHxB+Z&nApnqFP?8i~g zFaSd*H8o?0_UNMgfo;&=Yp{Wk4oOK##rc412aBI#!04r=HbVF3fj;?Cr4;~u$l0@m zW)b?4__o3Q?{DAU>KQ9VLV5zs5T!NRA;9vz?=)6d-+Z8_X=2U>!DjE}&>7dQ?BTEE znRk(0dA#qemGPh=Yn!v5cY{}^pz$g6+k-HgOVTkhdcry9wQk(xJhD?vtZpr z-x(exyfcGfo*Ni^sD1rF#_0Ku$jFPXS+`E|$7#>=d>G>EeIC*vufVc>IpK3j_>y3< zu@TkHXBYYT!Y6aApP#QjI%6oOpsMRN#^|$XPredc74E4FvZZV?cDnk^$en(;K(q#Ln!Tm z^o@>UOlx)qw{0VfAUDBiZ2zXvs`Z+1_(!GN{>`z%_cyoG4VKzW5Ecj#2h2JFfd96Q z(_&B!>ei6V8XmKdNur_gA z0N?->ZGL{=>CtcT#lpTS@PtVAO#Hr?`Fp#5K0J zdtJO}Ibwu9Oxw;DRMRN@(cpQ&T(6UD&{4(i_S5o*D)}aGEa3z7uwU1S@%BdKWQ+$W z%B|On8cvvy*eXdg7-CAs< zS#x=Wj`aNb%jfFLTKB?FioQsnnTcOXZ=Iu}zFD`BUPs1%)T%X0?A9(8>X&QJ^CRwE z=-zPUI^`iZUKIKJw9fWcj+QI%r}z!<%WmB4y>m21*BZ!f%pg4jcW`cQook55+!0Qp zIK7Y$svv}#b&uxN5zJ?@jTe^=-oMXMDxuI4B@aA!jyqyTIilsxl@=aQDfjQUgB)N~ zIBnU1=dmPwV}V``X3d@0cSFPl?h2DoxCCo;x9r7>%))$C9{x+=gCW%BaR|R?6eTBvxBkmA2Mw;%!ttVFR?TX>{Pmc&#xnO) zhSUDdqagh%ffwr4`b&P5Gk<7}>Q1ejt=GNUaO?8r%dI`89=u^cHSX^A6mF_Kd$W>*&&lEr{qFu3o7b(06)a z23X53y#FCzNM{@RR)x>p20IN9Qjz7ps+d<#`*-)b;S5e$?Z4-nG_`_js$FG55tS(CjeHH^lKZYhGg{;iKjpU}< z^7aZ@9iy(!?GR$f5-DXWojSc~boM6yL~gEr`eQ@Av(9-s^}@n@f;rMhj9CNaG8uUS5`RQi%1xW_$=RelbAaWN;Ov038Wv5&n6#Lf;($Mw(QD1x_x=0Z zATax$^+(PuufatDjsysCpbEp5nBc{nNZp3n5gtWb&=iHnTmwo}YXoC}hXnh%JTuL4 zP$jMZZQX>vbZhH_3T!54I7Z+GvO#Bu(gH(b>Cgt;vEv}-0PNlFP_q3Cej>nS(_gRg z*)X@~+S~7+z(oTu-^2e6pLdja^v4#^$_qMzeavi9_EN~}b z19%==W5Sgx^Ai$!T;cwK87ys!k^TpSg)!>|$R;0sq0OBfaZ{iyr}#cKG(_CKEhsE( zQ{NF162e1wqLl{DCWU9rjoC#3ilaEN866&GW@Rn04FJq<=rfKNy6h$|GrqjF0yd^ab{+%xy z%*CmhfTx8Z6Qxey(eV!TlK!elkwy88-9l5!t&fA~xDs7fd|=u7@r>Z$%?`Dnlug7B z9Xca7IZoM$PP(aSdG$Ker)yn^lj9!xJ%N~>$M_dMhPnQfwsHt?->n-( zRepPS!otGhPzXlPp!=FCQS;`_wLvC3Dm$+8XRqy5pIYoaAe&^@%>uU4NKjPC(r$?z zBse)6-R3+_(wpEDbLH8+r{KaKLBYO(>k)Fwf7TP^*j2(?UcA|_o9}gCVf^*&UHK*c zBe_jFYima`G_%v08N9uZ@x5z%YE)Hu_M{%Yu*LgFO09x9{S%`mvGGi7(()JcvtC15 zfeIuoE#Bmyd3j)^zr$&zb*i4qr;Zk)`nf4&%T=d6B&|fJ7i;AHa7ZjEks_;wJKY?A zndDeR{8^PFr#RcMm}73HS*Bf(Ch2tlj+%Yle*Q#Q&eu0jGPs7cwLM%swwZH2{W7=<>F;tH9za&?A}kHWPu1E-q(Y zt9UT=yhEk|mcNn=JN299W>`GL)5ssecuZn6b5oNmdfV95FJRwx1q@3$pE*8IdBns# z(Lhy5A;5eD98CE820#*RShS{>P-)ZbI!rEaZ$ApHRshm3v0oVMyRbJ>wa0sC4>}IO zw;XJ3cT0IXqWOt$VaEKmR(~8PwRx+Hf9qYFDr4)zxJAuq6=CYRh11|^;b$j(zt1jX z3vRf|!NGwtb3aCRfIJUJR9_<_<}1kmptb<>8dWq>AWF)hzsjJghodK8h8WMDDbF$d z?Zs@`iD-ha!U3Kd)I)T^IH6x=IP`*Bp4IILh#3oSuu31$V`n`Qt-Eywu1us>b_0~~ z)w*WQRy_37h}{4K9;K$@lYxQgiN=6|Q%N=gP0JjqHX^s_wSoV8{(v`n*`3n*XbK3M zl@$ZkgE-+6=Ow4j)fGfPc> zg7eh3NO9#uL;E5&9(L5QCe1kJzGP34F5*hQBPV1WbBZ?_!>FpA>h}FdV~L9;d-Y(- zI)hV^C>DjnJ zeX_Oq*g~kzp`{Pzd>z@;SF(1_^d{)<%Q~B{6($->4aF*g;B?`e4I9+I<14*MoF(BoII3Kho=qzjOU-gCBe+)6rjjQP+8 zm2k_S8YBY57vYHt`B5Ldv!k5p%$YB36hRwh*_jS-?W0Wg4;**=_F|)yl!OFHUY^vJ z^Ln6$;q_r>=S!FRF!*sC1NeCMRt&TL=({rKeyjS)N;J!!FwWx-({KLzddQWhxR`^E zQ*bL885NcM;snWF@co+&6ckf)Im}nPy7x>^^YLd%7#SS*J_pRdk<=5^ZRURBhu|V>NjiLlmSK~M%DMA7Q8Dxq zQg1tVoj4IYNf-R(DeEQaZ{>!EmX`Xfp9iqF=fYQ8Sy@$!GH7EkI-)2sjf|?J+dk($ zYE2KS361)pW#^eU6PCTcl}GdB@1OJzAv^|BL9QV;c9itZx-1Iko_<|_@3|M~Ir$|@ z$+E-Uto|zxbsxtErXe5ry=tg2HvFoE9<{K`K#R6GXBc!eC%V6t-8^JvX?1-IQ{RuY z347I4y;G;|Or0ipAT~A%3JQ99^yNCIQGUIConoI?BPkker_Fz^8nih8Uj&N|`dnbb z*o&AaIWeBZxd}~r$QeM~3IX4{q2WBc8X5S$C<#HmUxH+p%x}Kc5N+XKQ)_$Zmn(@h z%DOfR9W!iyVyF}-_dg&)0Kwg%i|L+$hB(rh|D;bj=T5fPRUt_zo4C0ra!ouwEQ}_i z#!6ESZ*tDTLF&vK@-v80`4439){kc@s2+jh3W`m%aiK{kWIm99-6klDN}^|QJ3u&wv87yRECs=3I7}lL z`KoYBj?12pT={}`UykevO=@+IPH(m^Tc)O8RjDfiV9zr1-cV2{T6+HLXhiyFvP?qNiVgyXQ%G?59*wn#Cf!_n z=BL0$6R-6lK=jGFRKLdu3x&Z0Su>lL$DCR>x6yQg5m51|@HVe+Bxd6|-Wz{bv}Q=+ zq)~Bx z9&hi8p4$CGxt5!mPG_KU+n%g-(lh6p0xPt$t!g$r`FUG^5B=(d*?7lQi_2sL9@~=n zWbSje{FN})>B%bFuZ$)p2gTlpFnnpXqm>Zn&eyO9zzE&2Ear4= zW!A(r08B9N(226vjIDZO9&=-qgue!xRa#Dtkb=W4(P}nZX7da;JkDOBnMJe}(w zKYmzam<$|jQ9re~C$wHLIN_9c(J+b40B8T0RWbYpp|HhvR3J;Y zpOz%pix#1D(7bCTh#@*KQgN`h{()%)sC!yt*O#)l6SQa}qYgxnn8iZeTQU8&;WIfD z^fPWD6^r!cGPSGAwWh~Y)C9G9YPBN!&6%r(KD3JTJevutvg0rP9erNYJ}I+9O1Jit z+R>BV-*)KJT@7KVlj1lWazfX8^-x>7h6_gesLJ@1^cut*<{@t=a+wRZXjY2gu;Vf3 ze4G#;l+`XcJeEzbqj%rVZu5%&Nh&)wIy(OT+lILuoMc^Hw!M{)jt!VPr|1jlKWi=* z*U@#E;{zdHGfrJqSHAu59Z837mNRF7SFf)Vl9C5G6W3IAAv%M%C~-|r=1HJ8B6#$u z@u8VZ$PDqT{`~PHe-koL`28C-q4(WLbS!IY@dXZqbC;t;zD#aG)M z;-c-cON875_1bwWr|fG^N6>zZ4|}-*es>#Bty*5o^UI3OT9H+d^Zqb-gQ1@Jrzq5=XNis!^iABK#--dPJrSvbZ$0LRxj2q3EiFNu0aVbNonAOzfW6hk<%R=Tg8F6GMYM4m znL&;8=XdX)O%xP_y$UP`q&&w#8~jhcX3C5G2aRqhqfnM7+I<;71!P@+5ak1yl_ejG zoqN}@3E^b`Y5kEggQ)xWccT|IIGEmFDQy0dst>YeZJlKxtgCl@wMC%DC@}h@ylhQ# zO#l1j4o$F+4Hg#%LRA)j$24Lt61v~mAuoHz5 z(7mxoWh_UI6hUT*d*g+kJ&x=jWxGj#ui-g+`-$ExkIcZ&#)uz@vL# zVSt>FnOfdU1y0V0L~+VXdg!T)W~#Kh+Su@J;U}7?a9On*C1@riFKzZ%q$XyfF@$sq z0ZxM#FoK(>CnnTj^Z`cH!Pe%|NP0ZFkD&U)mIA|zF;(MUVq&Ijyl`}4;z(a#{)O(c z0H`UlVu62Sek~B$|Z zI+o~ps-NeH|M+#OSd3*9Kw2EzB@iP1w zW1|^@6#-kIsY>{dq$e1>FAc5GBS}VLZ=>Y>g*hfQ143w~K}Ugoa+;|%7RZ>AvNC?_ zuSj#oO#VIohecVLDKxCMZz;GQT_Ks|UwK*aB6l;}rU$PlermggIBM!f(CdgCN_ilY zsS=4;Xemc6f{mw$Vu2M0HO zH8no<%47eRiq^I^duH6lB%JR}cMCSr5R`v04!9#_gDGmULm+14GssZ0bvqTz0=D-!j zvqQEI(LV3NgZYgdA~MY|#73~Ugnt0o`74Ogn1*J7nxpPWQ&R^xu9&Xa^5x4#{5?A6 z5FG*8_z9goXoqb&od|qRgSWe8ip8W_>ce|LLImOo*Mv`{#uYxIw42GVfrDQLIL?~A6MeY+*J^=x^(N6*r zWuV^FUh;26kVvmm!CdzCu6r&q7%NcM8({e0XzJR!@8H6(x)O(20RuiJVZF-b4A*|e z!Kv?RhKA{}u}$w3Pqchumysd9Zq+~P_Z)wlUR5Me-$#ec7U^+> zV4^Vo6toK$vn{ldNTRlEflB%u=TdG;Vd2b)GB2;%LuCKmK#$Q1y00A?1uyU4HQ%f~ z8QW2uc(yqT&QS#lhIMN9N25_v1DQ9Q`j#KpX^l&TR?s)0#rtUlJW3}Pmjrwx4)>=D)Oz z;}iP&0ljgtzXya(Q_BP*MS3Di#io~ecHAjAG`;+8fHqmnPj(k;uSKefoukHv*T2vG zpeG|q=Gi>HzcBYQ*><;NjJrE=^L&rv=7pU;`Db0+sY`JSQ`1Cu+S7WEV1l z2oMs+O9=`gGCwpa^Xp+eN6eb7ug9!wytc-7nn4;{bAjcZtEGTJPCk@wv$JmQ?vBrz z9psP}Ag^%4h))RrY9%+inbDF+A_w5rhu{vh4+cs|J@9SAU!NUlSMqS6zIpb|4YW-* zL*Vr~TvoNYL{k7XyFsyapmSFwup*KL*$y5`PZj4|rA>wYZK z2`BG!6boL>eOgv#66=Fr09ZvRbIe^_3hZBGWvP|8z)Zntv=L{W(38iUHx*LAm57X_ z4SEbqeY3AB%Miq+tbs=#Mn?R&en2 z{5+15`-jhkfQH=e@mh`$@)}1$RhF{M$6f}82G++c?h3f9zjRKpM*ID`{O$1%;|$j1 z&V(O>gCGE$6pnvpuEQ#hTSi>ApS0jME%^dV+r~v%OH1P@ z%@;e%8B5!MjTB$PSVjCLmsgtFEt-C7N;Qaa)X`O@krOMJkutzoHzu4^s17)xs&@4*=hTg7pY!>V+ zFc?Jtb=2nIkZrrV5uRQPc>%vet4GiiLIXAK{(Xp?Sa$B5trN&2=Fuv~z_bbFCvuv> zp`r7T(Dqb(t*`%uys2t!2B-NN9mXQRXLSY{6U+cuFt)a2Y@eH&vi11}GBDCo9EABY zj$cdbyStN|7%^1(_lgHwgcoWg3`;51L1GNdYttq>dwZk=sL%;#eT1ZI235?yU;z<^ z7IAU8#zjAYMeTb8xL+6!RFJ};H)oqp!3Bw<30&Tw-UPS@W+MM*8r))G@$?A)9)Lx zQ$JWRayR2{{r;}6&*F4N4tf7PzlB8V4m^F*#l`&>i&?p{VV;f+ubqSLpLG#G2_cJ< zva;4zZ#{xZQ^Q}%X&*2q-tO^@@SI4~&$b;h7>~lf7Rp=R!GYPHH@xm$)TeY3? z&}a=gTG*F*iVp_>K|R8$SWrMqeG^&d?gxlt(lW3$0j=>X?j5FoK*&v~&GD6~iHWNj zlk_+AS9*QMp2B@XjDzE$&{u(2H5gaG8mX?g*Mc`XY}b(tv~FP}P!SlYtg89}Isotn zq~MVW&eBbVNRR=dYY}4+$(&(Gg9;oS8Fij0Yzi0~!dh$q{$b)GB6^d$9dlQ4T!)3L zBZLc|hWDK+57#5;guqP4(KB=DC1D}-O1{7dt8gXx&)N_G74s7NRy0LH$&rzf>Af@% z2H1oSI;6;mhzJed(D3jJ6=P@61V;Jz2S(5pSeA;I<2T!=!cGk3eA@ELN1PBW;G?0- zO_(}@poaJ8c>8O7yrZ`Cu+LmWPngi2CyfcW6dytHv9REX?4Ae=At5u1i?E=E8^Yq^ zB6!1Q5Jh5RUAnY{)z~|J0i}m&R+hF@ZQO(X^Ytby3rI5X6l^TEY9?>EsQ`V?@4WP# z-V-l|OuTJa!)oz4aHC9F8cJWT|H~?_c(WX>E-ls*5#1|O@iz}AY0@+4Dv~QHLQsf& zT;FhKvew(c#@UAEsqZ50e7knJm~oM$ccrm@ACYvu!6?La;DF@i`#Cw!b15E!2;DbJPx4RQdD$(u?DmP0{(Nq zr?3w*w32i6_yKPKY8x9H3;xjANzh*5b)xw6{52o8+;qw;c5%q-Fo06ZF1QP!7V=%a&6^c%8Q$FAbc*jXoATafOU zfu_N^qV7GM<(*$$A;Uv&3ZuRWH^%F?kOida*rC;(8trs$u0`BoP=3@(0lh9%6t*Cr z;NhZWnO{^iFntMDkAMp^GTy&>b>)`lcn2*rvjm*$lGFVF+MFyFK_;`Hk_Hu+~7@!s=S` zlck+r_5(VO4S}K+@467i!WPkUe56Mv+a|AqY*?h+brz)rdia1 z(c8PR*si5YZjX#ws*0Q04tb{Zr%#>i>^glMauMYrPsHKC#K`z_a4_@2B>Z^b^^bw< zr}#SJ(2@~c>fl?qMQ7yv`Ji!bC>bE-D8iBhT7e?`e+n{336`4I8TTKpA7Uxtvr_Q!^pvbLb#DF-M#gpxiW5}O=V zY(C^Yyps}(WjJ1l#HRNJ(Gm8W^95 zjC7wL{e8;H7@Tiy994F7zlY>R9GMdn|HdIvRq;2vL*p8>v?2kr6>Eo|8Xr%-9FibS z5(oN@FbZX4vdtd@;dm^M!lhInsu?_FL2~28zPAim2jFrbsr(8W5!MlG0`ZXhQb#4l zacphG7*fFNYoOxeaK@+>I6k1K)x7ep^2;=W!G8J>JXl+M`_Bo7Qq$|P1WrDX_8$Ji z>G=$Wz%3AMS207*_9IUEmoNb$?3xO#H{Yvy5q8(#GIby>CI(3!oRsDlNr)7>x^Bn~ zKxT8Um^XlsAwhzMuM_>5uaoK-V_d+V1?7v`)LkHw!bN~6)ptdjX zj}XzN#GM0tHCbLoV35TSR0|sy@`#AEfbIeJDGg(BMj=#I6` zoZ{F)h-H|W!6KcPy>&XNJJr6$IZ8AIf!JC=|LSL;vigP56~D9_|MD!Jm6nSA73MrE zEQEpB=oT|4MfbVA15Xq)!X@|7(Q%fB==6(ap8EoBq2JypbtzQ+*6Wzh5ji@%AQ z3~?4ZU)6M-(lA(wgdW8M7o(OHlkx`RTKWN20D+I-6w%3SK@dkh3ZeX)O+~_1@Y>SJ zbO#{>Y}Tx;7Tm~q6hRDQ_I!q_76sULYU&kua(4=Vtu6p3Ew~v1KE42Y38wP|tF}IV zA@ui&OG-&0D?!N%z%=|Rd??q@*EP&B;*9_J&ngDKf~{Usm;;Sm?}1!^dF<7XwY8j& z8l7xsKMw)gN)ABQ3Y{__ExF=Au?KbnsgEm-)hP>~Ju^f|fHB4|*i`_l!c3lNxI1F3 zNrqin0p@-rmArW2T~zLr&JR>HQ6r;EUtOzU#YXG!_*2~^RZO@P2(p#r1t#SG=I`@2 z(Ka`K016abU+{_xbyZSQeH^sWonm;{f|t)@bzqG+J2x=mfNQx&FLrnFMJS|^ms=)% zKUg20XNv=44W$sKVm^7ohxXIY`g`~jTv=XcaVN)F-(YFkBqwAtA|*+FbCgVe)@Wra zG6SAh85#A{?A(uSZIsPcs&q)CE1tUA$DoyV{&H!aKQ=z~7&mDLt)0l-60*Kb;K$|x zN$&2$kCSbuEOWETu6Q@yAYZ_4KAN&u6F_QWO#P{4Fj}vO?hYudS2qAW)+ zcLDH?e}<7TIEPxleAxk!cx)^d34T==m!KddigZ+a^YcIia&mLUL`1BmAQuJ4A7?wX zVH}Ta*q0Fb%b!1g5)Ol?q0!O1kOcy0Z&E)1`(>PAh%8Yx1OAXBAP@dcxHmdFg4l|{ zP*G6%S)hBk)|oaf^EI;|1XN$mI0hgtw4yn3o`y zBJOZ{`rfhqA1*&UUard@D>%T%7z%`4ZG#hzTb>;|s^sR@)cBnMF-T=k5Mq3M9${U53v%a{cDQ*{#EJqL@WQX+i=6GP z#7P8WJiaA@8HjtHoZR5E1&Zwj950Y$XT9VuS2Cg`$#o6}eC)VOO&sbxpHB2cJTaE14i{vb5}*oUFp|F4<%) zMdH|~@F`K{A*`3tCy-kmKLUF(SUTbk?rbDXnh%&uV=@NLX8Z|~pXghq7@q}NHdxhS z{(Ue7zq~wiZhint*{4PYgqaH}GxR98QB$9_Fav5W2lZ-ohM^6%As)-n(2${-*>8B- zpve6SPbI)sA3hAf-7e?otMw3>=w(#L$St0>d_j~$D60gbsYuVvyo6sAu*wjOJUJc# z&;*gy2DKQDKOSQKmpu+G2<0?Y@I8PMD zi5jISpF!Hy`(6EIW$BqK*Hh`D`tTF#e*;^+4j(-pAeJXEO2H2Vwun~V0$C`eY@HHN z=*}C9;!Zvn-pvC0v+>Z^IaO#Q@cJrXZFNwfl*xLTs>vxR~Q*0 zO%ANC{#{=bN0o4Z<`%a+Y^(_i+^%w6nPf}R6!wbj#r?M2^f1=i-sH;Vz$L%jEgP_HJI@=H-j0r9U2E^Sy)j~{rA8yNBBZ&};WbM7QL ziS%#)ls`39RhYm3AIjc55UX}=8^4?9WG+IPLgu*$Ns=Kc^O($$c}he{$dqK3Awy=F zDnlr9lBr0Dl9`Z@3cq9Z?7iP_zrTOJZ~b9E&$H`xueGl0yw3ADj`KK8o`L2O5fPCy zwXk^nX)KHVYL9ULvJ3$NYmY)J{eM~*d(*4`H}ZY zEjnEvq4JZJ{Y8tIx~@1bH}N7RAA#u>Kf6H?hj{a=2yS2!-oMz~Z70D&Kk=$x>{m z-xu)Zu*rc-#sk@u7-6eU>;NN=2{vKt=|rSyDB_?ta{B)DEZ${)i&X@HFk@sGR2Y*C zGzcl^Hh|O1KxeA%H9s^bqx^Br|K2+(mr~Q66o4J;8byhKFs}bV(F_#8yG^JKvvPA; znQ`(VX^FDJa8XD|C-jXxZXN+egA@|NNnASbL}2-sMFcKbHS<-#)udksh;`z_%OahGY1GmqKT54x!;=w!B&E{mZz`QWEo`xO zbxmUR_u!9-$4$eVWQdu3|IiT_&x@!SpP2Zz>Xo6cuA&?WD&lbKDM-R$@GDQ|&``NO z$>&VO{rhOKBx>A0e>_3i0~uNQ{o921n1ZV6^1=dkHR17yB;h&l*k^W?IA>J9IIV$r z!N)ry076e--6gOrgJofU&hVXw4-L?p>Ea?1Ustv;DR=~cUpqN5dELS(_H zD6-A;pPj8%<*QcSMs}es5g;b%q2je`Wn9ylcO{Wx7ERXo0OGpsh=7RcBAtCkd1$>1;v)lI2 z!K+9Jg*yHkq#*VNblU)A0^dPizLgm^pJ3Q;K6@tCbNWOmuM;zFq#pM)8dH=pb%Auo2zyGLQZ|sR~57UK!2~e|4N>zO5S73v=jUwo`Id>?1@-Hh z(1R{o}4H8actQ}Ma_%jDYZT9z!;5(6I;(<&Xz1b2rpbFhDa2cZ{kbT!i zj~~DFbTcJ=9w*=9jOg$GJb*{(Y;^3{t2LCy3o6CpCeFfV)9Z#ioZ7-4A6fZ%uYm9K z-J>MQJqlv7XVlbA?xJaLlkU1c+cB1O@!9m`Mv|)5$&)V!D%>uv2cBlUCdsID{J6L{ zknKVASVi&;xH0E`s`6+YFejrz4ALn`1j=}ybY0(itUjuH`{vuB3HZRd-Rhd14<(j|gL?`ts*zh+gK%9H zAD;XC^~rJ2+oh{@5!K?C_F3SkTvNf5E_Mga|FLRtQ<;|J0&Ttis__w6T- z9(}>_!0uC8o!kYk**3A( zFTsh4X$5UAk)-z4Lj&6x&Ru41jXQnzY>Dxv7YlodHN6ZR8ZBHp9|W+iu;TC&&RB4D z4M1RmS1N4v6j(3sLfmUOSVU?s2WNm1e;$p)I114;PS}$lbIOR1r|)q&ImRBY0D0{X zOv^=|4tia{M6ui=!yVV8BqSt2aD*clVgbqJekUYU$kB_y5O2Mu)c&%ru`vlZ3rZYz zcQB&BzqrcC_!Jil^|+LVJrzE0Q=XC4?HkxSN~NNlxYCPQN-FXH^QU?^Sj_IiRi62k zub&;H--_CvRx-RBDBc1|1xcOW3V zecRN`Y!8#vANaa?U}i1Qz~}i>RTdE!ZOR+oJ!rS2#z&Pu{qA`8ZaI_1pD8{r&ch50 zj?RB7BvNyZepK2dvkl~-vwk#h$8;~^)i$!upY!?{Y27Y|{L#@-utlP1h;W|P32H>A zw#aJvNEIezYz?V_0(AQOOe^>Tm?~mN`Av=4Qn3 z0|Yf%Ea9nL&b zN!6F@G3PBhuEdB*HtWadmv!=PN=jMz`LPCvA8*Hp&AD@NjgP9_z56JW<8E+TE_Y}9 zq40n^yUW%sYDg$N$`wgIG{hp-)j9BDRdn?S<%{3ETeheH`@+%H&IM~2)H#3MVUq6M ztD%7iAwc1;qWmTNLl8zGOloc2!^60tJO=7F!a58K4$XD!?CjWDbIZ$+eO3Z%=}AB7 z2DO4c?i>`$5}24NWa-$3M%QObQMNG~5-YmBib{g&#^--)0sc~0P!jqA$L}$`eiaZn z&VGH`EputG$MN;`g&T3YI+rvW=%|lsj!#YH*tJI`Tuv2XV^cR8{3+w%K}NONRqcEuiOpI$jtnm((q3G0$20LxXMb{9sdrLzv(l@wSn|;>xBIH=Bo8X&D>7<#T5GhOcN$5zaJcA5;%kJ>Er5v2Z`4X ztqq(!b0IW9FV@suMzr4lBh5hhA<|PS<9|^@qZAnxgdICJuL}zF7Ni*KYn-O0RyRDS zQos)T$Rt%s#`zUf8|8)u@4=CIg+qr-hO1}4Lwv9=NmW-@KLKd4c_} z?&(2-vg5HGo4=0ACnkQKI15J3j)-=ouq}8x2aAe8rbtvL|Cz|agbqj;_m&G2Pv)EzngY>I{uyI);W0e><;!<& zvWGAp{qlvVT&Q*?nMxybLG}P>8lm(Y)K3N9lY^RDTH=K)y4F{Xr0wi_v<$DEJ=6{# zB@OkC4>6lJzFK~a4<|i;bXTZITFmym*NK0HzVV5(`T6d(TS*2R5c;e*B1^ob^K?(c z03(ovyp2i0Aa*@$iM z^d8ZAT1XUes53|oz*7ZvLZ4y$%i&}2>Vx2VW@_p;s5<)n`|S;g zjUe-kJwna#`=CQZyja%LD0fMZZ^!BmY)B4*zT|l98|9tblaFdyzUR`dPIPuD%?99DQvN>o^+F)v%Zx9)NBAFe-Im*piHPC=ZC-5(ht2!{N?2dP$beu(U#rMNo0x zt5Ze^R72C#f52z9!p+!V3EQtDyekA{Gys4#++ClUkUIquN2F>CKYmDJHa8J={^o$r zERM(6*j68!1&6X{!G15(dmTp{FYoO(=MBj%#7#4G*Ub;OHGfK!m9=a?gsPb2u8HCc zG$A}LK&a#V!s^83;2=N_4j@pDkn9onURa7a#49*N3d@013NIRY7;YZ^P!MD#@Z+9$ zP+|lkTJD-$Tu3uADd)iq9YLOgX_FV)gyR^h8Y7>K_8+?6_2yqlUQ(*8B z4?c%vpzm=U5kvZ|`xMPt*0j`9p`l-gPu2QIJU((vA_7_ujg2HpJ>;ksk@sa6M%C1* zKwvO=$sIpVoB}my$+?eZ*WDZ5Y5~kE9VB~cDV*czOWonmpx?8r-2pTNDi5fk;Ke?J zuY12`1Zu`O+&+#%5OgB^4>vg*AVI@~Ib`9u@xXw9rj{0j4Zs*oxbbJtmH{pxGoq0a zLOSR3O_4Vm;{;}r_I!F~$D}1vi8YU$jlhHg2@NFT0KyG0Ags26%I~j1T%D4Gh6zKU zz5(k*gFO^BkjoA9_vgc!k5Fmg2fQupD(8V^%3~0n%%StDVxnHj{{CmC7U9DNXHx)- zEtm^}MT9_x%AZK6(7p`ERJ<>YD>S`&^#wpNX=!QZ?7TdTnzK+;+$r%3L@-Q+^^QlQ zbVb674qJr&*@22@={w_XHFb0jP*Gv#s1Ah7AOyaBTf@B3xs^XrTT{}Dt$%O7?(PnU zNP;Ai_Le$&)EcTzr6_JJjn&WoOaR1)0}i(p7aNNaYIR**5i^w&=OOPA)g!o(R4G2y zHfRH+R)2KC&>R_c{uSb_kKg~ku>S4se#UcVX2{sHzXc=C$|{k@zumLFeNLGdcGQ-b zMfL3Q>hI>h_^DgqYqw^pzkU^(TgDRqsXRYFGyq_j_6N21Utnn$H|4QGJSr)PXyEX> zbB8Dy&@+k+f=5LUnE(vqfyqA4-|Mppsu9%S;04V=A-TIhSLb@)(cu6?5YHNTuBobq zO$nl6A|-}PLvDuR3grM$?*uA{d>}@s`ZakJ1CL^rMIq8bYUPCj6{rIQXee(akUC*S z;jo2;o~~{jRMh|>OH0k{CgsBzQNoI1FJNjL$O$Bn1DND`V&EUSMP4-PUsF9LMa2Ni z|0`ufHQM8VAY!XC(}~&YgGq+-F$NeYjdf<0nkrFe+i4mY%uGzIK=^|rItoIGyJ#sj z71V(q253mJZ~JuCiO%hf4Gmn8ui^g*eiW_Mh;x{u0L!&fbiiUxh5_nU4-aD8#2L)F zgY@RmrAac)#U$D%>Xio!f{%k@d_SlkN)k-ne=z{~R|>@s4X)^&tI06OK(y;YAa^uu`ZsP(HTbgx^&i z`iah*8N`G&@F}1Ppt+o!gj+_L^biEj5DVoW-GXoHu8X8~4)n6RhK7TN44QH99-&gJ zs#?S5`2?{R`hQUGGb41sVj%Ij3)j>}OEWVOuV2pT7trMr1LViZNL3CtHQ4t+Kqd{A z-#OjnIq`)0|53$&L#3pHk!WYaBknANWAan=lwansHr}ywC*Z#)B_*a|$8mJxc#=l; z3G_}xVtcDcFuARIASi#ZQj@QP{QORPd7b#Zk6lo(s5d2s-&nS5C)4n?YuV^2COT`t zfjDXtg{jPAmgtKYDA-ufdrE>TBqvwbSJu^KrC1$!*wGd7W3h~vij=&mYqXr?bL9Oq zKEFGis?r^u>CQ{sGapZPWjGj6l4Q1}rl*fU7Bn=(55>{@*YK1?MAisu1W9LZVL=&= z4FuQ?$1o@-lv}Q@G=Xx+H@@b3`Yfrz7mkL;6@8QV(+!P{m?DHs;asdBVaEOh-~%G}2uw9Tz)@F%xHUb$+qdz$ zVdGxaJ5Ha}2AL298s!I7w!2}WAmc@9NZB#c5*^qC>CGxcY~48idcQ+ChYvw9a1k2? z^+bDnO*f9neQHOus-hS_+(otb7S0f8Xh8}CX$yZ?BMbA=lImi`d(`tlVnO=a^*{go z?c1l4*&(q(&#ulgNqIj+cey$)WBK6yC*{y?W8HEnQ?g;Z*dxPDQNO1%mX>2_IY8PK-H#TgsRc>!xH&MKT zPDs1JNseSC>wc)s1|G(gi#Yr$(AxkJ71#{y>r-+VeZqwOg>VYX?U!fTEPT$S;jLrD z&E({9fb35*5ZwXYAg{(HCAEg?2~d?Bc4p&+@5s#lv8@A&6EnkrmvfwGddIMFRYLOH zI2Ng82$j4e_!JHAshJrSIe-k;(9WCWbrq>Oan3o9@2hC}WDVsHGVAJ&DC8CHD4mzF z4bbI_q&sEC-#vI6+D@)wq2Pqt0SBeU#er(?b-)#LS5074Ee8x3lDxC3s?iFplSW(@ zIjHgyT1?cNiXw6Mgnl3dQf~4SR}Rfu1wT<#I@K|~d@J#f{meLmA`&Z*R%1^IIjqm# z%st^{fM_sSLll?rB@jm>X_0eb{FGyKXXl6V+#mVoj;%}ie5NUAxU zejyfhE=34553u`a@9t)Vs0!d4Ruee!?O1mC)|j6nCopn&N$9O?!~iQ+ zRsw`XVuHrp04P5&F=l2R!75AbIz4eq7H}((!OTdEMIz+*c>R|yB`dH(UY7*XEhIPi z^DrxrLS~HYA37+h;g6uE0xjWSG;Is*M1fH?BNY{d2hv5h-oPQCy(T(K0PA3`B{Cdk zxt)HG{=OuvI9IfyKwl`1W-2snV6s-1@Bjum$jT9v9GoT;Sn(p^56bX62LKeIY>ae5 ziGHuylq~POS23oC=tENqcp}@GWlB&AnA}scEhiq5YdW~P+PZRR=4y914WZM@WmQ#mbU1l_11WjHk|R0GAQ*3s$h>jSeGJy5g- z-bin*?!nh=Yrv!|_|#m`(t2ElAJ3|)3=i#7juXZhzhyjSMognZB9}D(=N&M)uk-E* zm?mx@a3FFA#BS(0Uk`5ypg^kJG|2X}u&NI2gO(RiG6dNeSAKz;2E6Y8R31G&V&IP< z$);|FCCvZ9x<@fu_I>{emn-qgyHlP^|l_}XBa#nAW(=koTvVih(@BI5#g=R$;XGm z8F#>0lcNPu{`6^sDo-8w#2{4)*_y%@Ch!V0Bj9o7@PJmCnV}&dh^dwNB2N+tFXj2uXTzqF(vGx)$*DQn5GaCS zfp9PY9T3PVu@Nz55Y;-I2CPj?YBASA7k)qX22#XYWx#|5Z5S1#I;Y+RXspbRiI@K1 zJRBX5d;Ka&O&u=gM1RG0zgJMdVBX<{QbAaxzF7Vg1W*;jHkOx-u!)k|jy%GF3)@B< z?K7}CL2V9>CKd%>;5J zmcTl|+s9JVd}{`U71Cy4At;7g6X|m7G2d)5UPDWZ0HuJiF3rtBuLLHKn8Ro$*o#Li zz53(g;z>)d4}DUv(A4r1{b=a5T?2%fjrtsgZFI{BfIS2WG=gYD>w_;2^-zjB7gGL% z`}PrZe8wqbDE4gpcpfemCxpvzMe^#Fj04ZW8Iyo9EkY6mph5Eg>iGKguL_Cb#i_cg z)V#Yw9v+?TDXdhE1{?q=ZUTHYQ)FY1QfBg$*|P`qV@xI;X($%iA>tnQbPQ@zTwoL; zBiW)`0s~r=KNc8Ci}G;l)zo#j-^ZB=@C*+Zi7Cn{J(O}dXPvpNX&3*z}FH#5jOCzNQ&~?h#PpW2FJmO zW;DQEv9?bCE3SnO_4H{tW#vFrYiXI8pAYg36K9}v6^zZTtkh?ZzzjF&klBwMDYhFw z@!;momq0=#Od5h8dmVqcS4r&4-BZyH2r?jTkk%m`!1Ou?{b*uS&6NlXpI3Z6IB>vj zFe8qxvzz_MW1twDw(cu;C6Vk2Z0^_V7ONTEkH!AKmLCsP08t}=jPV8np6lvDFolw( zv#Sf@Bha>qn1Gmn81fO(*AgEQ87I2N4ygX#!f+C61u76oDzqO7h=^#w$37-zH}GaG zw|~u+7qX7tNMg9H%npbxk!zap@O>>skei`la;E511}chflfV5lCZ1#uOAL@X@BD9-VOdmD>Bg<#{N_9Ubn=g+qzcoRZth(aWX zkKIaQ3yB(gj|vc6gi4RwBj;h01cPU=8-YNm1OrE*w7z$5AHmrlCGZzZRSgX)%2PXb zc#B!)=3yqPqy0~bw}1p;_J`bqBzGH&lu1AU5{X-*z`UQ~ zIepy2ak?mm+{{e${{YWWOfSORp)B>H5zNW*lYRL;0MC~@yXit8w@=gMpxh+p3bXJ! z&CsUddF^lKvDT^2BEW%)^XIysnU~i(Obn6zvA75}37(k*byHf36dLaddkdi&%IpvM zy3#L^#1%I`pwH{U_#F-^Fs(!)fmWJFAKOq8e7ZghU34WT7r703(NdE01EvLC1SY{o z^vZZJM4-qx7l8Y~&JoMdw&T(1xR|{=h?}XNwkdb=|JI)pvmdE?XQx6I>&1&m(YNje z&D^|WL1rV#`8;qeu~+QbYjdaWH(L%I*L{AEap@&Hwn!Fs;EC^qdJ4CVY7%ChM4b){ zBl}6}O|jv$-Y-yy;;)K->5=z#PD0+i`)K(0iOu?GNC>~caf zg4c)PM#wY5VVWlU^o?eAxikfNSfdcIJ*?f;Bk$?nZ{+=i?#RZMvbVYQKU{!icmF-M zy*mB(uGZ+X7U^{x7A_9&+`JJF5&#Z<-jsp4gB4g&I<_LxqtMX3N=$?meE;Df)}pO< zvlW>8d`?p&wFYD*fWE{yMvVc0ELIp~S6ocY!y%>%0W!)U191D7J8O+c1Ouy3fx($; ztG}gd?@L4>dJ;p#KRme^0RJ1<{0+^_w7RIxSwh+Id%$gQ1}RO-d2XYsKaf)m0qUbA zD)~8aba)1(;uSdgUpC=nzw;X5_t%eP3Q6gR2SAjdg96Lw&nx-0n4&J%5XSEBW!w=9Pf;6S1*tCgQkrE-0@9uhl-di&=H4+$=&nw$F|w53IInq z?ub!hc>f|In4v?%qbq#nU8aAc!PToXsIdW~09E}mF>wI;O5jIBw5sEBtQ5`I9)L;q z(a=CAR|@SEn^M$}2vH6_RJySyoe_KP9DCUxCLxuIGN{mF2FOXt#j@q(mEPBHX!Gj2Ep_Q`Qmu> zqB}Mq!b-2D1=1x+j4f~bbOrZDU{)O+YOEB6a;Xs!lmsCIc~2vRmKtZzXe<>@$l_sN zyLPO_DF?&2kt%b~a_rlV7_qWmCwnjZ>Id_L1WuBSSjt`c?2Wg$MVfxmb^1OytVC0! z6NA&c<4rkz5syyssrR4WiCy|!@2~mF(LZWowOXjh&0+7zW@nnxM` zRL%3Q?}rrv3r2K7EYdGBZN{i}=t0`fcsvLB1|<@riyI_ZW%}R7#>8;MMjLv-;BcLj zdiUIIG(^L`<{IXspng(H?*w0qf#j7yh<|bs42iSn;^Koi59y|udolt7>cD?Z&0M6L z#wQg)iG8^hn}G~=JJz>eP%v84I3yDcy&^^JGNinogDoK?h9VOu`ay6e_5rE^HAsYo z+`Ea$ld&L?;Nyb6iD+Qppo%+ztVuQH{D%`P?1)TwN3fg&^tPg>6BX`9hjjLXIm!cI zBH#LM7ZwUUTiislKg|`XDRmz25XnUrkb%lak7Qk*AsKn}=$4r!-Ap5}Pbh2J#&T#r z)IF4BR4uJR`2HKa)pvPH83Bgn8IlztIn!{nD9Ghn9FEtH4fqh;9CAM(JJ-1Qtei)C z&yz*3r-l4c+-cj2`HOk)>W@{2|aMj~}U zW{bi&$zB>aLNGjNt3$L`~#1H~W)hGJFrg=QEUb8TtNPVa+MLD?z~P3g>zWqQh7TKeiDbLQK`@JK2YUw>&Ms^p8%%J@ zxGpaZ2HBu%UmE5=DW-$x$KK}_&@nK8Apu?@F0^2|xRhQ=>Gdl58iJG*3{}Ml#>28% zFV}w&vH7C5RNI2+ePaQvLdOlLlbUiQYvR`g%O7`;M7WPix=P6v5 zKTJy{**K^4!QBn~+%yI?z&Qr9H)m&NPT=*>8oIwks;H+IKQ)<56!v&xfT)jquX$=~ z$H=D4&Cka|AB4$`C~q1;XyFP$cbDSp)k7w-8wbiyv$4rpwr(f2hX9z7kyFr4194js{)Q4B|3IUZ+2P1Q2@dnw%Uo7MW@@-pTLO9UW5scv9?48aSzu zxJu5nRW1w-dWT47GYFG(gCb9T1x#$3pZ&nfN!g3Q%$&kr?#RlcdfCdyTBj%zKLI6oF~TB)B3K(=UkX zxMKhPZ9m%+#8fCu@w@lss2V=?V%yvPI{zXz z_E(#n&)d^4P9}5BG-f`t);PWCERV{ErB?M0nfIU7$xkh*Ca$gAxIisnx<1D=T&cdU zt`TUV@#XyDn&u)|!n-xTHzO_r75rYkw#Y|dTe}G6^`~BO-hmZQN9Rf=(;q+5 zHf$nL71ZoLEDB;9|Kz3JuKIavX@(``p47_i(KnFI2Z(I5$0bb zv~d#Aw|uR-bAQu+9lf77Gdx{3v8kuv@tpn6JzjUWU2Q%U))aU^sHr2oyI`znE3~d3 z>QZz45zVMuq>3u=s|a9J>!0j1yOnG+6!uYsp0Y!SC+WrCf^x+QNMZ2WpZHcV^LMQ z{Z*yGAC^>`)vX?|sH>e`)#Wr?%+H-znv5@{(6e#nV5Gm!*BJHwV)f+gCJjEW_q$XV zCpAX4oaLd*{H2xpv5ZS9^Z4z_k-Qs+MERT~5*cKcF>Pr7k_;xyg@<<_VgkH>fgoO4 ziN1+4-hIc>mQ)0<7hGtjg=h^nO+c`5aEH=~T)~S4SUmegNC|IC=Gg_EvsqcozJz8= zd3T{vhK{wohMRneIo>688vO=3%Akpy0?Wp|MNg97=WrexTJNh^c+NFdxjxKCL*9E* zXN!)yOuPP*1omf&XXvB38=E zq8U1|J2|%paNnA?{}4UMGq8q{z4@wb2H72mI>R>n--b zb?cW-@%oszg0g7`v(H!44ArrPwm#2~=489cEIOFY-#ouSd-e2`78TsM$-}2QSBx9W zMG<(1MT1M<&uI3%cy6qa&wI6-|4Mh7h(W}A_QNfA3PtIbni<3wxBL@wOTi5AE z73tY8(#vns>&-Jxj%tYgc;{MOQ2)%Iu!4Xlmr+noI7Cv>I$Ps5eJ#f2ey zs)WKjH=gsSCy&UIb=C>v>m3(VU*E~wMt`MKv-q6S9&SBFfx7`E)}UXF#0YuVAympm zH({tJJk7?$v#Rge46p-mPzAyU$pcZxtQ4A zgO`50e)5Xmw9WmGgVgWc($Y~p!`~|UM3rkyFTdwHmrzsd%W~%V6z^!;Hjbkvt>}vU z+C<*puU&e#%B#1KC}(QPj(I%TvgB5yaPHuG88m+3{q7W1x)*-aH1Kg{US0 z2Vx9wk#nJAIyA^^tgI;2xc+7h-3exp^5W@V1Q^q5v_q`lz830-O&d3I8|32So$*lz zrO(;q3UvKg9=xc&d1%U7ng8kyMq!1#1E=M_c5)7II2t#G6+3gzRw=EoNiOWZn4z5< z1_MC>H{O*MclRfkw~$FI8&vE(dh}K8R3FEkI~OjVlHG`|eUC4*ZJ%ooO1;Tc!weWl zHnC4l-Fdl&ArTi-H(6UxbofRai89}z_3rp``O%~2%Z90AU&@?zGbn0M8+o@z8wr~2 zOizFFu;l?~TE_P#7AopOZ?x52qrao0Q9s_XdGp+8ytYoE6{V0xk<*dkMj>k&RjISu z`)gtZ4jz;Bl=Snv?SD~U*;%+NqtK42D?`9^`?kF$Gc+TkovHo;ol$pITE(81Q_#q} ziXJ;gy7-ua()aP$$o1d<>;pNuv{Tvn`4DwUdi=;d_JxL?{yK7am;}|-*Qfs@v6@ER zJ5XF*T^)H^Dv2k066_T^tI=!1-*}+41!$BH(mu5ApkDxs{Y_v4PEPYaR^rX-BlTuw z-G8#-gLWvx@U#xeZTZ(B6H``rljOyxTT>%01z^q7PBoFQ{jqp@m4*M_;A-drq4Ca< zY?^x!wN7n?#+%;14`ynEEtgvj`$U6A&fKEer1}->iGlbBR9svb!G6r)R=&g9XHk$U(zY1EH)`>x@yXO-E9DUTIYzPhyq zdq`ro#5g8L6W*#v&h4YydETHkibpxFt~p}&fzBVhD_jL^69hh$uh&9+o}{Xy(`Tzz z8~#*EnUC-7!{JD+7>Vc)+7MawuDqJfA{H`nDd+(kf((EW4xLz@04#7xNmT){1DY`P zu`~xgPUzLaQ2SaxfXh?mZM-e-H6XtLlmc`xG4Ydq%4hnq*;%GeZA7c+oIetlL=iz9A=PU%ThE;N5_x$aLpag+5lcLJyJk+4axk zP1C)Y!|LCt!86oE&VG)S&9Apu=h@!3yEr$pQ`%LXwdJK3y%%?d_0O*#kjGg5H1dqt z#N?1i4Zq!OTE! zjax>-6&L4$Mr^{-sH6nlLJNCAyuu#|d^$KA6d1}IHDq!yv+UR_FAZz2ruU}S6C33|#tvOFyyjOQgd2?6Z|D)Yjd3XJ z@!WFt1+71SoDv=$5O3F>83b!M-W!pp7m{pD>A%;Z4dzX4)4i3eOZA57MfYd=dMj5h z@LpMKa&r_64{xBs2wtrobKb9G+W_)EHO8d&y2h?*@6=RBM+IfL8mUbdX58tP_Pb&A zEOXKLT;iLWn{N_ZzYXlBZVgj{Wx@mb<}>!vT4XvJ!+Ef!V_S&-yI zu8cl9cC5Af-7kzJ8_OvO2pvsY7na)X{7bm75Yh1h7`rDnu@36`2bsLzR9?&5^XH45 z+NnG;r)CPAa)ayUQ<^sx=xO*g%hibFfVj8|pd|XMJ}_>r0;cH!MFF5%=&@rLLh<}Y z#|=-{)L?PjU0RcK|fPL<;cX9$g=V)&a=l)_e zU>qA8gE5Sg&iWxNP8CcSIOZZQRFdGMgu%Xjo~LP z6;+IK1}K|5^z?~ku%S@7m3Z^!O@h~2S`vLMi~QHi)AQhz`3)>}@-k5>Dx_zF4+KP` z(paxpN19QQhcBHJx)}6FePqO@_toV4gVJwX#TI@J|C!Ws{^r^H)<{3NSV+ixAEj>u zWlg?;a!gG_$eV;6?G<7N4%F2j*h4PM;c%)7Y8jk6L3FRy zvm5nktQd=9`sHa~j3k7p&9A?_*UHK~#C)qxj?vwx&+Z6ssPDGkDh3OSTfS${-CJurgfy@kx z052Kf_2~HwAg%~B#~#4)brO0jL(324oe3R8bSY~X`MQtxjDAA6S#S`G2z5*z)1aJ1lw%h7M&-Xt`qhEY&CUwb<}c1C`yL4}~@KA+~g zi>d-v_va^z+ls6xt$Q4o2S`&rNcwL36`Joc@~ZDl-_3{-dpTO0-o(|Lgb7@dN!`>K zTHg{xCUvPUK&jHwL7+{#&26xwfJszT{Mh^(p_n6?0*~p}f1x=zIRit9Vuk$8rEB_s zQHL=MyHyVlojiCjM$pf!#ol3qxL4e@g`Zz`O;5*&hmTv9yO^wcFnS-nwBk7Wb|geh z`w8h%2Xhp+@o+;B0ab7ty?q@?;;Vjhip<#T{TKec-2K7C0d zpKC@7@F_qfSl8URA$1YgYjsKtvap07td%$;#>%eZ9R82RS;x zYG8&CHYZL8oUPb%e?A=U{Pd{`|0&wdnfPoP^^3I=T?yhRZMct|+n>@fZ9}pc`^9ZC zSoLG#)TQL2U_5$WBH@dDc%miVuE>_b%BtU$eqmJLhNu79*^UI;ck5RFSuTJ7fmg+h z&EoC;i%Lh>9sh`*2|cgBd+6Iaxy|9>w{P#?b@C)^n9DEYfNnWCAs>G9QPF+q;=2nh zW({ReT^ri)t%A(kTPfOXhoacse;exAzDkb-SY;0-yZ!oVFoV+Lb5Z%zih{A)g}11WlCTB+nMN(7i=9>ed5Qo2NpnBG zC6MyZ+@>R{j^A02oV#~V=GrlzXxh)88)^?)?A~36@y*o82(=#&ze&TEcm2;1yBGD* zMqj2{>~7SSSnWP&IZ^aqHz4=*dsgn(H?hBZ(6Jy&IrUCTjbY%=?KmIrB`v zFIkaiS$fbuBB1`gR@7{H=jZDhoxZc~*wG+seAuU0$k_Py9SX*CmYMVR&Lw{z?@Ux) z`mTKw?J(1tV7Dy~q%|D+>G1TbNe?gNSRW&e*6wp&+%L2hJ|bG2%*@fRO<$RQSsCLo z@K>lPHQ%#kOBAo{f1b?o>_46?)gSm}uMWye9s;uuuw|elkbdib@A}dP!6vEt-Fm!3O&0@{-e#Eue z6EKy7N%9|uZ_j<3BXDGEX(>e$vvvOG>Xf3Uc9?w75m0D*#mXsXqn_TzO%v~f=Iq&( zliln*mf1PB>zN(JjdGtHym>m`;N(ee{iaubrWOmI{cZXhR+lectZlo|aC?VxjEvmv zbfv$z#=l<#d70+Oh{$C9hbJs7|JsCLDkN!&q>G^EYLC{u9?J$Y0*x zfr`5=ar3sWvf}h9ETnKv#FNg%=M_R`J1=IShHx7!bUISuiU|GfTQHp&E5pD5kHLR3 z-@lu`DN@bwoUU${Yj9!VgQ$%k`Y0)6ONlAkDgwshxqDOA0wTwFf}=) zPNk;CZJ>DhQAhjyXaB5x^BNM%=zeOm39kPnf`8Wu?^zA%tSnZx@CR~^MTPfb6y)y| zo?8AUPup-d!u|VMlQL^9IHKc|qa(2!XABj#7n=)M)2ysae`?J)$TeswGW+qZmBEeQ zd^d~y(75IQ{`|Oz@DAbnmh3Rq)CRsk{5<%7K~v zjbUOmw{FcXYuzQ%K{~Z^wXes=CYm2`D#vcL|07=EI^TTcO?)Fu*ggu-lE{mm7(0Kn znUMXjw~)4)na|EryPYr2H`v9Y;XVcF=uuD4?Ymj|?-iQt*eQ4`_~y+Iy*lL{Si*n9 z(1Z*#OJMNVSPKr`(c-qB<19dsG4rP*90k}9OWTT&CIuA(;;j*1A7BaQhRn}P{?1KT z`ezfA-MhQ>o@)wj`kQtp}U&lPeC^vvA8Jv0@R#AIwNe(Ybrv<9Y$7MTJ8PbLg*tyZw+R0CuZd{tt?apJ7 ztgLq)7ID||UJ|-PHdar|x4K(IWH-ZWizKV9JBWJ-w^nlziH%K5yBDW;1)A4{V9>~f37_sa#zpxuwdtZ?xJ)oM9h8ek&)UJ?dLe)7HWRz` zh__Fij;ycp;V|+gd-^$3siOJsTk6b>qkEe;^5#Hir?}G{A&bf4-~$KLHC~2wo&Eir za$ilG_uCiC6#FeVAEFMXyno&8^`uDXM!~O@CU!Mq|={HJ0L15 zcbc5KUa0N7+Dk2?`Cbdpr2`9N7d7P-wm37_9 z%D=N(8r(jwn%q}i3Q9~GHZ|8R-y7~~{ed5I4cHqxUGSS*p4wTwrt%4-TZ4x4Z&mb%q!KNX(k)a|-I~f>eoQr5Bnh~3ySjS*JS^6a z!8?_UG%RO|TzSI7J%95IHxxQ^N=bRnZD6|5)RD@qjZ*CAFH{0*Y7Oa09(ON3cAq`* zts>0(k8iF20pZM2H7XhkhLBPbYU+a$@`F`>=EI(s6`Gt0qP-hxK7YBtKjwI(%hZQw zVatPKtINIBN!MrDI0ISEJb7xnR${KHdE1|ow&!WZ&KTuf-TFXEcX#`*+ua80|E!SA z%uuH_M;ttME1o__v*Vea^(o6GgMeTgbMC<#EsvAFzuX4Q$<5B%Etfh>>NV4vkN>t4 z9{l!)k~|$hpA@NVE~xtW#l=8Bu6ljPjyJKuXMw6ZvaPIKkp`m;_*?n(me^Q%cLAP| zAI_a!XO&o3d`pCP?hGEVxjMhpFo@B<8#iLY*kBUl2@FdbG$JR+1FJ!Vv2Z1IjrwpF zY!ob-r1g6dzNsvmw(d7>G_K{H)7nEG9-3@Ic=LW8i7qTcgE=OW)Xz$Aw96eZHufo5y(+28lF$?95+wMsl{E$F58>aG&BCeaj}zgaLWE zL!bSDpl95H%Q5Fg4j!{_`WecHMIz5Irep@JVhBgujy>racW!Ua&Yt^GH<*-qW&@*l z0&Ifb)YbbH3EsN3|3n;*9w|GgY(^BnmnUS-{x0B3^N+&NLw^*$v-@++2A_|*CclO` zFCuB&%kU_fL>o;r#mCFeb@%$L2pwCZ1XiZH#(b+7740+ElydjWr?>c%30^ZpZl z9|03_$J;;Mcka@of3-4;v5c+3W{X!GohCYJIi5#Km@|G{DJouBoxQf|;zK~IqkVP< z_-outBk^jLcnp?nHc(K+WnF7OR8$QX1}Vqzo%k;el}N8k@)p)1>SBy+SZW$ z^lP@gee_IBe^%!g)33V?_qLH?aK(!dZ$4rV>w6O~wS`5XL*e+1`7MQoA3p4(F=u5s z6MTrjy>l@zKwEa3vRKvpRx-(&?!0~{vYOwsLMB_Sdjzk>vE}?~wHqIZmtM`fdL}*n z^Q@}E_Q&To#3)Pt*w^=L!F#=t&-)tN>j&n@9hf@}zkZ$Tce42)<03NLSnQJ1!OF)S z9C1V-*501vK0-~yeQ8qt(>4G9hMi45l{^<`X4bAwY-HT@eBs>M0+XPiz2oJvbAo~~ zBD+vzQ69`M}dy}a-1y$VxPMc3Ql^;8k`}^qz(u1x&rt6*_ zsV{S?{Jzs^jDlV%jPaDXD;!AnPZC-HafxT{&;EH)_c|{K3M#0IB`$oY%QH7qGq^ep zJHRyRHt)SVFC1~ij+;of;W6+D&_5z8yL|_~zE24j?QjcU@3XM#^@o#JJeIzW#vc&8 z9dCQNhBQ6RZIF)_dSFyqZP3BL@VFI)_iy^ZK$=`)x(@G1=C^^Hzh-qpL$PSVn&?0> zjzD_RpaNAnvQh_TWLrPFa`m?DpE>oWL;lhiIU4RmQj9}^NBCp${QLD^w`AoC!?Df3 z&(@@NE93RxuE$yVptjsTeg5pkVx#>b$JX@h~{Z8d{~9~v9(91tR5584@}uA3G6 ziAdaz`sBxMV)ZERR8Fqx!11*?e|h?6wq_%W!$d;^U1})R>(#J=lh`wNd(hlIqx7)XuC7{<~8wRR1Cd(W)wY zYO*yNoNv~AZJzG8dU==k$bwPbuASTl{wUr=h8Nl#T+N4MOiI1Im!|Qzp4y6ZhN%2p z*|2#t>EQ9Y6U$F-oG7+fSn3OLjTiE-m>q3D{K?&y*68cX7&gCc87PZg>!k$*racwE zF?9dShLD5eHF?jTx(6J)6`P=JnpRlfM{ntHe_SsBvG%A1&z&unqVf39sfJU_1-`|8nY<)pWBpTPvH?76=Dy^eD8 zwur>HP2roj0z-Lv^-avn0P=>Letw`JtJhDcN;Ss_NUpH1tk6o7d#_Pm`eA9ZxY$$p zRJ43EHTC@Wmc^Vrs=;5+-&Rw%hE9F4Mpj(*DB+>b^Y)+azB=~&pFX)?6RGw-x3?x! zjnwt{qE7RNLYY({66Fz!eKnowG0JjsbK|La>(jjr`tS4lUeMEdRws&vWO9J;2oBD; z9u-Z0Sixz%noKIwdje?8aXn)*jX}Q=&uGt&-Lu)p)@d0Gq`P1!^k>S5z}h=4FONSL z@6LZwQ>uH7R<|P~<^8+4=xY9}x~U=6zo-oj5o;YBtbHHNtJqHQ7!=*Uw{LCL4*T-8 zA`On=4Mee_a0YW?n(>cP<~wCw-4oAiK~A)W z1)n^E%A8PK)cR5%b^mFc+Hy{VI`s^)`FOj_X7w2=z;NF_1Yw!0gSTdEOfqRe0yRI6 zq>S;LgFr`za(qLT7k=D3d{CUUj}D7q#}0Lk&l7>w(*9&lKlxMT)h@hx9og^BqW7%G zL!_+i$M{KiaR&z~T1x8r7t3^cY;6xs#?NPG{~V1U)my{2rNY2xQ?o*oZSi7Y{41B} z9!k(l{FubFf<^B;1$rt<)`dSc4R4v-*3SI)14uKm=mvA3-BaLEte-Spj-+%6g`E8$VDH&a9~ZyL+wNRsft+K{hJe^Zf}fNRn>BrR6ViOEveUfyD07K%3ZojI*14ql|sbwqdRwsI|uMp4b2&^{WfxRd{W9L z{2-I#(W8K1)AmD>lH5Rw6!e_mIJ5jO4qW_r(G_a!g)f^^Qb>^Z_r6Lyn;_YI@32bS z6KmSx26D!?fs~8hfy?uUrIU&Tef~Rb8SV)mJ>`h}qCgrJz~Q#~l`-R%f`Y-){+slk z@_QXul^)3KP^;Zk;cE8wprI$ZghbWv(Bx!!i5N8qvHEl0F>bsT5uol(5#>^MQ8mreL4+v#u84t^kz7cq3@xSQ`rne0t4b{IL z9f2xG8w$QHwxaa<_0Bt09|;xHHtni}GN)_9drZ2AuPtal3ssfQv+J|b)PM795n`Xh zLh<95ty`WuaO-QY+r9a6Ing_Dwkp*~+Q!D-@k^}5lVa<6*&v!i(;eQwDC0#7U3p9z zzjrE0E+4GHmR#DuX={n=$23;W0`pcnpZ7T{Gj( z8Tw&0+BzJ>_oUe5iyYC!JhSoChv$V875wh};o-T41D4$XoA3D39`|!_eWb84GaKgv zqgTm|-@j*zJ&*a5b*1l8ivIqi3&&coMM%8o@&M1L&g|^b+3HAY->uN-IQ`(*vZbz0 zcva^df#H1&%FdQQT)z+zH0qad@a|nYhVdaEfB*UMkJMyg=9hyK6Bn7x5$l1OgaBo8 z3{g}SE4OEmdh^oP)NI4gUv$QenH;uNv9<$$*HX@LoAQq7|AYJwm6$bc+^d|Ck>qIj zKcu~)>puQi_XQP4r`{(w->I8ikMMdk*%^YeJ@G`y@m~p2D(Cl|@-MP8658^P;b#NA z^U+hjd5-VKcdXI6nAF)LO6pkt?f%}n8y0vjQJi5oSv{}i| zFJ!M>jE-<4O>1*K`$>5+G8J-mY>v)v55@FgMPK@|jZ9jaU724qB4TBfet7<)wW;}K zv(pOO5&o&`lTYs6@ALTaX#n^Wb5iREEiAU~71sQ{40kh+CDSR*?mVFjiGZbM2gfrL z4pLBZa#}s`$juTMEw*h=IfY_jsz>O$s9m*JA$45a|JT-)heNr(VJZWWIskG+mNMfA)F{XF|x!7DMGS^7E6{GBkPcep|LAVN;&+VQCFwa`F($U z-fQOK^S$fy-uM09&#g3P^2Kf5ew*9$bp~INZ$Ye{>dK91qcsTlRhCzkn*V^rZ6&~f zi>IN1m)F23_@%lkGZgubwMfv%sZzYWaw&YT$%6<51q;ilurSuz+QvuK)iPk33i2-! zv{2{qEi7ETcDm{fG3f|AUMV20E%jU}Tg_m4I2&GQI-G4Qr{n8Auo@R0A`tjdV_o{w zUEZ~|-hRTelFRQQ*yBR9Vb>i>v6w3N>UZc#Z{e{k%87}Q z2o3{dk7B;xL@0r4^{gV@xx(#f%!0?J>Y56z+o{$icH1_y$`I3vJ1~G3&dl5^$jKbG zMLP864BnU?(h`yOepu{GFnxQuBRw8R<+#QEs1aU=PxW@c!xoN}_{dFB6pfk{%p^ zg9JC&)zm(BWt=+m?#DU+A~q+_wL79gd54`{UN&bwjE%w4-zbe%++*EA8z=1UJgR1B zv0X5Miuqd(9GQ9QmnJ`dW_n=WBw2BkpeI|eeTJo(oL$b3MDE_*R~{woI`-_VqIc{o zgPP(kq_W(rle&^c=P$QCJlfFskFq2!L1`J?KtN!y^&MlRgs9on-dJKHKe*4V9K~@ zGX~d04J%aMgvH9p0OO?^!lWyH+xLccLZs<0lyl@B?_7OZ*FDz$SJM#?q$18#5Fy4J zjoA#;@|(&h^IJLinU0vfh(7?UbV)lmKO8vs|H!99lKD0(b3#_@7?s8#W{~3fD}_+vi3Z7;?H z_~%4j7!KLOB29$ku$X!E#Rfm$g|P(5Xrye(WPzL8a1P0Pu2OS!O7R*ezJ|%xws06M zOcBDU)WE^FU))_>viMm@7t8K~GWwN#fz=sKw5|LY-QH8)<(>}7o*v~Wq3fecS~gBg zOzb#wmNEN-nnorsVxN4+*xRq1e7u4@@yYn`6NZr9C5TJkIf0UX(e3E*ritMb&y!OlMCpdIy6CD_xq$n%&-B+rP_v03rvmYc?-< z96qSlR!s_!3!U5mtcC`2*UF(ClTx zizXhC_9hYF6w1nQ<~%zML@vz?rpE3J4&n3pH-`!J=OD|7s$ORrA5=TJjnk#H_)c*5 z@7z4FT=d~+qy0})8QLA@H-p=@IecN;{-Uu_RO}x%dZPv4Z?FP*#jmY-^qQ8Z108WlAS zEs=$Z_jzE~tdGxr@m{Q6+OYLHZOI`opLu3>eo<`y7HeyK?J65vrg3gQmW|6{Xuy>R z(UvR?e2SPBZOU;n_*EqF+iuBbXS;oolaPRoAAw?E z$ZUfTiP@p5x@F6&ELLXbEn8{tV~V7PhQNBl4*Ica1u+eyZ7b?Tg^gDb^XdXAQmCO# z0rCM&(tbSaTcMDH@kE@}I0fMCJws$2x>d~Nq@A7M?4D2W4~m6s)auL(L|0gB)*!xq zJa*@s!J-8Nb>&dvAX8o*lcN&^BGCx^io5bFqgyk>3uD>MvZhV}onUI4+c5VVBF1pq+&*gSW-VAf;eRPr3vuEDELI}u&I=}E} zLJ+w47wW#t&T9vdNN4AJd38OB()fqPBUv%clxI~RuUlw+pJFzkoS%B31)Qq@G!vzy zSlTzo)l8NPhWFDPlU7N`H#L*T-Y6YLMloRYg}PP_EEc0OKVRFFYq;9cW!z;IA!lL` z^s<|lUsk56-xR!QZ9I_aK|z02;(g;HBcES71(kIp>^}*(f**8>#iFDncspNZAD_nH z6{USwBexqFPn%;mEiXT=7A~=@t`?3F&p&=V<*MoHicX`21=Lhry2}`-zu+wHe5kzq z@1|W9Qkz*9-UlMTVPyY2uhX8F;dbg3Z*LpC2j8_r2s0PSl@(roqu=c??CggQW!?*4^e1OV-rikBv&HzAZ7%ewbY(-62C0DBx<4a@G<3IDU$#!a_{(Hr zVaga`ad*icMimr0(Sue#|YxWWgxSC}W3*M}7Y;0>Q$< z&8wjYY)|n${ktGcv~asvOPOnlGAVR;_l}p(5Z5PHfU7Y3l$K$=?r3Nzn=2DoTv;Ww zPeV$ou1-ipP}tthMT#~qrr&;dQq$aA*^9RJ)rWSSpAaSRecXTl5f{Ojioz|}wX}94 zCOby!{P_8fImS~z7#f@)qH^_(ak#gZMI%r8?9CU2LpHrl}Pr&guYW9Ho}lgC45PIXN(*GV}wE@7gssZfthiLBhvJ zbARChdL%wqPf_U)LRgkqI(l^21~V`K8!mbI$B&sBH9>c$mkwu29zM$3aXRIbYjZ=+ zWcEOBZ(HaTnFLl{3n_1{tn{?CyQ1jbHfKO?6SXXXk{7=qpHc8Ao@QIqEU}4&rMnwm z1iactaSI5<8mu`aw9k_t884YpHIz27rAypiVawrp9O##oyG5~&NFS& zt(YBW&vy5^k49lW@+OEo^m_f$TCLiXKx0*w_YL4(14r%`o5zy~*>ejEk^WX1EaC}q zBeK|3k68L3xxKRTCP^V-Ty}hUDmchAT*=Ny)yu?kQpUovxV*64w^u_cJw56r>7-hw zs!>-57rOfH)dqXhqJseet8@j-{FV?_^QvDKoVaO*@=Mg+5;%uoZpA;DIz+*!nHfBC7c#@?aSA z<|CG&KTSy>_6jy}K`v@B5WQx7K*9W$aaC+_mxwh?nvo1a)z6oE4+v;}{@{C=%I~Bj uu=oFb(aAVC@ZZbbg~6cz_bQZJ7tx-nf1dcIz!=VWF==b)sTZo*1pg1s#0xS2 literal 0 HcmV?d00001 From 3164519d22f548631d01ba42980725b2b04bc458 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Sun, 22 Mar 2020 16:47:47 +0100 Subject: [PATCH 032/627] fix some stuff for roslaunch check --- carla_ad_demo/package.xml | 1 + pcl_recorder/CMakeLists.txt | 4 +++- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 4d354b9e..50f72d56 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -15,6 +15,7 @@ carla_twist_to_control carla_spectator_camera carla_ros_scenario_runner + rostopic diff --git a/pcl_recorder/CMakeLists.txt b/pcl_recorder/CMakeLists.txt index 24541e17..64be9a4c 100644 --- a/pcl_recorder/CMakeLists.txt +++ b/pcl_recorder/CMakeLists.txt @@ -13,7 +13,9 @@ find_package(catkin REQUIRED COMPONENTS catkin_package() -roslaunch_add_file_check(launch) +roslaunch_add_file_check(launch DEPENDENCIES + ${PROJECT_NAME}_node +) include_directories( include From dd1fa20f15274d72e4ff28f70204fb40b37c8615 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 24 Mar 2020 10:20:26 +0100 Subject: [PATCH 033/627] In order to not run into a timeout while pausing the simulation, set scenario runner timeout to 1000000 --- .../src/carla_ros_scenario_runner/scenario_runner_runner.py | 1 + 1 file changed, 1 insertion(+) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py index 9ff8da61..07cb72f0 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py @@ -29,5 +29,6 @@ def execute_scenario(self, scenario_file): cmdline = ["/usr/bin/python", "{}/scenario_runner.py".format(self._path), "--openscenario", "{}".format(scenario_file), "--waitForEgo", + "--timeout", "1000000", "--host", self._host] return self.execute(cmdline, env=os.environ) From f60c57281cabfe02feba0e4547f09df0c294f3b3 Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Tue, 24 Mar 2020 10:38:59 +0100 Subject: [PATCH 034/627] Update changelog for 0.9.8 tag (#249) --- CHANGELOG.md | 2 ++ README.md | 56 ++++++++++++++++++++++++---------------------------- 2 files changed, 28 insertions(+), 30 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 79d65801..448e01c5 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,7 @@ ## Latest changed +## CARLA-ROS-Bridge 0.9.8 + * change Lidar range in meters * add new attributes for Gnss and Camera sensor * add IMU and Radar sensor diff --git a/README.md b/README.md index 49259054..761daa6a 100644 --- a/README.md +++ b/README.md @@ -2,30 +2,40 @@ This ROS package aims at providing a simple ROS bridge for CARLA simulator. -**Important Note:** -This documentation is for CARLA versions _newer_ than 0.9.4. - ![rviz setup](./docs/images/rviz_carla_default.png "rviz") -![depthcloud](./docs/images/depth_cloud_and_lidar.png "depthcloud") - -![short video](https://youtu.be/S_NoN2GBtdY) ## Features -- [x] Cameras (depth, segmentation, rgb) support -- [x] Transform publications -- [x] Manual control using ackermann msg -- [x] Handle ROS dependencies -- [x] Marker/bounding box messages for cars/pedestrian -- [x] Lidar sensor support -- [x] Support CARLA synchronous mode -- [ ] Add traffic light support +- Provide Sensor Data (Lidar, Cameras (depth, segmentation, rgb), GNSS, Radar, IMU) +- Provide Object Data (Transforms (via [tf](http://wiki.ros.org/tf)), Traffic light status, Visualization markers, Collision, Lane invasion) +- Control AD Agents (Steer/Throttle/Brake) +- Control CARLA (Support synchronous mode, Play/pause simulation, Set simulation parameters) + +### Additional Functionality + +Beside the bridging functionality, there are many more features provided in separate packages. + +| Name | Description | +| --------------------------------- | ------------------------------------------------------------------------------------------------------- | +| [Carla Ego Vehicle](carla_ego_vehicle/README.md) | Provides a generic way to spawn an ego vehicle and attach sensors to it. | +| [Carla Manual Control](carla_manual_control/README.md) | A ROS-based visualization and control tool for an ego vehicle (similar to carla_manual_control.py provided by CARLA) | +| [Carla Infrastructure](carla_infrastructure/README.md) | Provides a generic way to spawn a set of infrastructure sensors defined in a config file. | +| [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API | +| [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. | +| [Carla Ackermann Control](carla_ackermann_control/README.md) | A controller to convert ackermann commands to steer/throttle/brake| +| [Carla AD Agent](carla_ad_agent/README.md) | A basic AD agent, that follows a route, avoids collisions with other vehicles and stops on red traffic lights. | +| [RVIZ Carla Plugin](rviz_carla_plugin/README.md) | A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. | +| [RQT Carla Plugin](rqt_carla_plugin/README.md) | A [RQT](http://wiki.ros.org/rqt) plugin to control CARLA. | + +For a quick overview, after following the [Setup section](#setup), please run the [CARLA AD Demo](carla_ad_demo/README.md). It provides a ready-to-use demonstrator of many of the features. + ## Setup -### For User +### For Users + +First add the apt repository: - First add the apt repository: ##### For ROS Melodic Users sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 81061A1A042F527D && sudo add-apt-repository "deb [trusted=yes] http://dist.carla.org/carla-ros-bridge-melodic/ bionic main" @@ -292,20 +302,6 @@ The following markers are supported in 'map'-frame: | ---------------------------------- | ------------------------------------------------------------------------------------------------------ | --------------------------- | | `/carla/debug_marker` (subscriber) | [visualization_msgs.MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) | draw markers in CARLA world | - -## Additional Functionality - -| Name | Description | -| --------------------------------- | ------------------------------------------------------------------------------------------------------- | -| [Carla Ego Vehicle](carla_ego_vehicle/README.md) | Provides a generic way to spawn an ego vehicle and attach sensors to it. | -| [Carla Infrastructure](carla_infrastructure/README.md) | Provides a generic way to spawn a set of infrastructure sensors defined in a config file. | -| [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API | -| [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. | -| [Carla AD Agent](carla_ad_agent/README.md) | A basic AD agent, that can follow a route and avoid collisions with other vehicles and stop on red traffic lights. | -| [Carla AD Demo](carla_ad_demo/README.md) | A meta package that provides everything to launch a CARLA ROS environment with an AD vehicle. | -| [RVIZ Carla Plugin](rviz_carla_plugin/README.md) | A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. | -| [RQT Carla Plugin](rqt_carla_plugin/README.md) | A [RQT](http://wiki.ros.org/rqt) plugin to control CARLA. | - ## Troubleshooting ### ImportError: No module named carla From 87a801b8a0be6fe13b6888af05caf1a788588e2d Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Tue, 24 Mar 2020 14:29:56 +0100 Subject: [PATCH 035/627] carla_ros_bridge: Update traffic light topics (#248) - Only publish to /carla/traffic_lights on change - Publish /carla/traffic_lights_info, containing the location and the trigger volume of a traffic light --- CHANGELOG.md | 2 + README.md | 1 + carla_msgs | 2 +- .../src/carla_ros_bridge/traffic.py | 17 ++++++- .../carla_ros_bridge/traffic_lights_sensor.py | 27 +++++++++-- carla_ros_bridge/test/ros_bridge_client.py | 48 +++++++++++++------ carla_ros_bridge/test/ros_bridge_client.test | 9 +++- 7 files changed, 84 insertions(+), 22 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 448e01c5..892ac42d 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,7 @@ ## Latest changed +* Traffic Lights: Only publish to /carla/traffic_lights on change +* Traffic Lights: Publish /carla/traffic_lights_info, containing the location and the trigger volume ## CARLA-ROS-Bridge 0.9.8 * change Lidar range in meters diff --git a/README.md b/README.md index 761daa6a..9abd0ad9 100644 --- a/README.md +++ b/README.md @@ -264,6 +264,7 @@ You can find further documentation [here](carla_ackermann_control/README.md). | `/carla/marker` | [visualization_msgs.Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) | visualization of vehicles and walkers | | `/carla/actor_list` | [carla_msgs.CarlaActorList](carla_msgs/msg/CarlaActorList.msg) | list of all carla actors | | `/carla/traffic_lights` | [carla_msgs.CarlaTrafficLightStatusList](carla_msgs/msg/CarlaTrafficLightStatusList.msg) | list of all traffic lights with their status | +| `/carla/traffic_lights_info` | [carla_msgs.CarlaTrafficLightInfoList](carla_msgs/msg/CarlaTrafficLightInfoList.msg) | static information for all traffic lights (e.g. position)| #### Status of CARLA diff --git a/carla_msgs b/carla_msgs index d38e482c..1df89a32 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit d38e482ce0abe0f1b6d78b3649fd687faee28fe6 +Subproject commit 1df89a326ea413668f7120a72d43f075a6575e35 diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 9c6e6e7f..04690cc4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -11,7 +11,8 @@ """ from carla_ros_bridge.actor import Actor -from carla_msgs.msg import CarlaTrafficLightStatus +import carla_ros_bridge.transforms as trans +from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo from carla import TrafficLightState @@ -78,3 +79,17 @@ def get_status(self): else: status.state = CarlaTrafficLightStatus.UNKNOWN return status + + def get_info(self): + """ + Get the info of the traffic light + """ + info = CarlaTrafficLightInfo() + info.id = self.get_id() + info.transform = self.get_current_ros_pose() + info.trigger_volume.center = trans.carla_location_to_ros_point( + self.carla_actor.trigger_volume.location) + info.trigger_volume.size.x = self.carla_actor.trigger_volume.extent.x * 2.0 + info.trigger_volume.size.y = self.carla_actor.trigger_volume.extent.y * 2.0 + info.trigger_volume.size.z = self.carla_actor.trigger_volume.extent.z * 2.0 + return info diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 25da32cd..32221482 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -9,7 +9,8 @@ a sensor that reports the state of all traffic lights """ -from carla_msgs.msg import CarlaTrafficLightStatusList +from carla_msgs.msg import CarlaTrafficLightStatusList,\ + CarlaTrafficLightInfoList from carla_ros_bridge.traffic import TrafficLight from carla_ros_bridge.pseudo_actor import PseudoActor @@ -32,8 +33,10 @@ def __init__(self, parent, communication, actor_list): super(TrafficLightsSensor, self).__init__(parent=parent, communication=communication, - prefix='traffic_lights') + prefix="") self.actor_list = actor_list + self.traffic_light_status = CarlaTrafficLightStatusList() + self.traffic_light_actors = [] def destroy(self): """ @@ -47,9 +50,23 @@ def update(self, frame, timestamp): """ Get the state of all known traffic lights """ - traffic_lights = CarlaTrafficLightStatusList() + traffic_light_status = CarlaTrafficLightStatusList() + traffic_light_actors = [] for actor_id in self.actor_list: actor = self.actor_list[actor_id] if isinstance(actor, TrafficLight): - traffic_lights.traffic_lights.append(actor.get_status()) - self.publish_message(self.get_topic_prefix(), traffic_lights) + traffic_light_actors.append(actor) + traffic_light_status.traffic_lights.append(actor.get_status()) + + if traffic_light_actors != self.traffic_light_actors: + self.traffic_light_actors = traffic_light_actors + traffic_light_info_list = CarlaTrafficLightInfoList() + for traffic_light in traffic_light_actors: + traffic_light_info_list.traffic_lights.append(traffic_light.get_info()) + self.publish_message(self.get_topic_prefix() + "traffic_lights_info", + traffic_light_info_list, is_latched=True) + + if traffic_light_status != self.traffic_light_status: + self.traffic_light_status = traffic_light_status + self.publish_message(self.get_topic_prefix() + "traffic_lights", + traffic_light_status, is_latched=True) diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 01d68095..ad584049 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -22,9 +22,11 @@ from derived_object_msgs.msg import ObjectArray from visualization_msgs.msg import Marker from carla_msgs.msg import (CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, - CarlaActorList) + CarlaActorList, CarlaTrafficLightStatusList, + CarlaTrafficLightInfoList) PKG = 'test_roslaunch' +TIMEOUT = 20 class TestClock(unittest.TestCase): @@ -37,7 +39,7 @@ def test_clock(self): Tests clock """ rospy.init_node('test_node', anonymous=True) - clock_msg = rospy.wait_for_message("/clock", Clock, timeout=15) + clock_msg = rospy.wait_for_message("/clock", Clock, timeout=TIMEOUT) self.assertNotEqual(Clock(), clock_msg) def test_vehicle_status(self): @@ -46,7 +48,7 @@ def test_vehicle_status(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus, timeout=15) + "/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus, timeout=TIMEOUT) self.assertNotEqual(msg.header, Header()) # todo: check frame-id self.assertNotEqual(msg.orientation, Quaternion()) @@ -56,7 +58,7 @@ def test_vehicle_info(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/vehicle_info", CarlaEgoVehicleInfo, timeout=15) + "/carla/ego_vehicle/vehicle_info", CarlaEgoVehicleInfo, timeout=TIMEOUT) self.assertNotEqual(msg.id, 0) self.assertEqual(msg.type, "vehicle.tesla.model3") self.assertEqual(msg.rolename, "ego_vehicle") @@ -80,7 +82,7 @@ def test_odometry(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/odometry", Odometry, timeout=15) + "/carla/ego_vehicle/odometry", Odometry, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "map") self.assertEqual(msg.child_frame_id, "ego_vehicle") self.assertNotEqual(msg.pose, Pose()) @@ -91,7 +93,7 @@ def test_gnss(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/gnss/gnss1/fix", NavSatFix, timeout=15) + "/carla/ego_vehicle/gnss/gnss1/fix", NavSatFix, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/gnss/gnss1") self.assertNotEqual(msg.latitude, 0.0) self.assertNotEqual(msg.longitude, 0.0) @@ -115,7 +117,7 @@ def test_camera_info(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/camera/rgb/front/camera_info", CameraInfo, timeout=15) + "/carla/ego_vehicle/camera/rgb/front/camera_info", CameraInfo, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/rgb/front") self.assertEqual(msg.height, 600) self.assertEqual(msg.width, 800) @@ -126,7 +128,7 @@ def test_camera_image(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/camera/rgb/front/image_color", Image, timeout=15) + "/carla/ego_vehicle/camera/rgb/front/image_color", Image, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/rgb/front") self.assertEqual(msg.height, 600) self.assertEqual(msg.width, 800) @@ -138,7 +140,7 @@ def test_lidar(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/lidar/lidar1/point_cloud", PointCloud2, timeout=15) + "/carla/ego_vehicle/lidar/lidar1/point_cloud", PointCloud2, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/lidar/lidar1") def test_radar(self): @@ -147,7 +149,7 @@ def test_radar(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/radar/front/radar", RadarTargetArray, timeout=15) + "/carla/ego_vehicle/radar/front/radar", RadarTargetArray, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/radar/front") def test_ego_vehicle_objects(self): @@ -165,7 +167,7 @@ def test_objects(self): Tests carla objects """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/objects", ObjectArray, timeout=15) + msg = rospy.wait_for_message("/carla/objects", ObjectArray, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "map") self.assertEqual(len(msg.objects), 1) # only ego vehicle exists @@ -174,7 +176,7 @@ def test_marker(self): Tests marker """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/marker", Marker, timeout=15) + msg = rospy.wait_for_message("/carla/marker", Marker, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle") self.assertNotEqual(msg.id, 0) self.assertEqual(msg.type, 1) @@ -190,7 +192,7 @@ def test_world_info(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/world_info", CarlaWorldInfo, timeout=15) + "/carla/world_info", CarlaWorldInfo, timeout=TIMEOUT) self.assertNotEqual(len(msg.map_name), 0) self.assertNotEqual(len(msg.opendrive), 0) @@ -200,9 +202,27 @@ def test_actor_list(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/actor_list", CarlaActorList, timeout=15) + "/carla/actor_list", CarlaActorList, timeout=TIMEOUT) self.assertNotEqual(len(msg.actors), 0) + def test_traffic_lights(self): + """ + Tests traffic_lights + """ + rospy.init_node('test_node', anonymous=True) + msg = rospy.wait_for_message( + "/carla/traffic_lights", CarlaTrafficLightStatusList, timeout=TIMEOUT) + self.assertNotEqual(len(msg.traffic_lights), 0) + + def test_traffic_lights_info(self): + """ + Tests traffic_lights + """ + rospy.init_node('test_node', anonymous=True) + msg = rospy.wait_for_message( + "/carla/traffic_lights_info", CarlaTrafficLightInfoList, timeout=TIMEOUT) + self.assertNotEqual(len(msg.traffic_lights), 0) + if __name__ == '__main__': rostest.rosrun(PKG, 'tests', TestClock) diff --git a/carla_ros_bridge/test/ros_bridge_client.test b/carla_ros_bridge/test/ros_bridge_client.test index a8740c08..8362066d 100644 --- a/carla_ros_bridge/test/ros_bridge_client.test +++ b/carla_ros_bridge/test/ros_bridge_client.test @@ -1,13 +1,20 @@ + + - + + + + + + From 32608114667168625a35ece23df0d67b9b0bbeb3 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 27 Mar 2020 11:49:02 +0100 Subject: [PATCH 036/627] Fix carla_msgs submodule --- carla_msgs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_msgs b/carla_msgs index 1df89a32..cf488bb9 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 1df89a326ea413668f7120a72d43f075a6575e35 +Subproject commit cf488bb9bca9e745e3159b1edc884c282d328012 From 1a0d4a44e2ee9eadb2b13ce5569f04b751392962 Mon Sep 17 00:00:00 2001 From: ll7 <32880741+ll7@users.noreply.github.com> Date: Tue, 31 Mar 2020 16:37:01 +0200 Subject: [PATCH 037/627] typo in the second export Replace := with = in the export SCENARIO_RUNNER_PATH --- carla_ad_demo/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_demo/README.md b/carla_ad_demo/README.md index cc134da3..2bcb2299 100644 --- a/carla_ad_demo/README.md +++ b/carla_ad_demo/README.md @@ -10,7 +10,7 @@ The Node setup is visualized [here](../docs/images/ad_demo.png "AD Demo Node Set ## Startup export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ - export SCENARIO_RUNNER_PATH:= + export SCENARIO_RUNNER_PATH= roslaunch carla_ad_demo carla_ad_demo_with_rviz.launch ### Modes From 0eb9c0d1f6841926cf3895a7d89b84852bcff788 Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Thu, 16 Apr 2020 10:23:48 +0200 Subject: [PATCH 038/627] Add support to load opendrive map --- CHANGELOG.md | 2 ++ README.md | 22 ++++++++++++++----- .../src/carla_ad_agent/local_planner.py | 5 ----- .../carla_ego_vehicle/carla_ego_vehicle.py | 11 +++++++++- ...ros_bridge_with_example_ego_vehicle.launch | 10 +++++++-- .../src/carla_ros_bridge/bridge.py | 19 +++++++++++----- .../carla_twist_to_control.py | 6 ++++- 7 files changed, 55 insertions(+), 20 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 892ac42d..e4d383c0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,7 +1,9 @@ ## Latest changed +* Support loading OpenDRIVE map * Traffic Lights: Only publish to /carla/traffic_lights on change * Traffic Lights: Publish /carla/traffic_lights_info, containing the location and the trigger volume + ## CARLA-ROS-Bridge 0.9.8 * change Lidar range in meters diff --git a/README.md b/README.md index 9abd0ad9..d6691720 100644 --- a/README.md +++ b/README.md @@ -103,22 +103,32 @@ Start the ros bridge (choose one option): # Option 2: start the ros bridge together with an example ego vehicle roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch -## Settings +## Configuration -You can setup the ros bridge configuration [carla_ros_bridge/config/settings.yaml](carla_ros_bridge/config/settings.yaml). +### Settings file + +You can modify the ros bridge configuration by editing [carla_ros_bridge/config/settings.yaml](carla_ros_bridge/config/settings.yaml). If the rolename is within the list specified by ROS parameter `/carla/ego_vehicle/rolename`, the client is interpreted as an controllable ego vehicle and all relevant ROS topics are created. -### Mode +### Launch file + +Certain parameters can be set within the launch file [carla_ros_bridge.launch](carla_ros_bridge/launch/carla_ros_bridge.launch). + +#### Map + +The bridge is able to load a CARLA map by setting the launch-file parameter ```town```. Either specify an available CARLA Town (e.g. 'Town01') or a OpenDRIVE file (with ending '.xodr'). + +#### Mode -#### Default Mode +##### Default Mode In default mode (`synchronous_mode: false`) data is published: - on every `world.on_tick()` callback - on every `sensor.listen()` callback -#### Synchronous Mode +##### Synchronous Mode CAUTION: In synchronous mode, only the ros-bridge is allowed to tick. Other CARLA clients must passively wait. @@ -126,7 +136,7 @@ In synchronous mode (`synchronous_mode: true`), the bridge waits for all sensor Additionally you might set `synchronous_mode_wait_for_vehicle_control_command` to `true` to wait for a vehicle control command before executing the next tick. -##### Control Synchronous Mode +###### Control Synchronous Mode It is possible to control the simulation execution: diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index ab14dfca..a978634c 100644 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -52,7 +52,6 @@ def __init__(self, role_name, opt_dict=None): PID controller {'K_P':, 'K_D':, 'K_I'} """ - self._current_waypoint = None self.target_waypoint = None self._vehicle_controller = None self._global_plan = None @@ -127,7 +126,6 @@ def _init_controller(self, opt_dict): if 'longitudinal_control_dict' in opt_dict: args_longitudinal_dict = opt_dict['longitudinal_control_dict'] - self._current_waypoint = self.get_waypoint(self._current_pose.position) self._vehicle_controller = VehiclePIDController(args_lateral=args_lateral_dict, args_longitudinal=args_longitudinal_dict) @@ -167,9 +165,6 @@ def run_step(self, target_speed): else: break - # current vehicle waypoint - self._current_waypoint = self.get_waypoint(self._current_pose.position) - # target waypoint target_route_point = self._waypoint_buffer[0] diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index c7b12eba..c32e0c76 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -180,8 +180,17 @@ def setup_sensors(self, sensors): """ actors = [] bp_library = self.world.get_blueprint_library() + sensor_rolenames = [] for sensor_spec in sensors: try: + if sensor_spec['id'] in sensor_rolenames: + rospy.logfatal( + "Sensor rolename '{}' is only allowed to be used once.".format( + sensor_spec['id'])) + raise NameError( + "Sensor rolename '{}' is only allowed to be used once.".format( + sensor_spec['id'])) + sensor_rolenames.append(sensor_spec['id']) bp = bp_library.find(str(sensor_spec['type'])) bp.set_attribute('role_name', str(sensor_spec['id'])) if sensor_spec['type'].startswith('sensor.camera'): @@ -305,7 +314,7 @@ def setup_sensors(self, sensors): except KeyError as e: rospy.logfatal( "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) - continue + raise e # create sensor sensor_transform = carla.Transform(sensor_location, sensor_rotation) diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index c40db57b..f95507f2 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -1,12 +1,18 @@ + + + - - + + + + + diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 4da77024..085d1359 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -52,7 +52,7 @@ class CarlaRosBridge(object): Carla Ros bridge """ - CARLA_VERSION = "0.9.6" + CARLA_VERSION = "0.9.8" def __init__(self, carla_world, params): """ @@ -502,14 +502,23 @@ def main(): carla_world = carla_client.get_world() - if "town" in parameters and carla_world.get_map().name != parameters["town"]: - rospy.loginfo("Loading new town: {} (previous: {})".format( - parameters["town"], carla_world.get_map().name)) - carla_world = carla_client.load_world(parameters["town"]) + if "town" in parameters: + if parameters["town"].endswith(".xodr"): + rospy.loginfo("Loading opendrive world from file '{}'".format(parameters["town"])) + with open(parameters["town"]) as od_file: + data = od_file.read() + carla_world = carla_client.generate_opendrive_world(str(data)) + else: + if carla_world.get_map().name != parameters["town"]: + rospy.loginfo("Loading town '{}' (previous: '{}').".format( + parameters["town"], carla_world.get_map().name)) + carla_world = carla_client.load_world(parameters["town"]) carla_world.tick() carla_bridge = CarlaRosBridge(carla_client.get_world(), parameters) carla_bridge.run() + except (IOError, RuntimeError) as e: + rospy.logerr("Error: {}".format(e)) finally: del carla_world del carla_client diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index dea8861a..5a435099 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -73,7 +73,11 @@ def twist_received(self, twist): else: control.steer = -max(-self.max_steering_angle, twist.angular.z) / \ self.max_steering_angle - self.pub.publish(control) + try: + self.pub.publish(control) + except rospy.ROSException as e: + if not rospy.is_shutdown(): + rospy.logwarn("Error while publishing control: {}".format(e)) def main(): From 274589373822001754d4648f99b28183e11d6a6e Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 16 Apr 2020 11:52:09 +0200 Subject: [PATCH 039/627] Object-sensor: Fix object-twist (was published in vehicle-frame) --- CHANGELOG.md | 1 + carla_ros_bridge/src/carla_ros_bridge/actor.py | 15 +++++++++++++-- .../src/carla_ros_bridge/traffic_participant.py | 2 +- .../src/carla_ros_bridge/transforms.py | 9 ++++++--- 4 files changed, 21 insertions(+), 6 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index e4d383c0..ec450e79 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* ObjectSensor: Fix object twist * Support loading OpenDRIVE map * Traffic Lights: Only publish to /carla/traffic_lights on change * Traffic Lights: Publish /carla/traffic_lights_info, containing the location and the trigger volume diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index c4ab05b9..23b46735 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -66,9 +66,9 @@ def get_current_ros_pose(self): return trans.carla_transform_to_ros_pose( self.carla_actor.get_transform()) - def get_current_ros_twist(self): + def get_current_ros_twist_rotated(self): """ - Function to provide the current ROS twist + Function to provide the current ROS twist rotated :return: the ROS twist of this actor :rtype: geometry_msgs.msg.Twist @@ -78,6 +78,17 @@ def get_current_ros_twist(self): self.carla_actor.get_angular_velocity(), self.carla_actor.get_transform().rotation) + def get_current_ros_twist(self): + """ + Function to provide the current ROS twist + + :return: the ROS twist of this actor + :rtype: geometry_msgs.msg.Twist + """ + return trans.carla_velocity_to_ros_twist( + self.carla_actor.get_velocity(), + self.carla_actor.get_angular_velocity()) + def get_current_ros_accel(self): """ Function to provide the current ROS accel diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index fcf62d8c..1f28439e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -68,7 +68,7 @@ def send_odometry(self): odometry = Odometry(header=self.get_msg_header("map")) odometry.child_frame_id = self.get_prefix() odometry.pose.pose = self.get_current_ros_pose() - odometry.twist.twist = self.get_current_ros_twist() + odometry.twist.twist = self.get_current_ros_twist_rotated() self.publish_message(self.get_topic_prefix() + "/odometry", odometry) def get_object_info(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/transforms.py b/carla_ros_bridge/src/carla_ros_bridge/transforms.py index 3c7a143b..8b6ee7be 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/transforms.py +++ b/carla_ros_bridge/src/carla_ros_bridge/transforms.py @@ -207,7 +207,7 @@ def carla_vector_to_ros_vector_rotated(carla_vector, carla_rotation): return ros_vector -def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, carla_rotation): +def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, carla_rotation=None): """ Convert a carla velocity to a ROS twist @@ -218,13 +218,16 @@ def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, c :type carla_velocity: carla.Vector3D :param carla_angular_velocity: the carla angular velocity :type carla_angular_velocity: carla.Vector3D - :param carla_rotation: the carla rotation + :param carla_rotation: the carla rotation. If None, no rotation is executed :type carla_rotation: carla.Rotation :return: a ROS twist (with rotation) :rtype: geometry_msgs.msg.Twist """ ros_twist = Twist() - ros_twist.linear = carla_vector_to_ros_vector_rotated(carla_linear_velocity, carla_rotation) + if carla_rotation: + ros_twist.linear = carla_vector_to_ros_vector_rotated(carla_linear_velocity, carla_rotation) + else: + ros_twist.linear = carla_location_to_ros_vector3(carla_linear_velocity) ros_twist.angular.x = math.radians(carla_angular_velocity.x) ros_twist.angular.y = -math.radians(carla_angular_velocity.y) ros_twist.angular.z = -math.radians(carla_angular_velocity.z) From 17e161adb906ae8599c51d396152fde0bdcda819 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Apr 2020 09:27:45 +0200 Subject: [PATCH 040/627] carla_ego_vehicle: fix check for duplicate sensor role names --- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index c32e0c76..52955a5c 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -180,17 +180,18 @@ def setup_sensors(self, sensors): """ actors = [] bp_library = self.world.get_blueprint_library() - sensor_rolenames = [] + sensor_names = [] for sensor_spec in sensors: try: - if sensor_spec['id'] in sensor_rolenames: + sensor_name = str(sensor_spec['type']) + "/" + str(sensor_spec['id']) + if sensor_name in sensor_names: rospy.logfatal( "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) raise NameError( "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) - sensor_rolenames.append(sensor_spec['id']) + sensor_names.append(sensor_name) bp = bp_library.find(str(sensor_spec['type'])) bp.set_attribute('role_name', str(sensor_spec['id'])) if sensor_spec['type'].startswith('sensor.camera'): From 80d1e0656564c92d9654adf3a5b748936e1aaf66 Mon Sep 17 00:00:00 2001 From: Fabian Oboril Date: Fri, 24 Apr 2020 11:44:18 +0200 Subject: [PATCH 041/627] Added Timeout ROS-Parameter for CARLA Server communication --- CHANGELOG.md | 1 + .../launch/carla_ros_bridge_with_ackermann_control.launch | 3 --- carla_ad_demo/launch/carla_ad_demo.launch | 6 ++++++ carla_ad_demo/launch/carla_ad_demo_with_rviz.launch | 4 ++++ carla_ego_vehicle/launch/carla_ego_vehicle.launch | 2 ++ carla_ego_vehicle/launch/carla_example_ego_vehicle.launch | 2 ++ .../src/carla_ego_vehicle/carla_ego_vehicle.py | 3 ++- carla_infrastructure/launch/carla_infrastructure.launch | 2 ++ .../src/carla_infrastructure/carla_infrastructure.py | 3 ++- carla_ros_bridge/config/settings.yaml | 1 + carla_ros_bridge/launch/carla_ros_bridge.launch | 2 ++ .../launch/carla_ros_bridge_with_example_ego_vehicle.launch | 3 +++ carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- carla_spectator_camera/launch/carla_spectator_camera.launch | 2 ++ .../src/carla_spectator_camera/carla_spectator_camera.py | 3 ++- .../launch/carla_waypoint_publisher.launch | 2 ++ .../carla_waypoint_publisher/carla_waypoint_publisher.py | 3 ++- 17 files changed, 36 insertions(+), 8 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index ec450e79..5efa82e9 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,6 +4,7 @@ * Support loading OpenDRIVE map * Traffic Lights: Only publish to /carla/traffic_lights on change * Traffic Lights: Publish /carla/traffic_lights_info, containing the location and the trigger volume +* Added ROS Parameter to set the CARLA client timeout value for all nodes consistently ## CARLA-ROS-Bridge 0.9.8 diff --git a/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch b/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch index fcfedfee..c53090d9 100644 --- a/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch +++ b/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch @@ -1,8 +1,5 @@ - - - diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index c679c7bf..c80c1e04 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -6,6 +6,7 @@ + @@ -32,6 +33,7 @@ + @@ -41,6 +43,7 @@ + @@ -56,6 +59,9 @@ + + + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch index 2efff80c..e560d76f 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch @@ -4,6 +4,7 @@ + @@ -31,6 +32,7 @@ + @@ -46,6 +48,7 @@ + @@ -73,6 +76,7 @@ + diff --git a/carla_ego_vehicle/launch/carla_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_ego_vehicle.launch index 729bcf5b..841f2f40 100644 --- a/carla_ego_vehicle/launch/carla_ego_vehicle.launch +++ b/carla_ego_vehicle/launch/carla_ego_vehicle.launch @@ -2,6 +2,7 @@ + @@ -12,6 +13,7 @@ + + @@ -22,6 +23,7 @@ + @@ -30,6 +32,7 @@ + diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 085d1359..09d0d368 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -498,7 +498,7 @@ def main(): carla_client = carla.Client( host=parameters['host'], port=parameters['port']) - carla_client.set_timeout(2.0) + carla_client.set_timeout(parameters['timeout']) carla_world = carla_client.get_world() diff --git a/carla_spectator_camera/launch/carla_spectator_camera.launch b/carla_spectator_camera/launch/carla_spectator_camera.launch index 8213f154..16c10aec 100644 --- a/carla_spectator_camera/launch/carla_spectator_camera.launch +++ b/carla_spectator_camera/launch/carla_spectator_camera.launch @@ -2,6 +2,7 @@ + @@ -9,6 +10,7 @@ + diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 4d1c3201..f3e0a538 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -45,6 +45,7 @@ def __init__(self): self.camera_fov = rospy.get_param("~fov", 50) self.host = rospy.get_param('/carla/host', '127.0.0.1') self.port = rospy.get_param('/carla/port', '2000') + self.timeout = rospy.get_param("/carla/timeout", 2) self.world = None self.pose = None self.camera_actor = None @@ -162,7 +163,7 @@ def run(self): rospy.loginfo("CARLA world available. Waiting for ego vehicle...") client = carla.Client(self.host, self.port) - client.set_timeout(2.0) + client.set_timeout(self.timeout) self.world = client.get_world() try: diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch index 90451407..c33ca134 100644 --- a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch @@ -2,10 +2,12 @@ + + diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 95191278..a11a3df5 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -266,13 +266,14 @@ def main(): host = rospy.get_param("/carla/host", "127.0.0.1") port = rospy.get_param("/carla/port", 2000) + timeout = rospy.get_param("/carla/timeout", 2) rospy.loginfo("CARLA world available. Trying to connect to {host}:{port}".format( host=host, port=port)) try: carla_client = carla.Client(host=host, port=port) - carla_client.set_timeout(2) + carla_client.set_timeout(timeout) carla_world = carla_client.get_world() From 47cdee1870900c141c5ce69c0f61ea09e1ea2931 Mon Sep 17 00:00:00 2001 From: himanshugoswami <41889803+himanshugoswami@users.noreply.github.com> Date: Fri, 24 Apr 2020 20:38:56 +0530 Subject: [PATCH 042/627] Adding script for creating debian package for carla-ros-bridge packages (#265) --- CreateROSbridgeDebian.sh | 119 +++++++++++++++++++++++++++++ README.md | 4 +- packaging/CreateROSbridgeDebian.sh | 119 +++++++++++++++++++++++++++++ 3 files changed, 240 insertions(+), 2 deletions(-) create mode 100644 CreateROSbridgeDebian.sh create mode 100644 packaging/CreateROSbridgeDebian.sh diff --git a/CreateROSbridgeDebian.sh b/CreateROSbridgeDebian.sh new file mode 100644 index 00000000..7b820a90 --- /dev/null +++ b/CreateROSbridgeDebian.sh @@ -0,0 +1,119 @@ +#!/bin/sh + +#This script builds debian package for CARLA ROS Bridge +#Tested with Ubuntu 14.04, 16.04, 18.04 and 19.10 + +sudo apt-get install build-essential dh-make + +#Adding maintainer name +DEBFULLNAME=Carla\ Simulator\ Team +export DEBFULLNAME + +#carla-ros-bridge github repository +ROS_BRIDGE_GIT=https://github.com/carla-simulator/ros-bridge.git + +mkdir -p carla-ros-debian/carla-ros-bridge/catkin_ws/src +mkdir -p carla-ros-debian/carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ + +cd carla-ros-debian/carla-ros-bridge + +#cloning carla-ros-bridge git repository +git clone ${ROS_BRIDGE_GIT} +rm -r ros-bridge/carla_msgs +cp -a ros-bridge/* catkin_ws/src/ + +cd catkin_ws + +source /opt/ros/$(rosversion -d)/setup.bash + +#installing required dependency packages to build catkin_make +sudo apt install ros-$(rosversion -d)-ainstein-radar-msgs ros-$(rosversion -d)-derived-object-msgs \ +ros-$(rosversion -d)-ackermann-msgs ros-$(rosversion -d)-carla-msgs ros-$(rosversion -d)-pcl-conversions \ +ros-$(rosversion -d)-rviz ros-$(rosversion -d)-rqt ros-$(rosversion -d)-pcl-ros + +catkin_make install + +cp -r install ../../carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ + +cd ../../carla-ros-bridge-$(rosversion -d)-0.9.8/ +mv carla-ros-bridge/install carla-ros-bridge/$(rosversion -d) + +rm Makefile + +#Making debian package to install Carla-ros-bridge in /opt folder +cat >> Makefile <> control < +Build-Depends: debhelper (>= 9) +Standards-Version:0.9.7 +Homepage: https://github.com/carla-simulator/ros-bridge + +Package: carla-ros-bridge-$(rosversion -d) +Architecture: amd64 +Depends: ros-$(rosversion -d)-carla-msgs, + ros-$(rosversion -d)-roslaunch, + ros-$(rosversion -d)-catkin, + ros-$(rosversion -d)-rospy, + ros-$(rosversion -d)-nav-msgs, + ros-$(rosversion -d)-ackermann-msgs, + ros-$(rosversion -d)-std-msgs, + ros-$(rosversion -d)-dynamic-reconfigure, + ros-$(rosversion -d)-topic-tools, + ros-$(rosversion -d)-sensor-msgs, + ros-$(rosversion -d)-message-runtime, + ros-$(rosversion -d)-geometry-msgs, + ros-$(rosversion -d)-message-generation, + ros-$(rosversion -d)-ainstein-radar-msgs, + ros-$(rosversion -d)-visualization-msgs, + ros-$(rosversion -d)-tf, + ros-$(rosversion -d)-tf2, + ros-$(rosversion -d)-rviz, + ros-$(rosversion -d)-cv-bridge, + ros-$(rosversion -d)-rosbag-storage, + ros-$(rosversion -d)-derived-object-msgs, + ros-$(rosversion -d)-shape-msgs, + ros-$(rosversion -d)-tf2-msgs, + ros-$(rosversion -d)-rosgraph-msgs, + ros-$(rosversion -d)-roscpp, + ros-$(rosversion -d)-pcl-conversions, + ros-$(rosversion -d)-pcl-ros, + ros-$(rosversion -d)-rostopic, + ros-$(rosversion -d)-rqt-gui-py +Description: The carla_ros_bridge package aims at providing a simple ROS bridge for CARLA simulator. +EOF + +rm copyright +cp ../../../carla-ros-bridge/ros-bridge/LICENSE ./copyright + + +#Updating debian/Changelog +awk '{sub(/UNRELEASED/,"stable")}1' changelog > tmp && mv tmp changelog +awk '{sub(/unstable/,"stable")}1' changelog > tmp && mv tmp changelog + +cd .. + +dpkg-buildpackage -uc -us -b #building debian package + +#install debian package using "sudo dpkg -i ../carla_ros-bridge-_amd64.deb" + diff --git a/README.md b/README.md index d6691720..6c7aaebb 100644 --- a/README.md +++ b/README.md @@ -38,11 +38,11 @@ First add the apt repository: ##### For ROS Melodic Users sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 81061A1A042F527D && - sudo add-apt-repository "deb [trusted=yes] http://dist.carla.org/carla-ros-bridge-melodic/ bionic main" + sudo add-apt-repository "deb [arch=amd64 trusted=yes] http://dist.carla.org/carla-ros-bridge-melodic/ bionic main" ##### For ROS Kinetic Users sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 9BE2A0CDC0161D6C && - sudo add-apt-repository "deb [trusted=yes] http://dist.carla.org/carla-ros-bridge-kinetic xenial main" + sudo add-apt-repository "deb [arch=amd64 trusted=yes] http://dist.carla.org/carla-ros-bridge-kinetic xenial main" Then simply install the ROS bridge: diff --git a/packaging/CreateROSbridgeDebian.sh b/packaging/CreateROSbridgeDebian.sh new file mode 100644 index 00000000..7b820a90 --- /dev/null +++ b/packaging/CreateROSbridgeDebian.sh @@ -0,0 +1,119 @@ +#!/bin/sh + +#This script builds debian package for CARLA ROS Bridge +#Tested with Ubuntu 14.04, 16.04, 18.04 and 19.10 + +sudo apt-get install build-essential dh-make + +#Adding maintainer name +DEBFULLNAME=Carla\ Simulator\ Team +export DEBFULLNAME + +#carla-ros-bridge github repository +ROS_BRIDGE_GIT=https://github.com/carla-simulator/ros-bridge.git + +mkdir -p carla-ros-debian/carla-ros-bridge/catkin_ws/src +mkdir -p carla-ros-debian/carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ + +cd carla-ros-debian/carla-ros-bridge + +#cloning carla-ros-bridge git repository +git clone ${ROS_BRIDGE_GIT} +rm -r ros-bridge/carla_msgs +cp -a ros-bridge/* catkin_ws/src/ + +cd catkin_ws + +source /opt/ros/$(rosversion -d)/setup.bash + +#installing required dependency packages to build catkin_make +sudo apt install ros-$(rosversion -d)-ainstein-radar-msgs ros-$(rosversion -d)-derived-object-msgs \ +ros-$(rosversion -d)-ackermann-msgs ros-$(rosversion -d)-carla-msgs ros-$(rosversion -d)-pcl-conversions \ +ros-$(rosversion -d)-rviz ros-$(rosversion -d)-rqt ros-$(rosversion -d)-pcl-ros + +catkin_make install + +cp -r install ../../carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ + +cd ../../carla-ros-bridge-$(rosversion -d)-0.9.8/ +mv carla-ros-bridge/install carla-ros-bridge/$(rosversion -d) + +rm Makefile + +#Making debian package to install Carla-ros-bridge in /opt folder +cat >> Makefile <> control < +Build-Depends: debhelper (>= 9) +Standards-Version:0.9.7 +Homepage: https://github.com/carla-simulator/ros-bridge + +Package: carla-ros-bridge-$(rosversion -d) +Architecture: amd64 +Depends: ros-$(rosversion -d)-carla-msgs, + ros-$(rosversion -d)-roslaunch, + ros-$(rosversion -d)-catkin, + ros-$(rosversion -d)-rospy, + ros-$(rosversion -d)-nav-msgs, + ros-$(rosversion -d)-ackermann-msgs, + ros-$(rosversion -d)-std-msgs, + ros-$(rosversion -d)-dynamic-reconfigure, + ros-$(rosversion -d)-topic-tools, + ros-$(rosversion -d)-sensor-msgs, + ros-$(rosversion -d)-message-runtime, + ros-$(rosversion -d)-geometry-msgs, + ros-$(rosversion -d)-message-generation, + ros-$(rosversion -d)-ainstein-radar-msgs, + ros-$(rosversion -d)-visualization-msgs, + ros-$(rosversion -d)-tf, + ros-$(rosversion -d)-tf2, + ros-$(rosversion -d)-rviz, + ros-$(rosversion -d)-cv-bridge, + ros-$(rosversion -d)-rosbag-storage, + ros-$(rosversion -d)-derived-object-msgs, + ros-$(rosversion -d)-shape-msgs, + ros-$(rosversion -d)-tf2-msgs, + ros-$(rosversion -d)-rosgraph-msgs, + ros-$(rosversion -d)-roscpp, + ros-$(rosversion -d)-pcl-conversions, + ros-$(rosversion -d)-pcl-ros, + ros-$(rosversion -d)-rostopic, + ros-$(rosversion -d)-rqt-gui-py +Description: The carla_ros_bridge package aims at providing a simple ROS bridge for CARLA simulator. +EOF + +rm copyright +cp ../../../carla-ros-bridge/ros-bridge/LICENSE ./copyright + + +#Updating debian/Changelog +awk '{sub(/UNRELEASED/,"stable")}1' changelog > tmp && mv tmp changelog +awk '{sub(/unstable/,"stable")}1' changelog > tmp && mv tmp changelog + +cd .. + +dpkg-buildpackage -uc -us -b #building debian package + +#install debian package using "sudo dpkg -i ../carla_ros-bridge-_amd64.deb" + From 83f8285183bc9733b6792a1ff9bfd0c93837e7c5 Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Mon, 27 Apr 2020 10:19:42 +0200 Subject: [PATCH 043/627] AD Agent make querying waypoints optional if risk is not avoided (#262) * add carla_walker_agent * Add abbility to set weather parameters --- CHANGELOG.md | 1 + README.md | 15 + carla_ad_agent/src/carla_ad_agent/agent.py | 41 +- .../src/carla_ad_agent/basic_agent.py | 49 +- .../src/carla_ad_agent/carla_ad_agent.py | 30 +- .../src/carla_ad_agent/local_planner.py | 76 +-- .../config/FollowLeadingVehicle.xosc | 532 +++++++++--------- carla_ad_demo/launch/carla_ad_demo.launch | 2 +- .../launch/carla_ad_demo_with_rviz.launch | 7 +- .../launch/carla_ego_vehicle.launch | 4 +- carla_msgs | 2 +- carla_ros_bridge/config/settings.yaml | 2 +- .../src/carla_ros_bridge/actor.py | 14 +- .../src/carla_ros_bridge/bridge.py | 28 +- .../src/carla_ros_bridge/camera.py | 4 +- .../src/carla_ros_bridge/ego_vehicle.py | 6 +- .../src/carla_ros_bridge/lidar.py | 4 +- .../src/carla_ros_bridge/sensor.py | 11 +- .../carla_ros_bridge/traffic_participant.py | 2 +- .../src/carla_ros_bridge/vehicle.py | 15 - .../src/carla_ros_bridge/walker.py | 20 +- .../launch/carla_ros_scenario_runner.launch | 4 + .../carla_ros_scenario_runner.py | 52 +- .../msg/CarlaScenario.msg | 2 +- .../carla_twist_to_control.py | 10 +- carla_walker_agent/CMakeLists.txt | 27 + carla_walker_agent/README.md | 9 + .../launch/carla_walker_agent.launch | 13 + carla_walker_agent/package.xml | 18 + carla_walker_agent/setup.py | 10 + .../src/carla_walker_agent/__init__.py | 0 .../carla_walker_agent/carla_walker_agent.py | 136 +++++ 32 files changed, 718 insertions(+), 428 deletions(-) create mode 100644 carla_walker_agent/CMakeLists.txt create mode 100644 carla_walker_agent/README.md create mode 100644 carla_walker_agent/launch/carla_walker_agent.launch create mode 100644 carla_walker_agent/package.xml create mode 100644 carla_walker_agent/setup.py create mode 100644 carla_walker_agent/src/carla_walker_agent/__init__.py create mode 100755 carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py diff --git a/CHANGELOG.md b/CHANGELOG.md index 5efa82e9..a8bfdb17 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Rework tf frame names * ObjectSensor: Fix object twist * Support loading OpenDRIVE map * Traffic Lights: Only publish to /carla/traffic_lights on change diff --git a/README.md b/README.md index 6c7aaebb..92f461ce 100644 --- a/README.md +++ b/README.md @@ -24,6 +24,7 @@ Beside the bridging functionality, there are many more features provided in sepa | [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. | | [Carla Ackermann Control](carla_ackermann_control/README.md) | A controller to convert ackermann commands to steer/throttle/brake| | [Carla AD Agent](carla_ad_agent/README.md) | A basic AD agent, that follows a route, avoids collisions with other vehicles and stops on red traffic lights. | +| [Carla Walker Agent](carla_walker_agent/README.md) | A basic walker agent, that follows a route. | | [RVIZ Carla Plugin](rviz_carla_plugin/README.md) | A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. | | [RQT Carla Plugin](rqt_carla_plugin/README.md) | A [RQT](http://wiki.ros.org/rqt) plugin to control CARLA. | @@ -275,6 +276,7 @@ You can find further documentation [here](carla_ackermann_control/README.md). | `/carla/actor_list` | [carla_msgs.CarlaActorList](carla_msgs/msg/CarlaActorList.msg) | list of all carla actors | | `/carla/traffic_lights` | [carla_msgs.CarlaTrafficLightStatusList](carla_msgs/msg/CarlaTrafficLightStatusList.msg) | list of all traffic lights with their status | | `/carla/traffic_lights_info` | [carla_msgs.CarlaTrafficLightInfoList](carla_msgs/msg/CarlaTrafficLightInfoList.msg) | static information for all traffic lights (e.g. position)| +| `/carla/weather_control` | [carla_msgs.CarlaWeatherParameters](carla_msgs/msg/CarlaWeatherParameters.msg) | set the CARLA weather parameters| #### Status of CARLA @@ -296,6 +298,19 @@ You can find further documentation [here](carla_ackermann_control/README.md). | ------------------------------ | ---------------------------------------------------------------------------- | ------------------- | | `/carla/vehicle//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of vehicle | +### TF + +The tf data is published for all traffic participants and sensors. + +#### TF for traffic participants + +The `child_frame_id` corresponds with the CARLA actor id. +If a role name is specified, an additional (static) transform with role name as child_frame_id is published. + +#### TF for sensors + +Sensors publish the transform, when the measurement is done. The `child_frame_id` corresponds with the prefix of the sensor topics. + ### Debug Marker It is possible to draw markers in CARLA. diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index c1cc8c55..531898ae 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -33,7 +33,7 @@ class Agent(object): Base class for agent """ - def __init__(self, role_name, vehicle_id): + def __init__(self, role_name, vehicle_id, avoid_risk): """ """ self._proximity_threshold = 10.0 # meters @@ -44,27 +44,30 @@ def __init__(self, role_name, vehicle_id): self._vehicle_id = vehicle_id self._last_traffic_light = None - rospy.wait_for_service('/carla_waypoint_publisher/{}/get_waypoint'.format(role_name)) + if avoid_risk: + rospy.wait_for_service('/carla_waypoint_publisher/{}/get_waypoint'.format(role_name)) - self._get_waypoint_client = rospy.ServiceProxy( - '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) + self._get_waypoint_client = rospy.ServiceProxy( + '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) - self._traffic_lights = [] - self._traffic_light_status_subscriber = rospy.Subscriber( - "/carla/traffic_lights", CarlaTrafficLightStatusList, self.traffic_lights_updated) + self._traffic_lights = [] + self._traffic_light_status_subscriber = rospy.Subscriber( + "/carla/traffic_lights", CarlaTrafficLightStatusList, self.traffic_lights_updated) - self._world_info_subscriber = rospy.Subscriber( - "/carla/world_info", CarlaWorldInfo, self.world_info_updated) + self._world_info_subscriber = rospy.Subscriber( + "/carla/world_info", CarlaWorldInfo, self.world_info_updated) def traffic_lights_updated(self, traffic_lights): """ callback on new traffic light list + Only used if risk should be avoided. """ self._traffic_lights = traffic_lights.traffic_lights def world_info_updated(self, world_info): """ callback on new world info + Only used if risk should be avoided. """ self._map_name = world_info.map_name @@ -81,14 +84,6 @@ def odometry_updated(self, odo): ) _, _, self._vehicle_yaw = euler_from_quaternion(quaternion) - def run_step(self, target_speed): # pylint: disable=no-self-use,unused-argument - """ - Execute one step of navigation. - :return: control - """ - control = CarlaEgoVehicleControl() - return control - def _is_light_red(self, lights_list): """ Method to check if there is a red light affecting us. This version of @@ -144,7 +139,8 @@ def _is_light_red_europe_style(self, lights_list): def get_waypoint(self, location): """ - Helper to get waypoint for location via ros service + Helper to get waypoint for location via ros service. + Only used if risk should be avoided. """ if rospy.is_shutdown(): return None @@ -177,8 +173,13 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc # It is too late. Do not block the intersection! Keep going! return (False, None) - if self._local_planner.target_waypoint is not None: - if self._local_planner.target_waypoint.is_junction: + if self._local_planner.target_route_point is not None: + target_waypoint = self.get_waypoint(self._local_planner.target_route_point.position) + if not target_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for target route point.") + return (False, None) + if target_waypoint.is_junction: min_angle = 180.0 sel_magnitude = 0.0 # pylint: disable=unused-variable sel_traffic_light = None diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 91ac8ee1..811ee007 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -10,8 +10,10 @@ target destination. This agent respects traffic lights and other vehicles. """ +import math import rospy from nav_msgs.msg import Odometry +from geometry_msgs.msg import Pose from derived_object_msgs.msg import ObjectArray from carla_msgs.msg import CarlaActorList from agent import Agent, AgentState @@ -28,35 +30,38 @@ class BasicAgent(Agent): def __init__(self, role_name, ego_vehicle_id, avoid_risk=True): """ """ - super(BasicAgent, self).__init__(role_name, ego_vehicle_id) + super(BasicAgent, self).__init__(role_name, ego_vehicle_id, avoid_risk) + self._avoid_risk = avoid_risk + self._current_speed = 0.0 # Km/h + self._current_pose = Pose() self._proximity_threshold = 10.0 # meters self._state = AgentState.NAVIGATING - self._avoid_risk = avoid_risk args_lateral_dict = { 'K_P': 0.9, 'K_D': 0.0, 'K_I': 0.1} - self._local_planner = LocalPlanner(role_name, - opt_dict={'lateral_control_dict': args_lateral_dict}) + self._local_planner = LocalPlanner(opt_dict={'lateral_control_dict': args_lateral_dict}) - self._vehicle_id_list = [] - self._lights_id_list = [] - self._actors_subscriber = rospy.Subscriber( - "/carla/actor_list", CarlaActorList, self.actors_updated) - self._objects = [] - self._objects_subscriber = rospy.Subscriber( - "/carla/{}/objects".format(role_name), ObjectArray, self.objects_updated) + if self._avoid_risk: + self._vehicle_id_list = [] + self._lights_id_list = [] + self._actors_subscriber = rospy.Subscriber( + "/carla/actor_list", CarlaActorList, self.actors_updated) + self._objects = [] + self._objects_subscriber = rospy.Subscriber( + "/carla/{}/objects".format(role_name), ObjectArray, self.objects_updated) + self._get_actor_waypoint_client = rospy.ServiceProxy( + '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), + GetActorWaypoint) self._odometry_subscriber = rospy.Subscriber( "/carla/{}/odometry".format(role_name), Odometry, self.odometry_updated) - self._get_actor_waypoint_client = rospy.ServiceProxy( - '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), GetActorWaypoint) - def get_actor_waypoint(self, actor_id): """ helper method to get waypoint for actor via ros service + Only used if risk should be avoided. """ try: response = self._get_actor_waypoint_client(actor_id) @@ -69,12 +74,16 @@ def odometry_updated(self, odo): """ callback on new odometry """ - self._local_planner.odometry_updated(odo) + self._current_speed = math.sqrt(odo.twist.twist.linear.x ** 2 + + odo.twist.twist.linear.y ** 2 + + odo.twist.twist.linear.z ** 2) * 3.6 + self._current_pose = odo.pose.pose super(BasicAgent, self).odometry_updated(odo) def actors_updated(self, actors): """ callback on new actor list + Only used if risk should be avoided. """ # retrieve relevant elements for safe navigation, i.e.: traffic lights # and other vehicles @@ -84,11 +93,13 @@ def actors_updated(self, actors): if "vehicle" in actor.type: self._vehicle_id_list.append(actor.id) elif "traffic_light" in actor.type: - self._lights_id_list.append((actor.id, self.get_actor_waypoint(actor.id))) + self._lights_id_list.append( + (actor.id, self.get_actor_waypoint(actor.id))) def objects_updated(self, objects): """ callback on new objects + Only used if risk should be avoided. """ self._objects = objects.objects @@ -97,6 +108,7 @@ def run_step(self, target_speed): Execute one step of navigation. :return: carla.VehicleControl """ + finished = False # is there an obstacle in front of us? hazard_detected = False @@ -124,6 +136,7 @@ def run_step(self, target_speed): else: self._state = AgentState.NAVIGATING # standard local planner behavior - control = self._local_planner.run_step(target_speed) + control, finished = self._local_planner.run_step( + target_speed, self._current_speed, self._current_pose) - return control + return control, finished diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 9c3abff8..3768737a 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -31,8 +31,13 @@ def __init__(self, role_name, target_speed, avoid_risk): rospy.on_shutdown(self.on_shutdown) # wait for ego vehicle - vehicle_info = rospy.wait_for_message( - "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) + vehicle_info = None + try: + vehicle_info = rospy.wait_for_message( + "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) + except rospy.ROSInterruptException as e: + if not rospy.is_shutdown(): + raise e self._route_subscriber = rospy.Subscriber( "/carla/{}/waypoints".format(role_name), Path, self.path_updated) @@ -91,7 +96,10 @@ def run_step(self): self._global_plan.poses) self._route_assigned = True else: - control = self._agent.run_step(self._target_speed) + control, finished = self._agent.run_step(self._target_speed) + if finished: + self._global_plan = None + self._route_assigned = False return control @@ -102,12 +110,18 @@ def run(self): :return: """ - + r = rospy.Rate(10) while not rospy.is_shutdown(): - control = self.run_step() - if control: - control.steer = -control.steer - self.vehicle_control_publisher.publish(control) + if self._global_plan: + control = self.run_step() + if control: + control.steer = -control.steer + self.vehicle_control_publisher.publish(control) + else: + try: + r.sleep() + except rospy.ROSInterruptException: + pass def main(): diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index a978634c..8603d731 100644 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -11,12 +11,8 @@ """ from collections import deque -import math import rospy from geometry_msgs.msg import PointStamped -from geometry_msgs.msg import Pose -from tf.transformations import euler_from_quaternion -from carla_waypoint_types.srv import GetWaypoint from carla_msgs.msg import CarlaEgoVehicleControl from vehicle_pid_controller import VehiclePIDController from misc import distance_vehicle @@ -36,7 +32,7 @@ class LocalPlanner(object): # total distance) MIN_DISTANCE_PERCENTAGE = 0.9 - def __init__(self, role_name, opt_dict=None): + def __init__(self, opt_dict=None): """ :param vehicle: actor to apply to local planner logic onto :param opt_dict: dictionary of arguments with the following semantics: @@ -52,54 +48,18 @@ def __init__(self, role_name, opt_dict=None): PID controller {'K_P':, 'K_D':, 'K_I'} """ - self.target_waypoint = None + self.target_route_point = None self._vehicle_controller = None - self._global_plan = None self._waypoints_queue = deque(maxlen=20000) self._buffer_size = 5 self._waypoint_buffer = deque(maxlen=self._buffer_size) - self._vehicle_yaw = None - self._current_speed = None - self._current_pose = None self._target_point_publisher = rospy.Publisher( "/next_target", PointStamped, queue_size=1) - rospy.wait_for_service('/carla_waypoint_publisher/{}/get_waypoint'.format(role_name)) - - self._get_waypoint_client = rospy.ServiceProxy( - '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) # initializing controller self._init_controller(opt_dict) - def get_waypoint(self, location): - """ - Helper to get waypoint from a ros service - """ - try: - response = self._get_waypoint_client(location) - return response.waypoint - except (rospy.ServiceException, rospy.ROSInterruptException) as e: - if not rospy.is_shutdown: - rospy.logwarn("Service call failed: {}".format(e)) - - def odometry_updated(self, odo): - """ - Callback on new odometry - """ - self._current_speed = math.sqrt(odo.twist.twist.linear.x ** 2 + - odo.twist.twist.linear.y ** 2 + - odo.twist.twist.linear.z ** 2) * 3.6 - - self._current_pose = odo.pose.pose - quaternion = ( - odo.pose.pose.orientation.x, - odo.pose.pose.orientation.y, - odo.pose.pose.orientation.z, - odo.pose.pose.orientation.w - ) - _, _, self._vehicle_yaw = euler_from_quaternion(quaternion) - def _init_controller(self, opt_dict): """ Controller initialization. @@ -108,8 +68,6 @@ def _init_controller(self, opt_dict): :return: """ # default params - self._current_speed = 0.0 # Km/h - self._current_pose = Pose() args_lateral_dict = { 'K_P': 1.95, 'K_D': 0.01, @@ -129,24 +87,22 @@ def _init_controller(self, opt_dict): self._vehicle_controller = VehiclePIDController(args_lateral=args_lateral_dict, args_longitudinal=args_longitudinal_dict) - self._global_plan = False - def set_global_plan(self, current_plan): """ set a global plan to follow """ - self._waypoints_queue.clear() + self.target_route_point = None self._waypoint_buffer.clear() + self._waypoints_queue.clear() for elem in current_plan: self._waypoints_queue.append(elem.pose) - self._global_plan = True - def run_step(self, target_speed): + def run_step(self, target_speed, current_speed, current_pose): """ Execute one step of local planning which involves running the longitudinal and lateral PID controllers to follow the waypoints trajectory. """ - if not self._waypoints_queue: + if not self._waypoint_buffer and not self._waypoints_queue: control = CarlaEgoVehicleControl() control.steer = 0.0 control.throttle = 0.0 @@ -154,7 +110,8 @@ def run_step(self, target_speed): control.hand_brake = False control.manual_gear_shift = False - return control + rospy.loginfo("Route finished.") + return control, True # Buffering the waypoints if not self._waypoint_buffer: @@ -166,20 +123,17 @@ def run_step(self, target_speed): break # target waypoint - target_route_point = self._waypoint_buffer[0] - - # for us redlight-detection - self.target_waypoint = self.get_waypoint(target_route_point.position) + self.target_route_point = self._waypoint_buffer[0] target_point = PointStamped() target_point.header.frame_id = "map" - target_point.point.x = target_route_point.position.x - target_point.point.y = target_route_point.position.y - target_point.point.z = target_route_point.position.z + target_point.point.x = self.target_route_point.position.x + target_point.point.y = self.target_route_point.position.y + target_point.point.z = self.target_route_point.position.z self._target_point_publisher.publish(target_point) # move using PID controllers control = self._vehicle_controller.run_step( - target_speed, self._current_speed, self._current_pose, target_route_point) + target_speed, current_speed, current_pose, self.target_route_point) # purge the queue of obsolete waypoints max_index = -1 @@ -189,10 +143,10 @@ def run_step(self, target_speed): for i, route_point in enumerate(self._waypoint_buffer): if distance_vehicle( - route_point, self._current_pose.position) < min_distance: + route_point, current_pose.position) < min_distance: max_index = i if max_index >= 0: for i in range(max_index + 1): self._waypoint_buffer.popleft() - return control + return control, False diff --git a/carla_ad_demo/config/FollowLeadingVehicle.xosc b/carla_ad_demo/config/FollowLeadingVehicle.xosc index db33827d..7011b7fc 100644 --- a/carla_ad_demo/config/FollowLeadingVehicle.xosc +++ b/carla_ad_demo/config/FollowLeadingVehicle.xosc @@ -1,270 +1,266 @@ - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - - - - - - - - - - -
- - - - - -
- - - - - - - - - - - -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+ + + + + + + + + + + + + + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index c80c1e04..48a21178 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -7,7 +7,7 @@ - + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch index e560d76f..ddde764d 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch @@ -68,7 +68,9 @@ { 'name': 'FollowLeadingVehicle', 'scenario_file': '$(find carla_ad_demo)/config/FollowLeadingVehicle.xosc', - 'destination': { 'position': { 'x': 7.1, 'y': 187.3, 'z': 0.0 } }, + 'waypoints': [ + { 'position': { 'x': 7.1, 'y': 187.3, 'z': 0.0 } } + ], 'target_speed': 15 } ] @@ -79,7 +81,8 @@ - + + diff --git a/carla_ego_vehicle/launch/carla_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_ego_vehicle.launch index 841f2f40..efb0e5f3 100644 --- a/carla_ego_vehicle/launch/carla_ego_vehicle.launch +++ b/carla_ego_vehicle/launch/carla_ego_vehicle.launch @@ -21,8 +21,8 @@ This does not work for multiple ego-vehicles. --> - - + + diff --git a/carla_msgs b/carla_msgs index cf488bb9..708e9c83 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit cf488bb9bca9e745e3159b1edc884c282d328012 +Subproject commit 708e9c830bbd1637f89b5cf49dae8c3a327d021a diff --git a/carla_ros_bridge/config/settings.yaml b/carla_ros_bridge/config/settings.yaml index 93680b24..84c94bcf 100644 --- a/carla_ros_bridge/config/settings.yaml +++ b/carla_ros_bridge/config/settings.yaml @@ -16,4 +16,4 @@ carla: # the role name of the vehicles that acts as ego vehicle for this ros bridge instance # Only the vehicles within this list are controllable from within ROS. # (the vehicle from CARLA is selected which has the attribute 'role_name' set to this value) - role_name: ["hero", "ego_vehicle"] + role_name: ["hero", "ego_vehicle", "hero1", "hero2", "hero3"] diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 23b46735..da417ca6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -107,7 +107,7 @@ def get_id(self): """ return self.carla_actor_id - def get_ros_transform(self, transform=None): + def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ Function to provide the current ROS transform @@ -115,10 +115,16 @@ def get_ros_transform(self, transform=None): :rtype: geometry_msgs.msg.TransformStamped """ tf_msg = TransformStamped() - tf_msg.header = self.get_msg_header("map") - tf_msg.child_frame_id = self.get_prefix() + if frame_id: + tf_msg.header = self.get_msg_header(frame_id) + else: + tf_msg.header = self.get_msg_header("map") + if child_frame_id: + tf_msg.child_frame_id = child_frame_id + else: + tf_msg.child_frame_id = self.get_prefix() if transform: - tf_msg.transform = trans.carla_transform_to_ros_transform(transform) + tf_msg.transform = transform else: tf_msg.transform = trans.carla_transform_to_ros_transform( self.carla_actor.get_transform()) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 09d0d368..8a3387a6 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -43,7 +43,7 @@ from carla_ros_bridge.walker import Walker from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor -from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl +from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters class CarlaRosBridge(object): @@ -74,6 +74,7 @@ def __init__(self, carla_world, params): self.actors = {} self.pseudo_actors = [] self.carla_world = carla_world + self.synchronous_mode_update_thread = None self.shutdown = Event() # set carla world settings @@ -133,6 +134,10 @@ def __init__(self, carla_world, params): # register callback to update actors self.on_tick_id = self.carla_world.on_tick(self._carla_time_tick) + self.carla_weather_subscriber = \ + rospy.Subscriber("/carla/weather_control", + CarlaWeatherParameters, self.on_weather_changed) + # add world info self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, communication=self.comm)) @@ -158,6 +163,7 @@ def destroy(self): rospy.signal_shutdown("") self.debug_helper.destroy() self.shutdown.set() + self.carla_weather_subscriber.unregister() self.carla_control_queue.put(CarlaControl.STEP_ONCE) if not self.carla_settings.synchronous_mode: if self.on_tick_id: @@ -167,6 +173,26 @@ def destroy(self): rospy.loginfo("Exiting Bridge") + def on_weather_changed(self, weather_parameters): + """ + Callback on new weather parameters + :return: + """ + if not self.carla_world: + return + rospy.loginfo("Applying weather parameters...") + weather = carla.WeatherParameters() + weather.cloudiness = weather_parameters.cloudiness + weather.precipitation = weather_parameters.precipitation + weather.precipitation_deposits = weather_parameters.precipitation_deposits + weather.wind_intensity = weather_parameters.wind_intensity + weather.fog_density = weather_parameters.fog_density + weather.fog_distance = weather_parameters.fog_distance + weather.wetness = weather_parameters.wetness + weather.sun_azimuth_angle = weather_parameters.sun_azimuth_angle + weather.sun_altitude_angle = weather_parameters.sun_altitude_angle + self.carla_world.set_weather(weather) + def process_run_state(self): """ process state changes diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 31ab843d..7ba8ec83 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -111,7 +111,7 @@ def sensor_data_updated(self, carla_image): self.publish_message( self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) - def get_ros_transform(self, transform=None): + def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ Function (override) to modify the tf messages sent by this camera. @@ -121,7 +121,7 @@ def get_ros_transform(self, transform=None): :return: the filled tf message :rtype: geometry_msgs.msg.TransformStamped """ - tf_msg = super(Camera, self).get_ros_transform(transform) + tf_msg = super(Camera, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation quat = [rotation.x, rotation.y, rotation.z, rotation.w] quat_swap = tf.transformations.quaternion_from_matrix( diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index ca084ab8..01d93017 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -16,7 +16,7 @@ from std_msgs.msg import ColorRGBA from std_msgs.msg import Bool -from geometry_msgs.msg import Twist +from geometry_msgs.msg import Twist, Transform from carla import VehicleControl from carla import Vector3D @@ -167,6 +167,10 @@ def update(self, frame, timestamp): """ self.send_vehicle_msgs() super(EgoVehicle, self).update(frame, timestamp) + no_rotation = Transform() + no_rotation.rotation.x = 1.0 + self.publish_transform(self.get_ros_transform( + no_rotation, frame_id=str(self.get_id()), child_frame_id=self.get_prefix())) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 943746b3..68dcbba7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -43,7 +43,7 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): synchronous_mode=synchronous_mode, prefix='lidar/' + carla_actor.attributes.get('role_name')) - def get_ros_transform(self, transform=None): + def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ Function (override) to modify the tf messages sent by this lidar. @@ -54,7 +54,7 @@ def get_ros_transform(self, transform=None): :return: the filled tf message :rtype: geometry_msgs.msg.TransformStamped """ - tf_msg = super(Lidar, self).get_ros_transform(transform) + tf_msg = super(Lidar, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation quat = [rotation.x, rotation.y, rotation.z, rotation.w] diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index d4ff7782..d025ec10 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -18,6 +18,7 @@ import rospy from carla_ros_bridge.actor import Actor +import carla_ros_bridge.transforms as trans class Sensor(Actor): @@ -99,7 +100,8 @@ def _callback_sensor_data(self, carla_sensor_data): float(self.sensor_tick_time) self.queue.put(carla_sensor_data) else: - self.publish_transform(self.get_ros_transform(carla_sensor_data.transform)) + self.publish_transform(self.get_ros_transform( + trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) self.sensor_data_updated(carla_sensor_data) @abstractmethod @@ -128,7 +130,8 @@ def _update_synchronous_event_sensor(self, frame): rospy.logdebug("{}({}): process {}".format( self.__class__.__name__, self.get_id(), frame)) self.publish_transform( - self.get_ros_transform(carla_sensor_data.transform)) + self.get_ros_transform( + trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) self.sensor_data_updated(carla_sensor_data) except queue.Empty: return @@ -145,7 +148,9 @@ def _update_synchronous_sensor(self, frame, timestamp): rospy.logdebug("{}({}): process {}".format( self.__class__.__name__, self.get_id(), frame)) self.publish_transform( - self.get_ros_transform(carla_sensor_data.transform)) + self.get_ros_transform( + trans.carla_transform_to_ros_transform( + carla_sensor_data.transform))) self.sensor_data_updated(carla_sensor_data) return else: diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 1f28439e..d2b9ea3d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -54,7 +54,7 @@ def update(self, frame, timestamp): :return: """ self.classification_age += 1 - self.publish_transform(self.get_ros_transform()) + self.publish_transform(self.get_ros_transform(None, None, str(self.get_id()))) self.publish_marker() self.send_odometry() diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 4c9538b5..cc83b34b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -56,21 +56,6 @@ def __init__(self, carla_actor, parent, communication, prefix=None): communication=communication, prefix=prefix) - def update(self, frame, timestamp): - """ - Function (override) to update this object. - - On update vehicles send: - - tf global frame - - object message - - marker message - - :return: - """ - self.publish_transform(self.get_ros_transform()) - self.publish_marker() - super(Vehicle, self).update(frame, timestamp) - def get_marker_color(self): # pylint: disable=no-self-use """ Function (override) to return the color for marker messages. diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index f03fe842..b6c2e98f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -23,7 +23,7 @@ class Walker(TrafficParticipant): Actor implementation details for pedestrians """ - def __init__(self, carla_actor, parent, communication, prefix=None): + def __init__(self, carla_actor, parent, communication): """ Constructor @@ -36,7 +36,9 @@ def __init__(self, carla_actor, parent, communication, prefix=None): :param prefix: the topic prefix to be used for this actor :type prefix: string """ - if not prefix: + if carla_actor.attributes.get('role_name'): + prefix = carla_actor.attributes.get('role_name') + else: prefix = "walker/{:03}".format(carla_actor.id) super(Walker, self).__init__(carla_actor=carla_actor, @@ -48,6 +50,20 @@ def __init__(self, carla_actor, parent, communication, prefix=None): self.get_topic_prefix() + "/walker_control_cmd", CarlaWalkerControl, self.control_command_updated) + def destroy(self): + """ + Function (override) to destroy this object. + + Terminate ROS subscriptions + Finally forward call to super class. + + :return: + """ + rospy.logdebug("Destroy Walker(id={})".format(self.get_id())) + self.control_subscriber.unregister() + self.control_subscriber = None + super(Walker, self).destroy() + def control_command_updated(self, ros_walker_control): """ Receive a CarlaWalkerControl msg and send to CARLA diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch index def00183..59666293 100644 --- a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch @@ -4,12 +4,16 @@ + + + + diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py index 77ae976e..e33ed646 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -18,6 +18,7 @@ import Queue as queue import rospy from geometry_msgs.msg import PoseStamped +from nav_msgs.msg import Path from std_msgs.msg import Float64 from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus @@ -46,14 +47,22 @@ class CarlaRosScenarioRunner(object): Execute scenarios via ros service """ - def __init__(self, role_name, host, scenario_runner_path): + def __init__(self, role_name, host, scenario_runner_path, publish_waypoints, publish_goal): """ Constructor """ - self._goal_publisher = rospy.Publisher( - "/carla/{}/goal".format(role_name), PoseStamped, queue_size=1, latch=True) + self._goal_publisher = None + if publish_goal: + self._goal_publisher = rospy.Publisher( + "/carla/{}/goal".format(role_name), PoseStamped, queue_size=1, latch=True) self._target_speed_publisher = rospy.Publisher( "/carla/{}/target_speed".format(role_name), Float64, queue_size=1, latch=True) + + self._path_publisher = None + if publish_waypoints: + self._path_publisher = rospy.Publisher( + "/carla/{}/waypoints".format(role_name), Path, queue_size=1, latch=True) + self._status_publisher = rospy.Publisher( "/scenario_runner/status", CarlaScenarioRunnerStatus, queue_size=1, latch=True) self.scenario_runner_status_updated(ApplicationStatus.STOPPED) @@ -122,17 +131,33 @@ def run(self): self._scenario_runner.shutdown() rospy.loginfo("Scenario Runner stopped.") rospy.loginfo("Executing scenario {}...".format(current_req.name)) - # publish goal - goal = PoseStamped(pose=current_req.destination) - goal.header.stamp = rospy.get_rostime() - goal.header.frame_id = "map" - self._goal_publisher.publish(goal) - # publish target speed - self._target_speed_publisher.publish(Float64(data=current_req.target_speed)) + # execute scenario scenario_executed = self._scenario_runner.execute_scenario( current_req.scenario_file) - if not scenario_executed: + if scenario_executed: + # publish target speed + self._target_speed_publisher.publish(Float64(data=current_req.target_speed)) + + # publish last pose of route as goal + # (can be used in conjunction with carla_waypoint_publisher) + if self._goal_publisher: + goal = PoseStamped() + if current_req.waypoints: + goal.pose = current_req.waypoints[-1] + goal.header.stamp = rospy.get_rostime() + goal.header.frame_id = "map" + self._goal_publisher.publish(goal) + + # publish the waypoints (can directly be used within carla_ad_agent) + if self._path_publisher: + path = Path() + path.header.stamp = rospy.get_rostime() + path.header.frame_id = "map" + for pose in current_req.waypoints: + path.poses.append(PoseStamped(pose=pose)) + self._path_publisher.publish(path) + else: rospy.logwarn("Unable to execute scenario.") current_req = None else: @@ -157,7 +182,10 @@ def main(): role_name = rospy.get_param("~role_name", "ego_vehicle") scenario_runner_path = rospy.get_param("~scenario_runner_path", "") host = rospy.get_param("~host", "localhost") - scenario_runner = CarlaRosScenarioRunner(role_name, host, scenario_runner_path) + publish_waypoints = rospy.get_param("~publish_waypoints", False) + publish_goal = rospy.get_param("~publish_goal", True) + scenario_runner = CarlaRosScenarioRunner( + role_name, host, scenario_runner_path, publish_waypoints, publish_goal) try: scenario_runner.run() finally: diff --git a/carla_ros_scenario_runner_types/msg/CarlaScenario.msg b/carla_ros_scenario_runner_types/msg/CarlaScenario.msg index bdb90fa3..0b32ca5a 100644 --- a/carla_ros_scenario_runner_types/msg/CarlaScenario.msg +++ b/carla_ros_scenario_runner_types/msg/CarlaScenario.msg @@ -6,6 +6,6 @@ # string name string scenario_file -geometry_msgs/Pose destination +geometry_msgs/Pose[] waypoints float64 target_speed diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index 5a435099..00ebb477 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -29,8 +29,14 @@ def __init__(self, role_name): Constructor """ rospy.loginfo("Wait for vehicle info...") - vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), - CarlaEgoVehicleInfo) + try: + vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), + CarlaEgoVehicleInfo) + except rospy.ROSInterruptException as e: + if not rospy.is_shutdown(): + raise e + else: + sys.exit(0) if not vehicle_info.wheels: # pylint: disable=no-member rospy.logerr("Cannot determine max steering angle: Vehicle has no wheels.") sys.exit(1) diff --git a/carla_walker_agent/CMakeLists.txt b/carla_walker_agent/CMakeLists.txt new file mode 100644 index 00000000..8d29bb89 --- /dev/null +++ b/carla_walker_agent/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_walker_agent) + +find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch +) + +catkin_python_setup() + +roslaunch_add_file_check(launch) + +catkin_package( + CATKIN_DEPENDS + rospy +) + +catkin_install_python(PROGRAMS + src/carla_walker_agent/carla_walker_agent.py + src/carla_walker_agent/__init__.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + diff --git a/carla_walker_agent/README.md b/carla_walker_agent/README.md new file mode 100644 index 00000000..5eb7f315 --- /dev/null +++ b/carla_walker_agent/README.md @@ -0,0 +1,9 @@ +# CARLA Walker Agent + +An simple walker agent that can follow a given route. + +## Publications + +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | +| `/carla//walker_control_cmd` | [carla_msgs.CarlaWalkerControl](../carla_msgs/msg/CarlaWalkerControl.msg) | Walker control command | diff --git a/carla_walker_agent/launch/carla_walker_agent.launch b/carla_walker_agent/launch/carla_walker_agent.launch new file mode 100644 index 00000000..cfaa9aa3 --- /dev/null +++ b/carla_walker_agent/launch/carla_walker_agent.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/carla_walker_agent/package.xml b/carla_walker_agent/package.xml new file mode 100644 index 00000000..9e8d6653 --- /dev/null +++ b/carla_walker_agent/package.xml @@ -0,0 +1,18 @@ + + + carla_walker_agent + 0.0.1 + The carla_walker_agent package + CARLA Simulator Team + MIT + catkin + rospy + roslaunch + rospy + rospy + topic_tools + nav_msgs + carla_msgs + + + diff --git a/carla_walker_agent/setup.py b/carla_walker_agent/setup.py new file mode 100644 index 00000000..d6185015 --- /dev/null +++ b/carla_walker_agent/setup.py @@ -0,0 +1,10 @@ +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_walker_agent'], + package_dir={'': 'src'} +) + +setup(**d) + diff --git a/carla_walker_agent/src/carla_walker_agent/__init__.py b/carla_walker_agent/src/carla_walker_agent/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py new file mode 100755 index 00000000..df57ffc6 --- /dev/null +++ b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py @@ -0,0 +1,136 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +Agent for Walker +""" +import rospy +import math +from nav_msgs.msg import Path, Odometry +from std_msgs.msg import Float64 +from carla_msgs.msg import CarlaWalkerControl +from geometry_msgs.msg import Pose, Vector3 + + +class CarlaWalkerAgent(object): + """ + walker agent + """ + # minimum distance to target waypoint before switching to next + MIN_DISTANCE = 0.5 + + def __init__(self, role_name, target_speed): + """ + Constructor + """ + self._route_assigned = False + self._target_speed = target_speed + self._waypoints = [] + self._current_pose = Pose() + rospy.on_shutdown(self.on_shutdown) + + #wait for ros bridge to create relevant topics + try: + rospy.wait_for_message( + "/carla/{}/odometry".format(role_name), Odometry) + except rospy.ROSInterruptException as e: + if not rospy.is_shutdown(): + raise e + + self._odometry_subscriber = rospy.Subscriber( + "/carla/{}/odometry".format(role_name), Odometry, self.odometry_updated) + + self.control_publisher = rospy.Publisher( + "/carla/{}/walker_control_cmd".format(role_name), CarlaWalkerControl, queue_size=1) + + self._route_subscriber = rospy.Subscriber( + "/carla/{}/waypoints".format(role_name), Path, self.path_updated) + + self._target_speed_subscriber = rospy.Subscriber( + "/carla/{}/target_speed".format(role_name), Float64, self.target_speed_updated) + + def on_shutdown(self): + """ + callback on shutdown + """ + rospy.loginfo("Shutting down, stopping walker...") + self.control_publisher.publish(CarlaWalkerControl()) #stop + + def target_speed_updated(self, target_speed): + """ + callback on new target speed + """ + rospy.loginfo("New target speed received: {}".format(target_speed.data)) + self._target_speed = target_speed.data + + def path_updated(self, path): + """ + callback on new route + """ + rospy.loginfo("New plan with {} waypoints received. Assigning plan...".format(len(path.poses))) + self.control_publisher.publish(CarlaWalkerControl()) #stop + self._waypoints = [] + for elem in path.poses: + self._waypoints.append(elem.pose) + + def odometry_updated(self, odo): + """ + callback on new odometry + """ + self._current_pose = odo.pose.pose + + def run(self): + """ + + Control loop + + :return: + """ + r = rospy.Rate(20) + while not rospy.is_shutdown(): + if self._waypoints: + control = CarlaWalkerControl() + direction = Vector3() + direction.x = self._waypoints[0].position.x - self._current_pose.position.x + direction.y = self._waypoints[0].position.y - self._current_pose.position.y + direction_norm = math.sqrt(direction.x**2 + direction.y**2) + if direction_norm > CarlaWalkerAgent.MIN_DISTANCE: + control.speed = self._target_speed + control.direction.x = direction.x / direction_norm + control.direction.y = direction.y / direction_norm + else: + self._waypoints = self._waypoints[1:] + if self._waypoints: + rospy.loginfo("next waypoint: {} {}".format(self._waypoints[0].position.x, self._waypoints[0].position.y)) + else: + rospy.loginfo("Route finished.") + self.control_publisher.publish(control) + try: + r.sleep() + except rospy.ROSInterruptException: + pass + +def main(): + """ + + main function + + :return: + """ + rospy.init_node('carla_walker_agent', anonymous=True) + role_name = rospy.get_param("~role_name", "ego_vehicle") + target_speed = rospy.get_param("~target_speed", 20) + controller = CarlaWalkerAgent(role_name, target_speed) + try: + controller.run() + finally: + del controller + rospy.loginfo("Done") + + +if __name__ == "__main__": + main() From b83e62a9bb7ab318f9dc24e21b92fa75f5a9ffb0 Mon Sep 17 00:00:00 2001 From: umateusz Date: Wed, 29 Apr 2020 16:44:34 +0200 Subject: [PATCH 044/627] Add role name to imu topic (#256) * add role name to imu topic Co-authored-by: fpasch <46815108+fpasch@users.noreply.github.com> --- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 83f0e4e7..ddd6b762 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -39,7 +39,7 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): parent=parent, communication=communication, synchronous_mode=synchronous_mode, - prefix="imu") + prefix="imu/" + carla_actor.attributes.get('role_name')) # pylint: disable=arguments-differ def sensor_data_updated(self, carla_imu_measurement): From c391d311715df48bbde19142b82d4639027c502a Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 29 Apr 2020 16:30:05 +0200 Subject: [PATCH 045/627] Support carla 0.9.9 - improve version checking --- CHANGELOG.md | 2 ++ README.md | 2 ++ .../src/carla_ad_agent/carla_ad_agent.py | 7 +++--- .../launch/carla_ad_demo_with_rviz.launch | 2 -- .../carla_ego_vehicle/carla_ego_vehicle.py | 6 +++-- .../launch/carla_ros_bridge.launch | 2 +- .../src/carla_ros_bridge/bridge.py | 24 ++++++++++++------- .../carla_spectator_camera.py | 3 ++- .../carla_waypoint_publisher.py | 16 ++++++------- 9 files changed, 38 insertions(+), 26 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index a8bfdb17..70207d0e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,7 @@ ## Latest changed +* Improve version check +* Fix cleanup * Rework tf frame names * ObjectSensor: Fix object twist * Support loading OpenDRIVE map diff --git a/README.md b/README.md index 92f461ce..db733ad3 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,8 @@ This ROS package aims at providing a simple ROS bridge for CARLA simulator. ![rviz setup](./docs/images/rviz_carla_default.png "rviz") +**This version requires CARLA 0.9.9** + ## Features - Provide Sensor Data (Lidar, Cameras (depth, segmentation, rgb), GNSS, Radar, IMU) diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 3768737a..61461c3d 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -8,6 +8,7 @@ """ A basic AD agent using CARLA waypoints """ +import sys import rospy from nav_msgs.msg import Path from std_msgs.msg import Float64 @@ -35,9 +36,9 @@ def __init__(self, role_name, target_speed, avoid_risk): try: vehicle_info = rospy.wait_for_message( "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) - except rospy.ROSInterruptException as e: - if not rospy.is_shutdown(): - raise e + except rospy.ROSException: + rospy.logerr("Timeout while waiting for world info!") + sys.exit(1) self._route_subscriber = rospy.Subscriber( "/carla/{}/waypoints".format(role_name), Path, self.path_updated) diff --git a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch index ddde764d..c8089f94 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch @@ -77,8 +77,6 @@ }' -l"/> - - diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 8a5d7110..dc9abcce 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -20,6 +20,7 @@ from abc import abstractmethod import os +import sys import random import math import json @@ -354,9 +355,10 @@ def run(self): rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException as e: + except rospy.ROSException: rospy.logerr("Timeout while waiting for world info!") - raise e + sys.exit(1) + rospy.loginfo("CARLA world available. Spawn ego vehicle...") client = carla.Client(self.host, self.port) diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index 6c5c292c..b7a5707a 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -30,6 +30,6 @@ value="$(arg town)" unless="$(eval town == '')"/> - + diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 8a3387a6..44c45e13 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -15,7 +15,8 @@ except ImportError: import Queue as queue -from distutils.version import LooseVersion +import sys +from distutils.version import StrictVersion from threading import Thread, Lock, Event import pkg_resources import rospy @@ -52,7 +53,7 @@ class CarlaRosBridge(object): Carla Ros bridge """ - CARLA_VERSION = "0.9.8" + CARLA_VERSION = "0.9.9" def __init__(self, carla_world, params): """ @@ -63,13 +64,6 @@ def __init__(self, carla_world, params): :param params: dict of parameters, see settings.yaml :type params: dict """ - # check CARLA version - dist = pkg_resources.get_distribution("carla") - if LooseVersion(dist.version) < LooseVersion(self.CARLA_VERSION): - raise ImportError( - "CARLA version {} or newer required. CARLA version found: {}".format( - self.CARLA_VERSION, dist)) - self.parameters = params self.actors = {} self.pseudo_actors = [] @@ -525,6 +519,18 @@ def main(): host=parameters['host'], port=parameters['port']) carla_client.set_timeout(parameters['timeout']) + + # check carla version + dist = pkg_resources.get_distribution("carla") + if StrictVersion(dist.version) != StrictVersion(CarlaRosBridge.CARLA_VERSION): + rospy.logfatal("CARLA python module version {} required. Found: {}".format( + CarlaRosBridge.CARLA_VERSION, dist.version)) + sys.exit(1) + + if StrictVersion(carla_client.get_server_version()) != StrictVersion(CarlaRosBridge.CARLA_VERSION): + rospy.logfatal("CARLA Server version {} required. Found: {}".format( + CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) + sys.exit(1) carla_world = carla_client.get_world() diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index f3e0a538..dff7362f 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -11,6 +11,7 @@ to /carla//spectator_position. """ +import sys import math import rospy from tf.transformations import euler_from_quaternion @@ -159,7 +160,7 @@ def run(self): rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) except rospy.ROSException as e: rospy.logerr("Timeout while waiting for world info!") - raise e + sys.exit(1) rospy.loginfo("CARLA world available. Waiting for ego vehicle...") client = carla.Client(self.host, self.port) diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index a11a3df5..6e7276d0 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -18,6 +18,7 @@ Additionally, services are provided to interface CARLA waypoints. """ import math +import sys import threading import rospy @@ -214,7 +215,7 @@ def calculate_route(self, goal): goal.location.y, goal.location.z)) - dao = GlobalRoutePlannerDAO(self.world.get_map()) + dao = GlobalRoutePlannerDAO(self.world.get_map(), sampling_resolution=1) grp = GlobalRoutePlanner(dao) grp.setup() route = grp.trace_route(self.ego_vehicle.get_location(), @@ -254,15 +255,14 @@ def main(): """ main function """ - rospy.init_node("carla_waypoint_publisher", anonymous=True) - - # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: + rospy.init_node("carla_waypoint_publisher", anonymous=True) + # wait for ros-bridge to set up CARLA world + rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException as e: - rospy.logerr("Timeout while waiting for world info!") - raise e + except rospy.ROSException: + rospy.logerr("Error while waiting for world info!") + sys.exit(1) host = rospy.get_param("/carla/host", "127.0.0.1") port = rospy.get_param("/carla/port", 2000) From 8b5db6d66cad5cccdeafafb991efe982d8aeafc4 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 29 Apr 2020 16:42:22 +0200 Subject: [PATCH 046/627] Fix object markers --- carla_ros_bridge/src/carla_ros_bridge/actor.py | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index da417ca6..eb4e7d32 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -155,15 +155,11 @@ def get_marker(self): """ Helper function to create a ROS visualization_msgs.msg.Marker for the actor - :param use_parent_frame: per default (True) the header.frame_id - is set to the frame of the actor's parent. - If this is set to False, the actor's own frame is used as basis. - :type use_parent_frame: boolean :return: visualization_msgs.msg.Marker """ marker = Marker( - header=self.get_msg_header()) + header=self.get_msg_header(frame_id=str(self.get_id()))) marker.color = self.get_marker_color() marker.color.a = 0.3 marker.id = self.get_id() From e22992f9b7409e4aa1ed335a21c0e2425d936d0c Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 29 Apr 2020 17:08:31 +0200 Subject: [PATCH 047/627] cleanup --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 11 ++++++----- .../carla_spectator_camera/carla_spectator_camera.py | 4 ++-- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 44c45e13..cb940077 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -519,17 +519,18 @@ def main(): host=parameters['host'], port=parameters['port']) carla_client.set_timeout(parameters['timeout']) - + # check carla version dist = pkg_resources.get_distribution("carla") if StrictVersion(dist.version) != StrictVersion(CarlaRosBridge.CARLA_VERSION): rospy.logfatal("CARLA python module version {} required. Found: {}".format( - CarlaRosBridge.CARLA_VERSION, dist.version)) + CarlaRosBridge.CARLA_VERSION, dist.version)) sys.exit(1) - - if StrictVersion(carla_client.get_server_version()) != StrictVersion(CarlaRosBridge.CARLA_VERSION): + + if StrictVersion(carla_client.get_server_version()) != \ + StrictVersion(CarlaRosBridge.CARLA_VERSION): rospy.logfatal("CARLA Server version {} required. Found: {}".format( - CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) + CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) sys.exit(1) carla_world = carla_client.get_world() diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index dff7362f..898fac23 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -158,8 +158,8 @@ def run(self): rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException as e: - rospy.logerr("Timeout while waiting for world info!") + except rospy.ROSException: + rospy.logerr("Error while waiting for world info!") sys.exit(1) rospy.loginfo("CARLA world available. Waiting for ego vehicle...") From f58c12ed8d8b49ef6892776aa05c6464c3959597 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 30 Apr 2020 09:16:49 +0200 Subject: [PATCH 048/627] Add port to carla_ros_scenario_runner --- carla_ad_demo/launch/carla_ad_demo_with_rviz.launch | 1 + .../carla_ros_scenario_runner/carla_ros_scenario_runner.py | 6 ++++-- .../src/carla_ros_scenario_runner/scenario_runner_runner.py | 6 ++++-- 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch index c8089f94..e636d320 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch @@ -77,6 +77,7 @@ }' -l"/> + diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py index e33ed646..83c04b78 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -47,7 +47,7 @@ class CarlaRosScenarioRunner(object): Execute scenarios via ros service """ - def __init__(self, role_name, host, scenario_runner_path, publish_waypoints, publish_goal): + def __init__(self, role_name, host, port, scenario_runner_path, publish_waypoints, publish_goal): """ Constructor """ @@ -69,6 +69,7 @@ def __init__(self, role_name, host, scenario_runner_path, publish_waypoints, pub self._scenario_runner = ScenarioRunnerRunner( scenario_runner_path, host, + port, self.scenario_runner_status_updated, self.scenario_runner_log) self._request_queue = queue.Queue() @@ -182,10 +183,11 @@ def main(): role_name = rospy.get_param("~role_name", "ego_vehicle") scenario_runner_path = rospy.get_param("~scenario_runner_path", "") host = rospy.get_param("~host", "localhost") + port = rospy.get_param("~port", 2000) publish_waypoints = rospy.get_param("~publish_waypoints", False) publish_goal = rospy.get_param("~publish_goal", True) scenario_runner = CarlaRosScenarioRunner( - role_name, host, scenario_runner_path, publish_waypoints, publish_goal) + role_name, host, port, scenario_runner_path, publish_waypoints, publish_goal) try: scenario_runner.run() finally: diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py index 07cb72f0..3216ccdd 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py @@ -14,9 +14,10 @@ class ScenarioRunnerRunner(ApplicationRunner): Executes scenario runner """ - def __init__(self, path, host, status_updated_fct, log_fct): + def __init__(self, path, host, port, status_updated_fct, log_fct): self._path = path self._host = host + self._port = port super(ScenarioRunnerRunner, self).__init__( status_updated_fct, log_fct, @@ -30,5 +31,6 @@ def execute_scenario(self, scenario_file): "--openscenario", "{}".format(scenario_file), "--waitForEgo", "--timeout", "1000000", - "--host", self._host] + "--host", self._host, + "--port", str(self._port)] return self.execute(cmdline, env=os.environ) From 3c8f0fcd2b3d822b4bb837a229da6f843720e0b6 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 30 Apr 2020 18:07:32 +0200 Subject: [PATCH 049/627] Relax version check --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index cb940077..76280872 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -16,7 +16,7 @@ import Queue as queue import sys -from distutils.version import StrictVersion +from distutils.version import LooseVersion from threading import Thread, Lock, Event import pkg_resources import rospy @@ -522,13 +522,13 @@ def main(): # check carla version dist = pkg_resources.get_distribution("carla") - if StrictVersion(dist.version) != StrictVersion(CarlaRosBridge.CARLA_VERSION): + if LooseVersion(dist.version) <= LooseVersion(CarlaRosBridge.CARLA_VERSION): rospy.logfatal("CARLA python module version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, dist.version)) sys.exit(1) - if StrictVersion(carla_client.get_server_version()) != \ - StrictVersion(CarlaRosBridge.CARLA_VERSION): + if LooseVersion(carla_client.get_server_version()) <= \ + LooseVersion(CarlaRosBridge.CARLA_VERSION): rospy.logfatal("CARLA Server version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) sys.exit(1) From c64fd6966a3375a3147538a63d8e4f9660ce1b29 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 4 May 2020 13:56:06 +0200 Subject: [PATCH 050/627] Fix version check --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 76280872..c667982f 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -522,12 +522,12 @@ def main(): # check carla version dist = pkg_resources.get_distribution("carla") - if LooseVersion(dist.version) <= LooseVersion(CarlaRosBridge.CARLA_VERSION): + if LooseVersion(dist.version) < LooseVersion(CarlaRosBridge.CARLA_VERSION): rospy.logfatal("CARLA python module version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, dist.version)) sys.exit(1) - if LooseVersion(carla_client.get_server_version()) <= \ + if LooseVersion(carla_client.get_server_version()) < \ LooseVersion(CarlaRosBridge.CARLA_VERSION): rospy.logfatal("CARLA Server version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) From 6affc519ec5507658094c4649358e502053813c2 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Mon, 4 May 2020 17:33:44 +0200 Subject: [PATCH 051/627] remove duplicated script --- CreateROSbridgeDebian.sh | 119 --------------------------------------- 1 file changed, 119 deletions(-) delete mode 100644 CreateROSbridgeDebian.sh diff --git a/CreateROSbridgeDebian.sh b/CreateROSbridgeDebian.sh deleted file mode 100644 index 7b820a90..00000000 --- a/CreateROSbridgeDebian.sh +++ /dev/null @@ -1,119 +0,0 @@ -#!/bin/sh - -#This script builds debian package for CARLA ROS Bridge -#Tested with Ubuntu 14.04, 16.04, 18.04 and 19.10 - -sudo apt-get install build-essential dh-make - -#Adding maintainer name -DEBFULLNAME=Carla\ Simulator\ Team -export DEBFULLNAME - -#carla-ros-bridge github repository -ROS_BRIDGE_GIT=https://github.com/carla-simulator/ros-bridge.git - -mkdir -p carla-ros-debian/carla-ros-bridge/catkin_ws/src -mkdir -p carla-ros-debian/carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ - -cd carla-ros-debian/carla-ros-bridge - -#cloning carla-ros-bridge git repository -git clone ${ROS_BRIDGE_GIT} -rm -r ros-bridge/carla_msgs -cp -a ros-bridge/* catkin_ws/src/ - -cd catkin_ws - -source /opt/ros/$(rosversion -d)/setup.bash - -#installing required dependency packages to build catkin_make -sudo apt install ros-$(rosversion -d)-ainstein-radar-msgs ros-$(rosversion -d)-derived-object-msgs \ -ros-$(rosversion -d)-ackermann-msgs ros-$(rosversion -d)-carla-msgs ros-$(rosversion -d)-pcl-conversions \ -ros-$(rosversion -d)-rviz ros-$(rosversion -d)-rqt ros-$(rosversion -d)-pcl-ros - -catkin_make install - -cp -r install ../../carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ - -cd ../../carla-ros-bridge-$(rosversion -d)-0.9.8/ -mv carla-ros-bridge/install carla-ros-bridge/$(rosversion -d) - -rm Makefile - -#Making debian package to install Carla-ros-bridge in /opt folder -cat >> Makefile <> control < -Build-Depends: debhelper (>= 9) -Standards-Version:0.9.7 -Homepage: https://github.com/carla-simulator/ros-bridge - -Package: carla-ros-bridge-$(rosversion -d) -Architecture: amd64 -Depends: ros-$(rosversion -d)-carla-msgs, - ros-$(rosversion -d)-roslaunch, - ros-$(rosversion -d)-catkin, - ros-$(rosversion -d)-rospy, - ros-$(rosversion -d)-nav-msgs, - ros-$(rosversion -d)-ackermann-msgs, - ros-$(rosversion -d)-std-msgs, - ros-$(rosversion -d)-dynamic-reconfigure, - ros-$(rosversion -d)-topic-tools, - ros-$(rosversion -d)-sensor-msgs, - ros-$(rosversion -d)-message-runtime, - ros-$(rosversion -d)-geometry-msgs, - ros-$(rosversion -d)-message-generation, - ros-$(rosversion -d)-ainstein-radar-msgs, - ros-$(rosversion -d)-visualization-msgs, - ros-$(rosversion -d)-tf, - ros-$(rosversion -d)-tf2, - ros-$(rosversion -d)-rviz, - ros-$(rosversion -d)-cv-bridge, - ros-$(rosversion -d)-rosbag-storage, - ros-$(rosversion -d)-derived-object-msgs, - ros-$(rosversion -d)-shape-msgs, - ros-$(rosversion -d)-tf2-msgs, - ros-$(rosversion -d)-rosgraph-msgs, - ros-$(rosversion -d)-roscpp, - ros-$(rosversion -d)-pcl-conversions, - ros-$(rosversion -d)-pcl-ros, - ros-$(rosversion -d)-rostopic, - ros-$(rosversion -d)-rqt-gui-py -Description: The carla_ros_bridge package aims at providing a simple ROS bridge for CARLA simulator. -EOF - -rm copyright -cp ../../../carla-ros-bridge/ros-bridge/LICENSE ./copyright - - -#Updating debian/Changelog -awk '{sub(/UNRELEASED/,"stable")}1' changelog > tmp && mv tmp changelog -awk '{sub(/unstable/,"stable")}1' changelog > tmp && mv tmp changelog - -cd .. - -dpkg-buildpackage -uc -us -b #building debian package - -#install debian package using "sudo dpkg -i ../carla_ros-bridge-_amd64.deb" - From 4306e9c440a3d0aa289562b06e34aaa50b2a7fb3 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Thu, 7 May 2020 16:38:54 +0200 Subject: [PATCH 052/627] activate catkin test for travis (#294) * activate catkin test for travis * don't run catkin test on kinetic as it does not support all options --- .travis.yml | 3 ++- carla_ad_demo/package.xml | 1 + carla_ego_vehicle/CMakeLists.txt | 2 +- carla_infrastructure/CMakeLists.txt | 2 +- carla_ros_bridge/CMakeLists.txt | 3 ++- carla_ros_scenario_runner/CMakeLists.txt | 2 +- 6 files changed, 8 insertions(+), 5 deletions(-) diff --git a/.travis.yml b/.travis.yml index 1ccb0633..75fa0fac 100644 --- a/.travis.yml +++ b/.travis.yml @@ -74,7 +74,8 @@ install: script: - catkin build - #- catkin test + - export SCENARIO_RUNNER_PATH="" # the env var needs to be set for testing + - if [ ! $ROS_DISTRO -eq kinetic ]; then catkin test; fi; - catkin config --install - source devel/setup.bash - cd src/ros-bridge diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 50f72d56..050c468e 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -16,6 +16,7 @@ carla_spectator_camera carla_ros_scenario_runner rostopic + rviz diff --git a/carla_ego_vehicle/CMakeLists.txt b/carla_ego_vehicle/CMakeLists.txt index 965a326b..7573b76b 100644 --- a/carla_ego_vehicle/CMakeLists.txt +++ b/carla_ego_vehicle/CMakeLists.txt @@ -8,7 +8,7 @@ find_package(catkin REQUIRED COMPONENTS catkin_python_setup() -roslaunch_add_file_check(launch) +roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) catkin_package( CATKIN_DEPENDS diff --git a/carla_infrastructure/CMakeLists.txt b/carla_infrastructure/CMakeLists.txt index 6223118e..91b6ca33 100644 --- a/carla_infrastructure/CMakeLists.txt +++ b/carla_infrastructure/CMakeLists.txt @@ -8,7 +8,7 @@ find_package(catkin REQUIRED COMPONENTS catkin_python_setup() -roslaunch_add_file_check(launch) +roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) catkin_package( CATKIN_DEPENDS diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index fb76b2b1..7e212f75 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -17,6 +17,7 @@ catkin_python_setup() catkin_package() roslaunch_add_file_check(launch) +roslaunch_add_file_check(test) include_directories( ${catkin_INCLUDE_DIRS} @@ -41,7 +42,7 @@ install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch ) -if(CATKIN_ENABLE_TESTING) +if(CATKIN_ENABLE_TESTING AND NOT $ENV{CI}) find_package(rostest REQUIRED) add_rostest(test/ros_bridge_client.test) endif() diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt index 877653c6..39ddf14f 100644 --- a/carla_ros_scenario_runner/CMakeLists.txt +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -7,7 +7,7 @@ find_package(catkin REQUIRED COMPONENTS catkin_python_setup() -roslaunch_add_file_check(launch) +roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) catkin_package() From b211545f66f77fe33be2858b5a21c8b2d43aa7ef Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 10:22:55 +0200 Subject: [PATCH 053/627] Add Dockerfile for eloquent --- docker/Dockerfile.eloquent | 48 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 48 insertions(+) create mode 100644 docker/Dockerfile.eloquent diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent new file mode 100644 index 00000000..f630ee8c --- /dev/null +++ b/docker/Dockerfile.eloquent @@ -0,0 +1,48 @@ +ARG CARLA_VERSION='0.9.9' +ARG ROS_VERSION='eloquent' +ARG CARLA_BUILD='' + +FROM carlasim/carla:$CARLA_VERSION$CARLA_BUILD as carla + +FROM ros:$ROS_VERSION-ros-base + +ARG ROS_VERSION + +RUN mkdir -p /carla_ws/src +WORKDIR /carla_ws + +RUN apt-get update \ + && apt-get install -y --no-install-recommends \ + libpng16-16 \ + # ros-$ROS_VERSION-ackermann-msgs \ + # ros-$ROS_VERSION-derived-object-msgs \ + # ros-$ROS_VERSION-tf \ + ros-$ROS_VERSION-cv-bridge \ + ros-$ROS_VERSION-pcl-conversions \ + # ros-$ROS_VERSION-pcl-ros \ + # ros-$ROS_VERSION-ainstein-radar \ + # python-catkin-tools \ + && rm -rf /var/lib/apt/lists/* + +ARG CARLA_VERSION + +COPY --from=carla --chown=root /home/carla/PythonAPI /opt/carla/PythonAPI +RUN sudo apt-get update && sudo apt-get install python-pip python3-pip -y --no-install-recommends +RUN python -m pip install setuptools +RUN python3 -m pip install setuptools +RUN easy_install --user --no-deps "/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py2.7-linux-x86_64.egg" +RUN easy_install --user --no-deps "/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py3.7-linux-x86_64.egg" + +COPY . src/ + +RUN echo "source /opt/ros/$ROS_VERSION/setup.bash" >> ~/.bashrc +RUN echo "source /carla_ws/devel/setup.bash" >> ~/.bashrc + +SHELL ["/bin/bash", "-c" , "-l"] + +RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment +RUN rosdep install --from-paths src -r +RUN colcon info carla_msgs +RUN colcon build --symlink-install + +CMD ["ros2", "run", "carla_msgs" , "simple_publisher.py"] From 8ddae754ad4f3a1bc1a49cd0c1b93ff79bdd4b00 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 22 May 2020 12:15:35 +0200 Subject: [PATCH 054/627] Add ros_compatibility module --- ros_compatibility/CMakeLists.txt | 39 ++++++++ ros_compatibility/__init__.py | 1 + ros_compatibility/package.xml | 26 +++++ ros_compatibility/resource/ros_compatibility | 0 ros_compatibility/setup.cfg | 4 + ros_compatibility/setup.py | 44 +++++++++ ros_compatibility/src/__init__.py | 0 .../src/ros_compatibility/__init__.py | 4 + .../ros_compatibility/ros_compatible_node.py | 95 +++++++++++++++++++ 9 files changed, 213 insertions(+) create mode 100644 ros_compatibility/CMakeLists.txt create mode 100644 ros_compatibility/__init__.py create mode 100644 ros_compatibility/package.xml create mode 100644 ros_compatibility/resource/ros_compatibility create mode 100644 ros_compatibility/setup.cfg create mode 100644 ros_compatibility/setup.py create mode 100644 ros_compatibility/src/__init__.py create mode 100644 ros_compatibility/src/ros_compatibility/__init__.py create mode 100644 ros_compatibility/src/ros_compatibility/ros_compatible_node.py diff --git a/ros_compatibility/CMakeLists.txt b/ros_compatibility/CMakeLists.txt new file mode 100644 index 00000000..ccb664f4 --- /dev/null +++ b/ros_compatibility/CMakeLists.txt @@ -0,0 +1,39 @@ +cmake_minimum_required(VERSION 2.8.3) +project(ros_compatibility) + +# Update the policy setting to avoid an error when loading the ament_cmake package +# at the current cmake version level +if(POLICY CMP0057) + cmake_policy(SET CMP0057 NEW) +endif() + +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) + +if (${ROS_VERSION} EQUAL 1) + + find_package(catkin REQUIRED COMPONENTS + rospy + ) + + catkin_python_setup() + + catkin_package( + CATKIN_DEPENDS + rospy + ) + + include_directories() + + catkin_install_python( + PROGRAMS src/ros_compatibility/ros_compatible_node.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + +endif() diff --git a/ros_compatibility/__init__.py b/ros_compatibility/__init__.py new file mode 100644 index 00000000..0c1cfee4 --- /dev/null +++ b/ros_compatibility/__init__.py @@ -0,0 +1 @@ +from ros_compatibility.src.ros_compatibility.ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/package.xml b/ros_compatibility/package.xml new file mode 100644 index 00000000..f08a9b15 --- /dev/null +++ b/ros_compatibility/package.xml @@ -0,0 +1,26 @@ + + + + ros_compatibility + 0.0.0 + The ros_compatibility package + CARLA Simulator Team + MIT + + + rclpy + + + catkin + rospy + std_msgs + rospy + std_msgs + rospy + std_msgs + + + catkin + ament_python + + diff --git a/ros_compatibility/resource/ros_compatibility b/ros_compatibility/resource/ros_compatibility new file mode 100644 index 00000000..e69de29b diff --git a/ros_compatibility/setup.cfg b/ros_compatibility/setup.cfg new file mode 100644 index 00000000..9c25a3a8 --- /dev/null +++ b/ros_compatibility/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/ros_compatibility +[install] +install-scripts=$base/lib/ros_compatibility diff --git a/ros_compatibility/setup.py b/ros_compatibility/setup.py new file mode 100644 index 00000000..55754977 --- /dev/null +++ b/ros_compatibility/setup.py @@ -0,0 +1,44 @@ +import os + +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup + + d = generate_distutils_setup( + packages=['ros_compatibility'], + package_dir={'': 'src'} + ) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'ros_compatibility' + + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + py_modules=[ + 'src.ros_compatibility.ros_compatible_node'], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='The ros_compatibility package', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'ros_compatible_node = src.ros_compatibility.ros_compatible_node:main' + ], + }, + ) diff --git a/ros_compatibility/src/__init__.py b/ros_compatibility/src/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py new file mode 100644 index 00000000..3c2a8ca4 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -0,0 +1,4 @@ +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) +if ROS_VERSION == 1: + from ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py new file mode 100644 index 00000000..56f513d1 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -0,0 +1,95 @@ +import os + +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + import rospy + + + class QoSProfile(): + def __init__(self, **kwargs): + self.depth = kwargs['depth'] + + + class CompatibleNode(object): + def __init__(self, node_name, queue_size=10): + rospy.init_node(node_name, anonymous=True) + self.qos_profile = QoSProfile(depth=queue_size) + + def get_param(self, name, alternative_value=None, alternative_name=None): + if alternative_value is None: + return rospy.get_param(name) + return rospy.get_param(name, alternative_value) + + def loginfo(self, text): + rospy.loginfo(text) + + def logfatal(self, arg): + rospy.logfatal(arg) + + def create_subscriber(self, msg_type, topic, + callback, qos_profile=None): + if qos_profile is None: + qos_profile = self.qos_profile + return rospy.Subscriber(topic, msg_type, + callback, queue_size=qos_profile.depth) + + def spin(self): + rospy.spin() + + def shutdown(self): + pass + +elif ROS_VERSION == 2: + from rclpy.node import Node + from rclpy import Parameter + from rclpy.qos import QoSProfile + import rclpy + + + class CompatibleNode(Node): + def __init__(self, node_name, queue_size=10): + super().__init__(node_name, allow_undeclared_parameters=True, + automatically_declare_parameters_from_overrides=True) + self.logger = self.get_logger() + self.qos_profile = QoSProfile(depth=queue_size) + + def get_param(self, name, alternative_value=None, alternative_name=None): + if alternative_value is None: + return self.get_parameter(name).value + if alternative_name is None: + alternative_name = name + return self.get_parameter_or(name, + Parameter(alternative_name, value=alternative_value)).value + + def loginfo(self, text): + self.logger.info(text) + + def logfatal(self, arg): + self.logger.fatal(arg) + + def create_subscriber(self, msg_type, topic, + callback, qos_profile=None): + if qos_profile is None: + qos_profile = self.qos_profile + return self.create_subscription(msg_type, topic, + callback, qos_profile) + + def spin(self): + rclpy.spin(self) + + def shutdown(self): + rclpy.shutdown() + +else: + raise NotImplementedError("Make sure you have valid " + + "ROS_VERSION env variable"); + + +def main(): + print('This is a ros1 - ros2 compatibility module.', + "It's not meant to be executed, but rather imported") + + +if __name__ == '__main__': + main() From 959002c6c1642d4eb48f1adf5201fcca5bea30a8 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 22 May 2020 12:19:03 +0200 Subject: [PATCH 055/627] Add carla_ego_vehicle package --- carla_ego_vehicle/CMakeLists.txt | 53 +++--- carla_ego_vehicle/README.md | 45 ----- carla_ego_vehicle/config/sensors.json | 2 +- carla_ego_vehicle/config/settings.yaml | 21 +++ carla_ego_vehicle/package.xml | 24 ++- carla_ego_vehicle/resource/carla_ego_vehicle | 0 carla_ego_vehicle/setup.cfg | 4 + carla_ego_vehicle/setup.py | 46 ++++- .../carla_ego_vehicle/carla_ego_vehicle.py | 167 ++++++++++++------ 9 files changed, 230 insertions(+), 132 deletions(-) delete mode 100644 carla_ego_vehicle/README.md create mode 100644 carla_ego_vehicle/config/settings.yaml create mode 100644 carla_ego_vehicle/resource/carla_ego_vehicle create mode 100644 carla_ego_vehicle/setup.cfg diff --git a/carla_ego_vehicle/CMakeLists.txt b/carla_ego_vehicle/CMakeLists.txt index 965a326b..97a8098e 100644 --- a/carla_ego_vehicle/CMakeLists.txt +++ b/carla_ego_vehicle/CMakeLists.txt @@ -1,29 +1,42 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ego_vehicle) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if (${ROS_VERSION} EQUAL 1) -roslaunch_add_file_check(launch) + find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch + ) -catkin_package( - CATKIN_DEPENDS - rospy -) + catkin_python_setup() -catkin_install_python(PROGRAMS - src/carla_ego_vehicle/carla_ego_vehicle.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) + roslaunch_add_file_check(launch) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + catkin_package( + CATKIN_DEPENDS + rospy + ) -install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config -) + catkin_install_python(PROGRAMS + src/carla_ego_vehicle/carla_ego_vehicle.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + ) + + install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config + ) + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + +endif() \ No newline at end of file diff --git a/carla_ego_vehicle/README.md b/carla_ego_vehicle/README.md deleted file mode 100644 index bcad5ed5..00000000 --- a/carla_ego_vehicle/README.md +++ /dev/null @@ -1,45 +0,0 @@ -# ROS Ego Vehicle - -The reference Carla client `carla_ego_vehicle` can be used to spawn an ego vehicle (role-name: "ego_vehicle") with attached sensors. - -Info: To be able to use `carla_manual_control` a camera with role-name 'view' and resolution of 800x600 is required. - -If no specific position is set, the ego vehicle is spawned at a random position. - -## Spawning at specific position - -It is possible to (re)spawn the ego vehicle at the specific location by publishing to `/carla//initialpose`. - -The preferred way of doing that is using RVIZ: - -![Autoware Runtime Manager Settings](../docs/images/rviz_set_start_goal.png) - -Selecting a Pose with '2D Pose Estimate' will delete the current ego_vehicle and respawn it at the specified position. - -## Re-use existing vehicle as ego-vehicle - -It is possible to re-use an existing vehicle as ego-vehicle, instead of spawning a new vehicle. In this case, the role_name is used to identify the vehicle -among all CARLA actors through the rolename attribute. Upon success, the requested sensors are attached to this actor, and the actor becomes the new ego vehicle. - -To make use of this option, set the ROS parameter spawn_ego_vehicle to false. - -## Create your own sensor setup - -Sensors, attached to the ego vehicle can be defined via a json file. `carla_ego_vehicle` reads it from the file location defined via the private ros parameter `sensor_definition_file`. - -The format is defined like that: - - { "sensors" = [ - { - "type": "", - "id": "", - "x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, # pose of the sensor, relative to the vehicle - - }, - ... - ] - } - -Define sensors with their attributes as described in the Carla Documentation about [Cameras and Sensors](https://github.com/carla-simulator/carla/blob/master/Docs/cameras_and_sensors.md). - -An example is provided by [carla_example_ego_vehicle.launch](launch/carla_example_ego_vehicle.launch). It uses the sensors from [sensors.json](config/sensors.json) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index c0e8e0f7..0a465c4d 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -7,7 +7,7 @@ "width": 800, "height": 600, "fov": 100, - "sensor_tick": 0.05, + "^": 0.05, "gamma": 2.2, "shutter_speed": 60.0, "iso": 1200.0, diff --git a/carla_ego_vehicle/config/settings.yaml b/carla_ego_vehicle/config/settings.yaml new file mode 100644 index 00000000..80a2b9d2 --- /dev/null +++ b/carla_ego_vehicle/config/settings.yaml @@ -0,0 +1,21 @@ +ego_vehicle_node: + ros__parameters: + use_sim_time: true + carla: + # the network connection for the python connection to CARLA + host: localhost + port: 2000 + # vehicles + vehicle_filter: vehicle.* + # enable/disable synchronous mode. If enabled ros-bridge waits until + # expected data is received for all sensors + synchronous_mode: true + synchronous_mode_wait_for_vehicle_control_command: false + # set the fixed timestep length + fixed_delta_seconds: 0.05 + # configuration values for the ego vehicle + ego_vehicle: + # the role name of the vehicles that acts as ego vehicle for this ros bridge instance + # Only the vehicles within this list are controllable from within ROS. + # (the vehicle from CARLA is selected which has the attribute 'role_name' set to this value) + role_name: ["hero", "ego_vehicle"] diff --git a/carla_ego_vehicle/package.xml b/carla_ego_vehicle/package.xml index 9e07e85b..9f5a4d3e 100644 --- a/carla_ego_vehicle/package.xml +++ b/carla_ego_vehicle/package.xml @@ -1,16 +1,26 @@ - + + carla_ego_vehicle 0.0.0 The carla_ego_vehicle package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy - topic_tools + + + rclpy + + + catkin + rospy + roslaunch + rospy + rospy + std_msgs + topic_tools + + catkin + ament_python diff --git a/carla_ego_vehicle/resource/carla_ego_vehicle b/carla_ego_vehicle/resource/carla_ego_vehicle new file mode 100644 index 00000000..e69de29b diff --git a/carla_ego_vehicle/setup.cfg b/carla_ego_vehicle/setup.cfg new file mode 100644 index 00000000..881fac0a --- /dev/null +++ b/carla_ego_vehicle/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_ego_vehicle +[install] +install-scripts=$base/lib/carla_ego_vehicle diff --git a/carla_ego_vehicle/setup.py b/carla_ego_vehicle/setup.py index 4449d475..b4a0b071 100644 --- a/carla_ego_vehicle/setup.py +++ b/carla_ego_vehicle/setup.py @@ -1,13 +1,45 @@ """ Setup for carla_ego_vehicle """ +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_ego_vehicle'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_ego_vehicle'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_ego_vehicle' + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', + ['config/settings.yaml', 'config/sensors.json']) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ego vehicle for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'ego_vehicle = src.carla_ego_vehicle.carla_ego_vehicle:main' + ], + }, + ) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 8a5d7110..9897510f 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -16,29 +16,49 @@ /initialpose might be published via RVIZ '2D Pose Estimate" button. """ - -from abc import abstractmethod - +import json +import math import os import random -import math -import json -import rospy -from tf.transformations import euler_from_quaternion, quaternion_from_euler +from abc import abstractmethod + +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + import rospy + from tf.transformations import euler_from_quaternion, quaternion_from_euler + from ros_compatibility import CompatibleNode + + +elif ROS_VERSION == 2: + import sys + import os + print(os.getcwd()) + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + import rclpy + from rclpy.node import Node + from rclpy import executors + from ament_index_python.packages import get_package_share_directory + from transformations.transformations import euler_from_quaternion, quaternion_from_euler + from ros_compatible_node import CompatibleNode + from geometry_msgs.msg import PoseWithCovarianceStamped, Pose -from carla_msgs.msg import CarlaWorldInfo +from carla_msgs.msg import CarlaStatus, CarlaWorldInfo import carla secure_random = random.SystemRandom() + +# TODO: Add launch files. + # ============================================================================== # -- CarlaEgoVehicle ------------------------------------------------------------ # ============================================================================== -class CarlaEgoVehicle(object): - +class CarlaEgoVehicle(CompatibleNode): """ Handles the spawning of the ego vehicle and its sensors @@ -46,22 +66,36 @@ class CarlaEgoVehicle(object): """ def __init__(self): - rospy.init_node('ego_vehicle', anonymous=True) - self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', '2000') - self.timeout = rospy.get_param('/carla/timeout', '2') - self.sensor_definition_file = rospy.get_param('~sensor_definition_file') + super(CarlaEgoVehicle, self).__init__('ego_vehicle_node') self.world = None self.player = None self.player_created = False self.sensor_actors = [] - self.actor_filter = rospy.get_param('~vehicle_filter', 'vehicle.*') self.actor_spawnpoint = None - self.role_name = rospy.get_param('~role_name', 'ego_vehicle') - # check argument and set spawn_point - spawn_point_param = rospy.get_param('~spawn_point') - if spawn_point_param and rospy.get_param('~spawn_ego_vehicle'): - rospy.loginfo("Using ros parameter for spawnpoint: {}".format(spawn_point_param)) + self.timeout = self.get_param('/carla/timeout', 2) + + if ROS_VERSION == 1: + self.host = self.get_param('/carla/host', '127.0.0.1') + self.port = self.get_param('/carla/port', '2000') + self.sensor_definition_file = self.get_param('~sensor_definition_file', 'sensors.json') + self.actor_filter = self.get_param('~vehicle_filter', 'vehicle.*') + self.role_name = self.get_param('~role_name', 'ego_vehicle') + # check argument and set spawn_point + spawn_point_param = self.get_param('~spawn_point') + + + elif ROS_VERSION == 2: + self.host = self.get_param('carla.host', 'localhost') + self.port = self.get_param('carla.port', 2000) + sensor_path = get_package_share_directory('carla_ego_vehicle') + '/config/sensors.json' + self.sensor_definition_file = self.get_param('sensor_definition_file', sensor_path) + self.actor_filter = self.get_param('vehicle_filter', 'vehicle.*') + self.role_name = self.get_param('role_name', 'ego_vehicle') + # check argument and set spawn_point + spawn_point_param = self.get_param('spawn_point') + + if spawn_point_param and self.spawn_ego_vehicle(): + self.loginfo("Using ros parameter for spawnpoint: {}".format(spawn_point_param)) spawn_point = spawn_point_param.split(',') if len(spawn_point) != 6: raise ValueError("Invalid spawnpoint '{}'".format(spawn_point_param)) @@ -79,12 +113,20 @@ def __init__(self): pose.orientation.w = quat[3] self.actor_spawnpoint = pose - self.initialpose_subscriber = rospy.Subscriber( - "/carla/{}/initialpose".format(self.role_name), - PoseWithCovarianceStamped, - self.on_initialpose) - rospy.loginfo('listening to server %s:%s', self.host, self.port) - rospy.loginfo('using vehicle filter: %s', self.actor_filter) + self.initialpose_subscriber = self.create_subscriber(PoseWithCovarianceStamped, + "/carla/{}/initialpose".format(self.role_name), + self.on_initialpose) + + self.loginfo("listening to server {}:{}".format(self.host, self.port)) + self.loginfo("using vehicle filter: {}".format(self.actor_filter)) + + + def spawn_ego_vehicle(self): + if ROS_VERSION == 1: + return self.get_param('~spawn_ego_vehicle') + elif ROS_VERSION == 2: + return self.get_parameter('spawn_ego_vehicle') + def on_initialpose(self, initial_pose): """ @@ -113,7 +155,7 @@ def restart(self): color = secure_random.choice(blueprint.get_attribute('color').recommended_values) blueprint.set_attribute('color', color) # Spawn the vehicle. - if not rospy.get_param('~spawn_ego_vehicle'): + if not self.spawn_ego_vehicle(): actors = self.world.get_actors().filter(self.actor_filter) for actor in actors: if actor.attributes['role_name'] == self.role_name: @@ -125,7 +167,7 @@ def restart(self): spawn_point.location.x = self.actor_spawnpoint.position.x spawn_point.location.y = -self.actor_spawnpoint.position.y spawn_point.location.z = self.actor_spawnpoint.position.z + \ - 2 # spawn 2m above ground + 2 # spawn 2m above ground quaternion = ( self.actor_spawnpoint.orientation.x, self.actor_spawnpoint.orientation.y, @@ -134,11 +176,11 @@ def restart(self): ) _, _, yaw = euler_from_quaternion(quaternion) spawn_point.rotation.yaw = -math.degrees(yaw) - rospy.loginfo("Spawn {} at x={} y={} z={} yaw={}".format(self.role_name, - spawn_point.location.x, - spawn_point.location.y, - spawn_point.location.z, - spawn_point.rotation.yaw)) + self.loginfo("Spawn {} at x={} y={} z={} yaw={}".format(self.role_name, + spawn_point.location.x, + spawn_point.location.y, + spawn_point.location.z, + spawn_point.rotation.yaw)) if self.player is not None: self.player.set_transform(spawn_point) while self.player is None: @@ -314,7 +356,7 @@ def setup_sensors(self, sensors): bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) bp.set_attribute('range', str(sensor_spec['range'])) except KeyError as e: - rospy.logfatal( + self.logfatal( "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) raise e @@ -350,32 +392,32 @@ def run(self): """ main loop """ - # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") - try: - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException as e: - rospy.logerr("Timeout while waiting for world info!") - raise e - rospy.loginfo("CARLA world available. Spawn ego vehicle...") + if ROS_VERSION == 1: + # wait for ros-bridge to set up CARLA world + rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") + try: + rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) + except rospy.ROSException: + rospy.logerr("Timeout while waiting for world info!") + sys.exit(1) + + self.loginfo("CARLA world available. Spawn ego vehicle...") client = carla.Client(self.host, self.port) client.set_timeout(self.timeout) self.world = client.get_world() self.restart() + self.loginfo("Ego spawned.") try: - rospy.spin() - except rospy.ROSInterruptException: - pass - -# ============================================================================== -# -- main() -------------------------------------------------------------------- -# ============================================================================== + self.spin() + except: + self.shutdown() -def main(): +def run_ego_vehicle(msg): """ - main function + Callback function: + Called when bridge started - indicated by published /carla/status topic and runs CarlaEgoVehicle afterwards """ ego_vehicle = CarlaEgoVehicle() try: @@ -385,5 +427,26 @@ def main(): ego_vehicle.destroy() +def main(): + """ + main function + """ + + if ROS_VERSION == 1: + run_ego_vehicle(None) + + elif ROS_VERSION == 2: + # Setup init_ego node. + rclpy.init(args=None) + executor = rclpy.executors.MultiThreadedExecutor() + init_node = rclpy.create_node("init_ego") + init_node.create_subscription(CarlaStatus, + '/carla/status', + run_ego_vehicle, + 1) + executor.add_node(init_node) + init_node.get_logger().info("Waiting for carla_bridge to start...") + executor.spin() + if __name__ == '__main__': main() From 26c76d091547b11075cad1ddfc93c6514d26d47b Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 22 May 2020 13:30:52 +0200 Subject: [PATCH 056/627] add ros_compatibility --- ros_compatibility/CMakeLists.txt | 39 ++++++++ ros_compatibility/__init__.py | 1 + ros_compatibility/package.xml | 26 +++++ ros_compatibility/resource/ros_compatibility | 0 ros_compatibility/setup.cfg | 4 + ros_compatibility/setup.py | 44 +++++++++ ros_compatibility/src/__init__.py | 0 .../src/ros_compatibility/__init__.py | 4 + .../ros_compatibility/ros_compatible_node.py | 95 +++++++++++++++++++ 9 files changed, 213 insertions(+) create mode 100644 ros_compatibility/CMakeLists.txt create mode 100644 ros_compatibility/__init__.py create mode 100644 ros_compatibility/package.xml create mode 100644 ros_compatibility/resource/ros_compatibility create mode 100644 ros_compatibility/setup.cfg create mode 100644 ros_compatibility/setup.py create mode 100644 ros_compatibility/src/__init__.py create mode 100644 ros_compatibility/src/ros_compatibility/__init__.py create mode 100644 ros_compatibility/src/ros_compatibility/ros_compatible_node.py diff --git a/ros_compatibility/CMakeLists.txt b/ros_compatibility/CMakeLists.txt new file mode 100644 index 00000000..ccb664f4 --- /dev/null +++ b/ros_compatibility/CMakeLists.txt @@ -0,0 +1,39 @@ +cmake_minimum_required(VERSION 2.8.3) +project(ros_compatibility) + +# Update the policy setting to avoid an error when loading the ament_cmake package +# at the current cmake version level +if(POLICY CMP0057) + cmake_policy(SET CMP0057 NEW) +endif() + +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) + +if (${ROS_VERSION} EQUAL 1) + + find_package(catkin REQUIRED COMPONENTS + rospy + ) + + catkin_python_setup() + + catkin_package( + CATKIN_DEPENDS + rospy + ) + + include_directories() + + catkin_install_python( + PROGRAMS src/ros_compatibility/ros_compatible_node.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + +endif() diff --git a/ros_compatibility/__init__.py b/ros_compatibility/__init__.py new file mode 100644 index 00000000..0c1cfee4 --- /dev/null +++ b/ros_compatibility/__init__.py @@ -0,0 +1 @@ +from ros_compatibility.src.ros_compatibility.ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/package.xml b/ros_compatibility/package.xml new file mode 100644 index 00000000..f08a9b15 --- /dev/null +++ b/ros_compatibility/package.xml @@ -0,0 +1,26 @@ + + + + ros_compatibility + 0.0.0 + The ros_compatibility package + CARLA Simulator Team + MIT + + + rclpy + + + catkin + rospy + std_msgs + rospy + std_msgs + rospy + std_msgs + + + catkin + ament_python + + diff --git a/ros_compatibility/resource/ros_compatibility b/ros_compatibility/resource/ros_compatibility new file mode 100644 index 00000000..e69de29b diff --git a/ros_compatibility/setup.cfg b/ros_compatibility/setup.cfg new file mode 100644 index 00000000..9c25a3a8 --- /dev/null +++ b/ros_compatibility/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/ros_compatibility +[install] +install-scripts=$base/lib/ros_compatibility diff --git a/ros_compatibility/setup.py b/ros_compatibility/setup.py new file mode 100644 index 00000000..55754977 --- /dev/null +++ b/ros_compatibility/setup.py @@ -0,0 +1,44 @@ +import os + +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup + + d = generate_distutils_setup( + packages=['ros_compatibility'], + package_dir={'': 'src'} + ) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'ros_compatibility' + + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + py_modules=[ + 'src.ros_compatibility.ros_compatible_node'], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='The ros_compatibility package', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'ros_compatible_node = src.ros_compatibility.ros_compatible_node:main' + ], + }, + ) diff --git a/ros_compatibility/src/__init__.py b/ros_compatibility/src/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py new file mode 100644 index 00000000..3c2a8ca4 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -0,0 +1,4 @@ +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) +if ROS_VERSION == 1: + from ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py new file mode 100644 index 00000000..56f513d1 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -0,0 +1,95 @@ +import os + +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + import rospy + + + class QoSProfile(): + def __init__(self, **kwargs): + self.depth = kwargs['depth'] + + + class CompatibleNode(object): + def __init__(self, node_name, queue_size=10): + rospy.init_node(node_name, anonymous=True) + self.qos_profile = QoSProfile(depth=queue_size) + + def get_param(self, name, alternative_value=None, alternative_name=None): + if alternative_value is None: + return rospy.get_param(name) + return rospy.get_param(name, alternative_value) + + def loginfo(self, text): + rospy.loginfo(text) + + def logfatal(self, arg): + rospy.logfatal(arg) + + def create_subscriber(self, msg_type, topic, + callback, qos_profile=None): + if qos_profile is None: + qos_profile = self.qos_profile + return rospy.Subscriber(topic, msg_type, + callback, queue_size=qos_profile.depth) + + def spin(self): + rospy.spin() + + def shutdown(self): + pass + +elif ROS_VERSION == 2: + from rclpy.node import Node + from rclpy import Parameter + from rclpy.qos import QoSProfile + import rclpy + + + class CompatibleNode(Node): + def __init__(self, node_name, queue_size=10): + super().__init__(node_name, allow_undeclared_parameters=True, + automatically_declare_parameters_from_overrides=True) + self.logger = self.get_logger() + self.qos_profile = QoSProfile(depth=queue_size) + + def get_param(self, name, alternative_value=None, alternative_name=None): + if alternative_value is None: + return self.get_parameter(name).value + if alternative_name is None: + alternative_name = name + return self.get_parameter_or(name, + Parameter(alternative_name, value=alternative_value)).value + + def loginfo(self, text): + self.logger.info(text) + + def logfatal(self, arg): + self.logger.fatal(arg) + + def create_subscriber(self, msg_type, topic, + callback, qos_profile=None): + if qos_profile is None: + qos_profile = self.qos_profile + return self.create_subscription(msg_type, topic, + callback, qos_profile) + + def spin(self): + rclpy.spin(self) + + def shutdown(self): + rclpy.shutdown() + +else: + raise NotImplementedError("Make sure you have valid " + + "ROS_VERSION env variable"); + + +def main(): + print('This is a ros1 - ros2 compatibility module.', + "It's not meant to be executed, but rather imported") + + +if __name__ == '__main__': + main() From 12c7a33924db854e76517245b196c8c1cbe27611 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 14:31:31 +0200 Subject: [PATCH 057/627] Limit colcon to build carla_msgs only --- docker/Dockerfile.eloquent | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent index f630ee8c..a537f47e 100644 --- a/docker/Dockerfile.eloquent +++ b/docker/Dockerfile.eloquent @@ -41,8 +41,9 @@ RUN echo "source /carla_ws/devel/setup.bash" >> ~/.bashrc SHELL ["/bin/bash", "-c" , "-l"] RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment -RUN rosdep install --from-paths src -r +RUN rosdep install --from-paths src/carla_msgs -r -y RUN colcon info carla_msgs -RUN colcon build --symlink-install +# .bashrc does not seem to do the source +RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --packages-select carla_msgs -CMD ["ros2", "run", "carla_msgs" , "simple_publisher.py"] +CMD ["ros2", "run", "carla_ros_bridge" , "carla_ros_bridge.py"] From 879eba5c92d23cbcc538a9c0cbdc2421e2b4e42d Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 14:34:05 +0200 Subject: [PATCH 058/627] Use carla_msgs with ROS2 compatibility --- carla_msgs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_msgs b/carla_msgs index 708e9c83..0501e759 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 708e9c830bbd1637f89b5cf49dae8c3a327d021a +Subproject commit 0501e759321ce314a230e814a58e43cbb66d1fa2 From 9ed3c503af3faf938079804d3c125fa7b530fcd5 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 15:12:20 +0200 Subject: [PATCH 059/627] Add ignore for temporary vscode --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 1f93b7e8..ade5bf10 100644 --- a/.gitignore +++ b/.gitignore @@ -2,3 +2,4 @@ build.gradle /CMakeLists.txt .catkin_workspace +.vscode/ From 1f122c7b9531a5735b65b99711ad35cdebe51f8b Mon Sep 17 00:00:00 2001 From: Diego-ort Date: Fri, 22 May 2020 15:20:12 +0200 Subject: [PATCH 060/627] Modification of the meta-files of the carla_manual_control and carla_ros_bridge modules --- carla_manual_control/CMakeLists.txt | 44 +++++++------ carla_manual_control/package.xml | 29 ++++++--- carla_manual_control/setup.cfg | 4 ++ carla_manual_control/setup.py | 46 +++++++++++--- carla_ros_bridge/CMakeLists.txt | 95 ++++++++++++++++------------- carla_ros_bridge/package.xml | 56 ++++++++++------- carla_ros_bridge/setup.cfg | 4 ++ carla_ros_bridge/setup.py | 46 +++++++++++--- 8 files changed, 220 insertions(+), 104 deletions(-) create mode 100644 carla_manual_control/setup.cfg create mode 100644 carla_ros_bridge/setup.cfg diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index 8a43818a..c3be3b60 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -1,25 +1,35 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_manual_control) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(ament_cmake QUIET) +if ( ament_cmake_FOUND ) + find_package(rclpy REQUIRED) -catkin_python_setup() + ament_export_dependencies(rclpy) + ament_package() -roslaunch_add_file_check(launch) +elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) + + find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch + ) -catkin_package( - CATKIN_DEPENDS - rospy -) + catkin_python_setup() -catkin_install_python(PROGRAMS - src/carla_manual_control/carla_manual_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) + roslaunch_add_file_check(launch) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + catkin_package( + CATKIN_DEPENDS + rospy + ) + + catkin_install_python(PROGRAMS + src/carla_manual_control/carla_manual_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + ) +endif() diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index 1fd821f9..5e736ee2 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -5,14 +5,27 @@ The carla_manual_control package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy - carla_msgs - sensor_msgs - std_msgs + + + rclpy + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + catkin + rospy + roslaunch + rospy + rospy + carla_msgs + sensor_msgs + std_msgs + + + catkin + ament_python diff --git a/carla_manual_control/setup.cfg b/carla_manual_control/setup.cfg new file mode 100644 index 00000000..18dba7db --- /dev/null +++ b/carla_manual_control/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_manual_control +[install] +install-scripts=$base/lib/carla_manual_control diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index 2a8638ad..baaae96c 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -1,13 +1,45 @@ """ Setup for carla_manual_control """ +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_manual_control'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_manual_control'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_manual_control' + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', + ['config/settings.yaml', 'config/sensors.json']) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ego vehicle for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'manual_control = carla_manual_control.carla_manual_control:main' + ], + }, + ) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 7e212f75..508ab8f6 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -2,47 +2,56 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_bridge) ## Find catkin macros and libraries -find_package(catkin REQUIRED COMPONENTS - rospy - sensor_msgs - geometry_msgs - derived_object_msgs - ainstein_radar_msgs - tf - roslaunch -) - -catkin_python_setup() - -catkin_package() - -roslaunch_add_file_check(launch) -roslaunch_add_file_check(test) - -include_directories( - ${catkin_INCLUDE_DIRS} -) - -install(PROGRAMS - src/carla_ros_bridge/bridge.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) - -install(FILES - test/ros_bridge_client.test - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) - -install(DIRECTORY - config - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) - -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) - -if(CATKIN_ENABLE_TESTING AND NOT $ENV{CI}) - find_package(rostest REQUIRED) - add_rostest(test/ros_bridge_client.test) +find_package(ament_cmake QUIET) +if ( ament_cmake_FOUND ) + find_package(rclpy REQUIRED) + + ament_export_dependencies(rclpy) + ament_package() + +elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) + + find_package(catkin REQUIRED COMPONENTS + rospy + sensor_msgs + geometry_msgs + derived_object_msgs + ainstein_radar_msgs + tf + roslaunch + ) + + catkin_python_setup() + + catkin_package() + + roslaunch_add_file_check(launch) + + include_directories( + ${catkin_INCLUDE_DIRS} + ) + + install(PROGRAMS + src/carla_ros_bridge/bridge.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + install(FILES + test/ros_bridge_client.test + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + ) + + install(DIRECTORY + config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + ) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + ) + + if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + add_rostest(test/ros_bridge_client.test) + endif() endif() diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index e94f23d1..2429de54 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -5,28 +5,40 @@ The carla_ros_bridge package CARLA Simulator Team MIT - catkin - roslaunch - ainstein_radar_msgs - rospy - sensor_msgs - visualization_msgs - tf - tf2 - rviz - cv_bridge - geometry_msgs - std_msgs - rosbag_storage - derived_object_msgs - shape_msgs - nav_msgs - tf2_msgs - rosgraph_msgs - cv_bridge - carla_msgs - carla_ego_vehicle - carla_manual_control + + + rclpy + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + catkin + roslaunch + ainstein_radar_msgs + rospy + sensor_msgs + visualization_msgs + tf + tf2 + rviz + cv_bridge + geometry_msgs + std_msgs + rosbag_storage + derived_object_msgs + shape_msgs + nav_msgs + tf2_msgs + rosgraph_msgs + cv_bridge + carla_msgs + carla_ego_vehicle + carla_manual_control + + catkin + ament_python diff --git a/carla_ros_bridge/setup.cfg b/carla_ros_bridge/setup.cfg new file mode 100644 index 00000000..bf9eb67b --- /dev/null +++ b/carla_ros_bridge/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_ros_bridge +[install] +install-scripts=$base/lib/carla_ros_bridge diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index f4bdc1a1..0346c466 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -1,13 +1,45 @@ """ Setup for carla_ros_bridge """ +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup + if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_ros_bridge'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_ros_bridge'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_ros_bridge' + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', + ['config/settings.yaml', 'config/sensors.json']) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ego vehicle for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'bridge = carla_ros_bridge.bridge:main' + ], + }, + ) From 6978df2f94b8b9b585a301da6a40d4263ee4d38f Mon Sep 17 00:00:00 2001 From: Diego-ort Date: Fri, 22 May 2020 16:54:55 +0200 Subject: [PATCH 061/627] Correction of meta-files --- carla_manual_control/CMakeLists.txt | 17 ++++++++++------- carla_manual_control/package.xml | 7 ++----- carla_manual_control/setup.py | 2 +- carla_ros_bridge/CMakeLists.txt | 18 ++++++++++-------- carla_ros_bridge/package.xml | 9 +++------ carla_ros_bridge/setup.py | 4 ++-- 6 files changed, 28 insertions(+), 29 deletions(-) diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index c3be3b60..ed7e27e6 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -1,15 +1,11 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_manual_control) -find_package(ament_cmake QUIET) -if ( ament_cmake_FOUND ) - find_package(rclpy REQUIRED) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) - ament_export_dependencies(rclpy) - ament_package() +if (${ROS_VERSION} EQUAL 1) -elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) - find_package(catkin REQUIRED COMPONENTS rospy roslaunch @@ -32,4 +28,11 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch ) + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + endif() diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index 5e736ee2..2d9012ed 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -1,5 +1,6 @@ - + + carla_manual_control 0.0.0 The carla_manual_control package @@ -8,10 +9,6 @@ rclpy - ament_copyright - ament_flake8 - ament_pep257 - python3-pytest catkin diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index baaae96c..dc4e3602 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -34,7 +34,7 @@ zip_safe=True, maintainer='CARLA Simulator Team', maintainer_email='carla.simulator@gmail.com', - description='CARLA ego vehicle for ROS2 bridge', + description='CARLA manual control for ROS2 bridge', license='MIT', tests_require=['pytest'], entry_points={ diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 508ab8f6..40f8d871 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -1,15 +1,10 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_bridge) -## Find catkin macros and libraries -find_package(ament_cmake QUIET) -if ( ament_cmake_FOUND ) - find_package(rclpy REQUIRED) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) - ament_export_dependencies(rclpy) - ament_package() - -elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) +if (${ROS_VERSION} EQUAL 1) find_package(catkin REQUIRED COMPONENTS rospy @@ -54,4 +49,11 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) find_package(rostest REQUIRED) add_rostest(test/ros_bridge_client.test) endif() + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + endif() diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 2429de54..b0be55bb 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -1,17 +1,14 @@ - + + carla_ros_bridge - 0.0.1 + 0.0.0 The carla_ros_bridge package CARLA Simulator Team MIT rclpy - ament_copyright - ament_flake8 - ament_pep257 - python3-pytest catkin diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index 0346c466..b6a90900 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -4,7 +4,7 @@ import os ROS_VERSION = int(os.environ['ROS_VERSION']) - if ROS_VERSION == 1: +if ROS_VERSION == 1: from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup @@ -34,7 +34,7 @@ zip_safe=True, maintainer='CARLA Simulator Team', maintainer_email='carla.simulator@gmail.com', - description='CARLA ego vehicle for ROS2 bridge', + description='CARLA ROS2 bridge', license='MIT', tests_require=['pytest'], entry_points={ From fd7eb7951959c79db3e8dbfe97a09e0ec9e448ba Mon Sep 17 00:00:00 2001 From: Diego-ort Date: Fri, 22 May 2020 17:14:27 +0200 Subject: [PATCH 062/627] Corrections of data_file[] arguments of setup.py files of both modules --- carla_manual_control/setup.py | 2 -- carla_ros_bridge/setup.py | 3 +-- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index dc4e3602..b2dd051f 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -27,8 +27,6 @@ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - ('share/' + package_name + '/config', - ['config/settings.yaml', 'config/sensors.json']) ], install_requires=['setuptools'], zip_safe=True, diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index b6a90900..b2c744c6 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -27,8 +27,7 @@ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - ('share/' + package_name + '/config', - ['config/settings.yaml', 'config/sensors.json']) + (os.path.join('share', package_name), glob('launch/*.launch.py')), ], install_requires=['setuptools'], zip_safe=True, From 5f914ea54081c51da957c5b3eaaee4ac50fa6d07 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 17:54:01 +0200 Subject: [PATCH 063/627] Avoid key error by using get() --- ros_compatibility/src/ros_compatibility/__init__.py | 2 +- ros_compatibility/src/ros_compatibility/ros_compatible_node.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py index 3c2a8ca4..bd5614f4 100644 --- a/ros_compatibility/src/ros_compatibility/__init__.py +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -1,4 +1,4 @@ import os -ROS_VERSION = int(os.environ['ROS_VERSION']) +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: from ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 56f513d1..d0fd3110 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -1,6 +1,6 @@ import os -ROS_VERSION = int(os.environ['ROS_VERSION']) +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: import rospy From f2ff4582f9c0de119dfede445b4423c41aa91b68 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 17:57:15 +0200 Subject: [PATCH 064/627] Remove semicolon --- ros_compatibility/src/ros_compatibility/ros_compatible_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index d0fd3110..92283751 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -83,7 +83,7 @@ def shutdown(self): else: raise NotImplementedError("Make sure you have valid " + - "ROS_VERSION env variable"); + "ROS_VERSION env variable") def main(): From 72dfc2e7d2424582844ea9d98fc56fc2c7f6391f Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 17:59:56 +0200 Subject: [PATCH 065/627] Use uniform ' --- .../src/ros_compatibility/ros_compatible_node.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 92283751..58912265 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -82,13 +82,13 @@ def shutdown(self): rclpy.shutdown() else: - raise NotImplementedError("Make sure you have valid " + - "ROS_VERSION env variable") + raise NotImplementedError('Make sure you have valid ' + + 'ROS_VERSION env variable') def main(): print('This is a ros1 - ros2 compatibility module.', - "It's not meant to be executed, but rather imported") + 'It's not meant to be executed, but rather imported') if __name__ == '__main__': From 0648bcabdc984c6f723d42a37e3a1464da3a6793 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 18:06:29 +0200 Subject: [PATCH 066/627] Add ros_compatibility node to dockerfile --- docker/Dockerfile.eloquent | 4 ++-- .../src/ros_compatibility/ros_compatible_node.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent index a537f47e..39ba0049 100644 --- a/docker/Dockerfile.eloquent +++ b/docker/Dockerfile.eloquent @@ -41,9 +41,9 @@ RUN echo "source /carla_ws/devel/setup.bash" >> ~/.bashrc SHELL ["/bin/bash", "-c" , "-l"] RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment -RUN rosdep install --from-paths src/carla_msgs -r -y +RUN rosdep install --from-paths src/carla_msgs src/ros_compatibility -r -y RUN colcon info carla_msgs # .bashrc does not seem to do the source -RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --packages-select carla_msgs +RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --packages-select carla_msgs ros_compatibility CMD ["ros2", "run", "carla_ros_bridge" , "carla_ros_bridge.py"] diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 58912265..29665cfd 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -88,7 +88,7 @@ def shutdown(self): def main(): print('This is a ros1 - ros2 compatibility module.', - 'It's not meant to be executed, but rather imported') + 'It is not meant to be executed, but rather imported') if __name__ == '__main__': From 83bf3a5da1236a836590752d28dae5a611df76e8 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 22 May 2020 18:42:12 +0200 Subject: [PATCH 067/627] Convert carla_manula_conrol --- .../carla_manual_control.py | 277 +++++++++++++----- 1 file changed, 210 insertions(+), 67 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index ebf2dddc..681c1d1c 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -27,13 +27,41 @@ """ from __future__ import print_function - +# import random +import os import datetime import math import numpy -import rospy -import tf +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + import rospy + from tf import LookupException + from tf import ConnectivityException + from tf import ExtrapolationException + import tf + from ros_compatibility import CompatibleNode, QoSProfile + +elif ROS_VERSION == 2: + # TODO: Optimise ros2 imports + import rclpy + from rclpy.callback_groups import ReentrantCallbackGroup + from transformations import euler_from_quaternion + import transformations as tf + import cv2 + import time + from tf2_ros import LookupException + from tf2_ros import ConnectivityException + from tf2_ros import ExtrapolationException + import tf2_ros + from rclpy.qos import QoSProfile + from threading import Thread, Lock, Event + from builtin_interfaces.msg import Time + + sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + from ros_compatible_node import CompatibleNode + from std_msgs.msg import Bool from sensor_msgs.msg import NavSatFix from sensor_msgs.msg import Image @@ -76,30 +104,38 @@ # ============================================================================== -class World(object): +class World(CompatibleNode): """ Handle the rendering """ def __init__(self, role_name, hud): + super(World, self).__init__("World", rospy_init=False) self._surface = None self.hud = hud self.role_name = role_name - self.image_subscriber = rospy.Subscriber( - "/carla/{}/camera/rgb/view/image_color".format(self.role_name), - Image, self.on_view_image) - self.collision_subscriber = rospy.Subscriber( - "/carla/{}/collision".format(self.role_name), CarlaCollisionEvent, self.on_collision) - self.lane_invasion_subscriber = rospy.Subscriber( - "/carla/{}/lane_invasion".format(self.role_name), - CarlaLaneInvasionEvent, self.on_lane_invasion) + + if ROS_VERSION == 2: + self.callback_group = ReentrantCallbackGroup() + + self.image_subscriber = self.create_subscriber(Image, + "/carla/{}/camera/rgb/view/image_color".format(self.role_name), + self.on_view_image) + + self.collision_subscriber = self.create_subscriber(CarlaCollisionEvent, + "/carla/{}/collision".format(self.role_name), + self.on_collision) + + self.lane_invasion_subscriber = self.create_subscriber(CarlaLaneInvasionEvent, + "/carla/{}/lane_invasion".format(self.role_name), + self.on_lane_invasion) def on_collision(self, data): """ Callback on collision event """ - intensity = math.sqrt(data.normal_impulse.x**2 + - data.normal_impulse.y**2 + data.normal_impulse.z**2) + intensity = math.sqrt(data.normal_impulse.x ** 2 + + data.normal_impulse.y ** 2 + data.normal_impulse.z ** 2) self.hud.notification('Collision with {} (impulse {})'.format( data.other_actor_id, intensity)) @@ -141,21 +177,27 @@ def destroy(self): """ destroy all objects """ - self.image_subscriber.unregister() - self.collision_subscriber.unregister() - self.lane_invasion_subscriber.unregister() + if ROS_VERSION == 1: + self.image_subscriber.unregister() + self.collision_subscriber.unregister() + self.lane_invasion_subscriber.unregister() + elif ROS_VERSION == 2: + self.image_subscriber.destroy() + self.collision_subscriber.destroy() + self.lane_invasion_subscriber.destroy() # ============================================================================== # -- KeyboardControl ----------------------------------------------------------- # ============================================================================== -class KeyboardControl(object): +class KeyboardControl(CompatibleNode): """ Handle input events """ def __init__(self, role_name, hud): + super(KeyboardControl, self).__init__("keyboard_control", rospy_init=False) self.role_name = role_name self.hud = hud @@ -163,17 +205,30 @@ def __init__(self, role_name, hud): self._control = CarlaEgoVehicleControl() self._steer_cache = 0.0 - self.vehicle_control_manual_override_publisher = rospy.Publisher( - "/carla/{}/vehicle_control_manual_override".format(self.role_name), - Bool, queue_size=1, latch=True) + if ROS_VERSION == 2: + self.callback_group = ReentrantCallbackGroup() + + fast_qos_profile = QoSProfile(depth=1) + + self.vehicle_control_manual_override_publisher = self.new_publisher(Bool, + "/carla/{}/vehicle_control_manual_override".format( + self.role_name), + qos_profile=fast_qos_profile) + self.vehicle_control_manual_override = False - self.auto_pilot_enable_publisher = rospy.Publisher( - "/carla/{}/enable_autopilot".format(self.role_name), Bool, queue_size=1) - self.vehicle_control_publisher = rospy.Publisher( - "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), - CarlaEgoVehicleControl, queue_size=1) - self.carla_status_subscriber = rospy.Subscriber( - "/carla/status", CarlaStatus, self._on_new_carla_frame) + + self.auto_pilot_enable_publisher = self.new_publisher(Bool, + "/carla/{}/enable_autopilot".format(self.role_name), + qos_profile=fast_qos_profile) + + self.vehicle_control_publisher = self.new_publisher(CarlaEgoVehicleControl, + "/carla/{}/vehicle_control_cmd_manual".format( + self.role_name), + qos_profile=fast_qos_profile) + + self.carla_status_subscriber = self.create_subscriber(CarlaStatus, + "/carla/status", + self._on_new_carla_frame) self.set_autopilot(self._autopilot_enabled) @@ -181,9 +236,14 @@ def __init__(self, role_name, hud): self.vehicle_control_manual_override) # disable manual override def __del__(self): - self.auto_pilot_enable_publisher.unregister() - self.vehicle_control_publisher.unregister() - self.vehicle_control_manual_override_publisher.unregister() + if ROS_VERSION == 1: + self.auto_pilot_enable_publisher.unregister() + self.vehicle_control_publisher.unregister() + self.vehicle_control_manual_override_publisher.unregister() + elif ROS_VERSION == 2: + self.auto_pilot_enable_publisher.destroy() + self.vehicle_control_publisher.destroy() + self.vehicle_control_manual_override_publisher.destroy() def set_vehicle_control_manual_override(self, enable): """ @@ -246,8 +306,8 @@ def _on_new_carla_frame(self, data): if not self._autopilot_enabled and self.vehicle_control_manual_override: try: self.vehicle_control_publisher.publish(self._control) - except ROSException as error: - rospy.logwarn("Could not send vehicle control: {}".format(error)) + except Exception as error: + self.logwarn("Could not send vehicle control: {}".format(error)) def _parse_vehicle_keys(self, keys, milliseconds): """ @@ -276,12 +336,13 @@ def _is_quit_shortcut(key): # ============================================================================== -class HUD(object): +class HUD(CompatibleNode): """ Handle the info display """ def __init__(self, role_name, width, height): + super(HUD, self).__init__(role_name, rospy_init=False) self.role_name = role_name self.dim = (width, height) font = pygame.font.Font(pygame.font.get_default_font(), 20) @@ -295,31 +356,63 @@ def __init__(self, role_name, width, height): self._show_info = True self._info_text = [] self.vehicle_status = CarlaEgoVehicleStatus() - self.tf_listener = tf.TransformListener() - self.vehicle_status_subscriber = rospy.Subscriber( - "/carla/{}/vehicle_status".format(self.role_name), - CarlaEgoVehicleStatus, self.vehicle_status_updated) + + if ROS_VERSION == 1: + self.tf_listener = tf.TransformListener() + elif ROS_VERSION == 2: + self.tf_listener_node = rclpy.create_node("tf_listener") + self.tfBuffer = tf2_ros.Buffer() + self.tf_listener = tf2_ros.TransformListener(self.tfBuffer, node=self.tf_listener_node) + # for pub in self.tf_listener.node.publishers: + # print(pub.topic) + self.time = Time() + self.callback_group = ReentrantCallbackGroup() + + self.vehicle_status_subscriber = self.create_subscriber(CarlaEgoVehicleStatus, + "/carla/{}/vehicle_status".format(self.role_name), + self.vehicle_status_updated) + + self.vehicle_status_subscriber = self.create_subscriber(CarlaEgoVehicleStatus, + "/carla/{}/vehicle_status".format(self.role_name), + self.vehicle_status_updated) + self.vehicle_info = CarlaEgoVehicleInfo() - self.vehicle_info_subscriber = rospy.Subscriber( - "/carla/{}/vehicle_info".format(self.role_name), - CarlaEgoVehicleInfo, self.vehicle_info_updated) + self.vehicle_info_subscriber = self.create_subscriber(CarlaEgoVehicleInfo, + "/carla/{}/vehicle_info".format(self.role_name), + self.vehicle_info_updated) + self.latitude = 0 self.longitude = 0 self.manual_control = False - self.gnss_subscriber = rospy.Subscriber( - "/carla/{}/gnss/gnss1/fix".format(self.role_name), NavSatFix, self.gnss_updated) - self.manual_control_subscriber = rospy.Subscriber( - "/carla/{}/vehicle_control_manual_override".format(self.role_name), - Bool, self.manual_control_override_updated) + + self.gnss_subscriber = self.create_subscriber(NavSatFix, + "/carla/{}/gnss/gnss1/fix".format(self.role_name), + self.gnss_updated) + + self.manual_control_subscriber = self.create_subscriber(Bool, + "/carla/{}/vehicle_control_manual_override".format( + self.role_name), + self.manual_control_override_updated) self.carla_status = CarlaStatus() - self.status_subscriber = rospy.Subscriber( - "/carla/status", CarlaStatus, self.carla_status_updated) + self.start_frame = None + self.status_subscriber = self.create_subscriber(CarlaStatus, + "/carla/status", + self.carla_status_updated) + if ROS_VERSION == 2: + self.clock_subscriber = self.create_subscriber(Time, + "/clock", + self.clock_status_updated) def __del__(self): - self.gnss_subscriber.unregister() - self.vehicle_status_subscriber.unregister() - self.vehicle_info_subscriber.unregister() + if ROS_VERSION == 1: + self.gnss_subscriber.unregister() + self.vehicle_status_subscriber.unregister() + self.vehicle_info_subscriber.unregister() + elif ROS_VERSION == 2: + self.gnss_subscriber.destroy() + self.vehicle_status_subscriber.destroy() + self.vehicle_info_subscriber.destroy() def tick(self, clock): """ @@ -327,11 +420,16 @@ def tick(self, clock): """ self._notifications.tick(clock) + def clock_status_updated(self, time): + self.time = time + def carla_status_updated(self, data): """ Callback on carla status """ self.carla_status = data + if self.start_frame is None: + self.start_frame = self.carla_status.frame self.update_info_text() def manual_control_override_updated(self, data): @@ -370,14 +468,25 @@ def update_info_text(self): if not self._show_info: return try: - (position, quaternion) = self.tf_listener.lookupTransform( - '/map', self.role_name, rospy.Time()) - _, _, yaw = tf.transformations.euler_from_quaternion(quaternion) - yaw = -math.degrees(yaw) - x = position[0] - y = -position[1] - z = position[2] - except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException): + if ROS_VERSION == 1: + (position, quaternion) = self.tf_listener.lookupTransform( + '/map', self.role_name, rospy.Time()) + _, _, yaw = tf.transformations.euler_from_quaternion(quaternion) + yaw = -math.degrees(yaw) + x = position[0] + y = -position[1] + z = position[2] + elif ROS_VERSION == 2: + when = self.time + q = self.tfBuffer.lookup_transform('map', self.role_name, when) + quaternion = q.transform.rotation + position = q.transform.translation + _, __, yaw = euler_from_quaternion(quaternion) + yaw = -math.degrees(yaw) + x = position.x + y = -position.y + z = position.z + except (LookupException, ConnectivityException, ExtrapolationException): x = 0 y = 0 z = 0 @@ -387,12 +496,18 @@ def update_info_text(self): heading += 'E' if 179.5 > yaw > 0.5 else '' heading += 'W' if -0.5 > yaw > -179.5 else '' fps = 0 + + if ROS_VERSION == 1: + time = int(rospy.get_rostime().to_sec()) + elif ROS_VERSION == 2: + time = float((self.carla_status.frame - self.start_frame) * self.carla_status.fixed_delta_seconds) + if self.carla_status.fixed_delta_seconds: fps = 1 / self.carla_status.fixed_delta_seconds self._info_text = [ 'Frame: % 22s' % self.carla_status.frame, 'Simulation time: % 12s' % datetime.timedelta( - seconds=int(rospy.get_rostime().to_sec())), + seconds=time), 'FPS: % 24.1f' % fps, '', 'Vehicle: % 20s' % ' '.join(self.vehicle_info.type.title().split('.')[1:]), @@ -479,6 +594,7 @@ def render(self, display): self._notifications.render(display) self.help.render(display) + # ============================================================================== # -- FadingText ---------------------------------------------------------------- # ============================================================================== @@ -520,6 +636,7 @@ def render(self, display): """ display.blit(self.surface, self.pos) + # ============================================================================== # -- HelpText ------------------------------------------------------------------ # ============================================================================== @@ -557,18 +674,28 @@ def render(self, display): if self._render: display.blit(self.surface, self.pos) + # ============================================================================== # -- main() -------------------------------------------------------------------- # ============================================================================== -def main(): +def run(executer): + executer.spin() + + +def main(args=None): """ main function """ - rospy.init_node('carla_manual_control', anonymous=True) - - role_name = rospy.get_param("~role_name", "ego_vehicle") + if ROS_VERSION == 1: + rospy.init_node('carla_manual_control', anonymous=True) + role_name = rospy.get_param("~role_name", "ego_vehicle") + elif ROS_VERSION == 2: + rclpy.init(args=args) + node = rclpy.create_node('carla_manual_control') + role_name = rclpy.Parameter("~role_name", value="ego_vehicle").value + thread = Thread() # resolution should be similar to spawned camera with role-name 'view' resolution = {"width": 800, "height": 600} @@ -585,10 +712,18 @@ def main(): hud = HUD(role_name, resolution['width'], resolution['height']) world = World(role_name, hud) controller = KeyboardControl(role_name, hud) - clock = pygame.time.Clock() - while not rospy.core.is_shutdown(): + if ROS_VERSION == 2: + executer = rclpy.executors.MultiThreadedExecutor(num_threads=12) + executer.add_node(hud.tf_listener_node) + executer.add_node(hud.node) + executer.add_node(world.node) + executer.add_node(controller.node) + thread = Thread(target=run, args=(executer,)) + thread.start() + + while not_shutdown(): clock.tick_busy_loop(60) if controller.parse_events(clock): return @@ -599,9 +734,17 @@ def main(): finally: if world is not None: world.destroy() + if ROS_VERSION == 2: + thread.join() pygame.quit() -if __name__ == '__main__': +def not_shutdown(): + if ROS_VERSION == 1: + return not rospy.core.is_shutdown() + elif ROS_VERSION == 2: + return rclpy.ok() + +if __name__ == '__main__': main() From aeda9cb8c41abe46278ff16f0b984f9166eb2b11 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 22 May 2020 18:44:16 +0200 Subject: [PATCH 068/627] Add publisher functionality --- .../ros_compatibility/ros_compatible_node.py | 44 ++++++++++++++++--- 1 file changed, 38 insertions(+), 6 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 56f513d1..f1f80c99 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -12,9 +12,11 @@ def __init__(self, **kwargs): class CompatibleNode(object): - def __init__(self, node_name, queue_size=10): - rospy.init_node(node_name, anonymous=True) + def __init__(self, node_name, queue_size=10, rospy_init=True): + if rospy_init: + rospy.init_node(node_name, anonymous=True) self.qos_profile = QoSProfile(depth=queue_size) + self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_value is None: @@ -24,11 +26,25 @@ def get_param(self, name, alternative_value=None, alternative_name=None): def loginfo(self, text): rospy.loginfo(text) + def logwarn(self, text): + rospy.logwarn(text) + def logfatal(self, arg): rospy.logfatal(arg) + # assymetry in publisher/subscriber method naming due to rclpy having + # create_publisher method. + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return rospy.Publisher(topic, msg_type, queue_size=qos_profile.depth) + def create_subscriber(self, msg_type, topic, - callback, qos_profile=None): + callback, qos_profile=None, + callback_group=None): if qos_profile is None: qos_profile = self.qos_profile return rospy.Subscriber(topic, msg_type, @@ -48,11 +64,12 @@ def shutdown(self): class CompatibleNode(Node): - def __init__(self, node_name, queue_size=10): + def __init__(self, node_name, queue_size=10, rospy_init=True): super().__init__(node_name, allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True) self.logger = self.get_logger() self.qos_profile = QoSProfile(depth=queue_size) + self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_value is None: @@ -65,15 +82,30 @@ def get_param(self, name, alternative_value=None, alternative_name=None): def loginfo(self, text): self.logger.info(text) + def logwarn(self, text): + self.logger.warn(text) + def logfatal(self, arg): self.logger.fatal(arg) + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) + def create_subscriber(self, msg_type, topic, - callback, qos_profile=None): + callback, qos_profile=None, callback_group=None): if qos_profile is None: qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group return self.create_subscription(msg_type, topic, - callback, qos_profile) + callback, qos_profile, + callback_group=callback_group) def spin(self): rclpy.spin(self) From 2e7d4e2c87e78135abf0b7658202b0bfea2d90c9 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 22 May 2020 18:49:21 +0200 Subject: [PATCH 069/627] Remove debug comments --- .../src/carla_manual_control/carla_manual_control.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 681c1d1c..43ff5912 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -27,7 +27,6 @@ """ from __future__ import print_function -# import random import os import datetime import math @@ -363,8 +362,6 @@ def __init__(self, role_name, width, height): self.tf_listener_node = rclpy.create_node("tf_listener") self.tfBuffer = tf2_ros.Buffer() self.tf_listener = tf2_ros.TransformListener(self.tfBuffer, node=self.tf_listener_node) - # for pub in self.tf_listener.node.publishers: - # print(pub.topic) self.time = Time() self.callback_group = ReentrantCallbackGroup() From a6beeadad123e783432df208909efdeea3737421 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 19:06:03 +0200 Subject: [PATCH 070/627] Use .get() to access the environ --- ros_compatibility/setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_compatibility/setup.py b/ros_compatibility/setup.py index 55754977..207e7c97 100644 --- a/ros_compatibility/setup.py +++ b/ros_compatibility/setup.py @@ -1,6 +1,6 @@ import os -ROS_VERSION = int(os.environ['ROS_VERSION']) +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: from distutils.core import setup From 7c2ff7bf2a6a398326a6c27df146b6e5541469b4 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 19:42:03 +0200 Subject: [PATCH 071/627] Fix version --- carla_ros_bridge/package.xml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index b0be55bb..875141e6 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -1,8 +1,7 @@ - carla_ros_bridge - 0.0.0 + 0.0.1 The carla_ros_bridge package CARLA Simulator Team MIT From 19382350e52d6fbf06f270d112e480b7485349a7 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 19:44:45 +0200 Subject: [PATCH 072/627] Remove xml schema --- carla_manual_control/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index 2d9012ed..da4f535b 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -1,5 +1,4 @@ - carla_manual_control 0.0.0 From d0b714c74128c7d135145559b43e123244ea9b5b Mon Sep 17 00:00:00 2001 From: Fabian Oboril Date: Tue, 26 May 2020 11:13:50 +0200 Subject: [PATCH 073/627] Fixed ego_vehicle TF Replaced setting of quaternion x to 1.0 with w. --- CHANGELOG.md | 1 + carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 70207d0e..3af64edc 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Fixed wrong TF for ego_vehicle * Improve version check * Fix cleanup * Rework tf frame names diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 01d93017..c15daaaa 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -168,7 +168,7 @@ def update(self, frame, timestamp): self.send_vehicle_msgs() super(EgoVehicle, self).update(frame, timestamp) no_rotation = Transform() - no_rotation.rotation.x = 1.0 + no_rotation.rotation.w = 1.0 self.publish_transform(self.get_ros_transform( no_rotation, frame_id=str(self.get_id()), child_frame_id=self.get_prefix())) From 12aada8e114dad066a4d31564fde828b52a82e33 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 16:52:26 +0200 Subject: [PATCH 074/627] Destroy ROS2 clock_subscriber in __del__ --- .../src/carla_manual_control/carla_manual_control.py | 1 + 1 file changed, 1 insertion(+) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 43ff5912..5fb1b1ba 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -410,6 +410,7 @@ def __del__(self): self.gnss_subscriber.destroy() self.vehicle_status_subscriber.destroy() self.vehicle_info_subscriber.destroy() + self.clock_subscriber.destroy() def tick(self, clock): """ From dd3d30d7345054c530401d02fa8d012557ba5e45 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 17:07:16 +0200 Subject: [PATCH 075/627] Change subscription type from `Time` to `Clock` in /clock subscriber. --- .../src/carla_manual_control/carla_manual_control.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 5fb1b1ba..a91cab5f 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -56,7 +56,8 @@ import tf2_ros from rclpy.qos import QoSProfile from threading import Thread, Lock, Event - from builtin_interfaces.msg import Time + # from builtin_interfaces.msg import Time + from rosgraph_msgs.msg import Clock sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') from ros_compatible_node import CompatibleNode @@ -397,7 +398,7 @@ def __init__(self, role_name, width, height): "/carla/status", self.carla_status_updated) if ROS_VERSION == 2: - self.clock_subscriber = self.create_subscriber(Time, + self.clock_subscriber = self.create_subscriber(Clock, "/clock", self.clock_status_updated) @@ -418,8 +419,8 @@ def tick(self, clock): """ self._notifications.tick(clock) - def clock_status_updated(self, time): - self.time = time + def clock_status_updated(self, clock): + self.time = clock.get_time() def carla_status_updated(self, data): """ From c208f0059b2d476bb76e6a71ca04f8a62a52f056 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 18:52:06 +0200 Subject: [PATCH 076/627] Update ros_compatible_node.py --- .../ros_compatibility/ros_compatible_node.py | 119 +++++++++++++++--- 1 file changed, 102 insertions(+), 17 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index e98bd8ce..2bb45363 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -5,17 +5,34 @@ if ROS_VERSION == 1: import rospy + def ros_timestamp(sec=0, nsec=0, from_sec=False): + if from_sec: + return rospy.Time.from_sec(sec) + return rospy.Time(int(sec), int(nsec)) - class QoSProfile(): - def __init__(self, **kwargs): - self.depth = kwargs['depth'] + def ros_ok(): + return not rospy.is_shutdown() + + def ros_shutdown(): + pass + + def destroy_subscription(subsription): + subsription.unregister() + class QoSProfile(): + def __init__(self, depth=10, durability=None, **kwargs): + self.depth = depth + if durability is not None and durability is not False: + self.latch = True + else: + self.latch = False + class CompatibleNode(object): - def __init__(self, node_name, queue_size=10, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): if rospy_init: rospy.init_node(node_name, anonymous=True) - self.qos_profile = QoSProfile(depth=queue_size) + self.qos_profile = QoSProfile(depth=queue_size, durability=latch) self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): @@ -23,12 +40,24 @@ def get_param(self, name, alternative_value=None, alternative_name=None): return rospy.get_param(name) return rospy.get_param(name, alternative_value) + def logdebug(self, text): + rospy.logdebug(text) + def loginfo(self, text): rospy.loginfo(text) def logwarn(self, text): rospy.logwarn(text) + def logwarn(self, text): + rospy.logwarn(text) + + def logwarn(self, text): + rospy.logwarn(text) + + def logerr(self, text): + rospy.logerr(text) + def logfatal(self, arg): rospy.logfatal(arg) @@ -40,7 +69,8 @@ def new_publisher(self, msg_type, topic, qos_profile = self.qos_profile if callback_group is None: callback_group = self.callback_group - return rospy.Publisher(topic, msg_type, queue_size=qos_profile.depth) + return rospy.Publisher(topic, msg_type, latch=qos_profile.latch, + queue_size=qos_profile.depth) def create_subscriber(self, msg_type, topic, callback, qos_profile=None, @@ -50,7 +80,7 @@ def create_subscriber(self, msg_type, topic, return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) - def spin(self): + def spin(self, executor=None): rospy.spin() def shutdown(self): @@ -59,16 +89,40 @@ def shutdown(self): elif ROS_VERSION == 2: from rclpy.node import Node from rclpy import Parameter - from rclpy.qos import QoSProfile + from rclpy.qos import QoSProfile, QoSDurabilityPolicy import rclpy + from builtin_interfaces.msg import Time + + def ros_timestamp(sec=0, nsec=0, from_sec=False): + time = Time() + if from_sec: + time.sec = int(sec) + time.nanosec = int((sec - int(sec)) * 1000_000_000) + else: + time.sec = int(sec) + time.nanosec = int(nsec) + return time + + def ros_ok(): + return rclpy.ok() + + def ros_shutdown(): + rclpy.shutdown() + + def destroy_subscription(subsription): + subsription.destroy() class CompatibleNode(Node): - def __init__(self, node_name, queue_size=10, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): super().__init__(node_name, allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True) - self.logger = self.get_logger() - self.qos_profile = QoSProfile(depth=queue_size) + if latch: + self.qos_profile = QoSProfile( + depth=queue_size, + durability=QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) + else: + self.qos_profile = QoSProfile(depth=queue_size) self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): @@ -77,16 +131,47 @@ def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_name is None: alternative_name = name return self.get_parameter_or(name, - Parameter(alternative_name, value=alternative_value)).value + Parameter(alternative_name, value=alternative_value) + ).value + + def logdebug(self, text): + self.get_logger().debug(text) def loginfo(self, text): - self.logger.info(text) + self.get_logger().info(text) def logwarn(self, text): - self.logger.warn(text) + self.get_logger().warn(text) - def logfatal(self, arg): - self.logger.fatal(arg) + def logerr(self, text): + self.get_logger().error(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logfatal(self, text): + self.get_logger().fatal(text) + + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) + + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): @@ -107,7 +192,7 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile, callback_group=callback_group) - def spin(self): + def spin(self, executor=None): rclpy.spin(self) def shutdown(self): From 6e9f611a1b408c500cf98d906dca4d1bc5122a0d Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 18:52:06 +0200 Subject: [PATCH 077/627] Update ros_compatible_node.py --- .../ros_compatibility/ros_compatible_node.py | 119 +++++++++++++++--- 1 file changed, 102 insertions(+), 17 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index e98bd8ce..2bb45363 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -5,17 +5,34 @@ if ROS_VERSION == 1: import rospy + def ros_timestamp(sec=0, nsec=0, from_sec=False): + if from_sec: + return rospy.Time.from_sec(sec) + return rospy.Time(int(sec), int(nsec)) - class QoSProfile(): - def __init__(self, **kwargs): - self.depth = kwargs['depth'] + def ros_ok(): + return not rospy.is_shutdown() + + def ros_shutdown(): + pass + + def destroy_subscription(subsription): + subsription.unregister() + class QoSProfile(): + def __init__(self, depth=10, durability=None, **kwargs): + self.depth = depth + if durability is not None and durability is not False: + self.latch = True + else: + self.latch = False + class CompatibleNode(object): - def __init__(self, node_name, queue_size=10, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): if rospy_init: rospy.init_node(node_name, anonymous=True) - self.qos_profile = QoSProfile(depth=queue_size) + self.qos_profile = QoSProfile(depth=queue_size, durability=latch) self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): @@ -23,12 +40,24 @@ def get_param(self, name, alternative_value=None, alternative_name=None): return rospy.get_param(name) return rospy.get_param(name, alternative_value) + def logdebug(self, text): + rospy.logdebug(text) + def loginfo(self, text): rospy.loginfo(text) def logwarn(self, text): rospy.logwarn(text) + def logwarn(self, text): + rospy.logwarn(text) + + def logwarn(self, text): + rospy.logwarn(text) + + def logerr(self, text): + rospy.logerr(text) + def logfatal(self, arg): rospy.logfatal(arg) @@ -40,7 +69,8 @@ def new_publisher(self, msg_type, topic, qos_profile = self.qos_profile if callback_group is None: callback_group = self.callback_group - return rospy.Publisher(topic, msg_type, queue_size=qos_profile.depth) + return rospy.Publisher(topic, msg_type, latch=qos_profile.latch, + queue_size=qos_profile.depth) def create_subscriber(self, msg_type, topic, callback, qos_profile=None, @@ -50,7 +80,7 @@ def create_subscriber(self, msg_type, topic, return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) - def spin(self): + def spin(self, executor=None): rospy.spin() def shutdown(self): @@ -59,16 +89,40 @@ def shutdown(self): elif ROS_VERSION == 2: from rclpy.node import Node from rclpy import Parameter - from rclpy.qos import QoSProfile + from rclpy.qos import QoSProfile, QoSDurabilityPolicy import rclpy + from builtin_interfaces.msg import Time + + def ros_timestamp(sec=0, nsec=0, from_sec=False): + time = Time() + if from_sec: + time.sec = int(sec) + time.nanosec = int((sec - int(sec)) * 1000_000_000) + else: + time.sec = int(sec) + time.nanosec = int(nsec) + return time + + def ros_ok(): + return rclpy.ok() + + def ros_shutdown(): + rclpy.shutdown() + + def destroy_subscription(subsription): + subsription.destroy() class CompatibleNode(Node): - def __init__(self, node_name, queue_size=10, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): super().__init__(node_name, allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True) - self.logger = self.get_logger() - self.qos_profile = QoSProfile(depth=queue_size) + if latch: + self.qos_profile = QoSProfile( + depth=queue_size, + durability=QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) + else: + self.qos_profile = QoSProfile(depth=queue_size) self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): @@ -77,16 +131,47 @@ def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_name is None: alternative_name = name return self.get_parameter_or(name, - Parameter(alternative_name, value=alternative_value)).value + Parameter(alternative_name, value=alternative_value) + ).value + + def logdebug(self, text): + self.get_logger().debug(text) def loginfo(self, text): - self.logger.info(text) + self.get_logger().info(text) def logwarn(self, text): - self.logger.warn(text) + self.get_logger().warn(text) - def logfatal(self, arg): - self.logger.fatal(arg) + def logerr(self, text): + self.get_logger().error(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logfatal(self, text): + self.get_logger().fatal(text) + + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) + + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): @@ -107,7 +192,7 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile, callback_group=callback_group) - def spin(self): + def spin(self, executor=None): rclpy.spin(self) def shutdown(self): From 8671bd61f02190af6d8c8c9c98ca2e3815b62a9b Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 19:31:16 +0200 Subject: [PATCH 078/627] Add latching to vehicle_control_manual_override --- .../carla_manual_control.py | 26 ++++++++++--------- 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index a91cab5f..e7dfed63 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -208,23 +208,25 @@ def __init__(self, role_name, hud): if ROS_VERSION == 2: self.callback_group = ReentrantCallbackGroup() - fast_qos_profile = QoSProfile(depth=1) + fast_qos = QoSProfile(depth=1) + fast_latched_qos = QoSProfile(depth=1, durability=latch_on) # imported from ros_compat. - self.vehicle_control_manual_override_publisher = self.new_publisher(Bool, - "/carla/{}/vehicle_control_manual_override".format( - self.role_name), - qos_profile=fast_qos_profile) + self.vehicle_control_manual_override_publisher = \ + self.new_publisher(Bool, + "/carla/{}/vehicle_control_manual_override".format(self.role_name), + qos_profile=fast_latched_qos) self.vehicle_control_manual_override = False - self.auto_pilot_enable_publisher = self.new_publisher(Bool, - "/carla/{}/enable_autopilot".format(self.role_name), - qos_profile=fast_qos_profile) + self.auto_pilot_enable_publisher = \ + self.new_publisher(Bool, + "/carla/{}/enable_autopilot".format(self.role_name), + qos_profile=fast_qos) - self.vehicle_control_publisher = self.new_publisher(CarlaEgoVehicleControl, - "/carla/{}/vehicle_control_cmd_manual".format( - self.role_name), - qos_profile=fast_qos_profile) + self.vehicle_control_publisher = \ + self.new_publisher(CarlaEgoVehicleControl, + "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), + qos_profile=fast_qos) self.carla_status_subscriber = self.create_subscriber(CarlaStatus, "/carla/status", From 289b04d57af550c650cc7abb57bf3b72a2708c88 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 19:42:16 +0200 Subject: [PATCH 079/627] bridge.py initial draft --- .../src/carla_ros_bridge/bridge.py | 42 +++++++++---------- 1 file changed, 20 insertions(+), 22 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index c667982f..0e0a5e90 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -79,9 +79,9 @@ def __init__(self, carla_world, params): self.carla_settings.synchronous_mode = False carla_world.apply_settings(self.carla_settings) - rospy.loginfo("synchronous_mode: {}".format(self.parameters["synchronous_mode"])) + self.loginfo("synchronous_mode: {}".format(self.parameters["synchronous_mode"])) self.carla_settings.synchronous_mode = self.parameters["synchronous_mode"] - rospy.loginfo("fixed_delta_seconds: {}".format(self.parameters["fixed_delta_seconds"])) + self.loginfo("fixed_delta_seconds: {}".format(self.parameters["fixed_delta_seconds"])) self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) @@ -202,15 +202,15 @@ def process_run_state(self): if self.carla_run_state == CarlaControl.PAUSE: # wait for next command - rospy.loginfo("State set to PAUSED") + self.loginfo("State set to PAUSED") self.status_publisher.set_synchronous_mode_running(False) command = self.carla_control_queue.get() elif self.carla_run_state == CarlaControl.PLAY: - rospy.loginfo("State set to PLAY") + self.loginfo("State set to PLAY") self.status_publisher.set_synchronous_mode_running(True) return elif self.carla_run_state == CarlaControl.STEP_ONCE: - rospy.loginfo("Execute single step.") + self.loginfo("Execute single step.") self.status_publisher.set_synchronous_mode_running(True) self.carla_control_queue.put(CarlaControl.PAUSE) return @@ -235,10 +235,9 @@ def _synchronous_mode_update(self): self.status_publisher.set_frame(frame) self.comm.update_clock(world_snapshot.timestamp) - rospy.logdebug("Tick for frame {} returned. Waiting for sensor data...".format( - frame)) + self.logdebug("Tick for frame {} returned. Waiting for sensor data...".format(frame)) self._update(frame, world_snapshot.timestamp.elapsed_seconds) - rospy.logdebug("Waiting for sensor data finished.") + self.logdebug("Waiting for sensor data finished.") self.comm.send_msgs() self._update_actors(set([x.id for x in world_snapshot])) @@ -246,9 +245,9 @@ def _synchronous_mode_update(self): # wait for all ego vehicles to send a vehicle control command if self._expected_ego_vehicle_control_command_ids: if not self._all_vehicle_control_commands_received.wait(1): - rospy.logwarn("Timeout (1s) while waiting for vehicle control commands. " - "Missing command from actor ids {}".format( - self._expected_ego_vehicle_control_command_ids)) + self.logwarn("Timeout (1s) while waiting for vehicle control commands. " + "Missing command from actor ids {}".format( + self._expected_ego_vehicle_control_command_ids)) self._all_vehicle_control_commands_received.clear() def _carla_time_tick(self, carla_snapshot): @@ -312,7 +311,7 @@ def _update_actors(self, current_actors): # remove actor actor = self.actors[id_to_delete] with self.update_lock: - rospy.loginfo("Remove {}(id={}, parent_id={}, prefix={})".format( + self.loginfo("Remove {}(id={}, parent_id={}, prefix={})".format( actor.__class__.__name__, actor.get_id(), actor.get_parent_id(), actor.get_prefix())) @@ -323,7 +322,7 @@ def _update_actors(self, current_actors): updated_pseudo_actors = [] for pseudo_actor in self.pseudo_actors: if pseudo_actor.get_parent_id() == id_to_delete: - rospy.loginfo("Remove {}(parent_id={}, prefix={})".format( + self.loginfo("Remove {}(parent_id={}, prefix={})".format( pseudo_actor.__class__.__name__, pseudo_actor.get_parent_id(), pseudo_actor.get_prefix())) @@ -430,16 +429,15 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m else: actor = Actor(carla_actor, parent, self.comm) - rospy.loginfo("Created {}(id={}, parent_id={}," - " type={}, prefix={}, attributes={})".format( - actor.__class__.__name__, actor.get_id(), - actor.get_parent_id(), carla_actor.type_id, - actor.get_prefix(), carla_actor.attributes)) + self.loginfo("Created {}(id={}, parent_id={}," + " type={}, prefix={}, attributes={})".format(actor.__class__.__name__, actor.get_id(), + actor.get_parent_id(), carla_actor.type_id, + actor.get_prefix(), carla_actor.attributes)) with self.update_lock: self.actors[carla_actor.id] = actor for pseudo_actor in pseudo_actors: - rospy.loginfo("Created {}(parent_id={}, prefix={})".format( + self.loginfo("Created {}(parent_id={}, prefix={})".format( pseudo_actor.__class__.__name__, pseudo_actor.get_parent_id(), pseudo_actor.get_prefix())) @@ -466,7 +464,7 @@ def on_shutdown(self): This function is registered at rospy as shutdown handler. """ - rospy.loginfo("Shutdown requested") + self.loginfo("Shutdown requested") self.destroy() def _update(self, frame_id, timestamp): @@ -483,7 +481,7 @@ def _update(self, frame_id, timestamp): try: self.actors[actor_id].update(frame_id, timestamp) except RuntimeError as e: - rospy.logwarn("Update actor {}({}) failed: {}".format( + self.logwarn("Update actor {}({}) failed: {}".format( self.actors[actor_id].__class__.__name__, actor_id, e)) continue @@ -495,7 +493,7 @@ def _ego_vehicle_control_applied_callback(self, ego_vehicle_id): if ego_vehicle_id in self._expected_ego_vehicle_control_command_ids: self._expected_ego_vehicle_control_command_ids.remove(ego_vehicle_id) else: - rospy.logwarn( + self.logwarn( "Unexpected vehicle control command received from {}".format(ego_vehicle_id)) if not self._expected_ego_vehicle_control_command_ids: self._all_vehicle_control_commands_received.set() From ea1752d9f460d30787111b4b758e346dca3af766 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 19:43:29 +0200 Subject: [PATCH 080/627] camera.py initial draft --- .../src/carla_ros_bridge/camera.py | 27 ++++++++++++++----- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 7ba8ec83..f44cc6ab 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -9,13 +9,26 @@ """ Class to handle Carla camera sensors """ +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + import rospy + from tf import transformations + from ros_compatibility import * +elif ROS_VERSION == 2: + import rclpy + import cv2 + import transformations + # TODO: import ros_compatibilty +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") + from abc import abstractmethod import math import numpy -import rospy -import tf from cv_bridge import CvBridge from sensor_msgs.msg import CameraInfo @@ -55,8 +68,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= prefix=prefix) if self.__class__.__name__ == "Camera": - rospy.logwarn("Created Unsupported Camera Actor" - "(id={}, parent_id={}, type={}, attributes={})".format( + self.logwarn("Created Unsupported Camera Actor" + "(id={}, parent_id={}, type={}, attributes={})".format( self.get_id(), self.get_parent_id(), self.carla_actor.type_id, self.carla_actor.attributes)) else: @@ -96,7 +109,7 @@ def sensor_data_updated(self, carla_image): """ if ((carla_image.height != self._camera_info.height) or (carla_image.width != self._camera_info.width)): - rospy.logerr( + self.logerr( "Camera{} received image not matching configuration".format(self.get_prefix())) image_data_array, encoding = self.get_carla_image_data_array( carla_image=carla_image) @@ -124,12 +137,12 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): tf_msg = super(Camera, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation quat = [rotation.x, rotation.y, rotation.z, rotation.w] - quat_swap = tf.transformations.quaternion_from_matrix( + quat_swap = transformations.quaternion_from_matrix( [[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) - quat = tf.transformations.quaternion_multiply(quat, quat_swap) + quat = transformations.quaternion_multiply(quat, quat_swap) tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion( quat) From 4381620fbb1ca12e19ff7bcece976e91af25b924 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 19:45:51 +0200 Subject: [PATCH 081/627] carla_status_publisher.py initial draft --- .../carla_status_publisher.py | 27 +++++++++++++++---- 1 file changed, 22 insertions(+), 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 0f296750..1390fec3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -9,14 +9,24 @@ """ report the carla status """ +import os -import rospy +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -from carla_msgs.msg import CarlaStatus +if ROS_VERSION == 1: + import rospy + from ros_compatibility import CompatibleNode +elif ROS_VERSION == 2: + import rclpy + from rclpy.callback_groups import ReentrantCallbackGroup + # TODO: import ros_compatibilty +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +from carla_msgs.msg import CarlaStatus -class CarlaStatusPublisher(object): +class CarlaStatusPublisher(CompatibleNode): """ report the carla status """ @@ -26,12 +36,19 @@ def __init__(self, synchronous_mode, fixed_delta_seconds): Constructor """ + super(CarlaStatusPublisher, self).__init__("carla_status_publisher", + latch=True, + rospy_init=False) self.synchronous_mode = synchronous_mode self.synchronous_mode_running = True self.fixed_delta_seconds = fixed_delta_seconds self.frame = 0 - self.carla_status_publisher = rospy.Publisher( - "/carla/status", CarlaStatus, queue_size=10, latch=True) + if ROS_VERSION == 1: + callback_group = None + elif ROS_VERSION == 2: + callback_group = ReentrantCallBackGroup() + self.carla_status_publisher = self.new_publisher(CarlaStatus, "/carla/status", + callback_group=callback_group) self.publish() def publish(self): From 6dfdb4339048068ebe54396b135411ae49aa22fb Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 19:46:19 +0200 Subject: [PATCH 082/627] communication.py initial draft --- .../src/carla_ros_bridge/communication.py | 49 ++++++++++++------- 1 file changed, 32 insertions(+), 17 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 08fe7ca2..21b64b89 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -9,13 +9,28 @@ """ Handle communication of ROS topics """ -import rospy +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + import rospy + from ros_compatibility import * + latch = True +elif ROS_VERSION == 2: + import rclpy + from rclpy.qos import QoSDurabilityPolicy + from rclpy.qos import QoSProfile + from ros_compatibility import * + latch = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") from rosgraph_msgs.msg import Clock from tf2_msgs.msg import TFMessage +from builtin_interfaces.msg import Time -class Communication(object): +class Communication(CompatibleNode): """ Handle communication of ROS topics @@ -25,17 +40,17 @@ def __init__(self): """ Constructor """ + super(Communication, self).__init__("communication", rospy_init=False) self.tf_to_publish = [] self.msgs_to_publish = [] self.publishers = {} self.subscribers = {} - self.ros_timestamp = rospy.Time() + self.ros_timestamp = ros_timestamp() # needed? - self.publishers['clock'] = rospy.Publisher( - 'clock', Clock, queue_size=10) - self.publishers['tf'] = rospy.Publisher( - 'tf', TFMessage, queue_size=100) + self.publishers['clock'] = self.new_publisher(Clock, 'clock') + self.publishers['tf'] = self.new_publisher(TFMessage, 'tf', + qos_profile=QoSProfile(depth=100)) def send_msgs(self): """ @@ -47,18 +62,14 @@ def send_msgs(self): tf_msg = TFMessage(self.tf_to_publish) try: self.publishers['tf'].publish(tf_msg) - except rospy.ROSSerializationException as error: - rospy.logwarn("Failed to serialize message on publishing: {}".format(error)) except Exception as error: # pylint: disable=broad-except - rospy.logwarn("Failed to publish message: {}".format(error)) + self.logwarn("Failed to publish message: {}".format(error)) for publisher, msg in self.msgs_to_publish: try: publisher.publish(msg) - except rospy.ROSSerializationException as error: # pylint: disable=broad-except - rospy.logwarn("Failed to serialize message on publishing: {}".format(error)) except Exception as error: # pylint: disable=broad-except - rospy.logwarn("Failed to publish message: {}".format(error)) + self.logwarn("Failed to publish message: {}".format(error)) self.msgs_to_publish = [] self.tf_to_publish = [] @@ -84,8 +95,13 @@ def publish_message(self, topic, msg, is_latched=False): self.tf_to_publish.append(msg) else: if topic not in self.publishers: - self.publishers[topic] = rospy.Publisher( - topic, type(msg), queue_size=10, latch=is_latched) + if is_latched: + qos_profile = QoSProfile(depth=10, durability=latch) + self.publishers[topic] = self.new_publisher(type(msg), topic, + qos_profile=qos_profile) + else: + # Use default QoS profile. + self.publishers[topic] = self.new_publisher(type(msg), topic) self.msgs_to_publish.append((self.publishers[topic], msg)) def update_clock(self, carla_timestamp): @@ -96,8 +112,7 @@ def update_clock(self, carla_timestamp): :type carla_timestamp: carla.Timestamp :return: """ - self.ros_timestamp = rospy.Time.from_sec( - carla_timestamp.elapsed_seconds) + self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_secs=True) self.publish_message('clock', Clock(self.ros_timestamp)) def get_current_ros_time(self): From 8d4eb58b18bc1283a7ca0523a3173646aa01afab Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 19:53:52 +0200 Subject: [PATCH 083/627] Add new logging methods and wrapper functions --- .../ros_compatibility/ros_compatible_node.py | 122 +++++++++++++++--- 1 file changed, 104 insertions(+), 18 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 2d4a6da9..eea97c92 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -5,17 +5,33 @@ if ROS_VERSION == 1: import rospy + latch_on = True - class QoSProfile(): - def __init__(self, **kwargs): - self.depth = kwargs['depth'] + def ros_timestamp(sec=0, nsec=0, from_sec=False): + if from_sec: + return rospy.Time.from_sec(sec) + return rospy.Time(int(sec), int(nsec)) + + def ros_ok(): + return not rospy.is_shutdown() + + def ros_shutdown(): + pass + def destroy_subscription(subsription): + subsription.unregister() + + + class QoSProfile(): + def __init__(self, depth=10, durability=None, **kwargs): + self.depth = depth + self.latch = bool(durability) class CompatibleNode(object): - def __init__(self, node_name, queue_size=10, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): if rospy_init: rospy.init_node(node_name, anonymous=True) - self.qos_profile = QoSProfile(depth=queue_size) + self.qos_profile = QoSProfile(depth=queue_size, durability=latch) self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): @@ -23,12 +39,24 @@ def get_param(self, name, alternative_value=None, alternative_name=None): return rospy.get_param(name) return rospy.get_param(name, alternative_value) + def logdebug(self, text): + rospy.logdebug(text) + def loginfo(self, text): rospy.loginfo(text) def logwarn(self, text): rospy.logwarn(text) + def logwarn(self, text): + rospy.logwarn(text) + + def logwarn(self, text): + rospy.logwarn(text) + + def logerr(self, text): + rospy.logerr(text) + def logfatal(self, arg): rospy.logfatal(arg) @@ -40,7 +68,8 @@ def new_publisher(self, msg_type, topic, qos_profile = self.qos_profile if callback_group is None: callback_group = self.callback_group - return rospy.Publisher(topic, msg_type, queue_size=qos_profile.depth) + return rospy.Publisher(topic, msg_type, latch=qos_profile.latch, + queue_size=qos_profile.depth) def create_subscriber(self, msg_type, topic, callback, qos_profile=None, @@ -50,7 +79,7 @@ def create_subscriber(self, msg_type, topic, return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) - def spin(self): + def spin(self, executor=None): rospy.spin() def shutdown(self): @@ -59,16 +88,42 @@ def shutdown(self): elif ROS_VERSION == 2: from rclpy.node import Node from rclpy import Parameter - from rclpy.qos import QoSProfile + from rclpy.qos import QoSProfile, QoSDurabilityPolicy import rclpy + from builtin_interfaces.msg import Time + + latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL + + def ros_timestamp(sec=0, nsec=0, from_sec=False): + time = Time() + if from_sec: + time.sec = int(sec) + time.nanosec = int((sec - int(sec)) * 1000_000_000) + else: + time.sec = int(sec) + time.nanosec = int(nsec) + return time + + def ros_ok(): + return rclpy.ok() + + def ros_shutdown(): + rclpy.shutdown() + + def destroy_subscription(subsription): + subsription.destroy() class CompatibleNode(Node): - def __init__(self, node_name, queue_size=10, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): super().__init__(node_name, allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True) - self.logger = self.get_logger() - self.qos_profile = QoSProfile(depth=queue_size) + if latch: + self.qos_profile = QoSProfile( + depth=queue_size, + durability=QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) + else: + self.qos_profile = QoSProfile(depth=queue_size) self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): @@ -77,16 +132,47 @@ def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_name is None: alternative_name = name return self.get_parameter_or(name, - Parameter(alternative_name, value=alternative_value)).value + Parameter(alternative_name, value=alternative_value) + ).value + + def logdebug(self, text): + self.get_logger().debug(text) def loginfo(self, text): - self.logger.info(text) + self.get_logger().info(text) def logwarn(self, text): - self.logger.warn(text) + self.get_logger().warn(text) - def logfatal(self, arg): - self.logger.fatal(arg) + def logerr(self, text): + self.get_logger().error(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logfatal(self, text): + self.get_logger().fatal(text) + + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) + + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): @@ -107,7 +193,7 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile, callback_group=callback_group) - def spin(self): + def spin(self, executor=None): rclpy.spin(self) def shutdown(self): @@ -120,7 +206,7 @@ def shutdown(self): def main(): print('This is a ros1 - ros2 compatibility module.', - 'It's not meant to be executed, but rather imported') + 'It is not meant to be executed, but rather imported') if __name__ == '__main__': From 8bc3ff849ee5b1c0579ba3cb6238f593c2423a59 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 19:53:52 +0200 Subject: [PATCH 084/627] Merge ros_compatible_node.py --- .../src/ros_compatibility/ros_compatible_node.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 2bb45363..eea97c92 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -5,6 +5,8 @@ if ROS_VERSION == 1: import rospy + latch_on = True + def ros_timestamp(sec=0, nsec=0, from_sec=False): if from_sec: return rospy.Time.from_sec(sec) @@ -23,10 +25,7 @@ def destroy_subscription(subsription): class QoSProfile(): def __init__(self, depth=10, durability=None, **kwargs): self.depth = depth - if durability is not None and durability is not False: - self.latch = True - else: - self.latch = False + self.latch = bool(durability) class CompatibleNode(object): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): @@ -93,6 +92,8 @@ def shutdown(self): import rclpy from builtin_interfaces.msg import Time + latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL + def ros_timestamp(sec=0, nsec=0, from_sec=False): time = Time() if from_sec: From 0ad7152ea9b10669230d1ec7368d16b6327f1cbf Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 20:24:01 +0200 Subject: [PATCH 085/627] debug_helper.py initial draft --- .../src/carla_ros_bridge/debug_helper.py | 44 +++++++++++++------ 1 file changed, 30 insertions(+), 14 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 7518408d..080b6183 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -8,14 +8,29 @@ """ Class to draw marker """ +import os + +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + import rospy + from tf.transformations import euler_from_quaternion + from ros_compatibility import CompatibleNode +elif ROS_VERSION == 2: + import rclpy + from transformations.transformations import euler_from_quaternion + # TODO: fix import + from ros_compatibility import CompatibleNode +else: + raise NotImplementedError('Make sure you have valid ' + + 'ROS_VERSION env variable') + import math -import rospy from visualization_msgs.msg import Marker, MarkerArray -from tf.transformations import euler_from_quaternion import carla -class DebugHelper(object): +class DebugHelper(CompatibleNode): """ Helper to draw markers in CARLA @@ -28,9 +43,10 @@ def __init__(self, carla_debug_helper): :param carla_debug_helper: carla debug helper :type carla_debug_helper: carla.DebugHelper """ + super(DebugHelper, self).__init__("debug_helper", rospy_init=False) self.debug = carla_debug_helper - self.marker_subscriber = rospy.Subscriber( - "/carla/debug_marker", MarkerArray, self.on_marker) + self.marker_subscriber = self.create_subscription( + MarkerArray, "/carla/debug_marker", self.on_marker) def destroy(self): """ @@ -42,7 +58,7 @@ def destroy(self): """ rospy.logdebug("Destroy DebugHelper") self.debug = None - self.marker_subscriber.unregister() + destroy_subscription(self.marker_subscriber) self.marker_subscriber = None def on_marker(self, marker_array): @@ -51,7 +67,7 @@ def on_marker(self, marker_array): """ for marker in marker_array.markers: if marker.header.frame_id != "map": - rospy.logwarn( + self.logwarn( "Could not draw marker in frame '{}'. Only 'map' supported.".format( marker.header.frame_id)) continue @@ -80,7 +96,7 @@ def draw_arrow(self, marker, lifetime, color): """ if marker.points: if not len(marker.points) == 2: - rospy.logwarn( + self.logwarn( "Drawing arrow from points requires two points. Received {}".format( len(marker.points))) return @@ -90,7 +106,7 @@ def draw_arrow(self, marker, lifetime, color): x=marker.points[0].x, y=-marker.points[0].y, z=marker.points[0].z) end = carla.Location( x=marker.points[1].x, y=-marker.points[1].y, z=marker.points[1].z) - rospy.loginfo("Draw Arrow from {} to {} (color: {}, lifetime: {}, " + self.loginfo("Draw Arrow from {} to {} (color: {}, lifetime: {}, " "thickness: {}, arrow_size: {})".format( start, end, color, lifetime, thickness, arrow_size)) self.debug.draw_arrow( @@ -102,7 +118,7 @@ def draw_arrow(self, marker, lifetime, color): life_time=lifetime) else: - rospy.logwarn( + self.logwarn( "Drawing arrow from Position/Orientation not yet supported. " "Please use points.") @@ -113,7 +129,7 @@ def draw_points(self, marker, lifetime, color): for point in marker.points: location = carla.Location(x=point.x, y=-point.y, z=point.z) size = marker.scale.x - rospy.loginfo("Draw Point {} (color: {}, lifetime: {}, size: {})".format( + self.loginfo("Draw Point {} (color: {}, lifetime: {}, size: {})".format( location, color, lifetime, size)) self.debug.draw_point(location, size=size, color=color, life_time=lifetime) @@ -122,7 +138,7 @@ def draw_line_strips(self, marker, lifetime, color): draw lines from ros marker """ if len(marker.points) < 2: - rospy.logwarn( + self.logwarn( "Drawing line-strip requires at least two points. Received {}".format( len(marker.points))) return @@ -132,7 +148,7 @@ def draw_line_strips(self, marker, lifetime, color): if last_point: start = carla.Location(x=last_point.x, y=-last_point.y, z=last_point.z) end = carla.Location(x=point.x, y=-point.y, z=point.z) - rospy.loginfo( + self.loginfo( "Draw Line from {} to {} (color: {}, lifetime: {}, " "thickness: {})".format( start, end, color, lifetime, thickness)) @@ -165,6 +181,6 @@ def draw_box(self, marker, lifetime, color): rotation.roll = math.degrees(roll) rotation.pitch = math.degrees(pitch) rotation.yaw = -math.degrees(yaw) - rospy.loginfo("Draw Box {} (rotation: {}, color: {}, lifetime: {})".format( + self.loginfo("Draw Box {} (rotation: {}, color: {}, lifetime: {})".format( box, rotation, color, lifetime)) self.debug.draw_box(box, rotation, thickness=0.1, color=color, life_time=lifetime) From 5a4e6fd439de056123c50f1df79da0c4585094fb Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 3 Jun 2020 09:15:14 +0200 Subject: [PATCH 086/627] Add setup.py --- carla_ros_bridge/setup.py | 20 +++++++------------- 1 file changed, 7 insertions(+), 13 deletions(-) diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index b2c744c6..e0b1e779 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -2,16 +2,14 @@ Setup for carla_ros_bridge """ import os +from glob import glob ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup - d = generate_distutils_setup( - packages=['carla_ros_bridge'], - package_dir={'': 'src'} - ) + d = generate_distutils_setup(packages=['carla_ros_bridge'], package_dir={'': 'src'}) setup(**d) @@ -23,12 +21,10 @@ name=package_name, version='0.0.0', packages=['src/' + package_name], - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), - (os.path.join('share', package_name), glob('launch/*.launch.py')), - ], + data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', ['config/settings.yaml']), + (os.path.join('share', package_name), glob('launch/*.launch.py'))], install_requires=['setuptools'], zip_safe=True, maintainer='CARLA Simulator Team', @@ -37,8 +33,6 @@ license='MIT', tests_require=['pytest'], entry_points={ - 'console_scripts': [ - 'bridge = carla_ros_bridge.bridge:main' - ], + 'console_scripts': ['bridge = src.carla_ros_bridge.bridge:main'], }, ) From 7eca8e3d29adc69b044874bd442431b92dba01bd Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 3 Jun 2020 09:16:11 +0200 Subject: [PATCH 087/627] Add ROS_VERSION checking in libraries import --- .../src/carla_ros_bridge/bridge.py | 108 +++++++++--------- 1 file changed, 55 insertions(+), 53 deletions(-) mode change 100755 => 100644 carla_ros_bridge/src/carla_ros_bridge/bridge.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py old mode 100755 new mode 100644 index 0e0a5e90..08b72969 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -19,7 +19,6 @@ from distutils.version import LooseVersion from threading import Thread, Lock, Event import pkg_resources -import rospy import carla @@ -46,9 +45,18 @@ from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + import rospy +elif ROS_VERSION == 2: + import rclpy +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -class CarlaRosBridge(object): +class CarlaRosBridge(object): """ Carla Ros bridge """ @@ -90,9 +98,8 @@ def __init__(self, carla_world, params): self.carla_control_queue = queue.Queue() - self.status_publisher = CarlaStatusPublisher( - self.carla_settings.synchronous_mode, - self.carla_settings.fixed_delta_seconds) + self.status_publisher = CarlaStatusPublisher(self.carla_settings.synchronous_mode, + self.carla_settings.fixed_delta_seconds) # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. @@ -128,25 +135,22 @@ def __init__(self, carla_world, params): # register callback to update actors self.on_tick_id = self.carla_world.on_tick(self._carla_time_tick) - self.carla_weather_subscriber = \ - rospy.Subscriber("/carla/weather_control", - CarlaWeatherParameters, self.on_weather_changed) + # self.carla_weather_subscriber = \ + # rospy.Subscriber("/carla/weather_control", + # CarlaWeatherParameters, self.on_weather_changed) # add world info - self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, - communication=self.comm)) + self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, communication=self.comm)) # add global object sensor - self.pseudo_actors.append(ObjectSensor(parent=None, - communication=self.comm, - actor_list=self.actors, - filtered_id=None)) + self.pseudo_actors.append( + ObjectSensor(parent=None, communication=self.comm, actor_list=self.actors, + filtered_id=None)) self.debug_helper = DebugHelper(carla_world.debug) # add traffic light pseudo sensor - self.pseudo_actors.append(TrafficLightsSensor(parent=None, - communication=self.comm, - actor_list=self.actors)) + self.pseudo_actors.append( + TrafficLightsSensor(parent=None, communication=self.comm, actor_list=self.actors)) def destroy(self): """ @@ -247,7 +251,7 @@ def _synchronous_mode_update(self): if not self._all_vehicle_control_commands_received.wait(1): self.logwarn("Timeout (1s) while waiting for vehicle control commands. " "Missing command from actor ids {}".format( - self._expected_ego_vehicle_control_command_ids)) + self._expected_ego_vehicle_control_command_ids)) self._all_vehicle_control_commands_received.clear() def _carla_time_tick(self, carla_snapshot): @@ -312,8 +316,7 @@ def _update_actors(self, current_actors): actor = self.actors[id_to_delete] with self.update_lock: self.loginfo("Remove {}(id={}, parent_id={}, prefix={})".format( - actor.__class__.__name__, actor.get_id(), - actor.get_parent_id(), + actor.__class__.__name__, actor.get_id(), actor.get_parent_id(), actor.get_prefix())) actor.destroy() del self.actors[id_to_delete] @@ -323,8 +326,7 @@ def _update_actors(self, current_actors): for pseudo_actor in self.pseudo_actors: if pseudo_actor.get_parent_id() == id_to_delete: self.loginfo("Remove {}(parent_id={}, prefix={})".format( - pseudo_actor.__class__.__name__, - pseudo_actor.get_parent_id(), + pseudo_actor.__class__.__name__, pseudo_actor.get_parent_id(), pseudo_actor.get_prefix())) pseudo_actor.destroy() del pseudo_actor @@ -383,28 +385,27 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m elif carla_actor.type_id.startswith("vehicle"): if carla_actor.attributes.get('role_name')\ in self.parameters['ego_vehicle']['role_name']: - actor = EgoVehicle( - carla_actor, parent, self.comm, self._ego_vehicle_control_applied_callback) - pseudo_actors.append(ObjectSensor(parent=actor, - communication=self.comm, - actor_list=self.actors, - filtered_id=carla_actor.id)) + actor = EgoVehicle(carla_actor, parent, self.comm, + self._ego_vehicle_control_applied_callback) + pseudo_actors.append( + ObjectSensor(parent=actor, communication=self.comm, actor_list=self.actors, + filtered_id=carla_actor.id)) else: actor = Vehicle(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("sensor"): if carla_actor.type_id.startswith("sensor.camera"): if carla_actor.type_id.startswith("sensor.camera.rgb"): - actor = RgbCamera( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = RgbCamera(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.camera.depth"): - actor = DepthCamera( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = DepthCamera(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.camera.semantic_segmentation"): - actor = SemanticSegmentationCamera( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = SemanticSegmentationCamera(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) else: - actor = Camera( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Camera(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.lidar"): actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): @@ -412,14 +413,14 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): - actor = ImuSensor( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = ImuSensor(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): - actor = CollisionSensor( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = CollisionSensor(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): - actor = LaneInvasionSensor( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = LaneInvasionSensor(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) else: actor = Sensor(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("spectator"): @@ -430,16 +431,18 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m actor = Actor(carla_actor, parent, self.comm) self.loginfo("Created {}(id={}, parent_id={}," - " type={}, prefix={}, attributes={})".format(actor.__class__.__name__, actor.get_id(), - actor.get_parent_id(), carla_actor.type_id, - actor.get_prefix(), carla_actor.attributes)) + " type={}, prefix={}, attributes={})".format(actor.__class__.__name__, + actor.get_id(), + actor.get_parent_id(), + carla_actor.type_id, + actor.get_prefix(), + carla_actor.attributes)) with self.update_lock: self.actors[carla_actor.id] = actor for pseudo_actor in pseudo_actors: self.loginfo("Created {}(parent_id={}, prefix={})".format( - pseudo_actor.__class__.__name__, - pseudo_actor.get_parent_id(), + pseudo_actor.__class__.__name__, pseudo_actor.get_parent_id(), pseudo_actor.get_prefix())) with self.update_lock: self.pseudo_actors.append(pseudo_actor) @@ -506,16 +509,14 @@ def main(): """ rospy.init_node("carla_bridge", anonymous=True) parameters = rospy.get_param('carla') - rospy.loginfo("Trying to connect to {host}:{port}".format( - host=parameters['host'], port=parameters['port'])) + rospy.loginfo("Trying to connect to {host}:{port}".format(host=parameters['host'], + port=parameters['port'])) carla_bridge = None carla_world = None carla_client = None try: - carla_client = carla.Client( - host=parameters['host'], - port=parameters['port']) + carla_client = carla.Client(host=parameters['host'], port=parameters['port']) carla_client.set_timeout(parameters['timeout']) # check carla version @@ -542,7 +543,8 @@ def main(): else: if carla_world.get_map().name != parameters["town"]: rospy.loginfo("Loading town '{}' (previous: '{}').".format( - parameters["town"], carla_world.get_map().name)) + parameters["town"], + carla_world.get_map().name)) carla_world = carla_client.load_world(parameters["town"]) carla_world.tick() From 27b4400b79bc0e3c5f228828179eb1d30cb17537 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 3 Jun 2020 10:12:56 +0200 Subject: [PATCH 088/627] Add src folder to import files from same package --- .../src/carla_ros_bridge/actor.py | 33 +++++++------------ 1 file changed, 12 insertions(+), 21 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index eb4e7d32..5807f016 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -15,12 +15,11 @@ from std_msgs.msg import ColorRGBA from visualization_msgs.msg import Marker -from carla_ros_bridge.pseudo_actor import PseudoActor -import carla_ros_bridge.transforms as trans +from src.carla_ros_bridge.pseudo_actor import PseudoActor +import src.carla_ros_bridge.transforms as trans class Actor(PseudoActor): - """ Generic base class for all carla actors """ @@ -37,9 +36,7 @@ def __init__(self, carla_actor, parent, communication, prefix=None): :param prefix: the topic prefix to be used for this actor :type prefix: string """ - super(Actor, self).__init__(parent=parent, - prefix=prefix, - communication=communication) + super(Actor, self).__init__(parent=parent, prefix=prefix, communication=communication) self.carla_actor = carla_actor if carla_actor.id > np.iinfo(np.uint32).max: @@ -63,8 +60,7 @@ def get_current_ros_pose(self): :return: the ROS pose of this actor :rtype: geometry_msgs.msg.Pose """ - return trans.carla_transform_to_ros_pose( - self.carla_actor.get_transform()) + return trans.carla_transform_to_ros_pose(self.carla_actor.get_transform()) def get_current_ros_twist_rotated(self): """ @@ -73,10 +69,9 @@ def get_current_ros_twist_rotated(self): :return: the ROS twist of this actor :rtype: geometry_msgs.msg.Twist """ - return trans.carla_velocity_to_ros_twist( - self.carla_actor.get_velocity(), - self.carla_actor.get_angular_velocity(), - self.carla_actor.get_transform().rotation) + return trans.carla_velocity_to_ros_twist(self.carla_actor.get_velocity(), + self.carla_actor.get_angular_velocity(), + self.carla_actor.get_transform().rotation) def get_current_ros_twist(self): """ @@ -85,9 +80,8 @@ def get_current_ros_twist(self): :return: the ROS twist of this actor :rtype: geometry_msgs.msg.Twist """ - return trans.carla_velocity_to_ros_twist( - self.carla_actor.get_velocity(), - self.carla_actor.get_angular_velocity()) + return trans.carla_velocity_to_ros_twist(self.carla_actor.get_velocity(), + self.carla_actor.get_angular_velocity()) def get_current_ros_accel(self): """ @@ -96,8 +90,7 @@ def get_current_ros_accel(self): :return: the ROS twist of this actor :rtype: geometry_msgs.msg.Twist """ - return trans.carla_acceleration_to_ros_accel( - self.carla_actor.get_acceleration()) + return trans.carla_acceleration_to_ros_accel(self.carla_actor.get_acceleration()) def get_id(self): """ @@ -158,8 +151,7 @@ def get_marker(self): :return: visualization_msgs.msg.Marker """ - marker = Marker( - header=self.get_msg_header(frame_id=str(self.get_id()))) + marker = Marker(header=self.get_msg_header(frame_id=str(self.get_id()))) marker.color = self.get_marker_color() marker.color.a = 0.3 marker.id = self.get_id() @@ -175,8 +167,7 @@ def publish_marker(self): marker = self.get_marker() marker.type = Marker.CUBE - marker.pose = trans.carla_location_to_pose( - self.carla_actor.bounding_box.location) + marker.pose = trans.carla_location_to_pose(self.carla_actor.bounding_box.location) marker.scale.x = self.carla_actor.bounding_box.extent.x * 2.0 marker.scale.y = self.carla_actor.bounding_box.extent.y * 2.0 marker.scale.z = self.carla_actor.bounding_box.extent.z * 2.0 From 67fa4d65fc1d5f88f8a52da20af850dafd598bfc Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 3 Jun 2020 10:13:23 +0200 Subject: [PATCH 089/627] Add src folder to import python files from same package --- .../src/carla_ros_bridge/bridge.py | 57 ++++++++++--------- 1 file changed, 30 insertions(+), 27 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 08b72969..7565da79 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -22,27 +22,27 @@ import carla -from carla_ros_bridge.actor import Actor -from carla_ros_bridge.communication import Communication -from carla_ros_bridge.sensor import Sensor - -from carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher -from carla_ros_bridge.world_info import WorldInfo -from carla_ros_bridge.spectator import Spectator -from carla_ros_bridge.traffic import Traffic, TrafficLight -from carla_ros_bridge.vehicle import Vehicle -from carla_ros_bridge.lidar import Lidar -from carla_ros_bridge.radar import Radar -from carla_ros_bridge.gnss import Gnss -from carla_ros_bridge.imu import ImuSensor -from carla_ros_bridge.ego_vehicle import EgoVehicle -from carla_ros_bridge.collision_sensor import CollisionSensor -from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera -from carla_ros_bridge.object_sensor import ObjectSensor -from carla_ros_bridge.walker import Walker -from carla_ros_bridge.debug_helper import DebugHelper -from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor +from src.carla_ros_bridge.actor import Actor +from src.carla_ros_bridge.communication import Communication +from src.carla_ros_bridge.sensor import Sensor + +from src.carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher +from src.carla_ros_bridge.world_info import WorldInfo +from src.carla_ros_bridge.spectator import Spectator +from src.carla_ros_bridge.traffic import Traffic, TrafficLight +from src.carla_ros_bridge.vehicle import Vehicle +from src.carla_ros_bridge.lidar import Lidar +from src.carla_ros_bridge.radar import Radar +from src.carla_ros_bridge.gnss import Gnss +from src.carla_ros_bridge.imu import ImuSensor +from src.carla_ros_bridge.ego_vehicle import EgoVehicle +from src.carla_ros_bridge.collision_sensor import CollisionSensor +from src.carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor +from src.carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera +from src.carla_ros_bridge.object_sensor import ObjectSensor +from src.carla_ros_bridge.walker import Walker +from src.carla_ros_bridge.debug_helper import DebugHelper +from src.carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters import os @@ -144,8 +144,8 @@ def __init__(self, carla_world, params): # add global object sensor self.pseudo_actors.append( - ObjectSensor(parent=None, communication=self.comm, actor_list=self.actors, - filtered_id=None)) + ObjectSensor( + parent=None, communication=self.comm, actor_list=self.actors, filtered_id=None)) self.debug_helper = DebugHelper(carla_world.debug) # add traffic light pseudo sensor @@ -388,8 +388,11 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m actor = EgoVehicle(carla_actor, parent, self.comm, self._ego_vehicle_control_applied_callback) pseudo_actors.append( - ObjectSensor(parent=actor, communication=self.comm, actor_list=self.actors, - filtered_id=carla_actor.id)) + ObjectSensor( + parent=actor, + communication=self.comm, + actor_list=self.actors, + filtered_id=carla_actor.id)) else: actor = Vehicle(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("sensor"): @@ -509,8 +512,8 @@ def main(): """ rospy.init_node("carla_bridge", anonymous=True) parameters = rospy.get_param('carla') - rospy.loginfo("Trying to connect to {host}:{port}".format(host=parameters['host'], - port=parameters['port'])) + rospy.loginfo("Trying to connect to {host}:{port}".format( + host=parameters['host'], port=parameters['port'])) carla_bridge = None carla_world = None From ea5d6df8415c87d250e4517e1156c1d3c503810b Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 3 Jun 2020 11:40:10 +0200 Subject: [PATCH 090/627] Add construction of compatible ros nodes --- .../src/carla_ros_bridge/bridge.py | 98 ++++++++++++------- 1 file changed, 62 insertions(+), 36 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 7565da79..51470a76 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -20,29 +20,29 @@ from threading import Thread, Lock, Event import pkg_resources -import carla +# import carla from src.carla_ros_bridge.actor import Actor -from src.carla_ros_bridge.communication import Communication -from src.carla_ros_bridge.sensor import Sensor - -from src.carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher -from src.carla_ros_bridge.world_info import WorldInfo -from src.carla_ros_bridge.spectator import Spectator -from src.carla_ros_bridge.traffic import Traffic, TrafficLight -from src.carla_ros_bridge.vehicle import Vehicle -from src.carla_ros_bridge.lidar import Lidar -from src.carla_ros_bridge.radar import Radar -from src.carla_ros_bridge.gnss import Gnss -from src.carla_ros_bridge.imu import ImuSensor -from src.carla_ros_bridge.ego_vehicle import EgoVehicle -from src.carla_ros_bridge.collision_sensor import CollisionSensor -from src.carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -from src.carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera -from src.carla_ros_bridge.object_sensor import ObjectSensor -from src.carla_ros_bridge.walker import Walker -from src.carla_ros_bridge.debug_helper import DebugHelper -from src.carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor +# from src.carla_ros_bridge.communication import Communication +# from src.carla_ros_bridge.sensor import Sensor + +# from src.carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher +# from src.carla_ros_bridge.world_info import WorldInfo +# from src.carla_ros_bridge.spectator import Spectator +# from src.carla_ros_bridge.traffic import Traffic, TrafficLight +# from src.carla_ros_bridge.vehicle import Vehicle +# from src.carla_ros_bridge.lidar import Lidar +# from src.carla_ros_bridge.radar import Radar +# from src.carla_ros_bridge.gnss import Gnss +# from src.carla_ros_bridge.imu import ImuSensor +# from src.carla_ros_bridge.ego_vehicle import EgoVehicle +# from src.carla_ros_bridge.collision_sensor import CollisionSensor +# from src.carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor +# from src.carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera +# from src.carla_ros_bridge.object_sensor import ObjectSensor +# from src.carla_ros_bridge.walker import Walker +# from src.carla_ros_bridge.debug_helper import DebugHelper +# from src.carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters import os @@ -50,20 +50,31 @@ if ROS_VERSION == 1: import rospy + from ros_compatibility import CompatibleNode elif ROS_VERSION == 2: + import sys + import os + print(os.getcwd()) + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') import rclpy + from rclpy.node import Node + from rclpy import executors + from ament_index_python.packages import get_package_share_directory + from ros_compatible_node import CompatibleNode else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -class CarlaRosBridge(object): +class CarlaRosBridge(CompatibleNode): """ Carla Ros bridge """ CARLA_VERSION = "0.9.9" - def __init__(self, carla_world, params): + def __init__(self, rospy_init=True): """ Constructor @@ -72,6 +83,9 @@ def __init__(self, carla_world, params): :param params: dict of parameters, see settings.yaml :type params: dict """ + super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init) + + def initialize_bridge(self, carla_world, params): self.parameters = params self.actors = {} self.pseudo_actors = [] @@ -112,8 +126,8 @@ def __init__(self, carla_world, params): self.carla_run_state = CarlaControl.PLAY self.carla_control_subscriber = \ - rospy.Subscriber("/carla/control", CarlaControl, - lambda control: self.carla_control_queue.put(control.command)) + self.create_subscriber(CarlaControl, "/carla/control", None, + qos_profile=lambda control: self.carla_control_queue.put(control.command)) self.synchronous_mode_update_thread = Thread(target=self._synchronous_mode_update) self.synchronous_mode_update_thread.start() @@ -510,14 +524,25 @@ def main(): main function for carla simulator ROS bridge maintaining the communication client and the CarlaBridge object """ - rospy.init_node("carla_bridge", anonymous=True) - parameters = rospy.get_param('carla') - rospy.loginfo("Trying to connect to {host}:{port}".format( - host=parameters['host'], port=parameters['port'])) - carla_bridge = None carla_world = None carla_client = None + + if ROS_VERSION == 1: + carla_bridge = CarlaRosBridge() + + elif ROS_VERSION == 2: + rclpy.init(args=None) + carla_bridge = CarlaRosBridge() + executor = rclpy.executors.MultiThreadedExecutor() + init_node = rclpy.create_node("init_ros_bridge") + executor.add_node(init_node) + + parameters = carla_bridge.get_param('carla.host') + print(parameters) + carla_bridge.loginfo("Trying to connect to {host}:{port}".format( + host=parameters['host'], port=parameters['port'])) + try: carla_client = carla.Client(host=parameters['host'], port=parameters['port']) carla_client.set_timeout(parameters['timeout']) @@ -525,13 +550,13 @@ def main(): # check carla version dist = pkg_resources.get_distribution("carla") if LooseVersion(dist.version) < LooseVersion(CarlaRosBridge.CARLA_VERSION): - rospy.logfatal("CARLA python module version {} required. Found: {}".format( + carla_bridge.logfatal("CARLA python module version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, dist.version)) sys.exit(1) if LooseVersion(carla_client.get_server_version()) < \ LooseVersion(CarlaRosBridge.CARLA_VERSION): - rospy.logfatal("CARLA Server version {} required. Found: {}".format( + carla_bridge.logfatal("CARLA Server version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) sys.exit(1) @@ -539,22 +564,23 @@ def main(): if "town" in parameters: if parameters["town"].endswith(".xodr"): - rospy.loginfo("Loading opendrive world from file '{}'".format(parameters["town"])) + carla_bridge.loginfo("Loading opendrive world from file '{}'".format( + parameters["town"])) with open(parameters["town"]) as od_file: data = od_file.read() carla_world = carla_client.generate_opendrive_world(str(data)) else: if carla_world.get_map().name != parameters["town"]: - rospy.loginfo("Loading town '{}' (previous: '{}').".format( + carla_bridge.loginfo("Loading town '{}' (previous: '{}').".format( parameters["town"], carla_world.get_map().name)) carla_world = carla_client.load_world(parameters["town"]) carla_world.tick() - carla_bridge = CarlaRosBridge(carla_client.get_world(), parameters) + carla_bridge.initialize_bridge(carla_client.get_world(), parameters) carla_bridge.run() except (IOError, RuntimeError) as e: - rospy.logerr("Error: {}".format(e)) + carla_bridge.logerr("Error: {}".format(e)) finally: del carla_world del carla_client From 687af834cfdb7ab648db6cf49dd6b8265a1903cf Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 3 Jun 2020 11:41:05 +0200 Subject: [PATCH 091/627] Add import for both ROS versions --- .../src/carla_ros_bridge/pseudo_actor.py | 18 +++++++++++++++--- 1 file changed, 15 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 18fa9c02..3e199ec7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -10,11 +10,17 @@ """ from std_msgs.msg import Header -import rospy +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +if ROS_VERSION == 1: + import rospy +elif ROS_VERSION == 2: + import rclpy +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") class PseudoActor(object): - """ Generic base class for Pseudo actors (that are not existing in Carla world) """ @@ -72,7 +78,13 @@ def get_msg_header(self, frame_id=None, timestamp=None): else: header.frame_id = self.get_prefix() if timestamp: - header.stamp = rospy.Time.from_sec(timestamp) + if ROS_VERSION == 1: + header.stamp = rospy.Time.from_sec(timestamp) + elif ROS_VERSION == 2: + header.stamp = rclpy.Time.from_sec(timestamp) + else: + raise NotImplementedError( + "Make sure you have a valid ROS_VERSION env variable set.") else: header.stamp = self.communication.get_current_ros_time() return header From d624ed24b3ee0fbe1cd040dd7ad7dfb84f98f684 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 3 Jun 2020 11:41:28 +0200 Subject: [PATCH 092/627] Add import of transformation libraries for both versions --- .../src/carla_ros_bridge/transforms.py | 39 +++++++++---------- 1 file changed, 18 insertions(+), 21 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/transforms.py b/carla_ros_bridge/src/carla_ros_bridge/transforms.py index 8b6ee7be..2048c5ef 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/transforms.py +++ b/carla_ros_bridge/src/carla_ros_bridge/transforms.py @@ -13,9 +13,18 @@ import math import numpy -import tf from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + from tf.transformations import euler_matrix, quaternion_from_euler +elif ROS_VERSION == 2: + from transformations.transformations import euler_matrix, quaternion_from_euler +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") + def carla_location_to_numpy_vector(carla_location): """ @@ -29,11 +38,7 @@ def carla_location_to_numpy_vector(carla_location): :return: a numpy.array with 3 elements :rtype: numpy.array """ - return numpy.array([ - carla_location.x, - -carla_location.y, - carla_location.z - ]) + return numpy.array([carla_location.x, -carla_location.y, carla_location.z]) def carla_location_to_ros_vector3(carla_location): @@ -127,7 +132,7 @@ def carla_rotation_to_numpy_quaternion(carla_rotation): :rtype: numpy.array """ roll, pitch, yaw = carla_rotation_to_RPY(carla_rotation) - quat = tf.transformations.quaternion_from_euler(roll, pitch, yaw) + quat = quaternion_from_euler(roll, pitch, yaw) return quat @@ -165,7 +170,7 @@ def carla_rotation_to_numpy_rotation_matrix(carla_rotation): :rtype: numpy.array """ roll, pitch, yaw = carla_rotation_to_RPY(carla_rotation) - numpy_array = tf.transformations.euler_matrix(roll, pitch, yaw) + numpy_array = euler_matrix(roll, pitch, yaw) rotation_matrix = numpy_array[:3, :3] return rotation_matrix @@ -246,11 +251,7 @@ def carla_velocity_to_numpy_vector(carla_velocity): :return: a numpy.array with 3 elements :rtype: numpy.array """ - return numpy.array([ - carla_velocity.x, - -carla_velocity.y, - carla_velocity.z - ]) + return numpy.array([carla_velocity.x, -carla_velocity.y, carla_velocity.z]) def carla_acceleration_to_ros_accel(carla_acceleration): @@ -287,10 +288,8 @@ def carla_transform_to_ros_transform(carla_transform): """ ros_transform = Transform() - ros_transform.translation = carla_location_to_ros_vector3( - carla_transform.location) - ros_transform.rotation = carla_rotation_to_ros_quaternion( - carla_transform.rotation) + ros_transform.translation = carla_location_to_ros_vector3(carla_transform.location) + ros_transform.rotation = carla_rotation_to_ros_quaternion(carla_transform.rotation) return ros_transform @@ -308,10 +307,8 @@ def carla_transform_to_ros_pose(carla_transform): """ ros_pose = Pose() - ros_pose.position = carla_location_to_ros_point( - carla_transform.location) - ros_pose.orientation = carla_rotation_to_ros_quaternion( - carla_transform.rotation) + ros_pose.position = carla_location_to_ros_point(carla_transform.location) + ros_pose.orientation = carla_rotation_to_ros_quaternion(carla_transform.rotation) return ros_pose From fb1f3cf7e1a99e5a53a6bfa940907eea86935634 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 3 Jun 2020 14:24:12 +0200 Subject: [PATCH 093/627] Add parameter readings for ROS2 version --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 51470a76..5f50438d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -20,7 +20,7 @@ from threading import Thread, Lock, Event import pkg_resources -# import carla +import carla from src.carla_ros_bridge.actor import Actor # from src.carla_ros_bridge.communication import Communication @@ -527,7 +527,7 @@ def main(): carla_bridge = None carla_world = None carla_client = None - + parameters = {} if ROS_VERSION == 1: carla_bridge = CarlaRosBridge() @@ -538,7 +538,17 @@ def main(): init_node = rclpy.create_node("init_ros_bridge") executor.add_node(init_node) - parameters = carla_bridge.get_param('carla.host') + parameters['host'] = carla_bridge.get_param('carla.host', 'localhost') + parameters['port'] = carla_bridge.get_param('carla.port', 2000) + parameters['timeout'] = carla_bridge.get_param('carla.timeout', 2) + parameters['synchronous_mode'] = carla_bridge.get_param('carla.synchronous_mode', False) + parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( + 'carla.synchronous_mode_wait_for_vehicle_control_command', True) + parameters['fixed_delta_seconds'] = carla_bridge.get_param('carla.fixed_delta_seconds', + 0.05) + parameters['ego_vehicle'] = carla_bridge.get_param( + 'carla.ego_vehicle', ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) + print(parameters) carla_bridge.loginfo("Trying to connect to {host}:{port}".format( host=parameters['host'], port=parameters['port'])) From 595acf6dd641cc7f64658ea459219f1d60ea1891 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:32:48 +0200 Subject: [PATCH 094/627] Adapt bridge.py for ROS2 compatibility --- .../src/carla_ros_bridge/bridge.py | 47 +++++++++---------- 1 file changed, 23 insertions(+), 24 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 5f50438d..d9973e7b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -23,14 +23,14 @@ import carla from src.carla_ros_bridge.actor import Actor -# from src.carla_ros_bridge.communication import Communication -# from src.carla_ros_bridge.sensor import Sensor - -# from src.carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher -# from src.carla_ros_bridge.world_info import WorldInfo -# from src.carla_ros_bridge.spectator import Spectator -# from src.carla_ros_bridge.traffic import Traffic, TrafficLight -# from src.carla_ros_bridge.vehicle import Vehicle +from src.carla_ros_bridge.communication import Communication +from src.carla_ros_bridge.sensor import Sensor + +from src.carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher +from src.carla_ros_bridge.world_info import WorldInfo +from src.carla_ros_bridge.spectator import Spectator +from src.carla_ros_bridge.traffic import Traffic, TrafficLight +from src.carla_ros_bridge.vehicle import Vehicle # from src.carla_ros_bridge.lidar import Lidar # from src.carla_ros_bridge.radar import Radar # from src.carla_ros_bridge.gnss import Gnss @@ -39,10 +39,10 @@ # from src.carla_ros_bridge.collision_sensor import CollisionSensor # from src.carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor # from src.carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera -# from src.carla_ros_bridge.object_sensor import ObjectSensor -# from src.carla_ros_bridge.walker import Walker -# from src.carla_ros_bridge.debug_helper import DebugHelper -# from src.carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor +from src.carla_ros_bridge.object_sensor import ObjectSensor +from src.carla_ros_bridge.walker import Walker +from src.carla_ros_bridge.debug_helper import DebugHelper +from src.carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters import os @@ -53,7 +53,6 @@ from ros_compatibility import CompatibleNode elif ROS_VERSION == 2: import sys - import os print(os.getcwd()) # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) sys.path.append(os.getcwd() + @@ -158,8 +157,8 @@ def initialize_bridge(self, carla_world, params): # add global object sensor self.pseudo_actors.append( - ObjectSensor( - parent=None, communication=self.comm, actor_list=self.actors, filtered_id=None)) + ObjectSensor(parent=None, communication=self.comm, actor_list=self.actors, + filtered_id=None)) self.debug_helper = DebugHelper(carla_world.debug) # add traffic light pseudo sensor @@ -402,11 +401,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m actor = EgoVehicle(carla_actor, parent, self.comm, self._ego_vehicle_control_applied_callback) pseudo_actors.append( - ObjectSensor( - parent=actor, - communication=self.comm, - actor_list=self.actors, - filtered_id=carla_actor.id)) + ObjectSensor(parent=actor, communication=self.comm, actor_list=self.actors, + filtered_id=carla_actor.id)) else: actor = Vehicle(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("sensor"): @@ -474,8 +470,11 @@ def run(self): :return: """ - rospy.on_shutdown(self.on_shutdown) - rospy.spin() + if ROS_VERSION == 1: + rospy.on_shutdown(self.on_shutdown) + elif ROS_VERSION == 2: + rclpy.get_default_context().on_shutdown(self.on_shutdown) + self.spin() def on_shutdown(self): """ @@ -550,8 +549,8 @@ def main(): 'carla.ego_vehicle', ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) print(parameters) - carla_bridge.loginfo("Trying to connect to {host}:{port}".format( - host=parameters['host'], port=parameters['port'])) + carla_bridge.loginfo("Trying to connect to {host}:{port}".format(host=parameters['host'], + port=parameters['port'])) try: carla_client = carla.Client(host=parameters['host'], port=parameters['port']) From d61efa3c67ef001ee02eae4f03a28621edf9b79b Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:33:23 +0200 Subject: [PATCH 095/627] Adapt pseudo_actor.py for ROS2 compatibility --- .../src/carla_ros_bridge/pseudo_actor.py | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 3e199ec7..3d9abd27 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -14,13 +14,26 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: import rospy + from ros_compatibility import * elif ROS_VERSION == 2: import rclpy + from rclpy.qos import QoSDurabilityPolicy + from rclpy.qos import QoSProfile + import sys + print(os.getcwd()) + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + import rclpy + from rclpy.node import Node + from rclpy import executors + from ament_index_python.packages import get_package_share_directory + from ros_compatible_node import CompatibleNode else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -class PseudoActor(object): +class PseudoActor(CompatibleNode): """ Generic base class for Pseudo actors (that are not existing in Carla world) """ From 67bc8cec2f3f68ee8bd359099907012c3721325a Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:33:51 +0200 Subject: [PATCH 096/627] Adapt communication.py for ROS2 compatibility --- .../src/carla_ros_bridge/communication.py | 43 +++++++++++-------- 1 file changed, 25 insertions(+), 18 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 21b64b89..636f9e5c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -20,7 +20,16 @@ import rclpy from rclpy.qos import QoSDurabilityPolicy from rclpy.qos import QoSProfile - from ros_compatibility import * + import sys + print(os.getcwd()) + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + import rclpy + from rclpy.node import Node + from rclpy import executors + from ament_index_python.packages import get_package_share_directory + from ros_compatible_node import CompatibleNode, ros_timestamp latch = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -31,7 +40,6 @@ class Communication(CompatibleNode): - """ Handle communication of ROS topics """ @@ -43,14 +51,13 @@ def __init__(self): super(Communication, self).__init__("communication", rospy_init=False) self.tf_to_publish = [] self.msgs_to_publish = [] - self.publishers = {} + self.pub = {} self.subscribers = {} self.ros_timestamp = ros_timestamp() # needed? - self.publishers['clock'] = self.new_publisher(Clock, 'clock') - self.publishers['tf'] = self.new_publisher(TFMessage, 'tf', - qos_profile=QoSProfile(depth=100)) + # self.pub['clock'] = self.new_publisher(Clock, 'clock') + # self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100)) def send_msgs(self): """ @@ -59,11 +66,11 @@ def send_msgs(self): :return: """ # prepare tf message - tf_msg = TFMessage(self.tf_to_publish) - try: - self.publishers['tf'].publish(tf_msg) - except Exception as error: # pylint: disable=broad-except - self.logwarn("Failed to publish message: {}".format(error)) + # tf_msg = TFMessage(self.tf_to_publish) + # try: + # self.pub['tf'].publish(tf_msg) + # except Exception as error: # pylint: disable=broad-except + # self.logwarn("Failed to publish message: {}".format(error)) for publisher, msg in self.msgs_to_publish: try: @@ -94,15 +101,14 @@ def publish_message(self, topic, msg, is_latched=False): # transform are merged in same message self.tf_to_publish.append(msg) else: - if topic not in self.publishers: + if topic not in self.pub: if is_latched: qos_profile = QoSProfile(depth=10, durability=latch) - self.publishers[topic] = self.new_publisher(type(msg), topic, - qos_profile=qos_profile) + self.pub[topic] = self.new_publisher(type(msg), topic, qos_profile=qos_profile) else: # Use default QoS profile. - self.publishers[topic] = self.new_publisher(type(msg), topic) - self.msgs_to_publish.append((self.publishers[topic], msg)) + self.pub[topic] = self.new_publisher(type(msg), topic) + self.msgs_to_publish.append((self.pub[topic], msg)) def update_clock(self, carla_timestamp): """ @@ -112,8 +118,9 @@ def update_clock(self, carla_timestamp): :type carla_timestamp: carla.Timestamp :return: """ - self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_secs=True) - self.publish_message('clock', Clock(self.ros_timestamp)) + # self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_secs=True) + # self.publish_message('clock', Clock(self.ros_timestamp)) + pass def get_current_ros_time(self): """ From e05212212f8460187af60f0755282bdd786d3a22 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:34:13 +0200 Subject: [PATCH 097/627] Adapt carla_status_publisher.py for ROS2 compatibility --- .../carla_ros_bridge/carla_status_publisher.py | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 1390fec3..65219072 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -19,7 +19,15 @@ elif ROS_VERSION == 2: import rclpy from rclpy.callback_groups import ReentrantCallbackGroup - # TODO: import ros_compatibilty + import sys + print(os.getcwd()) + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + from rclpy.node import Node + from rclpy import executors + from ament_index_python.packages import get_package_share_directory + from ros_compatible_node import CompatibleNode else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -36,8 +44,7 @@ def __init__(self, synchronous_mode, fixed_delta_seconds): Constructor """ - super(CarlaStatusPublisher, self).__init__("carla_status_publisher", - latch=True, + super(CarlaStatusPublisher, self).__init__("carla_status_publisher", latch=True, rospy_init=False) self.synchronous_mode = synchronous_mode self.synchronous_mode_running = True @@ -46,7 +53,7 @@ def __init__(self, synchronous_mode, fixed_delta_seconds): if ROS_VERSION == 1: callback_group = None elif ROS_VERSION == 2: - callback_group = ReentrantCallBackGroup() + callback_group = ReentrantCallbackGroup() self.carla_status_publisher = self.new_publisher(CarlaStatus, "/carla/status", callback_group=callback_group) self.publish() From 5f33fb71962abae8c1368ed942b1ecbeac4ae283 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:34:33 +0200 Subject: [PATCH 098/627] Adapt debug_helper.py for ROS2 compatibility --- .../src/carla_ros_bridge/debug_helper.py | 80 ++++++++----------- 1 file changed, 33 insertions(+), 47 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 080b6183..5797865a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -19,11 +19,17 @@ elif ROS_VERSION == 2: import rclpy from transformations.transformations import euler_from_quaternion - # TODO: fix import - from ros_compatibility import CompatibleNode + import sys + print(os.getcwd()) + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + from rclpy.node import Node + from rclpy import executors + from ament_index_python.packages import get_package_share_directory + from ros_compatible_node import CompatibleNode else: - raise NotImplementedError('Make sure you have valid ' + - 'ROS_VERSION env variable') + raise NotImplementedError('Make sure you have valid ' + 'ROS_VERSION env variable') import math from visualization_msgs.msg import Marker, MarkerArray @@ -31,7 +37,6 @@ class DebugHelper(CompatibleNode): - """ Helper to draw markers in CARLA """ @@ -45,8 +50,8 @@ def __init__(self, carla_debug_helper): """ super(DebugHelper, self).__init__("debug_helper", rospy_init=False) self.debug = carla_debug_helper - self.marker_subscriber = self.create_subscription( - MarkerArray, "/carla/debug_marker", self.on_marker) + self.marker_subscriber = self.create_subscriber(MarkerArray, "/carla/debug_marker", + self.on_marker) def destroy(self): """ @@ -67,17 +72,14 @@ def on_marker(self, marker_array): """ for marker in marker_array.markers: if marker.header.frame_id != "map": - self.logwarn( - "Could not draw marker in frame '{}'. Only 'map' supported.".format( - marker.header.frame_id)) + self.logwarn("Could not draw marker in frame '{}'. Only 'map' supported.".format( + marker.header.frame_id)) continue lifetime = -1. if marker.lifetime: lifetime = marker.lifetime.to_sec() - color = carla.Color(int(marker.color.r * 255), - int(marker.color.g * 255), - int(marker.color.b * 255), - int(marker.color.a * 255)) + color = carla.Color(int(marker.color.r * 255), int(marker.color.g * 255), + int(marker.color.b * 255), int(marker.color.a * 255)) if marker.type == Marker.POINTS: self.draw_points(marker, lifetime, color) @@ -96,31 +98,23 @@ def draw_arrow(self, marker, lifetime, color): """ if marker.points: if not len(marker.points) == 2: - self.logwarn( - "Drawing arrow from points requires two points. Received {}".format( - len(marker.points))) + self.logwarn("Drawing arrow from points requires two points. Received {}".format( + len(marker.points))) return thickness = marker.scale.x arrow_size = marker.scale.y - start = carla.Location( - x=marker.points[0].x, y=-marker.points[0].y, z=marker.points[0].z) - end = carla.Location( - x=marker.points[1].x, y=-marker.points[1].y, z=marker.points[1].z) + start = carla.Location(x=marker.points[0].x, y=-marker.points[0].y, + z=marker.points[0].z) + end = carla.Location(x=marker.points[1].x, y=-marker.points[1].y, z=marker.points[1].z) self.loginfo("Draw Arrow from {} to {} (color: {}, lifetime: {}, " - "thickness: {}, arrow_size: {})".format( - start, end, color, lifetime, thickness, arrow_size)) - self.debug.draw_arrow( - start, - end, - thickness=thickness, - arrow_size=arrow_size, - color=color, - life_time=lifetime) + "thickness: {}, arrow_size: {})".format(start, end, color, lifetime, + thickness, arrow_size)) + self.debug.draw_arrow(start, end, thickness=thickness, arrow_size=arrow_size, + color=color, life_time=lifetime) else: - self.logwarn( - "Drawing arrow from Position/Orientation not yet supported. " - "Please use points.") + self.logwarn("Drawing arrow from Position/Orientation not yet supported. " + "Please use points.") def draw_points(self, marker, lifetime, color): """ @@ -138,9 +132,8 @@ def draw_line_strips(self, marker, lifetime, color): draw lines from ros marker """ if len(marker.points) < 2: - self.logwarn( - "Drawing line-strip requires at least two points. Received {}".format( - len(marker.points))) + self.logwarn("Drawing line-strip requires at least two points. Received {}".format( + len(marker.points))) return last_point = None thickness = marker.scale.x @@ -148,14 +141,9 @@ def draw_line_strips(self, marker, lifetime, color): if last_point: start = carla.Location(x=last_point.x, y=-last_point.y, z=last_point.z) end = carla.Location(x=point.x, y=-point.y, z=point.z) - self.loginfo( - "Draw Line from {} to {} (color: {}, lifetime: {}, " - "thickness: {})".format( - start, end, color, lifetime, thickness)) - self.debug.draw_line(start, - end, - thickness=thickness, - color=color, + self.loginfo("Draw Line from {} to {} (color: {}, lifetime: {}, " + "thickness: {})".format(start, end, color, lifetime, thickness)) + self.debug.draw_line(start, end, thickness=thickness, color=color, life_time=lifetime) last_point = point @@ -172,9 +160,7 @@ def draw_box(self, marker, lifetime, color): box.extent.z = marker.scale.z / 2 roll, pitch, yaw = euler_from_quaternion([ - marker.pose.orientation.x, - marker.pose.orientation.y, - marker.pose.orientation.z, + marker.pose.orientation.x, marker.pose.orientation.y, marker.pose.orientation.z, marker.pose.orientation.w ]) rotation = carla.Rotation() From dcd89fc5401628874f6321429875d84f61bb49f2 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:35:17 +0200 Subject: [PATCH 099/627] Adapt object_sensor.py for ROS2 compatibility --- carla_ros_bridge/src/carla_ros_bridge/object_sensor.py | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 7eb803c3..b3dac308 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -10,13 +10,12 @@ """ from derived_object_msgs.msg import ObjectArray -from carla_ros_bridge.vehicle import Vehicle -from carla_ros_bridge.walker import Walker -from carla_ros_bridge.pseudo_actor import PseudoActor +from src.carla_ros_bridge.vehicle import Vehicle +from src.carla_ros_bridge.walker import Walker +from src.carla_ros_bridge.pseudo_actor import PseudoActor class ObjectSensor(PseudoActor): - """ Pseudo object sensor """ @@ -36,8 +35,7 @@ def __init__(self, parent, communication, actor_list, filtered_id): :type filtered_id: int """ - super(ObjectSensor, self).__init__(parent=parent, - communication=communication, + super(ObjectSensor, self).__init__(parent=parent, communication=communication, prefix='objects') self.actor_list = actor_list self.filtered_id = filtered_id From e7e0b20d1c177e0b108b2fbbe3efea0260deb12f Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:35:31 +0200 Subject: [PATCH 100/627] Adapt sensor.py for ROS2 compatibility --- .../src/carla_ros_bridge/sensor.py | 79 ++++++++++--------- 1 file changed, 41 insertions(+), 38 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index d025ec10..221853fd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -14,29 +14,33 @@ except ImportError: import Queue as queue +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +if ROS_VERSION == 1: + import rospy +elif ROS_VERSION == 2: + import rclpy -import rospy - -from carla_ros_bridge.actor import Actor -import carla_ros_bridge.transforms as trans +from src.carla_ros_bridge.actor import Actor +import src.carla_ros_bridge.transforms as trans class Sensor(Actor): - """ Actor implementation details for sensors """ - def __init__(self, # pylint: disable=too-many-arguments - carla_actor, - parent, - communication, - synchronous_mode, - is_event_sensor=False, # only relevant in synchronous_mode: - # if a sensor only delivers data on special events, - # do not wait for it. That means you might get data from a - # sensor, that belongs to a different frame - prefix=None): + def __init__( + self, # pylint: disable=too-many-arguments + carla_actor, + parent, + communication, + synchronous_mode, + is_event_sensor=False, # only relevant in synchronous_mode: + # if a sensor only delivers data on special events, + # do not wait for it. That means you might get data from a + # sensor, that belongs to a different frame + prefix=None): """ Constructor @@ -53,10 +57,8 @@ def __init__(self, # pylint: disable=too-many-arguments """ if prefix is None: prefix = 'sensor' - super(Sensor, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - prefix=prefix) + super(Sensor, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, prefix=prefix) self.synchronous_mode = synchronous_mode self.queue = queue.Queue() @@ -65,7 +67,7 @@ def __init__(self, # pylint: disable=too-many-arguments self.is_event_sensor = is_event_sensor try: self.sensor_tick_time = float(carla_actor.attributes["sensor_tick"]) - rospy.logdebug("Sensor tick time is {}".format(self.sensor_tick_time)) + self.logdebug("Sensor tick time is {}".format(self.sensor_tick_time)) except (KeyError, ValueError): self.sensor_tick_time = None @@ -81,7 +83,7 @@ def destroy(self): :return: """ - rospy.logdebug("Destroy Sensor(id={})".format(self.get_id())) + self.logdebug("Destroy Sensor(id={})".format(self.get_id())) if self.carla_actor.is_listening: self.carla_actor.stop() super(Sensor, self).destroy() @@ -93,15 +95,22 @@ def _callback_sensor_data(self, carla_sensor_data): :param carla_sensor_data: carla sensor data object :type carla_sensor_data: carla.SensorData """ - if not rospy.is_shutdown(): + is_shutdown = None + if ROS_VERSION == 1: + is_shutdown = rospy.is_shutdown() + elif ROS_VERSION == 2: + is_shutdown = False # No is_shutdown equivalent in rclpy available without actually shutting down the node https://discourse.ros.org/t/mapping-between-rospy-and-rclpy/5737/2 + + if not is_shutdown: if self.synchronous_mode: if self.sensor_tick_time: self.next_data_expected_time = carla_sensor_data.timestamp + \ float(self.sensor_tick_time) self.queue.put(carla_sensor_data) else: - self.publish_transform(self.get_ros_transform( - trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) + self.publish_transform( + self.get_ros_transform( + trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) self.sensor_data_updated(carla_sensor_data) @abstractmethod @@ -113,8 +122,7 @@ def sensor_data_updated(self, carla_sensor_data): :param carla_sensor_data: carla sensor data object :type carla_sensor_data: carla.SensorData """ - raise NotImplementedError( - "This function has to be implemented by the derived classes") + raise NotImplementedError("This function has to be implemented by the derived classes") def _update_synchronous_event_sensor(self, frame): while True: @@ -123,12 +131,10 @@ def _update_synchronous_event_sensor(self, frame): if carla_sensor_data.frame != frame: rospy.logwarn("{}({}): Received event for frame {}" " (expected {}). Process it anyways.".format( - self.__class__.__name__, - self.get_id(), - carla_sensor_data.frame, - frame)) - rospy.logdebug("{}({}): process {}".format( - self.__class__.__name__, self.get_id(), frame)) + self.__class__.__name__, self.get_id(), + carla_sensor_data.frame, frame)) + rospy.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), + frame)) self.publish_transform( self.get_ros_transform( trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) @@ -145,8 +151,8 @@ def _update_synchronous_sensor(self, frame, timestamp): try: carla_sensor_data = self.queue.get(timeout=1.0) if carla_sensor_data.frame == frame: - rospy.logdebug("{}({}): process {}".format( - self.__class__.__name__, self.get_id(), frame)) + rospy.logdebug("{}({}): process {}".format(self.__class__.__name__, + self.get_id(), frame)) self.publish_transform( self.get_ros_transform( trans.carla_transform_to_ros_transform( @@ -155,10 +161,7 @@ def _update_synchronous_sensor(self, frame, timestamp): return else: rospy.logwarn("{}({}): skipping old frame {}, expected {}".format( - self.__class__.__name__, - self.get_id(), - carla_sensor_data.frame, - frame)) + self.__class__.__name__, self.get_id(), carla_sensor_data.frame, frame)) except queue.Empty: if not rospy.is_shutdown(): rospy.logwarn("{}({}): Expected Frame {} not received".format( From e33e1cdcd7f642f2f479f543fa72aafa11448939 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:35:47 +0200 Subject: [PATCH 101/627] Adapt spectator.py for ROS2 compatibility --- carla_ros_bridge/src/carla_ros_bridge/spectator.py | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/spectator.py b/carla_ros_bridge/src/carla_ros_bridge/spectator.py index 92ddfa31..f35e17bc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/spectator.py +++ b/carla_ros_bridge/src/carla_ros_bridge/spectator.py @@ -10,11 +10,10 @@ Classes to handle Carla spectator """ -from carla_ros_bridge.actor import Actor +from src.carla_ros_bridge.actor import Actor class Spectator(Actor): - """ Actor implementation details for spectators """ @@ -30,7 +29,5 @@ def __init__(self, carla_actor, parent, communication): :param communication: communication-handle :type communication: carla_ros_bridge.communication """ - super(Spectator, self).__init__(carla_actor=carla_actor, - parent=parent, - prefix='spectator', + super(Spectator, self).__init__(carla_actor=carla_actor, parent=parent, prefix='spectator', communication=communication) From 97f6947ad4154017c638bcecefab328fcef038fc Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:37:19 +0200 Subject: [PATCH 102/627] Adapt traffic.py for ROS2 compatibility --- .../src/carla_ros_bridge/traffic.py | 21 +++++++------------ 1 file changed, 8 insertions(+), 13 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 04690cc4..90e1ef70 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -10,14 +10,13 @@ Classes to handle Carla traffic objects """ -from carla_ros_bridge.actor import Actor -import carla_ros_bridge.transforms as trans +from src.carla_ros_bridge.actor import Actor +import src.carla_ros_bridge.transforms as trans from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo from carla import TrafficLightState class Traffic(Actor): - """ Actor implementation details for traffic objects """ @@ -33,14 +32,11 @@ def __init__(self, carla_actor, parent, communication): :param communication: communication-handle :type communication: carla_ros_bridge.communication """ - super(Traffic, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - prefix='traffic') + super(Traffic, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, prefix='traffic') class TrafficLight(Actor): - """ Traffic implementation details for traffic lights """ @@ -56,10 +52,9 @@ def __init__(self, carla_actor, parent, communication): :param communication: communication-handle :type communication: carla_ros_bridge.communication """ - super(TrafficLight, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - prefix='traffic.traffic_light') + super(TrafficLight, + self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + prefix='traffic.traffic_light') def get_status(self): """ @@ -87,7 +82,7 @@ def get_info(self): info = CarlaTrafficLightInfo() info.id = self.get_id() info.transform = self.get_current_ros_pose() - info.trigger_volume.center = trans.carla_location_to_ros_point( + info.trigger_volume.center = trans.carla_location_to_ros_vector3( self.carla_actor.trigger_volume.location) info.trigger_volume.size.x = self.carla_actor.trigger_volume.extent.x * 2.0 info.trigger_volume.size.y = self.carla_actor.trigger_volume.extent.y * 2.0 From 19410873d06b5c6dd4f1999a9db4243878fe8e42 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:37:33 +0200 Subject: [PATCH 103/627] Adapt traffic_lights_sensor.py for ROS2 compatibility --- .../src/carla_ros_bridge/traffic_lights_sensor.py | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 32221482..d8d760dd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -11,8 +11,8 @@ from carla_msgs.msg import CarlaTrafficLightStatusList,\ CarlaTrafficLightInfoList -from carla_ros_bridge.traffic import TrafficLight -from carla_ros_bridge.pseudo_actor import PseudoActor +from src.carla_ros_bridge.traffic import TrafficLight +from src.carla_ros_bridge.pseudo_actor import PseudoActor class TrafficLightsSensor(PseudoActor): @@ -31,8 +31,7 @@ def __init__(self, parent, communication, actor_list): :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(TrafficLightsSensor, self).__init__(parent=parent, - communication=communication, + super(TrafficLightsSensor, self).__init__(parent=parent, communication=communication, prefix="") self.actor_list = actor_list self.traffic_light_status = CarlaTrafficLightStatusList() @@ -68,5 +67,5 @@ def update(self, frame, timestamp): if traffic_light_status != self.traffic_light_status: self.traffic_light_status = traffic_light_status - self.publish_message(self.get_topic_prefix() + "traffic_lights", - traffic_light_status, is_latched=True) + self.publish_message(self.get_topic_prefix() + "traffic_lights", traffic_light_status, + is_latched=True) From 1515a406e8e95875c0ae327adf9ab8225ae955cc Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:37:49 +0200 Subject: [PATCH 104/627] Adapt traffic_participant.py for ROS2 compatibility --- .../src/carla_ros_bridge/traffic_participant.py | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index d2b9ea3d..07518b98 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -14,11 +14,10 @@ from nav_msgs.msg import Odometry from shape_msgs.msg import SolidPrimitive -from carla_ros_bridge.actor import Actor +from src.carla_ros_bridge.actor import Actor class TrafficParticipant(Actor): - """ actor implementation details for traffic participant """ @@ -37,10 +36,8 @@ def __init__(self, carla_actor, parent, communication, prefix): :type prefix: string """ self.classification_age = 0 - super(TrafficParticipant, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - prefix=prefix) + super(TrafficParticipant, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, prefix=prefix) def update(self, frame, timestamp): """ @@ -93,7 +90,8 @@ def get_object_info(self): obj.shape.dimensions.extend([ self.carla_actor.bounding_box.extent.x * 2.0, self.carla_actor.bounding_box.extent.y * 2.0, - self.carla_actor.bounding_box.extent.z * 2.0]) + self.carla_actor.bounding_box.extent.z * 2.0 + ]) # Classification if available in attributes if self.get_classification() != Object.CLASSIFICATION_UNKNOWN: From cdf752f332344167859c376ddb44e5ee1d008abc Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:38:08 +0200 Subject: [PATCH 105/627] Adapt vehicle.py for ROS2 compatibility --- carla_ros_bridge/src/carla_ros_bridge/vehicle.py | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index cc83b34b..ec0fce0a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -13,11 +13,10 @@ from std_msgs.msg import ColorRGBA from derived_object_msgs.msg import Object -from carla_ros_bridge.traffic_participant import TrafficParticipant +from src.carla_ros_bridge.traffic_participant import TrafficParticipant class Vehicle(TrafficParticipant): - """ Actor implementation details for vehicles """ @@ -51,10 +50,8 @@ def __init__(self, carla_actor, parent, communication, prefix=None): elif carla_actor.attributes['object_type'] == 'other': self.classification = Object.CLASSIFICATION_OTHER_VEHICLE - super(Vehicle, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - prefix=prefix) + super(Vehicle, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, prefix=prefix) def get_marker_color(self): # pylint: disable=no-self-use """ From 8cb81f6102a3af1f484b652f20f11c37059de5f7 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:38:21 +0200 Subject: [PATCH 106/627] Adapt walker.py for ROS2 compatibility --- .../src/carla_ros_bridge/walker.py | 19 ++++++++----------- 1 file changed, 8 insertions(+), 11 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index b6c2e98f..ac5cfa6e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -9,16 +9,15 @@ """ Classes to handle Carla pedestrians """ -import rospy + from derived_object_msgs.msg import Object -from carla_ros_bridge.traffic_participant import TrafficParticipant +from src.carla_ros_bridge.traffic_participant import TrafficParticipant from carla_msgs.msg import CarlaWalkerControl from carla import WalkerControl class Walker(TrafficParticipant): - """ Actor implementation details for pedestrians """ @@ -41,14 +40,12 @@ def __init__(self, carla_actor, parent, communication): else: prefix = "walker/{:03}".format(carla_actor.id) - super(Walker, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - prefix=prefix) + super(Walker, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, prefix=prefix) - self.control_subscriber = rospy.Subscriber( - self.get_topic_prefix() + "/walker_control_cmd", - CarlaWalkerControl, self.control_command_updated) + self.control_subscriber = self.create_subscriber( + CarlaWalkerControl, + self.get_topic_prefix() + "/walker_control_cmd", self.control_command_updated) def destroy(self): """ @@ -59,7 +56,7 @@ def destroy(self): :return: """ - rospy.logdebug("Destroy Walker(id={})".format(self.get_id())) + self.logdebug("Destroy Walker(id={})".format(self.get_id())) self.control_subscriber.unregister() self.control_subscriber = None super(Walker, self).destroy() From 73303ca0b374a14489898302eba02c9d0278d27b Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 16:38:33 +0200 Subject: [PATCH 107/627] Adapt world_info.py for ROS2 compatibility --- carla_ros_bridge/src/carla_ros_bridge/world_info.py | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index c341fc02..97e86282 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -10,14 +10,11 @@ Class to handle the carla map """ -import rospy - from carla_msgs.msg import CarlaWorldInfo -from carla_ros_bridge.pseudo_actor import PseudoActor +from src.carla_ros_bridge.pseudo_actor import PseudoActor class WorldInfo(PseudoActor): - """ Publish the map """ @@ -32,8 +29,7 @@ def __init__(self, carla_world, communication): :type communication: carla_ros_bridge.communication """ - super(WorldInfo, self).__init__(parent=None, - communication=communication, + super(WorldInfo, self).__init__(parent=None, communication=communication, prefix="world_info") self.carla_map = carla_world.get_map() @@ -49,7 +45,7 @@ def destroy(self): :return: """ - rospy.logdebug("Destroying WorldInfo()") + self.logdebug("Destroying WorldInfo()") self.carla_map = None super(WorldInfo, self).destroy() From f5bb4ef206925510b5b8e71f05e7b9e044d43405 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 3 Jun 2020 18:00:46 +0200 Subject: [PATCH 108/627] Start port of ego_vehicle --- .../src/carla_ros_bridge/bridge.py | 34 ++++++----- .../src/carla_ros_bridge/ego_vehicle.py | 57 ++++++++--------- .../src/carla_ros_bridge/pseudo_actor.py | 3 + .../ros_compatibility/ros_compatible_node.py | 61 +++++++------------ 4 files changed, 69 insertions(+), 86 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index d9973e7b..29984ca9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -31,14 +31,14 @@ from src.carla_ros_bridge.spectator import Spectator from src.carla_ros_bridge.traffic import Traffic, TrafficLight from src.carla_ros_bridge.vehicle import Vehicle -# from src.carla_ros_bridge.lidar import Lidar -# from src.carla_ros_bridge.radar import Radar -# from src.carla_ros_bridge.gnss import Gnss -# from src.carla_ros_bridge.imu import ImuSensor -# from src.carla_ros_bridge.ego_vehicle import EgoVehicle -# from src.carla_ros_bridge.collision_sensor import CollisionSensor -# from src.carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -# from src.carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera +from src.carla_ros_bridge.lidar import Lidar +from src.carla_ros_bridge.radar import Radar +from src.carla_ros_bridge.gnss import Gnss +from src.carla_ros_bridge.imu import ImuSensor +from src.carla_ros_bridge.ego_vehicle import EgoVehicle +from src.carla_ros_bridge.collision_sensor import CollisionSensor +from src.carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor +from src.carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera from src.carla_ros_bridge.object_sensor import ObjectSensor from src.carla_ros_bridge.walker import Walker from src.carla_ros_bridge.debug_helper import DebugHelper @@ -148,9 +148,9 @@ def initialize_bridge(self, carla_world, params): # register callback to update actors self.on_tick_id = self.carla_world.on_tick(self._carla_time_tick) - # self.carla_weather_subscriber = \ - # rospy.Subscriber("/carla/weather_control", - # CarlaWeatherParameters, self.on_weather_changed) + self.carla_weather_subscriber = \ + self.create_subscriber("/carla/weather_control", + CarlaWeatherParameters, self.on_weather_changed) # add world info self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, communication=self.comm)) @@ -171,7 +171,7 @@ def destroy(self): :return: """ - rospy.signal_shutdown("") + self.signal_shutdown("") self.debug_helper.destroy() self.shutdown.set() self.carla_weather_subscriber.unregister() @@ -182,7 +182,7 @@ def destroy(self): self.update_actor_thread.join() self._update_actors(set()) - rospy.loginfo("Exiting Bridge") + self.loginfo("Exiting Bridge") def on_weather_changed(self, weather_parameters): """ @@ -191,7 +191,7 @@ def on_weather_changed(self, weather_parameters): """ if not self.carla_world: return - rospy.loginfo("Applying weather parameters...") + self.loginfo("Applying weather parameters...") weather = carla.WeatherParameters() weather.cloudiness = weather_parameters.cloudiness weather.precipitation = weather_parameters.precipitation @@ -529,6 +529,7 @@ def main(): parameters = {} if ROS_VERSION == 1: carla_bridge = CarlaRosBridge() + rospy.init_node('carla_ros_bridge', anonymous=True) elif ROS_VERSION == 2: rclpy.init(args=None) @@ -545,8 +546,9 @@ def main(): 'carla.synchronous_mode_wait_for_vehicle_control_command', True) parameters['fixed_delta_seconds'] = carla_bridge.get_param('carla.fixed_delta_seconds', 0.05) - parameters['ego_vehicle'] = carla_bridge.get_param( - 'carla.ego_vehicle', ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) + role_name = carla_bridge.get_param('carla.ego_vehicle.role_name', + ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) + parameters["ego_vehicle"] = {"role_name": role_name} print(parameters) carla_bridge.loginfo("Trying to connect to {host}:{port}".format(host=parameters['host'], diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 01d93017..e1e73d15 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -12,8 +12,6 @@ import math import numpy -import rospy - from std_msgs.msg import ColorRGBA from std_msgs.msg import Bool from geometry_msgs.msg import Twist, Transform @@ -21,15 +19,14 @@ from carla import VehicleControl from carla import Vector3D -from carla_ros_bridge.vehicle import Vehicle -import carla_ros_bridge.transforms as transforms +from src.carla_ros_bridge.vehicle import Vehicle +import src.carla_ros_bridge.transforms as transforms from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel,\ CarlaEgoVehicleControl, CarlaEgoVehicleStatus class EgoVehicle(Vehicle): - """ Vehicle implementation details for the ego vehicle """ @@ -45,36 +42,36 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c :param communication: communication-handle :type communication: carla_ros_bridge.communication """ - super(EgoVehicle, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - prefix=carla_actor.attributes.get('role_name')) + super(EgoVehicle, + self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + prefix=carla_actor.attributes.get('role_name')) self.vehicle_info_published = False self.vehicle_control_override = False self._vehicle_control_applied_callback = vehicle_control_applied_callback - self.control_subscriber = rospy.Subscriber( - self.get_topic_prefix() + "/vehicle_control_cmd", + self.control_subscriber = self.create_subscriber( CarlaEgoVehicleControl, + self.get_topic_prefix() + "/vehicle_control_cmd", lambda data: self.control_command_updated(data, manual_override=False)) - self.manual_control_subscriber = rospy.Subscriber( - self.get_topic_prefix() + "/vehicle_control_cmd_manual", + self.manual_control_subscriber = self.create_subscriber( CarlaEgoVehicleControl, + self.get_topic_prefix() + "/vehicle_control_cmd_manual", lambda data: self.control_command_updated(data, manual_override=True)) - self.control_override_subscriber = rospy.Subscriber( + self.control_override_subscriber = self.create_subscriber( + Bool, self.get_topic_prefix() + "/vehicle_control_manual_override", - Bool, self.control_command_override) + self.control_command_override) - self.enable_autopilot_subscriber = rospy.Subscriber( - self.get_topic_prefix() + "/enable_autopilot", - Bool, self.enable_autopilot_updated) + self.enable_autopilot_subscriber = self.create_subscriber( + Bool, + self.get_topic_prefix() + "/enable_autopilot", self.enable_autopilot_updated) - self.twist_control_subscriber = rospy.Subscriber( - self.get_topic_prefix() + "/twist_cmd", - Twist, self.twist_command_updated) + self.twist_control_subscriber = self.create_subscriber( + Twist, + self.get_topic_prefix() + "/twist_cmd", self.twist_command_updated) def get_marker_color(self): """ @@ -97,8 +94,7 @@ def send_vehicle_msgs(self): :return: """ - vehicle_status = CarlaEgoVehicleStatus( - header=self.get_msg_header("map")) + vehicle_status = CarlaEgoVehicleStatus(header=self.get_msg_header("map")) vehicle_status.velocity = self.get_vehicle_speed_abs(self.carla_actor) vehicle_status.acceleration.linear = transforms.carla_vector_to_ros_vector_rotated( self.carla_actor.get_acceleration(), @@ -132,8 +128,8 @@ def send_vehicle_msgs(self): wheel_info.max_handbrake_torque = wheel.max_handbrake_torque wheel_info.position.x = (wheel.position.x/100.0) - \ self.carla_actor.get_transform().location.x - wheel_info.position.y = -((wheel.position.y/100.0) - - self.carla_actor.get_transform().location.y) + wheel_info.position.y = -( + (wheel.position.y / 100.0) - self.carla_actor.get_transform().location.y) wheel_info.position.z = (wheel.position.z/100.0) - \ self.carla_actor.get_transform().location.z vehicle_info.wheels.append(wheel_info) @@ -169,8 +165,9 @@ def update(self, frame, timestamp): super(EgoVehicle, self).update(frame, timestamp) no_rotation = Transform() no_rotation.rotation.x = 1.0 - self.publish_transform(self.get_ros_transform( - no_rotation, frame_id=str(self.get_id()), child_frame_id=self.get_prefix())) + self.publish_transform( + self.get_ros_transform(no_rotation, frame_id=str(self.get_id()), + child_frame_id=self.get_prefix())) def destroy(self): """ @@ -181,7 +178,7 @@ def destroy(self): :return: """ - rospy.logdebug("Destroy Vehicle(id={})".format(self.get_id())) + self.logdebug("Destroy Vehicle(id={})".format(self.get_id())) self.control_subscriber.unregister() self.control_subscriber = None self.enable_autopilot_subscriber.unregister() @@ -211,7 +208,7 @@ def twist_command_updated(self, twist): linear_velocity.y = -rotated_linear_vector[1] linear_velocity.z = rotated_linear_vector[2] - rospy.logdebug("Set velocity linear: {}, angular: {}".format( + self.logdebug("Set velocity linear: {}, angular: {}".format( linear_velocity, angular_velocity)) self.carla_actor.set_velocity(linear_velocity) self.carla_actor.set_angular_velocity(angular_velocity) @@ -255,7 +252,7 @@ def enable_autopilot_updated(self, enable_auto_pilot): :type enable_auto_pilot: std_msgs.Bool :return: """ - rospy.logdebug("Ego vehicle: Set autopilot to {}".format(enable_auto_pilot.data)) + self.logdebug("Ego vehicle: Set autopilot to {}".format(enable_auto_pilot.data)) self.carla_actor.set_autopilot(enable_auto_pilot.data) @staticmethod diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 3d9abd27..4c21e4c9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -48,6 +48,9 @@ def __init__(self, parent, communication, prefix=None): :param communication: communication-handle :type communication: carla_ros_bridge.communication """ + + super(PseudoActor, self).__init__("pseudo_actor_node") + self.parent = parent if self.parent: self.parent_id = parent.get_id() diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index cdff3cb0..33aee2b2 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -5,6 +5,8 @@ if ROS_VERSION == 1: import rospy + latch_on = True + def ros_timestamp(sec=0, nsec=0, from_sec=False): if from_sec: return rospy.Time.from_sec(sec) @@ -19,13 +21,14 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.unregister() - class QoSProfile(): + def __init__(self, depth=10, durability=None, **kwargs): self.depth = depth self.latch = bool(durability) class QoSProfile(): + def __init__(self, depth=10, durability=None, **kwargs): self.depth = depth if durability is not None and durability is not False: @@ -34,6 +37,7 @@ def __init__(self, depth=10, durability=None, **kwargs): self.latch = False class CompatibleNode(object): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): if rospy_init: rospy.init_node(node_name, anonymous=True) @@ -68,8 +72,7 @@ def logfatal(self, arg): # assymetry in publisher/subscriber method naming due to rclpy having # create_publisher method. - def new_publisher(self, msg_type, topic, - qos_profile=None, callback_group=None): + def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): if qos_profile is None: qos_profile = self.qos_profile if callback_group is None: @@ -77,13 +80,11 @@ def new_publisher(self, msg_type, topic, return rospy.Publisher(topic, msg_type, latch=qos_profile.latch, queue_size=qos_profile.depth) - def create_subscriber(self, msg_type, topic, - callback, qos_profile=None, + def create_subscriber(self, msg_type, topic, callback, qos_profile=None, callback_group=None): if qos_profile is None: qos_profile = self.qos_profile - return rospy.Subscriber(topic, msg_type, - callback, queue_size=qos_profile.depth) + return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) def spin(self, executor=None): rospy.spin() @@ -98,11 +99,13 @@ def shutdown(self): import rclpy from builtin_interfaces.msg import Time + latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL + def ros_timestamp(sec=0, nsec=0, from_sec=False): time = Time() if from_sec: time.sec = int(sec) - time.nanosec = int((sec - int(sec)) * 1000_000_000) + time.nanosec = int((sec - int(sec)) * 1000000000) else: time.sec = int(sec) time.nanosec = int(nsec) @@ -117,8 +120,8 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.destroy() - class CompatibleNode(Node): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): super().__init__(node_name, allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True) @@ -135,9 +138,8 @@ def get_param(self, name, alternative_value=None, alternative_name=None): return self.get_parameter(name).value if alternative_name is None: alternative_name = name - return self.get_parameter_or(name, - Parameter(alternative_name, value=alternative_value) - ).value + return self.get_parameter_or(name, Parameter(alternative_name, + value=alternative_value)).value def logdebug(self, text): self.get_logger().debug(text) @@ -160,41 +162,21 @@ def logwarn(self, text): def logfatal(self, text): self.get_logger().fatal(text) - def new_publisher(self, msg_type, topic, - qos_profile=None, callback_group=None): + def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): if qos_profile is None: qos_profile = self.qos_profile if callback_group is None: callback_group = self.callback_group - return self.create_publisher(msg_type, topic, - qos_profile, callback_group=callback_group) + return self.create_publisher(msg_type, topic, qos_profile, + callback_group=callback_group) - def new_publisher(self, msg_type, topic, - qos_profile=None, callback_group=None): - if qos_profile is None: - qos_profile = self.qos_profile - if callback_group is None: - callback_group = self.callback_group - return self.create_publisher(msg_type, topic, - qos_profile, callback_group=callback_group) - - def new_publisher(self, msg_type, topic, - qos_profile=None, callback_group=None): - if qos_profile is None: - qos_profile = self.qos_profile - if callback_group is None: - callback_group = self.callback_group - return self.create_publisher(msg_type, topic, - qos_profile, callback_group=callback_group) - - def create_subscriber(self, msg_type, topic, - callback, qos_profile=None, callback_group=None): + def create_subscriber(self, msg_type, topic, callback, qos_profile=None, + callback_group=None): if qos_profile is None: qos_profile = self.qos_profile if callback_group is None: callback_group = self.callback_group - return self.create_subscription(msg_type, topic, - callback, qos_profile, + return self.create_subscription(msg_type, topic, callback, qos_profile, callback_group=callback_group) def spin(self, executor=None): @@ -204,8 +186,7 @@ def shutdown(self): rclpy.shutdown() else: - raise NotImplementedError('Make sure you have valid ' + - 'ROS_VERSION env variable') + raise NotImplementedError('Make sure you have valid ' + 'ROS_VERSION env variable') def main(): From f58a84076b1f9aab28e9735653dc9b3008ee8af0 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 16:59:22 +0200 Subject: [PATCH 109/627] Remove duplicated methods, Directly use qos profile --- .../ros_compatibility/ros_compatible_node.py | 24 +++---------------- 1 file changed, 3 insertions(+), 21 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 33aee2b2..b0140bec 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -21,12 +21,6 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.unregister() - class QoSProfile(): - - def __init__(self, depth=10, durability=None, **kwargs): - self.depth = depth - self.latch = bool(durability) - class QoSProfile(): def __init__(self, depth=10, durability=None, **kwargs): @@ -58,12 +52,6 @@ def loginfo(self, text): def logwarn(self, text): rospy.logwarn(text) - def logwarn(self, text): - rospy.logwarn(text) - - def logwarn(self, text): - rospy.logwarn(text) - def logerr(self, text): rospy.logerr(text) @@ -74,7 +62,7 @@ def logfatal(self, arg): # create_publisher method. def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): if qos_profile is None: - qos_profile = self.qos_profile + qos_profile = QoSProfile(depth=10, durability=False) if callback_group is None: callback_group = self.callback_group return rospy.Publisher(topic, msg_type, latch=qos_profile.latch, @@ -83,14 +71,14 @@ def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): def create_subscriber(self, msg_type, topic, callback, qos_profile=None, callback_group=None): if qos_profile is None: - qos_profile = self.qos_profile + qos_profile = QoSProfile(depth=10, durability=False) return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) def spin(self, executor=None): rospy.spin() def shutdown(self): - pass + rospy.signal_shutdown("") elif ROS_VERSION == 2: from rclpy.node import Node @@ -153,12 +141,6 @@ def logwarn(self, text): def logerr(self, text): self.get_logger().error(text) - def logwarn(self, text): - self.get_logger().warn(text) - - def logwarn(self, text): - self.get_logger().warn(text) - def logfatal(self, text): self.get_logger().fatal(text) From fb5f432306dbd7ae282b76cc4d8f6244c49def86 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:05:14 +0200 Subject: [PATCH 110/627] Add latch_on --- .../src/carla_manual_control/carla_manual_control.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index e7dfed63..20827014 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -34,6 +34,8 @@ ROS_VERSION = int(os.environ['ROS_VERSION']) +latch_on = None + if ROS_VERSION == 1: import rospy from tf import LookupException @@ -42,6 +44,8 @@ import tf from ros_compatibility import CompatibleNode, QoSProfile + latch_on = True + elif ROS_VERSION == 2: # TODO: Optimise ros2 imports import rclpy @@ -54,7 +58,7 @@ from tf2_ros import ConnectivityException from tf2_ros import ExtrapolationException import tf2_ros - from rclpy.qos import QoSProfile + from rclpy.qos import QoSProfile, QoSDurabilityPolicy from threading import Thread, Lock, Event # from builtin_interfaces.msg import Time from rosgraph_msgs.msg import Clock @@ -62,6 +66,8 @@ sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') from ros_compatible_node import CompatibleNode + latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL + from std_msgs.msg import Bool from sensor_msgs.msg import NavSatFix from sensor_msgs.msg import Image From d19cfdc71341ad2c83f927bb0e93fa147b9b28ed Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:05:51 +0200 Subject: [PATCH 111/627] Uncomment time import --- .../src/carla_manual_control/carla_manual_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 20827014..adc6c301 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -60,7 +60,7 @@ import tf2_ros from rclpy.qos import QoSProfile, QoSDurabilityPolicy from threading import Thread, Lock, Event - # from builtin_interfaces.msg import Time + from builtin_interfaces.msg import Time from rosgraph_msgs.msg import Clock sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') From 51fdd8757c835cb8d4dcddbdce082b82da15bb69 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:06:09 +0200 Subject: [PATCH 112/627] Add sys import --- .../src/carla_manual_control/carla_manual_control.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index adc6c301..34ee7efa 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -62,8 +62,9 @@ from threading import Thread, Lock, Event from builtin_interfaces.msg import Time from rosgraph_msgs.msg import Clock - - sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + import sys + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') from ros_compatible_node import CompatibleNode latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL From ec294d262a4944cae091bb89279cb57c5765b329 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:06:30 +0200 Subject: [PATCH 113/627] Remove .node suffix from hud world controller nodes --- .../src/carla_manual_control/carla_manual_control.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 34ee7efa..9f1ec994 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -725,9 +725,9 @@ def main(args=None): if ROS_VERSION == 2: executer = rclpy.executors.MultiThreadedExecutor(num_threads=12) executer.add_node(hud.tf_listener_node) - executer.add_node(hud.node) - executer.add_node(world.node) - executer.add_node(controller.node) + executer.add_node(hud) + executer.add_node(world) + executer.add_node(controller) thread = Thread(target=run, args=(executer,)) thread.start() From 0226b97a395845ff78e14c4fb5c6d92c0804b1fd Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:06:45 +0200 Subject: [PATCH 114/627] Auto formatting --- .../carla_manual_control.py | 114 +++++++++--------- 1 file changed, 55 insertions(+), 59 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 9f1ec994..f9fdcc4c 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -105,7 +105,6 @@ except ImportError: raise RuntimeError('cannot import pygame, make sure pygame package is installed') - # ============================================================================== # -- World --------------------------------------------------------------------- # ============================================================================== @@ -125,26 +124,25 @@ def __init__(self, role_name, hud): if ROS_VERSION == 2: self.callback_group = ReentrantCallbackGroup() - self.image_subscriber = self.create_subscriber(Image, - "/carla/{}/camera/rgb/view/image_color".format(self.role_name), - self.on_view_image) + self.image_subscriber = self.create_subscriber( + Image, "/carla/{}/camera/rgb/view/image_color".format(self.role_name), + self.on_view_image) - self.collision_subscriber = self.create_subscriber(CarlaCollisionEvent, - "/carla/{}/collision".format(self.role_name), - self.on_collision) + self.collision_subscriber = self.create_subscriber( + CarlaCollisionEvent, "/carla/{}/collision".format(self.role_name), self.on_collision) - self.lane_invasion_subscriber = self.create_subscriber(CarlaLaneInvasionEvent, - "/carla/{}/lane_invasion".format(self.role_name), - self.on_lane_invasion) + self.lane_invasion_subscriber = self.create_subscriber( + CarlaLaneInvasionEvent, "/carla/{}/lane_invasion".format(self.role_name), + self.on_lane_invasion) def on_collision(self, data): """ Callback on collision event """ - intensity = math.sqrt(data.normal_impulse.x ** 2 + - data.normal_impulse.y ** 2 + data.normal_impulse.z ** 2) - self.hud.notification('Collision with {} (impulse {})'.format( - data.other_actor_id, intensity)) + intensity = math.sqrt(data.normal_impulse.x**2 + data.normal_impulse.y**2 + + data.normal_impulse.z**2) + self.hud.notification('Collision with {} (impulse {})'.format(data.other_actor_id, + intensity)) def on_lane_invasion(self, data): """ @@ -198,6 +196,7 @@ def destroy(self): # -- KeyboardControl ----------------------------------------------------------- # ============================================================================== + class KeyboardControl(CompatibleNode): """ Handle input events @@ -235,8 +234,7 @@ def __init__(self, role_name, hud): "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), qos_profile=fast_qos) - self.carla_status_subscriber = self.create_subscriber(CarlaStatus, - "/carla/status", + self.carla_status_subscriber = self.create_subscriber(CarlaStatus, "/carla/status", self._on_new_carla_frame) self.set_autopilot(self._autopilot_enabled) @@ -290,8 +288,9 @@ def parse_events(self, clock): self._control.gear = 1 if self._control.reverse else -1 elif event.key == K_m: self._control.manual_gear_shift = not self._control.manual_gear_shift - self.hud.notification('%s Transmission' % ( - 'Manual' if self._control.manual_gear_shift else 'Automatic')) + self.hud.notification( + '%s Transmission' % + ('Manual' if self._control.manual_gear_shift else 'Automatic')) elif self._control.manual_gear_shift and event.key == K_COMMA: self._control.gear = max(-1, self._control.gear - 1) elif self._control.manual_gear_shift and event.key == K_PERIOD: @@ -299,8 +298,8 @@ def parse_events(self, clock): elif event.key == K_p: self._autopilot_enabled = not self._autopilot_enabled self.set_autopilot(self._autopilot_enabled) - self.hud.notification('Autopilot %s' % ( - 'On' if self._autopilot_enabled else 'Off')) + self.hud.notification('Autopilot %s' % + ('On' if self._autopilot_enabled else 'Off')) if not self._autopilot_enabled and self.vehicle_control_manual_override: self._parse_vehicle_keys(pygame.key.get_pressed(), clock.get_time()) self._control.reverse = self._control.gear < 0 @@ -375,40 +374,36 @@ def __init__(self, role_name, width, height): self.time = Time() self.callback_group = ReentrantCallbackGroup() - self.vehicle_status_subscriber = self.create_subscriber(CarlaEgoVehicleStatus, - "/carla/{}/vehicle_status".format(self.role_name), - self.vehicle_status_updated) + self.vehicle_status_subscriber = self.create_subscriber( + CarlaEgoVehicleStatus, "/carla/{}/vehicle_status".format(self.role_name), + self.vehicle_status_updated) - self.vehicle_status_subscriber = self.create_subscriber(CarlaEgoVehicleStatus, - "/carla/{}/vehicle_status".format(self.role_name), - self.vehicle_status_updated) + self.vehicle_status_subscriber = self.create_subscriber( + CarlaEgoVehicleStatus, "/carla/{}/vehicle_status".format(self.role_name), + self.vehicle_status_updated) self.vehicle_info = CarlaEgoVehicleInfo() - self.vehicle_info_subscriber = self.create_subscriber(CarlaEgoVehicleInfo, - "/carla/{}/vehicle_info".format(self.role_name), - self.vehicle_info_updated) + self.vehicle_info_subscriber = self.create_subscriber( + CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(self.role_name), + self.vehicle_info_updated) self.latitude = 0 self.longitude = 0 self.manual_control = False - self.gnss_subscriber = self.create_subscriber(NavSatFix, - "/carla/{}/gnss/gnss1/fix".format(self.role_name), - self.gnss_updated) + self.gnss_subscriber = self.create_subscriber( + NavSatFix, "/carla/{}/gnss/gnss1/fix".format(self.role_name), self.gnss_updated) - self.manual_control_subscriber = self.create_subscriber(Bool, - "/carla/{}/vehicle_control_manual_override".format( - self.role_name), - self.manual_control_override_updated) + self.manual_control_subscriber = self.create_subscriber( + Bool, "/carla/{}/vehicle_control_manual_override".format(self.role_name), + self.manual_control_override_updated) self.carla_status = CarlaStatus() self.start_frame = None - self.status_subscriber = self.create_subscriber(CarlaStatus, - "/carla/status", + self.status_subscriber = self.create_subscriber(CarlaStatus, "/carla/status", self.carla_status_updated) if ROS_VERSION == 2: - self.clock_subscriber = self.create_subscriber(Clock, - "/clock", + self.clock_subscriber = self.create_subscriber(Clock, "/clock", self.clock_status_updated) def __del__(self): @@ -477,8 +472,9 @@ def update_info_text(self): return try: if ROS_VERSION == 1: - (position, quaternion) = self.tf_listener.lookupTransform( - '/map', self.role_name, rospy.Time()) + (position, + quaternion) = self.tf_listener.lookupTransform('/map', self.role_name, + rospy.Time()) _, _, yaw = tf.transformations.euler_from_quaternion(quaternion) yaw = -math.degrees(yaw) x = position[0] @@ -508,23 +504,22 @@ def update_info_text(self): if ROS_VERSION == 1: time = int(rospy.get_rostime().to_sec()) elif ROS_VERSION == 2: - time = float((self.carla_status.frame - self.start_frame) * self.carla_status.fixed_delta_seconds) + time = float((self.carla_status.frame - self.start_frame) * + self.carla_status.fixed_delta_seconds) if self.carla_status.fixed_delta_seconds: fps = 1 / self.carla_status.fixed_delta_seconds self._info_text = [ 'Frame: % 22s' % self.carla_status.frame, - 'Simulation time: % 12s' % datetime.timedelta( - seconds=time), - 'FPS: % 24.1f' % fps, - '', + 'Simulation time: % 12s' % datetime.timedelta(seconds=time), + 'FPS: % 24.1f' % fps, '', 'Vehicle: % 20s' % ' '.join(self.vehicle_info.type.title().split('.')[1:]), 'Speed: % 15.0f km/h' % (3.6 * self.vehicle_status.velocity), u'Heading:% 16.0f\N{DEGREE SIGN} % 2s' % (yaw, heading), 'Location:% 20s' % ('(% 5.1f, % 5.1f)' % (x, y)), 'GNSS:% 24s' % ('(% 2.6f, % 3.6f)' % (self.latitude, self.longitude)), - 'Height: % 18.0f m' % z, - ''] + 'Height: % 18.0f m' % z, '' + ] self._info_text += [ ('Throttle:', self.vehicle_status.control.throttle, 0.0, 1.0), ('Steer:', self.vehicle_status.control.steer, -1.0, 1.0), @@ -532,9 +527,11 @@ def update_info_text(self): ('Reverse:', self.vehicle_status.control.reverse), ('Hand brake:', self.vehicle_status.control.hand_brake), ('Manual:', self.vehicle_status.control.manual_gear_shift), - 'Gear: %s' % {-1: 'R', 0: 'N'}.get(self.vehicle_status.control.gear, - self.vehicle_status.control.gear), - ''] + 'Gear: %s' % { + -1: 'R', + 0: 'N' + }.get(self.vehicle_status.control.gear, self.vehicle_status.control.gear), '' + ] self._info_text += [('Manual ctrl:', self.manual_control)] if self.carla_status.synchronous_mode: self._info_text += [('Sync mode running:', self.carla_status.synchronous_mode_running)] @@ -574,8 +571,8 @@ def render(self, display): break if isinstance(item, list): if len(item) > 1: - points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) - for x, y in enumerate(item)] + points = [(x + 8, v_offset + 8 + (1.0 - y) * 30) for x, y in enumerate(item) + ] pygame.draw.lines(display, (255, 136, 0), False, points, 2) item = None v_offset += 18 @@ -588,8 +585,8 @@ def render(self, display): pygame.draw.rect(display, (255, 255, 255), rect_border, 1) f = (item[1] - item[2]) / (item[3] - item[2]) if item[2] < 0.0: - rect = pygame.Rect( - (bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6)) + rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), + (6, 6)) else: f = 0.0 rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6)) @@ -713,9 +710,8 @@ def main(args=None): pygame.display.set_caption("CARLA ROS manual control") world = None try: - display = pygame.display.set_mode( - (resolution['width'], resolution['height']), - pygame.HWSURFACE | pygame.DOUBLEBUF) + display = pygame.display.set_mode((resolution['width'], resolution['height']), + pygame.HWSURFACE | pygame.DOUBLEBUF) hud = HUD(role_name, resolution['width'], resolution['height']) world = World(role_name, hud) From e94b48b22abd54c88f72e8c35e5e66c3e680ad58 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:07:00 +0200 Subject: [PATCH 115/627] Change package dir --- carla_manual_control/setup.py | 15 +++++---------- 1 file changed, 5 insertions(+), 10 deletions(-) diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index b2dd051f..bb0b9d96 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -8,10 +8,7 @@ from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup - d = generate_distutils_setup( - packages=['carla_manual_control'], - package_dir={'': 'src'} - ) + d = generate_distutils_setup(packages=['carla_manual_control'], package_dir={'': 'src'}) setup(**d) @@ -22,10 +19,9 @@ setup( name=package_name, version='0.0.0', - packages=['src/' + package_name], + packages=[package_name], data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ], install_requires=['setuptools'], @@ -36,8 +32,7 @@ license='MIT', tests_require=['pytest'], entry_points={ - 'console_scripts': [ - 'manual_control = carla_manual_control.carla_manual_control:main' - ], + 'console_scripts': ['manual_control = carla_manual_control.carla_manual_control:main'], }, + package_dir={'': 'src'}, ) From 6238ca94b0e54a08f318f49f4f80bf67f360b86c Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:07:55 +0200 Subject: [PATCH 116/627] Remove redundant line --- carla_ros_bridge/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 875141e6..0f15b7dd 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -19,7 +19,6 @@ tf tf2 rviz - cv_bridge geometry_msgs std_msgs rosbag_storage From 09a8f04180549e4796bbb01adf7f0d94a5d11d6d Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:08:45 +0200 Subject: [PATCH 117/627] Auto formatting --- carla_ros_bridge/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 0f15b7dd..fadbc555 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -31,7 +31,7 @@ carla_msgs carla_ego_vehicle carla_manual_control - + catkin ament_python From 7eccfea13ce85bc7db1a064a02a2a335eace7487 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:09:02 +0200 Subject: [PATCH 118/627] Change package dir --- carla_ros_bridge/setup.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index e0b1e779..11801552 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -20,7 +20,7 @@ setup( name=package_name, version='0.0.0', - packages=['src/' + package_name], + packages=[package_name], data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ('share/' + package_name + '/config', ['config/settings.yaml']), @@ -33,6 +33,7 @@ license='MIT', tests_require=['pytest'], entry_points={ - 'console_scripts': ['bridge = src.carla_ros_bridge.bridge:main'], + 'console_scripts': ['bridge = carla_ros_bridge.bridge:main'], }, + package_dir={'': 'src'}, ) From 0b4fd76b794d12d33bc7346833bb76aef1237f9d Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:12:13 +0200 Subject: [PATCH 119/627] Fix compatibility issues --- .../src/carla_ros_bridge/actor.py | 4 +- .../src/carla_ros_bridge/bridge.py | 53 ++++----- .../src/carla_ros_bridge/camera.py | 108 ++++++++---------- .../src/carla_ros_bridge/communication.py | 1 - .../src/carla_ros_bridge/ego_vehicle.py | 35 ++++-- carla_ros_bridge/src/carla_ros_bridge/imu.py | 27 +++-- .../src/carla_ros_bridge/lidar.py | 32 +++--- .../src/carla_ros_bridge/object_sensor.py | 6 +- .../src/carla_ros_bridge/pseudo_actor.py | 14 ++- .../src/carla_ros_bridge/sensor.py | 25 +++- .../src/carla_ros_bridge/spectator.py | 2 +- .../src/carla_ros_bridge/traffic.py | 4 +- .../carla_ros_bridge/traffic_lights_sensor.py | 4 +- .../carla_ros_bridge/traffic_participant.py | 4 +- .../src/carla_ros_bridge/vehicle.py | 2 +- .../src/carla_ros_bridge/walker.py | 2 +- .../src/carla_ros_bridge/world_info.py | 2 +- 17 files changed, 174 insertions(+), 151 deletions(-) mode change 100644 => 100755 carla_ros_bridge/src/carla_ros_bridge/bridge.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 5807f016..1b0b8fc3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -15,8 +15,8 @@ from std_msgs.msg import ColorRGBA from visualization_msgs.msg import Marker -from src.carla_ros_bridge.pseudo_actor import PseudoActor -import src.carla_ros_bridge.transforms as trans +from carla_ros_bridge.pseudo_actor import PseudoActor +import carla_ros_bridge.transforms as trans class Actor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py old mode 100644 new mode 100755 index 29984ca9..ddcfd1ce --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -22,27 +22,27 @@ import carla -from src.carla_ros_bridge.actor import Actor -from src.carla_ros_bridge.communication import Communication -from src.carla_ros_bridge.sensor import Sensor - -from src.carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher -from src.carla_ros_bridge.world_info import WorldInfo -from src.carla_ros_bridge.spectator import Spectator -from src.carla_ros_bridge.traffic import Traffic, TrafficLight -from src.carla_ros_bridge.vehicle import Vehicle -from src.carla_ros_bridge.lidar import Lidar -from src.carla_ros_bridge.radar import Radar -from src.carla_ros_bridge.gnss import Gnss -from src.carla_ros_bridge.imu import ImuSensor -from src.carla_ros_bridge.ego_vehicle import EgoVehicle -from src.carla_ros_bridge.collision_sensor import CollisionSensor -from src.carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -from src.carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera -from src.carla_ros_bridge.object_sensor import ObjectSensor -from src.carla_ros_bridge.walker import Walker -from src.carla_ros_bridge.debug_helper import DebugHelper -from src.carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor +from carla_ros_bridge.actor import Actor +from carla_ros_bridge.communication import Communication +from carla_ros_bridge.sensor import Sensor + +from carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher +from carla_ros_bridge.world_info import WorldInfo +from carla_ros_bridge.spectator import Spectator +from carla_ros_bridge.traffic import Traffic, TrafficLight +from carla_ros_bridge.vehicle import Vehicle +# from carla_ros_bridge.lidar import Lidar +# from carla_ros_bridge.radar import Radar +from carla_ros_bridge.gnss import Gnss +from carla_ros_bridge.imu import ImuSensor +from carla_ros_bridge.ego_vehicle import EgoVehicle +from carla_ros_bridge.collision_sensor import CollisionSensor +from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor +from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera +from carla_ros_bridge.object_sensor import ObjectSensor +from carla_ros_bridge.walker import Walker +from carla_ros_bridge.debug_helper import DebugHelper +from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters import os @@ -82,7 +82,7 @@ def __init__(self, rospy_init=True): :param params: dict of parameters, see settings.yaml :type params: dict """ - super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init) + super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) def initialize_bridge(self, carla_world, params): self.parameters = params @@ -149,8 +149,8 @@ def initialize_bridge(self, carla_world, params): self.on_tick_id = self.carla_world.on_tick(self._carla_time_tick) self.carla_weather_subscriber = \ - self.create_subscriber("/carla/weather_control", - CarlaWeatherParameters, self.on_weather_changed) + self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", + self.on_weather_changed) # add world info self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, communication=self.comm)) @@ -171,7 +171,7 @@ def destroy(self): :return: """ - self.signal_shutdown("") + self.shutdown("") self.debug_helper.destroy() self.shutdown.set() self.carla_weather_subscriber.unregister() @@ -529,7 +529,8 @@ def main(): parameters = {} if ROS_VERSION == 1: carla_bridge = CarlaRosBridge() - rospy.init_node('carla_ros_bridge', anonymous=True) + # rospy.init_node('carla_ros_bridge', anonymous=True) + parameters = rospy.get_param('carla') elif ROS_VERSION == 2: rclpy.init(args=None) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index f44cc6ab..51b1349e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -18,7 +18,7 @@ from ros_compatibility import * elif ROS_VERSION == 2: import rclpy - import cv2 + # import cv2 import transformations # TODO: import ros_compatibilty else: @@ -38,7 +38,6 @@ class Camera(Sensor): - """ Sensor implementation details for cameras """ @@ -61,17 +60,15 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= """ if not prefix: prefix = 'camera' - super(Camera, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - prefix=prefix) + super(Camera, + self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + synchronous_mode=synchronous_mode, prefix=prefix) if self.__class__.__name__ == "Camera": self.logwarn("Created Unsupported Camera Actor" "(id={}, parent_id={}, type={}, attributes={})".format( - self.get_id(), self.get_parent_id(), - self.carla_actor.type_id, self.carla_actor.attributes)) + self.get_id(), self.get_parent_id(), self.carla_actor.type_id, + self.carla_actor.attributes)) else: self._build_camera_info() @@ -83,7 +80,7 @@ def _build_camera_info(self): """ camera_info = CameraInfo() # store info without header - camera_info.header = None + # camera_info.header = None # TODO uncomment for ros 1 (?) camera_info.width = int(self.carla_actor.attributes['image_size_x']) camera_info.height = int(self.carla_actor.attributes['image_size_y']) camera_info.distortion_model = 'plumb_bob' @@ -92,10 +89,16 @@ def _build_camera_info(self): fx = camera_info.width / ( 2.0 * math.tan(float(self.carla_actor.attributes['fov']) * math.pi / 360.0)) fy = fx - camera_info.K = [fx, 0, cx, 0, fy, cy, 0, 0, 1] - camera_info.D = [0, 0, 0, 0, 0] - camera_info.R = [1.0, 0, 0, 0, 1.0, 0, 0, 0, 1.0] - camera_info.P = [fx, 0, cx, 0, 0, fy, cy, 0, 0, 0, 1.0, 0] + if ROS_VERSION == 1: + camera_info.K = [fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0] + camera_info.D = [0.0, 0.0, 0.0, 0.0, 0.0] + camera_info.R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] + camera_info.P = [fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0] + elif ROS_VERSION == 2: + camera_info.k = [fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0] + camera_info.d = [0.0, 0.0, 0.0, 0.0, 0.0] + camera_info.r = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] + camera_info.p = [fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0] self._camera_info = camera_info # pylint: disable=arguments-differ @@ -108,11 +111,10 @@ def sensor_data_updated(self, carla_image): :type carla_image: carla.Image """ if ((carla_image.height != self._camera_info.height) or - (carla_image.width != self._camera_info.width)): - self.logerr( - "Camera{} received image not matching configuration".format(self.get_prefix())) - image_data_array, encoding = self.get_carla_image_data_array( - carla_image=carla_image) + (carla_image.width != self._camera_info.width)): + self.logerr("Camera{} received image not matching configuration".format( + self.get_prefix())) + image_data_array, encoding = self.get_carla_image_data_array(carla_image=carla_image) img_msg = Camera.cv_bridge.cv2_to_imgmsg(image_data_array, encoding=encoding) # the camera data is in respect to the camera's own frame img_msg.header = self.get_msg_header() @@ -121,8 +123,7 @@ def sensor_data_updated(self, carla_image): cam_info.header = img_msg.header self.publish_message(self.get_topic_prefix() + '/camera_info', cam_info) - self.publish_message( - self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) + self.publish_message(self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ @@ -137,15 +138,11 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): tf_msg = super(Camera, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation quat = [rotation.x, rotation.y, rotation.z, rotation.w] - quat_swap = transformations.quaternion_from_matrix( - [[0, 0, 1, 0], - [-1, 0, 0, 0], - [0, -1, 0, 0], - [0, 0, 0, 1]]) + quat_swap = transformations.quaternion_from_matrix([[0, 0, 1, 0], [-1, 0, 0, 0], + [0, -1, 0, 0], [0, 0, 0, 1]]) quat = transformations.quaternion_multiply(quat, quat_swap) - tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion( - quat) + tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion(quat) return tf_msg @abstractmethod @@ -159,8 +156,7 @@ def get_carla_image_data_array(self, carla_image): :return tuple (numpy data array containing the image information, encoding) :rtype tuple(numpy.ndarray, string) """ - raise NotImplementedError( - "This function has to be re-implemented by derived classes") + raise NotImplementedError("This function has to be re-implemented by derived classes") @abstractmethod def get_image_topic_name(self): @@ -170,12 +166,10 @@ def get_image_topic_name(self): :return image topic name :rtype string """ - raise NotImplementedError( - "This function has to be re-implemented by derived classes") + raise NotImplementedError("This function has to be re-implemented by derived classes") class RgbCamera(Camera): - """ Camera implementation details for rgb camera """ @@ -193,12 +187,10 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(RgbCamera, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - prefix='camera/rgb/' + - carla_actor.attributes.get('role_name')) + super(RgbCamera, + self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + synchronous_mode=synchronous_mode, + prefix='camera/rgb/' + carla_actor.attributes.get('role_name')) def get_carla_image_data_array(self, carla_image): """ @@ -213,9 +205,8 @@ def get_carla_image_data_array(self, carla_image): :rtype tuple(numpy.ndarray, string) """ - carla_image_data_array = numpy.ndarray( - shape=(carla_image.height, carla_image.width, 4), - dtype=numpy.uint8, buffer=carla_image.raw_data) + carla_image_data_array = numpy.ndarray(shape=(carla_image.height, carla_image.width, 4), + dtype=numpy.uint8, buffer=carla_image.raw_data) return carla_image_data_array, 'bgra8' @@ -230,7 +221,6 @@ def get_image_topic_name(self): class DepthCamera(Camera): - """ Camera implementation details for depth camera """ @@ -248,12 +238,10 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(DepthCamera, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - prefix='camera/depth/' + - carla_actor.attributes.get('role_name')) + super(DepthCamera, + self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + synchronous_mode=synchronous_mode, + prefix='camera/depth/' + carla_actor.attributes.get('role_name')) def get_carla_image_data_array(self, carla_image): """ @@ -282,9 +270,8 @@ def get_carla_image_data_array(self, carla_image): # shape=(carla_image.height, carla_image.width, 1), # dtype=numpy.float32, buffer=carla_image.raw_data) # - bgra_image = numpy.ndarray( - shape=(carla_image.height, carla_image.width, 4), - dtype=numpy.uint8, buffer=carla_image.raw_data) + bgra_image = numpy.ndarray(shape=(carla_image.height, carla_image.width, 4), + dtype=numpy.uint8, buffer=carla_image.raw_data) # Apply (R + G * 256 + B * 256 * 256) / (256**3 - 1) * 1000 # according to the documentation: @@ -307,7 +294,6 @@ def get_image_topic_name(self): class SemanticSegmentationCamera(Camera): - """ Camera implementation details for segmentation camera """ @@ -325,13 +311,10 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super( - SemanticSegmentationCamera, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - prefix='camera/semantic_segmentation/' + - carla_actor.attributes.get('role_name')) + super(SemanticSegmentationCamera, self).__init__( + carla_actor=carla_actor, parent=parent, communication=communication, + synchronous_mode=synchronous_mode, + prefix='camera/semantic_segmentation/' + carla_actor.attributes.get('role_name')) def get_carla_image_data_array(self, carla_image): """ @@ -348,9 +331,8 @@ def get_carla_image_data_array(self, carla_image): """ carla_image.convert(carla.ColorConverter.CityScapesPalette) - carla_image_data_array = numpy.ndarray( - shape=(carla_image.height, carla_image.width, 4), - dtype=numpy.uint8, buffer=carla_image.raw_data) + carla_image_data_array = numpy.ndarray(shape=(carla_image.height, carla_image.width, 4), + dtype=numpy.uint8, buffer=carla_image.raw_data) return carla_image_data_array, 'bgra8' def get_image_topic_name(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 636f9e5c..f5287e55 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -36,7 +36,6 @@ from rosgraph_msgs.msg import Clock from tf2_msgs.msg import TFMessage -from builtin_interfaces.msg import Time class Communication(CompatibleNode): diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index e1e73d15..137fc04f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -12,6 +12,22 @@ import math import numpy +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + from ros_compatibility import CompatibleNode +elif ROS_VERSION == 2: + import sys + print(os.getcwd()) + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + from ament_index_python.packages import get_package_share_directory + from ros_compatible_node import CompatibleNode +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") + from std_msgs.msg import ColorRGBA from std_msgs.msg import Bool from geometry_msgs.msg import Twist, Transform @@ -19,14 +35,14 @@ from carla import VehicleControl from carla import Vector3D -from src.carla_ros_bridge.vehicle import Vehicle -import src.carla_ros_bridge.transforms as transforms +from carla_ros_bridge.vehicle import Vehicle +import carla_ros_bridge.transforms as transforms from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel,\ CarlaEgoVehicleControl, CarlaEgoVehicleStatus -class EgoVehicle(Vehicle): +class EgoVehicle(Vehicle, CompatibleNode): """ Vehicle implementation details for the ego vehicle """ @@ -42,9 +58,10 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c :param communication: communication-handle :type communication: carla_ros_bridge.communication """ - super(EgoVehicle, - self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, - prefix=carla_actor.attributes.get('role_name')) + Vehicle.__init__(self, carla_actor=carla_actor, parent=parent, communication=communication, + prefix=carla_actor.attributes.get('role_name')) + if ROS_VERSION == 2: + CompatibleNode.__init__(self, "ego_vehicle") self.vehicle_info_published = False self.vehicle_control_override = False @@ -83,9 +100,9 @@ def get_marker_color(self): :rtpye : std_msgs.msg.ColorRGBA """ color = ColorRGBA() - color.r = 0 - color.g = 255 - color.b = 0 + color.r = 0.0 + color.g = 255.0 + color.b = 0.0 return color def send_vehicle_msgs(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index ddd6b762..88d524eb 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -8,7 +8,13 @@ """ import math -import tf +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + from tf.transformations import quaternion_from_euler +elif ROS_VERSION == 2: + from transformations.transformations import quaternion_from_euler from sensor_msgs.msg import Imu @@ -17,7 +23,6 @@ class ImuSensor(Sensor): - """ Actor implementation details for imu sensor """ @@ -35,11 +40,10 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(ImuSensor, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - prefix="imu/" + carla_actor.attributes.get('role_name')) + super(ImuSensor, + self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + synchronous_mode=synchronous_mode, + prefix="imu/" + carla_actor.attributes.get('role_name')) # pylint: disable=arguments-differ def sensor_data_updated(self, carla_imu_measurement): @@ -62,9 +66,8 @@ def sensor_data_updated(self, carla_imu_measurement): imu_rotation = carla_imu_measurement.transform.rotation - quat = tf.transformations.quaternion_from_euler(math.radians(imu_rotation.roll), - math.radians(imu_rotation.pitch), - math.radians(imu_rotation.yaw)) + quat = quaternion_from_euler(math.radians(imu_rotation.roll), + math.radians(imu_rotation.pitch), + math.radians(imu_rotation.yaw)) imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) - self.publish_message( - self.get_topic_prefix(), imu_msg) + self.publish_message(self.get_topic_prefix(), imu_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 68dcbba7..48ab5488 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -12,7 +12,13 @@ import numpy -import tf +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + from tf.transformations import euler_from_quaternion, quaternion_from_euler +elif ROS_VERSION == 2: + from transformations.transformations import euler_from_quaternion, quaternion_from_euler from sensor_msgs.point_cloud2 import create_cloud_xyz32 @@ -21,7 +27,6 @@ class Lidar(Sensor): - """ Actor implementation details for lidars """ @@ -37,10 +42,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param communication: communication-handle :type communication: carla_ros_bridge.communication """ - super(Lidar, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, + super(Lidar, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, synchronous_mode=synchronous_mode, prefix='lidar/' + carla_actor.attributes.get('role_name')) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): @@ -58,12 +61,10 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): rotation = tf_msg.transform.rotation quat = [rotation.x, rotation.y, rotation.z, rotation.w] - dummy_roll, dummy_pitch, yaw = tf.transformations.euler_from_quaternion( - quat) + dummy_roll, dummy_pitch, yaw = euler_from_quaternion(quat) # set roll and pitch to zero - quat = tf.transformations.quaternion_from_euler(0, 0, yaw) - tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion( - quat) + quat = quaternion_from_euler(0, 0, yaw) + tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion(quat) return tf_msg # pylint: disable=arguments-differ @@ -76,10 +77,8 @@ def sensor_data_updated(self, carla_lidar_measurement): """ header = self.get_msg_header() - lidar_data = numpy.frombuffer( - carla_lidar_measurement.raw_data, dtype=numpy.float32) - lidar_data = numpy.reshape( - lidar_data, (int(lidar_data.shape[0] / 3), 3)) + lidar_data = numpy.frombuffer(carla_lidar_measurement.raw_data, dtype=numpy.float32) + lidar_data = numpy.reshape(lidar_data, (int(lidar_data.shape[0] / 3), 3)) # we take the oposite of y axis # (as lidar point are express in left handed coordinate system, and ros need right handed) # we need a copy here, because the data are read only in carla numpy @@ -88,5 +87,4 @@ def sensor_data_updated(self, carla_lidar_measurement): # we also need to permute x and y lidar_data = lidar_data[..., [1, 0, 2]] point_cloud_msg = create_cloud_xyz32(header, lidar_data) - self.publish_message( - self.get_topic_prefix() + "/point_cloud", point_cloud_msg) + self.publish_message(self.get_topic_prefix() + "/point_cloud", point_cloud_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index b3dac308..2a62b3d2 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -10,9 +10,9 @@ """ from derived_object_msgs.msg import ObjectArray -from src.carla_ros_bridge.vehicle import Vehicle -from src.carla_ros_bridge.walker import Walker -from src.carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.vehicle import Vehicle +from carla_ros_bridge.walker import Walker +from carla_ros_bridge.pseudo_actor import PseudoActor class ObjectSensor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 4c21e4c9..be23d5da 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -24,9 +24,9 @@ # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - import rclpy from rclpy.node import Node from rclpy import executors + from rclpy.time import Time from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode else: @@ -49,7 +49,7 @@ def __init__(self, parent, communication, prefix=None): :type communication: carla_ros_bridge.communication """ - super(PseudoActor, self).__init__("pseudo_actor_node") + # super(PseudoActor, self).__init__("pseudo_actor_node") self.parent = parent if self.parent: @@ -97,7 +97,15 @@ def get_msg_header(self, frame_id=None, timestamp=None): if ROS_VERSION == 1: header.stamp = rospy.Time.from_sec(timestamp) elif ROS_VERSION == 2: - header.stamp = rclpy.Time.from_sec(timestamp) + + def ros_timestamp(sec=0): + from builtin_interfaces.msg import Time + time = Time() + time.sec = int(sec) + time.nanosec = int((sec - int(sec)) * 1000000000) + return time + + header.stamp = ros_timestamp(timestamp) else: raise NotImplementedError( "Make sure you have a valid ROS_VERSION env variable set.") diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 221853fd..61b448c1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -16,16 +16,29 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + if ROS_VERSION == 1: import rospy + from ros_compatibility import CompatibleNode elif ROS_VERSION == 2: + import sys + print(os.getcwd()) + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') import rclpy + from rclpy.node import Node + from rclpy import executors + from ament_index_python.packages import get_package_share_directory + from ros_compatible_node import CompatibleNode +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -from src.carla_ros_bridge.actor import Actor -import src.carla_ros_bridge.transforms as trans +from carla_ros_bridge.actor import Actor +import carla_ros_bridge.transforms as trans -class Sensor(Actor): +class Sensor(Actor, CompatibleNode): """ Actor implementation details for sensors """ @@ -57,8 +70,10 @@ def __init__( """ if prefix is None: prefix = 'sensor' - super(Sensor, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, prefix=prefix) + Actor.__init__(self, carla_actor=carla_actor, parent=parent, communication=communication, + prefix=prefix) + if ROS_VERSION == 2: + CompatibleNode.__init__(self, "sensor") self.synchronous_mode = synchronous_mode self.queue = queue.Queue() diff --git a/carla_ros_bridge/src/carla_ros_bridge/spectator.py b/carla_ros_bridge/src/carla_ros_bridge/spectator.py index f35e17bc..f2be7019 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/spectator.py +++ b/carla_ros_bridge/src/carla_ros_bridge/spectator.py @@ -10,7 +10,7 @@ Classes to handle Carla spectator """ -from src.carla_ros_bridge.actor import Actor +from carla_ros_bridge.actor import Actor class Spectator(Actor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 90e1ef70..1bfefcd9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -10,8 +10,8 @@ Classes to handle Carla traffic objects """ -from src.carla_ros_bridge.actor import Actor -import src.carla_ros_bridge.transforms as trans +from carla_ros_bridge.actor import Actor +import carla_ros_bridge.transforms as trans from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo from carla import TrafficLightState diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index d8d760dd..1850ed76 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -11,8 +11,8 @@ from carla_msgs.msg import CarlaTrafficLightStatusList,\ CarlaTrafficLightInfoList -from src.carla_ros_bridge.traffic import TrafficLight -from src.carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.traffic import TrafficLight +from carla_ros_bridge.pseudo_actor import PseudoActor class TrafficLightsSensor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 07518b98..c03f1ec6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -14,7 +14,7 @@ from nav_msgs.msg import Odometry from shape_msgs.msg import SolidPrimitive -from src.carla_ros_bridge.actor import Actor +from carla_ros_bridge.actor import Actor class TrafficParticipant(Actor): @@ -97,7 +97,7 @@ def get_object_info(self): if self.get_classification() != Object.CLASSIFICATION_UNKNOWN: obj.object_classified = True obj.classification = self.get_classification() - obj.classification_certainty = 1.0 + obj.classification_certainty = 1 obj.classification_age = self.classification_age return obj diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index ec0fce0a..0bb24721 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -13,7 +13,7 @@ from std_msgs.msg import ColorRGBA from derived_object_msgs.msg import Object -from src.carla_ros_bridge.traffic_participant import TrafficParticipant +from carla_ros_bridge.traffic_participant import TrafficParticipant class Vehicle(TrafficParticipant): diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index ac5cfa6e..5f96d7af 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -12,7 +12,7 @@ from derived_object_msgs.msg import Object -from src.carla_ros_bridge.traffic_participant import TrafficParticipant +from carla_ros_bridge.traffic_participant import TrafficParticipant from carla_msgs.msg import CarlaWalkerControl from carla import WalkerControl diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index 97e86282..0e2ecd39 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -11,7 +11,7 @@ """ from carla_msgs.msg import CarlaWorldInfo -from src.carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.pseudo_actor import PseudoActor class WorldInfo(PseudoActor): From d663b8deb80c51a7ef5d43b4097c930a83ab4f8e Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:12:44 +0200 Subject: [PATCH 120/627] Do not use lidar and radar for now due to compiler and dependency issues --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index ddcfd1ce..50674d7a 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -419,10 +419,10 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m else: actor = Camera(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.lidar"): - actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.other.radar"): - actor = Radar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + # elif carla_actor.type_id.startswith("sensor.lidar"): + # actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + # elif carla_actor.type_id.startswith("sensor.other.radar"): + # actor = Radar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): From 6ac40a930a42ea83f40a06c06641c93a87dc7017 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:13:13 +0200 Subject: [PATCH 121/627] Add ainstein_radar_msgs --- ainstein_radar/.gitignore | 1 + ainstein_radar/LICENSE | 29 +++++ ainstein_radar/README.md | 5 + .../ainstein_radar_msgs/CHANGELOG.rst | 64 +++++++++++ .../ainstein_radar_msgs/CMakeLists.txt | 84 ++++++++++++++ .../ainstein_radar_msgs/msg/RadarAlarm.msg | 5 + .../msg/RadarAlarmArray.msg | 5 + .../msg/RadarAlarmStamped.msg | 7 ++ .../ainstein_radar_msgs/msg/RadarInfo.msg | 106 ++++++++++++++++++ .../ainstein_radar_msgs/msg/RadarTarget.msg | 8 ++ .../msg/RadarTargetArray.msg | 5 + .../msg/RadarTargetStamped.msg | 5 + .../ainstein_radar_msgs/package.xml | 39 +++++++ 13 files changed, 363 insertions(+) create mode 100644 ainstein_radar/.gitignore create mode 100644 ainstein_radar/LICENSE create mode 100644 ainstein_radar/README.md create mode 100644 ainstein_radar/ainstein_radar_msgs/CHANGELOG.rst create mode 100644 ainstein_radar/ainstein_radar_msgs/CMakeLists.txt create mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarAlarm.msg create mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmArray.msg create mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmStamped.msg create mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarInfo.msg create mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarTarget.msg create mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarTargetArray.msg create mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarTargetStamped.msg create mode 100644 ainstein_radar/ainstein_radar_msgs/package.xml diff --git a/ainstein_radar/.gitignore b/ainstein_radar/.gitignore new file mode 100644 index 00000000..4c4c99ba --- /dev/null +++ b/ainstein_radar/.gitignore @@ -0,0 +1 @@ +bagfiles/ \ No newline at end of file diff --git a/ainstein_radar/LICENSE b/ainstein_radar/LICENSE new file mode 100644 index 00000000..51036f7b --- /dev/null +++ b/ainstein_radar/LICENSE @@ -0,0 +1,29 @@ +BSD 3-Clause License + +Copyright (c) 2018-2019, Ainstein AI, Inc. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name of the copyright holder nor the names of its + contributors may be used to endorse or promote products derived from + this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/ainstein_radar/README.md b/ainstein_radar/README.md new file mode 100644 index 00000000..beaef139 --- /dev/null +++ b/ainstein_radar/README.md @@ -0,0 +1,5 @@ +# Overview + +ainstein_radar is a collection of ROS packages containing functionality for interfacing with, filtering, displaying and using data from Ainstein radars for robotics applications. + +For more details on usage, see the corresponding [ROS Wiki Pages](http://wiki.ros.org/ainstein_radar). \ No newline at end of file diff --git a/ainstein_radar/ainstein_radar_msgs/CHANGELOG.rst b/ainstein_radar/ainstein_radar_msgs/CHANGELOG.rst new file mode 100644 index 00000000..33bf8202 --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/CHANGELOG.rst @@ -0,0 +1,64 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package ainstein_radar_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +3.0.1 (2020-02-11) +------------------ + +3.0.0 (2020-02-06) +------------------ + +2.0.2 (2019-11-19) +------------------ + +2.0.1 (2019-11-12) +------------------ + +2.0.0 (2019-11-12) +------------------ +* Update RadarInfo msg, refactor for K79 and add T79 + Updated the RadarInfo message slightly. Also refactored the K79 + interface class to publish the RadarInfo message. + Added publishing the RadarInfo message for T79 as well, needs testing. +* Update RadarInfo message and fix dependencies + Updated the RadarInfo message with new fields fully describing the data + and added comments to explain them. + Also fixed a small dependency in the RViz plugins package for display + of the RadarInfo messages, however this plugin is not complete anyway. +* Contributors: Nick Rotella + +1.1.0 (2019-10-29) +------------------ +* Minor fixes to package XML formatting + Fixed the package XML file formatting and added missing content to + conform to the suggested style guidelines. +* Contributors: Nick Rotella + +1.0.3 (2019-10-03) +------------------ + +1.0.2 (2019-09-25) +------------------ + +1.0.1 (2019-09-24) +------------------ +* Minor, remove unnecessary install target for radar_msgs +* Merge branch 'master' of https://github.com/AinsteinAI/ainstein_radar +* Add ainstein_radar_msgs/RadarInfo msg definition + Added a new message type to ainstein_radar_msgs to store information + about a radar sensor's properties, configuration, etc. Currently + contains physical limits for range, speed and angles. +* Fix radar stamped msg, add nearest target filter + Fixed the RadarTargetStamped message to use the unstamped RadarTarget + message rather than duplicating fields. + Added a nearest target filter which extracts the nearest target (by + range) within set min/max range bounds and optionally low-pass filters + it before publishing as both a RadarTargetStamped and as an array with + one message (called "tracked"). Will remove the array published after + implementing a proper tracked target filter. +* Refactor radar message types, other ainstein_radar subpkgs WILL NOT BUILD + Refactored the message types defined for radars, breaking all other subpkgs + in the ainstein_radar metapkg. Now refactoring all other pkgs to use the + new message definitions. +* Migrate old radar_sensor_msgs pkg to new ainstein_radar_msgs subpkg +* Contributors: Nick Rotella diff --git a/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt b/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt new file mode 100644 index 00000000..6e9d752a --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt @@ -0,0 +1,84 @@ +project(ainstein_radar_msgs) + +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) + +set(CMAKE_CXX_STANDARD 11) + +set(MSG_FILES + RadarInfo.msg + RadarAlarm.msg + RadarAlarmArray.msg + RadarAlarmStamped.msg + RadarTarget.msg + RadarTargetArray.msg + RadarTargetStamped.msg + ) + +if (${ROS_VERSION} EQUAL 1) + cmake_minimum_required(VERSION 3.0.0) + + find_package(catkin REQUIRED COMPONENTS + std_msgs + message_generation + ) + + add_message_files( + DIRECTORY msg + FILES + ${MSG_FILES} + ) + + generate_messages( + DEPENDENCIES + std_msgs + ) + + catkin_package( + CATKIN_DEPENDS message_runtime + ) + + include_directories( + ${catkin_INCLUDE_DIRS} + ) + + install(TARGETS + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + +elseif (${ROS_VERSION} EQUAL 2) + cmake_minimum_required(VERSION 3.5) + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + + find_package(ament_cmake REQUIRED) + find_package(builtin_interfaces REQUIRED) + find_package(std_msgs REQUIRED) + find_package(rosidl_default_generators REQUIRED) + + # Apend "msg/" to each file name + set(TEMP_LIST "") + foreach(MSG_FILE ${MSG_FILES}) + list(APPEND TEMP_LIST "msg/${MSG_FILE}") + endforeach() + set(MSG_FILES ${TEMP_LIST}) + + rosidl_generate_interfaces(${PROJECT_NAME} + ${MSG_FILES} + DEPENDENCIES builtin_interfaces std_msgs + ADD_LINTER_TESTS + ) + + if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + endif() + + ament_export_dependencies(rosidl_default_runtime) + + ament_package() +endif() \ No newline at end of file diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarm.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarm.msg new file mode 100644 index 00000000..7de37504 --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarm.msg @@ -0,0 +1,5 @@ +# This message describes alarms (eg BSD) from a RADAR sensor. + +bool lca_alarm # Lane Change Assist alarm +bool cvw_alarm # Collision (Vehicle?) Warning alarm +bool bsd_alarm # Blind Spot Detection alarm diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmArray.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmArray.msg new file mode 100644 index 00000000..0186fc1a --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmArray.msg @@ -0,0 +1,5 @@ +# This message describes an array of alarms with a timestamp. + +std_msgs/Header header + +RadarAlarm[] alarms diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmStamped.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmStamped.msg new file mode 100644 index 00000000..8782cc67 --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmStamped.msg @@ -0,0 +1,7 @@ +# This message describes alarms (eg BSD) from a RADAR sensor. + +std_msgs/Header header + +bool lca_alarm # Lane Change Assist alarm +bool cvw_alarm # Collision (Vehicle?) Warning alarm +bool bsd_alarm # Blind Spot Detection alarm diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo.msg new file mode 100644 index 00000000..4dfaa443 --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo.msg @@ -0,0 +1,106 @@ +# This message defines meta information for a radar sensor. It should +# be in a radar namespace on topic "radar_info" and accompanied by up +# to three radar topics named: +# +# targets/raw - raw (untracked) radar detections +# targets/tracked - tracked radar detections +# alarms - alarms based on detections, eg BSD +# +# In general, all Ainstein radars output raw detections and may also +# output tracked detections if trackign algorithms are implemented in +# firmware. Tracking from raw data is also available in ROS; see the +# ainstein_radar_filters package for more information. Most radars do +# not output alarms as this is specific to the automotive use case, +# however this message type is retained for the time being for backward +# compatibility. + +####################################################################### +# Data acquisition info # +####################################################################### + +# Time of data acquisition, radar coordinate frame ID +Header header # Header timestamp should be acquisition time of data + # Header frame_id should be radar sensing frame + # origin of frame should be center of sensor + # +x should point radially outwards from the radar + # +y should point to complete a right-handed frame + # +z should point upwards + +####################################################################### +# General sensor properties # +####################################################################### + +# The nominal update rate of the sensor reported in Hz. +float64 update_rate + +# The maximum number of detections (targets) the sensors can report. +uint16 max_num_targets + +####################################################################### +# Physical sensing limits # +####################################################################### +# These are limits imposed by the antenna hardware and/or cutoffs set # +# in the detection processing firmware. They come from sensor data # +# sheets and must be updated with each hardware revision as necessary.# +####################################################################### + +# The minimum and maximum range, in meters, of detections (targets) +# reported by the sensor. +float64 range_min +float64 range_max + +# The minimum and maximum speed, in meters per second, of detections +# (targets) reported by the sensor. +float64 speed_min +float64 speed_max + +# The minimum and maximum azimuth angle, in degrees. +float64 azimuth_min +float64 azimuth_max + +# The minimum and maximum azimuth angle, in degrees. +float64 elevation_min +float64 elevation_max + +####################################################################### +# Physical sensing precision # +####################################################################### +# These are also imposed by the antenna hardware and/or set in the # +# detection processing firmware. They also come from sensor data # +# sheets and must be updated with each hardware revision as necessary.# +####################################################################### + +# Range resolution, in meters. The resolution is defined as the minimum +# distance between two objects which results in distinct detections. +float64 range_resolution + +# Range accuracy, in meters. The accuracy is defined as the precision +# with which range of a detection is reported. +float64 range_accuracy + +# Speed resolution, in meters per second. The resolution is defined as +# the minimum speed difference between two objects which results in +# distinct detections. +float64 speed_resolution + +# Speed accuracy, in meters per second. The accuracy is defined as the +# precision with which speed of a detection is reported. +float64 speed_accuracy + +# Azimuth angle resolution, in degrees. The resolution is defined as +# the minimum azimuth angle between two objects which results in +# distinct detections. +float64 azimuth_resolution + +# Azimuth angle accuracy, in degrees. The accuracy is defined as the +# precision with which the azimuth angle of a detection is reported. +float64 azimuth_accuracy + +# Elevation angle resolution, in degrees. The resolution is defined as +# the minimum elevation angle between two objects which results in +# distinct detections. +float64 elevation_resolution + +# Elevation angle accuracy, in degrees. The accuracy is defined as the +# precision with which the elevation angle of a detection is reported. +float64 elevation_accuracy diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarTarget.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarTarget.msg new file mode 100644 index 00000000..3bb5f280 --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/msg/RadarTarget.msg @@ -0,0 +1,8 @@ +# This message describes a target (detection) from a RADAR sensor. + +uint16 target_id # ID of the target, as set by the sensor +float64 snr # Signal-to-noise ratio +float64 range # Distance from sensor to target along sensor x-axis +float64 speed # Speed (range rate of change) of target along sensor x-axis +float64 azimuth # Angle of target relative to sensor within x-y plane +float64 elevation # Angle of target relative to sensor within y-z plane diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetArray.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetArray.msg new file mode 100644 index 00000000..7bdc2295 --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetArray.msg @@ -0,0 +1,5 @@ +# This message describes an array of targets with a timestamp. + +std_msgs/Header header + +RadarTarget[] targets diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetStamped.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetStamped.msg new file mode 100644 index 00000000..f955037f --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetStamped.msg @@ -0,0 +1,5 @@ +# This message describes a target (detection) from a RADAR sensor with a timestamp. + +std_msgs/Header header + +RadarTarget target diff --git a/ainstein_radar/ainstein_radar_msgs/package.xml b/ainstein_radar/ainstein_radar_msgs/package.xml new file mode 100644 index 00000000..fcc15d99 --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/package.xml @@ -0,0 +1,39 @@ + + + + ainstein_radar_msgs + 3.0.1 + + ROS message definitions for Ainstein radars. + + Nick Rotella + Nick Rotella + BSD + https://wiki.ros.org/ainstein_radar_msgs + https://github.com/AinsteinAI/ainstein_radar + https://github.com/AinsteinAI/ainstein_radar/issues + + catkin + ament_cmake + + message_generation + rosidl_default_generators + ros_environment + + builtin_interfaces + std_msgs + + message_runtime + rosidl_default_runtime + + ament_lint_auto + ament_lint_common + + rosidl_interface_packages + + + catkin + ament_cmake + + + From a42e41a387a30f70c381ef868c883ef37d155791 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:15:41 +0200 Subject: [PATCH 122/627] Add astuff_sensor_msgs for derived_object_msgs --- astuff_sensor_msgs/.gitignore | 10 ++ astuff_sensor_msgs/LICENSE | 19 ++++ astuff_sensor_msgs/README.md | 19 ++++ .../derived_object_msgs/CHANGELOG.rst | 30 ++++++ .../derived_object_msgs/CMakeLists.txt | 101 ++++++++++++++++++ .../derived_object_msgs/msg/CipvTrack.msg | 6 ++ .../derived_object_msgs/msg/Lane.msg | 47 ++++++++ .../derived_object_msgs/msg/LaneModels.msg | 9 ++ .../derived_object_msgs/msg/Object.msg | 56 ++++++++++ .../derived_object_msgs/msg/ObjectArray.msg | 3 + .../msg/ObjectWithCovariance.msg | 56 ++++++++++ .../msg/ObjectWithCovarianceArray.msg | 3 + .../msg/SolidPrimitiveWithCovariance.msg | 43 ++++++++ .../derived_object_msgs/package.xml | 40 +++++++ astuff_sensor_msgs/radar_msgs/CHANGELOG.rst | 29 +++++ astuff_sensor_msgs/radar_msgs/CMakeLists.txt | 86 +++++++++++++++ .../radar_msgs/msg/RadarDetection.msg | 10 ++ .../radar_msgs/msg/RadarDetectionArray.msg | 3 + .../radar_msgs/msg/RadarDetectionStamped.msg | 3 + .../radar_msgs/msg/RadarErrorStatus.msg | 9 ++ .../radar_msgs/msg/RadarStatus.msg | 12 +++ .../radar_msgs/msg/RadarTrack.msg | 16 +++ .../radar_msgs/msg/RadarTrackArray.msg | 3 + .../radar_msgs/msg/RadarTrackStamped.msg | 3 + astuff_sensor_msgs/radar_msgs/package.xml | 38 +++++++ 25 files changed, 654 insertions(+) create mode 100644 astuff_sensor_msgs/.gitignore create mode 100644 astuff_sensor_msgs/LICENSE create mode 100644 astuff_sensor_msgs/README.md create mode 100644 astuff_sensor_msgs/derived_object_msgs/CHANGELOG.rst create mode 100644 astuff_sensor_msgs/derived_object_msgs/CMakeLists.txt create mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/CipvTrack.msg create mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/Lane.msg create mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/LaneModels.msg create mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/Object.msg create mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/ObjectArray.msg create mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovariance.msg create mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovarianceArray.msg create mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg create mode 100644 astuff_sensor_msgs/derived_object_msgs/package.xml create mode 100644 astuff_sensor_msgs/radar_msgs/CHANGELOG.rst create mode 100644 astuff_sensor_msgs/radar_msgs/CMakeLists.txt create mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarDetection.msg create mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarDetectionArray.msg create mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarDetectionStamped.msg create mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarErrorStatus.msg create mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarStatus.msg create mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarTrack.msg create mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarTrackArray.msg create mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarTrackStamped.msg create mode 100644 astuff_sensor_msgs/radar_msgs/package.xml diff --git a/astuff_sensor_msgs/.gitignore b/astuff_sensor_msgs/.gitignore new file mode 100644 index 00000000..86ca0249 --- /dev/null +++ b/astuff_sensor_msgs/.gitignore @@ -0,0 +1,10 @@ +build/ +bin/ +lib/ +lib_include/ +*.log +*.swp +*.user +*~ +.idea/ +.vscode diff --git a/astuff_sensor_msgs/LICENSE b/astuff_sensor_msgs/LICENSE new file mode 100644 index 00000000..964fe6b9 --- /dev/null +++ b/astuff_sensor_msgs/LICENSE @@ -0,0 +1,19 @@ +Copyright (c) 2017 AutonomouStuff, LLC + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/astuff_sensor_msgs/README.md b/astuff_sensor_msgs/README.md new file mode 100644 index 00000000..cef4b5d2 --- /dev/null +++ b/astuff_sensor_msgs/README.md @@ -0,0 +1,19 @@ +# ROS Messages for AutonomouStuff-provided Drivers # + +[![CircleCI](https://circleci.com/gh/astuff/astuff_sensor_msgs/tree/master.svg?style=svg)](https://circleci.com/gh/astuff/astuff_sensor_msgs/tree/master) + +A set of messages for each AutonomouStuff-provided driver. `astuff_sensor_msgs` contains: + +- `delphi_esr_msgs` +- `delphi_mrr_msgs` +- `delphi_srr_msgs` +- `ibeo_lux_msgs` +- `ibeo_msgs` (Messages for all Ibeo sensors) +- `kartech_linear_actuator_msgs` +- `mobileye_560_660_msgs` +- `neobotix_usboard_msgs` +- `pacmod_msgs` +- `radar_msgs` (generic radar output messages not currently available in `sensor_msgs`) +- `derived_object_msgs` (abstracted sensor messages for like Objects and Closest In-Path Vehicles) + +For more information on the individual drivers, see the [AutonomouStuff Wiki](https://autonomoustuff.atlassian.net/wiki/spaces/RW/pages/17478581/Supported+Devices). diff --git a/astuff_sensor_msgs/derived_object_msgs/CHANGELOG.rst b/astuff_sensor_msgs/derived_object_msgs/CHANGELOG.rst new file mode 100644 index 00000000..70e6bc77 --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/CHANGELOG.rst @@ -0,0 +1,30 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package derived_object_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +3.0.1 (2020-01-23) +------------------ +* Adding ros_environment as required package to all packages. +* Hybridize derived_object_msgs. (`#44 `_) +* Adding hybrid CI. +* Updating package.xml files for ROS2 rosdep. +* Adding message migration rules. +* Contributors: Joshua Whitley + +2.3.1 (2018-12-07) +------------------ +* Merge pull request `#31 `_ from astuff/maint/add_urls +* Adding URLs to package.xml files. +* Contributors: Daniel-Stanek, Joshua Whitley + +2.3.0 (2018-10-04) +------------------ + +2.2.2 (2018-08-30) +------------------ + +2.2.1 (2018-08-08) +------------------ +* Renamed perception_msgs to derived_object_msgs for clarification. +* Moving perception_msgs from platform_automation_msgs. +* Contributors: Joe Buckner, Joshua Whitley diff --git a/astuff_sensor_msgs/derived_object_msgs/CMakeLists.txt b/astuff_sensor_msgs/derived_object_msgs/CMakeLists.txt new file mode 100644 index 00000000..d1660a52 --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/CMakeLists.txt @@ -0,0 +1,101 @@ +project(derived_object_msgs) + +find_package(ros_environment REQUIRED) + +set(ROS_VERSION $ENV{ROS_VERSION}) + +set(MSG_FILES + "CipvTrack.msg" + "Lane.msg" + "LaneModels.msg" + "Object.msg" + "ObjectArray.msg" + "ObjectWithCovariance.msg" + "ObjectWithCovarianceArray.msg" + "SolidPrimitiveWithCovariance.msg" +) + +if(${ROS_VERSION} EQUAL 1) + + cmake_minimum_required(VERSION 2.8.3) + + # Default to C++11 + if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 11) + endif() + + find_package(catkin REQUIRED + COMPONENTS + geometry_msgs + message_generation + radar_msgs + shape_msgs + std_msgs + ) + + add_message_files(FILES + ${MSG_FILES} + DIRECTORY msg + ) + + generate_messages( + DEPENDENCIES + geometry_msgs + radar_msgs + shape_msgs + std_msgs + ) + + catkin_package( + CATKIN_DEPENDS message_runtime + ) + +elseif(${ROS_VERSION} EQUAL 2) + + cmake_minimum_required(VERSION 3.5) + + if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_STANDARD 14) + endif() + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + + find_package(ament_cmake REQUIRED) + find_package(builtin_interfaces REQUIRED) + find_package(geometry_msgs REQUIRED) + find_package(radar_msgs REQUIRED) + find_package(rosidl_default_generators REQUIRED) + find_package(shape_msgs REQUIRED) + find_package(std_msgs REQUIRED) + + # Apend "msg/" to each file name + set(TEMP_LIST "") + foreach(MSG_FILE ${MSG_FILES}) + list(APPEND TEMP_LIST "msg/${MSG_FILE}") + endforeach() + set(MSG_FILES ${TEMP_LIST}) + + rosidl_generate_interfaces(${PROJECT_NAME} + ${MSG_FILES} + DEPENDENCIES + builtin_interfaces + geometry_msgs + shape_msgs + std_msgs + radar_msgs + ADD_LINTER_TESTS + ) + + ament_export_dependencies(rosidl_default_runtime) + + if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + endif() + + ament_package() + +endif() diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/CipvTrack.msg b/astuff_sensor_msgs/derived_object_msgs/msg/CipvTrack.msg new file mode 100644 index 00000000..f329e309 --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/msg/CipvTrack.msg @@ -0,0 +1,6 @@ +# Closest In-Path Vehicle Radar Track + +std_msgs/Header header + +bool is_valid # Whether or not the track is a valid CIPV +radar_msgs/RadarTrack track # The CIPV track diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/Lane.msg b/astuff_sensor_msgs/derived_object_msgs/msg/Lane.msg new file mode 100644 index 00000000..d931b632 --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/msg/Lane.msg @@ -0,0 +1,47 @@ +# Lane Definition Message +# Contains information on a single lane marker + +uint8 quality # Visual quality of lane marker +uint8 LANE_QUALITY_INVALID = 0 +uint8 LANE_QUALITY_UNKNOWN = 1 +uint8 LANE_QUALITY_NOT_AVAILABLE = 2 +uint8 LANE_QUALITY_0 = 3 +uint8 LANE_QUALITY_1 = 4 +uint8 LANE_QUALITY_2 = 5 +uint8 LANE_QUALITY_3 = 6 +uint8 LANE_QUALITY_4 = 7 +uint8 LANE_QUALITY_5 = 8 +uint8 LANE_QUALITY_6 = 9 +uint8 LANE_QUALITY_7 = 10 +uint8 LANE_QUALITY_8 = 11 +uint8 LANE_QUALITY_9 = 12 +uint8 LANE_QUALITY_KIND_COUNT = 13 + +uint8 marker_kind # Solid, dashed, ... +uint8 LANE_MARKER_INVALID = 0 +uint8 LANE_MARKER_UNKNOWN = 1 +uint8 LANE_MARKER_NOT_AVAILABLE = 2 +uint8 LANE_MARKER_NONE = 3 +uint8 LANE_MARKER_SOLID = 4 +uint8 LANE_MARKER_DASHED = 5 +uint8 LANE_MARKER_VIRTUAL = 6 +uint8 LANE_MARKER_DOTS = 7 +uint8 LANE_MARKER_ROAD_EDGE = 8 +uint8 LANE_MARKER_DOUBLE_LINE = 9 +uint8 LANE_MARKER_KIND_COUNT = 10 + +uint8 curve_model_kind # Order of equation +uint8 LANE_CURVE_MODEL_INVALID = 0 +uint8 LANE_CURVE_MODEL_UNKNOWN = 1 +uint8 LANE_CURVE_MODEL_NOT_AVAILABLE = 2 +uint8 LANE_CURVE_MODEL_LINEAR = 3 +uint8 LANE_CURVE_MODEL_PARABOLIC = 4 +uint8 LANE_CURVE_MODEL_3D = 5 +uint8 LANE_CURVE_MODEL_KIND_COUNT = 6 + +float64 marker_offset # Lateral distance from sensor to marker (m) +float64 heading_angle # Angle of marker relative to sensor (rad) +float64 curvature # Curvature of the lane marker at the camera (1/m) +float64 curvature_derivative # Amount curvature changes as you move away from the camera (1/m^2) +float64 marker_width # Width of the painted marker (not distance between lane markers) (m) +float64 view_range # Physical view range of the lane mark (m) diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/LaneModels.msg b/astuff_sensor_msgs/derived_object_msgs/msg/LaneModels.msg new file mode 100644 index 00000000..9be89705 --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/msg/LaneModels.msg @@ -0,0 +1,9 @@ +# Lane Models Message +# Contains multiple lanes detected by the sensor + +std_msgs/Header header + +derived_object_msgs/Lane left_lane +derived_object_msgs/Lane right_lane + +derived_object_msgs/Lane[] additional_lanes diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/Object.msg b/astuff_sensor_msgs/derived_object_msgs/msg/Object.msg new file mode 100644 index 00000000..27cc705c --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/msg/Object.msg @@ -0,0 +1,56 @@ +# This represents a detected or tracked object with reference coordinate frame and timestamp. + +std_msgs/Header header + +# The id of the object (presumably from the detecting sensor). +uint32 id + +# A Detected object is one which has been seen in at least one scan/frame of a sensor. +# A Tracked object is one which has been correlated over multiple scans/frames of a sensor. +# An object which is detected can only be assumed to have valid pose and shape properties. +# An object which is tracked should also be assumed to have valid twist and accel properties. +uint8 detection_level +uint8 OBJECT_DETECTED=0 +uint8 OBJECT_TRACKED=1 + +# A Classified object is one which has been identified as a certain object type. +# Classified objects should have valid classification, classification_certainty, and classification_age properties. +bool object_classified + +# The detected position and orientation of the object. +geometry_msgs/Pose pose + +# The detected linear and angular velocities of the object. +geometry_msgs/Twist twist + +# The detected linear and angular accelerations of the object. +geometry_msgs/Accel accel + +# (OPTIONAL) The polygon defining the detection points at the outer edges of the object. +geometry_msgs/Polygon polygon + +# A shape conforming to the outer bounding edges of the object. +shape_msgs/SolidPrimitive shape + +# The type of classification given to this object. +uint8 classification +uint8 CLASSIFICATION_UNKNOWN=0 +uint8 CLASSIFICATION_UNKNOWN_SMALL=1 +uint8 CLASSIFICATION_UNKNOWN_MEDIUM=2 +uint8 CLASSIFICATION_UNKNOWN_BIG=3 +uint8 CLASSIFICATION_PEDESTRIAN=4 +uint8 CLASSIFICATION_BIKE=5 +uint8 CLASSIFICATION_CAR=6 +uint8 CLASSIFICATION_TRUCK=7 +uint8 CLASSIFICATION_MOTORCYCLE=8 +uint8 CLASSIFICATION_OTHER_VEHICLE=9 +uint8 CLASSIFICATION_BARRIER=10 +uint8 CLASSIFICATION_SIGN=11 + +# The certainty of the classification from the originating sensor. +# Higher value indicates greater certainty (MAX=255). +# It is recommended that a native sensor value be scaled to 0-255 for interoperability. +uint8 classification_certainty + +# The number of scans/frames from the sensor that this object has been classified as the current classification. +uint32 classification_age diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectArray.msg b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectArray.msg new file mode 100644 index 00000000..b6b3606f --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectArray.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +derived_object_msgs/Object[] objects diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovariance.msg b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovariance.msg new file mode 100644 index 00000000..3c95024f --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovariance.msg @@ -0,0 +1,56 @@ +# This represents an estimated object with reference coordinate frame and timestamp. +std_msgs/Header header + +# The id of the object (presumably from the detecting sensor). +uint32 id + +# A Detected object is one which has been seen in at least one scan/frame of a sensor. +# A Tracked object is one which has been correlated over multiple scans/frames of a sensor. +# An object which is detected can only be assumed to have valid pose and shape properties. +# An object which is tracked should also be assumed to have valid twist and accel properties. +# The validity of the individual components of each object property are defined by the property's covariance matrix. +uint8 detection_level +uint8 OBJECT_DETECTED=0 +uint8 OBJECT_TRACKED=1 + +# A Classified object is one which has been identified as a certain object type. +# Classified objects should have valid classification, classification_certainty, and classification_age properties. +bool object_classified + +# The detected position and orientation of the object. +geometry_msgs/PoseWithCovariance pose + +# The detected linear and angular velocities of the object. +geometry_msgs/TwistWithCovariance twist + +# The detected linear and angular accelerations of the object. +geometry_msgs/AccelWithCovariance accel + +# (OPTIONAL) The polygon defining the detection points at the outer edges of the object. +geometry_msgs/Polygon polygon + +# A shape conforming to the outer bounding edges of the object. +derived_object_msgs/SolidPrimitiveWithCovariance shape + +# The type of classification given to this object. +uint8 classification +uint8 CLASSIFICATION_UNKNOWN=0 +uint8 CLASSIFICATION_UNKNOWN_SMALL=1 +uint8 CLASSIFICATION_UNKNOWN_MEDIUM=2 +uint8 CLASSIFICATION_UNKNOWN_BIG=3 +uint8 CLASSIFICATION_PEDESTRIAN=4 +uint8 CLASSIFICATION_BIKE=5 +uint8 CLASSIFICATION_CAR=6 +uint8 CLASSIFICATION_TRUCK=7 +uint8 CLASSIFICATION_MOTORCYCLE=8 +uint8 CLASSIFICATION_OTHER_VEHICLE=9 +uint8 CLASSIFICATION_BARRIER=10 +uint8 CLASSIFICATION_SIGN=11 + +# The certainty of the classification from the originating sensor. +# Higher value indicates greater certainty (MAX=255). +# It is recommended that a native sensor value be scaled to 0-255 for interoperability. +uint8 classification_certainty + +# The number of scans/frames from the sensor that this object has been classified as the current classification. +uint32 classification_age diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovarianceArray.msg b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovarianceArray.msg new file mode 100644 index 00000000..fdcd9488 --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovarianceArray.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +derived_object_msgs/ObjectWithCovariance[] objects diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg b/astuff_sensor_msgs/derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg new file mode 100644 index 00000000..ffed1312 --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg @@ -0,0 +1,43 @@ +# Define box, sphere, cylinder, cone +# All shapes are defined to have their bounding boxes centered around 0,0,0. +# This message based on shape_msgs/SolidPrimitive + +# The type of the shape +uint8 type +uint8 BOX=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 CONE=4 + +# The dimensions of the shape +float64[] dimensions + +# The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array +# For the BOX type, the X, Y, and Z dimensions are the length of the corresponding +# sides of the box. +uint8 BOX_X=0 +uint8 BOX_Y=1 +uint8 BOX_Z=2 + +# For the SPHERE type, only one component is used, and it gives the radius of +# the sphere. +uint8 SPHERE_RADIUS=0 + +# For the CYLINDER and CONE types, the center line is oriented along +# the Z axis. Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component +# of dimensions gives the height of the cylinder (cone). The +# CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the +# radius of the base of the cylinder (cone). Cone and cylinder +# primitives are defined to be circular. The tip of the cone is +# pointing up, along +Z axis. +uint8 CYLINDER_HEIGHT=0 +uint8 CYLINDER_RADIUS=1 + +uint8 CONE_HEIGHT=0 +uint8 CONE_RADIUS=1 + +# Row-major representation of the covariance matrix associated with the shape. +# For the BOX type, this should be a 3x3 matrix defining the uncertainty of the X, Y, and Z measurements. +# For the SPHERE type, this should contain only one value for the radius. +# For the CYLINDER and CONE types, this will be a 2x2 matrix defining the uncertainty of the HEIGHT and RADIUS measurements. +float64[] covariance diff --git a/astuff_sensor_msgs/derived_object_msgs/package.xml b/astuff_sensor_msgs/derived_object_msgs/package.xml new file mode 100644 index 00000000..69ee5dca --- /dev/null +++ b/astuff_sensor_msgs/derived_object_msgs/package.xml @@ -0,0 +1,40 @@ + + + + derived_object_msgs + 3.0.1 + Abstracted Messages from Perception Modalities + AutonomouStuff Software Development Team + MIT + http://wiki.ros.org/derived_object_msgs + https://github.com/astuff/astuff_sensor_msgs + https://github.com/astuff/astuff_sensor_msgs/issues + Daniel Stanek + Josh Whitley + + catkin + ament_cmake + + message_generation + rosidl_default_generators + ros_environment + + builtin_interfaces + geometry_msgs + radar_msgs + shape_msgs + std_msgs + + message_runtime + rosidl_default_runtime + + ament_lint_auto + ament_lint_common + + rosidl_interface_packages + + + catkin + ament_cmake + + diff --git a/astuff_sensor_msgs/radar_msgs/CHANGELOG.rst b/astuff_sensor_msgs/radar_msgs/CHANGELOG.rst new file mode 100644 index 00000000..56a23af0 --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/CHANGELOG.rst @@ -0,0 +1,29 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package radar_msgs +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +3.0.1 (2020-01-23) +------------------ +* Adding ros_environment as required package to all packages. +* Hybridizing radar_msgs. (`#41 `_) +* Adding hybrid CI. +* Updating package.xml files for ROS2 rosdep. +* Adding message migration rules. +* Contributors: Joshua Whitley + +2.3.1 (2018-12-07) +------------------ +* Merge pull request `#31 `_ from astuff/maint/add_urls +* Adding URLs to package.xml files. +* Contributors: Daniel-Stanek, Joshua Whitley + +2.3.0 (2018-10-04) +------------------ + +2.2.2 (2018-08-30) +------------------ + +2.2.1 (2018-08-08) +------------------ +* Moving radar_msgs from platform_automation_msgs. +* Contributors: Joe Buckner, Joshua Whitley, Sam Rustan diff --git a/astuff_sensor_msgs/radar_msgs/CMakeLists.txt b/astuff_sensor_msgs/radar_msgs/CMakeLists.txt new file mode 100644 index 00000000..a9e433bd --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/CMakeLists.txt @@ -0,0 +1,86 @@ +project(radar_msgs) + +find_package(ros_environment REQUIRED) + +set(ROS_VERSION $ENV{ROS_VERSION}) + +set(MSG_FILES + "RadarDetection.msg" + "RadarDetectionArray.msg" + "RadarDetectionStamped.msg" + "RadarErrorStatus.msg" + "RadarStatus.msg" + "RadarTrack.msg" + "RadarTrackArray.msg" + "RadarTrackStamped.msg" +) + +if(${ROS_VERSION} EQUAL 1) + + cmake_minimum_required(VERSION 2.8.3) + + # Default to C++11 + if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 11) + endif() + + find_package(catkin REQUIRED + COMPONENTS + message_generation + geometry_msgs + std_msgs + ) + + add_message_files(FILES + ${MSG_FILES} + DIRECTORY msg + ) + + generate_messages(DEPENDENCIES geometry_msgs std_msgs) + + catkin_package( + CATKIN_DEPENDS message_runtime + ) + +elseif(${ROS_VERSION} EQUAL 2) + + cmake_minimum_required(VERSION 3.5) + + if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_STANDARD 14) + endif() + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + + find_package(ament_cmake REQUIRED) + find_package(builtin_interfaces REQUIRED) + find_package(geometry_msgs REQUIRED) + find_package(std_msgs REQUIRED) + find_package(rosidl_default_generators REQUIRED) + + # Apend "msg/" to each file name + set(TEMP_LIST "") + foreach(MSG_FILE ${MSG_FILES}) + list(APPEND TEMP_LIST "msg/${MSG_FILE}") + endforeach() + set(MSG_FILES ${TEMP_LIST}) + + rosidl_generate_interfaces(${PROJECT_NAME} + ${MSG_FILES} + DEPENDENCIES builtin_interfaces geometry_msgs std_msgs + ADD_LINTER_TESTS + ) + + ament_export_dependencies(rosidl_default_runtime) + + if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + endif() + + ament_package() + +endif() diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarDetection.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarDetection.msg new file mode 100644 index 00000000..d315e627 --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/msg/RadarDetection.msg @@ -0,0 +1,10 @@ +# All variables below are relative to the radar's frame of reference. +# This message is not meant to be used alone but as part of a stamped or array message. + +uint16 detection_id # The ID of this detection generated by the radar. If + # the radar does not generate IDs, this is intended as + # a sequential identifier for each detection in a scan. + +geometry_msgs/Point position # Only the x and y components are valid. +geometry_msgs/Vector3 velocity # range_rate rectangular transformation to x and y components +float64 amplitude # The detection amplitude in dB. diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionArray.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionArray.msg new file mode 100644 index 00000000..a36e284c --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionArray.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +radar_msgs/RadarDetection[] detections diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionStamped.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionStamped.msg new file mode 100644 index 00000000..2df71fb8 --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionStamped.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +radar_msgs/RadarDetection detection diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarErrorStatus.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarErrorStatus.msg new file mode 100644 index 00000000..c4d784fc --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/msg/RadarErrorStatus.msg @@ -0,0 +1,9 @@ +std_msgs/Header header + +# Error Status + +bool comm_error +bool overheat_error +bool range_perf_error +bool internal_error +bool xcvr_operational diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarStatus.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarStatus.msg new file mode 100644 index 00000000..b6f7d90a --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/msg/RadarStatus.msg @@ -0,0 +1,12 @@ +std_msgs/Header header + +# Status of the radar + +int16 curvature +float32 yaw_rate +float32 vehicle_speed +uint8 max_track_targets +bool raw_data_mode +int8 temperature +bool patial_blockage +bool side_lobe_blockage diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarTrack.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarTrack.msg new file mode 100644 index 00000000..f3dbc67a --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/msg/RadarTrack.msg @@ -0,0 +1,16 @@ +# All variables below are relative to the radar's frame of reference. +# This message is not meant to be used alone but as part of a stamped or array message. + +uint16 track_id # The ID of this track generated by the radar. If + # the radar does not generate IDs, this is intended as + # a sequential identifier for each track in a scan. + +geometry_msgs/Polygon track_shape # The shape and position of the detection. This polygon + # encompasses a 2D plane which approximates the size and + # shape of the detection based on the distance from the + # radar, the detection angle, the width of all detections + # grouped into this track, and the height of the radar's + # vertical field of view at the detection distance. + +geometry_msgs/Vector3 linear_velocity # Only the x and y components are valid. +geometry_msgs/Vector3 linear_acceleration # Only the x component is valid. diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarTrackArray.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarTrackArray.msg new file mode 100644 index 00000000..9f3eab75 --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/msg/RadarTrackArray.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +radar_msgs/RadarTrack[] tracks diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarTrackStamped.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarTrackStamped.msg new file mode 100644 index 00000000..452e9a3f --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/msg/RadarTrackStamped.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +radar_msgs/RadarTrack track diff --git a/astuff_sensor_msgs/radar_msgs/package.xml b/astuff_sensor_msgs/radar_msgs/package.xml new file mode 100644 index 00000000..158cdca5 --- /dev/null +++ b/astuff_sensor_msgs/radar_msgs/package.xml @@ -0,0 +1,38 @@ + + + + radar_msgs + 3.0.1 + Generic Radar Messages + AutonomouStuff Software Development Team + MIT + http://wiki.ros.org/radar_msgs + https://github.com/astuff/astuff_sensor_msgs + https://github.com/astuff/astuff_sensor_msgs/issues + Daniel Stanek + Josh Whitley + + catkin + ament_cmake + + message_generation + rosidl_default_generators + ros_environment + + builtin_interfaces + geometry_msgs + std_msgs + + message_runtime + rosidl_default_runtime + + ament_lint_auto + ament_lint_common + + rosidl_interface_packages + + + catkin + ament_cmake + + From 883e2606e35b57debb7d7c0d67fa633900c30b66 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 4 Jun 2020 17:16:46 +0200 Subject: [PATCH 123/627] Add resource dirs and corresponding files to avoid compilation errors related to ros2 with setup.py --- carla_manual_control/resource/carla_manual_control | 0 carla_ros_bridge/resource/carla_ros_bridge | 0 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 carla_manual_control/resource/carla_manual_control create mode 100644 carla_ros_bridge/resource/carla_ros_bridge diff --git a/carla_manual_control/resource/carla_manual_control b/carla_manual_control/resource/carla_manual_control new file mode 100644 index 00000000..e69de29b diff --git a/carla_ros_bridge/resource/carla_ros_bridge b/carla_ros_bridge/resource/carla_ros_bridge new file mode 100644 index 00000000..e69de29b From 466d85de0c11131fea1c45f358627cb0240596ae Mon Sep 17 00:00:00 2001 From: sergimoya Date: Fri, 5 Jun 2020 10:04:38 +0200 Subject: [PATCH 124/627] Modify CMake to build different versions of RadarInfo.msg --- ainstein_radar/ainstein_radar_msgs/CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt b/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt index 6e9d752a..b6678453 100644 --- a/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt +++ b/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt @@ -6,7 +6,7 @@ set(ROS_VERSION $ENV{ROS_VERSION}) set(CMAKE_CXX_STANDARD 11) set(MSG_FILES - RadarInfo.msg + # RadarInfo.msg RadarAlarm.msg RadarAlarmArray.msg RadarAlarmStamped.msg @@ -27,6 +27,7 @@ if (${ROS_VERSION} EQUAL 1) DIRECTORY msg FILES ${MSG_FILES} + RadarInfo.msg ) generate_messages( @@ -69,6 +70,7 @@ elseif (${ROS_VERSION} EQUAL 2) rosidl_generate_interfaces(${PROJECT_NAME} ${MSG_FILES} + "msg/RadarInfo2.msg" DEPENDENCIES builtin_interfaces std_msgs ADD_LINTER_TESTS ) From 3bf6edc5a54356efe64f8043c872dc699e145bf8 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Fri, 5 Jun 2020 10:04:59 +0200 Subject: [PATCH 125/627] Add RadarInfo2.msg for ROS2 version --- .../ainstein_radar_msgs/msg/RadarInfo2.msg | 106 ++++++++++++++++++ 1 file changed, 106 insertions(+) create mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarInfo2.msg diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo2.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo2.msg new file mode 100644 index 00000000..eadccbb2 --- /dev/null +++ b/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo2.msg @@ -0,0 +1,106 @@ +# This message defines meta information for a radar sensor. It should +# be in a radar namespace on topic "radar_info" and accompanied by up +# to three radar topics named: +# +# targets/raw - raw (untracked) radar detections +# targets/tracked - tracked radar detections +# alarms - alarms based on detections, eg BSD +# +# In general, all Ainstein radars output raw detections and may also +# output tracked detections if trackign algorithms are implemented in +# firmware. Tracking from raw data is also available in ROS; see the +# ainstein_radar_filters package for more information. Most radars do +# not output alarms as this is specific to the automotive use case, +# however this message type is retained for the time being for backward +# compatibility. + +####################################################################### +# Data acquisition info # +####################################################################### + +# Time of data acquisition, radar coordinate frame ID +std_msgs/Header header # Header timestamp should be acquisition time of data + # Header frame_id should be radar sensing frame + # origin of frame should be center of sensor + # +x should point radially outwards from the radar + # +y should point to complete a right-handed frame + # +z should point upwards + +####################################################################### +# General sensor properties # +####################################################################### + +# The nominal update rate of the sensor reported in Hz. +float64 update_rate + +# The maximum number of detections (targets) the sensors can report. +uint16 max_num_targets + +####################################################################### +# Physical sensing limits # +####################################################################### +# These are limits imposed by the antenna hardware and/or cutoffs set # +# in the detection processing firmware. They come from sensor data # +# sheets and must be updated with each hardware revision as necessary.# +####################################################################### + +# The minimum and maximum range, in meters, of detections (targets) +# reported by the sensor. +float64 range_min +float64 range_max + +# The minimum and maximum speed, in meters per second, of detections +# (targets) reported by the sensor. +float64 speed_min +float64 speed_max + +# The minimum and maximum azimuth angle, in degrees. +float64 azimuth_min +float64 azimuth_max + +# The minimum and maximum azimuth angle, in degrees. +float64 elevation_min +float64 elevation_max + +####################################################################### +# Physical sensing precision # +####################################################################### +# These are also imposed by the antenna hardware and/or set in the # +# detection processing firmware. They also come from sensor data # +# sheets and must be updated with each hardware revision as necessary.# +####################################################################### + +# Range resolution, in meters. The resolution is defined as the minimum +# distance between two objects which results in distinct detections. +float64 range_resolution + +# Range accuracy, in meters. The accuracy is defined as the precision +# with which range of a detection is reported. +float64 range_accuracy + +# Speed resolution, in meters per second. The resolution is defined as +# the minimum speed difference between two objects which results in +# distinct detections. +float64 speed_resolution + +# Speed accuracy, in meters per second. The accuracy is defined as the +# precision with which speed of a detection is reported. +float64 speed_accuracy + +# Azimuth angle resolution, in degrees. The resolution is defined as +# the minimum azimuth angle between two objects which results in +# distinct detections. +float64 azimuth_resolution + +# Azimuth angle accuracy, in degrees. The accuracy is defined as the +# precision with which the azimuth angle of a detection is reported. +float64 azimuth_accuracy + +# Elevation angle resolution, in degrees. The resolution is defined as +# the minimum elevation angle between two objects which results in +# distinct detections. +float64 elevation_resolution + +# Elevation angle accuracy, in degrees. The accuracy is defined as the +# precision with which the elevation angle of a detection is reported. +float64 elevation_accuracy From 312416edc5439d9b27ba5336409a6bfb54d31436 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 5 Jun 2020 10:26:52 +0200 Subject: [PATCH 126/627] Enable lidar compatibility --- .../src/carla_ros_bridge/bridge.py | 6 +- .../src/carla_ros_bridge/lidar.py | 76 ++++++++++++++++++- 2 files changed, 77 insertions(+), 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 50674d7a..ee5479ce 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -31,7 +31,7 @@ from carla_ros_bridge.spectator import Spectator from carla_ros_bridge.traffic import Traffic, TrafficLight from carla_ros_bridge.vehicle import Vehicle -# from carla_ros_bridge.lidar import Lidar +from carla_ros_bridge.lidar import Lidar # from carla_ros_bridge.radar import Radar from carla_ros_bridge.gnss import Gnss from carla_ros_bridge.imu import ImuSensor @@ -419,8 +419,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m else: actor = Camera(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) - # elif carla_actor.type_id.startswith("sensor.lidar"): - # actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + elif carla_actor.type_id.startswith("sensor.lidar"): + actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) # elif carla_actor.type_id.startswith("sensor.other.radar"): # actor = Radar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 48ab5488..7df75014 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -18,9 +18,16 @@ if ROS_VERSION == 1: from tf.transformations import euler_from_quaternion, quaternion_from_euler elif ROS_VERSION == 2: + import ctypes + from sensor_msgs.msg import PointCloud2, PointField + import struct from transformations.transformations import euler_from_quaternion, quaternion_from_euler -from sensor_msgs.point_cloud2 import create_cloud_xyz32 +_DATATYPES = {} +_DATATYPES[PointField.FLOAT32] = ('f', 4) + +# from sensor_msgs.point_cloud2 import create_cloud_xyz32 +# from sensor_msgs.msg import PointCloud2 from carla_ros_bridge.sensor import Sensor import carla_ros_bridge.transforms as trans @@ -86,5 +93,70 @@ def sensor_data_updated(self, carla_lidar_measurement): lidar_data = -lidar_data # we also need to permute x and y lidar_data = lidar_data[..., [1, 0, 2]] - point_cloud_msg = create_cloud_xyz32(header, lidar_data) + + # -- taken from http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html + + point_field_x_msg = PointField() + point_field_x_msg.name = "x" + point_field_x_msg.offset = 0 + point_field_x_msg.datatype = PointField.FLOAT32 + point_field_x_msg.count = 1 + + point_field_y_msg = PointField() + point_field_y_msg.name = "y" + point_field_y_msg.offset = 4 + point_field_y_msg.datatype = PointField.FLOAT32 + point_field_y_msg.count = 1 + + point_field_z_msg = PointField() + point_field_z_msg.name = "z" + point_field_z_msg.offset = 8 + point_field_z_msg.datatype = PointField.FLOAT32 + point_field_z_msg.count = 1 + + fields = [point_field_x_msg, point_field_y_msg, point_field_z_msg] + + cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) + buff = ctypes.create_string_buffer(cloud_struct.size * len(lidar_data)) + + point_step, pack_into = cloud_struct.size, cloud_struct.pack_into + + offset = 0 + for pt in lidar_data: + pack_into(buff, offset, *pt) + offset += point_step + + point_cloud_msg = PointCloud2() + point_cloud_msg.header = header + point_cloud_msg.height = 1 + point_cloud_msg.width = len(lidar_data) + point_cloud_msg.is_dense = False + point_cloud_msg.is_bigendian = False + point_cloud_msg.fields = fields + point_cloud_msg.point_step = cloud_struct.size + point_cloud_msg.row_step = cloud_struct.size * len(lidar_data) + point_cloud_msg.data = buff.raw + + # -- + self.publish_message(self.get_topic_prefix() + "/point_cloud", point_cloud_msg) + + +# http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html +def _get_struct_fmt(is_bigendian, fields, field_names=None): + fmt = '>' if is_bigendian else '<' + + offset = 0 + for field in (f for f in sorted(fields, key=lambda f: f.offset) + if field_names is None or f.name in field_names): + if offset < field.offset: + fmt += 'x' * (field.offset - offset) + offset = field.offset + if field.datatype not in _DATATYPES: + print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr) + else: + datatype_fmt, datatype_length = _DATATYPES[field.datatype] + fmt += field.count * datatype_fmt + offset += field.count * datatype_length + + return fmt \ No newline at end of file From 6b73c12a17373184d86553fe0666f5548fcacaa3 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 5 Jun 2020 10:29:54 +0200 Subject: [PATCH 127/627] Uncomment radar in bridge.py --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index ee5479ce..2588ab00 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -32,7 +32,7 @@ from carla_ros_bridge.traffic import Traffic, TrafficLight from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.lidar import Lidar -# from carla_ros_bridge.radar import Radar +from carla_ros_bridge.radar import Radar from carla_ros_bridge.gnss import Gnss from carla_ros_bridge.imu import ImuSensor from carla_ros_bridge.ego_vehicle import EgoVehicle @@ -421,8 +421,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.lidar"): actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) - # elif carla_actor.type_id.startswith("sensor.other.radar"): - # actor = Radar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + elif carla_actor.type_id.startswith("sensor.other.radar"): + actor = Radar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): From d7d2c78bc823b196eaf6ae6a34c4b0dd7ea458a8 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 5 Jun 2020 16:46:19 +0200 Subject: [PATCH 128/627] Add sensor_name keyword argument to avoid all sensor having same node name --- .../src/carla_ros_bridge/camera.py | 27 ++++++++++++------- .../src/carla_ros_bridge/collision_sensor.py | 14 +++++----- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 12 ++++----- carla_ros_bridge/src/carla_ros_bridge/imu.py | 5 ++-- .../carla_ros_bridge/lane_invasion_sensor.py | 14 +++++----- .../src/carla_ros_bridge/lidar.py | 21 ++++++++------- .../src/carla_ros_bridge/radar.py | 12 ++++----- .../src/carla_ros_bridge/sensor.py | 27 +++++++++++-------- 8 files changed, 69 insertions(+), 63 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 51b1349e..b3a38605 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -45,7 +45,8 @@ class Camera(Sensor): # global cv bridge to convert image between opencv and ros cv_bridge = CvBridge() - def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments + def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix=None, + sensor_name="Camera"): # pylint: disable=too-many-arguments """ Constructor @@ -60,9 +61,9 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= """ if not prefix: prefix = 'camera' - super(Camera, - self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, - synchronous_mode=synchronous_mode, prefix=prefix) + super(Camera, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, synchronous_mode=synchronous_mode, + prefix=prefix, sensor_name=sensor_name) if self.__class__.__name__ == "Camera": self.logwarn("Created Unsupported Camera Actor" @@ -174,7 +175,8 @@ class RgbCamera(Camera): Camera implementation details for rgb camera """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, + sensor_name="RGBCamera"): """ Constructor @@ -190,7 +192,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): super(RgbCamera, self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, synchronous_mode=synchronous_mode, - prefix='camera/rgb/' + carla_actor.attributes.get('role_name')) + prefix='camera/rgb/' + carla_actor.attributes.get('role_name'), + sensor_name=sensor_name) def get_carla_image_data_array(self, carla_image): """ @@ -225,7 +228,8 @@ class DepthCamera(Camera): Camera implementation details for depth camera """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, + sensor_name="DepthCamera"): """ Constructor @@ -241,7 +245,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): super(DepthCamera, self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, synchronous_mode=synchronous_mode, - prefix='camera/depth/' + carla_actor.attributes.get('role_name')) + prefix='camera/depth/' + carla_actor.attributes.get('role_name'), + sensor_name=sensor_name) def get_carla_image_data_array(self, carla_image): """ @@ -298,7 +303,8 @@ class SemanticSegmentationCamera(Camera): Camera implementation details for segmentation camera """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, + sensor_name="SemanticSegmentationCamera"): """ Constructor @@ -314,7 +320,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): super(SemanticSegmentationCamera, self).__init__( carla_actor=carla_actor, parent=parent, communication=communication, synchronous_mode=synchronous_mode, - prefix='camera/semantic_segmentation/' + carla_actor.attributes.get('role_name')) + prefix='camera/semantic_segmentation/' + carla_actor.attributes.get('role_name'), + sensor_name=sensor_name) def get_carla_image_data_array(self, carla_image): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index 36c349a0..cef2709d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -15,12 +15,12 @@ class CollisionSensor(Sensor): - """ Actor implementation details for a collision sensor """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, + sensor_name="CollisionSensor"): """ Constructor @@ -33,12 +33,10 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(CollisionSensor, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - is_event_sensor=True, - prefix="collision") + super(CollisionSensor, + self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + synchronous_mode=synchronous_mode, is_event_sensor=True, + prefix="collision", sensor_name=sensor_name) # pylint: disable=arguments-differ def sensor_data_updated(self, collision_event): diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index 49a8cc52..f0bf0730 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -16,12 +16,11 @@ class Gnss(Sensor): - """ Actor implementation details for gnss sensor """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="GNSS"): """ Constructor @@ -34,11 +33,10 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(Gnss, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - prefix="gnss/" + carla_actor.attributes.get('role_name')) + super(Gnss, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, synchronous_mode=synchronous_mode, + prefix="gnss/" + carla_actor.attributes.get('role_name'), + sensor_name=sensor_name) # pylint: disable=arguments-differ def sensor_data_updated(self, carla_gnss_measurement): diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 88d524eb..aee457c4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -27,7 +27,7 @@ class ImuSensor(Sensor): Actor implementation details for imu sensor """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="IMU"): """ Constructor @@ -43,7 +43,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): super(ImuSensor, self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, synchronous_mode=synchronous_mode, - prefix="imu/" + carla_actor.attributes.get('role_name')) + prefix="imu/" + carla_actor.attributes.get('role_name'), + sensor_name=sensor_name) # pylint: disable=arguments-differ def sensor_data_updated(self, carla_imu_measurement): diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 9f3317f5..5dc62fc3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -15,12 +15,12 @@ class LaneInvasionSensor(Sensor): - """ Actor implementation details for a lane invasion sensor """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, + sensor_name="LaneInvasionSensor"): """ Constructor @@ -33,12 +33,10 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(LaneInvasionSensor, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - is_event_sensor=True, - prefix="lane_invasion") + super(LaneInvasionSensor, + self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + synchronous_mode=synchronous_mode, is_event_sensor=True, + prefix="lane_invasion", sensor_name=sensor_name) # pylint: disable=arguments-differ def sensor_data_updated(self, lane_invasion_event): diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 7df75014..e40159ff 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -10,35 +10,35 @@ Classes to handle Carla lidars """ +from __future__ import print_function import numpy +import ctypes +import struct + import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: from tf.transformations import euler_from_quaternion, quaternion_from_euler elif ROS_VERSION == 2: - import ctypes - from sensor_msgs.msg import PointCloud2, PointField - import struct from transformations.transformations import euler_from_quaternion, quaternion_from_euler -_DATATYPES = {} -_DATATYPES[PointField.FLOAT32] = ('f', 4) - -# from sensor_msgs.point_cloud2 import create_cloud_xyz32 -# from sensor_msgs.msg import PointCloud2 +from sensor_msgs.msg import PointCloud2, PointField from carla_ros_bridge.sensor import Sensor import carla_ros_bridge.transforms as trans +_DATATYPES = {} +_DATATYPES[PointField.FLOAT32] = ('f', 4) + class Lidar(Sensor): """ Actor implementation details for lidars """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="Lidar"): """ Constructor @@ -51,7 +51,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): """ super(Lidar, self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, synchronous_mode=synchronous_mode, - prefix='lidar/' + carla_actor.attributes.get('role_name')) + prefix='lidar/' + carla_actor.attributes.get('role_name'), + sensor_name=sensor_name) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 65d042cc..559434f5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -17,12 +17,11 @@ class Radar(Sensor): - """ Actor implementation details of Carla RADAR """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="Radar"): """ Constructor :param carla_actor: carla actor object @@ -34,11 +33,10 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(Radar, self).__init__(carla_actor=carla_actor, - parent=parent, - communication=communication, - synchronous_mode=synchronous_mode, - prefix="radar/" + carla_actor.attributes.get('role_name')) + super(Radar, self).__init__(carla_actor=carla_actor, parent=parent, + communication=communication, synchronous_mode=synchronous_mode, + prefix="radar/" + carla_actor.attributes.get('role_name'), + sensor_name=sensor_name) # pylint: disable=arguments-differ def sensor_data_updated(self, carla_radar_measurement): diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 61b448c1..8e9a7658 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -44,16 +44,17 @@ class Sensor(Actor, CompatibleNode): """ def __init__( - self, # pylint: disable=too-many-arguments - carla_actor, - parent, - communication, - synchronous_mode, - is_event_sensor=False, # only relevant in synchronous_mode: - # if a sensor only delivers data on special events, - # do not wait for it. That means you might get data from a - # sensor, that belongs to a different frame - prefix=None): + self, # pylint: disable=too-many-arguments + carla_actor, + parent, + communication, + synchronous_mode, + is_event_sensor=False, # only relevant in synchronous_mode: + # if a sensor only delivers data on special events, + # do not wait for it. That means you might get data from a + # sensor, that belongs to a different frame + prefix=None, + sensor_name=None): """ Constructor @@ -67,13 +68,17 @@ def __init__( :type synchronous_mode: bool :param prefix: the topic prefix to be used for this actor :type prefix: string + :param sensor_name: sensor type + :type sensor_name: string """ if prefix is None: prefix = 'sensor' Actor.__init__(self, carla_actor=carla_actor, parent=parent, communication=communication, prefix=prefix) + if sensor_name is None: + sensor_name = "Sensor" if ROS_VERSION == 2: - CompatibleNode.__init__(self, "sensor") + CompatibleNode.__init__(self, sensor_name) self.synchronous_mode = synchronous_mode self.queue = queue.Queue() From 8df4ac1634d016e28991949deffd048a665fe572 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 5 Jun 2020 16:46:41 +0200 Subject: [PATCH 129/627] Auto formatting --- carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py | 3 +-- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 3 +-- carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py | 3 +-- 3 files changed, 3 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index cef2709d..05293b4a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -53,5 +53,4 @@ def sensor_data_updated(self, collision_event): collision_msg.normal_impulse.y = collision_event.normal_impulse.y collision_msg.normal_impulse.z = collision_event.normal_impulse.z - self.publish_message( - self.get_topic_prefix(), collision_msg) + self.publish_message(self.get_topic_prefix(), collision_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index f0bf0730..e9c55114 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -51,5 +51,4 @@ def sensor_data_updated(self, carla_gnss_measurement): navsatfix_msg.latitude = carla_gnss_measurement.latitude navsatfix_msg.longitude = carla_gnss_measurement.longitude navsatfix_msg.altitude = carla_gnss_measurement.altitude - self.publish_message( - self.get_topic_prefix() + "/fix", navsatfix_msg) + self.publish_message(self.get_topic_prefix() + "/fix", navsatfix_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 5dc62fc3..b632d4b6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -50,5 +50,4 @@ def sensor_data_updated(self, lane_invasion_event): lane_invasion_msg.header = self.get_msg_header() for marking in lane_invasion_event.crossed_lane_markings: lane_invasion_msg.crossed_lane_markings.append(marking.type) - self.publish_message( - self.get_topic_prefix(), lane_invasion_msg) + self.publish_message(self.get_topic_prefix(), lane_invasion_msg) From d2179eb63843a701cb2b2f2e0761d18e5d145e20 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 5 Jun 2020 16:47:13 +0200 Subject: [PATCH 130/627] Uncomment and fix clock and tf_publish calls for ros 2 --- .../src/carla_ros_bridge/communication.py | 29 ++++++++++++------- 1 file changed, 19 insertions(+), 10 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index f5287e55..fe73cc6f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -55,8 +55,8 @@ def __init__(self): self.ros_timestamp = ros_timestamp() # needed? - # self.pub['clock'] = self.new_publisher(Clock, 'clock') - # self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100)) + self.pub['clock'] = self.new_publisher(Clock, 'clock') + self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100)) def send_msgs(self): """ @@ -64,12 +64,19 @@ def send_msgs(self): :return: """ + # prepare tf message - # tf_msg = TFMessage(self.tf_to_publish) - # try: - # self.pub['tf'].publish(tf_msg) - # except Exception as error: # pylint: disable=broad-except - # self.logwarn("Failed to publish message: {}".format(error)) + tf_msg = None + + if ROS_VERSION == 1: + tf_msg = TFMessage(self.tf_to_publish) + elif ROS_VERSION == 2: + tf_msg = TFMessage() + tf_msg.transforms = self.tf_to_publish + try: + self.pub['tf'].publish(tf_msg) + except Exception as error: # pylint: disable=broad-except + self.logwarn("Failed to publish message: {}".format(error)) for publisher, msg in self.msgs_to_publish: try: @@ -117,9 +124,11 @@ def update_clock(self, carla_timestamp): :type carla_timestamp: carla.Timestamp :return: """ - # self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_secs=True) - # self.publish_message('clock', Clock(self.ros_timestamp)) - pass + if ROS_VERSION == 1: + self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) + self.publish_message('clock', Clock(self.ros_timestamp)) + elif ROS_VERSION == 2: + self.publish_message('clock', Clock()) # removed argument in ros 2 (?) def get_current_ros_time(self): """ From 238ad3ef9ab1822645a76fd49dcf41f60e185405 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 5 Jun 2020 16:47:41 +0200 Subject: [PATCH 131/627] Make unregisteration of subscribers use compatibility node --- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 137fc04f..c81e12c6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -24,7 +24,7 @@ sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode + from ros_compatible_node import CompatibleNode, destroy_subscription else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -196,15 +196,15 @@ def destroy(self): :return: """ self.logdebug("Destroy Vehicle(id={})".format(self.get_id())) - self.control_subscriber.unregister() + destroy_subscription(self.control_subscriber) self.control_subscriber = None - self.enable_autopilot_subscriber.unregister() + destroy_subscription(self.enable_autopilot_subscriber) self.enable_autopilot_subscriber = None - self.twist_control_subscriber.unregister() + destroy_subscription(self.twist_control_subscriber) self.twist_control_subscriber = None - self.control_override_subscriber.unregister() + destroy_subscription(self.control_override_subscriber) self.control_override_subscriber = None - self.manual_control_subscriber.unregister() + destroy_subscription(self.manual_control_subscriber) self.manual_control_subscriber = None super(EgoVehicle, self).destroy() From 8ece1a09e0dae69daa0e90a13ed877a37337c28e Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 5 Jun 2020 17:52:00 +0200 Subject: [PATCH 132/627] Make ros_compatibility easily importable, pass down **kwargs to rclpy's Node --- ros_compatibility/__init__.py | 1 - ros_compatibility/setup.py | 22 ++++++++++--------- ros_compatibility/src/__init__.py | 0 .../src/ros_compatibility/__init__.py | 5 +---- .../ros_compatibility/ros_compatible_node.py | 13 +++++------ 5 files changed, 19 insertions(+), 22 deletions(-) delete mode 100644 ros_compatibility/__init__.py delete mode 100644 ros_compatibility/src/__init__.py diff --git a/ros_compatibility/__init__.py b/ros_compatibility/__init__.py deleted file mode 100644 index 0c1cfee4..00000000 --- a/ros_compatibility/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from ros_compatibility.src.ros_compatibility.ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/setup.py b/ros_compatibility/setup.py index 55754977..0adb896a 100644 --- a/ros_compatibility/setup.py +++ b/ros_compatibility/setup.py @@ -17,18 +17,19 @@ from setuptools import setup package_name = 'ros_compatibility' - setup( name=package_name, version='0.0.0', - packages=['src/' + package_name], - py_modules=[ - 'src.ros_compatibility.ros_compatible_node'], - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), - ], + packages=[package_name], + data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ('share/' + package_name, ['package.xml'])], + # py_modules=[ + # 'src.ros_compatibility.ros_compatible_node'], + # data_files=[ + # ('share/ament_index/resource_index/packages', + # ['resource/' + package_name]), + # ('share/' + package_name, ['package.xml']), + # ], install_requires=['setuptools'], zip_safe=True, maintainer='CARLA Simulator Team', @@ -38,7 +39,8 @@ tests_require=['pytest'], entry_points={ 'console_scripts': [ - 'ros_compatible_node = src.ros_compatibility.ros_compatible_node:main' + 'ros_compatible_node = ros_compatibility.ros_compatible_node:main' ], }, + package_dir={'': 'src'}, ) diff --git a/ros_compatibility/src/__init__.py b/ros_compatibility/src/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py index bd5614f4..5760b616 100644 --- a/ros_compatibility/src/ros_compatibility/__init__.py +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -1,4 +1 @@ -import os -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from ros_compatible_node import * \ No newline at end of file +from ros_compatibility.ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index eea97c92..858da94a 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -76,8 +76,7 @@ def create_subscriber(self, msg_type, topic, callback_group=None): if qos_profile is None: qos_profile = self.qos_profile - return rospy.Subscriber(topic, msg_type, - callback, queue_size=qos_profile.depth) + return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) def spin(self, executor=None): rospy.spin() @@ -98,7 +97,7 @@ def ros_timestamp(sec=0, nsec=0, from_sec=False): time = Time() if from_sec: time.sec = int(sec) - time.nanosec = int((sec - int(sec)) * 1000_000_000) + time.nanosec = int((sec - int(sec)) * 1000000000) else: time.sec = int(sec) time.nanosec = int(nsec) @@ -115,9 +114,9 @@ def destroy_subscription(subsription): class CompatibleNode(Node): - def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): super().__init__(node_name, allow_undeclared_parameters=True, - automatically_declare_parameters_from_overrides=True) + automatically_declare_parameters_from_overrides=True, **kwargs) if latch: self.qos_profile = QoSProfile( depth=queue_size, @@ -200,8 +199,8 @@ def shutdown(self): rclpy.shutdown() else: - raise NotImplementedError('Make sure you have valid ' + - 'ROS_VERSION env variable') + raise NotImplementedError('Make sure you have valid ROS_VERSION env variable.') + def main(): From db11c026d00e85adae68b278ee4c31c943163ac5 Mon Sep 17 00:00:00 2001 From: arkadiy-telegin <58264717+arkadiy-telegin@users.noreply.github.com> Date: Fri, 5 Jun 2020 17:54:22 +0200 Subject: [PATCH 133/627] Mirror __init__ signature in ROS1 --- ros_compatibility/src/ros_compatibility/ros_compatible_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 858da94a..5ce163fe 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -28,7 +28,7 @@ def __init__(self, depth=10, durability=None, **kwargs): self.latch = bool(durability) class CompatibleNode(object): - def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): if rospy_init: rospy.init_node(node_name, anonymous=True) self.qos_profile = QoSProfile(depth=queue_size, durability=latch) From f8eccac32bc12df8cc8ff5dc5a3007ed1fb17498 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Mon, 8 Jun 2020 12:14:26 +0200 Subject: [PATCH 134/627] Remove unused imported python ros client libraries by using compatiblenode methods --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 2588ab00..9d3cd938 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -214,7 +214,7 @@ def process_run_state(self): while not self.carla_control_queue.empty(): command = self.carla_control_queue.get() - while command is not None and not rospy.is_shutdown(): + while command is not None and self.ros_ok(): self.carla_run_state = command if self.carla_run_state == CarlaControl.PAUSE: @@ -552,8 +552,8 @@ def main(): parameters["ego_vehicle"] = {"role_name": role_name} print(parameters) - carla_bridge.loginfo("Trying to connect to {host}:{port}".format(host=parameters['host'], - port=parameters['port'])) + carla_bridge.loginfo("Trying to connect to {host}:{port}".format( + host=parameters['host'], port=parameters['port'])) try: carla_client = carla.Client(host=parameters['host'], port=parameters['port']) From 42876c2c13d865646034ac9ae7e9636ca3fb5708 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Mon, 8 Jun 2020 12:16:37 +0200 Subject: [PATCH 135/627] Remove unused ros python client libraries --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index b3a38605..224c22c2 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -13,11 +13,9 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy from tf import transformations from ros_compatibility import * elif ROS_VERSION == 2: - import rclpy # import cv2 import transformations # TODO: import ros_compatibilty From d881e46e50e245498f33ce14da0b05519489caa8 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Mon, 8 Jun 2020 12:17:20 +0200 Subject: [PATCH 136/627] Remove unused ros python client libraries --- .../src/carla_ros_bridge/carla_status_publisher.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 65219072..4f6bf281 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -14,7 +14,6 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy from ros_compatibility import CompatibleNode elif ROS_VERSION == 2: import rclpy @@ -24,8 +23,6 @@ # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from rclpy.node import Node - from rclpy import executors from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode else: From f5634f760a1cc61a59f20b402c166e4f148d7c6c Mon Sep 17 00:00:00 2001 From: sergimoya Date: Mon, 8 Jun 2020 12:17:43 +0200 Subject: [PATCH 137/627] Remove unused ros python client libraries --- carla_ros_bridge/src/carla_ros_bridge/communication.py | 5 ----- 1 file changed, 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index fe73cc6f..16c5e756 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -13,11 +13,9 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy from ros_compatibility import * latch = True elif ROS_VERSION == 2: - import rclpy from rclpy.qos import QoSDurabilityPolicy from rclpy.qos import QoSProfile import sys @@ -25,9 +23,6 @@ # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - import rclpy - from rclpy.node import Node - from rclpy import executors from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode, ros_timestamp latch = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL From 3d0fb9bc1975c2af9402e64280a1f013000fb9d1 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Mon, 8 Jun 2020 12:18:29 +0200 Subject: [PATCH 138/627] Remove unused ros python client libraries --- .../src/carla_ros_bridge/debug_helper.py | 19 ++++++++----------- 1 file changed, 8 insertions(+), 11 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 5797865a..dcf15b44 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -8,32 +8,28 @@ """ Class to draw marker """ +import carla +from visualization_msgs.msg import Marker, MarkerArray +import math import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy from tf.transformations import euler_from_quaternion from ros_compatibility import CompatibleNode elif ROS_VERSION == 2: - import rclpy from transformations.transformations import euler_from_quaternion import sys print(os.getcwd()) # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from rclpy.node import Node - from rclpy import executors from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode else: - raise NotImplementedError('Make sure you have valid ' + 'ROS_VERSION env variable') - -import math -from visualization_msgs.msg import Marker, MarkerArray -import carla + raise NotImplementedError( + 'Make sure you have valid ' + 'ROS_VERSION env variable') class DebugHelper(CompatibleNode): @@ -61,7 +57,7 @@ def destroy(self): :return: """ - rospy.logdebug("Destroy DebugHelper") + self.logdebug("Destroy DebugHelper") self.debug = None destroy_subscription(self.marker_subscriber) self.marker_subscriber = None @@ -90,7 +86,8 @@ def on_marker(self, marker_array): elif marker.type == Marker.CUBE: self.draw_box(marker, lifetime, color) else: - rospy.logwarn("Marker type '{}' not supported.".format(marker.type)) + self.logwarn( + "Marker type '{}' not supported.".format(marker.type)) def draw_arrow(self, marker, lifetime, color): """ From 6f02aca1da909d31e9fc4498902d202e942f4275 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Mon, 8 Jun 2020 12:19:06 +0200 Subject: [PATCH 139/627] Remove unused ros python client libraries --- carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index be23d5da..ce032745 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -13,24 +13,19 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy from ros_compatibility import * elif ROS_VERSION == 2: - import rclpy - from rclpy.qos import QoSDurabilityPolicy - from rclpy.qos import QoSProfile import sys print(os.getcwd()) # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from rclpy.node import Node - from rclpy import executors from rclpy.time import Time from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode else: - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") + raise NotImplementedError( + "Make sure you have a valid ROS_VERSION env variable set.") class PseudoActor(CompatibleNode): @@ -95,7 +90,7 @@ def get_msg_header(self, frame_id=None, timestamp=None): header.frame_id = self.get_prefix() if timestamp: if ROS_VERSION == 1: - header.stamp = rospy.Time.from_sec(timestamp) + header.stamp = self.ros_timestamp(sec=timestamp, from_sec=True) elif ROS_VERSION == 2: def ros_timestamp(sec=0): From 1f57f1e529f71301065d959d5323ddc6d707cce3 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Mon, 8 Jun 2020 12:23:39 +0200 Subject: [PATCH 140/627] Remove unused ros python client libraries --- .../src/carla_ros_bridge/sensor.py | 42 +++++++++---------- 1 file changed, 20 insertions(+), 22 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 8e9a7658..dbea1878 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -18,7 +18,6 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy from ros_compatibility import CompatibleNode elif ROS_VERSION == 2: import sys @@ -26,9 +25,6 @@ # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - import rclpy - from rclpy.node import Node - from rclpy import executors from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode else: @@ -115,13 +111,13 @@ def _callback_sensor_data(self, carla_sensor_data): :param carla_sensor_data: carla sensor data object :type carla_sensor_data: carla.SensorData """ - is_shutdown = None - if ROS_VERSION == 1: - is_shutdown = rospy.is_shutdown() - elif ROS_VERSION == 2: - is_shutdown = False # No is_shutdown equivalent in rclpy available without actually shutting down the node https://discourse.ros.org/t/mapping-between-rospy-and-rclpy/5737/2 + # is_shutdown = None + # if ROS_VERSION == 1: + # is_shutdown = rospy.is_shutdown() + # elif ROS_VERSION == 2: + # is_shutdown = False # No is_shutdown equivalent in rclpy available without actually shutting down the node https://discourse.ros.org/t/mapping-between-rospy-and-rclpy/5737/2 - if not is_shutdown: + if self.ros_ok(): if self.synchronous_mode: if self.sensor_tick_time: self.next_data_expected_time = carla_sensor_data.timestamp + \ @@ -142,19 +138,20 @@ def sensor_data_updated(self, carla_sensor_data): :param carla_sensor_data: carla sensor data object :type carla_sensor_data: carla.SensorData """ - raise NotImplementedError("This function has to be implemented by the derived classes") + raise NotImplementedError( + "This function has to be implemented by the derived classes") def _update_synchronous_event_sensor(self, frame): while True: try: carla_sensor_data = self.queue.get(block=False) if carla_sensor_data.frame != frame: - rospy.logwarn("{}({}): Received event for frame {}" - " (expected {}). Process it anyways.".format( - self.__class__.__name__, self.get_id(), - carla_sensor_data.frame, frame)) - rospy.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), - frame)) + self.logwarn("{}({}): Received event for frame {}" + " (expected {}). Process it anyways.".format( + self.__class__.__name__, self.get_id(), + carla_sensor_data.frame, frame)) + self.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), + frame)) self.publish_transform( self.get_ros_transform( trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) @@ -171,8 +168,8 @@ def _update_synchronous_sensor(self, frame, timestamp): try: carla_sensor_data = self.queue.get(timeout=1.0) if carla_sensor_data.frame == frame: - rospy.logdebug("{}({}): process {}".format(self.__class__.__name__, - self.get_id(), frame)) + self.logdebug("{}({}): process {}".format(self.__class__.__name__, + self.get_id(), frame)) self.publish_transform( self.get_ros_transform( trans.carla_transform_to_ros_transform( @@ -180,11 +177,12 @@ def _update_synchronous_sensor(self, frame, timestamp): self.sensor_data_updated(carla_sensor_data) return else: - rospy.logwarn("{}({}): skipping old frame {}, expected {}".format( + self.logwarn("{}({}): skipping old frame {}, expected {}".format( self.__class__.__name__, self.get_id(), carla_sensor_data.frame, frame)) except queue.Empty: - if not rospy.is_shutdown(): - rospy.logwarn("{}({}): Expected Frame {} not received".format( + # if not rospy.is_shutdown(): + if self.ros_ok(): + self.logwarn("{}({}): Expected Frame {} not received".format( self.__class__.__name__, self.get_id(), frame)) return From 5e52c4e556c5b8c91b2c559ee56de1aa69ba50f8 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 13:35:55 +0200 Subject: [PATCH 141/627] Fix use of ros_ok from compatible_node --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 6 +++--- carla_ros_bridge/src/carla_ros_bridge/sensor.py | 8 ++++---- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 9d3cd938..00b20ebe 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -50,7 +50,7 @@ if ROS_VERSION == 1: import rospy - from ros_compatibility import CompatibleNode + from ros_compatibility import CompatibleNode, ros_ok elif ROS_VERSION == 2: import sys print(os.getcwd()) @@ -61,7 +61,7 @@ from rclpy.node import Node from rclpy import executors from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode + from ros_compatible_node import CompatibleNode, ros_ok else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -214,7 +214,7 @@ def process_run_state(self): while not self.carla_control_queue.empty(): command = self.carla_control_queue.get() - while command is not None and self.ros_ok(): + while command is not None and ros_ok(): self.carla_run_state = command if self.carla_run_state == CarlaControl.PAUSE: diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index dbea1878..1e1db8ad 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -18,7 +18,7 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from ros_compatibility import CompatibleNode + from ros_compatibility import CompatibleNode, ros_ok elif ROS_VERSION == 2: import sys print(os.getcwd()) @@ -26,7 +26,7 @@ sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode + from ros_compatible_node import CompatibleNode, ros_ok else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -117,7 +117,7 @@ def _callback_sensor_data(self, carla_sensor_data): # elif ROS_VERSION == 2: # is_shutdown = False # No is_shutdown equivalent in rclpy available without actually shutting down the node https://discourse.ros.org/t/mapping-between-rospy-and-rclpy/5737/2 - if self.ros_ok(): + if ros_ok(): if self.synchronous_mode: if self.sensor_tick_time: self.next_data_expected_time = carla_sensor_data.timestamp + \ @@ -181,7 +181,7 @@ def _update_synchronous_sensor(self, frame, timestamp): self.__class__.__name__, self.get_id(), carla_sensor_data.frame, frame)) except queue.Empty: # if not rospy.is_shutdown(): - if self.ros_ok(): + if ros_ok(): self.logwarn("{}({}): Expected Frame {} not received".format( self.__class__.__name__, self.get_id(), frame)) return From 63aaa1963849467e6e478db423286056f462c2d6 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 14:18:10 +0200 Subject: [PATCH 142/627] Add missing import from compatibility node in ros1 --- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index c81e12c6..65cdd8c3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -16,7 +16,7 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from ros_compatibility import CompatibleNode + from ros_compatibility import CompatibleNode, destroy_subscription elif ROS_VERSION == 2: import sys print(os.getcwd()) From 06341e3bf37d90c8dffe6f0925bae65e98907301 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:16:18 +0200 Subject: [PATCH 143/627] Add callback group to subscribers and publishers --- .../carla_manual_control.py | 48 +++++++++++-------- .../src/carla_ros_bridge/bridge.py | 12 +++-- .../src/carla_ros_bridge/communication.py | 10 +++- .../src/carla_ros_bridge/ego_vehicle.py | 20 +++++--- 4 files changed, 60 insertions(+), 30 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index f9fdcc4c..f39dcc29 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -121,19 +121,22 @@ def __init__(self, role_name, hud): self.hud = hud self.role_name = role_name - if ROS_VERSION == 2: + if ROS_VERSION == 1: + self.callback_group = None + elif ROS_VERSION == 2: self.callback_group = ReentrantCallbackGroup() self.image_subscriber = self.create_subscriber( Image, "/carla/{}/camera/rgb/view/image_color".format(self.role_name), - self.on_view_image) + self.on_view_image, callback_group=self.callback_group) self.collision_subscriber = self.create_subscriber( - CarlaCollisionEvent, "/carla/{}/collision".format(self.role_name), self.on_collision) + CarlaCollisionEvent, "/carla/{}/collision".format(self.role_name), + self.on_collision, callback_group=self.callback_group) self.lane_invasion_subscriber = self.create_subscriber( CarlaLaneInvasionEvent, "/carla/{}/lane_invasion".format(self.role_name), - self.on_lane_invasion) + self.on_lane_invasion, callback_group=self.callback_group) def on_collision(self, data): """ @@ -211,31 +214,34 @@ def __init__(self, role_name, hud): self._control = CarlaEgoVehicleControl() self._steer_cache = 0.0 - if ROS_VERSION == 2: + if ROS_VERSION == 1: + self.callback_group = None + elif ROS_VERSION == 2: self.callback_group = ReentrantCallbackGroup() - fast_qos = QoSProfile(depth=1) - fast_latched_qos = QoSProfile(depth=1, durability=latch_on) # imported from ros_compat. + fast_qos = QoSProfile(depth=10) + fast_latched_qos = QoSProfile(depth=10) # imported from ros_compat. self.vehicle_control_manual_override_publisher = \ self.new_publisher(Bool, "/carla/{}/vehicle_control_manual_override".format(self.role_name), - qos_profile=fast_latched_qos) + qos_profile=fast_latched_qos, callback_group=self.callback_group) self.vehicle_control_manual_override = False self.auto_pilot_enable_publisher = \ self.new_publisher(Bool, "/carla/{}/enable_autopilot".format(self.role_name), - qos_profile=fast_qos) + qos_profile=fast_qos, callback_group=self.callback_group) self.vehicle_control_publisher = \ self.new_publisher(CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), - qos_profile=fast_qos) + qos_profile=fast_qos, callback_group=self.callback_group) self.carla_status_subscriber = self.create_subscriber(CarlaStatus, "/carla/status", - self._on_new_carla_frame) + self._on_new_carla_frame, + callback_group=self.callback_group) self.set_autopilot(self._autopilot_enabled) @@ -367,6 +373,7 @@ def __init__(self, role_name, width, height): if ROS_VERSION == 1: self.tf_listener = tf.TransformListener() + self.callback_group = None elif ROS_VERSION == 2: self.tf_listener_node = rclpy.create_node("tf_listener") self.tfBuffer = tf2_ros.Buffer() @@ -376,35 +383,38 @@ def __init__(self, role_name, width, height): self.vehicle_status_subscriber = self.create_subscriber( CarlaEgoVehicleStatus, "/carla/{}/vehicle_status".format(self.role_name), - self.vehicle_status_updated) + self.vehicle_status_updated, callback_group=self.callback_group) self.vehicle_status_subscriber = self.create_subscriber( CarlaEgoVehicleStatus, "/carla/{}/vehicle_status".format(self.role_name), - self.vehicle_status_updated) + self.vehicle_status_updated, callback_group=self.callback_group) self.vehicle_info = CarlaEgoVehicleInfo() self.vehicle_info_subscriber = self.create_subscriber( CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(self.role_name), - self.vehicle_info_updated) + self.vehicle_info_updated, callback_group=self.callback_group) self.latitude = 0 self.longitude = 0 self.manual_control = False self.gnss_subscriber = self.create_subscriber( - NavSatFix, "/carla/{}/gnss/gnss1/fix".format(self.role_name), self.gnss_updated) + NavSatFix, "/carla/{}/gnss/gnss1/fix".format(self.role_name), self.gnss_updated, + callback_group=self.callback_group) self.manual_control_subscriber = self.create_subscriber( Bool, "/carla/{}/vehicle_control_manual_override".format(self.role_name), - self.manual_control_override_updated) + self.manual_control_override_updated, callback_group=self.callback_group) self.carla_status = CarlaStatus() self.start_frame = None self.status_subscriber = self.create_subscriber(CarlaStatus, "/carla/status", - self.carla_status_updated) + self.carla_status_updated, + callback_group=self.callback_group) if ROS_VERSION == 2: - self.clock_subscriber = self.create_subscriber(Clock, "/clock", - self.clock_status_updated) + self.clock_subscriber = self.create_subscriber(Time, "/clock", + self.clock_status_updated, + callback_group=self.callback_group) def __del__(self): if ROS_VERSION == 1: diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 00b20ebe..15111ddb 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -60,6 +60,7 @@ import rclpy from rclpy.node import Node from rclpy import executors + from rclpy.callback_groups import ReentrantCallbackGroup from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode, ros_ok else: @@ -90,6 +91,11 @@ def initialize_bridge(self, carla_world, params): self.pseudo_actors = [] self.carla_world = carla_world + if ROS_VERSION == 1: + self.callback_group = None + elif ROS_VERSION == 2: + self.callback_group = ReentrantCallbackGroup() + self.synchronous_mode_update_thread = None self.shutdown = Event() # set carla world settings @@ -125,8 +131,8 @@ def initialize_bridge(self, carla_world, params): self.carla_run_state = CarlaControl.PLAY self.carla_control_subscriber = \ - self.create_subscriber(CarlaControl, "/carla/control", None, - qos_profile=lambda control: self.carla_control_queue.put(control.command)) + self.create_subscriber(CarlaControl, "/carla/control", + lambda control: self.carla_control_queue.put(control.command), callback_group=self.callback_group) self.synchronous_mode_update_thread = Thread(target=self._synchronous_mode_update) self.synchronous_mode_update_thread.start() @@ -150,7 +156,7 @@ def initialize_bridge(self, carla_world, params): self.carla_weather_subscriber = \ self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", - self.on_weather_changed) + self.on_weather_changed, callback_group=self.callback_group) # add world info self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, communication=self.comm)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 16c5e756..fa721509 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -18,6 +18,7 @@ elif ROS_VERSION == 2: from rclpy.qos import QoSDurabilityPolicy from rclpy.qos import QoSProfile + from rclpy.callback_groups import ReentrantCallbackGroup import sys print(os.getcwd()) # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) @@ -49,6 +50,11 @@ def __init__(self): self.subscribers = {} self.ros_timestamp = ros_timestamp() + if ROS_VERSION == 1: + self.callback_group = None + elif ROS_VERSION == 2: + self.callback_group = ReentrantCallbackGroup() + # needed? self.pub['clock'] = self.new_publisher(Clock, 'clock') self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100)) @@ -105,10 +111,10 @@ def publish_message(self, topic, msg, is_latched=False): if topic not in self.pub: if is_latched: qos_profile = QoSProfile(depth=10, durability=latch) - self.pub[topic] = self.new_publisher(type(msg), topic, qos_profile=qos_profile) + self.pub[topic] = self.new_publisher(type(msg), topic, qos_profile=qos_profile, callback_group=self.callback_group) else: # Use default QoS profile. - self.pub[topic] = self.new_publisher(type(msg), topic) + self.pub[topic] = self.new_publisher(type(msg), topic, callback_group=self.callback_group) self.msgs_to_publish.append((self.pub[topic], msg)) def update_clock(self, carla_timestamp): diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 65cdd8c3..a881218f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -25,6 +25,7 @@ '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode, destroy_subscription + from rclpy.callback_groups import ReentrantCallbackGroup else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -60,8 +61,11 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c """ Vehicle.__init__(self, carla_actor=carla_actor, parent=parent, communication=communication, prefix=carla_actor.attributes.get('role_name')) - if ROS_VERSION == 2: + if ROS_VERSION == 1: + self.callback_group = None + elif ROS_VERSION == 2: CompatibleNode.__init__(self, "ego_vehicle") + self.callback_group = ReentrantCallbackGroup() self.vehicle_info_published = False self.vehicle_control_override = False @@ -70,25 +74,29 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c self.control_subscriber = self.create_subscriber( CarlaEgoVehicleControl, self.get_topic_prefix() + "/vehicle_control_cmd", - lambda data: self.control_command_updated(data, manual_override=False)) + lambda data: self.control_command_updated(data, manual_override=False), + callback_group=self.callback_group) self.manual_control_subscriber = self.create_subscriber( CarlaEgoVehicleControl, self.get_topic_prefix() + "/vehicle_control_cmd_manual", - lambda data: self.control_command_updated(data, manual_override=True)) + lambda data: self.control_command_updated(data, manual_override=True), + callback_group=self.callback_group) self.control_override_subscriber = self.create_subscriber( Bool, self.get_topic_prefix() + "/vehicle_control_manual_override", - self.control_command_override) + self.control_command_override, callback_group=self.callback_group) self.enable_autopilot_subscriber = self.create_subscriber( Bool, - self.get_topic_prefix() + "/enable_autopilot", self.enable_autopilot_updated) + self.get_topic_prefix() + "/enable_autopilot", self.enable_autopilot_updated, + callback_group=self.callback_group) self.twist_control_subscriber = self.create_subscriber( Twist, - self.get_topic_prefix() + "/twist_cmd", self.twist_command_updated) + self.get_topic_prefix() + "/twist_cmd", self.twist_command_updated, + callback_group=self.callback_group) def get_marker_color(self): """ From a8b4e2b0fe909fdf1950278ccb45ff20b036fc4a Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:16:47 +0200 Subject: [PATCH 144/627] Cast key to bool --- .../src/carla_manual_control/carla_manual_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index f39dcc29..71e483cc 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -338,7 +338,7 @@ def _parse_vehicle_keys(self, keys, milliseconds): self._steer_cache = min(0.7, max(-0.7, self._steer_cache)) self._control.steer = round(self._steer_cache, 1) self._control.brake = 1.0 if keys[K_DOWN] or keys[K_s] else 0.0 - self._control.hand_brake = keys[K_SPACE] + self._control.hand_brake = bool(keys[K_SPACE]) @staticmethod def _is_quit_shortcut(key): From 932464001de9de12bcd1511a9827fc48898728e3 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:17:22 +0200 Subject: [PATCH 145/627] Manually transform quaternion to euler --- .../carla_manual_control.py | 20 ++++++++++++++++++- 1 file changed, 19 insertions(+), 1 deletion(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 71e483cc..39edff96 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -473,6 +473,24 @@ def gnss_updated(self, data): self.latitude = data.latitude self.longitude = data.longitude self.update_info_text() + + @staticmethod + def quaternion_to_euler(x, y, z, w): + + import math + t0 = +2.0 * (w * x + y * z) + t1 = +1.0 - 2.0 * (x * x + y * y) + X = math.degrees(math.atan2(t0, t1)) + + t2 = +2.0 * (w * y - z * x) + t2 = +1.0 if t2 > +1.0 else t2 + t2 = -1.0 if t2 < -1.0 else t2 + Y = math.degrees(math.asin(t2)) + + t3 = +2.0 * (w * z + x * y) + t4 = +1.0 - 2.0 * (y * y + z * z) + Z = math.degrees(math.atan2(t3, t4)) + return X, Y, Z def update_info_text(self): """ @@ -495,7 +513,7 @@ def update_info_text(self): q = self.tfBuffer.lookup_transform('map', self.role_name, when) quaternion = q.transform.rotation position = q.transform.translation - _, __, yaw = euler_from_quaternion(quaternion) + _, __, yaw = self.quaternion_to_euler(quaternion.x, quaternion.y, quaternion.z, quaternion.w) yaw = -math.degrees(yaw) x = position.x y = -position.y From 4cf2bb8c32e6f0597d7482f75789d62d526a8804 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:17:55 +0200 Subject: [PATCH 146/627] Fix import line --- carla_ros_bridge/src/carla_ros_bridge/communication.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index fa721509..ff4f32cf 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -16,8 +16,7 @@ from ros_compatibility import * latch = True elif ROS_VERSION == 2: - from rclpy.qos import QoSDurabilityPolicy - from rclpy.qos import QoSProfile + from rclpy.qos import QoSDurabilityPolicy, QoSProfile from rclpy.callback_groups import ReentrantCallbackGroup import sys print(os.getcwd()) From 23c0732e89ee52b46dbc8d87314be06a9fdc2888 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:18:26 +0200 Subject: [PATCH 147/627] Use Time instead of Clock in ros2 --- carla_ros_bridge/src/carla_ros_bridge/communication.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index ff4f32cf..45fd43f8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -26,6 +26,7 @@ from ament_index_python.packages import get_package_share_directory from ros_compatible_node import CompatibleNode, ros_timestamp latch = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL + from builtin_interfaces.msg import Time else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -51,12 +52,13 @@ def __init__(self): if ROS_VERSION == 1: self.callback_group = None + self.pub['clock'] = self.new_publisher(Clock, 'clock', qos_profile=QoSProfile(depth=10), callback_group=self.callback_group) elif ROS_VERSION == 2: self.callback_group = ReentrantCallbackGroup() + self.pub['clock'] = self.new_publisher(Time, 'clock', qos_profile=QoSProfile(depth=10), callback_group=self.callback_group) # needed? - self.pub['clock'] = self.new_publisher(Clock, 'clock') - self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100)) + self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100), callback_group=self.callback_group) def send_msgs(self): """ @@ -124,11 +126,11 @@ def update_clock(self, carla_timestamp): :type carla_timestamp: carla.Timestamp :return: """ + self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) if ROS_VERSION == 1: - self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) self.publish_message('clock', Clock(self.ros_timestamp)) elif ROS_VERSION == 2: - self.publish_message('clock', Clock()) # removed argument in ros 2 (?) + self.publish_message('clock', self.ros_timestamp) def get_current_ros_time(self): """ From 0131f01dee35e6df1611185fb7cd4d35cc8a4d41 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:19:11 +0200 Subject: [PATCH 148/627] Change clock.get_time to clock_time --- .../src/carla_manual_control/carla_manual_control.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 39edff96..b67bead4 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -433,8 +433,8 @@ def tick(self, clock): """ self._notifications.tick(clock) - def clock_status_updated(self, clock): - self.time = clock.get_time() + def clock_status_updated(self, clock_time): + self.time = clock_time def carla_status_updated(self, data): """ From 5795caeb98baa97d913b8d203ff92cd8e7418549 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:57:28 +0200 Subject: [PATCH 149/627] Add empty resource file --- carla_twist_to_control/resource/carla_twist_to_control | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 carla_twist_to_control/resource/carla_twist_to_control diff --git a/carla_twist_to_control/resource/carla_twist_to_control b/carla_twist_to_control/resource/carla_twist_to_control new file mode 100644 index 00000000..e69de29b From fc26a5ba6f39afa5f5cca51d4ba09805cbf3cfc6 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:57:43 +0200 Subject: [PATCH 150/627] Add fb-compatible CMakeLists.txt --- carla_twist_to_control/CMakeLists.txt | 48 +++++++++++++++++---------- 1 file changed, 31 insertions(+), 17 deletions(-) diff --git a/carla_twist_to_control/CMakeLists.txt b/carla_twist_to_control/CMakeLists.txt index f219cafc..def8635e 100644 --- a/carla_twist_to_control/CMakeLists.txt +++ b/carla_twist_to_control/CMakeLists.txt @@ -1,25 +1,39 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_twist_to_control) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if (${ROS_VERSION} EQUAL 1) -roslaunch_add_file_check(launch) + find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch + ) -catkin_package( - CATKIN_DEPENDS - rospy -) + catkin_python_setup() -catkin_install_python(PROGRAMS - src/carla_twist_to_control/carla_twist_to_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) + roslaunch_add_file_check(launch) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + catkin_package( + CATKIN_DEPENDS + rospy + ) + + catkin_install_python(PROGRAMS + src/carla_twist_to_control/carla_twist_to_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + ) +endif() + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + +endif() From 4984f4035eb123abf4511a87e108596297531c22 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:57:55 +0200 Subject: [PATCH 151/627] Add fb-compatible package.xml --- carla_twist_to_control/package.xml | 24 ++++++++++++++++-------- 1 file changed, 16 insertions(+), 8 deletions(-) diff --git a/carla_twist_to_control/package.xml b/carla_twist_to_control/package.xml index fc9890a7..1b670ef7 100644 --- a/carla_twist_to_control/package.xml +++ b/carla_twist_to_control/package.xml @@ -1,17 +1,25 @@ - + carla_twist_to_control 0.0.0 The carla_twist_to_control package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy - carla_msgs - geometry_msgs + + + rclpy + + + catkin + rospy + roslaunch + rospy + rospy + carla_msgs + geometry_msgs + + catkin + ament_python From 0a597136abc80d7bf75015657156af36d4a33f8d Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:58:07 +0200 Subject: [PATCH 152/627] Add fb-compatible setup.py --- carla_twist_to_control/setup.py | 42 +++++++++++++++++++++++++++------ 1 file changed, 35 insertions(+), 7 deletions(-) diff --git a/carla_twist_to_control/setup.py b/carla_twist_to_control/setup.py index b62eb811..65816235 100644 --- a/carla_twist_to_control/setup.py +++ b/carla_twist_to_control/setup.py @@ -2,12 +2,40 @@ Setup for carla_twist_to_control """ -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) -d = generate_distutils_setup( - packages=['carla_twist_to_control'], - package_dir={'': 'src'} -) +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -setup(**d) + d = generate_distutils_setup( + packages=['carla_twist_to_control'], + package_dir={'': 'src'} + ) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_twist_to_control' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA twist to control for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': ['twist_to_control = carla_twist_to_control.carla_twist_to_control:main'], + }, + package_dir={'': 'src'}, + ) From 2d287fd87655c168ff8451ea67b9281ac567c254 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 8 Jun 2020 17:58:51 +0200 Subject: [PATCH 153/627] Initial port of twist-to-control; Add ROSExceptions to compatibility-node --- .../carla_twist_to_control.py | 64 ++++++++++++++----- .../ros_compatibility/ros_compatible_node.py | 12 ++++ 2 files changed, 59 insertions(+), 17 deletions(-) diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index 00ebb477..5c7e297c 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -10,12 +10,25 @@ use max wheel steer angle """ import sys -import rospy from geometry_msgs.msg import Twist from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo +import os +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -class TwistToVehicleControl(object): # pylint: disable=too-few-public-methods +if ROS_VERSION == 1: + import rospy + from ros_compatibility import CompatibleNode, ros_ok, ROSException, ROSInterruptException +elif ROS_VERSION == 2: + import rclpy + # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) + sys.path.append(os.getcwd() + + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') + from ament_index_python.packages import get_package_share_directory + from ros_compatible_node import CompatibleNode, ros_ok, ROSException, ROSInterruptException + + +class TwistToVehicleControl(CompatibleNode): # pylint: disable=too-few-public-methods """ receive geometry_nav_msgs::Twist and publish carla_msgs::CarlaEgoVehicleControl @@ -24,29 +37,32 @@ class TwistToVehicleControl(object): # pylint: disable=too-few-public-methods MAX_LON_ACCELERATION = 10 - def __init__(self, role_name): + def __init__(self, rospy_init=True): """ Constructor """ - rospy.loginfo("Wait for vehicle info...") + super(TwistToVehicleControl, self).__init__("twist_to_control", rospy_init=rospy_init) + + def initialize_twist_to_control(self, role_name): + self.loginfo("Wait for vehicle info...") try: vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) - except rospy.ROSInterruptException as e: - if not rospy.is_shutdown(): + except ROSInterruptException as e: + if ros_ok: raise e else: sys.exit(0) if not vehicle_info.wheels: # pylint: disable=no-member - rospy.logerr("Cannot determine max steering angle: Vehicle has no wheels.") + self.logerr("Cannot determine max steering angle: Vehicle has no wheels.") sys.exit(1) self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle # pylint: disable=no-member if not self.max_steering_angle: - rospy.logerr("Cannot determine max steering angle: Value is %s", + self.logerr("Cannot determine max steering angle: Value is %s", self.max_steering_angle) sys.exit(1) - rospy.loginfo("Vehicle info received. Max steering angle=%s", + self.loginfo("Vehicle info received. Max steering angle=%s", self.max_steering_angle) rospy.Subscriber("/carla/{}/twist".format(role_name), Twist, self.twist_received) @@ -81,9 +97,9 @@ def twist_received(self, twist): self.max_steering_angle try: self.pub.publish(control) - except rospy.ROSException as e: - if not rospy.is_shutdown(): - rospy.logwarn("Error while publishing control: {}".format(e)) + except ROSException as e: + if ros_ok(): + self.logwarn("Error while publishing control: {}".format(e)) def main(): @@ -92,15 +108,29 @@ def main(): :return: """ - rospy.init_node('convert_twist_to_vehicle_control', anonymous=True) - role_name = rospy.get_param("~role_name", "ego_vehicle") + # rospy.init_node('convert_twist_to_vehicle_control', anonymous=True) + + role_name = None + twist_to_vehicle_control = None + + if ROS_VERSION == 1: + twist_to_vehicle_control = TwistToVehicleControl() + role_name = rospy.get_param("~role_name", "ego_vehicle") + elif ROS_VERSION == 2: + rclpy.init(args=None) + twist_to_vehicle_control = TwistToVehicleControl() + executor = rclpy.executors.MultiThreadedExecutor() + init_node = rclpy.create_node("twist_to_control") # TODO maybe this is initializing the node twice? + executor.add_node(init_node) + role_name = twist_to_vehicle_control.get_param("role_name", "ego_vehicle") + + twist_to_vehicle_control.initialize_twist_to_control(role_name) - twist_to_vehicle_control = TwistToVehicleControl(role_name) try: - rospy.spin() + twist_to_vehicle_control.spin() finally: + twist_to_vehicle_control.loginfo("Done, deleting twist to control") del twist_to_vehicle_control - rospy.loginfo("Done") if __name__ == "__main__": diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index b0140bec..55235a94 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -21,6 +21,12 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.unregister() + class ROSException(rospy.ROSException): + pass + + class ROSInterruptException(rospy.ROSInterruptException): + pass + class QoSProfile(): def __init__(self, depth=10, durability=None, **kwargs): @@ -108,6 +114,12 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.destroy() + class ROSException(Exception): + pass + + class ROSInterruptException(rclpy.ROSInterruptException): + pass + class CompatibleNode(Node): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): From 54d38278be099f0d0c547a6a3977db6f9b0f3940 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 09:35:50 +0200 Subject: [PATCH 154/627] Fix imports and destroying nodes --- .../src/carla_ros_bridge/ego_vehicle.py | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 137fc04f..92f77889 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -19,12 +19,8 @@ from ros_compatibility import CompatibleNode elif ROS_VERSION == 2: import sys - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode + from ros_compatibility import * else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -196,15 +192,15 @@ def destroy(self): :return: """ self.logdebug("Destroy Vehicle(id={})".format(self.get_id())) - self.control_subscriber.unregister() + destroy_subscription(self.control_subscriber) self.control_subscriber = None - self.enable_autopilot_subscriber.unregister() + destroy_subscription(self.enable_autopilot_subscriber) self.enable_autopilot_subscriber = None - self.twist_control_subscriber.unregister() + destroy_subscription(self.twist_control_subscriber) self.twist_control_subscriber = None - self.control_override_subscriber.unregister() + destroy_subscription(self.control_override_subscriber) self.control_override_subscriber = None - self.manual_control_subscriber.unregister() + destroy_subscription(self.manual_control_subscriber) self.manual_control_subscriber = None super(EgoVehicle, self).destroy() From c3467922d2530628b24c854a9046e015674fd041 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 15:49:52 +0200 Subject: [PATCH 155/627] Fix imports bridge.py --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 15111ddb..ace091a9 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -50,22 +50,14 @@ if ROS_VERSION == 1: import rospy - from ros_compatibility import CompatibleNode, ros_ok elif ROS_VERSION == 2: - import sys - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') import rclpy - from rclpy.node import Node - from rclpy import executors from rclpy.callback_groups import ReentrantCallbackGroup - from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode, ros_ok else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +from ros_compatibility import * + class CarlaRosBridge(CompatibleNode): """ From e7e47120c11f53f1754eb2e324aaaadd028c2f61 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 15:51:18 +0200 Subject: [PATCH 156/627] Fix imports camera.py --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 224c22c2..df1d1441 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -14,14 +14,13 @@ if ROS_VERSION == 1: from tf import transformations - from ros_compatibility import * elif ROS_VERSION == 2: - # import cv2 import transformations - # TODO: import ros_compatibilty else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +from ros_compatibility import * + from abc import abstractmethod import math From b7ea806b574995cd0776d2ca9b2e5e203aa8edbb Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 15:53:01 +0200 Subject: [PATCH 157/627] Fix imports carla_status_publisher.py --- .../carla_status_publisher.py | 19 ++++++------------- 1 file changed, 6 insertions(+), 13 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 4f6bf281..e09c43b7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -13,21 +13,14 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from ros_compatibility import CompatibleNode -elif ROS_VERSION == 2: - import rclpy - from rclpy.callback_groups import ReentrantCallbackGroup - import sys - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode -else: +if ROS_VERSION not in (1, 2): raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +if ROS_VERSION == 2: + from rclpy.callback_groups import ReentrantCallbackGroup + +from ros_compatibility import * + from carla_msgs.msg import CarlaStatus From 1d368c769382160c2dcab0d2f4f9613e53a632ae Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 9 Jun 2020 16:14:35 +0200 Subject: [PATCH 158/627] Add missing compatibility call --- carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 9897510f..757f79fa 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -228,7 +228,7 @@ def setup_sensors(self, sensors): try: sensor_name = str(sensor_spec['type']) + "/" + str(sensor_spec['id']) if sensor_name in sensor_names: - rospy.logfatal( + self.logfatal( "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) raise NameError( From a1b55cd9c6b7e00d389f9f709ce380cbb43ac3cf Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 9 Jun 2020 16:16:10 +0200 Subject: [PATCH 159/627] Call executor spin and have executor as member to add egovehicle node --- .../src/carla_ros_bridge/bridge.py | 21 ++++++++++++------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 15111ddb..2a993c8e 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -74,7 +74,7 @@ class CarlaRosBridge(CompatibleNode): CARLA_VERSION = "0.9.9" - def __init__(self, rospy_init=True): + def __init__(self, rospy_init=True, executor=None): """ Constructor @@ -84,6 +84,7 @@ def __init__(self, rospy_init=True): :type params: dict """ super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) + self.executor = executor def initialize_bridge(self, carla_world, params): self.parameters = params @@ -409,6 +410,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m pseudo_actors.append( ObjectSensor(parent=actor, communication=self.comm, actor_list=self.actors, filtered_id=carla_actor.id)) + if ROS_VERSION == 2: + self.executor.add_node(actor) else: actor = Vehicle(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("sensor"): @@ -468,7 +471,7 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m return actor - def run(self): + def run(self, executor=None): """ Run the bridge functionality. @@ -478,9 +481,10 @@ def run(self): """ if ROS_VERSION == 1: rospy.on_shutdown(self.on_shutdown) + self.spin() elif ROS_VERSION == 2: rclpy.get_default_context().on_shutdown(self.on_shutdown) - self.spin() + executor.spin() def on_shutdown(self): """ @@ -532,6 +536,7 @@ def main(): carla_bridge = None carla_world = None carla_client = None + executor = None parameters = {} if ROS_VERSION == 1: carla_bridge = CarlaRosBridge() @@ -540,10 +545,10 @@ def main(): elif ROS_VERSION == 2: rclpy.init(args=None) - carla_bridge = CarlaRosBridge() - executor = rclpy.executors.MultiThreadedExecutor() - init_node = rclpy.create_node("init_ros_bridge") - executor.add_node(init_node) + executor = rclpy.executors.MultiThreadedExecutor(num_threads=12) + carla_bridge = CarlaRosBridge(executor=executor) + # init_node = rclpy.create_node("init_ros_bridge") + executor.add_node(carla_bridge) parameters['host'] = carla_bridge.get_param('carla.host', 'localhost') parameters['port'] = carla_bridge.get_param('carla.port', 2000) @@ -596,7 +601,7 @@ def main(): carla_world.tick() carla_bridge.initialize_bridge(carla_client.get_world(), parameters) - carla_bridge.run() + carla_bridge.run(executor=executor) except (IOError, RuntimeError) as e: carla_bridge.logerr("Error: {}".format(e)) finally: From 07909f513d49522f7ff211e8ccc6407b199a7937 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 9 Jun 2020 16:17:06 +0200 Subject: [PATCH 160/627] Explicitly call parent class init --- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index a881218f..c5319f7d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -187,7 +187,7 @@ def update(self, frame, timestamp): :return: """ self.send_vehicle_msgs() - super(EgoVehicle, self).update(frame, timestamp) + Vehicle.update(self, frame, timestamp) no_rotation = Transform() no_rotation.rotation.x = 1.0 self.publish_transform( @@ -214,7 +214,7 @@ def destroy(self): self.control_override_subscriber = None destroy_subscription(self.manual_control_subscriber) self.manual_control_subscriber = None - super(EgoVehicle, self).destroy() + Vehicle.destroy(self) def twist_command_updated(self, twist): """ From 453e6981712adae818b5cf0a08d821539e041250 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:19:48 +0200 Subject: [PATCH 161/627] Fix imports communication.py, optimize code --- .../src/carla_ros_bridge/communication.py | 32 +++++++------------ 1 file changed, 11 insertions(+), 21 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 45fd43f8..934df472 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -12,24 +12,14 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from ros_compatibility import * - latch = True -elif ROS_VERSION == 2: - from rclpy.qos import QoSDurabilityPolicy, QoSProfile +if ROS_VERSION not in (1, 2): + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") + +if ROS_VERSION == 2: from rclpy.callback_groups import ReentrantCallbackGroup - import sys - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode, ros_timestamp - latch = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL from builtin_interfaces.msg import Time -else: - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +from ros_compatibility import * from rosgraph_msgs.msg import Clock from tf2_msgs.msg import TFMessage @@ -52,13 +42,13 @@ def __init__(self): if ROS_VERSION == 1: self.callback_group = None - self.pub['clock'] = self.new_publisher(Clock, 'clock', qos_profile=QoSProfile(depth=10), callback_group=self.callback_group) + self.pub['clock'] = self.new_publisher(Clock, 'clock') elif ROS_VERSION == 2: self.callback_group = ReentrantCallbackGroup() - self.pub['clock'] = self.new_publisher(Time, 'clock', qos_profile=QoSProfile(depth=10), callback_group=self.callback_group) + self.pub['clock'] = self.new_publisher(Time, 'clock') # needed? - self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100), callback_group=self.callback_group) + self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100)) def send_msgs(self): """ @@ -111,11 +101,11 @@ def publish_message(self, topic, msg, is_latched=False): else: if topic not in self.pub: if is_latched: - qos_profile = QoSProfile(depth=10, durability=latch) - self.pub[topic] = self.new_publisher(type(msg), topic, qos_profile=qos_profile, callback_group=self.callback_group) + latched_profile = QoSProfile(depth=10, durability=latch) + self.pub[topic] = self.new_publisher(type(msg), topic, qos_profile=latched_profile) else: # Use default QoS profile. - self.pub[topic] = self.new_publisher(type(msg), topic, callback_group=self.callback_group) + self.pub[topic] = self.new_publisher(type(msg), topic) self.msgs_to_publish.append((self.pub[topic], msg)) def update_clock(self, carla_timestamp): From 04d2995a0192031ecb19bc1cfc436a2c01b81ef3 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:21:08 +0200 Subject: [PATCH 162/627] Fix imports debug_helper.py --- carla_ros_bridge/src/carla_ros_bridge/debug_helper.py | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index dcf15b44..2348a7fe 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -17,20 +17,14 @@ if ROS_VERSION == 1: from tf.transformations import euler_from_quaternion - from ros_compatibility import CompatibleNode elif ROS_VERSION == 2: from transformations.transformations import euler_from_quaternion - import sys - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode else: raise NotImplementedError( 'Make sure you have valid ' + 'ROS_VERSION env variable') +from ros_compatibility import * + class DebugHelper(CompatibleNode): """ From 6f09c38e6bf43127331c0dd3463848a731a1e63e Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:23:50 +0200 Subject: [PATCH 163/627] Fix imports ego_vehicle.py, optimize code --- .../src/carla_ros_bridge/ego_vehicle.py | 31 ++++++------------- 1 file changed, 10 insertions(+), 21 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index a881218f..c38eee5b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -15,20 +15,13 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from ros_compatibility import CompatibleNode, destroy_subscription -elif ROS_VERSION == 2: - import sys - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode, destroy_subscription - from rclpy.callback_groups import ReentrantCallbackGroup -else: +if ROS_VERSION not in (1, 2): raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +if ROS_VERSION == 2: + from rclpy.callback_groups import ReentrantCallbackGroup + +from ros_compatibility import * from std_msgs.msg import ColorRGBA from std_msgs.msg import Bool from geometry_msgs.msg import Twist, Transform @@ -74,29 +67,25 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c self.control_subscriber = self.create_subscriber( CarlaEgoVehicleControl, self.get_topic_prefix() + "/vehicle_control_cmd", - lambda data: self.control_command_updated(data, manual_override=False), - callback_group=self.callback_group) + lambda data: self.control_command_updated(data, manual_override=False)) self.manual_control_subscriber = self.create_subscriber( CarlaEgoVehicleControl, self.get_topic_prefix() + "/vehicle_control_cmd_manual", - lambda data: self.control_command_updated(data, manual_override=True), - callback_group=self.callback_group) + lambda data: self.control_command_updated(data, manual_override=True)) self.control_override_subscriber = self.create_subscriber( Bool, self.get_topic_prefix() + "/vehicle_control_manual_override", - self.control_command_override, callback_group=self.callback_group) + self.control_command_override) self.enable_autopilot_subscriber = self.create_subscriber( Bool, - self.get_topic_prefix() + "/enable_autopilot", self.enable_autopilot_updated, - callback_group=self.callback_group) + self.get_topic_prefix() + "/enable_autopilot", self.enable_autopilot_updated) self.twist_control_subscriber = self.create_subscriber( Twist, - self.get_topic_prefix() + "/twist_cmd", self.twist_command_updated, - callback_group=self.callback_group) + self.get_topic_prefix() + "/twist_cmd", self.twist_command_updated) def get_marker_color(self): """ From 5ce26816608e0ac25b0c1cce94f352e4d0e25c64 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:24:46 +0200 Subject: [PATCH 164/627] Add check for invalid ROS_VERSION in imu.py --- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index aee457c4..2494894b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -15,6 +15,8 @@ from tf.transformations import quaternion_from_euler elif ROS_VERSION == 2: from transformations.transformations import quaternion_from_euler +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") from sensor_msgs.msg import Imu From bacd62adf8000c85bd92b6611086d551508c5f4e Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:25:23 +0200 Subject: [PATCH 165/627] Add check for invalid ROS_VERSION in lidar.py --- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index e40159ff..00fe1500 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -23,6 +23,8 @@ from tf.transformations import euler_from_quaternion, quaternion_from_euler elif ROS_VERSION == 2: from transformations.transformations import euler_from_quaternion, quaternion_from_euler +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") from sensor_msgs.msg import PointCloud2, PointField From 7d9d0ca90ba0b8669d3848647e6af0cb84b4d76c Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:29:00 +0200 Subject: [PATCH 166/627] Fix imports, use ros_compatibility for timestamps --- .../src/carla_ros_bridge/pseudo_actor.py | 35 ++++--------------- 1 file changed, 6 insertions(+), 29 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index ce032745..2c7a0e9b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -12,20 +12,11 @@ from std_msgs.msg import Header import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from ros_compatibility import * -elif ROS_VERSION == 2: - import sys - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from rclpy.time import Time - from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode -else: - raise NotImplementedError( - "Make sure you have a valid ROS_VERSION env variable set.") + +if ROS_VERSION not in (1, 2): + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") + +from ros_compatibility import * class PseudoActor(CompatibleNode): @@ -89,21 +80,7 @@ def get_msg_header(self, frame_id=None, timestamp=None): else: header.frame_id = self.get_prefix() if timestamp: - if ROS_VERSION == 1: - header.stamp = self.ros_timestamp(sec=timestamp, from_sec=True) - elif ROS_VERSION == 2: - - def ros_timestamp(sec=0): - from builtin_interfaces.msg import Time - time = Time() - time.sec = int(sec) - time.nanosec = int((sec - int(sec)) * 1000000000) - return time - - header.stamp = ros_timestamp(timestamp) - else: - raise NotImplementedError( - "Make sure you have a valid ROS_VERSION env variable set.") + header.stamp = self.ros_timestamp(sec=timestamp, from_sec=True) else: header.stamp = self.communication.get_current_ros_time() return header From fde60b035870bde42dd38b3367ace659a1556158 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:31:56 +0200 Subject: [PATCH 167/627] Optimize imports and code in sensor.py --- .../src/carla_ros_bridge/sensor.py | 22 +++---------------- 1 file changed, 3 insertions(+), 19 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 1e1db8ad..d0e9979b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -17,17 +17,7 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from ros_compatibility import CompatibleNode, ros_ok -elif ROS_VERSION == 2: - import sys - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode, ros_ok -else: +if ROS_VERSION not in (1, 2): raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") from carla_ros_bridge.actor import Actor @@ -73,8 +63,8 @@ def __init__( prefix=prefix) if sensor_name is None: sensor_name = "Sensor" - if ROS_VERSION == 2: - CompatibleNode.__init__(self, sensor_name) + + CompatibleNode.__init__(self, sensor_name, rospy_init=False) self.synchronous_mode = synchronous_mode self.queue = queue.Queue() @@ -111,12 +101,6 @@ def _callback_sensor_data(self, carla_sensor_data): :param carla_sensor_data: carla sensor data object :type carla_sensor_data: carla.SensorData """ - # is_shutdown = None - # if ROS_VERSION == 1: - # is_shutdown = rospy.is_shutdown() - # elif ROS_VERSION == 2: - # is_shutdown = False # No is_shutdown equivalent in rclpy available without actually shutting down the node https://discourse.ros.org/t/mapping-between-rospy-and-rclpy/5737/2 - if ros_ok(): if self.synchronous_mode: if self.sensor_tick_time: From 8a92b391b1ec68714031c3be5578179a913e0b80 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 9 Jun 2020 16:32:08 +0200 Subject: [PATCH 168/627] Change iteritems to items in for loop --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 2a993c8e..5417981c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -250,7 +250,7 @@ def _synchronous_mode_update(self): # fill list of available ego vehicles self._expected_ego_vehicle_control_command_ids = [] with self._expected_ego_vehicle_control_command_ids_lock: - for actor_id, actor in self.actors.iteritems(): + for actor_id, actor in self.actors.items(): if isinstance(actor, EgoVehicle): self._expected_ego_vehicle_control_command_ids.append(actor_id) From d83e4d907c9cb374eddfd14dfc8147401463ee18 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 9 Jun 2020 16:33:02 +0200 Subject: [PATCH 169/627] Enable synchronous mode as default --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 5417981c..02e1fd00 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -553,7 +553,7 @@ def main(): parameters['host'] = carla_bridge.get_param('carla.host', 'localhost') parameters['port'] = carla_bridge.get_param('carla.port', 2000) parameters['timeout'] = carla_bridge.get_param('carla.timeout', 2) - parameters['synchronous_mode'] = carla_bridge.get_param('carla.synchronous_mode', False) + parameters['synchronous_mode'] = carla_bridge.get_param('carla.synchronous_mode', True) parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( 'carla.synchronous_mode_wait_for_vehicle_control_command', True) parameters['fixed_delta_seconds'] = carla_bridge.get_param('carla.fixed_delta_seconds', From b570aedc619a620c211d82b07ea2d7eebdac936f Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:33:35 +0200 Subject: [PATCH 170/627] Optimize code in ego_vehicle.py --- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index c38eee5b..1a5f9b67 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -54,12 +54,14 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c """ Vehicle.__init__(self, carla_actor=carla_actor, parent=parent, communication=communication, prefix=carla_actor.attributes.get('role_name')) + if ROS_VERSION == 1: self.callback_group = None elif ROS_VERSION == 2: - CompatibleNode.__init__(self, "ego_vehicle") self.callback_group = ReentrantCallbackGroup() + CompatibleNode.__init__(self, "ego_vehicle", rospy_init=False) + self.vehicle_info_published = False self.vehicle_control_override = False self._vehicle_control_applied_callback = vehicle_control_applied_callback From affe163612c41152c948ad786eb68a2679561ef2 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:36:22 +0200 Subject: [PATCH 171/627] Use ros_compatibility to destroy subscription in walker.py --- carla_ros_bridge/src/carla_ros_bridge/walker.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index 5f96d7af..a31e935c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -16,6 +16,8 @@ from carla_msgs.msg import CarlaWalkerControl from carla import WalkerControl +from ros_compatibility import destroy_subscription + class Walker(TrafficParticipant): """ @@ -57,7 +59,7 @@ def destroy(self): :return: """ self.logdebug("Destroy Walker(id={})".format(self.get_id())) - self.control_subscriber.unregister() + destroy_subscription(self.control_subscriber) self.control_subscriber = None super(Walker, self).destroy() From bcaa6595e2b82c64f1c79674f923af0b79791167 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 16:39:17 +0200 Subject: [PATCH 172/627] Use ros_compatibility to destroy subscription in bridge.py --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index ace091a9..581fe61b 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -172,7 +172,7 @@ def destroy(self): self.shutdown("") self.debug_helper.destroy() self.shutdown.set() - self.carla_weather_subscriber.unregister() + destroy_subscription(self.carla_weather_subscriber) self.carla_control_queue.put(CarlaControl.STEP_ONCE) if not self.carla_settings.synchronous_mode: if self.on_tick_id: From d9219a3892dd48fa5f511dd76bacec63bb10b500 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 9 Jun 2020 16:51:16 +0200 Subject: [PATCH 173/627] Use better imports, use correct ros_timestamp in both ros1 and ros2 --- .../src/carla_ros_bridge/communication.py | 2 +- .../src/carla_ros_bridge/pseudo_actor.py | 20 +++---------------- 2 files changed, 4 insertions(+), 18 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 45fd43f8..871ebdac 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -13,7 +13,7 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from ros_compatibility import * + from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile latch = True elif ROS_VERSION == 2: from rclpy.qos import QoSDurabilityPolicy, QoSProfile diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index ce032745..839ecb14 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -13,7 +13,7 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from ros_compatibility import * + from ros_compatibility import CompatibleNode, ros_timestamp elif ROS_VERSION == 2: import sys print(os.getcwd()) @@ -22,7 +22,7 @@ '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') from rclpy.time import Time from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode + from ros_compatible_node import CompatibleNode, ros_timestamp else: raise NotImplementedError( "Make sure you have a valid ROS_VERSION env variable set.") @@ -89,21 +89,7 @@ def get_msg_header(self, frame_id=None, timestamp=None): else: header.frame_id = self.get_prefix() if timestamp: - if ROS_VERSION == 1: - header.stamp = self.ros_timestamp(sec=timestamp, from_sec=True) - elif ROS_VERSION == 2: - - def ros_timestamp(sec=0): - from builtin_interfaces.msg import Time - time = Time() - time.sec = int(sec) - time.nanosec = int((sec - int(sec)) * 1000000000) - return time - - header.stamp = ros_timestamp(timestamp) - else: - raise NotImplementedError( - "Make sure you have a valid ROS_VERSION env variable set.") + header.stamp = ros_timestamp(sec=timestamp, from_sec=True) else: header.stamp = self.communication.get_current_ros_time() return header From b71b2cdff9bd599c0780591d3f567e15a772dbd8 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 17:09:40 +0200 Subject: [PATCH 174/627] fix naming on latch --- carla_ros_bridge/src/carla_ros_bridge/communication.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 934df472..ff17755f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -101,7 +101,7 @@ def publish_message(self, topic, msg, is_latched=False): else: if topic not in self.pub: if is_latched: - latched_profile = QoSProfile(depth=10, durability=latch) + latched_profile = QoSProfile(depth=10, durability=latch_on) self.pub[topic] = self.new_publisher(type(msg), topic, qos_profile=latched_profile) else: # Use default QoS profile. From c4272128399161084912e2d01ec5626caf7ae577 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 17:37:47 +0200 Subject: [PATCH 175/627] fix imports in carla_manual_control.py --- .../carla_manual_control.py | 20 ++++--------------- 1 file changed, 4 insertions(+), 16 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index b67bead4..53628633 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -34,26 +34,18 @@ ROS_VERSION = int(os.environ['ROS_VERSION']) -latch_on = None - if ROS_VERSION == 1: import rospy from tf import LookupException from tf import ConnectivityException from tf import ExtrapolationException import tf - from ros_compatibility import CompatibleNode, QoSProfile - - latch_on = True + from ros_compatibility import QoSProfile elif ROS_VERSION == 2: - # TODO: Optimise ros2 imports import rclpy from rclpy.callback_groups import ReentrantCallbackGroup - from transformations import euler_from_quaternion import transformations as tf - import cv2 - import time from tf2_ros import LookupException from tf2_ros import ConnectivityException from tf2_ros import ExtrapolationException @@ -61,13 +53,9 @@ from rclpy.qos import QoSProfile, QoSDurabilityPolicy from threading import Thread, Lock, Event from builtin_interfaces.msg import Time - from rosgraph_msgs.msg import Clock - import sys - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from ros_compatible_node import CompatibleNode - latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL +from ros_compatibility import CompatibleNode, latch_on + from std_msgs.msg import Bool from sensor_msgs.msg import NavSatFix @@ -220,7 +208,7 @@ def __init__(self, role_name, hud): self.callback_group = ReentrantCallbackGroup() fast_qos = QoSProfile(depth=10) - fast_latched_qos = QoSProfile(depth=10) # imported from ros_compat. + fast_latched_qos = QoSProfile(depth=10, durability=latch_on) # imported from ros_compat. self.vehicle_control_manual_override_publisher = \ self.new_publisher(Bool, From 142d9ae1fa345fdff613a57aea327a2f45c9295e Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Tue, 9 Jun 2020 17:39:49 +0200 Subject: [PATCH 176/627] Add ROS_VERSION validity check --- .../src/carla_manual_control/carla_manual_control.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 53628633..f622bd47 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -53,6 +53,8 @@ from rclpy.qos import QoSProfile, QoSDurabilityPolicy from threading import Thread, Lock, Event from builtin_interfaces.msg import Time +else: + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") from ros_compatibility import CompatibleNode, latch_on From 5b3ae9872a6d225a54157b54659acb6a5016b4ab Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 9 Jun 2020 17:48:45 +0200 Subject: [PATCH 177/627] Adjust import of compatibility node --- carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/communication.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/sensor.py | 2 ++ 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 757f79fa..00f6a690 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -41,7 +41,7 @@ from rclpy import executors from ament_index_python.packages import get_package_share_directory from transformations.transformations import euler_from_quaternion, quaternion_from_euler - from ros_compatible_node import CompatibleNode + from ros_compatibility import CompatibleNode from geometry_msgs.msg import PoseWithCovarianceStamped, Pose from carla_msgs.msg import CarlaStatus, CarlaWorldInfo diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 302f9622..b96bc682 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -19,7 +19,7 @@ from rclpy.callback_groups import ReentrantCallbackGroup from builtin_interfaces.msg import Time -from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile +from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile, latch_on from rosgraph_msgs.msg import Clock from tf2_msgs.msg import TFMessage diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index d0e9979b..8ec71056 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -20,6 +20,8 @@ if ROS_VERSION not in (1, 2): raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +from ros_compatibility import CompatibleNode, ros_ok + from carla_ros_bridge.actor import Actor import carla_ros_bridge.transforms as trans From 2ce892670b1319f475bfe9964bc7c18f0b59327f Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 9 Jun 2020 17:49:20 +0200 Subject: [PATCH 178/627] Use transforms3d library instead of deprecated amnd numerically instable transformations --- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 3 ++- carla_ros_bridge/src/carla_ros_bridge/camera.py | 13 +++++++++---- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 4 +++- 3 files changed, 14 insertions(+), 6 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 00f6a690..4426c2c6 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -40,7 +40,8 @@ from rclpy.node import Node from rclpy import executors from ament_index_python.packages import get_package_share_directory - from transformations.transformations import euler_from_quaternion, quaternion_from_euler + from transforms3d.euler import euler2quat as quaternion_from_euler + from transforms3d.euler import quat2euler as euler_from_quaternion from ros_compatibility import CompatibleNode from geometry_msgs.msg import PoseWithCovarianceStamped, Pose diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index df1d1441..9f088a7d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -13,9 +13,10 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from tf import transformations + from tf.transformations import quaternion_from_matrix, quaternion_multiply elif ROS_VERSION == 2: - import transformations + from transforms3d.quaternions import mat2quat as quaternion_from_matrix + from transforms3d.quaternions import qmult as quaternion_multiply else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -136,9 +137,13 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): tf_msg = super(Camera, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation quat = [rotation.x, rotation.y, rotation.z, rotation.w] - quat_swap = transformations.quaternion_from_matrix([[0, 0, 1, 0], [-1, 0, 0, 0], + if ROS_VERSION == 1: + quat_swap = quaternion_from_matrix([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) - quat = transformations.quaternion_multiply(quat, quat_swap) + elif ROS_VERSION == 2: + quat_swap = quaternion_from_matrix(numpy.asarray([numpy.asarray([0, 0, 1]), numpy.asarray([-1, 0, 0]), + numpy.asarray([0, -1, 0])])) + quat = quaternion_multiply(quat, quat_swap) tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion(quat) return tf_msg diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 00fe1500..61f12348 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -22,7 +22,9 @@ if ROS_VERSION == 1: from tf.transformations import euler_from_quaternion, quaternion_from_euler elif ROS_VERSION == 2: - from transformations.transformations import euler_from_quaternion, quaternion_from_euler + from transforms3d.euler import euler2quat as quaternion_from_euler + from transforms3d.euler import quat2euler as euler_from_quaternion + # from transformations.transformations import euler_from_quaternion, quaternion_from_euler else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") From 48f299a136a91cb13c88b1040bf58c193302b13c Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 10 Jun 2020 13:18:49 +0200 Subject: [PATCH 179/627] Change topic for ros2 as rviz had problems --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 9f088a7d..a5f4796f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -121,7 +121,10 @@ def sensor_data_updated(self, carla_image): cam_info = self._camera_info cam_info.header = img_msg.header - self.publish_message(self.get_topic_prefix() + '/camera_info', cam_info) + if ROS_VERSION == 1: + self.publish_message(self.get_topic_prefix() + '/camera_info', cam_info) + elif ROS_VERSION == 2: + self.publish_message(self.get_topic_prefix() + '/' + self.get_image_topic_name() + '/camera_info', cam_info) self.publish_message(self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): From 86c13781812625ef56f50ef2ac653c5c61398c2e Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Wed, 10 Jun 2020 15:21:49 +0200 Subject: [PATCH 180/627] Add mixins to skip building (yet) unsupported packages --- mixin/index.yaml | 2 ++ mixin/skip.mixin | 21 +++++++++++++++++++++ 2 files changed, 23 insertions(+) create mode 100644 mixin/index.yaml create mode 100644 mixin/skip.mixin diff --git a/mixin/index.yaml b/mixin/index.yaml new file mode 100644 index 00000000..d8313acf --- /dev/null +++ b/mixin/index.yaml @@ -0,0 +1,2 @@ +mixin: + - skip.mixin \ No newline at end of file diff --git a/mixin/skip.mixin b/mixin/skip.mixin new file mode 100644 index 00000000..c5b103d2 --- /dev/null +++ b/mixin/skip.mixin @@ -0,0 +1,21 @@ +{ + "build": { + "skip": { + "packages-skip": ["carla_ackermann_control", + "carla_ad_agent", + "carla_ad_demo", + "carla_infrastructure", + "carla_ros_scenario_runner", + "carla_ros_scenario_runner_types", + "carla_spectator_camera", + "carla_walker_agent", + "carla_waypoint_publisher", + "carla_waypoint_types", + "pcl_recorder", + "rqt_carla_control", + "rviz_carla_plugin", + "carla_twist_to_control" + ], + } + } +} \ No newline at end of file From c68a6677731b6f4147dd062bf86579193c8301df Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Wed, 10 Jun 2020 15:54:49 +0200 Subject: [PATCH 181/627] Update package.xml files to reflect used dependencies --- carla_ego_vehicle/package.xml | 5 ++- .../carla_ego_vehicle/carla_ego_vehicle.py | 11 ++---- carla_manual_control/package.xml | 11 ++++-- carla_ros_bridge/package.xml | 36 +++++++++++-------- 4 files changed, 35 insertions(+), 28 deletions(-) diff --git a/carla_ego_vehicle/package.xml b/carla_ego_vehicle/package.xml index 9f5a4d3e..81d23f80 100644 --- a/carla_ego_vehicle/package.xml +++ b/carla_ego_vehicle/package.xml @@ -7,8 +7,12 @@ CARLA Simulator Team MIT + carla_msgs + ros_compatibility + rclpy + ament_python catkin @@ -16,7 +20,6 @@ roslaunch rospy rospy - std_msgs topic_tools diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 4426c2c6..859bc838 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -27,22 +27,15 @@ if ROS_VERSION == 1: import rospy from tf.transformations import euler_from_quaternion, quaternion_from_euler - from ros_compatibility import CompatibleNode - elif ROS_VERSION == 2: import sys - import os - print(os.getcwd()) - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') import rclpy - from rclpy.node import Node - from rclpy import executors from ament_index_python.packages import get_package_share_directory from transforms3d.euler import euler2quat as quaternion_from_euler from transforms3d.euler import quat2euler as euler_from_quaternion - from ros_compatibility import CompatibleNode + +from ros_compatibility import CompatibleNode from geometry_msgs.msg import PoseWithCovarianceStamped, Pose from carla_msgs.msg import CarlaStatus, CarlaWorldInfo diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index da4f535b..89327e55 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -6,8 +6,15 @@ CARLA Simulator Team MIT + carla_msgs + sensor_msgs + std_msgs + ros_compatibility + rclpy + ament_python + tf2_ros catkin @@ -15,9 +22,7 @@ roslaunch rospy rospy - carla_msgs - sensor_msgs - std_msgs + tf diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index fadbc555..b1d72afc 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -6,31 +6,37 @@ CARLA Simulator Team MIT + std_msgs + geometry_msgs + derived_object_msgs + shape_msgs + nav_msgs + tf2_msgs + rosgraph_msgs + ainstein_radar_msgs + sensor_msgs + visualization_msgs + carla_msgs + carla_ego_vehicle + carla_manual_control + cv_bridge + python-transforms3d-pip + ros_compatibility + rclpy + ament_python + tf2_ros + rviz2 catkin roslaunch - ainstein_radar_msgs rospy - sensor_msgs - visualization_msgs tf tf2 - rviz - geometry_msgs - std_msgs rosbag_storage - derived_object_msgs - shape_msgs - nav_msgs - tf2_msgs - rosgraph_msgs - cv_bridge - carla_msgs - carla_ego_vehicle - carla_manual_control + rviz catkin From 2eb04ff5a3c19e5635662053b7adf6879e1dfb68 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Wed, 10 Jun 2020 15:59:27 +0200 Subject: [PATCH 182/627] Port twist-to-control, not tested in ros2 yet --- carla_twist_to_control/CMakeLists.txt | 1 - carla_twist_to_control/setup.cfg | 4 ++ .../carla_twist_to_control.py | 64 ++++++++++++------- .../ros_compatibility/ros_compatible_node.py | 3 +- 4 files changed, 47 insertions(+), 25 deletions(-) create mode 100644 carla_twist_to_control/setup.cfg diff --git a/carla_twist_to_control/CMakeLists.txt b/carla_twist_to_control/CMakeLists.txt index def8635e..b7a9cd9c 100644 --- a/carla_twist_to_control/CMakeLists.txt +++ b/carla_twist_to_control/CMakeLists.txt @@ -28,7 +28,6 @@ if (${ROS_VERSION} EQUAL 1) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch ) -endif() elseif (${ROS_VERSION} EQUAL 2) find_package(ament_cmake REQUIRED) diff --git a/carla_twist_to_control/setup.cfg b/carla_twist_to_control/setup.cfg new file mode 100644 index 00000000..e19fecd4 --- /dev/null +++ b/carla_twist_to_control/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_twist_to_control +[install] +install-scripts=$base/lib/carla_twist_to_control diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index 5c7e297c..e18d91e1 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -18,14 +18,10 @@ if ROS_VERSION == 1: import rospy - from ros_compatibility import CompatibleNode, ros_ok, ROSException, ROSInterruptException elif ROS_VERSION == 2: import rclpy - # TODO: fix setup.py to easily import CompatibleNode (as in ROS1) - sys.path.append(os.getcwd() + - '/install/ros_compatibility/lib/python3.6/site-packages/src/ros_compatibility') - from ament_index_python.packages import get_package_share_directory - from ros_compatible_node import CompatibleNode, ros_ok, ROSException, ROSInterruptException + +from ros_compatibility import CompatibleNode, ros_ok, ROSException, ROSInterruptException class TwistToVehicleControl(CompatibleNode): # pylint: disable=too-few-public-methods @@ -42,17 +38,41 @@ def __init__(self, rospy_init=True): Constructor """ super(TwistToVehicleControl, self).__init__("twist_to_control", rospy_init=rospy_init) + self.max_steering_angle = None def initialize_twist_to_control(self, role_name): - self.loginfo("Wait for vehicle info...") - try: - vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), - CarlaEgoVehicleInfo) - except ROSInterruptException as e: - if ros_ok: - raise e - else: - sys.exit(0) + if ROS_VERSION == 1: + self.loginfo("Wait for vehicle info...") + try: + vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), + CarlaEgoVehicleInfo) + except ROSInterruptException as e: + if ros_ok: + raise e + else: + sys.exit(0) + + self.create_subscriber(CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(role_name), self.update_vehicle_info) + + # if not vehicle_info.wheels: # pylint: disable=no-member + # self.logerr("Cannot determine max steering angle: Vehicle has no wheels.") + # sys.exit(1) + + # self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle # pylint: disable=no-member + # if not self.max_steering_angle: + # self.logerr("Cannot determine max steering angle: Value is %s", + # self.max_steering_angle) + # sys.exit(1) + # self.loginfo("Vehicle info received. Max steering angle={}".format(self.max_steering_angle)) + + self.create_subscriber(Twist, "/carla/{}/twist".format(role_name), self.twist_received) + + self.pub = self.new_publisher(CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name)) + + def update_vehicle_info(self, vehicle_info): + """ + callback to receive ego-vehicle info + """ if not vehicle_info.wheels: # pylint: disable=no-member self.logerr("Cannot determine max steering angle: Vehicle has no wheels.") sys.exit(1) @@ -60,20 +80,18 @@ def initialize_twist_to_control(self, role_name): self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle # pylint: disable=no-member if not self.max_steering_angle: self.logerr("Cannot determine max steering angle: Value is %s", - self.max_steering_angle) + self.max_steering_angle) sys.exit(1) - self.loginfo("Vehicle info received. Max steering angle=%s", - self.max_steering_angle) - - rospy.Subscriber("/carla/{}/twist".format(role_name), Twist, self.twist_received) - - self.pub = rospy.Publisher("/carla/{}/vehicle_control_cmd".format(role_name), - CarlaEgoVehicleControl, queue_size=1) + self.loginfo("Vehicle info received. Max steering angle={}".format(self.max_steering_angle)) def twist_received(self, twist): """ receive twist and convert to carla vehicle control """ + if self.max_steering_angle is None: + self.logwarn("Did not yet receive vehicle info.") + return + control = CarlaEgoVehicleControl() if twist == Twist(): # stop diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 88d4b367..7b599ab9 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -82,6 +82,7 @@ def shutdown(self): rospy.signal_shutdown("") elif ROS_VERSION == 2: + from rclpy.exceptions import ROSInterruptException from rclpy.node import Node from rclpy import Parameter from rclpy.qos import QoSProfile, QoSDurabilityPolicy @@ -112,7 +113,7 @@ def destroy_subscription(subsription): class ROSException(Exception): pass - class ROSInterruptException(rclpy.ROSInterruptException): + class ROSInterruptException(ROSInterruptException): pass class CompatibleNode(Node): From 5b096ffdfa0aa993fbdd3cd9c59975cbd33055b2 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Wed, 10 Jun 2020 17:22:44 +0200 Subject: [PATCH 183/627] Fix twist in ROS2 --- .../src/carla_ros_bridge/ego_vehicle.py | 10 ++++++++-- .../carla_twist_to_control.py | 14 +------------- mixin/skip.mixin | 1 - 3 files changed, 9 insertions(+), 16 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 8d7bdd34..eecc9fb2 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -62,6 +62,7 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c CompatibleNode.__init__(self, "ego_vehicle", rospy_init=False) + self.vehicle_info = None self.vehicle_info_published = False self.vehicle_control_override = False self._vehicle_control_applied_callback = vehicle_control_applied_callback @@ -126,6 +127,7 @@ def send_vehicle_msgs(self): self.publish_message(self.get_topic_prefix() + "/vehicle_status", vehicle_status) # only send vehicle once (in latched-mode) + # TODO: Make latching work reliably in ROS2 if not self.vehicle_info_published: self.vehicle_info_published = True vehicle_info = CarlaEgoVehicleInfo() @@ -166,8 +168,12 @@ def send_vehicle_msgs(self): vehicle_info.center_of_mass.x = vehicle_physics.center_of_mass.x vehicle_info.center_of_mass.y = vehicle_physics.center_of_mass.y vehicle_info.center_of_mass.z = vehicle_physics.center_of_mass.z - - self.publish_message(self.get_topic_prefix() + "/vehicle_info", vehicle_info, True) + self.vehicle_info = vehicle_info + self.publish_message(self.get_topic_prefix() + "/vehicle_info", + vehicle_info, is_latched=True) + if ROS_VERSION == 2: + self.publish_message(self.get_topic_prefix() + "/vehicle_info", + self.vehicle_info, is_latched=True) def update(self, frame, timestamp): """ diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index e18d91e1..561105c7 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -54,17 +54,6 @@ def initialize_twist_to_control(self, role_name): self.create_subscriber(CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(role_name), self.update_vehicle_info) - # if not vehicle_info.wheels: # pylint: disable=no-member - # self.logerr("Cannot determine max steering angle: Vehicle has no wheels.") - # sys.exit(1) - - # self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle # pylint: disable=no-member - # if not self.max_steering_angle: - # self.logerr("Cannot determine max steering angle: Value is %s", - # self.max_steering_angle) - # sys.exit(1) - # self.loginfo("Vehicle info received. Max steering angle={}".format(self.max_steering_angle)) - self.create_subscriber(Twist, "/carla/{}/twist".format(role_name), self.twist_received) self.pub = self.new_publisher(CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name)) @@ -138,8 +127,7 @@ def main(): rclpy.init(args=None) twist_to_vehicle_control = TwistToVehicleControl() executor = rclpy.executors.MultiThreadedExecutor() - init_node = rclpy.create_node("twist_to_control") # TODO maybe this is initializing the node twice? - executor.add_node(init_node) + executor.add_node(twist_to_vehicle_control) role_name = twist_to_vehicle_control.get_param("role_name", "ego_vehicle") twist_to_vehicle_control.initialize_twist_to_control(role_name) diff --git a/mixin/skip.mixin b/mixin/skip.mixin index c5b103d2..ebc70708 100644 --- a/mixin/skip.mixin +++ b/mixin/skip.mixin @@ -14,7 +14,6 @@ "pcl_recorder", "rqt_carla_control", "rviz_carla_plugin", - "carla_twist_to_control" ], } } From 699586dbf9328f0d90d078d6fa3cd3a39484c7de Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Mon, 4 May 2020 17:33:44 +0200 Subject: [PATCH 184/627] remove duplicated script --- CreateROSbridgeDebian.sh | 119 --------------------------------------- 1 file changed, 119 deletions(-) delete mode 100644 CreateROSbridgeDebian.sh diff --git a/CreateROSbridgeDebian.sh b/CreateROSbridgeDebian.sh deleted file mode 100644 index 7b820a90..00000000 --- a/CreateROSbridgeDebian.sh +++ /dev/null @@ -1,119 +0,0 @@ -#!/bin/sh - -#This script builds debian package for CARLA ROS Bridge -#Tested with Ubuntu 14.04, 16.04, 18.04 and 19.10 - -sudo apt-get install build-essential dh-make - -#Adding maintainer name -DEBFULLNAME=Carla\ Simulator\ Team -export DEBFULLNAME - -#carla-ros-bridge github repository -ROS_BRIDGE_GIT=https://github.com/carla-simulator/ros-bridge.git - -mkdir -p carla-ros-debian/carla-ros-bridge/catkin_ws/src -mkdir -p carla-ros-debian/carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ - -cd carla-ros-debian/carla-ros-bridge - -#cloning carla-ros-bridge git repository -git clone ${ROS_BRIDGE_GIT} -rm -r ros-bridge/carla_msgs -cp -a ros-bridge/* catkin_ws/src/ - -cd catkin_ws - -source /opt/ros/$(rosversion -d)/setup.bash - -#installing required dependency packages to build catkin_make -sudo apt install ros-$(rosversion -d)-ainstein-radar-msgs ros-$(rosversion -d)-derived-object-msgs \ -ros-$(rosversion -d)-ackermann-msgs ros-$(rosversion -d)-carla-msgs ros-$(rosversion -d)-pcl-conversions \ -ros-$(rosversion -d)-rviz ros-$(rosversion -d)-rqt ros-$(rosversion -d)-pcl-ros - -catkin_make install - -cp -r install ../../carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ - -cd ../../carla-ros-bridge-$(rosversion -d)-0.9.8/ -mv carla-ros-bridge/install carla-ros-bridge/$(rosversion -d) - -rm Makefile - -#Making debian package to install Carla-ros-bridge in /opt folder -cat >> Makefile <> control < -Build-Depends: debhelper (>= 9) -Standards-Version:0.9.7 -Homepage: https://github.com/carla-simulator/ros-bridge - -Package: carla-ros-bridge-$(rosversion -d) -Architecture: amd64 -Depends: ros-$(rosversion -d)-carla-msgs, - ros-$(rosversion -d)-roslaunch, - ros-$(rosversion -d)-catkin, - ros-$(rosversion -d)-rospy, - ros-$(rosversion -d)-nav-msgs, - ros-$(rosversion -d)-ackermann-msgs, - ros-$(rosversion -d)-std-msgs, - ros-$(rosversion -d)-dynamic-reconfigure, - ros-$(rosversion -d)-topic-tools, - ros-$(rosversion -d)-sensor-msgs, - ros-$(rosversion -d)-message-runtime, - ros-$(rosversion -d)-geometry-msgs, - ros-$(rosversion -d)-message-generation, - ros-$(rosversion -d)-ainstein-radar-msgs, - ros-$(rosversion -d)-visualization-msgs, - ros-$(rosversion -d)-tf, - ros-$(rosversion -d)-tf2, - ros-$(rosversion -d)-rviz, - ros-$(rosversion -d)-cv-bridge, - ros-$(rosversion -d)-rosbag-storage, - ros-$(rosversion -d)-derived-object-msgs, - ros-$(rosversion -d)-shape-msgs, - ros-$(rosversion -d)-tf2-msgs, - ros-$(rosversion -d)-rosgraph-msgs, - ros-$(rosversion -d)-roscpp, - ros-$(rosversion -d)-pcl-conversions, - ros-$(rosversion -d)-pcl-ros, - ros-$(rosversion -d)-rostopic, - ros-$(rosversion -d)-rqt-gui-py -Description: The carla_ros_bridge package aims at providing a simple ROS bridge for CARLA simulator. -EOF - -rm copyright -cp ../../../carla-ros-bridge/ros-bridge/LICENSE ./copyright - - -#Updating debian/Changelog -awk '{sub(/UNRELEASED/,"stable")}1' changelog > tmp && mv tmp changelog -awk '{sub(/unstable/,"stable")}1' changelog > tmp && mv tmp changelog - -cd .. - -dpkg-buildpackage -uc -us -b #building debian package - -#install debian package using "sudo dpkg -i ../carla_ros-bridge-_amd64.deb" - From 1cb7f859428c673da4e453d24e1114554a89aca5 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Thu, 7 May 2020 16:38:54 +0200 Subject: [PATCH 185/627] activate catkin test for travis (#294) * activate catkin test for travis * don't run catkin test on kinetic as it does not support all options --- .travis.yml | 3 ++- carla_ad_demo/package.xml | 1 + carla_ego_vehicle/CMakeLists.txt | 2 +- carla_infrastructure/CMakeLists.txt | 2 +- carla_ros_bridge/CMakeLists.txt | 3 ++- carla_ros_scenario_runner/CMakeLists.txt | 2 +- 6 files changed, 8 insertions(+), 5 deletions(-) diff --git a/.travis.yml b/.travis.yml index 1ccb0633..75fa0fac 100644 --- a/.travis.yml +++ b/.travis.yml @@ -74,7 +74,8 @@ install: script: - catkin build - #- catkin test + - export SCENARIO_RUNNER_PATH="" # the env var needs to be set for testing + - if [ ! $ROS_DISTRO -eq kinetic ]; then catkin test; fi; - catkin config --install - source devel/setup.bash - cd src/ros-bridge diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 50f72d56..050c468e 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -16,6 +16,7 @@ carla_spectator_camera carla_ros_scenario_runner rostopic + rviz diff --git a/carla_ego_vehicle/CMakeLists.txt b/carla_ego_vehicle/CMakeLists.txt index 965a326b..7573b76b 100644 --- a/carla_ego_vehicle/CMakeLists.txt +++ b/carla_ego_vehicle/CMakeLists.txt @@ -8,7 +8,7 @@ find_package(catkin REQUIRED COMPONENTS catkin_python_setup() -roslaunch_add_file_check(launch) +roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) catkin_package( CATKIN_DEPENDS diff --git a/carla_infrastructure/CMakeLists.txt b/carla_infrastructure/CMakeLists.txt index 6223118e..91b6ca33 100644 --- a/carla_infrastructure/CMakeLists.txt +++ b/carla_infrastructure/CMakeLists.txt @@ -8,7 +8,7 @@ find_package(catkin REQUIRED COMPONENTS catkin_python_setup() -roslaunch_add_file_check(launch) +roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) catkin_package( CATKIN_DEPENDS diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index fb76b2b1..7e212f75 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -17,6 +17,7 @@ catkin_python_setup() catkin_package() roslaunch_add_file_check(launch) +roslaunch_add_file_check(test) include_directories( ${catkin_INCLUDE_DIRS} @@ -41,7 +42,7 @@ install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch ) -if(CATKIN_ENABLE_TESTING) +if(CATKIN_ENABLE_TESTING AND NOT $ENV{CI}) find_package(rostest REQUIRED) add_rostest(test/ros_bridge_client.test) endif() diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt index 877653c6..39ddf14f 100644 --- a/carla_ros_scenario_runner/CMakeLists.txt +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -7,7 +7,7 @@ find_package(catkin REQUIRED COMPONENTS catkin_python_setup() -roslaunch_add_file_check(launch) +roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) catkin_package() From 8a7b0a315811d470146e1e53239d3d5559ee296c Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 10:22:55 +0200 Subject: [PATCH 186/627] Add Dockerfile for eloquent --- docker/Dockerfile.eloquent | 48 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 48 insertions(+) create mode 100644 docker/Dockerfile.eloquent diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent new file mode 100644 index 00000000..f630ee8c --- /dev/null +++ b/docker/Dockerfile.eloquent @@ -0,0 +1,48 @@ +ARG CARLA_VERSION='0.9.9' +ARG ROS_VERSION='eloquent' +ARG CARLA_BUILD='' + +FROM carlasim/carla:$CARLA_VERSION$CARLA_BUILD as carla + +FROM ros:$ROS_VERSION-ros-base + +ARG ROS_VERSION + +RUN mkdir -p /carla_ws/src +WORKDIR /carla_ws + +RUN apt-get update \ + && apt-get install -y --no-install-recommends \ + libpng16-16 \ + # ros-$ROS_VERSION-ackermann-msgs \ + # ros-$ROS_VERSION-derived-object-msgs \ + # ros-$ROS_VERSION-tf \ + ros-$ROS_VERSION-cv-bridge \ + ros-$ROS_VERSION-pcl-conversions \ + # ros-$ROS_VERSION-pcl-ros \ + # ros-$ROS_VERSION-ainstein-radar \ + # python-catkin-tools \ + && rm -rf /var/lib/apt/lists/* + +ARG CARLA_VERSION + +COPY --from=carla --chown=root /home/carla/PythonAPI /opt/carla/PythonAPI +RUN sudo apt-get update && sudo apt-get install python-pip python3-pip -y --no-install-recommends +RUN python -m pip install setuptools +RUN python3 -m pip install setuptools +RUN easy_install --user --no-deps "/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py2.7-linux-x86_64.egg" +RUN easy_install --user --no-deps "/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py3.7-linux-x86_64.egg" + +COPY . src/ + +RUN echo "source /opt/ros/$ROS_VERSION/setup.bash" >> ~/.bashrc +RUN echo "source /carla_ws/devel/setup.bash" >> ~/.bashrc + +SHELL ["/bin/bash", "-c" , "-l"] + +RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment +RUN rosdep install --from-paths src -r +RUN colcon info carla_msgs +RUN colcon build --symlink-install + +CMD ["ros2", "run", "carla_msgs" , "simple_publisher.py"] From d9b50699871d660ded9969d8fe85a6ccf201f493 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 22 May 2020 12:15:35 +0200 Subject: [PATCH 187/627] Add ros_compatibility module --- ros_compatibility/CMakeLists.txt | 39 ++++++++ ros_compatibility/__init__.py | 1 + ros_compatibility/package.xml | 26 +++++ ros_compatibility/resource/ros_compatibility | 0 ros_compatibility/setup.cfg | 4 + ros_compatibility/setup.py | 44 +++++++++ ros_compatibility/src/__init__.py | 0 .../src/ros_compatibility/__init__.py | 4 + .../ros_compatibility/ros_compatible_node.py | 95 +++++++++++++++++++ 9 files changed, 213 insertions(+) create mode 100644 ros_compatibility/CMakeLists.txt create mode 100644 ros_compatibility/__init__.py create mode 100644 ros_compatibility/package.xml create mode 100644 ros_compatibility/resource/ros_compatibility create mode 100644 ros_compatibility/setup.cfg create mode 100644 ros_compatibility/setup.py create mode 100644 ros_compatibility/src/__init__.py create mode 100644 ros_compatibility/src/ros_compatibility/__init__.py create mode 100644 ros_compatibility/src/ros_compatibility/ros_compatible_node.py diff --git a/ros_compatibility/CMakeLists.txt b/ros_compatibility/CMakeLists.txt new file mode 100644 index 00000000..ccb664f4 --- /dev/null +++ b/ros_compatibility/CMakeLists.txt @@ -0,0 +1,39 @@ +cmake_minimum_required(VERSION 2.8.3) +project(ros_compatibility) + +# Update the policy setting to avoid an error when loading the ament_cmake package +# at the current cmake version level +if(POLICY CMP0057) + cmake_policy(SET CMP0057 NEW) +endif() + +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) + +if (${ROS_VERSION} EQUAL 1) + + find_package(catkin REQUIRED COMPONENTS + rospy + ) + + catkin_python_setup() + + catkin_package( + CATKIN_DEPENDS + rospy + ) + + include_directories() + + catkin_install_python( + PROGRAMS src/ros_compatibility/ros_compatible_node.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + +endif() diff --git a/ros_compatibility/__init__.py b/ros_compatibility/__init__.py new file mode 100644 index 00000000..0c1cfee4 --- /dev/null +++ b/ros_compatibility/__init__.py @@ -0,0 +1 @@ +from ros_compatibility.src.ros_compatibility.ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/package.xml b/ros_compatibility/package.xml new file mode 100644 index 00000000..f08a9b15 --- /dev/null +++ b/ros_compatibility/package.xml @@ -0,0 +1,26 @@ + + + + ros_compatibility + 0.0.0 + The ros_compatibility package + CARLA Simulator Team + MIT + + + rclpy + + + catkin + rospy + std_msgs + rospy + std_msgs + rospy + std_msgs + + + catkin + ament_python + + diff --git a/ros_compatibility/resource/ros_compatibility b/ros_compatibility/resource/ros_compatibility new file mode 100644 index 00000000..e69de29b diff --git a/ros_compatibility/setup.cfg b/ros_compatibility/setup.cfg new file mode 100644 index 00000000..9c25a3a8 --- /dev/null +++ b/ros_compatibility/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/ros_compatibility +[install] +install-scripts=$base/lib/ros_compatibility diff --git a/ros_compatibility/setup.py b/ros_compatibility/setup.py new file mode 100644 index 00000000..55754977 --- /dev/null +++ b/ros_compatibility/setup.py @@ -0,0 +1,44 @@ +import os + +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup + + d = generate_distutils_setup( + packages=['ros_compatibility'], + package_dir={'': 'src'} + ) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'ros_compatibility' + + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + py_modules=[ + 'src.ros_compatibility.ros_compatible_node'], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='The ros_compatibility package', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'ros_compatible_node = src.ros_compatibility.ros_compatible_node:main' + ], + }, + ) diff --git a/ros_compatibility/src/__init__.py b/ros_compatibility/src/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py new file mode 100644 index 00000000..3c2a8ca4 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -0,0 +1,4 @@ +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) +if ROS_VERSION == 1: + from ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py new file mode 100644 index 00000000..56f513d1 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -0,0 +1,95 @@ +import os + +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + import rospy + + + class QoSProfile(): + def __init__(self, **kwargs): + self.depth = kwargs['depth'] + + + class CompatibleNode(object): + def __init__(self, node_name, queue_size=10): + rospy.init_node(node_name, anonymous=True) + self.qos_profile = QoSProfile(depth=queue_size) + + def get_param(self, name, alternative_value=None, alternative_name=None): + if alternative_value is None: + return rospy.get_param(name) + return rospy.get_param(name, alternative_value) + + def loginfo(self, text): + rospy.loginfo(text) + + def logfatal(self, arg): + rospy.logfatal(arg) + + def create_subscriber(self, msg_type, topic, + callback, qos_profile=None): + if qos_profile is None: + qos_profile = self.qos_profile + return rospy.Subscriber(topic, msg_type, + callback, queue_size=qos_profile.depth) + + def spin(self): + rospy.spin() + + def shutdown(self): + pass + +elif ROS_VERSION == 2: + from rclpy.node import Node + from rclpy import Parameter + from rclpy.qos import QoSProfile + import rclpy + + + class CompatibleNode(Node): + def __init__(self, node_name, queue_size=10): + super().__init__(node_name, allow_undeclared_parameters=True, + automatically_declare_parameters_from_overrides=True) + self.logger = self.get_logger() + self.qos_profile = QoSProfile(depth=queue_size) + + def get_param(self, name, alternative_value=None, alternative_name=None): + if alternative_value is None: + return self.get_parameter(name).value + if alternative_name is None: + alternative_name = name + return self.get_parameter_or(name, + Parameter(alternative_name, value=alternative_value)).value + + def loginfo(self, text): + self.logger.info(text) + + def logfatal(self, arg): + self.logger.fatal(arg) + + def create_subscriber(self, msg_type, topic, + callback, qos_profile=None): + if qos_profile is None: + qos_profile = self.qos_profile + return self.create_subscription(msg_type, topic, + callback, qos_profile) + + def spin(self): + rclpy.spin(self) + + def shutdown(self): + rclpy.shutdown() + +else: + raise NotImplementedError("Make sure you have valid " + + "ROS_VERSION env variable"); + + +def main(): + print('This is a ros1 - ros2 compatibility module.', + "It's not meant to be executed, but rather imported") + + +if __name__ == '__main__': + main() From 099241ac24914cc7196ccf6a8211394c289cd9b6 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 14:31:31 +0200 Subject: [PATCH 188/627] Limit colcon to build carla_msgs only --- docker/Dockerfile.eloquent | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent index f630ee8c..a537f47e 100644 --- a/docker/Dockerfile.eloquent +++ b/docker/Dockerfile.eloquent @@ -41,8 +41,9 @@ RUN echo "source /carla_ws/devel/setup.bash" >> ~/.bashrc SHELL ["/bin/bash", "-c" , "-l"] RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment -RUN rosdep install --from-paths src -r +RUN rosdep install --from-paths src/carla_msgs -r -y RUN colcon info carla_msgs -RUN colcon build --symlink-install +# .bashrc does not seem to do the source +RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --packages-select carla_msgs -CMD ["ros2", "run", "carla_msgs" , "simple_publisher.py"] +CMD ["ros2", "run", "carla_ros_bridge" , "carla_ros_bridge.py"] From 055f3e2155a41b1fcb21a1ee581f8787e77fc470 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 14:34:05 +0200 Subject: [PATCH 189/627] Use carla_msgs with ROS2 compatibility --- carla_msgs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_msgs b/carla_msgs index 708e9c83..0501e759 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 708e9c830bbd1637f89b5cf49dae8c3a327d021a +Subproject commit 0501e759321ce314a230e814a58e43cbb66d1fa2 From d063ac39a1c7f81b6f46f99abfefd6920cbefc64 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 15:12:20 +0200 Subject: [PATCH 190/627] Add ignore for temporary vscode --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 1f93b7e8..ade5bf10 100644 --- a/.gitignore +++ b/.gitignore @@ -2,3 +2,4 @@ build.gradle /CMakeLists.txt .catkin_workspace +.vscode/ From ef4539d2401eb3e7dd8da7440a3b489f0087c077 Mon Sep 17 00:00:00 2001 From: Diego-ort Date: Fri, 22 May 2020 15:20:12 +0200 Subject: [PATCH 191/627] Modification of the meta-files of the carla_manual_control and carla_ros_bridge modules --- carla_manual_control/CMakeLists.txt | 44 +++++++------ carla_manual_control/package.xml | 29 ++++++--- carla_manual_control/setup.cfg | 4 ++ carla_manual_control/setup.py | 46 +++++++++++--- carla_ros_bridge/CMakeLists.txt | 95 ++++++++++++++++------------- carla_ros_bridge/package.xml | 56 ++++++++++------- carla_ros_bridge/setup.cfg | 4 ++ carla_ros_bridge/setup.py | 46 +++++++++++--- 8 files changed, 220 insertions(+), 104 deletions(-) create mode 100644 carla_manual_control/setup.cfg create mode 100644 carla_ros_bridge/setup.cfg diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index 8a43818a..c3be3b60 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -1,25 +1,35 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_manual_control) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(ament_cmake QUIET) +if ( ament_cmake_FOUND ) + find_package(rclpy REQUIRED) -catkin_python_setup() + ament_export_dependencies(rclpy) + ament_package() -roslaunch_add_file_check(launch) +elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) + + find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch + ) -catkin_package( - CATKIN_DEPENDS - rospy -) + catkin_python_setup() -catkin_install_python(PROGRAMS - src/carla_manual_control/carla_manual_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) + roslaunch_add_file_check(launch) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + catkin_package( + CATKIN_DEPENDS + rospy + ) + + catkin_install_python(PROGRAMS + src/carla_manual_control/carla_manual_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + ) +endif() diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index 1fd821f9..5e736ee2 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -5,14 +5,27 @@ The carla_manual_control package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy - carla_msgs - sensor_msgs - std_msgs + + + rclpy + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + catkin + rospy + roslaunch + rospy + rospy + carla_msgs + sensor_msgs + std_msgs + + + catkin + ament_python diff --git a/carla_manual_control/setup.cfg b/carla_manual_control/setup.cfg new file mode 100644 index 00000000..18dba7db --- /dev/null +++ b/carla_manual_control/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_manual_control +[install] +install-scripts=$base/lib/carla_manual_control diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index 2a8638ad..baaae96c 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -1,13 +1,45 @@ """ Setup for carla_manual_control """ +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_manual_control'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_manual_control'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_manual_control' + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', + ['config/settings.yaml', 'config/sensors.json']) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ego vehicle for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'manual_control = carla_manual_control.carla_manual_control:main' + ], + }, + ) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 7e212f75..508ab8f6 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -2,47 +2,56 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_bridge) ## Find catkin macros and libraries -find_package(catkin REQUIRED COMPONENTS - rospy - sensor_msgs - geometry_msgs - derived_object_msgs - ainstein_radar_msgs - tf - roslaunch -) - -catkin_python_setup() - -catkin_package() - -roslaunch_add_file_check(launch) -roslaunch_add_file_check(test) - -include_directories( - ${catkin_INCLUDE_DIRS} -) - -install(PROGRAMS - src/carla_ros_bridge/bridge.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) - -install(FILES - test/ros_bridge_client.test - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) - -install(DIRECTORY - config - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) - -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) - -if(CATKIN_ENABLE_TESTING AND NOT $ENV{CI}) - find_package(rostest REQUIRED) - add_rostest(test/ros_bridge_client.test) +find_package(ament_cmake QUIET) +if ( ament_cmake_FOUND ) + find_package(rclpy REQUIRED) + + ament_export_dependencies(rclpy) + ament_package() + +elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) + + find_package(catkin REQUIRED COMPONENTS + rospy + sensor_msgs + geometry_msgs + derived_object_msgs + ainstein_radar_msgs + tf + roslaunch + ) + + catkin_python_setup() + + catkin_package() + + roslaunch_add_file_check(launch) + + include_directories( + ${catkin_INCLUDE_DIRS} + ) + + install(PROGRAMS + src/carla_ros_bridge/bridge.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + + install(FILES + test/ros_bridge_client.test + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + ) + + install(DIRECTORY + config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + ) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch + ) + + if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + add_rostest(test/ros_bridge_client.test) + endif() endif() diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index e94f23d1..2429de54 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -5,28 +5,40 @@ The carla_ros_bridge package CARLA Simulator Team MIT - catkin - roslaunch - ainstein_radar_msgs - rospy - sensor_msgs - visualization_msgs - tf - tf2 - rviz - cv_bridge - geometry_msgs - std_msgs - rosbag_storage - derived_object_msgs - shape_msgs - nav_msgs - tf2_msgs - rosgraph_msgs - cv_bridge - carla_msgs - carla_ego_vehicle - carla_manual_control + + + rclpy + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + catkin + roslaunch + ainstein_radar_msgs + rospy + sensor_msgs + visualization_msgs + tf + tf2 + rviz + cv_bridge + geometry_msgs + std_msgs + rosbag_storage + derived_object_msgs + shape_msgs + nav_msgs + tf2_msgs + rosgraph_msgs + cv_bridge + carla_msgs + carla_ego_vehicle + carla_manual_control + + catkin + ament_python diff --git a/carla_ros_bridge/setup.cfg b/carla_ros_bridge/setup.cfg new file mode 100644 index 00000000..bf9eb67b --- /dev/null +++ b/carla_ros_bridge/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_ros_bridge +[install] +install-scripts=$base/lib/carla_ros_bridge diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index f4bdc1a1..0346c466 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -1,13 +1,45 @@ """ Setup for carla_ros_bridge """ +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup + if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_ros_bridge'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_ros_bridge'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_ros_bridge' + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', + ['config/settings.yaml', 'config/sensors.json']) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ego vehicle for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'bridge = carla_ros_bridge.bridge:main' + ], + }, + ) From b1d0173865fe83bf513a8d38f4aa586b9cec142f Mon Sep 17 00:00:00 2001 From: Diego-ort Date: Fri, 22 May 2020 16:54:55 +0200 Subject: [PATCH 192/627] Correction of meta-files --- carla_manual_control/CMakeLists.txt | 17 ++++++++++------- carla_manual_control/package.xml | 7 ++----- carla_manual_control/setup.py | 2 +- carla_ros_bridge/CMakeLists.txt | 18 ++++++++++-------- carla_ros_bridge/package.xml | 9 +++------ carla_ros_bridge/setup.py | 4 ++-- 6 files changed, 28 insertions(+), 29 deletions(-) diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index c3be3b60..ed7e27e6 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -1,15 +1,11 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_manual_control) -find_package(ament_cmake QUIET) -if ( ament_cmake_FOUND ) - find_package(rclpy REQUIRED) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) - ament_export_dependencies(rclpy) - ament_package() +if (${ROS_VERSION} EQUAL 1) -elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) - find_package(catkin REQUIRED COMPONENTS rospy roslaunch @@ -32,4 +28,11 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch ) + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + endif() diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index 5e736ee2..2d9012ed 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -1,5 +1,6 @@ - + + carla_manual_control 0.0.0 The carla_manual_control package @@ -8,10 +9,6 @@ rclpy - ament_copyright - ament_flake8 - ament_pep257 - python3-pytest catkin diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index baaae96c..dc4e3602 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -34,7 +34,7 @@ zip_safe=True, maintainer='CARLA Simulator Team', maintainer_email='carla.simulator@gmail.com', - description='CARLA ego vehicle for ROS2 bridge', + description='CARLA manual control for ROS2 bridge', license='MIT', tests_require=['pytest'], entry_points={ diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 508ab8f6..40f8d871 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -1,15 +1,10 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_bridge) -## Find catkin macros and libraries -find_package(ament_cmake QUIET) -if ( ament_cmake_FOUND ) - find_package(rclpy REQUIRED) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) - ament_export_dependencies(rclpy) - ament_package() - -elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) +if (${ROS_VERSION} EQUAL 1) find_package(catkin REQUIRED COMPONENTS rospy @@ -54,4 +49,11 @@ elseif( CATKIN_DEVEL_PREFIX OR CATKIN_BUILD_BINARY_PACKAGE) find_package(rostest REQUIRED) add_rostest(test/ros_bridge_client.test) endif() + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + endif() diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 2429de54..b0be55bb 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -1,17 +1,14 @@ - + + carla_ros_bridge - 0.0.1 + 0.0.0 The carla_ros_bridge package CARLA Simulator Team MIT rclpy - ament_copyright - ament_flake8 - ament_pep257 - python3-pytest catkin diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index 0346c466..b6a90900 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -4,7 +4,7 @@ import os ROS_VERSION = int(os.environ['ROS_VERSION']) - if ROS_VERSION == 1: +if ROS_VERSION == 1: from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup @@ -34,7 +34,7 @@ zip_safe=True, maintainer='CARLA Simulator Team', maintainer_email='carla.simulator@gmail.com', - description='CARLA ego vehicle for ROS2 bridge', + description='CARLA ROS2 bridge', license='MIT', tests_require=['pytest'], entry_points={ From 22f0e977176ba84e0a2ebfb165c3da725712d7a1 Mon Sep 17 00:00:00 2001 From: Diego-ort Date: Fri, 22 May 2020 17:14:27 +0200 Subject: [PATCH 193/627] Corrections of data_file[] arguments of setup.py files of both modules --- carla_manual_control/setup.py | 2 -- carla_ros_bridge/setup.py | 3 +-- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index dc4e3602..b2dd051f 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -27,8 +27,6 @@ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - ('share/' + package_name + '/config', - ['config/settings.yaml', 'config/sensors.json']) ], install_requires=['setuptools'], zip_safe=True, diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index b6a90900..b2c744c6 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -27,8 +27,7 @@ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - ('share/' + package_name + '/config', - ['config/settings.yaml', 'config/sensors.json']) + (os.path.join('share', package_name), glob('launch/*.launch.py')), ], install_requires=['setuptools'], zip_safe=True, From c18a6b406a23a0745bc6386a0116863afcda8ce8 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 17:54:01 +0200 Subject: [PATCH 194/627] Avoid key error by using get() --- ros_compatibility/src/ros_compatibility/__init__.py | 2 +- ros_compatibility/src/ros_compatibility/ros_compatible_node.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py index 3c2a8ca4..bd5614f4 100644 --- a/ros_compatibility/src/ros_compatibility/__init__.py +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -1,4 +1,4 @@ import os -ROS_VERSION = int(os.environ['ROS_VERSION']) +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: from ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 56f513d1..d0fd3110 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -1,6 +1,6 @@ import os -ROS_VERSION = int(os.environ['ROS_VERSION']) +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: import rospy From 71d2ad16ef7ec91d74cb531cb3ad898a047ba08e Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 17:57:15 +0200 Subject: [PATCH 195/627] Remove semicolon --- ros_compatibility/src/ros_compatibility/ros_compatible_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index d0fd3110..92283751 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -83,7 +83,7 @@ def shutdown(self): else: raise NotImplementedError("Make sure you have valid " + - "ROS_VERSION env variable"); + "ROS_VERSION env variable") def main(): From 75c2fe6cb0e4eab2e8d458f0485076b01e8e3dab Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 17:59:56 +0200 Subject: [PATCH 196/627] Use uniform ' --- .../src/ros_compatibility/ros_compatible_node.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 92283751..58912265 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -82,13 +82,13 @@ def shutdown(self): rclpy.shutdown() else: - raise NotImplementedError("Make sure you have valid " + - "ROS_VERSION env variable") + raise NotImplementedError('Make sure you have valid ' + + 'ROS_VERSION env variable') def main(): print('This is a ros1 - ros2 compatibility module.', - "It's not meant to be executed, but rather imported") + 'It's not meant to be executed, but rather imported') if __name__ == '__main__': From dd4192b409c7309f47ea84c7132c99bccd64affc Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 18:06:29 +0200 Subject: [PATCH 197/627] Add ros_compatibility node to dockerfile --- docker/Dockerfile.eloquent | 4 ++-- .../src/ros_compatibility/ros_compatible_node.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent index a537f47e..39ba0049 100644 --- a/docker/Dockerfile.eloquent +++ b/docker/Dockerfile.eloquent @@ -41,9 +41,9 @@ RUN echo "source /carla_ws/devel/setup.bash" >> ~/.bashrc SHELL ["/bin/bash", "-c" , "-l"] RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment -RUN rosdep install --from-paths src/carla_msgs -r -y +RUN rosdep install --from-paths src/carla_msgs src/ros_compatibility -r -y RUN colcon info carla_msgs # .bashrc does not seem to do the source -RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --packages-select carla_msgs +RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --packages-select carla_msgs ros_compatibility CMD ["ros2", "run", "carla_ros_bridge" , "carla_ros_bridge.py"] diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 58912265..29665cfd 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -88,7 +88,7 @@ def shutdown(self): def main(): print('This is a ros1 - ros2 compatibility module.', - 'It's not meant to be executed, but rather imported') + 'It is not meant to be executed, but rather imported') if __name__ == '__main__': From e4eff435b579f77f81dfa8319738fe9eb5dcbbc1 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Fri, 22 May 2020 18:44:16 +0200 Subject: [PATCH 198/627] Add publisher functionality --- .../ros_compatibility/ros_compatible_node.py | 44 ++++++++++++++++--- 1 file changed, 38 insertions(+), 6 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 29665cfd..e98bd8ce 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -12,9 +12,11 @@ def __init__(self, **kwargs): class CompatibleNode(object): - def __init__(self, node_name, queue_size=10): - rospy.init_node(node_name, anonymous=True) + def __init__(self, node_name, queue_size=10, rospy_init=True): + if rospy_init: + rospy.init_node(node_name, anonymous=True) self.qos_profile = QoSProfile(depth=queue_size) + self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_value is None: @@ -24,11 +26,25 @@ def get_param(self, name, alternative_value=None, alternative_name=None): def loginfo(self, text): rospy.loginfo(text) + def logwarn(self, text): + rospy.logwarn(text) + def logfatal(self, arg): rospy.logfatal(arg) + # assymetry in publisher/subscriber method naming due to rclpy having + # create_publisher method. + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return rospy.Publisher(topic, msg_type, queue_size=qos_profile.depth) + def create_subscriber(self, msg_type, topic, - callback, qos_profile=None): + callback, qos_profile=None, + callback_group=None): if qos_profile is None: qos_profile = self.qos_profile return rospy.Subscriber(topic, msg_type, @@ -48,11 +64,12 @@ def shutdown(self): class CompatibleNode(Node): - def __init__(self, node_name, queue_size=10): + def __init__(self, node_name, queue_size=10, rospy_init=True): super().__init__(node_name, allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True) self.logger = self.get_logger() self.qos_profile = QoSProfile(depth=queue_size) + self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_value is None: @@ -65,15 +82,30 @@ def get_param(self, name, alternative_value=None, alternative_name=None): def loginfo(self, text): self.logger.info(text) + def logwarn(self, text): + self.logger.warn(text) + def logfatal(self, arg): self.logger.fatal(arg) + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) + def create_subscriber(self, msg_type, topic, - callback, qos_profile=None): + callback, qos_profile=None, callback_group=None): if qos_profile is None: qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group return self.create_subscription(msg_type, topic, - callback, qos_profile) + callback, qos_profile, + callback_group=callback_group) def spin(self): rclpy.spin(self) From 892ccfc9d88f726a5efaefe19af54ed6b7faed01 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 19:06:03 +0200 Subject: [PATCH 199/627] Use .get() to access the environ --- ros_compatibility/setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_compatibility/setup.py b/ros_compatibility/setup.py index 55754977..207e7c97 100644 --- a/ros_compatibility/setup.py +++ b/ros_compatibility/setup.py @@ -1,6 +1,6 @@ import os -ROS_VERSION = int(os.environ['ROS_VERSION']) +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: from distutils.core import setup From 6ac769f549f894c14cd289d4b380813ab73ff8be Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 19:42:03 +0200 Subject: [PATCH 200/627] Fix version --- carla_ros_bridge/package.xml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index b0be55bb..875141e6 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -1,8 +1,7 @@ - carla_ros_bridge - 0.0.0 + 0.0.1 The carla_ros_bridge package CARLA Simulator Team MIT From 975fe0196f478009917bc2c0665a9a07712007f7 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 22 May 2020 19:44:45 +0200 Subject: [PATCH 201/627] Remove xml schema --- carla_manual_control/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index 2d9012ed..da4f535b 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -1,5 +1,4 @@ - carla_manual_control 0.0.0 From 619024d16aa6c39b0f464fcf68e3e77b358ec0e3 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 1 Jun 2020 19:53:52 +0200 Subject: [PATCH 202/627] Add new logging methods and wrapper functions --- .../ros_compatibility/ros_compatible_node.py | 120 +++++++++++++++--- 1 file changed, 103 insertions(+), 17 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index e98bd8ce..eea97c92 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -5,17 +5,33 @@ if ROS_VERSION == 1: import rospy + latch_on = True - class QoSProfile(): - def __init__(self, **kwargs): - self.depth = kwargs['depth'] + def ros_timestamp(sec=0, nsec=0, from_sec=False): + if from_sec: + return rospy.Time.from_sec(sec) + return rospy.Time(int(sec), int(nsec)) + + def ros_ok(): + return not rospy.is_shutdown() + + def ros_shutdown(): + pass + def destroy_subscription(subsription): + subsription.unregister() + + + class QoSProfile(): + def __init__(self, depth=10, durability=None, **kwargs): + self.depth = depth + self.latch = bool(durability) class CompatibleNode(object): - def __init__(self, node_name, queue_size=10, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): if rospy_init: rospy.init_node(node_name, anonymous=True) - self.qos_profile = QoSProfile(depth=queue_size) + self.qos_profile = QoSProfile(depth=queue_size, durability=latch) self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): @@ -23,12 +39,24 @@ def get_param(self, name, alternative_value=None, alternative_name=None): return rospy.get_param(name) return rospy.get_param(name, alternative_value) + def logdebug(self, text): + rospy.logdebug(text) + def loginfo(self, text): rospy.loginfo(text) def logwarn(self, text): rospy.logwarn(text) + def logwarn(self, text): + rospy.logwarn(text) + + def logwarn(self, text): + rospy.logwarn(text) + + def logerr(self, text): + rospy.logerr(text) + def logfatal(self, arg): rospy.logfatal(arg) @@ -40,7 +68,8 @@ def new_publisher(self, msg_type, topic, qos_profile = self.qos_profile if callback_group is None: callback_group = self.callback_group - return rospy.Publisher(topic, msg_type, queue_size=qos_profile.depth) + return rospy.Publisher(topic, msg_type, latch=qos_profile.latch, + queue_size=qos_profile.depth) def create_subscriber(self, msg_type, topic, callback, qos_profile=None, @@ -50,7 +79,7 @@ def create_subscriber(self, msg_type, topic, return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) - def spin(self): + def spin(self, executor=None): rospy.spin() def shutdown(self): @@ -59,16 +88,42 @@ def shutdown(self): elif ROS_VERSION == 2: from rclpy.node import Node from rclpy import Parameter - from rclpy.qos import QoSProfile + from rclpy.qos import QoSProfile, QoSDurabilityPolicy import rclpy + from builtin_interfaces.msg import Time + + latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL + + def ros_timestamp(sec=0, nsec=0, from_sec=False): + time = Time() + if from_sec: + time.sec = int(sec) + time.nanosec = int((sec - int(sec)) * 1000_000_000) + else: + time.sec = int(sec) + time.nanosec = int(nsec) + return time + + def ros_ok(): + return rclpy.ok() + + def ros_shutdown(): + rclpy.shutdown() + + def destroy_subscription(subsription): + subsription.destroy() class CompatibleNode(Node): - def __init__(self, node_name, queue_size=10, rospy_init=True): + def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): super().__init__(node_name, allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True) - self.logger = self.get_logger() - self.qos_profile = QoSProfile(depth=queue_size) + if latch: + self.qos_profile = QoSProfile( + depth=queue_size, + durability=QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) + else: + self.qos_profile = QoSProfile(depth=queue_size) self.callback_group = None def get_param(self, name, alternative_value=None, alternative_name=None): @@ -77,16 +132,47 @@ def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_name is None: alternative_name = name return self.get_parameter_or(name, - Parameter(alternative_name, value=alternative_value)).value + Parameter(alternative_name, value=alternative_value) + ).value + + def logdebug(self, text): + self.get_logger().debug(text) def loginfo(self, text): - self.logger.info(text) + self.get_logger().info(text) def logwarn(self, text): - self.logger.warn(text) + self.get_logger().warn(text) - def logfatal(self, arg): - self.logger.fatal(arg) + def logerr(self, text): + self.get_logger().error(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logfatal(self, text): + self.get_logger().fatal(text) + + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) + + def new_publisher(self, msg_type, topic, + qos_profile=None, callback_group=None): + if qos_profile is None: + qos_profile = self.qos_profile + if callback_group is None: + callback_group = self.callback_group + return self.create_publisher(msg_type, topic, + qos_profile, callback_group=callback_group) def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): @@ -107,7 +193,7 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile, callback_group=callback_group) - def spin(self): + def spin(self, executor=None): rclpy.spin(self) def shutdown(self): From b2992e5151e82b5995096c3f0189ee4f63c32e17 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 10 Jun 2020 10:08:36 +0200 Subject: [PATCH 203/627] Remove duplicated methods --- .../ros_compatibility/ros_compatible_node.py | 39 ++----------------- 1 file changed, 4 insertions(+), 35 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index eea97c92..0e66beff 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -21,7 +21,6 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.unregister() - class QoSProfile(): def __init__(self, depth=10, durability=None, **kwargs): self.depth = depth @@ -48,12 +47,6 @@ def loginfo(self, text): def logwarn(self, text): rospy.logwarn(text) - def logwarn(self, text): - rospy.logwarn(text) - - def logwarn(self, text): - rospy.logwarn(text) - def logerr(self, text): rospy.logerr(text) @@ -63,7 +56,7 @@ def logfatal(self, arg): # assymetry in publisher/subscriber method naming due to rclpy having # create_publisher method. def new_publisher(self, msg_type, topic, - qos_profile=None, callback_group=None): + qos_profile=None, callback_group=None): if qos_profile is None: qos_profile = self.qos_profile if callback_group is None: @@ -113,7 +106,6 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.destroy() - class CompatibleNode(Node): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True): super().__init__(node_name, allow_undeclared_parameters=True, @@ -132,7 +124,8 @@ def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_name is None: alternative_name = name return self.get_parameter_or(name, - Parameter(alternative_name, value=alternative_value) + Parameter(alternative_name, + value=alternative_value) ).value def logdebug(self, text): @@ -141,41 +134,17 @@ def logdebug(self, text): def loginfo(self, text): self.get_logger().info(text) - def logwarn(self, text): - self.get_logger().warn(text) - def logerr(self, text): self.get_logger().error(text) def logwarn(self, text): self.get_logger().warn(text) - def logwarn(self, text): - self.get_logger().warn(text) - def logfatal(self, text): self.get_logger().fatal(text) def new_publisher(self, msg_type, topic, - qos_profile=None, callback_group=None): - if qos_profile is None: - qos_profile = self.qos_profile - if callback_group is None: - callback_group = self.callback_group - return self.create_publisher(msg_type, topic, - qos_profile, callback_group=callback_group) - - def new_publisher(self, msg_type, topic, - qos_profile=None, callback_group=None): - if qos_profile is None: - qos_profile = self.qos_profile - if callback_group is None: - callback_group = self.callback_group - return self.create_publisher(msg_type, topic, - qos_profile, callback_group=callback_group) - - def new_publisher(self, msg_type, topic, - qos_profile=None, callback_group=None): + qos_profile=None, callback_group=None): if qos_profile is None: qos_profile = self.qos_profile if callback_group is None: From aad2d33512238d8456509a5e4948df470e62c73d Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 10 Jun 2020 10:15:19 +0200 Subject: [PATCH 204/627] Update package.xml with ros2 dependencies and remove std_msgs as dependency since is not used --- ros_compatibility/package.xml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ros_compatibility/package.xml b/ros_compatibility/package.xml index f08a9b15..29d932b9 100644 --- a/ros_compatibility/package.xml +++ b/ros_compatibility/package.xml @@ -8,16 +8,14 @@ MIT + ament_python rclpy catkin rospy - std_msgs rospy - std_msgs rospy - std_msgs catkin From 1a75093fa4baba0d118f3c218f17cd0f22d70024 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Wed, 10 Jun 2020 10:35:48 +0200 Subject: [PATCH 205/627] Revert: Modification of the meta-files of the carla_manual_control and carla_ros_bridge modules (1f122c7b) --- carla_ad_demo/package.xml | 1 - carla_manual_control/CMakeLists.txt | 47 +++++++++++------------------ 2 files changed, 17 insertions(+), 31 deletions(-) diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 050c468e..50f72d56 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -16,7 +16,6 @@ carla_spectator_camera carla_ros_scenario_runner rostopic - rviz diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index ed7e27e6..8a43818a 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -1,38 +1,25 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_manual_control) -find_package(ros_environment REQUIRED) -set(ROS_VERSION $ENV{ROS_VERSION}) +find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch +) -if (${ROS_VERSION} EQUAL 1) +catkin_python_setup() - find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch - ) +roslaunch_add_file_check(launch) - catkin_python_setup() +catkin_package( + CATKIN_DEPENDS + rospy +) - roslaunch_add_file_check(launch) +catkin_install_python(PROGRAMS + src/carla_manual_control/carla_manual_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) - catkin_package( - CATKIN_DEPENDS - rospy - ) - - catkin_install_python(PROGRAMS - src/carla_manual_control/carla_manual_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - - install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - ) - -elseif (${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - ament_package() - -endif() +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) From 6b7391ec4f036fe25637deda5a16f40d2b30685b Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Wed, 10 Jun 2020 10:37:22 +0200 Subject: [PATCH 206/627] Revert: Modification of the meta-files of the carla_manual_control and carla_ros_bridge modules (1f122c7b) --- carla_manual_control/package.xml | 27 +++------ carla_manual_control/setup.cfg | 4 -- carla_manual_control/setup.py | 44 +++----------- carla_ros_bridge/CMakeLists.txt | 99 ++++++++++++++------------------ carla_ros_bridge/package.xml | 54 ++++++++--------- carla_ros_bridge/setup.cfg | 4 -- carla_ros_bridge/setup.py | 45 +++------------ 7 files changed, 90 insertions(+), 187 deletions(-) delete mode 100644 carla_manual_control/setup.cfg delete mode 100644 carla_ros_bridge/setup.cfg diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index da4f535b..1fd821f9 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -1,27 +1,18 @@ - + carla_manual_control 0.0.0 The carla_manual_control package CARLA Simulator Team MIT - - - rclpy - - - catkin - rospy - roslaunch - rospy - rospy - carla_msgs - sensor_msgs - std_msgs - - + catkin + rospy + roslaunch + rospy + rospy + carla_msgs + sensor_msgs + std_msgs - catkin - ament_python diff --git a/carla_manual_control/setup.cfg b/carla_manual_control/setup.cfg deleted file mode 100644 index 18dba7db..00000000 --- a/carla_manual_control/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script-dir=$base/lib/carla_manual_control -[install] -install-scripts=$base/lib/carla_manual_control diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index b2dd051f..2a8638ad 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -1,43 +1,13 @@ """ Setup for carla_manual_control """ -import os -ROS_VERSION = int(os.environ['ROS_VERSION']) -if ROS_VERSION == 1: - from distutils.core import setup - from catkin_pkg.python_setup import generate_distutils_setup +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup - d = generate_distutils_setup( - packages=['carla_manual_control'], - package_dir={'': 'src'} - ) +d = generate_distutils_setup( + packages=['carla_manual_control'], + package_dir={'': 'src'} +) - setup(**d) - -elif ROS_VERSION == 2: - from setuptools import setup - - package_name = 'carla_manual_control' - setup( - name=package_name, - version='0.0.0', - packages=['src/' + package_name], - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), - ], - install_requires=['setuptools'], - zip_safe=True, - maintainer='CARLA Simulator Team', - maintainer_email='carla.simulator@gmail.com', - description='CARLA manual control for ROS2 bridge', - license='MIT', - tests_require=['pytest'], - entry_points={ - 'console_scripts': [ - 'manual_control = carla_manual_control.carla_manual_control:main' - ], - }, - ) +setup(**d) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 40f8d871..7e212f75 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -1,59 +1,48 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_bridge) -find_package(ros_environment REQUIRED) -set(ROS_VERSION $ENV{ROS_VERSION}) - -if (${ROS_VERSION} EQUAL 1) - - find_package(catkin REQUIRED COMPONENTS - rospy - sensor_msgs - geometry_msgs - derived_object_msgs - ainstein_radar_msgs - tf - roslaunch - ) - - catkin_python_setup() - - catkin_package() - - roslaunch_add_file_check(launch) - - include_directories( - ${catkin_INCLUDE_DIRS} - ) - - install(PROGRAMS - src/carla_ros_bridge/bridge.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - - install(FILES - test/ros_bridge_client.test - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - ) - - install(DIRECTORY - config - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} - ) - - install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch - ) - - if(CATKIN_ENABLE_TESTING) - find_package(rostest REQUIRED) - add_rostest(test/ros_bridge_client.test) - endif() - -elseif (${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - ament_package() - +## Find catkin macros and libraries +find_package(catkin REQUIRED COMPONENTS + rospy + sensor_msgs + geometry_msgs + derived_object_msgs + ainstein_radar_msgs + tf + roslaunch +) + +catkin_python_setup() + +catkin_package() + +roslaunch_add_file_check(launch) +roslaunch_add_file_check(test) + +include_directories( + ${catkin_INCLUDE_DIRS} +) + +install(PROGRAMS + src/carla_ros_bridge/bridge.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(FILES + test/ros_bridge_client.test + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY + config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + +if(CATKIN_ENABLE_TESTING AND NOT $ENV{CI}) + find_package(rostest REQUIRED) + add_rostest(test/ros_bridge_client.test) endif() diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 875141e6..e94f23d1 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -1,40 +1,32 @@ - + carla_ros_bridge 0.0.1 The carla_ros_bridge package CARLA Simulator Team MIT - - - rclpy - - - catkin - roslaunch - ainstein_radar_msgs - rospy - sensor_msgs - visualization_msgs - tf - tf2 - rviz - cv_bridge - geometry_msgs - std_msgs - rosbag_storage - derived_object_msgs - shape_msgs - nav_msgs - tf2_msgs - rosgraph_msgs - cv_bridge - carla_msgs - carla_ego_vehicle - carla_manual_control - + catkin + roslaunch + ainstein_radar_msgs + rospy + sensor_msgs + visualization_msgs + tf + tf2 + rviz + cv_bridge + geometry_msgs + std_msgs + rosbag_storage + derived_object_msgs + shape_msgs + nav_msgs + tf2_msgs + rosgraph_msgs + cv_bridge + carla_msgs + carla_ego_vehicle + carla_manual_control - catkin - ament_python diff --git a/carla_ros_bridge/setup.cfg b/carla_ros_bridge/setup.cfg deleted file mode 100644 index bf9eb67b..00000000 --- a/carla_ros_bridge/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script-dir=$base/lib/carla_ros_bridge -[install] -install-scripts=$base/lib/carla_ros_bridge diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index b2c744c6..f4bdc1a1 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -1,44 +1,13 @@ """ Setup for carla_ros_bridge """ -import os -ROS_VERSION = int(os.environ['ROS_VERSION']) -if ROS_VERSION == 1: - from distutils.core import setup - from catkin_pkg.python_setup import generate_distutils_setup +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup - d = generate_distutils_setup( - packages=['carla_ros_bridge'], - package_dir={'': 'src'} - ) +d = generate_distutils_setup( + packages=['carla_ros_bridge'], + package_dir={'': 'src'} +) - setup(**d) - -elif ROS_VERSION == 2: - from setuptools import setup - - package_name = 'carla_ros_bridge' - setup( - name=package_name, - version='0.0.0', - packages=['src/' + package_name], - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), - (os.path.join('share', package_name), glob('launch/*.launch.py')), - ], - install_requires=['setuptools'], - zip_safe=True, - maintainer='CARLA Simulator Team', - maintainer_email='carla.simulator@gmail.com', - description='CARLA ROS2 bridge', - license='MIT', - tests_require=['pytest'], - entry_points={ - 'console_scripts': [ - 'bridge = carla_ros_bridge.bridge:main' - ], - }, - ) +setup(**d) From fc5242cd02bdb37b0c803230468b08acaf707d42 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 10 Jun 2020 10:26:15 +0200 Subject: [PATCH 207/627] Remove package.xml changes since ROS2 port for carla_ros_bridge is not done yet --- carla_ros_bridge/package.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index e94f23d1..95796837 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -27,6 +27,9 @@ carla_msgs carla_ego_vehicle carla_manual_control +<<<<<<< HEAD +======= +>>>>>>> Remove package.xml changes since ROS2 port for carla_ros_bridge is not done yet From 982d92ed2baf1d51feab0e62ee74ef9aaabe5502 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 10 Jun 2020 10:35:01 +0200 Subject: [PATCH 208/627] Remove CMake carla_ros_bridge changes since is not fully ported yet --- carla_ros_bridge/CMakeLists.txt | 15 +++++++-------- carla_ros_bridge/package.xml | 5 ----- 2 files changed, 7 insertions(+), 13 deletions(-) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 7e212f75..ae737d07 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -3,9 +3,9 @@ project(carla_ros_bridge) ## Find catkin macros and libraries find_package(catkin REQUIRED COMPONENTS - rospy + rospy sensor_msgs - geometry_msgs + geometry_msgs derived_object_msgs ainstein_radar_msgs tf @@ -17,32 +17,31 @@ catkin_python_setup() catkin_package() roslaunch_add_file_check(launch) -roslaunch_add_file_check(test) include_directories( - ${catkin_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} ) install(PROGRAMS src/carla_ros_bridge/bridge.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +) install(FILES test/ros_bridge_client.test DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) +) install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) +) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch ) -if(CATKIN_ENABLE_TESTING AND NOT $ENV{CI}) +if(CATKIN_ENABLE_TESTING) find_package(rostest REQUIRED) add_rostest(test/ros_bridge_client.test) endif() diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 95796837..7a529666 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -27,9 +27,4 @@ carla_msgs carla_ego_vehicle carla_manual_control -<<<<<<< HEAD - - -======= ->>>>>>> Remove package.xml changes since ROS2 port for carla_ros_bridge is not done yet From 92c0bafc22fccdad1bbbbc743e5c25774e2ae616 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Wed, 10 Jun 2020 11:10:30 +0200 Subject: [PATCH 209/627] Update submodule commit --- carla_msgs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_msgs b/carla_msgs index 0501e759..58d8b3f5 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 0501e759321ce314a230e814a58e43cbb66d1fa2 +Subproject commit 58d8b3f58904500e8f8acb7579e5641f4838c0b1 From 9233c09a330f87aeb928e92d255faaa38382f140 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Wed, 10 Jun 2020 11:51:29 +0200 Subject: [PATCH 210/627] Remove blank spaces changes --- carla_ros_bridge/CMakeLists.txt | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index ae737d07..fb76b2b1 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -3,9 +3,9 @@ project(carla_ros_bridge) ## Find catkin macros and libraries find_package(catkin REQUIRED COMPONENTS - rospy + rospy sensor_msgs - geometry_msgs + geometry_msgs derived_object_msgs ainstein_radar_msgs tf @@ -19,23 +19,23 @@ catkin_package() roslaunch_add_file_check(launch) include_directories( - ${catkin_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} ) install(PROGRAMS src/carla_ros_bridge/bridge.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +) install(FILES test/ros_bridge_client.test DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) +) install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) +) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch From c74e87a8c26973210d3f54a09fcea68c48846e7a Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Mon, 15 Jun 2020 15:14:44 +0200 Subject: [PATCH 211/627] Autopep8 the project --- .../carla_ego_vehicle/carla_ego_vehicle.py | 19 +++++------ .../src/carla_ros_bridge/bridge.py | 11 +++---- .../src/carla_ros_bridge/camera.py | 32 ++++++++----------- .../carla_status_publisher.py | 6 ++-- .../src/carla_ros_bridge/communication.py | 10 +++--- .../src/carla_ros_bridge/debug_helper.py | 3 +- .../src/carla_ros_bridge/ego_vehicle.py | 24 ++++++-------- carla_ros_bridge/src/carla_ros_bridge/imu.py | 8 ++--- .../src/carla_ros_bridge/lidar.py | 9 +++--- .../src/carla_ros_bridge/pseudo_actor.py | 3 +- .../src/carla_ros_bridge/sensor.py | 8 ++--- 11 files changed, 56 insertions(+), 77 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 859bc838..5d86ea51 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -16,6 +16,10 @@ /initialpose might be published via RVIZ '2D Pose Estimate" button. """ +import carla +from carla_msgs.msg import CarlaStatus, CarlaWorldInfo +from geometry_msgs.msg import PoseWithCovarianceStamped, Pose +from ros_compatibility import CompatibleNode import json import math import os @@ -35,12 +39,6 @@ from transforms3d.euler import euler2quat as quaternion_from_euler from transforms3d.euler import quat2euler as euler_from_quaternion -from ros_compatibility import CompatibleNode - -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose -from carla_msgs.msg import CarlaStatus, CarlaWorldInfo - -import carla secure_random = random.SystemRandom() @@ -77,7 +75,6 @@ def __init__(self): # check argument and set spawn_point spawn_point_param = self.get_param('~spawn_point') - elif ROS_VERSION == 2: self.host = self.get_param('carla.host', 'localhost') self.port = self.get_param('carla.port', 2000) @@ -108,20 +105,19 @@ def __init__(self): self.actor_spawnpoint = pose self.initialpose_subscriber = self.create_subscriber(PoseWithCovarianceStamped, - "/carla/{}/initialpose".format(self.role_name), + "/carla/{}/initialpose".format( + self.role_name), self.on_initialpose) self.loginfo("listening to server {}:{}".format(self.host, self.port)) self.loginfo("using vehicle filter: {}".format(self.actor_filter)) - def spawn_ego_vehicle(self): if ROS_VERSION == 1: return self.get_param('~spawn_ego_vehicle') elif ROS_VERSION == 2: return self.get_parameter('spawn_ego_vehicle') - def on_initialpose(self, initial_pose): """ Callback for /initialpose @@ -161,7 +157,7 @@ def restart(self): spawn_point.location.x = self.actor_spawnpoint.position.x spawn_point.location.y = -self.actor_spawnpoint.position.y spawn_point.location.z = self.actor_spawnpoint.position.z + \ - 2 # spawn 2m above ground + 2 # spawn 2m above ground quaternion = ( self.actor_spawnpoint.orientation.x, self.actor_spawnpoint.orientation.y, @@ -442,5 +438,6 @@ def main(): init_node.get_logger().info("Waiting for carla_bridge to start...") executor.spin() + if __name__ == '__main__': main() diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index a74095f5..25cfb20d 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -11,7 +11,8 @@ Class that handle communication between CARLA and ROS """ try: - import queue +from ros_compatibility import * +import queue except ImportError: import Queue as queue @@ -56,8 +57,6 @@ else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -from ros_compatibility import * - class CarlaRosBridge(CompatibleNode): """ @@ -124,8 +123,8 @@ def initialize_bridge(self, carla_world, params): self.carla_run_state = CarlaControl.PLAY self.carla_control_subscriber = \ - self.create_subscriber(CarlaControl, "/carla/control", - lambda control: self.carla_control_queue.put(control.command), callback_group=self.callback_group) + self.create_subscriber(CarlaControl, "/carla/control", + lambda control: self.carla_control_queue.put(control.command), callback_group=self.callback_group) self.synchronous_mode_update_thread = Thread(target=self._synchronous_mode_update) self.synchronous_mode_update_thread.start() @@ -149,7 +148,7 @@ def initialize_bridge(self, carla_world, params): self.carla_weather_subscriber = \ self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", - self.on_weather_changed, callback_group=self.callback_group) + self.on_weather_changed, callback_group=self.callback_group) # add world info self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, communication=self.comm)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index a5f4796f..3280a518 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -9,6 +9,15 @@ """ Class to handle Carla camera sensors """ +import carla_ros_bridge.transforms as trans +from carla_ros_bridge.sensor import Sensor +import carla +from sensor_msgs.msg import CameraInfo +from cv_bridge import CvBridge +import numpy +import math +from abc import abstractmethod +from ros_compatibility import * import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -20,20 +29,6 @@ else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -from ros_compatibility import * - -from abc import abstractmethod - -import math -import numpy - -from cv_bridge import CvBridge -from sensor_msgs.msg import CameraInfo - -import carla -from carla_ros_bridge.sensor import Sensor -import carla_ros_bridge.transforms as trans - class Camera(Sensor): """ @@ -110,7 +105,7 @@ def sensor_data_updated(self, carla_image): :type carla_image: carla.Image """ if ((carla_image.height != self._camera_info.height) or - (carla_image.width != self._camera_info.width)): + (carla_image.width != self._camera_info.width)): self.logerr("Camera{} received image not matching configuration".format( self.get_prefix())) image_data_array, encoding = self.get_carla_image_data_array(carla_image=carla_image) @@ -124,7 +119,8 @@ def sensor_data_updated(self, carla_image): if ROS_VERSION == 1: self.publish_message(self.get_topic_prefix() + '/camera_info', cam_info) elif ROS_VERSION == 2: - self.publish_message(self.get_topic_prefix() + '/' + self.get_image_topic_name() + '/camera_info', cam_info) + self.publish_message(self.get_topic_prefix() + '/' + + self.get_image_topic_name() + '/camera_info', cam_info) self.publish_message(self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): @@ -142,10 +138,10 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): quat = [rotation.x, rotation.y, rotation.z, rotation.w] if ROS_VERSION == 1: quat_swap = quaternion_from_matrix([[0, 0, 1, 0], [-1, 0, 0, 0], - [0, -1, 0, 0], [0, 0, 0, 1]]) + [0, -1, 0, 0], [0, 0, 0, 1]]) elif ROS_VERSION == 2: quat_swap = quaternion_from_matrix(numpy.asarray([numpy.asarray([0, 0, 1]), numpy.asarray([-1, 0, 0]), - numpy.asarray([0, -1, 0])])) + numpy.asarray([0, -1, 0])])) quat = quaternion_multiply(quat, quat_swap) tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion(quat) diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index e09c43b7..4f883ccf 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -9,6 +9,8 @@ """ report the carla status """ +from carla_msgs.msg import CarlaStatus +from ros_compatibility import * import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -19,10 +21,6 @@ if ROS_VERSION == 2: from rclpy.callback_groups import ReentrantCallbackGroup -from ros_compatibility import * - -from carla_msgs.msg import CarlaStatus - class CarlaStatusPublisher(CompatibleNode): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index b96bc682..7dd96323 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -9,6 +9,9 @@ """ Handle communication of ROS topics """ +from tf2_msgs.msg import TFMessage +from rosgraph_msgs.msg import Clock +from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile, latch_on import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -19,10 +22,6 @@ from rclpy.callback_groups import ReentrantCallbackGroup from builtin_interfaces.msg import Time -from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile, latch_on -from rosgraph_msgs.msg import Clock -from tf2_msgs.msg import TFMessage - class Communication(CompatibleNode): """ @@ -102,7 +101,8 @@ def publish_message(self, topic, msg, is_latched=False): if topic not in self.pub: if is_latched: latched_profile = QoSProfile(depth=10, durability=latch_on) - self.pub[topic] = self.new_publisher(type(msg), topic, qos_profile=latched_profile) + self.pub[topic] = self.new_publisher( + type(msg), topic, qos_profile=latched_profile) else: # Use default QoS profile. self.pub[topic] = self.new_publisher(type(msg), topic) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 2348a7fe..3ce1b798 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -8,6 +8,7 @@ """ Class to draw marker """ +from ros_compatibility import * import carla from visualization_msgs.msg import Marker, MarkerArray import math @@ -23,8 +24,6 @@ raise NotImplementedError( 'Make sure you have valid ' + 'ROS_VERSION env variable') -from ros_compatibility import * - class DebugHelper(CompatibleNode): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index eecc9fb2..a3c14c48 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -9,6 +9,16 @@ """ Classes to handle Carla vehicles """ +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel,\ + CarlaEgoVehicleControl, CarlaEgoVehicleStatus +import carla_ros_bridge.transforms as transforms +from carla_ros_bridge.vehicle import Vehicle +from carla import Vector3D +from carla import VehicleControl +from geometry_msgs.msg import Twist, Transform +from std_msgs.msg import Bool +from std_msgs.msg import ColorRGBA +from ros_compatibility import * import math import numpy @@ -21,20 +31,6 @@ if ROS_VERSION == 2: from rclpy.callback_groups import ReentrantCallbackGroup -from ros_compatibility import * -from std_msgs.msg import ColorRGBA -from std_msgs.msg import Bool -from geometry_msgs.msg import Twist, Transform - -from carla import VehicleControl -from carla import Vector3D - -from carla_ros_bridge.vehicle import Vehicle -import carla_ros_bridge.transforms as transforms - -from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel,\ - CarlaEgoVehicleControl, CarlaEgoVehicleStatus - class EgoVehicle(Vehicle, CompatibleNode): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 2494894b..739f39b4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -6,6 +6,9 @@ """ Classes to handle Carla imu sensor """ +import carla_ros_bridge.transforms as trans +from carla_ros_bridge.sensor import Sensor +from sensor_msgs.msg import Imu import math import os @@ -18,11 +21,6 @@ else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -from sensor_msgs.msg import Imu - -from carla_ros_bridge.sensor import Sensor -import carla_ros_bridge.transforms as trans - class ImuSensor(Sensor): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 61f12348..ae99c32a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -11,6 +11,9 @@ """ from __future__ import print_function +import carla_ros_bridge.transforms as trans +from carla_ros_bridge.sensor import Sensor +from sensor_msgs.msg import PointCloud2, PointField import numpy import ctypes @@ -28,10 +31,6 @@ else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -from sensor_msgs.msg import PointCloud2, PointField - -from carla_ros_bridge.sensor import Sensor -import carla_ros_bridge.transforms as trans _DATATYPES = {} _DATATYPES[PointField.FLOAT32] = ('f', 4) @@ -164,4 +163,4 @@ def _get_struct_fmt(is_bigendian, fields, field_names=None): fmt += field.count * datatype_fmt offset += field.count * datatype_length - return fmt \ No newline at end of file + return fmt diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index b1b6544d..9bf2f4f7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -9,6 +9,7 @@ Base Class to handle Pseudo Actors (that are not existing in Carla world) """ +from ros_compatibility import CompatibleNode, ros_timestamp from std_msgs.msg import Header import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -16,8 +17,6 @@ if ROS_VERSION not in (1, 2): raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -from ros_compatibility import CompatibleNode, ros_timestamp - class PseudoActor(CompatibleNode): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 8ec71056..47d2dcb3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -8,6 +8,9 @@ """ Classes to handle Carla sensors """ +import carla_ros_bridge.transforms as trans +from carla_ros_bridge.actor import Actor +from ros_compatibility import CompatibleNode, ros_ok from abc import abstractmethod try: import queue @@ -20,11 +23,6 @@ if ROS_VERSION not in (1, 2): raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -from ros_compatibility import CompatibleNode, ros_ok - -from carla_ros_bridge.actor import Actor -import carla_ros_bridge.transforms as trans - class Sensor(Actor, CompatibleNode): """ From d0437c12f51ede053c9f637dc02dd38d0e1ebec6 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 8 Jun 2020 17:15:50 +0200 Subject: [PATCH 212/627] Scenario execution: Support ROS controller in OpenScenario --- .travis.yml | 3 +- carla_ad_demo/README.md | 12 ++- .../config/FollowLeadingVehicle.xosc | 96 +++++-------------- carla_ad_demo/launch/carla_ad_demo.launch | 15 +-- ...nch => carla_ad_demo_with_scenario.launch} | 38 ++++---- carla_common/CMakeLists.txt | 13 +++ carla_common/package.xml | 12 +++ carla_common/setup.py | 13 +++ carla_common/src/carla_common/__init__.py | 0 .../src/carla_common}/transforms.py | 0 .../launch/carla_ego_vehicle.launch | 1 - .../launch/carla_example_ego_vehicle.launch | 3 +- carla_ros_bridge/config/settings.yaml | 2 +- carla_ros_bridge/package.xml | 1 + .../src/carla_ros_bridge/actor.py | 2 +- .../src/carla_ros_bridge/camera.py | 2 +- .../src/carla_ros_bridge/ego_vehicle.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 +- .../src/carla_ros_bridge/lidar.py | 2 +- .../src/carla_ros_bridge/sensor.py | 4 +- .../src/carla_ros_bridge/traffic.py | 2 +- carla_ros_scenario_runner/CMakeLists.txt | 1 + carla_ros_scenario_runner/README.md | 6 +- .../launch/carla_ros_scenario_runner.launch | 6 +- carla_ros_scenario_runner/package.xml | 1 + .../carla_ros_scenario_runner.py | 44 +-------- .../ros_vehicle_control.py | 91 ++++++++++++++++++ .../scenario_runner_runner.py | 6 +- .../msg/CarlaScenario.msg | 3 - check.sh | 3 +- 30 files changed, 219 insertions(+), 167 deletions(-) rename carla_ad_demo/launch/{carla_ad_demo_with_rviz.launch => carla_ad_demo_with_scenario.launch} (79%) create mode 100644 carla_common/CMakeLists.txt create mode 100644 carla_common/package.xml create mode 100644 carla_common/setup.py create mode 100644 carla_common/src/carla_common/__init__.py rename {carla_ros_bridge/src/carla_ros_bridge => carla_common/src/carla_common}/transforms.py (100%) create mode 100644 carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py diff --git a/.travis.yml b/.travis.yml index 75fa0fac..53fe44a3 100644 --- a/.travis.yml +++ b/.travis.yml @@ -27,6 +27,7 @@ jobs: before_install: skip install: pip install --user pep8 autopep8 script: + - autopep8 carla_ros_bridge/src/carla_common/*.py --in-place --max-line-length=100 - autopep8 carla_ros_bridge/src/carla_ros_bridge/*.py --in-place --max-line-length=100 - autopep8 carla_ackermann_control/src/carla_ackermann_control/*.py --in-place --max-line-length=100 - autopep8 carla_ego_vehicle/src/carla_ego_vehicle/*.py --in-place --max-line-length=100 @@ -79,7 +80,7 @@ script: - catkin config --install - source devel/setup.bash - cd src/ros-bridge - - pylint --rcfile=.pylintrc carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ + - pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ after_failure: - tail --lines=2000 build.log diff --git a/carla_ad_demo/README.md b/carla_ad_demo/README.md index 2bcb2299..c530e90c 100644 --- a/carla_ad_demo/README.md +++ b/carla_ad_demo/README.md @@ -11,7 +11,7 @@ The Node setup is visualized [here](../docs/images/ad_demo.png "AD Demo Node Set export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ export SCENARIO_RUNNER_PATH= - roslaunch carla_ad_demo carla_ad_demo_with_rviz.launch + roslaunch carla_ad_demo carla_ad_demo.launch ### Modes @@ -27,11 +27,15 @@ You can modify start position and goal within the [launch file](launch/carla_ad_ #### Scenario Execution -If you prefer to execute a predefined scenario, select to example scenario "FollowLeadingVehicle" within the RVIZ Carla Plugin and press "Execute". The ego vehicle gets repositioned and the scenario is processed. +If you prefer to execute a predefined scenario, launch: -You can specify your own scenarios by publishing to `/carla/available_scenarios`. See the [launch file](launch/carla_ad_demo_with_rviz.launch) for an example. + roslaunch carla_ad_demo carla_ad_demo_with_scenario.launch + +Select to example scenario "FollowLeadingVehicle" within the RVIZ Carla Plugin and press "Execute". The ego vehicle gets repositioned and the scenario is processed. +You can specify your own scenarios by publishing to `/carla/available_scenarios`. See the [launch file](launch/carla_ad_demo_with_scenario.launch) for an example. -## Troubleshooting + +##### Troubleshooting If the example scenario fails, please analyze the ros log and follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working standalone. diff --git a/carla_ad_demo/config/FollowLeadingVehicle.xosc b/carla_ad_demo/config/FollowLeadingVehicle.xosc index 7011b7fc..904557b7 100644 --- a/carla_ad_demo/config/FollowLeadingVehicle.xosc +++ b/carla_ad_demo/config/FollowLeadingVehicle.xosc @@ -1,34 +1,10 @@ - + - - - - - - - - - - - - - - - - - - - - - - - - @@ -95,7 +71,28 @@ - + + + + + + + + + + + + + + + + + + + + + + @@ -120,7 +117,7 @@ - + @@ -143,53 +140,10 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -215,7 +169,7 @@ - + diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 48a21178..39ad3dcd 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -18,9 +18,6 @@ - - - @@ -64,14 +61,10 @@ - - - - - - - + + + + - diff --git a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch similarity index 79% rename from carla_ad_demo/launch/carla_ad_demo_with_rviz.launch rename to carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index e636d320..9c618993 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -15,10 +15,7 @@ - - - @@ -27,8 +24,8 @@ - - + + @@ -36,12 +33,24 @@ - + + + + + + + - - - - + + + + + + + + + + @@ -67,11 +76,7 @@ [ { 'name': 'FollowLeadingVehicle', - 'scenario_file': '$(find carla_ad_demo)/config/FollowLeadingVehicle.xosc', - 'waypoints': [ - { 'position': { 'x': 7.1, 'y': 187.3, 'z': 0.0 } } - ], - 'target_speed': 15 + 'scenario_file': '$(find carla_ad_demo)/config/FollowLeadingVehicle.xosc' } ] }' -l"/> @@ -80,8 +85,7 @@ - - + diff --git a/carla_common/CMakeLists.txt b/carla_common/CMakeLists.txt new file mode 100644 index 00000000..75e71fe3 --- /dev/null +++ b/carla_common/CMakeLists.txt @@ -0,0 +1,13 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_common) + +find_package(catkin) + +catkin_python_setup() + +catkin_package() + +catkin_install_python(PROGRAMS + src/carla_common/transforms.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) diff --git a/carla_common/package.xml b/carla_common/package.xml new file mode 100644 index 00000000..aacd9c7c --- /dev/null +++ b/carla_common/package.xml @@ -0,0 +1,12 @@ + + + carla_common + 0.0.1 + The carla_common package + CARLA Simulator Team + MIT + catkin + rospy + + + diff --git a/carla_common/setup.py b/carla_common/setup.py new file mode 100644 index 00000000..5d53510d --- /dev/null +++ b/carla_common/setup.py @@ -0,0 +1,13 @@ +""" +Setup for carla_common +""" + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_common'], + package_dir={'': 'src'} +) + +setup(**d) diff --git a/carla_common/src/carla_common/__init__.py b/carla_common/src/carla_common/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_ros_bridge/src/carla_ros_bridge/transforms.py b/carla_common/src/carla_common/transforms.py similarity index 100% rename from carla_ros_bridge/src/carla_ros_bridge/transforms.py rename to carla_common/src/carla_common/transforms.py diff --git a/carla_ego_vehicle/launch/carla_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_ego_vehicle.launch index efb0e5f3..3b12e060 100644 --- a/carla_ego_vehicle/launch/carla_ego_vehicle.launch +++ b/carla_ego_vehicle/launch/carla_ego_vehicle.launch @@ -33,4 +33,3 @@ - diff --git a/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch index cc1e204c..e3072989 100644 --- a/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch +++ b/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch @@ -8,6 +8,7 @@ + @@ -17,6 +18,6 @@ + - diff --git a/carla_ros_bridge/config/settings.yaml b/carla_ros_bridge/config/settings.yaml index 84c94bcf..103d6a66 100644 --- a/carla_ros_bridge/config/settings.yaml +++ b/carla_ros_bridge/config/settings.yaml @@ -16,4 +16,4 @@ carla: # the role name of the vehicles that acts as ego vehicle for this ros bridge instance # Only the vehicles within this list are controllable from within ROS. # (the vehicle from CARLA is selected which has the attribute 'role_name' set to this value) - role_name: ["hero", "ego_vehicle", "hero1", "hero2", "hero3"] + role_name: ["hero", "ego_vehicle", "hero0", "hero1", "hero2", "hero3", "hero4", "hero5", "hero6", "hero7", "hero8", "hero9", ] diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index e94f23d1..8bf2b6cc 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -9,6 +9,7 @@ roslaunch ainstein_radar_msgs rospy + carla_common sensor_msgs visualization_msgs tf diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index eb4e7d32..262d1375 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -16,7 +16,7 @@ from visualization_msgs.msg import Marker from carla_ros_bridge.pseudo_actor import PseudoActor -import carla_ros_bridge.transforms as trans +import carla_common.transforms as trans class Actor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 7ba8ec83..20464479 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -21,7 +21,7 @@ import carla from carla_ros_bridge.sensor import Sensor -import carla_ros_bridge.transforms as trans +import carla_common.transforms as trans class Camera(Sensor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index c15daaaa..30c74e8c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -22,7 +22,7 @@ from carla import Vector3D from carla_ros_bridge.vehicle import Vehicle -import carla_ros_bridge.transforms as transforms +import carla_common.transforms as transforms from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel,\ CarlaEgoVehicleControl, CarlaEgoVehicleStatus diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index ddd6b762..8582a0ef 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -13,7 +13,7 @@ from sensor_msgs.msg import Imu from carla_ros_bridge.sensor import Sensor -import carla_ros_bridge.transforms as trans +import carla_common.transforms as trans class ImuSensor(Sensor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 68dcbba7..0e04d1d7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -17,7 +17,7 @@ from sensor_msgs.point_cloud2 import create_cloud_xyz32 from carla_ros_bridge.sensor import Sensor -import carla_ros_bridge.transforms as trans +import carla_common.transforms as trans class Lidar(Sensor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index d025ec10..ded88160 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -18,7 +18,7 @@ import rospy from carla_ros_bridge.actor import Actor -import carla_ros_bridge.transforms as trans +import carla_common.transforms as trans class Sensor(Actor): @@ -153,7 +153,7 @@ def _update_synchronous_sensor(self, frame, timestamp): carla_sensor_data.transform))) self.sensor_data_updated(carla_sensor_data) return - else: + elif carla_sensor_data.frame < frame: rospy.logwarn("{}({}): skipping old frame {}, expected {}".format( self.__class__.__name__, self.get_id(), diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 04690cc4..ead18d86 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -11,7 +11,7 @@ """ from carla_ros_bridge.actor import Actor -import carla_ros_bridge.transforms as trans +import carla_common.transforms as trans from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo from carla import TrafficLightState diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt index 39ddf14f..f62a0ff1 100644 --- a/carla_ros_scenario_runner/CMakeLists.txt +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -15,6 +15,7 @@ catkin_install_python(PROGRAMS src/carla_ros_scenario_runner/carla_ros_scenario_runner.py src/carla_ros_scenario_runner/application_runner.py src/carla_ros_scenario_runner/scenario_runner_runner.py + src/carla_ros_scenario_runner/ros_vehicle_control.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) diff --git a/carla_ros_scenario_runner/README.md b/carla_ros_scenario_runner/README.md index ab803b35..fbadac39 100644 --- a/carla_ros_scenario_runner/README.md +++ b/carla_ros_scenario_runner/README.md @@ -4,6 +4,8 @@ This is a wrapper to execute OpenScenarios with the CARLA [scenario runner](http It is best used from within the [rviz_carla_plugin](../rviz_carla_plugin). +Currently it is not supported to switch the Carla Town. Therefore the scenario needs to use the currently active Town. + ## Setup Please follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) and verify, that scenario_runner is working, if started manually. @@ -24,7 +26,7 @@ To run the ROS node: To run a scenario from commandline: - rosservice call /scenario_runner/execute_scenario "{ 'scenario': { 'scenario_file': '', 'target_speed': 10.0, 'destination': { 'position': { 'x': 10, 'y': 10, 'z':0 } } } }" + rosservice call /scenario_runner/execute_scenario "{ 'scenario': { 'scenario_file': '' } }" ## Available services @@ -39,7 +41,5 @@ To run a scenario from commandline: | Topic | Description | Type | | ------------------------------------- | ----------- | -------------------------------------------------------------------- | -| `/carla//target_speed` | The ego vehicle target speed | [std_msgs.Float64](http://docs.ros.org/api/std_msgs/html/msg/Float64.html) | -| `/carla//goal` | The ego vehicle destination (e.g. used by [carla_waypoint_publisher](../carla_waypoint_publisher)) | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | | `/scenario_runner/status` | The current status of the scenario runner execution (e.g. used by the [rviz_carla_plugin](../rviz_carla_plugin)) | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch index 59666293..23cd19c6 100644 --- a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch @@ -4,16 +4,14 @@ - - + - - + diff --git a/carla_ros_scenario_runner/package.xml b/carla_ros_scenario_runner/package.xml index a7701fe1..271ac958 100644 --- a/carla_ros_scenario_runner/package.xml +++ b/carla_ros_scenario_runner/package.xml @@ -13,6 +13,7 @@ carla_msgs carla_ros_scenario_runner_types std_msgs + carla_common diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py index 83c04b78..af4d5c63 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -47,22 +47,10 @@ class CarlaRosScenarioRunner(object): Execute scenarios via ros service """ - def __init__(self, role_name, host, port, scenario_runner_path, publish_waypoints, publish_goal): + def __init__(self, role_name, host, port, scenario_runner_path, wait_for_ego): """ Constructor """ - self._goal_publisher = None - if publish_goal: - self._goal_publisher = rospy.Publisher( - "/carla/{}/goal".format(role_name), PoseStamped, queue_size=1, latch=True) - self._target_speed_publisher = rospy.Publisher( - "/carla/{}/target_speed".format(role_name), Float64, queue_size=1, latch=True) - - self._path_publisher = None - if publish_waypoints: - self._path_publisher = rospy.Publisher( - "/carla/{}/waypoints".format(role_name), Path, queue_size=1, latch=True) - self._status_publisher = rospy.Publisher( "/scenario_runner/status", CarlaScenarioRunnerStatus, queue_size=1, latch=True) self.scenario_runner_status_updated(ApplicationStatus.STOPPED) @@ -70,6 +58,7 @@ def __init__(self, role_name, host, port, scenario_runner_path, publish_waypoint scenario_runner_path, host, port, + wait_for_ego, self.scenario_runner_status_updated, self.scenario_runner_log) self._request_queue = queue.Queue() @@ -136,29 +125,7 @@ def run(self): # execute scenario scenario_executed = self._scenario_runner.execute_scenario( current_req.scenario_file) - if scenario_executed: - # publish target speed - self._target_speed_publisher.publish(Float64(data=current_req.target_speed)) - - # publish last pose of route as goal - # (can be used in conjunction with carla_waypoint_publisher) - if self._goal_publisher: - goal = PoseStamped() - if current_req.waypoints: - goal.pose = current_req.waypoints[-1] - goal.header.stamp = rospy.get_rostime() - goal.header.frame_id = "map" - self._goal_publisher.publish(goal) - - # publish the waypoints (can directly be used within carla_ad_agent) - if self._path_publisher: - path = Path() - path.header.stamp = rospy.get_rostime() - path.header.frame_id = "map" - for pose in current_req.waypoints: - path.poses.append(PoseStamped(pose=pose)) - self._path_publisher.publish(path) - else: + if not scenario_executed: rospy.logwarn("Unable to execute scenario.") current_req = None else: @@ -182,12 +149,11 @@ def main(): rospy.init_node('carla_ros_scenario_runner', anonymous=True) role_name = rospy.get_param("~role_name", "ego_vehicle") scenario_runner_path = rospy.get_param("~scenario_runner_path", "") + wait_for_ego = rospy.get_param("~wait_for_ego", "True") host = rospy.get_param("~host", "localhost") port = rospy.get_param("~port", 2000) - publish_waypoints = rospy.get_param("~publish_waypoints", False) - publish_goal = rospy.get_param("~publish_goal", True) scenario_runner = CarlaRosScenarioRunner( - role_name, host, port, scenario_runner_path, publish_waypoints, publish_goal) + role_name, host, port, scenario_runner_path, wait_for_ego) try: scenario_runner.run() finally: diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py new file mode 100644 index 00000000..b98f2a24 --- /dev/null +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -0,0 +1,91 @@ +#!/usr/bin/env python + +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +import rospy +import roslaunch +from std_msgs.msg import Float64 +from geometry_msgs.msg import PoseStamped +from nav_msgs.msg import Path +import carla_common.transforms as trans +from srunner.scenariomanager.actorcontrols.basic_control import BasicControl + + +class RosVehicleControl(BasicControl): + + def __init__(self, actor, args=None): + super(RosVehicleControl, self).__init__(actor) + self._carla_actor = actor + self._role_name = actor.attributes["role_name"] + if not self._role_name: + rospy.logerr("Invalid role_name!") + + rospy.init_node('ros_agent_{}'.format(self._role_name)) + self._current_target_speed = None + self._current_path = None + + self._target_speed_publisher = rospy.Publisher( + "/carla/{}/target_speed".format(self._role_name), Float64, queue_size=1, latch=True) + + self._path_publisher = rospy.Publisher( + "/carla/{}/waypoints".format(self._role_name), Path, queue_size=1, latch=True) + + if "launch" in args and "launch-package" in args: + uuid = roslaunch.rlutil.get_or_generate_uuid(None, False) + roslaunch.configure_logging(uuid) + launch_file = args["launch"] + launch_package = args["launch-package"] + + cli_args = [launch_package, launch_file] + cli_args.append('role_name:={}'.format(self._role_name)) + + # add additional launch parameters + launch_parameters = [] + for key, value in args.items(): + if not key == "launch" and not key == "launch-package": + launch_parameters.append('{}:={}'.format(key, value)) + cli_args.append('{}:={}'.format(key, value)) + + rospy.loginfo("{}: Launching {} from package {} (parameters: {})...".format( + self._role_name, launch_file, launch_package, launch_parameters)) + roslaunch_file = roslaunch.rlutil.resolve_launch_arguments(cli_args) + roslaunch_args = cli_args[2:] + launch_files = [(roslaunch_file[0], roslaunch_args)] + parent = roslaunch.parent.ROSLaunchParent(uuid, launch_files) + parent.start() + rospy.loginfo("{}: Successfully started ros vehicle control".format(self._role_name)) + else: + rospy.logerr( + "{}: Missing value for 'launch' and/or 'launch-package'.".format(self._role_name)) + + def update_target_speed(self, speed): + super(RosVehicleControl, self).update_target_speed(speed) + rospy.loginfo("{}: Target speed changed to {}".format(self._role_name, speed)) + self._target_speed_publisher.publish(Float64(data=speed)) + + def update_waypoints(self, waypoints, start_time=None): + super(RosVehicleControl, self).update_waypoints(waypoints, start_time) + rospy.loginfo("{}: Waypoints changed.".format(self._role_name)) + path = Path() + path.header.stamp = rospy.get_rostime() + path.header.frame_id = "map" + for wpt in waypoints: + print(wpt) + path.poses.append(PoseStamped(pose=trans.carla_transform_to_ros_pose(wpt))) + self._path_publisher.publish(path) + + def reset(self): + if self._carla_actor and self._carla_actor.is_alive: + self._carla_actor = None + if self._target_speed_publisher: + self._target_speed_publisher.unregister() + self._target_speed_publisher = None + if self._path_publisher: + self._path_publisher.unregister() + self._path_publisher = None + + def run_step(self): + pass diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py index 3216ccdd..b811c6ab 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py @@ -14,10 +14,11 @@ class ScenarioRunnerRunner(ApplicationRunner): Executes scenario runner """ - def __init__(self, path, host, port, status_updated_fct, log_fct): + def __init__(self, path, host, port, wait_for_ego, status_updated_fct, log_fct): self._path = path self._host = host self._port = port + self._wait_for_ego = wait_for_ego super(ScenarioRunnerRunner, self).__init__( status_updated_fct, log_fct, @@ -29,8 +30,9 @@ def execute_scenario(self, scenario_file): """ cmdline = ["/usr/bin/python", "{}/scenario_runner.py".format(self._path), "--openscenario", "{}".format(scenario_file), - "--waitForEgo", "--timeout", "1000000", "--host", self._host, "--port", str(self._port)] + if self._wait_for_ego: + cmdline.append("--waitForEgo") return self.execute(cmdline, env=os.environ) diff --git a/carla_ros_scenario_runner_types/msg/CarlaScenario.msg b/carla_ros_scenario_runner_types/msg/CarlaScenario.msg index 0b32ca5a..d8eafbac 100644 --- a/carla_ros_scenario_runner_types/msg/CarlaScenario.msg +++ b/carla_ros_scenario_runner_types/msg/CarlaScenario.msg @@ -6,6 +6,3 @@ # string name string scenario_file -geometry_msgs/Pose[] waypoints -float64 target_speed - diff --git a/check.sh b/check.sh index b16ec844..f69f8988 100755 --- a/check.sh +++ b/check.sh @@ -1,4 +1,5 @@ #!/bin/bash +autopep8 carla_common/src/carla_common/*.py --in-place --max-line-length=100 autopep8 carla_ros_bridge/src/carla_ros_bridge/*.py --in-place --max-line-length=100 autopep8 carla_ackermann_control/src/carla_ackermann_control/*.py --in-place --max-line-length=100 autopep8 carla_ego_vehicle/src/carla_ego_vehicle/*.py --in-place --max-line-length=100 @@ -10,4 +11,4 @@ autopep8 carla_twist_to_control/src/carla_twist_to_control/*.py --in-place --max autopep8 carla_spectator_camera/src/carla_spectator_camera/*.py --in-place --max-line-length=100 autopep8 carla_infrastructure/src/carla_infrastructure/*.py --in-place --max-line-length=100 -pylint --rcfile=.pylintrc carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ +pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ From 06e10004ffbb54105fa277b93eed49208e9d065a Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Mon, 15 Jun 2020 17:43:58 +0200 Subject: [PATCH 213/627] Use own messages for radar measurements (#317) --- README.md | 4 +--- carla_msgs | 2 +- carla_ros_bridge/CMakeLists.txt | 1 - carla_ros_bridge/package.xml | 1 - .../src/carla_ros_bridge/radar.py | 21 +++++++++---------- carla_ros_bridge/test/ros_bridge_client.py | 5 ++--- docker/Dockerfile | 1 - packaging/CreateROSbridgeDebian.sh | 3 +-- 8 files changed, 15 insertions(+), 23 deletions(-) diff --git a/README.md b/README.md index db733ad3..78639e54 100644 --- a/README.md +++ b/README.md @@ -181,9 +181,7 @@ Currently the following sensors are supported: | Topic | Type | | --------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | -| `/carla//radar//radar` | [ainstein_radar_msgs.RadarTargetArray](https://github.com/AinsteinAI/ainstein_radar/blob/master/ainstein_radar_msgs/msg/RadarTargetArray.msg) | - -Radar data can be visualized on rviz using [ainstein_radar_rviz_plugins](https://wiki.ros.org/ainstein_radar_rviz_plugins). +| `/carla//radar//radar` | [carla_msgs.CarlaRadarMeasurement](carla_msgs/msg/CarlaRadarMeasurement.msg) | ##### IMU diff --git a/carla_msgs b/carla_msgs index 708e9c83..c89458b3 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 708e9c830bbd1637f89b5cf49dae8c3a327d021a +Subproject commit c89458b34aefbe7e12cefe3241c3b48f4a9b35d7 diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 7e212f75..46b147a2 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -7,7 +7,6 @@ find_package(catkin REQUIRED COMPONENTS sensor_msgs geometry_msgs derived_object_msgs - ainstein_radar_msgs tf roslaunch ) diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 8bf2b6cc..ef4e9c12 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -7,7 +7,6 @@ MIT catkin roslaunch - ainstein_radar_msgs rospy carla_common sensor_msgs diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 65d042cc..4cfa93e4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -9,9 +9,8 @@ """ Classes to handle Carla Radar """ -import math -from ainstein_radar_msgs.msg import RadarTarget, RadarTargetArray +from carla_msgs.msg import CarlaRadarMeasurement, CarlaRadarDetection from carla_ros_bridge.sensor import Sensor @@ -48,13 +47,13 @@ def sensor_data_updated(self, carla_radar_measurement): :param carla_radar_measurement: carla Radar measurement object :type carla_radar_measurement: carla.RadarMeasurement """ - radar_target_array = RadarTargetArray() - radar_target_array.header = self.get_msg_header(timestamp=carla_radar_measurement.timestamp) + radar_msg = CarlaRadarMeasurement() + radar_msg.header = self.get_msg_header(timestamp=carla_radar_measurement.timestamp) for detection in carla_radar_measurement: - radar_target = RadarTarget() - radar_target.elevation = math.degrees(detection.altitude) - radar_target.speed = detection.velocity - radar_target.azimuth = math.degrees(detection.azimuth) - radar_target.range = detection.depth - radar_target_array.targets.append(radar_target) - self.publish_message(self.get_topic_prefix() + "/radar", radar_target_array) + radar_detection = CarlaRadarDetection() + radar_detection.altitude = detection.altitude + radar_detection.azimuth = detection.azimuth + radar_detection.depth = detection.depth + radar_detection.velocity = detection.velocity + radar_msg.detections.append(radar_detection) + self.publish_message(self.get_topic_prefix() + "/radar", radar_msg) diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index ad584049..7a016ab2 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -16,14 +16,13 @@ from std_msgs.msg import Header from rosgraph_msgs.msg import Clock from sensor_msgs.msg import CameraInfo, NavSatFix, Image, PointCloud2, Imu -from ainstein_radar_msgs.msg import RadarTargetArray from geometry_msgs.msg import Quaternion, Vector3, Pose from nav_msgs.msg import Odometry from derived_object_msgs.msg import ObjectArray from visualization_msgs.msg import Marker from carla_msgs.msg import (CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, CarlaActorList, CarlaTrafficLightStatusList, - CarlaTrafficLightInfoList) + CarlaTrafficLightInfoList, CarlaRadarMeasurement) PKG = 'test_roslaunch' TIMEOUT = 20 @@ -149,7 +148,7 @@ def test_radar(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/radar/front/radar", RadarTargetArray, timeout=TIMEOUT) + "/carla/ego_vehicle/radar/front/radar", CarlaRadarMeasurement, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/radar/front") def test_ego_vehicle_objects(self): diff --git a/docker/Dockerfile b/docker/Dockerfile index 9e5e54c5..49e024f0 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -17,7 +17,6 @@ RUN apt-get update \ ros-$ROS_VERSION-cv-bridge \ ros-$ROS_VERSION-pcl-conversions \ ros-$ROS_VERSION-pcl-ros \ - ros-$ROS_VERSION-ainstein-radar \ python-catkin-tools \ && rm -rf /var/lib/apt/lists/* diff --git a/packaging/CreateROSbridgeDebian.sh b/packaging/CreateROSbridgeDebian.sh index 7b820a90..aa01b723 100644 --- a/packaging/CreateROSbridgeDebian.sh +++ b/packaging/CreateROSbridgeDebian.sh @@ -27,7 +27,7 @@ cd catkin_ws source /opt/ros/$(rosversion -d)/setup.bash #installing required dependency packages to build catkin_make -sudo apt install ros-$(rosversion -d)-ainstein-radar-msgs ros-$(rosversion -d)-derived-object-msgs \ +sudo apt install ros-$(rosversion -d)-derived-object-msgs \ ros-$(rosversion -d)-ackermann-msgs ros-$(rosversion -d)-carla-msgs ros-$(rosversion -d)-pcl-conversions \ ros-$(rosversion -d)-rviz ros-$(rosversion -d)-rqt ros-$(rosversion -d)-pcl-ros @@ -84,7 +84,6 @@ Depends: ros-$(rosversion -d)-carla-msgs, ros-$(rosversion -d)-message-runtime, ros-$(rosversion -d)-geometry-msgs, ros-$(rosversion -d)-message-generation, - ros-$(rosversion -d)-ainstein-radar-msgs, ros-$(rosversion -d)-visualization-msgs, ros-$(rosversion -d)-tf, ros-$(rosversion -d)-tf2, From 21473d911aebb06b2856fe899a77e708b76cbbb6 Mon Sep 17 00:00:00 2001 From: sergimoya Date: Thu, 18 Jun 2020 10:06:14 +0200 Subject: [PATCH 214/627] Fix try identation error --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 25cfb20d..716c91eb 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -10,9 +10,10 @@ Class that handle communication between CARLA and ROS """ -try: + from ros_compatibility import * -import queue +try: + import queue except ImportError: import Queue as queue From 94256f5f37b277073026cd659b0b6f88426948af Mon Sep 17 00:00:00 2001 From: sergimoya Date: Thu, 18 Jun 2020 10:07:27 +0200 Subject: [PATCH 215/627] Add custom create_cloudxzy method --- .../src/carla_ros_bridge/lidar.py | 89 ++++++++++--------- 1 file changed, 47 insertions(+), 42 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index ae99c32a..00a2b19a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -24,6 +24,7 @@ if ROS_VERSION == 1: from tf.transformations import euler_from_quaternion, quaternion_from_euler + from sensor_msgs.point_cloud2 import create_cloud_xyz32 elif ROS_VERSION == 2: from transforms3d.euler import euler2quat as quaternion_from_euler from transforms3d.euler import quat2euler as euler_from_quaternion @@ -97,53 +98,57 @@ def sensor_data_updated(self, carla_lidar_measurement): lidar_data = -lidar_data # we also need to permute x and y lidar_data = lidar_data[..., [1, 0, 2]] + if ROS_VERSION == 1: + point_cloud_msg = create_cloud_xyz32(header, lidar_data) # -- taken from http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html - - point_field_x_msg = PointField() - point_field_x_msg.name = "x" - point_field_x_msg.offset = 0 - point_field_x_msg.datatype = PointField.FLOAT32 - point_field_x_msg.count = 1 - - point_field_y_msg = PointField() - point_field_y_msg.name = "y" - point_field_y_msg.offset = 4 - point_field_y_msg.datatype = PointField.FLOAT32 - point_field_y_msg.count = 1 - - point_field_z_msg = PointField() - point_field_z_msg.name = "z" - point_field_z_msg.offset = 8 - point_field_z_msg.datatype = PointField.FLOAT32 - point_field_z_msg.count = 1 - - fields = [point_field_x_msg, point_field_y_msg, point_field_z_msg] - - cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) - buff = ctypes.create_string_buffer(cloud_struct.size * len(lidar_data)) - - point_step, pack_into = cloud_struct.size, cloud_struct.pack_into - - offset = 0 - for pt in lidar_data: - pack_into(buff, offset, *pt) - offset += point_step - - point_cloud_msg = PointCloud2() - point_cloud_msg.header = header - point_cloud_msg.height = 1 - point_cloud_msg.width = len(lidar_data) - point_cloud_msg.is_dense = False - point_cloud_msg.is_bigendian = False - point_cloud_msg.fields = fields - point_cloud_msg.point_step = cloud_struct.size - point_cloud_msg.row_step = cloud_struct.size * len(lidar_data) - point_cloud_msg.data = buff.raw + elif ROS_VERSION == 2: + point_field_x_msg = PointField() + point_field_x_msg.name = "x" + point_field_x_msg.offset = 0 + point_field_x_msg.datatype = PointField.FLOAT32 + point_field_x_msg.count = 1 + + point_field_y_msg = PointField() + point_field_y_msg.name = "y" + point_field_y_msg.offset = 4 + point_field_y_msg.datatype = PointField.FLOAT32 + point_field_y_msg.count = 1 + + point_field_z_msg = PointField() + point_field_z_msg.name = "z" + point_field_z_msg.offset = 8 + point_field_z_msg.datatype = PointField.FLOAT32 + point_field_z_msg.count = 1 + + fields = [point_field_x_msg, point_field_y_msg, point_field_z_msg] + + cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) + buff = ctypes.create_string_buffer( + cloud_struct.size * len(lidar_data)) + + point_step, pack_into = cloud_struct.size, cloud_struct.pack_into + + offset = 0 + for pt in lidar_data: + pack_into(buff, offset, *pt) + offset += point_step + + point_cloud_msg = PointCloud2() + point_cloud_msg.header = header + point_cloud_msg.height = 1 + point_cloud_msg.width = len(lidar_data) + point_cloud_msg.is_dense = False + point_cloud_msg.is_bigendian = False + point_cloud_msg.fields = fields + point_cloud_msg.point_step = cloud_struct.size + point_cloud_msg.row_step = cloud_struct.size * len(lidar_data) + point_cloud_msg.data = buff.raw # -- - self.publish_message(self.get_topic_prefix() + "/point_cloud", point_cloud_msg) + self.publish_message(self.get_topic_prefix() + + "/point_cloud", point_cloud_msg) # http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html From 97e42a41463b8c8ae44b60cad0b2fc76bebf402b Mon Sep 17 00:00:00 2001 From: sergimoya Date: Thu, 18 Jun 2020 11:50:14 +0200 Subject: [PATCH 216/627] Fix camera topic name --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 3280a518..b9f8eb07 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -108,20 +108,20 @@ def sensor_data_updated(self, carla_image): (carla_image.width != self._camera_info.width)): self.logerr("Camera{} received image not matching configuration".format( self.get_prefix())) - image_data_array, encoding = self.get_carla_image_data_array(carla_image=carla_image) - img_msg = Camera.cv_bridge.cv2_to_imgmsg(image_data_array, encoding=encoding) + image_data_array, encoding = self.get_carla_image_data_array( + carla_image=carla_image) + img_msg = Camera.cv_bridge.cv2_to_imgmsg( + image_data_array, encoding=encoding) # the camera data is in respect to the camera's own frame img_msg.header = self.get_msg_header() cam_info = self._camera_info cam_info.header = img_msg.header - if ROS_VERSION == 1: - self.publish_message(self.get_topic_prefix() + '/camera_info', cam_info) - elif ROS_VERSION == 2: - self.publish_message(self.get_topic_prefix() + '/' + - self.get_image_topic_name() + '/camera_info', cam_info) - self.publish_message(self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) + self.publish_message(self.get_topic_prefix() + + '/camera_info', cam_info) + self.publish_message(self.get_topic_prefix() + + '/' + self.get_image_topic_name(), img_msg) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ From ea1629a7d5f41a8d37596e2ee2d1d0a32b9b9db2 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 18 Jun 2020 16:34:17 +0200 Subject: [PATCH 217/627] Remove ainstein radar msgs cause they are now integrate into carla_msgs --- ainstein_radar/.gitignore | 1 - ainstein_radar/LICENSE | 29 ----- ainstein_radar/README.md | 5 - .../ainstein_radar_msgs/CHANGELOG.rst | 64 ----------- .../ainstein_radar_msgs/CMakeLists.txt | 86 -------------- .../ainstein_radar_msgs/msg/RadarAlarm.msg | 5 - .../msg/RadarAlarmArray.msg | 5 - .../msg/RadarAlarmStamped.msg | 7 -- .../ainstein_radar_msgs/msg/RadarInfo.msg | 106 ------------------ .../ainstein_radar_msgs/msg/RadarInfo2.msg | 106 ------------------ .../ainstein_radar_msgs/msg/RadarTarget.msg | 8 -- .../msg/RadarTargetArray.msg | 5 - .../msg/RadarTargetStamped.msg | 5 - .../ainstein_radar_msgs/package.xml | 39 ------- 14 files changed, 471 deletions(-) delete mode 100644 ainstein_radar/.gitignore delete mode 100644 ainstein_radar/LICENSE delete mode 100644 ainstein_radar/README.md delete mode 100644 ainstein_radar/ainstein_radar_msgs/CHANGELOG.rst delete mode 100644 ainstein_radar/ainstein_radar_msgs/CMakeLists.txt delete mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarAlarm.msg delete mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmArray.msg delete mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmStamped.msg delete mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarInfo.msg delete mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarInfo2.msg delete mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarTarget.msg delete mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarTargetArray.msg delete mode 100644 ainstein_radar/ainstein_radar_msgs/msg/RadarTargetStamped.msg delete mode 100644 ainstein_radar/ainstein_radar_msgs/package.xml diff --git a/ainstein_radar/.gitignore b/ainstein_radar/.gitignore deleted file mode 100644 index 4c4c99ba..00000000 --- a/ainstein_radar/.gitignore +++ /dev/null @@ -1 +0,0 @@ -bagfiles/ \ No newline at end of file diff --git a/ainstein_radar/LICENSE b/ainstein_radar/LICENSE deleted file mode 100644 index 51036f7b..00000000 --- a/ainstein_radar/LICENSE +++ /dev/null @@ -1,29 +0,0 @@ -BSD 3-Clause License - -Copyright (c) 2018-2019, Ainstein AI, Inc. -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -* Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -* Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -* Neither the name of the copyright holder nor the names of its - contributors may be used to endorse or promote products derived from - this software without specific prior written permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/ainstein_radar/README.md b/ainstein_radar/README.md deleted file mode 100644 index beaef139..00000000 --- a/ainstein_radar/README.md +++ /dev/null @@ -1,5 +0,0 @@ -# Overview - -ainstein_radar is a collection of ROS packages containing functionality for interfacing with, filtering, displaying and using data from Ainstein radars for robotics applications. - -For more details on usage, see the corresponding [ROS Wiki Pages](http://wiki.ros.org/ainstein_radar). \ No newline at end of file diff --git a/ainstein_radar/ainstein_radar_msgs/CHANGELOG.rst b/ainstein_radar/ainstein_radar_msgs/CHANGELOG.rst deleted file mode 100644 index 33bf8202..00000000 --- a/ainstein_radar/ainstein_radar_msgs/CHANGELOG.rst +++ /dev/null @@ -1,64 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package ainstein_radar_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -3.0.1 (2020-02-11) ------------------- - -3.0.0 (2020-02-06) ------------------- - -2.0.2 (2019-11-19) ------------------- - -2.0.1 (2019-11-12) ------------------- - -2.0.0 (2019-11-12) ------------------- -* Update RadarInfo msg, refactor for K79 and add T79 - Updated the RadarInfo message slightly. Also refactored the K79 - interface class to publish the RadarInfo message. - Added publishing the RadarInfo message for T79 as well, needs testing. -* Update RadarInfo message and fix dependencies - Updated the RadarInfo message with new fields fully describing the data - and added comments to explain them. - Also fixed a small dependency in the RViz plugins package for display - of the RadarInfo messages, however this plugin is not complete anyway. -* Contributors: Nick Rotella - -1.1.0 (2019-10-29) ------------------- -* Minor fixes to package XML formatting - Fixed the package XML file formatting and added missing content to - conform to the suggested style guidelines. -* Contributors: Nick Rotella - -1.0.3 (2019-10-03) ------------------- - -1.0.2 (2019-09-25) ------------------- - -1.0.1 (2019-09-24) ------------------- -* Minor, remove unnecessary install target for radar_msgs -* Merge branch 'master' of https://github.com/AinsteinAI/ainstein_radar -* Add ainstein_radar_msgs/RadarInfo msg definition - Added a new message type to ainstein_radar_msgs to store information - about a radar sensor's properties, configuration, etc. Currently - contains physical limits for range, speed and angles. -* Fix radar stamped msg, add nearest target filter - Fixed the RadarTargetStamped message to use the unstamped RadarTarget - message rather than duplicating fields. - Added a nearest target filter which extracts the nearest target (by - range) within set min/max range bounds and optionally low-pass filters - it before publishing as both a RadarTargetStamped and as an array with - one message (called "tracked"). Will remove the array published after - implementing a proper tracked target filter. -* Refactor radar message types, other ainstein_radar subpkgs WILL NOT BUILD - Refactored the message types defined for radars, breaking all other subpkgs - in the ainstein_radar metapkg. Now refactoring all other pkgs to use the - new message definitions. -* Migrate old radar_sensor_msgs pkg to new ainstein_radar_msgs subpkg -* Contributors: Nick Rotella diff --git a/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt b/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt deleted file mode 100644 index b6678453..00000000 --- a/ainstein_radar/ainstein_radar_msgs/CMakeLists.txt +++ /dev/null @@ -1,86 +0,0 @@ -project(ainstein_radar_msgs) - -find_package(ros_environment REQUIRED) -set(ROS_VERSION $ENV{ROS_VERSION}) - -set(CMAKE_CXX_STANDARD 11) - -set(MSG_FILES - # RadarInfo.msg - RadarAlarm.msg - RadarAlarmArray.msg - RadarAlarmStamped.msg - RadarTarget.msg - RadarTargetArray.msg - RadarTargetStamped.msg - ) - -if (${ROS_VERSION} EQUAL 1) - cmake_minimum_required(VERSION 3.0.0) - - find_package(catkin REQUIRED COMPONENTS - std_msgs - message_generation - ) - - add_message_files( - DIRECTORY msg - FILES - ${MSG_FILES} - RadarInfo.msg - ) - - generate_messages( - DEPENDENCIES - std_msgs - ) - - catkin_package( - CATKIN_DEPENDS message_runtime - ) - - include_directories( - ${catkin_INCLUDE_DIRS} - ) - - install(TARGETS - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} - ) - -elseif (${ROS_VERSION} EQUAL 2) - cmake_minimum_required(VERSION 3.5) - - if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) - endif() - - find_package(ament_cmake REQUIRED) - find_package(builtin_interfaces REQUIRED) - find_package(std_msgs REQUIRED) - find_package(rosidl_default_generators REQUIRED) - - # Apend "msg/" to each file name - set(TEMP_LIST "") - foreach(MSG_FILE ${MSG_FILES}) - list(APPEND TEMP_LIST "msg/${MSG_FILE}") - endforeach() - set(MSG_FILES ${TEMP_LIST}) - - rosidl_generate_interfaces(${PROJECT_NAME} - ${MSG_FILES} - "msg/RadarInfo2.msg" - DEPENDENCIES builtin_interfaces std_msgs - ADD_LINTER_TESTS - ) - - if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() - endif() - - ament_export_dependencies(rosidl_default_runtime) - - ament_package() -endif() \ No newline at end of file diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarm.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarm.msg deleted file mode 100644 index 7de37504..00000000 --- a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarm.msg +++ /dev/null @@ -1,5 +0,0 @@ -# This message describes alarms (eg BSD) from a RADAR sensor. - -bool lca_alarm # Lane Change Assist alarm -bool cvw_alarm # Collision (Vehicle?) Warning alarm -bool bsd_alarm # Blind Spot Detection alarm diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmArray.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmArray.msg deleted file mode 100644 index 0186fc1a..00000000 --- a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmArray.msg +++ /dev/null @@ -1,5 +0,0 @@ -# This message describes an array of alarms with a timestamp. - -std_msgs/Header header - -RadarAlarm[] alarms diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmStamped.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmStamped.msg deleted file mode 100644 index 8782cc67..00000000 --- a/ainstein_radar/ainstein_radar_msgs/msg/RadarAlarmStamped.msg +++ /dev/null @@ -1,7 +0,0 @@ -# This message describes alarms (eg BSD) from a RADAR sensor. - -std_msgs/Header header - -bool lca_alarm # Lane Change Assist alarm -bool cvw_alarm # Collision (Vehicle?) Warning alarm -bool bsd_alarm # Blind Spot Detection alarm diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo.msg deleted file mode 100644 index 4dfaa443..00000000 --- a/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo.msg +++ /dev/null @@ -1,106 +0,0 @@ -# This message defines meta information for a radar sensor. It should -# be in a radar namespace on topic "radar_info" and accompanied by up -# to three radar topics named: -# -# targets/raw - raw (untracked) radar detections -# targets/tracked - tracked radar detections -# alarms - alarms based on detections, eg BSD -# -# In general, all Ainstein radars output raw detections and may also -# output tracked detections if trackign algorithms are implemented in -# firmware. Tracking from raw data is also available in ROS; see the -# ainstein_radar_filters package for more information. Most radars do -# not output alarms as this is specific to the automotive use case, -# however this message type is retained for the time being for backward -# compatibility. - -####################################################################### -# Data acquisition info # -####################################################################### - -# Time of data acquisition, radar coordinate frame ID -Header header # Header timestamp should be acquisition time of data - # Header frame_id should be radar sensing frame - # origin of frame should be center of sensor - # +x should point radially outwards from the radar - # +y should point to complete a right-handed frame - # +z should point upwards - -####################################################################### -# General sensor properties # -####################################################################### - -# The nominal update rate of the sensor reported in Hz. -float64 update_rate - -# The maximum number of detections (targets) the sensors can report. -uint16 max_num_targets - -####################################################################### -# Physical sensing limits # -####################################################################### -# These are limits imposed by the antenna hardware and/or cutoffs set # -# in the detection processing firmware. They come from sensor data # -# sheets and must be updated with each hardware revision as necessary.# -####################################################################### - -# The minimum and maximum range, in meters, of detections (targets) -# reported by the sensor. -float64 range_min -float64 range_max - -# The minimum and maximum speed, in meters per second, of detections -# (targets) reported by the sensor. -float64 speed_min -float64 speed_max - -# The minimum and maximum azimuth angle, in degrees. -float64 azimuth_min -float64 azimuth_max - -# The minimum and maximum azimuth angle, in degrees. -float64 elevation_min -float64 elevation_max - -####################################################################### -# Physical sensing precision # -####################################################################### -# These are also imposed by the antenna hardware and/or set in the # -# detection processing firmware. They also come from sensor data # -# sheets and must be updated with each hardware revision as necessary.# -####################################################################### - -# Range resolution, in meters. The resolution is defined as the minimum -# distance between two objects which results in distinct detections. -float64 range_resolution - -# Range accuracy, in meters. The accuracy is defined as the precision -# with which range of a detection is reported. -float64 range_accuracy - -# Speed resolution, in meters per second. The resolution is defined as -# the minimum speed difference between two objects which results in -# distinct detections. -float64 speed_resolution - -# Speed accuracy, in meters per second. The accuracy is defined as the -# precision with which speed of a detection is reported. -float64 speed_accuracy - -# Azimuth angle resolution, in degrees. The resolution is defined as -# the minimum azimuth angle between two objects which results in -# distinct detections. -float64 azimuth_resolution - -# Azimuth angle accuracy, in degrees. The accuracy is defined as the -# precision with which the azimuth angle of a detection is reported. -float64 azimuth_accuracy - -# Elevation angle resolution, in degrees. The resolution is defined as -# the minimum elevation angle between two objects which results in -# distinct detections. -float64 elevation_resolution - -# Elevation angle accuracy, in degrees. The accuracy is defined as the -# precision with which the elevation angle of a detection is reported. -float64 elevation_accuracy diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo2.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo2.msg deleted file mode 100644 index eadccbb2..00000000 --- a/ainstein_radar/ainstein_radar_msgs/msg/RadarInfo2.msg +++ /dev/null @@ -1,106 +0,0 @@ -# This message defines meta information for a radar sensor. It should -# be in a radar namespace on topic "radar_info" and accompanied by up -# to three radar topics named: -# -# targets/raw - raw (untracked) radar detections -# targets/tracked - tracked radar detections -# alarms - alarms based on detections, eg BSD -# -# In general, all Ainstein radars output raw detections and may also -# output tracked detections if trackign algorithms are implemented in -# firmware. Tracking from raw data is also available in ROS; see the -# ainstein_radar_filters package for more information. Most radars do -# not output alarms as this is specific to the automotive use case, -# however this message type is retained for the time being for backward -# compatibility. - -####################################################################### -# Data acquisition info # -####################################################################### - -# Time of data acquisition, radar coordinate frame ID -std_msgs/Header header # Header timestamp should be acquisition time of data - # Header frame_id should be radar sensing frame - # origin of frame should be center of sensor - # +x should point radially outwards from the radar - # +y should point to complete a right-handed frame - # +z should point upwards - -####################################################################### -# General sensor properties # -####################################################################### - -# The nominal update rate of the sensor reported in Hz. -float64 update_rate - -# The maximum number of detections (targets) the sensors can report. -uint16 max_num_targets - -####################################################################### -# Physical sensing limits # -####################################################################### -# These are limits imposed by the antenna hardware and/or cutoffs set # -# in the detection processing firmware. They come from sensor data # -# sheets and must be updated with each hardware revision as necessary.# -####################################################################### - -# The minimum and maximum range, in meters, of detections (targets) -# reported by the sensor. -float64 range_min -float64 range_max - -# The minimum and maximum speed, in meters per second, of detections -# (targets) reported by the sensor. -float64 speed_min -float64 speed_max - -# The minimum and maximum azimuth angle, in degrees. -float64 azimuth_min -float64 azimuth_max - -# The minimum and maximum azimuth angle, in degrees. -float64 elevation_min -float64 elevation_max - -####################################################################### -# Physical sensing precision # -####################################################################### -# These are also imposed by the antenna hardware and/or set in the # -# detection processing firmware. They also come from sensor data # -# sheets and must be updated with each hardware revision as necessary.# -####################################################################### - -# Range resolution, in meters. The resolution is defined as the minimum -# distance between two objects which results in distinct detections. -float64 range_resolution - -# Range accuracy, in meters. The accuracy is defined as the precision -# with which range of a detection is reported. -float64 range_accuracy - -# Speed resolution, in meters per second. The resolution is defined as -# the minimum speed difference between two objects which results in -# distinct detections. -float64 speed_resolution - -# Speed accuracy, in meters per second. The accuracy is defined as the -# precision with which speed of a detection is reported. -float64 speed_accuracy - -# Azimuth angle resolution, in degrees. The resolution is defined as -# the minimum azimuth angle between two objects which results in -# distinct detections. -float64 azimuth_resolution - -# Azimuth angle accuracy, in degrees. The accuracy is defined as the -# precision with which the azimuth angle of a detection is reported. -float64 azimuth_accuracy - -# Elevation angle resolution, in degrees. The resolution is defined as -# the minimum elevation angle between two objects which results in -# distinct detections. -float64 elevation_resolution - -# Elevation angle accuracy, in degrees. The accuracy is defined as the -# precision with which the elevation angle of a detection is reported. -float64 elevation_accuracy diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarTarget.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarTarget.msg deleted file mode 100644 index 3bb5f280..00000000 --- a/ainstein_radar/ainstein_radar_msgs/msg/RadarTarget.msg +++ /dev/null @@ -1,8 +0,0 @@ -# This message describes a target (detection) from a RADAR sensor. - -uint16 target_id # ID of the target, as set by the sensor -float64 snr # Signal-to-noise ratio -float64 range # Distance from sensor to target along sensor x-axis -float64 speed # Speed (range rate of change) of target along sensor x-axis -float64 azimuth # Angle of target relative to sensor within x-y plane -float64 elevation # Angle of target relative to sensor within y-z plane diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetArray.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetArray.msg deleted file mode 100644 index 7bdc2295..00000000 --- a/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetArray.msg +++ /dev/null @@ -1,5 +0,0 @@ -# This message describes an array of targets with a timestamp. - -std_msgs/Header header - -RadarTarget[] targets diff --git a/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetStamped.msg b/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetStamped.msg deleted file mode 100644 index f955037f..00000000 --- a/ainstein_radar/ainstein_radar_msgs/msg/RadarTargetStamped.msg +++ /dev/null @@ -1,5 +0,0 @@ -# This message describes a target (detection) from a RADAR sensor with a timestamp. - -std_msgs/Header header - -RadarTarget target diff --git a/ainstein_radar/ainstein_radar_msgs/package.xml b/ainstein_radar/ainstein_radar_msgs/package.xml deleted file mode 100644 index fcc15d99..00000000 --- a/ainstein_radar/ainstein_radar_msgs/package.xml +++ /dev/null @@ -1,39 +0,0 @@ - - - - ainstein_radar_msgs - 3.0.1 - - ROS message definitions for Ainstein radars. - - Nick Rotella - Nick Rotella - BSD - https://wiki.ros.org/ainstein_radar_msgs - https://github.com/AinsteinAI/ainstein_radar - https://github.com/AinsteinAI/ainstein_radar/issues - - catkin - ament_cmake - - message_generation - rosidl_default_generators - ros_environment - - builtin_interfaces - std_msgs - - message_runtime - rosidl_default_runtime - - ament_lint_auto - ament_lint_common - - rosidl_interface_packages - - - catkin - ament_cmake - - - From aec298202e87b3396ac401f3401c5f469cfe8c76 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 18 Jun 2020 16:35:06 +0200 Subject: [PATCH 218/627] Port carla_common meta-files and use transforms3d library --- carla_common/CMakeLists.txt | 27 ++++++++++---- carla_common/package.xml | 11 ++++-- carla_common/resource/carla_common | 0 carla_common/setup.cfg | 4 +++ carla_common/setup.py | 40 +++++++++++++++++---- carla_common/src/carla_common/transforms.py | 3 +- 6 files changed, 67 insertions(+), 18 deletions(-) create mode 100644 carla_common/resource/carla_common create mode 100644 carla_common/setup.cfg diff --git a/carla_common/CMakeLists.txt b/carla_common/CMakeLists.txt index 75e71fe3..413647b2 100644 --- a/carla_common/CMakeLists.txt +++ b/carla_common/CMakeLists.txt @@ -1,13 +1,26 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_common) -find_package(catkin) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if (${ROS_VERSION} EQUAL 1) -catkin_package() + find_package(catkin) -catkin_install_python(PROGRAMS - src/carla_common/transforms.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) + catkin_python_setup() + + catkin_package() + + catkin_install_python(PROGRAMS + src/carla_common/transforms.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + ) + +elseif (${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + ament_package() + +endif() diff --git a/carla_common/package.xml b/carla_common/package.xml index aacd9c7c..ed331092 100644 --- a/carla_common/package.xml +++ b/carla_common/package.xml @@ -1,12 +1,17 @@ - + carla_common 0.0.1 The carla_common package CARLA Simulator Team MIT - catkin - rospy + + catkin + + ament_python + + catkin + ament_python diff --git a/carla_common/resource/carla_common b/carla_common/resource/carla_common new file mode 100644 index 00000000..e69de29b diff --git a/carla_common/setup.cfg b/carla_common/setup.cfg new file mode 100644 index 00000000..b59f6965 --- /dev/null +++ b/carla_common/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_common +[install] +install-scripts=$base/lib/carla_common diff --git a/carla_common/setup.py b/carla_common/setup.py index 5d53510d..7ddf8860 100644 --- a/carla_common/setup.py +++ b/carla_common/setup.py @@ -2,12 +2,38 @@ Setup for carla_common """ -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) -d = generate_distutils_setup( - packages=['carla_common'], - package_dir={'': 'src'} -) +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -setup(**d) + d = generate_distutils_setup( + packages=['carla_common'], + package_dir={'': 'src'} + ) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_common' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA common providing transforms for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + package_dir={'': 'src'}, + ) diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index 2048c5ef..efd4739a 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -21,7 +21,8 @@ if ROS_VERSION == 1: from tf.transformations import euler_matrix, quaternion_from_euler elif ROS_VERSION == 2: - from transformations.transformations import euler_matrix, quaternion_from_euler + from transforms3d.euler import euler2mat as euler_matrix + from transforms3d.euler import euler2quat as quaternion_from_euler else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") From fbb3ae04758d3ed6ef0f246c2a1411d9c1aaa920 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 18 Jun 2020 16:36:10 +0200 Subject: [PATCH 219/627] Explicitly call super class to fix 90-degree point cloud rotation in ros 2 --- carla_ros_bridge/src/carla_ros_bridge/sensor.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 089db9b3..3baa1977 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -183,4 +183,4 @@ def update(self, frame, timestamp): else: self._update_synchronous_sensor(frame, timestamp) - super(Sensor, self).update(frame, timestamp) + Actor.update(self, frame, timestamp) From 8cde10a239b4fdf32bbee21eb65f6d72a379d4a5 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 18 Jun 2020 16:42:05 +0200 Subject: [PATCH 220/627] Remove astuff sensor msgs --- astuff_sensor_msgs/.gitignore | 10 -- astuff_sensor_msgs/LICENSE | 19 ---- astuff_sensor_msgs/README.md | 19 ---- .../derived_object_msgs/CHANGELOG.rst | 30 ------ .../derived_object_msgs/CMakeLists.txt | 101 ------------------ .../derived_object_msgs/msg/CipvTrack.msg | 6 -- .../derived_object_msgs/msg/Lane.msg | 47 -------- .../derived_object_msgs/msg/LaneModels.msg | 9 -- .../derived_object_msgs/msg/Object.msg | 56 ---------- .../derived_object_msgs/msg/ObjectArray.msg | 3 - .../msg/ObjectWithCovariance.msg | 56 ---------- .../msg/ObjectWithCovarianceArray.msg | 3 - .../msg/SolidPrimitiveWithCovariance.msg | 43 -------- .../derived_object_msgs/package.xml | 40 ------- astuff_sensor_msgs/radar_msgs/CHANGELOG.rst | 29 ----- astuff_sensor_msgs/radar_msgs/CMakeLists.txt | 86 --------------- .../radar_msgs/msg/RadarDetection.msg | 10 -- .../radar_msgs/msg/RadarDetectionArray.msg | 3 - .../radar_msgs/msg/RadarDetectionStamped.msg | 3 - .../radar_msgs/msg/RadarErrorStatus.msg | 9 -- .../radar_msgs/msg/RadarStatus.msg | 12 --- .../radar_msgs/msg/RadarTrack.msg | 16 --- .../radar_msgs/msg/RadarTrackArray.msg | 3 - .../radar_msgs/msg/RadarTrackStamped.msg | 3 - astuff_sensor_msgs/radar_msgs/package.xml | 38 ------- 25 files changed, 654 deletions(-) delete mode 100644 astuff_sensor_msgs/.gitignore delete mode 100644 astuff_sensor_msgs/LICENSE delete mode 100644 astuff_sensor_msgs/README.md delete mode 100644 astuff_sensor_msgs/derived_object_msgs/CHANGELOG.rst delete mode 100644 astuff_sensor_msgs/derived_object_msgs/CMakeLists.txt delete mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/CipvTrack.msg delete mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/Lane.msg delete mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/LaneModels.msg delete mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/Object.msg delete mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/ObjectArray.msg delete mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovariance.msg delete mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovarianceArray.msg delete mode 100644 astuff_sensor_msgs/derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg delete mode 100644 astuff_sensor_msgs/derived_object_msgs/package.xml delete mode 100644 astuff_sensor_msgs/radar_msgs/CHANGELOG.rst delete mode 100644 astuff_sensor_msgs/radar_msgs/CMakeLists.txt delete mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarDetection.msg delete mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarDetectionArray.msg delete mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarDetectionStamped.msg delete mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarErrorStatus.msg delete mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarStatus.msg delete mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarTrack.msg delete mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarTrackArray.msg delete mode 100644 astuff_sensor_msgs/radar_msgs/msg/RadarTrackStamped.msg delete mode 100644 astuff_sensor_msgs/radar_msgs/package.xml diff --git a/astuff_sensor_msgs/.gitignore b/astuff_sensor_msgs/.gitignore deleted file mode 100644 index 86ca0249..00000000 --- a/astuff_sensor_msgs/.gitignore +++ /dev/null @@ -1,10 +0,0 @@ -build/ -bin/ -lib/ -lib_include/ -*.log -*.swp -*.user -*~ -.idea/ -.vscode diff --git a/astuff_sensor_msgs/LICENSE b/astuff_sensor_msgs/LICENSE deleted file mode 100644 index 964fe6b9..00000000 --- a/astuff_sensor_msgs/LICENSE +++ /dev/null @@ -1,19 +0,0 @@ -Copyright (c) 2017 AutonomouStuff, LLC - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. diff --git a/astuff_sensor_msgs/README.md b/astuff_sensor_msgs/README.md deleted file mode 100644 index cef4b5d2..00000000 --- a/astuff_sensor_msgs/README.md +++ /dev/null @@ -1,19 +0,0 @@ -# ROS Messages for AutonomouStuff-provided Drivers # - -[![CircleCI](https://circleci.com/gh/astuff/astuff_sensor_msgs/tree/master.svg?style=svg)](https://circleci.com/gh/astuff/astuff_sensor_msgs/tree/master) - -A set of messages for each AutonomouStuff-provided driver. `astuff_sensor_msgs` contains: - -- `delphi_esr_msgs` -- `delphi_mrr_msgs` -- `delphi_srr_msgs` -- `ibeo_lux_msgs` -- `ibeo_msgs` (Messages for all Ibeo sensors) -- `kartech_linear_actuator_msgs` -- `mobileye_560_660_msgs` -- `neobotix_usboard_msgs` -- `pacmod_msgs` -- `radar_msgs` (generic radar output messages not currently available in `sensor_msgs`) -- `derived_object_msgs` (abstracted sensor messages for like Objects and Closest In-Path Vehicles) - -For more information on the individual drivers, see the [AutonomouStuff Wiki](https://autonomoustuff.atlassian.net/wiki/spaces/RW/pages/17478581/Supported+Devices). diff --git a/astuff_sensor_msgs/derived_object_msgs/CHANGELOG.rst b/astuff_sensor_msgs/derived_object_msgs/CHANGELOG.rst deleted file mode 100644 index 70e6bc77..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/CHANGELOG.rst +++ /dev/null @@ -1,30 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package derived_object_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -3.0.1 (2020-01-23) ------------------- -* Adding ros_environment as required package to all packages. -* Hybridize derived_object_msgs. (`#44 `_) -* Adding hybrid CI. -* Updating package.xml files for ROS2 rosdep. -* Adding message migration rules. -* Contributors: Joshua Whitley - -2.3.1 (2018-12-07) ------------------- -* Merge pull request `#31 `_ from astuff/maint/add_urls -* Adding URLs to package.xml files. -* Contributors: Daniel-Stanek, Joshua Whitley - -2.3.0 (2018-10-04) ------------------- - -2.2.2 (2018-08-30) ------------------- - -2.2.1 (2018-08-08) ------------------- -* Renamed perception_msgs to derived_object_msgs for clarification. -* Moving perception_msgs from platform_automation_msgs. -* Contributors: Joe Buckner, Joshua Whitley diff --git a/astuff_sensor_msgs/derived_object_msgs/CMakeLists.txt b/astuff_sensor_msgs/derived_object_msgs/CMakeLists.txt deleted file mode 100644 index d1660a52..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/CMakeLists.txt +++ /dev/null @@ -1,101 +0,0 @@ -project(derived_object_msgs) - -find_package(ros_environment REQUIRED) - -set(ROS_VERSION $ENV{ROS_VERSION}) - -set(MSG_FILES - "CipvTrack.msg" - "Lane.msg" - "LaneModels.msg" - "Object.msg" - "ObjectArray.msg" - "ObjectWithCovariance.msg" - "ObjectWithCovarianceArray.msg" - "SolidPrimitiveWithCovariance.msg" -) - -if(${ROS_VERSION} EQUAL 1) - - cmake_minimum_required(VERSION 2.8.3) - - # Default to C++11 - if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 11) - endif() - - find_package(catkin REQUIRED - COMPONENTS - geometry_msgs - message_generation - radar_msgs - shape_msgs - std_msgs - ) - - add_message_files(FILES - ${MSG_FILES} - DIRECTORY msg - ) - - generate_messages( - DEPENDENCIES - geometry_msgs - radar_msgs - shape_msgs - std_msgs - ) - - catkin_package( - CATKIN_DEPENDS message_runtime - ) - -elseif(${ROS_VERSION} EQUAL 2) - - cmake_minimum_required(VERSION 3.5) - - if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD_REQUIRED ON) - set(CMAKE_CXX_STANDARD 14) - endif() - - if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) - endif() - - find_package(ament_cmake REQUIRED) - find_package(builtin_interfaces REQUIRED) - find_package(geometry_msgs REQUIRED) - find_package(radar_msgs REQUIRED) - find_package(rosidl_default_generators REQUIRED) - find_package(shape_msgs REQUIRED) - find_package(std_msgs REQUIRED) - - # Apend "msg/" to each file name - set(TEMP_LIST "") - foreach(MSG_FILE ${MSG_FILES}) - list(APPEND TEMP_LIST "msg/${MSG_FILE}") - endforeach() - set(MSG_FILES ${TEMP_LIST}) - - rosidl_generate_interfaces(${PROJECT_NAME} - ${MSG_FILES} - DEPENDENCIES - builtin_interfaces - geometry_msgs - shape_msgs - std_msgs - radar_msgs - ADD_LINTER_TESTS - ) - - ament_export_dependencies(rosidl_default_runtime) - - if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() - endif() - - ament_package() - -endif() diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/CipvTrack.msg b/astuff_sensor_msgs/derived_object_msgs/msg/CipvTrack.msg deleted file mode 100644 index f329e309..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/msg/CipvTrack.msg +++ /dev/null @@ -1,6 +0,0 @@ -# Closest In-Path Vehicle Radar Track - -std_msgs/Header header - -bool is_valid # Whether or not the track is a valid CIPV -radar_msgs/RadarTrack track # The CIPV track diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/Lane.msg b/astuff_sensor_msgs/derived_object_msgs/msg/Lane.msg deleted file mode 100644 index d931b632..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/msg/Lane.msg +++ /dev/null @@ -1,47 +0,0 @@ -# Lane Definition Message -# Contains information on a single lane marker - -uint8 quality # Visual quality of lane marker -uint8 LANE_QUALITY_INVALID = 0 -uint8 LANE_QUALITY_UNKNOWN = 1 -uint8 LANE_QUALITY_NOT_AVAILABLE = 2 -uint8 LANE_QUALITY_0 = 3 -uint8 LANE_QUALITY_1 = 4 -uint8 LANE_QUALITY_2 = 5 -uint8 LANE_QUALITY_3 = 6 -uint8 LANE_QUALITY_4 = 7 -uint8 LANE_QUALITY_5 = 8 -uint8 LANE_QUALITY_6 = 9 -uint8 LANE_QUALITY_7 = 10 -uint8 LANE_QUALITY_8 = 11 -uint8 LANE_QUALITY_9 = 12 -uint8 LANE_QUALITY_KIND_COUNT = 13 - -uint8 marker_kind # Solid, dashed, ... -uint8 LANE_MARKER_INVALID = 0 -uint8 LANE_MARKER_UNKNOWN = 1 -uint8 LANE_MARKER_NOT_AVAILABLE = 2 -uint8 LANE_MARKER_NONE = 3 -uint8 LANE_MARKER_SOLID = 4 -uint8 LANE_MARKER_DASHED = 5 -uint8 LANE_MARKER_VIRTUAL = 6 -uint8 LANE_MARKER_DOTS = 7 -uint8 LANE_MARKER_ROAD_EDGE = 8 -uint8 LANE_MARKER_DOUBLE_LINE = 9 -uint8 LANE_MARKER_KIND_COUNT = 10 - -uint8 curve_model_kind # Order of equation -uint8 LANE_CURVE_MODEL_INVALID = 0 -uint8 LANE_CURVE_MODEL_UNKNOWN = 1 -uint8 LANE_CURVE_MODEL_NOT_AVAILABLE = 2 -uint8 LANE_CURVE_MODEL_LINEAR = 3 -uint8 LANE_CURVE_MODEL_PARABOLIC = 4 -uint8 LANE_CURVE_MODEL_3D = 5 -uint8 LANE_CURVE_MODEL_KIND_COUNT = 6 - -float64 marker_offset # Lateral distance from sensor to marker (m) -float64 heading_angle # Angle of marker relative to sensor (rad) -float64 curvature # Curvature of the lane marker at the camera (1/m) -float64 curvature_derivative # Amount curvature changes as you move away from the camera (1/m^2) -float64 marker_width # Width of the painted marker (not distance between lane markers) (m) -float64 view_range # Physical view range of the lane mark (m) diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/LaneModels.msg b/astuff_sensor_msgs/derived_object_msgs/msg/LaneModels.msg deleted file mode 100644 index 9be89705..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/msg/LaneModels.msg +++ /dev/null @@ -1,9 +0,0 @@ -# Lane Models Message -# Contains multiple lanes detected by the sensor - -std_msgs/Header header - -derived_object_msgs/Lane left_lane -derived_object_msgs/Lane right_lane - -derived_object_msgs/Lane[] additional_lanes diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/Object.msg b/astuff_sensor_msgs/derived_object_msgs/msg/Object.msg deleted file mode 100644 index 27cc705c..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/msg/Object.msg +++ /dev/null @@ -1,56 +0,0 @@ -# This represents a detected or tracked object with reference coordinate frame and timestamp. - -std_msgs/Header header - -# The id of the object (presumably from the detecting sensor). -uint32 id - -# A Detected object is one which has been seen in at least one scan/frame of a sensor. -# A Tracked object is one which has been correlated over multiple scans/frames of a sensor. -# An object which is detected can only be assumed to have valid pose and shape properties. -# An object which is tracked should also be assumed to have valid twist and accel properties. -uint8 detection_level -uint8 OBJECT_DETECTED=0 -uint8 OBJECT_TRACKED=1 - -# A Classified object is one which has been identified as a certain object type. -# Classified objects should have valid classification, classification_certainty, and classification_age properties. -bool object_classified - -# The detected position and orientation of the object. -geometry_msgs/Pose pose - -# The detected linear and angular velocities of the object. -geometry_msgs/Twist twist - -# The detected linear and angular accelerations of the object. -geometry_msgs/Accel accel - -# (OPTIONAL) The polygon defining the detection points at the outer edges of the object. -geometry_msgs/Polygon polygon - -# A shape conforming to the outer bounding edges of the object. -shape_msgs/SolidPrimitive shape - -# The type of classification given to this object. -uint8 classification -uint8 CLASSIFICATION_UNKNOWN=0 -uint8 CLASSIFICATION_UNKNOWN_SMALL=1 -uint8 CLASSIFICATION_UNKNOWN_MEDIUM=2 -uint8 CLASSIFICATION_UNKNOWN_BIG=3 -uint8 CLASSIFICATION_PEDESTRIAN=4 -uint8 CLASSIFICATION_BIKE=5 -uint8 CLASSIFICATION_CAR=6 -uint8 CLASSIFICATION_TRUCK=7 -uint8 CLASSIFICATION_MOTORCYCLE=8 -uint8 CLASSIFICATION_OTHER_VEHICLE=9 -uint8 CLASSIFICATION_BARRIER=10 -uint8 CLASSIFICATION_SIGN=11 - -# The certainty of the classification from the originating sensor. -# Higher value indicates greater certainty (MAX=255). -# It is recommended that a native sensor value be scaled to 0-255 for interoperability. -uint8 classification_certainty - -# The number of scans/frames from the sensor that this object has been classified as the current classification. -uint32 classification_age diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectArray.msg b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectArray.msg deleted file mode 100644 index b6b3606f..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectArray.msg +++ /dev/null @@ -1,3 +0,0 @@ -std_msgs/Header header - -derived_object_msgs/Object[] objects diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovariance.msg b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovariance.msg deleted file mode 100644 index 3c95024f..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovariance.msg +++ /dev/null @@ -1,56 +0,0 @@ -# This represents an estimated object with reference coordinate frame and timestamp. -std_msgs/Header header - -# The id of the object (presumably from the detecting sensor). -uint32 id - -# A Detected object is one which has been seen in at least one scan/frame of a sensor. -# A Tracked object is one which has been correlated over multiple scans/frames of a sensor. -# An object which is detected can only be assumed to have valid pose and shape properties. -# An object which is tracked should also be assumed to have valid twist and accel properties. -# The validity of the individual components of each object property are defined by the property's covariance matrix. -uint8 detection_level -uint8 OBJECT_DETECTED=0 -uint8 OBJECT_TRACKED=1 - -# A Classified object is one which has been identified as a certain object type. -# Classified objects should have valid classification, classification_certainty, and classification_age properties. -bool object_classified - -# The detected position and orientation of the object. -geometry_msgs/PoseWithCovariance pose - -# The detected linear and angular velocities of the object. -geometry_msgs/TwistWithCovariance twist - -# The detected linear and angular accelerations of the object. -geometry_msgs/AccelWithCovariance accel - -# (OPTIONAL) The polygon defining the detection points at the outer edges of the object. -geometry_msgs/Polygon polygon - -# A shape conforming to the outer bounding edges of the object. -derived_object_msgs/SolidPrimitiveWithCovariance shape - -# The type of classification given to this object. -uint8 classification -uint8 CLASSIFICATION_UNKNOWN=0 -uint8 CLASSIFICATION_UNKNOWN_SMALL=1 -uint8 CLASSIFICATION_UNKNOWN_MEDIUM=2 -uint8 CLASSIFICATION_UNKNOWN_BIG=3 -uint8 CLASSIFICATION_PEDESTRIAN=4 -uint8 CLASSIFICATION_BIKE=5 -uint8 CLASSIFICATION_CAR=6 -uint8 CLASSIFICATION_TRUCK=7 -uint8 CLASSIFICATION_MOTORCYCLE=8 -uint8 CLASSIFICATION_OTHER_VEHICLE=9 -uint8 CLASSIFICATION_BARRIER=10 -uint8 CLASSIFICATION_SIGN=11 - -# The certainty of the classification from the originating sensor. -# Higher value indicates greater certainty (MAX=255). -# It is recommended that a native sensor value be scaled to 0-255 for interoperability. -uint8 classification_certainty - -# The number of scans/frames from the sensor that this object has been classified as the current classification. -uint32 classification_age diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovarianceArray.msg b/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovarianceArray.msg deleted file mode 100644 index fdcd9488..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/msg/ObjectWithCovarianceArray.msg +++ /dev/null @@ -1,3 +0,0 @@ -std_msgs/Header header - -derived_object_msgs/ObjectWithCovariance[] objects diff --git a/astuff_sensor_msgs/derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg b/astuff_sensor_msgs/derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg deleted file mode 100644 index ffed1312..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/msg/SolidPrimitiveWithCovariance.msg +++ /dev/null @@ -1,43 +0,0 @@ -# Define box, sphere, cylinder, cone -# All shapes are defined to have their bounding boxes centered around 0,0,0. -# This message based on shape_msgs/SolidPrimitive - -# The type of the shape -uint8 type -uint8 BOX=1 -uint8 SPHERE=2 -uint8 CYLINDER=3 -uint8 CONE=4 - -# The dimensions of the shape -float64[] dimensions - -# The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array -# For the BOX type, the X, Y, and Z dimensions are the length of the corresponding -# sides of the box. -uint8 BOX_X=0 -uint8 BOX_Y=1 -uint8 BOX_Z=2 - -# For the SPHERE type, only one component is used, and it gives the radius of -# the sphere. -uint8 SPHERE_RADIUS=0 - -# For the CYLINDER and CONE types, the center line is oriented along -# the Z axis. Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component -# of dimensions gives the height of the cylinder (cone). The -# CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the -# radius of the base of the cylinder (cone). Cone and cylinder -# primitives are defined to be circular. The tip of the cone is -# pointing up, along +Z axis. -uint8 CYLINDER_HEIGHT=0 -uint8 CYLINDER_RADIUS=1 - -uint8 CONE_HEIGHT=0 -uint8 CONE_RADIUS=1 - -# Row-major representation of the covariance matrix associated with the shape. -# For the BOX type, this should be a 3x3 matrix defining the uncertainty of the X, Y, and Z measurements. -# For the SPHERE type, this should contain only one value for the radius. -# For the CYLINDER and CONE types, this will be a 2x2 matrix defining the uncertainty of the HEIGHT and RADIUS measurements. -float64[] covariance diff --git a/astuff_sensor_msgs/derived_object_msgs/package.xml b/astuff_sensor_msgs/derived_object_msgs/package.xml deleted file mode 100644 index 69ee5dca..00000000 --- a/astuff_sensor_msgs/derived_object_msgs/package.xml +++ /dev/null @@ -1,40 +0,0 @@ - - - - derived_object_msgs - 3.0.1 - Abstracted Messages from Perception Modalities - AutonomouStuff Software Development Team - MIT - http://wiki.ros.org/derived_object_msgs - https://github.com/astuff/astuff_sensor_msgs - https://github.com/astuff/astuff_sensor_msgs/issues - Daniel Stanek - Josh Whitley - - catkin - ament_cmake - - message_generation - rosidl_default_generators - ros_environment - - builtin_interfaces - geometry_msgs - radar_msgs - shape_msgs - std_msgs - - message_runtime - rosidl_default_runtime - - ament_lint_auto - ament_lint_common - - rosidl_interface_packages - - - catkin - ament_cmake - - diff --git a/astuff_sensor_msgs/radar_msgs/CHANGELOG.rst b/astuff_sensor_msgs/radar_msgs/CHANGELOG.rst deleted file mode 100644 index 56a23af0..00000000 --- a/astuff_sensor_msgs/radar_msgs/CHANGELOG.rst +++ /dev/null @@ -1,29 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package radar_msgs -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -3.0.1 (2020-01-23) ------------------- -* Adding ros_environment as required package to all packages. -* Hybridizing radar_msgs. (`#41 `_) -* Adding hybrid CI. -* Updating package.xml files for ROS2 rosdep. -* Adding message migration rules. -* Contributors: Joshua Whitley - -2.3.1 (2018-12-07) ------------------- -* Merge pull request `#31 `_ from astuff/maint/add_urls -* Adding URLs to package.xml files. -* Contributors: Daniel-Stanek, Joshua Whitley - -2.3.0 (2018-10-04) ------------------- - -2.2.2 (2018-08-30) ------------------- - -2.2.1 (2018-08-08) ------------------- -* Moving radar_msgs from platform_automation_msgs. -* Contributors: Joe Buckner, Joshua Whitley, Sam Rustan diff --git a/astuff_sensor_msgs/radar_msgs/CMakeLists.txt b/astuff_sensor_msgs/radar_msgs/CMakeLists.txt deleted file mode 100644 index a9e433bd..00000000 --- a/astuff_sensor_msgs/radar_msgs/CMakeLists.txt +++ /dev/null @@ -1,86 +0,0 @@ -project(radar_msgs) - -find_package(ros_environment REQUIRED) - -set(ROS_VERSION $ENV{ROS_VERSION}) - -set(MSG_FILES - "RadarDetection.msg" - "RadarDetectionArray.msg" - "RadarDetectionStamped.msg" - "RadarErrorStatus.msg" - "RadarStatus.msg" - "RadarTrack.msg" - "RadarTrackArray.msg" - "RadarTrackStamped.msg" -) - -if(${ROS_VERSION} EQUAL 1) - - cmake_minimum_required(VERSION 2.8.3) - - # Default to C++11 - if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 11) - endif() - - find_package(catkin REQUIRED - COMPONENTS - message_generation - geometry_msgs - std_msgs - ) - - add_message_files(FILES - ${MSG_FILES} - DIRECTORY msg - ) - - generate_messages(DEPENDENCIES geometry_msgs std_msgs) - - catkin_package( - CATKIN_DEPENDS message_runtime - ) - -elseif(${ROS_VERSION} EQUAL 2) - - cmake_minimum_required(VERSION 3.5) - - if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD_REQUIRED ON) - set(CMAKE_CXX_STANDARD 14) - endif() - - if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) - endif() - - find_package(ament_cmake REQUIRED) - find_package(builtin_interfaces REQUIRED) - find_package(geometry_msgs REQUIRED) - find_package(std_msgs REQUIRED) - find_package(rosidl_default_generators REQUIRED) - - # Apend "msg/" to each file name - set(TEMP_LIST "") - foreach(MSG_FILE ${MSG_FILES}) - list(APPEND TEMP_LIST "msg/${MSG_FILE}") - endforeach() - set(MSG_FILES ${TEMP_LIST}) - - rosidl_generate_interfaces(${PROJECT_NAME} - ${MSG_FILES} - DEPENDENCIES builtin_interfaces geometry_msgs std_msgs - ADD_LINTER_TESTS - ) - - ament_export_dependencies(rosidl_default_runtime) - - if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() - endif() - - ament_package() - -endif() diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarDetection.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarDetection.msg deleted file mode 100644 index d315e627..00000000 --- a/astuff_sensor_msgs/radar_msgs/msg/RadarDetection.msg +++ /dev/null @@ -1,10 +0,0 @@ -# All variables below are relative to the radar's frame of reference. -# This message is not meant to be used alone but as part of a stamped or array message. - -uint16 detection_id # The ID of this detection generated by the radar. If - # the radar does not generate IDs, this is intended as - # a sequential identifier for each detection in a scan. - -geometry_msgs/Point position # Only the x and y components are valid. -geometry_msgs/Vector3 velocity # range_rate rectangular transformation to x and y components -float64 amplitude # The detection amplitude in dB. diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionArray.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionArray.msg deleted file mode 100644 index a36e284c..00000000 --- a/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionArray.msg +++ /dev/null @@ -1,3 +0,0 @@ -std_msgs/Header header - -radar_msgs/RadarDetection[] detections diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionStamped.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionStamped.msg deleted file mode 100644 index 2df71fb8..00000000 --- a/astuff_sensor_msgs/radar_msgs/msg/RadarDetectionStamped.msg +++ /dev/null @@ -1,3 +0,0 @@ -std_msgs/Header header - -radar_msgs/RadarDetection detection diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarErrorStatus.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarErrorStatus.msg deleted file mode 100644 index c4d784fc..00000000 --- a/astuff_sensor_msgs/radar_msgs/msg/RadarErrorStatus.msg +++ /dev/null @@ -1,9 +0,0 @@ -std_msgs/Header header - -# Error Status - -bool comm_error -bool overheat_error -bool range_perf_error -bool internal_error -bool xcvr_operational diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarStatus.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarStatus.msg deleted file mode 100644 index b6f7d90a..00000000 --- a/astuff_sensor_msgs/radar_msgs/msg/RadarStatus.msg +++ /dev/null @@ -1,12 +0,0 @@ -std_msgs/Header header - -# Status of the radar - -int16 curvature -float32 yaw_rate -float32 vehicle_speed -uint8 max_track_targets -bool raw_data_mode -int8 temperature -bool patial_blockage -bool side_lobe_blockage diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarTrack.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarTrack.msg deleted file mode 100644 index f3dbc67a..00000000 --- a/astuff_sensor_msgs/radar_msgs/msg/RadarTrack.msg +++ /dev/null @@ -1,16 +0,0 @@ -# All variables below are relative to the radar's frame of reference. -# This message is not meant to be used alone but as part of a stamped or array message. - -uint16 track_id # The ID of this track generated by the radar. If - # the radar does not generate IDs, this is intended as - # a sequential identifier for each track in a scan. - -geometry_msgs/Polygon track_shape # The shape and position of the detection. This polygon - # encompasses a 2D plane which approximates the size and - # shape of the detection based on the distance from the - # radar, the detection angle, the width of all detections - # grouped into this track, and the height of the radar's - # vertical field of view at the detection distance. - -geometry_msgs/Vector3 linear_velocity # Only the x and y components are valid. -geometry_msgs/Vector3 linear_acceleration # Only the x component is valid. diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarTrackArray.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarTrackArray.msg deleted file mode 100644 index 9f3eab75..00000000 --- a/astuff_sensor_msgs/radar_msgs/msg/RadarTrackArray.msg +++ /dev/null @@ -1,3 +0,0 @@ -std_msgs/Header header - -radar_msgs/RadarTrack[] tracks diff --git a/astuff_sensor_msgs/radar_msgs/msg/RadarTrackStamped.msg b/astuff_sensor_msgs/radar_msgs/msg/RadarTrackStamped.msg deleted file mode 100644 index 452e9a3f..00000000 --- a/astuff_sensor_msgs/radar_msgs/msg/RadarTrackStamped.msg +++ /dev/null @@ -1,3 +0,0 @@ -std_msgs/Header header - -radar_msgs/RadarTrack track diff --git a/astuff_sensor_msgs/radar_msgs/package.xml b/astuff_sensor_msgs/radar_msgs/package.xml deleted file mode 100644 index 158cdca5..00000000 --- a/astuff_sensor_msgs/radar_msgs/package.xml +++ /dev/null @@ -1,38 +0,0 @@ - - - - radar_msgs - 3.0.1 - Generic Radar Messages - AutonomouStuff Software Development Team - MIT - http://wiki.ros.org/radar_msgs - https://github.com/astuff/astuff_sensor_msgs - https://github.com/astuff/astuff_sensor_msgs/issues - Daniel Stanek - Josh Whitley - - catkin - ament_cmake - - message_generation - rosidl_default_generators - ros_environment - - builtin_interfaces - geometry_msgs - std_msgs - - message_runtime - rosidl_default_runtime - - ament_lint_auto - ament_lint_common - - rosidl_interface_packages - - - catkin - ament_cmake - - From ef1034e1e2803da8f0f3218ab9d1b3529e453ce6 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 18 Jun 2020 16:48:36 +0200 Subject: [PATCH 221/627] Add astuff_sensor_msgs as submodule --- .gitmodules | 4 ++++ astuff_sensor_msgs | 1 + 2 files changed, 5 insertions(+) create mode 160000 astuff_sensor_msgs diff --git a/.gitmodules b/.gitmodules index 720c0ea7..3bfaaa5d 100644 --- a/.gitmodules +++ b/.gitmodules @@ -2,3 +2,7 @@ path = carla_msgs url = https://github.com/carla-simulator/ros-carla-msgs branch = master +[submodule "astuff_sensor_msgs"] + path = astuff_sensor_msgs + url = git@github.com:astuff/astuff_sensor_msgs.git + branch = maint/ros1_2_hybrid diff --git a/astuff_sensor_msgs b/astuff_sensor_msgs new file mode 160000 index 00000000..5a2c8979 --- /dev/null +++ b/astuff_sensor_msgs @@ -0,0 +1 @@ +Subproject commit 5a2c89793aead8a1e52fd772606ef0bc41085fb6 From 130721b9132be41981f89d1aff9120716d0dd5a3 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 18 Jun 2020 17:18:16 +0200 Subject: [PATCH 222/627] Add unused astuff_sensor_msgs packages to the colcon ignore mixin --- mixin/skip.mixin | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/mixin/skip.mixin b/mixin/skip.mixin index ebc70708..83500eb9 100644 --- a/mixin/skip.mixin +++ b/mixin/skip.mixin @@ -14,6 +14,15 @@ "pcl_recorder", "rqt_carla_control", "rviz_carla_plugin", + "astuff_sensor_msgs", + "delphi_esr_msgs", + "delphi_mrr_msgs", + "delphi_srr_msgs", + "ibeo_msgs", + "kartech_linear_actuator_msgs", + "mobileye_560_660_msgs", + "neobotix_usboard_msgs", + "pacmod_msgs", ], } } From c7d196559d1955244de9192ad883085168d6fccd Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 18 Jun 2020 18:29:40 +0200 Subject: [PATCH 223/627] Use library function --- .../carla_manual_control.py | 25 ++++--------------- 1 file changed, 5 insertions(+), 20 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index f622bd47..3c7ee5bc 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -41,6 +41,7 @@ from tf import ExtrapolationException import tf from ros_compatibility import QoSProfile + from tf.transformations import euler_from_quaternion elif ROS_VERSION == 2: import rclpy @@ -53,6 +54,7 @@ from rclpy.qos import QoSProfile, QoSDurabilityPolicy from threading import Thread, Lock, Event from builtin_interfaces.msg import Time + from transforms3d.euler import quat2euler as euler_from_quaternion else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -463,24 +465,6 @@ def gnss_updated(self, data): self.latitude = data.latitude self.longitude = data.longitude self.update_info_text() - - @staticmethod - def quaternion_to_euler(x, y, z, w): - - import math - t0 = +2.0 * (w * x + y * z) - t1 = +1.0 - 2.0 * (x * x + y * y) - X = math.degrees(math.atan2(t0, t1)) - - t2 = +2.0 * (w * y - z * x) - t2 = +1.0 if t2 > +1.0 else t2 - t2 = -1.0 if t2 < -1.0 else t2 - Y = math.degrees(math.asin(t2)) - - t3 = +2.0 * (w * z + x * y) - t4 = +1.0 - 2.0 * (y * y + z * z) - Z = math.degrees(math.atan2(t3, t4)) - return X, Y, Z def update_info_text(self): """ @@ -493,7 +477,7 @@ def update_info_text(self): (position, quaternion) = self.tf_listener.lookupTransform('/map', self.role_name, rospy.Time()) - _, _, yaw = tf.transformations.euler_from_quaternion(quaternion) + _, _, yaw = euler_from_quaternion(quaternion) yaw = -math.degrees(yaw) x = position[0] y = -position[1] @@ -503,7 +487,8 @@ def update_info_text(self): q = self.tfBuffer.lookup_transform('map', self.role_name, when) quaternion = q.transform.rotation position = q.transform.translation - _, __, yaw = self.quaternion_to_euler(quaternion.x, quaternion.y, quaternion.z, quaternion.w) + quaternion = [quaternion.w, quaternion.x, quaternion.y, quaternion.z] + _, __, yaw = euler_from_quaternion(quaternion) yaw = -math.degrees(yaw) x = position.x y = -position.y From bfba18d65c8d19ec22851d7a27cf6b7120359e64 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 19 Jun 2020 10:16:37 +0200 Subject: [PATCH 224/627] Remove unused import --- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 1 - 1 file changed, 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 278e2544..227e8ce0 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -28,7 +28,6 @@ elif ROS_VERSION == 2: from transforms3d.euler import euler2quat as quaternion_from_euler from transforms3d.euler import quat2euler as euler_from_quaternion - # from transformations.transformations import euler_from_quaternion, quaternion_from_euler else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") From f03fa5d9771634489dee0992e8798c8f76dd434a Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 19 Jun 2020 10:18:58 +0200 Subject: [PATCH 225/627] Add blank lines to improve readability. --- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 227e8ce0..d943e06e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -91,6 +91,7 @@ def sensor_data_updated(self, carla_lidar_measurement): lidar_data = numpy.frombuffer(carla_lidar_measurement.raw_data, dtype=numpy.float32) lidar_data = numpy.reshape(lidar_data, (int(lidar_data.shape[0] / 3), 3)) + # we take the oposite of y axis # (as lidar point are express in left handed coordinate system, and ros need right handed) # we need a copy here, because the data are read only in carla numpy @@ -98,6 +99,7 @@ def sensor_data_updated(self, carla_lidar_measurement): lidar_data = -lidar_data # we also need to permute x and y lidar_data = lidar_data[..., [1, 0, 2]] + if ROS_VERSION == 1: point_cloud_msg = create_cloud_xyz32(header, lidar_data) From 5726d03764e926c07a7ff976bc22e66283f1f2d4 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 19 Jun 2020 10:20:25 +0200 Subject: [PATCH 226/627] Change quaternion representation in ros2 due to transforms3d library --- carla_common/src/carla_common/transforms.py | 3 ++ .../carla_ego_vehicle/carla_ego_vehicle.py | 34 +++++++++++++------ .../src/carla_ros_bridge/lidar.py | 7 +++- 3 files changed, 33 insertions(+), 11 deletions(-) diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index efd4739a..9d370803 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -135,6 +135,9 @@ def carla_rotation_to_numpy_quaternion(carla_rotation): roll, pitch, yaw = carla_rotation_to_RPY(carla_rotation) quat = quaternion_from_euler(roll, pitch, yaw) + if ROS_VERSION == 2: + quat = [quat[1], quat[2], quat[3], quat[0]] + return quat diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 5d86ea51..d2e6cfe2 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -98,10 +98,16 @@ def __init__(self): math.radians(float(spawn_point[3])), math.radians(float(spawn_point[4])), math.radians(float(spawn_point[5]))) - pose.orientation.x = quat[0] - pose.orientation.y = quat[1] - pose.orientation.z = quat[2] - pose.orientation.w = quat[3] + if ROS_VERSION == 1: + pose.orientation.x = quat[0] + pose.orientation.y = quat[1] + pose.orientation.z = quat[2] + pose.orientation.w = quat[3] + elif ROS_VERSION == 2: + pose.orientation.x = quat[1] + pose.orientation.y = quat[2] + pose.orientation.z = quat[3] + pose.orientation.w = quat[0] self.actor_spawnpoint = pose self.initialpose_subscriber = self.create_subscriber(PoseWithCovarianceStamped, @@ -158,12 +164,20 @@ def restart(self): spawn_point.location.y = -self.actor_spawnpoint.position.y spawn_point.location.z = self.actor_spawnpoint.position.z + \ 2 # spawn 2m above ground - quaternion = ( - self.actor_spawnpoint.orientation.x, - self.actor_spawnpoint.orientation.y, - self.actor_spawnpoint.orientation.z, - self.actor_spawnpoint.orientation.w - ) + if ROS_VERSION == 1: + quaternion = [ + self.actor_spawnpoint.orientation.x, + self.actor_spawnpoint.orientation.y, + self.actor_spawnpoint.orientation.z, + self.actor_spawnpoint.orientation.w + ] + elif ROS_VERSION == 2: + quaternion = [ + self.actor_spawnpoint.orientation.w, + self.actor_spawnpoint.orientation.x, + self.actor_spawnpoint.orientation.y, + self.actor_spawnpoint.orientation.z + ] _, _, yaw = euler_from_quaternion(quaternion) spawn_point.rotation.yaw = -math.degrees(yaw) self.loginfo("Spawn {} at x={} y={} z={} yaw={}".format(self.role_name, diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index d943e06e..ac155b13 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -72,10 +72,15 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): tf_msg = super(Lidar, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation - quat = [rotation.x, rotation.y, rotation.z, rotation.w] + if ROS_VERSION == 1: + quat = [rotation.x, rotation.y, rotation.z, rotation.w] + elif ROS_VERSION == 2: + quat = [rotation.w, rotation.x, rotation.y, rotation.z] dummy_roll, dummy_pitch, yaw = euler_from_quaternion(quat) # set roll and pitch to zero quat = quaternion_from_euler(0, 0, yaw) + if ROS_VERSION == 2: + quat = [quat[1], quat[2], quat[3], quat[0]] tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion(quat) return tf_msg From 41161c6b1f86c283fa251975690425c98db5c312 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 19 Jun 2020 11:50:03 +0200 Subject: [PATCH 227/627] Fix quaternion order for camera sensor --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 61c1f66a..f4649ede 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -135,14 +135,18 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ tf_msg = super(Camera, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation - quat = [rotation.x, rotation.y, rotation.z, rotation.w] if ROS_VERSION == 1: + quat = [rotation.x, rotation.y, rotation.z, rotation.w] quat_swap = quaternion_from_matrix([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) + quat = quaternion_multiply(quat, quat_swap) elif ROS_VERSION == 2: + quat = [rotation.w, rotation.x, rotation.y, rotation.z] quat_swap = quaternion_from_matrix(numpy.asarray([numpy.asarray([0, 0, 1]), numpy.asarray([-1, 0, 0]), numpy.asarray([0, -1, 0])])) - quat = quaternion_multiply(quat, quat_swap) + quat_swap = [quat_swap[1], quat_swap[2], quat_swap[3], quat_swap[0]] + quat = quaternion_multiply(quat, quat_swap) + quat = [quat[1], quat[2], quat[3], quat[0]] tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion(quat) return tf_msg From dcf9acfe639aae0e7a6f1604ad1123747de6297a Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 19 Jun 2020 11:50:25 +0200 Subject: [PATCH 228/627] Use transforms3d library for imu sensor --- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 427f52fb..40b594dc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -18,7 +18,7 @@ if ROS_VERSION == 1: from tf.transformations import quaternion_from_euler elif ROS_VERSION == 2: - from transformations.transformations import quaternion_from_euler + from transforms3d.euler import euler2quat as quaternion_from_euler else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") From ed674fa0b6de81f9d3b092704425a84e8a0e180d Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 19 Jun 2020 11:50:38 +0200 Subject: [PATCH 229/627] Fix quaternion order for imu sensor --- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 40b594dc..bc0d9d7d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -72,5 +72,7 @@ def sensor_data_updated(self, carla_imu_measurement): quat = quaternion_from_euler(math.radians(imu_rotation.roll), math.radians(imu_rotation.pitch), math.radians(imu_rotation.yaw)) + if ROS_VERSION == 2: + quat = [quat[1], quat[2], quat[3], quat[0]] imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) self.publish_message(self.get_topic_prefix(), imu_msg) From 6a65ac9289051d2400bdbc6436724caf79b295d9 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 19 Jun 2020 12:42:12 +0200 Subject: [PATCH 230/627] Move quaternion and euler related functions to ros_compatibility to remove if-else switching where possible --- carla_common/src/carla_common/transforms.py | 11 +----- .../carla_ego_vehicle/carla_ego_vehicle.py | 39 ++++++------------- .../carla_manual_control.py | 6 +-- .../src/carla_ros_bridge/camera.py | 21 +++------- carla_ros_bridge/src/carla_ros_bridge/imu.py | 11 +----- .../src/carla_ros_bridge/lidar.py | 15 +------ .../ros_compatibility/ros_compatible_node.py | 39 +++++++++++++++++++ 7 files changed, 61 insertions(+), 81 deletions(-) diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index 9d370803..e7a4af33 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -18,13 +18,7 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from tf.transformations import euler_matrix, quaternion_from_euler -elif ROS_VERSION == 2: - from transforms3d.euler import euler2mat as euler_matrix - from transforms3d.euler import euler2quat as quaternion_from_euler -else: - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +from ros_compatibility import euler_matrix, quaternion_from_euler def carla_location_to_numpy_vector(carla_location): @@ -135,9 +129,6 @@ def carla_rotation_to_numpy_quaternion(carla_rotation): roll, pitch, yaw = carla_rotation_to_RPY(carla_rotation) quat = quaternion_from_euler(roll, pitch, yaw) - if ROS_VERSION == 2: - quat = [quat[1], quat[2], quat[3], quat[0]] - return quat diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index d2e6cfe2..23e849d6 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -19,7 +19,7 @@ import carla from carla_msgs.msg import CarlaStatus, CarlaWorldInfo from geometry_msgs.msg import PoseWithCovarianceStamped, Pose -from ros_compatibility import CompatibleNode +from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler import json import math import os @@ -30,14 +30,11 @@ if ROS_VERSION == 1: import rospy - from tf.transformations import euler_from_quaternion, quaternion_from_euler elif ROS_VERSION == 2: import sys import rclpy from ament_index_python.packages import get_package_share_directory - from transforms3d.euler import euler2quat as quaternion_from_euler - from transforms3d.euler import quat2euler as euler_from_quaternion secure_random = random.SystemRandom() @@ -98,16 +95,10 @@ def __init__(self): math.radians(float(spawn_point[3])), math.radians(float(spawn_point[4])), math.radians(float(spawn_point[5]))) - if ROS_VERSION == 1: - pose.orientation.x = quat[0] - pose.orientation.y = quat[1] - pose.orientation.z = quat[2] - pose.orientation.w = quat[3] - elif ROS_VERSION == 2: - pose.orientation.x = quat[1] - pose.orientation.y = quat[2] - pose.orientation.z = quat[3] - pose.orientation.w = quat[0] + pose.orientation.x = quat[0] + pose.orientation.y = quat[1] + pose.orientation.z = quat[2] + pose.orientation.w = quat[3] self.actor_spawnpoint = pose self.initialpose_subscriber = self.create_subscriber(PoseWithCovarianceStamped, @@ -164,20 +155,12 @@ def restart(self): spawn_point.location.y = -self.actor_spawnpoint.position.y spawn_point.location.z = self.actor_spawnpoint.position.z + \ 2 # spawn 2m above ground - if ROS_VERSION == 1: - quaternion = [ - self.actor_spawnpoint.orientation.x, - self.actor_spawnpoint.orientation.y, - self.actor_spawnpoint.orientation.z, - self.actor_spawnpoint.orientation.w - ] - elif ROS_VERSION == 2: - quaternion = [ - self.actor_spawnpoint.orientation.w, - self.actor_spawnpoint.orientation.x, - self.actor_spawnpoint.orientation.y, - self.actor_spawnpoint.orientation.z - ] + quaternion = [ + self.actor_spawnpoint.orientation.x, + self.actor_spawnpoint.orientation.y, + self.actor_spawnpoint.orientation.z, + self.actor_spawnpoint.orientation.w + ] _, _, yaw = euler_from_quaternion(quaternion) spawn_point.rotation.yaw = -math.degrees(yaw) self.loginfo("Spawn {} at x={} y={} z={} yaw={}".format(self.role_name, diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 3c7ee5bc..572e15b2 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -41,7 +41,6 @@ from tf import ExtrapolationException import tf from ros_compatibility import QoSProfile - from tf.transformations import euler_from_quaternion elif ROS_VERSION == 2: import rclpy @@ -54,11 +53,10 @@ from rclpy.qos import QoSProfile, QoSDurabilityPolicy from threading import Thread, Lock, Event from builtin_interfaces.msg import Time - from transforms3d.euler import quat2euler as euler_from_quaternion else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -from ros_compatibility import CompatibleNode, latch_on +from ros_compatibility import CompatibleNode, latch_on, euler_from_quaternion from std_msgs.msg import Bool @@ -487,7 +485,7 @@ def update_info_text(self): q = self.tfBuffer.lookup_transform('map', self.role_name, when) quaternion = q.transform.rotation position = q.transform.translation - quaternion = [quaternion.w, quaternion.x, quaternion.y, quaternion.z] + quaternion = [quaternion.x, quaternion.y, quaternion.z, quaternion.w] _, __, yaw = euler_from_quaternion(quaternion) yaw = -math.degrees(yaw) x = position.x diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index f4649ede..ebfdb624 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -17,19 +17,10 @@ import numpy import math from abc import abstractmethod -from ros_compatibility import * +from ros_compatibility import quaternion_from_matrix, quaternion_multiply import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from tf.transformations import quaternion_from_matrix, quaternion_multiply -elif ROS_VERSION == 2: - from transforms3d.quaternions import mat2quat as quaternion_from_matrix - from transforms3d.quaternions import qmult as quaternion_multiply -else: - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") - - class Camera(Sensor): """ Sensor implementation details for cameras @@ -135,18 +126,16 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ tf_msg = super(Camera, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation + quat = [rotation.x, rotation.y, rotation.z, rotation.w] + if ROS_VERSION == 1: - quat = [rotation.x, rotation.y, rotation.z, rotation.w] quat_swap = quaternion_from_matrix([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) - quat = quaternion_multiply(quat, quat_swap) elif ROS_VERSION == 2: - quat = [rotation.w, rotation.x, rotation.y, rotation.z] quat_swap = quaternion_from_matrix(numpy.asarray([numpy.asarray([0, 0, 1]), numpy.asarray([-1, 0, 0]), numpy.asarray([0, -1, 0])])) - quat_swap = [quat_swap[1], quat_swap[2], quat_swap[3], quat_swap[0]] - quat = quaternion_multiply(quat, quat_swap) - quat = [quat[1], quat[2], quat[3], quat[0]] + + quat = quaternion_multiply(quat, quat_swap) tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion(quat) return tf_msg diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index bc0d9d7d..1b5d7bd5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -15,14 +15,7 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from tf.transformations import quaternion_from_euler -elif ROS_VERSION == 2: - from transforms3d.euler import euler2quat as quaternion_from_euler -else: - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") - - +from ros_compatibility import quaternion_from_euler class ImuSensor(Sensor): """ @@ -72,7 +65,5 @@ def sensor_data_updated(self, carla_imu_measurement): quat = quaternion_from_euler(math.radians(imu_rotation.roll), math.radians(imu_rotation.pitch), math.radians(imu_rotation.yaw)) - if ROS_VERSION == 2: - quat = [quat[1], quat[2], quat[3], quat[0]] imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) self.publish_message(self.get_topic_prefix(), imu_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index ac155b13..b1dbf4e5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -23,15 +23,9 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from tf.transformations import euler_from_quaternion, quaternion_from_euler from sensor_msgs.point_cloud2 import create_cloud_xyz32 -elif ROS_VERSION == 2: - from transforms3d.euler import euler2quat as quaternion_from_euler - from transforms3d.euler import quat2euler as euler_from_quaternion -else: - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") - +from ros_compatibility import quaternion_from_euler, euler_from_quaternion _DATATYPES = {} _DATATYPES[PointField.FLOAT32] = ('f', 4) @@ -72,15 +66,10 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): tf_msg = super(Lidar, self).get_ros_transform(transform, frame_id, child_frame_id) rotation = tf_msg.transform.rotation - if ROS_VERSION == 1: - quat = [rotation.x, rotation.y, rotation.z, rotation.w] - elif ROS_VERSION == 2: - quat = [rotation.w, rotation.x, rotation.y, rotation.z] + quat = [rotation.x, rotation.y, rotation.z, rotation.w] dummy_roll, dummy_pitch, yaw = euler_from_quaternion(quat) # set roll and pitch to zero quat = quaternion_from_euler(0, 0, yaw) - if ROS_VERSION == 2: - quat = [quat[1], quat[2], quat[3], quat[0]] tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion(quat) return tf_msg diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 7b599ab9..236a0ec3 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -4,6 +4,7 @@ if ROS_VERSION == 1: import rospy + import tf.transformations as trans latch_on = True @@ -21,6 +22,21 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.unregister() + def euler_matrix(roll, pitch, yaw): + return trans.euler_matrix(roll, pitch, yaw) + + def euler_from_quaternion(quaternion): + return trans.euler_from_quaternion(quaternion) + + def quaternion_from_euler(roll, pitch, yaw): + return trans.quaternion_from_euler(roll, pitch, yaw) + + def quaternion_from_matrix(matrix): + return trans.quaternion_from_matrix(matrix) + + def quaternion_multiply(q1, q2): + return trans.quaternion_multiply(q1, q2) + class ROSException(rospy.ROSException): pass @@ -89,6 +105,9 @@ def shutdown(self): import rclpy from builtin_interfaces.msg import Time + from transforms3d.euler import euler2mat, euler2quat, quat2euler + from transforms3d.quaternions import mat2quat, qmult + latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL def ros_timestamp(sec=0, nsec=0, from_sec=False): @@ -110,6 +129,26 @@ def ros_shutdown(): def destroy_subscription(subsription): subsription.destroy() + def euler_matrix(roll, pitch, yaw): + return euler2mat(roll, pitch, yaw) + + def euler_from_quaternion(quaternion): + quat = [quaternion[3], quaternion[0], quaternion[1], quaternion[2]] + return quat2euler(quat) + + def quaternion_from_euler(roll, pitch, yaw): + quat = euler2quat(roll, pitch, yaw) + return [quat[1], quat[2], quat[3], quat[0]] + + def quaternion_from_matrix(matrix): + return mat2quat(matrix) + + def quaternion_multiply(q1, q2): + q1 = [q1[3], q1[0], q1[1], q1[2]] + q2 = [q2[3], q2[0], q2[1], q2[2]] + quat = qmult(q1, q2) + return [quat[1], quat[2], quat[3], quat[0]] + class ROSException(Exception): pass From f52bcaa214a85ac1ae700b7bbbc9d74edd37accd Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Fri, 19 Jun 2020 12:42:32 +0200 Subject: [PATCH 231/627] Import sys also in ros1 --- carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 23e849d6..b2716ae6 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -16,6 +16,7 @@ /initialpose might be published via RVIZ '2D Pose Estimate" button. """ +import sys import carla from carla_msgs.msg import CarlaStatus, CarlaWorldInfo from geometry_msgs.msg import PoseWithCovarianceStamped, Pose @@ -32,7 +33,6 @@ import rospy elif ROS_VERSION == 2: - import sys import rclpy from ament_index_python.packages import get_package_share_directory From c8e7f67317a1b263fc057b5aa32de48af6cad84f Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 19 Jun 2020 14:13:09 +0200 Subject: [PATCH 232/627] Add colcon mixin to build setup for eloquent --- docker/Dockerfile.eloquent | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent index 39ba0049..f7bb20cc 100644 --- a/docker/Dockerfile.eloquent +++ b/docker/Dockerfile.eloquent @@ -41,9 +41,11 @@ RUN echo "source /carla_ws/devel/setup.bash" >> ~/.bashrc SHELL ["/bin/bash", "-c" , "-l"] RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment -RUN rosdep install --from-paths src/carla_msgs src/ros_compatibility -r -y +RUN rosdep install --from-paths src -r -y RUN colcon info carla_msgs # .bashrc does not seem to do the source -RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --packages-select carla_msgs ros_compatibility +RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon mixin add skip file:///carla_ws/src/ros-bridge/mixin/index.yaml +RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon mixin update skip +RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --mixin skip CMD ["ros2", "run", "carla_ros_bridge" , "carla_ros_bridge.py"] From 52ac3ba07333c1b039487a53ff306667f53715b3 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 19 Jun 2020 14:26:44 +0200 Subject: [PATCH 233/627] Use /etc/profile to source ROS automatically for every RUN command --- docker/Dockerfile.eloquent | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent index f7bb20cc..49fd92c0 100644 --- a/docker/Dockerfile.eloquent +++ b/docker/Dockerfile.eloquent @@ -35,17 +35,18 @@ RUN easy_install --user --no-deps "/opt/carla/PythonAPI/carla/dist/carla-$CARLA_ COPY . src/ -RUN echo "source /opt/ros/$ROS_VERSION/setup.bash" >> ~/.bashrc -RUN echo "source /carla_ws/devel/setup.bash" >> ~/.bashrc - SHELL ["/bin/bash", "-c" , "-l"] +RUN echo "source /opt/ros/$ROS_VERSION/setup.bash" >> /etc/profile + RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment RUN rosdep install --from-paths src -r -y RUN colcon info carla_msgs # .bashrc does not seem to do the source -RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon mixin add skip file:///carla_ws/src/ros-bridge/mixin/index.yaml -RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon mixin update skip -RUN source /opt/ros/$ROS_VERSION/setup.bash && colcon build --mixin skip +RUN colcon mixin add skip file:///carla_ws/src/ros-bridge/mixin/index.yaml +RUN colcon mixin update skip +RUN colcon build --mixin skip + +RUN echo "source /carla_ws/install/setup.bash" >> /etc/profile CMD ["ros2", "run", "carla_ros_bridge" , "carla_ros_bridge.py"] From c564581836f9d189f7dbe9694bdc95503cd5ac22 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 19 Jun 2020 14:37:23 +0200 Subject: [PATCH 234/627] Add Eloquent to travis --- .travis.yml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.travis.yml b/.travis.yml index 53fe44a3..3c829a53 100644 --- a/.travis.yml +++ b/.travis.yml @@ -51,6 +51,11 @@ jobs: before_install: skip install: skip script: cd docker && ./build.sh --build-arg ROS_VERSION=melodic + - name: "Docker Eloquent" + services: docker + before_install: skip + install: skip + script: docker build -t carla-ros-bridge -f Dockerfile.eloquent ./.. before_install: - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' From 8c4c3aaa853d3090a2b3cda5cdf1bcbdbc15d6c7 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 19 Jun 2020 14:49:10 +0200 Subject: [PATCH 235/627] Autopep8 format --- carla_common/src/carla_common/transforms.py | 3 +-- carla_ros_bridge/src/carla_ros_bridge/camera.py | 1 + carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/sensor.py | 2 -- .../carla_twist_to_control.py | 13 +++++++------ 6 files changed, 11 insertions(+), 12 deletions(-) diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index e7a4af33..d15230db 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -10,6 +10,7 @@ Tool functions to convert transforms from carla to ROS coordinate system """ +from ros_compatibility import euler_matrix, quaternion_from_euler import math import numpy @@ -18,8 +19,6 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -from ros_compatibility import euler_matrix, quaternion_from_euler - def carla_location_to_numpy_vector(carla_location): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index ebfdb624..02e466a8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -21,6 +21,7 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + class Camera(Sensor): """ Sensor implementation details for cameras diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 1b5d7bd5..6931d9cc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -7,6 +7,7 @@ Classes to handle Carla imu sensor """ +from ros_compatibility import quaternion_from_euler import carla_common.transforms as trans from carla_ros_bridge.sensor import Sensor from sensor_msgs.msg import Imu @@ -15,7 +16,6 @@ import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -from ros_compatibility import quaternion_from_euler class ImuSensor(Sensor): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index b1dbf4e5..23cb81f1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -11,6 +11,7 @@ """ from __future__ import print_function +from ros_compatibility import quaternion_from_euler, euler_from_quaternion import carla_common.transforms as trans from carla_ros_bridge.sensor import Sensor from sensor_msgs.msg import PointCloud2, PointField @@ -25,7 +26,6 @@ if ROS_VERSION == 1: from sensor_msgs.point_cloud2 import create_cloud_xyz32 -from ros_compatibility import quaternion_from_euler, euler_from_quaternion _DATATYPES = {} _DATATYPES[PointField.FLOAT32] = ('f', 4) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 3baa1977..caf0ad5e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -25,8 +25,6 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") - - class Sensor(Actor, CompatibleNode): """ Actor implementation details for sensors diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index 561105c7..f0f2314b 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -9,6 +9,7 @@ use max wheel steer angle """ +from ros_compatibility import CompatibleNode, ros_ok, ROSException, ROSInterruptException import sys from geometry_msgs.msg import Twist from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo @@ -21,8 +22,6 @@ elif ROS_VERSION == 2: import rclpy -from ros_compatibility import CompatibleNode, ros_ok, ROSException, ROSInterruptException - class TwistToVehicleControl(CompatibleNode): # pylint: disable=too-few-public-methods """ @@ -45,18 +44,20 @@ def initialize_twist_to_control(self, role_name): self.loginfo("Wait for vehicle info...") try: vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), - CarlaEgoVehicleInfo) + CarlaEgoVehicleInfo) except ROSInterruptException as e: if ros_ok: raise e else: sys.exit(0) - self.create_subscriber(CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(role_name), self.update_vehicle_info) + self.create_subscriber(CarlaEgoVehicleInfo, + "/carla/{}/vehicle_info".format(role_name), self.update_vehicle_info) self.create_subscriber(Twist, "/carla/{}/twist".format(role_name), self.twist_received) - self.pub = self.new_publisher(CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name)) + self.pub = self.new_publisher(CarlaEgoVehicleControl, + "/carla/{}/vehicle_control_cmd".format(role_name)) def update_vehicle_info(self, vehicle_info): """ @@ -116,7 +117,7 @@ def main(): :return: """ # rospy.init_node('convert_twist_to_vehicle_control', anonymous=True) - + role_name = None twist_to_vehicle_control = None From 43bb192fa20a2cc2b7489da30b8d3587039748c5 Mon Sep 17 00:00:00 2001 From: FabianSchurig Date: Fri, 19 Jun 2020 14:56:43 +0200 Subject: [PATCH 236/627] Use public url with https instead of ssh --- .gitmodules | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.gitmodules b/.gitmodules index 3bfaaa5d..3cef1f6a 100644 --- a/.gitmodules +++ b/.gitmodules @@ -4,5 +4,5 @@ branch = master [submodule "astuff_sensor_msgs"] path = astuff_sensor_msgs - url = git@github.com:astuff/astuff_sensor_msgs.git + url = https://github.com/astuff/astuff_sensor_msgs.git branch = maint/ros1_2_hybrid From 3eb38016acb804ecc724c2d5f42b5df104bcd79e Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 12:16:09 +0200 Subject: [PATCH 237/627] Reformat project to conform to TravisCI's Pylint requirements --- carla_common/setup.py | 1 + carla_common/src/carla_common/transforms.py | 13 +++++--- .../src/carla_ros_bridge/actor.py | 8 ++--- .../src/carla_ros_bridge/bridge.py | 14 ++++++--- .../src/carla_ros_bridge/camera.py | 31 +++++++++++-------- .../carla_status_publisher.py | 4 ++- .../src/carla_ros_bridge/collision_sensor.py | 2 +- .../src/carla_ros_bridge/communication.py | 7 +++-- .../src/carla_ros_bridge/debug_helper.py | 8 +++-- .../src/carla_ros_bridge/ego_vehicle.py | 27 ++++++++-------- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 3 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 8 +++-- .../carla_ros_bridge/lane_invasion_sensor.py | 2 +- .../src/carla_ros_bridge/lidar.py | 13 ++++---- .../src/carla_ros_bridge/object_sensor.py | 4 +-- .../src/carla_ros_bridge/pseudo_actor.py | 7 +++-- .../src/carla_ros_bridge/sensor.py | 22 +++++++------ .../src/carla_ros_bridge/traffic.py | 4 +-- .../carla_ros_bridge/traffic_lights_sensor.py | 4 +-- .../carla_ros_bridge/traffic_participant.py | 3 +- .../src/carla_ros_bridge/vehicle.py | 5 ++- .../src/carla_ros_bridge/walker.py | 7 ++--- 22 files changed, 112 insertions(+), 85 deletions(-) diff --git a/carla_common/setup.py b/carla_common/setup.py index 7ddf8860..bebb2c05 100644 --- a/carla_common/setup.py +++ b/carla_common/setup.py @@ -3,6 +3,7 @@ """ import os + ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index d15230db..cfdbfda7 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -10,13 +10,14 @@ Tool functions to convert transforms from carla to ROS coordinate system """ -from ros_compatibility import euler_matrix, quaternion_from_euler import math -import numpy +import os +import numpy from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel -import os +from ros_compatibility import euler_matrix, quaternion_from_euler + ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -206,7 +207,8 @@ def carla_vector_to_ros_vector_rotated(carla_vector, carla_rotation): return ros_vector -def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, carla_rotation=None): +def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, + carla_rotation=None): """ Convert a carla velocity to a ROS twist @@ -224,7 +226,8 @@ def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, c """ ros_twist = Twist() if carla_rotation: - ros_twist.linear = carla_vector_to_ros_vector_rotated(carla_linear_velocity, carla_rotation) + ros_twist.linear = carla_vector_to_ros_vector_rotated(carla_linear_velocity, + carla_rotation) else: ros_twist.linear = carla_location_to_ros_vector3(carla_linear_velocity) ros_twist.angular.x = math.radians(carla_angular_velocity.x) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 532af0e9..f5ee390e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -10,14 +10,13 @@ Base Classes to handle Actor objects """ +import carla_common.transforms as trans import numpy as np +from carla_ros_bridge.pseudo_actor import PseudoActor from geometry_msgs.msg import TransformStamped from std_msgs.msg import ColorRGBA from visualization_msgs.msg import Marker -from carla_ros_bridge.pseudo_actor import PseudoActor -import carla_common.transforms as trans - class Actor(PseudoActor): """ @@ -40,7 +39,8 @@ def __init__(self, carla_actor, parent, communication, prefix=None): self.carla_actor = carla_actor if carla_actor.id > np.iinfo(np.uint32).max: - raise ValueError("Actor ID exceeds maximum supported value '{}'".format(carla_actor.id)) + raise ValueError( + "Actor ID exceeds maximum supported value '{}'".format(carla_actor.id)) self.carla_actor_id = carla_actor.id diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 716c91eb..653c4229 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -12,6 +12,7 @@ """ from ros_compatibility import * + try: import queue except ImportError: @@ -48,6 +49,7 @@ from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters import os + ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: @@ -125,7 +127,8 @@ def initialize_bridge(self, carla_world, params): self.carla_control_subscriber = \ self.create_subscriber(CarlaControl, "/carla/control", - lambda control: self.carla_control_queue.put(control.command), callback_group=self.callback_group) + lambda control: self.carla_control_queue.put( + control.command), callback_group=self.callback_group) self.synchronous_mode_update_thread = Thread(target=self._synchronous_mode_update) self.synchronous_mode_update_thread.start() @@ -263,7 +266,7 @@ def _synchronous_mode_update(self): if not self._all_vehicle_control_commands_received.wait(1): self.logwarn("Timeout (1s) while waiting for vehicle control commands. " "Missing command from actor ids {}".format( - self._expected_ego_vehicle_control_command_ids)) + self._expected_ego_vehicle_control_command_ids)) self._all_vehicle_control_commands_received.clear() def _carla_time_tick(self, carla_snapshot): @@ -395,7 +398,7 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m else: actor = Traffic(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("vehicle"): - if carla_actor.attributes.get('role_name')\ + if carla_actor.attributes.get('role_name') \ in self.parameters['ego_vehicle']['role_name']: actor = EgoVehicle(carla_actor, parent, self.comm, self._ego_vehicle_control_applied_callback) @@ -436,7 +439,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m actor = LaneInvasionSensor(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) else: - actor = Sensor(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Sensor(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("spectator"): actor = Spectator(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("walker"): @@ -570,7 +574,7 @@ def main(): sys.exit(1) if LooseVersion(carla_client.get_server_version()) < \ - LooseVersion(CarlaRosBridge.CARLA_VERSION): + LooseVersion(CarlaRosBridge.CARLA_VERSION): carla_bridge.logfatal("CARLA Server version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) sys.exit(1) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 02e466a8..93825a14 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -9,16 +9,19 @@ """ Class to handle Carla camera sensors """ +import math +import os +from abc import abstractmethod + +import carla import carla_common.transforms as trans +import numpy from carla_ros_bridge.sensor import Sensor -import carla -from sensor_msgs.msg import CameraInfo from cv_bridge import CvBridge -import numpy -import math -from abc import abstractmethod +from sensor_msgs.msg import CameraInfo + from ros_compatibility import quaternion_from_matrix, quaternion_multiply -import os + ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -47,14 +50,15 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= if not prefix: prefix = 'camera' super(Camera, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, synchronous_mode=synchronous_mode, + communication=communication, + synchronous_mode=synchronous_mode, prefix=prefix, sensor_name=sensor_name) if self.__class__.__name__ == "Camera": self.logwarn("Created Unsupported Camera Actor" "(id={}, parent_id={}, type={}, attributes={})".format( - self.get_id(), self.get_parent_id(), self.carla_actor.type_id, - self.carla_actor.attributes)) + self.get_id(), self.get_parent_id(), self.carla_actor.type_id, + self.carla_actor.attributes)) else: self._build_camera_info() @@ -73,7 +77,7 @@ def _build_camera_info(self): cx = camera_info.width / 2.0 cy = camera_info.height / 2.0 fx = camera_info.width / ( - 2.0 * math.tan(float(self.carla_actor.attributes['fov']) * math.pi / 360.0)) + 2.0 * math.tan(float(self.carla_actor.attributes['fov']) * math.pi / 360.0)) fy = fx if ROS_VERSION == 1: camera_info.K = [fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0] @@ -133,8 +137,9 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): quat_swap = quaternion_from_matrix([[0, 0, 1, 0], [-1, 0, 0, 0], [0, -1, 0, 0], [0, 0, 0, 1]]) elif ROS_VERSION == 2: - quat_swap = quaternion_from_matrix(numpy.asarray([numpy.asarray([0, 0, 1]), numpy.asarray([-1, 0, 0]), - numpy.asarray([0, -1, 0])])) + quat_swap = quaternion_from_matrix( + numpy.asarray([numpy.asarray([0, 0, 1]), numpy.asarray([-1, 0, 0]), + numpy.asarray([0, -1, 0])])) quat = quaternion_multiply(quat, quat_swap) @@ -276,7 +281,7 @@ def get_carla_image_data_array(self, carla_image): # Apply (R + G * 256 + B * 256 * 256) / (256**3 - 1) * 1000 # according to the documentation: # https://carla.readthedocs.io/en/latest/cameras_and_sensors/#camera-depth-map - scales = numpy.array([65536.0, 256.0, 1.0, 0]) / (256**3 - 1) * 1000 + scales = numpy.array([65536.0, 256.0, 1.0, 0]) / (256 ** 3 - 1) * 1000 depth_image = numpy.dot(bgra_image, scales).astype(numpy.float32) # actually we want encoding '32FC1' diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 4f883ccf..bc009adb 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -9,9 +9,11 @@ """ report the carla status """ +import os + from carla_msgs.msg import CarlaStatus + from ros_compatibility import * -import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index 05293b4a..eb60477a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -10,8 +10,8 @@ Classes to handle collision events """ -from carla_ros_bridge.sensor import Sensor from carla_msgs.msg import CarlaCollisionEvent +from carla_ros_bridge.sensor import Sensor class CollisionSensor(Sensor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index 7dd96323..cd59999b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -9,10 +9,13 @@ """ Handle communication of ROS topics """ -from tf2_msgs.msg import TFMessage +import os + from rosgraph_msgs.msg import Clock +from tf2_msgs.msg import TFMessage + from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile, latch_on -import os + ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION not in (1, 2): diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 3ce1b798..fae91b27 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -8,12 +8,14 @@ """ Class to draw marker """ -from ros_compatibility import * -import carla -from visualization_msgs.msg import Marker, MarkerArray import math import os +import carla +from visualization_msgs.msg import Marker, MarkerArray + +from ros_compatibility import * + ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 48aeb73d..d9006251 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -9,20 +9,21 @@ """ Classes to handle Carla vehicles """ -from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel,\ - CarlaEgoVehicleControl, CarlaEgoVehicleStatus +import math + import carla_common.transforms as transforms -from carla_ros_bridge.vehicle import Vehicle +import numpy from carla import Vector3D from carla import VehicleControl +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel, \ + CarlaEgoVehicleControl, CarlaEgoVehicleStatus +from carla_ros_bridge.vehicle import Vehicle from geometry_msgs.msg import Twist, Transform from std_msgs.msg import Bool from std_msgs.msg import ColorRGBA + from ros_compatibility import * -import math -import numpy -import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION not in (1, 2): @@ -140,12 +141,12 @@ def send_vehicle_msgs(self): wheel_info.radius = wheel.radius wheel_info.max_brake_torque = wheel.max_brake_torque wheel_info.max_handbrake_torque = wheel.max_handbrake_torque - wheel_info.position.x = (wheel.position.x/100.0) - \ - self.carla_actor.get_transform().location.x + wheel_info.position.x = (wheel.position.x / 100.0) - \ + self.carla_actor.get_transform().location.x wheel_info.position.y = -( - (wheel.position.y / 100.0) - self.carla_actor.get_transform().location.y) - wheel_info.position.z = (wheel.position.z/100.0) - \ - self.carla_actor.get_transform().location.z + (wheel.position.y / 100.0) - self.carla_actor.get_transform().location.y) + wheel_info.position.z = (wheel.position.z / 100.0) - \ + self.carla_actor.get_transform().location.z vehicle_info.wheels.append(wheel_info) vehicle_info.max_rpm = vehicle_physics.max_rpm @@ -282,8 +283,8 @@ def get_vector_length_squared(carla_vector): :rtype: float64 """ return carla_vector.x * carla_vector.x + \ - carla_vector.y * carla_vector.y + \ - carla_vector.z * carla_vector.z + carla_vector.y * carla_vector.y + \ + carla_vector.z * carla_vector.z @staticmethod def get_vehicle_speed_squared(carla_vehicle): diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index e9c55114..f6acbc13 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -10,9 +10,8 @@ Classes to handle Carla gnsss """ -from sensor_msgs.msg import NavSatFix - from carla_ros_bridge.sensor import Sensor +from sensor_msgs.msg import NavSatFix class Gnss(Sensor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 6931d9cc..c310887e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -7,13 +7,15 @@ Classes to handle Carla imu sensor """ -from ros_compatibility import quaternion_from_euler +import math +import os + import carla_common.transforms as trans from carla_ros_bridge.sensor import Sensor from sensor_msgs.msg import Imu -import math -import os +from ros_compatibility import quaternion_from_euler + ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index b632d4b6..d1e4672d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -10,8 +10,8 @@ Classes to handle lane invasion events """ -from carla_ros_bridge.sensor import Sensor from carla_msgs.msg import CarlaLaneInvasionEvent +from carla_ros_bridge.sensor import Sensor class LaneInvasionSensor(Sensor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 23cb81f1..c360c97c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -11,22 +11,23 @@ """ from __future__ import print_function -from ros_compatibility import quaternion_from_euler, euler_from_quaternion + +import ctypes +import os +import struct + import carla_common.transforms as trans +import numpy from carla_ros_bridge.sensor import Sensor from sensor_msgs.msg import PointCloud2, PointField -import numpy -import ctypes -import struct +from ros_compatibility import quaternion_from_euler, euler_from_quaternion -import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: from sensor_msgs.point_cloud2 import create_cloud_xyz32 - _DATATYPES = {} _DATATYPES[PointField.FLOAT32] = ('f', 4) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 2a62b3d2..5ddde373 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -9,10 +9,10 @@ handle a object sensor """ -from derived_object_msgs.msg import ObjectArray +from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.walker import Walker -from carla_ros_bridge.pseudo_actor import PseudoActor +from derived_object_msgs.msg import ObjectArray class ObjectSensor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 9bf2f4f7..99c983be 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -9,9 +9,12 @@ Base Class to handle Pseudo Actors (that are not existing in Carla world) """ -from ros_compatibility import CompatibleNode, ros_timestamp -from std_msgs.msg import Header import os + +from std_msgs.msg import Header + +from ros_compatibility import CompatibleNode, ros_timestamp + ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION not in (1, 2): diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index caf0ad5e..5142e670 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -9,16 +9,20 @@ Classes to handle Carla sensors """ +from abc import abstractmethod + import carla_common.transforms as trans from carla_ros_bridge.actor import Actor + from ros_compatibility import CompatibleNode, ros_ok -from abc import abstractmethod + try: import queue except ImportError: import Queue as queue import os + ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION not in (1, 2): @@ -40,7 +44,7 @@ def __init__( # if a sensor only delivers data on special events, # do not wait for it. That means you might get data from a # sensor, that belongs to a different frame - prefix=None, + prefix=None, sensor_name=None): """ Constructor @@ -106,7 +110,7 @@ def _callback_sensor_data(self, carla_sensor_data): if self.synchronous_mode: if self.sensor_tick_time: self.next_data_expected_time = carla_sensor_data.timestamp + \ - float(self.sensor_tick_time) + float(self.sensor_tick_time) self.queue.put(carla_sensor_data) else: self.publish_transform( @@ -133,8 +137,8 @@ def _update_synchronous_event_sensor(self, frame): if carla_sensor_data.frame != frame: self.logwarn("{}({}): Received event for frame {}" " (expected {}). Process it anyways.".format( - self.__class__.__name__, self.get_id(), - carla_sensor_data.frame, frame)) + self.__class__.__name__, self.get_id(), + carla_sensor_data.frame, frame)) self.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), frame)) self.publish_transform( @@ -145,10 +149,10 @@ def _update_synchronous_event_sensor(self, frame): return def _update_synchronous_sensor(self, frame, timestamp): - while not self.next_data_expected_time or\ - (not self.queue.empty() or - self.next_data_expected_time and - self.next_data_expected_time < timestamp): + while not self.next_data_expected_time or \ + (not self.queue.empty() or + self.next_data_expected_time and + self.next_data_expected_time < timestamp): while True: try: carla_sensor_data = self.queue.get(timeout=1.0) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 399b83a1..0f83bfd3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -10,10 +10,10 @@ Classes to handle Carla traffic objects """ -from carla_ros_bridge.actor import Actor import carla_common.transforms as trans -from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo from carla import TrafficLightState +from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo +from carla_ros_bridge.actor import Actor class Traffic(Actor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 1850ed76..a8c74439 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -9,10 +9,10 @@ a sensor that reports the state of all traffic lights """ -from carla_msgs.msg import CarlaTrafficLightStatusList,\ +from carla_msgs.msg import CarlaTrafficLightStatusList, \ CarlaTrafficLightInfoList -from carla_ros_bridge.traffic import TrafficLight from carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.traffic import TrafficLight class TrafficLightsSensor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index c03f1ec6..7dcefb57 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -10,12 +10,11 @@ Classes to handle Carla traffic participants """ +from carla_ros_bridge.actor import Actor from derived_object_msgs.msg import Object from nav_msgs.msg import Odometry from shape_msgs.msg import SolidPrimitive -from carla_ros_bridge.actor import Actor - class TrafficParticipant(Actor): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 0bb24721..25b9c8fd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -10,10 +10,9 @@ Classes to handle Carla vehicles """ -from std_msgs.msg import ColorRGBA -from derived_object_msgs.msg import Object - from carla_ros_bridge.traffic_participant import TrafficParticipant +from derived_object_msgs.msg import Object +from std_msgs.msg import ColorRGBA class Vehicle(TrafficParticipant): diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index a31e935c..b4582118 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -10,11 +10,10 @@ Classes to handle Carla pedestrians """ -from derived_object_msgs.msg import Object - -from carla_ros_bridge.traffic_participant import TrafficParticipant -from carla_msgs.msg import CarlaWalkerControl from carla import WalkerControl +from carla_msgs.msg import CarlaWalkerControl +from carla_ros_bridge.traffic_participant import TrafficParticipant +from derived_object_msgs.msg import Object from ros_compatibility import destroy_subscription From 91d4721e62ba04edf9f2f8f6b4e44b8af5e28aaa Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 12:28:33 +0200 Subject: [PATCH 238/627] Autopep8 non-compliant files --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/camera.py | 6 +++--- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 10 +++++----- carla_ros_bridge/src/carla_ros_bridge/sensor.py | 6 +++--- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 653c4229..0792043f 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -266,7 +266,7 @@ def _synchronous_mode_update(self): if not self._all_vehicle_control_commands_received.wait(1): self.logwarn("Timeout (1s) while waiting for vehicle control commands. " "Missing command from actor ids {}".format( - self._expected_ego_vehicle_control_command_ids)) + self._expected_ego_vehicle_control_command_ids)) self._all_vehicle_control_commands_received.clear() def _carla_time_tick(self, carla_snapshot): diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 93825a14..4d3ba249 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -57,8 +57,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= if self.__class__.__name__ == "Camera": self.logwarn("Created Unsupported Camera Actor" "(id={}, parent_id={}, type={}, attributes={})".format( - self.get_id(), self.get_parent_id(), self.carla_actor.type_id, - self.carla_actor.attributes)) + self.get_id(), self.get_parent_id(), self.carla_actor.type_id, + self.carla_actor.attributes)) else: self._build_camera_info() @@ -77,7 +77,7 @@ def _build_camera_info(self): cx = camera_info.width / 2.0 cy = camera_info.height / 2.0 fx = camera_info.width / ( - 2.0 * math.tan(float(self.carla_actor.attributes['fov']) * math.pi / 360.0)) + 2.0 * math.tan(float(self.carla_actor.attributes['fov']) * math.pi / 360.0)) fy = fx if ROS_VERSION == 1: camera_info.K = [fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0] diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index d9006251..7f9a8633 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -142,11 +142,11 @@ def send_vehicle_msgs(self): wheel_info.max_brake_torque = wheel.max_brake_torque wheel_info.max_handbrake_torque = wheel.max_handbrake_torque wheel_info.position.x = (wheel.position.x / 100.0) - \ - self.carla_actor.get_transform().location.x + self.carla_actor.get_transform().location.x wheel_info.position.y = -( - (wheel.position.y / 100.0) - self.carla_actor.get_transform().location.y) + (wheel.position.y / 100.0) - self.carla_actor.get_transform().location.y) wheel_info.position.z = (wheel.position.z / 100.0) - \ - self.carla_actor.get_transform().location.z + self.carla_actor.get_transform().location.z vehicle_info.wheels.append(wheel_info) vehicle_info.max_rpm = vehicle_physics.max_rpm @@ -283,8 +283,8 @@ def get_vector_length_squared(carla_vector): :rtype: float64 """ return carla_vector.x * carla_vector.x + \ - carla_vector.y * carla_vector.y + \ - carla_vector.z * carla_vector.z + carla_vector.y * carla_vector.y + \ + carla_vector.z * carla_vector.z @staticmethod def get_vehicle_speed_squared(carla_vehicle): diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 5142e670..c2e0f0ab 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -110,7 +110,7 @@ def _callback_sensor_data(self, carla_sensor_data): if self.synchronous_mode: if self.sensor_tick_time: self.next_data_expected_time = carla_sensor_data.timestamp + \ - float(self.sensor_tick_time) + float(self.sensor_tick_time) self.queue.put(carla_sensor_data) else: self.publish_transform( @@ -137,8 +137,8 @@ def _update_synchronous_event_sensor(self, frame): if carla_sensor_data.frame != frame: self.logwarn("{}({}): Received event for frame {}" " (expected {}). Process it anyways.".format( - self.__class__.__name__, self.get_id(), - carla_sensor_data.frame, frame)) + self.__class__.__name__, self.get_id(), + carla_sensor_data.frame, frame)) self.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), frame)) self.publish_transform( From 85bda5da83d51b51cb6d62e6bdf75534452237ca Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 14:01:03 +0200 Subject: [PATCH 239/627] Remove wildcard import --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 0792043f..205a4c1b 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -11,7 +11,7 @@ Class that handle communication between CARLA and ROS """ -from ros_compatibility import * +from ros_compatibility import CompatibleNode, ros_ok, destroy_subscription try: import queue From 4d0f581763b5a4138373a400718ecf1d648cd8f5 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 14:01:49 +0200 Subject: [PATCH 240/627] Ordering of imports --- carla_common/setup.py | 1 - carla_common/src/carla_common/transforms.py | 13 +++++-------- carla_ros_bridge/src/carla_ros_bridge/camera.py | 1 + carla_ros_bridge/src/carla_ros_bridge/lidar.py | 1 + carla_ros_bridge/src/carla_ros_bridge/sensor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/walker.py | 2 +- 6 files changed, 9 insertions(+), 11 deletions(-) diff --git a/carla_common/setup.py b/carla_common/setup.py index bebb2c05..7ddf8860 100644 --- a/carla_common/setup.py +++ b/carla_common/setup.py @@ -3,7 +3,6 @@ """ import os - ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index cfdbfda7..d15230db 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -10,14 +10,13 @@ Tool functions to convert transforms from carla to ROS coordinate system """ +from ros_compatibility import euler_matrix, quaternion_from_euler import math -import os - import numpy -from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel -from ros_compatibility import euler_matrix, quaternion_from_euler +from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel +import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -207,8 +206,7 @@ def carla_vector_to_ros_vector_rotated(carla_vector, carla_rotation): return ros_vector -def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, - carla_rotation=None): +def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, carla_rotation=None): """ Convert a carla velocity to a ROS twist @@ -226,8 +224,7 @@ def carla_velocity_to_ros_twist(carla_linear_velocity, carla_angular_velocity, """ ros_twist = Twist() if carla_rotation: - ros_twist.linear = carla_vector_to_ros_vector_rotated(carla_linear_velocity, - carla_rotation) + ros_twist.linear = carla_vector_to_ros_vector_rotated(carla_linear_velocity, carla_rotation) else: ros_twist.linear = carla_location_to_ros_vector3(carla_linear_velocity) ros_twist.angular.x = math.radians(carla_angular_velocity.x) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 4d3ba249..427a8a74 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -85,6 +85,7 @@ def _build_camera_info(self): camera_info.R = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] camera_info.P = [fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0] elif ROS_VERSION == 2: + # pylint: disable=assigning-non-slot camera_info.k = [fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0] camera_info.d = [0.0, 0.0, 0.0, 0.0, 0.0] camera_info.r = [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index c360c97c..a566f840 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -12,6 +12,7 @@ from __future__ import print_function +import sys import ctypes import os import struct diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index c2e0f0ab..3ba182d4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -9,6 +9,7 @@ Classes to handle Carla sensors """ +import os from abc import abstractmethod import carla_common.transforms as trans @@ -21,7 +22,6 @@ except ImportError: import Queue as queue -import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index b4582118..f54a6098 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -10,10 +10,10 @@ Classes to handle Carla pedestrians """ +from derived_object_msgs.msg import Object from carla import WalkerControl from carla_msgs.msg import CarlaWalkerControl from carla_ros_bridge.traffic_participant import TrafficParticipant -from derived_object_msgs.msg import Object from ros_compatibility import destroy_subscription From b14d3fbcf0da9c82fc1f94be3d2052ca7aad37e5 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 14:05:48 +0200 Subject: [PATCH 241/627] Add ros_compatibility package to pylint cheks --- check.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/check.sh b/check.sh index f69f8988..07fd4461 100755 --- a/check.sh +++ b/check.sh @@ -11,4 +11,4 @@ autopep8 carla_twist_to_control/src/carla_twist_to_control/*.py --in-place --max autopep8 carla_spectator_camera/src/carla_spectator_camera/*.py --in-place --max-line-length=100 autopep8 carla_infrastructure/src/carla_infrastructure/*.py --in-place --max-line-length=100 -pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ +pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ ros_compatiblity/src/ros_compatiblity From 99a09af5e55d7616ea13b08f6b5eca071c120d8d Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 14:06:58 +0200 Subject: [PATCH 242/627] Add ros_compatibility package to autopep8 checks --- check.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/check.sh b/check.sh index 07fd4461..6668b504 100755 --- a/check.sh +++ b/check.sh @@ -10,5 +10,6 @@ autopep8 carla_ros_scenario_runner/src/carla_ros_scenario_runner/*.py --in-place autopep8 carla_twist_to_control/src/carla_twist_to_control/*.py --in-place --max-line-length=100 autopep8 carla_spectator_camera/src/carla_spectator_camera/*.py --in-place --max-line-length=100 autopep8 carla_infrastructure/src/carla_infrastructure/*.py --in-place --max-line-length=100 +autopep8 ros_compatiblity/src/ros_compatiblity/*.py --in-place --max-line-length=100 pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ ros_compatiblity/src/ros_compatiblity From 94e61eb5e4a124d99dc6fe2781ede60e6a22064a Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 14:11:17 +0200 Subject: [PATCH 243/627] fix typo --- check.sh | 4 ++-- ros_compatibility/src/ros_compatibility/__init__.py | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/check.sh b/check.sh index 6668b504..05b94d85 100755 --- a/check.sh +++ b/check.sh @@ -10,6 +10,6 @@ autopep8 carla_ros_scenario_runner/src/carla_ros_scenario_runner/*.py --in-place autopep8 carla_twist_to_control/src/carla_twist_to_control/*.py --in-place --max-line-length=100 autopep8 carla_spectator_camera/src/carla_spectator_camera/*.py --in-place --max-line-length=100 autopep8 carla_infrastructure/src/carla_infrastructure/*.py --in-place --max-line-length=100 -autopep8 ros_compatiblity/src/ros_compatiblity/*.py --in-place --max-line-length=100 +autopep8 ros_compatibility/src/ros_compatibility/*.py --in-place --max-line-length=100 -pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ ros_compatiblity/src/ros_compatiblity +pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ ros_compatibility/src/ros_compatibility diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py index 5760b616..31f5cd28 100644 --- a/ros_compatibility/src/ros_compatibility/__init__.py +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -1 +1,2 @@ +# pylint: disable=no-name-in-module,import_error from ros_compatibility.ros_compatible_node import * \ No newline at end of file From 911fa7472dd68f35fc096e2ada18f9581380304b Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 14:17:14 +0200 Subject: [PATCH 244/627] Make ros_compatibility pylint compliant --- ros_compatibility/src/ros_compatibility/__init__.py | 2 +- ros_compatibility/src/ros_compatibility/ros_compatible_node.py | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py index 31f5cd28..acb7f1fe 100644 --- a/ros_compatibility/src/ros_compatibility/__init__.py +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -1,2 +1,2 @@ -# pylint: disable=no-name-in-module,import_error +# pylint: disable=no-name-in-module,import-error from ros_compatibility.ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 236a0ec3..8141fa48 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -1,3 +1,4 @@ +# pylint: disable=import-error import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -157,7 +158,7 @@ class ROSInterruptException(ROSInterruptException): class CompatibleNode(Node): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): - super().__init__(node_name, allow_undeclared_parameters=True, + super(CompatibleNode, self).__init__(node_name, allow_undeclared_parameters=True, automatically_declare_parameters_from_overrides=True, **kwargs) if latch: self.qos_profile = QoSProfile( From 8ce5c3f22e4d169fe1de4ae07eba7b75f42ea771 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 14:28:47 +0200 Subject: [PATCH 245/627] Pylint: ignore ros2 imports --- .../src/carla_infrastructure/carla_infrastructure.py | 2 +- .../src/carla_spectator_camera/carla_spectator_camera.py | 2 +- .../src/ros_compatibility/ros_compatible_node.py | 5 ++--- 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 64d0ac7e..9bc89ba5 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -8,7 +8,7 @@ """ base class for spawning infrastructure sensors in ROS """ - +# pylint: disable=import-error from __future__ import print_function import os diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 898fac23..44e815c2 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -10,7 +10,7 @@ The pose of the camera can be changed by publishing to /carla//spectator_position. """ - +# pylint: disable=import-error import sys import math import rospy diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 8141fa48..52d932c7 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -5,7 +5,7 @@ if ROS_VERSION == 1: import rospy - import tf.transformations as trans + import tf.transformations as trans latch_on = True @@ -159,7 +159,7 @@ class ROSInterruptException(ROSInterruptException): class CompatibleNode(Node): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): super(CompatibleNode, self).__init__(node_name, allow_undeclared_parameters=True, - automatically_declare_parameters_from_overrides=True, **kwargs) + automatically_declare_parameters_from_overrides=True, **kwargs) if latch: self.qos_profile = QoSProfile( depth=queue_size, @@ -219,7 +219,6 @@ def shutdown(self): raise NotImplementedError('Make sure you have valid ROS_VERSION env variable.') - def main(): print('This is a ros1 - ros2 compatibility module.', 'It is not meant to be executed, but rather imported') From c0e39c5fe966233a29e21611c2ae47d68d139624 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 14:29:29 +0200 Subject: [PATCH 246/627] Add pyling disable --- .../carla_ackermann_control_node.py | 8 ++++---- .../carla_control_physics.py | 2 +- carla_ad_agent/src/carla_ad_agent/agent.py | 8 ++++---- carla_ad_agent/src/carla_ad_agent/basic_agent.py | 10 +++++----- .../src/carla_ad_agent/carla_ad_agent.py | 8 ++++---- .../src/carla_ad_agent/local_planner.py | 6 +++--- .../src/carla_ad_agent/vehicle_pid_controller.py | 8 ++++---- carla_common/src/carla_common/transforms.py | 2 +- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 10 +++++----- carla_ros_bridge/src/carla_ros_bridge/actor.py | 6 +++--- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 8 ++++---- carla_ros_bridge/src/carla_ros_bridge/camera.py | 4 ++-- .../carla_ros_bridge/carla_status_publisher.py | 4 ++-- .../src/carla_ros_bridge/collision_sensor.py | 2 +- .../src/carla_ros_bridge/communication.py | 8 ++++---- .../src/carla_ros_bridge/debug_helper.py | 6 +++--- .../src/carla_ros_bridge/ego_vehicle.py | 10 +++++----- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 +- .../src/carla_ros_bridge/lane_invasion_sensor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 4 ++-- .../src/carla_ros_bridge/object_sensor.py | 2 +- .../src/carla_ros_bridge/pseudo_actor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/radar.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/traffic.py | 2 +- .../carla_ros_bridge/traffic_lights_sensor.py | 2 +- .../src/carla_ros_bridge/traffic_participant.py | 6 +++--- carla_ros_bridge/src/carla_ros_bridge/vehicle.py | 4 ++-- carla_ros_bridge/src/carla_ros_bridge/walker.py | 4 ++-- .../src/carla_ros_bridge/world_info.py | 2 +- .../application_runner.py | 2 +- .../carla_ros_scenario_runner.py | 12 ++++++------ .../ros_vehicle_control.py | 12 ++++++------ .../carla_twist_to_control.py | 8 ++++---- .../carla_waypoint_publisher.py | 16 ++++++++-------- .../src/rqt_carla_control/rqt_carla_control.py | 8 ++++---- 36 files changed, 102 insertions(+), 102 deletions(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index b3722618..74d39963 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -12,12 +12,12 @@ import sys import datetime import numpy -import rospy +import rospy # pylint: disable=import-error -from simple_pid import PID +from simple_pid import PID # pylint: disable=import-error -from dynamic_reconfigure.server import Server -from ackermann_msgs.msg import AckermannDrive +from dynamic_reconfigure.server import Server # pylint: disable=import-error +from ackermann_msgs.msg import AckermannDrive # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module,import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=no-name-in-module,import-error from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module,import-error diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py b/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py index a18b95cf..5d0b8e0b 100644 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py @@ -11,7 +11,7 @@ import math -from tf.transformations import euler_from_quaternion +from tf.transformations import euler_from_quaternion # pylint: disable=import-error def get_vehicle_lay_off_engine_acceleration(vehicle_info): diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 531898ae..a9904f7e 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -11,12 +11,12 @@ from enum import Enum import math -import rospy -from tf.transformations import euler_from_quaternion +import rospy # pylint: disable=import-error +from tf.transformations import euler_from_quaternion # pylint: disable=import-error from misc import is_within_distance_ahead, compute_magnitude_angle from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus,\ - CarlaTrafficLightStatusList, CarlaWorldInfo -from carla_waypoint_types.srv import GetWaypoint + CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error +from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error class AgentState(Enum): diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 811ee007..688da1b3 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -11,11 +11,11 @@ """ import math -import rospy -from nav_msgs.msg import Odometry -from geometry_msgs.msg import Pose -from derived_object_msgs.msg import ObjectArray -from carla_msgs.msg import CarlaActorList +import rospy # pylint: disable=import-error +from nav_msgs.msg import Odometry # pylint: disable=import-error +from geometry_msgs.msg import Pose # pylint: disable=import-error +from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error +from carla_msgs.msg import CarlaActorList # pylint: disable=import-error from agent import Agent, AgentState from local_planner import LocalPlanner from carla_waypoint_types.srv import GetActorWaypoint diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 61461c3d..d7612fa3 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -9,10 +9,10 @@ A basic AD agent using CARLA waypoints """ import sys -import rospy -from nav_msgs.msg import Path -from std_msgs.msg import Float64 -from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl +import rospy # pylint: disable=import-error +from nav_msgs.msg import Path # pylint: disable=import-error +from std_msgs.msg import Float64 # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl # pylint: disable=import-error from basic_agent import BasicAgent diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 8603d731..2865c679 100644 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -11,9 +11,9 @@ """ from collections import deque -import rospy -from geometry_msgs.msg import PointStamped -from carla_msgs.msg import CarlaEgoVehicleControl +import rospy # pylint: disable=import-error +from geometry_msgs.msg import PointStamped # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error from vehicle_pid_controller import VehiclePIDController from misc import distance_vehicle diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index 6d19936d..5c1d9da6 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -11,10 +11,10 @@ from collections import deque import math import numpy as np -import rospy -from tf.transformations import euler_from_quaternion -from geometry_msgs.msg import Point -from carla_msgs.msg import CarlaEgoVehicleControl +import rospy # pylint: disable=import-error +from tf.transformations import euler_from_quaternion # pylint: disable=import-error +from geometry_msgs.msg import Point # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error class VehiclePIDController(object): # pylint: disable=too-few-public-methods diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index d15230db..3d6a15c1 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -14,7 +14,7 @@ import math import numpy -from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel +from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel # pylint: disable=import-error import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index b2716ae6..2f39c527 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -18,8 +18,8 @@ """ import sys import carla -from carla_msgs.msg import CarlaStatus, CarlaWorldInfo -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose +from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error +from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler import json import math @@ -30,11 +30,11 @@ ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: - import rospy + import rospy # pylint: disable=import-error elif ROS_VERSION == 2: - import rclpy - from ament_index_python.packages import get_package_share_directory + import rclpy # pylint: disable=import-error + from ament_index_python.packages import get_package_share_directory # pylint: disable=import-error secure_random = random.SystemRandom() diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index f5ee390e..78348dfd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -13,9 +13,9 @@ import carla_common.transforms as trans import numpy as np from carla_ros_bridge.pseudo_actor import PseudoActor -from geometry_msgs.msg import TransformStamped -from std_msgs.msg import ColorRGBA -from visualization_msgs.msg import Marker +from geometry_msgs.msg import TransformStamped # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error +from visualization_msgs.msg import Marker # pylint: disable=import-error class Actor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 205a4c1b..9fffcb13 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -46,17 +46,17 @@ from carla_ros_bridge.walker import Walker from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor -from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters +from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters # pylint: disable=import-error import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy + import rospy # pylint: disable=import-error elif ROS_VERSION == 2: - import rclpy - from rclpy.callback_groups import ReentrantCallbackGroup + import rclpy # pylint: disable=import-error + from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 427a8a74..637a8dca 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -17,8 +17,8 @@ import carla_common.transforms as trans import numpy from carla_ros_bridge.sensor import Sensor -from cv_bridge import CvBridge -from sensor_msgs.msg import CameraInfo +from cv_bridge import CvBridge # pylint: disable=import-error +from sensor_msgs.msg import CameraInfo # pylint: disable=import-error from ros_compatibility import quaternion_from_matrix, quaternion_multiply diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index bc009adb..eac17e34 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -11,7 +11,7 @@ """ import os -from carla_msgs.msg import CarlaStatus +from carla_msgs.msg import CarlaStatus # pylint: disable=import-error from ros_compatibility import * @@ -21,7 +21,7 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup + from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error class CarlaStatusPublisher(CompatibleNode): diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index eb60477a..3077f12a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -10,7 +10,7 @@ Classes to handle collision events """ -from carla_msgs.msg import CarlaCollisionEvent +from carla_msgs.msg import CarlaCollisionEvent # pylint: disable=import-error from carla_ros_bridge.sensor import Sensor diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index cd59999b..ced564e9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -11,8 +11,8 @@ """ import os -from rosgraph_msgs.msg import Clock -from tf2_msgs.msg import TFMessage +from rosgraph_msgs.msg import Clock # pylint: disable=import-error +from tf2_msgs.msg import TFMessage # pylint: disable=import-error from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile, latch_on @@ -22,8 +22,8 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup - from builtin_interfaces.msg import Time + from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error + from builtin_interfaces.msg import Time # pylint: disable=import-error class Communication(CompatibleNode): diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index fae91b27..1921ff4d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -12,16 +12,16 @@ import os import carla -from visualization_msgs.msg import Marker, MarkerArray +from visualization_msgs.msg import Marker, MarkerArray # pylint: disable=import-error from ros_compatibility import * ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from tf.transformations import euler_from_quaternion + from tf.transformations import euler_from_quaternion # pylint: disable=import-error elif ROS_VERSION == 2: - from transformations.transformations import euler_from_quaternion + from transformations.transformations import euler_from_quaternion # pylint: disable=import-error else: raise NotImplementedError( 'Make sure you have valid ' + 'ROS_VERSION env variable') diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 7f9a8633..14a1c3ef 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -16,11 +16,11 @@ from carla import Vector3D from carla import VehicleControl from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel, \ - CarlaEgoVehicleControl, CarlaEgoVehicleStatus + CarlaEgoVehicleControl, CarlaEgoVehicleStatus # pylint: disable=import-error from carla_ros_bridge.vehicle import Vehicle -from geometry_msgs.msg import Twist, Transform -from std_msgs.msg import Bool -from std_msgs.msg import ColorRGBA +from geometry_msgs.msg import Twist, Transform # pylint: disable=import-error +from std_msgs.msg import Bool # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error from ros_compatibility import * @@ -30,7 +30,7 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup + from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error class EgoVehicle(Vehicle, CompatibleNode): diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index f6acbc13..7a43746f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -11,7 +11,7 @@ """ from carla_ros_bridge.sensor import Sensor -from sensor_msgs.msg import NavSatFix +from sensor_msgs.msg import NavSatFix # pylint: disable=import-error class Gnss(Sensor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index c310887e..95856aec 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -12,7 +12,7 @@ import carla_common.transforms as trans from carla_ros_bridge.sensor import Sensor -from sensor_msgs.msg import Imu +from sensor_msgs.msg import Imu # pylint: disable=import-error from ros_compatibility import quaternion_from_euler diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index d1e4672d..48c8e592 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -10,7 +10,7 @@ Classes to handle lane invasion events """ -from carla_msgs.msg import CarlaLaneInvasionEvent +from carla_msgs.msg import CarlaLaneInvasionEvent # pylint: disable=import-error from carla_ros_bridge.sensor import Sensor diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index a566f840..fed30f54 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -20,14 +20,14 @@ import carla_common.transforms as trans import numpy from carla_ros_bridge.sensor import Sensor -from sensor_msgs.msg import PointCloud2, PointField +from sensor_msgs.msg import PointCloud2, PointField # pylint: disable=import-error from ros_compatibility import quaternion_from_euler, euler_from_quaternion ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from sensor_msgs.point_cloud2 import create_cloud_xyz32 + from sensor_msgs.point_cloud2 import create_cloud_xyz32 # pylint: disable=import-error _DATATYPES = {} _DATATYPES[PointField.FLOAT32] = ('f', 4) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 5ddde373..4942868c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -12,7 +12,7 @@ from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.walker import Walker -from derived_object_msgs.msg import ObjectArray +from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error class ObjectSensor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 99c983be..4d67f27b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -11,7 +11,7 @@ import os -from std_msgs.msg import Header +from std_msgs.msg import Header # pylint: disable=import-error from ros_compatibility import CompatibleNode, ros_timestamp diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 33840b38..421d6ae7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -10,7 +10,7 @@ Classes to handle Carla Radar """ -from carla_msgs.msg import CarlaRadarMeasurement, CarlaRadarDetection +from carla_msgs.msg import CarlaRadarMeasurement, CarlaRadarDetection # pylint: disable=import-error from carla_ros_bridge.sensor import Sensor diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 0f83bfd3..44779eec 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -12,7 +12,7 @@ import carla_common.transforms as trans from carla import TrafficLightState -from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo +from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo # pylint: disable=import-error from carla_ros_bridge.actor import Actor diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index a8c74439..1e1c6f04 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -10,7 +10,7 @@ """ from carla_msgs.msg import CarlaTrafficLightStatusList, \ - CarlaTrafficLightInfoList + CarlaTrafficLightInfoList # pylint: disable=import-error from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.traffic import TrafficLight diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 7dcefb57..62dfaeb5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -11,9 +11,9 @@ """ from carla_ros_bridge.actor import Actor -from derived_object_msgs.msg import Object -from nav_msgs.msg import Odometry -from shape_msgs.msg import SolidPrimitive +from derived_object_msgs.msg import Object # pylint: disable=import-error +from nav_msgs.msg import Odometry # pylint: disable=import-error +from shape_msgs.msg import SolidPrimitive # pylint: disable=import-error class TrafficParticipant(Actor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 25b9c8fd..9025bcd9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -11,8 +11,8 @@ """ from carla_ros_bridge.traffic_participant import TrafficParticipant -from derived_object_msgs.msg import Object -from std_msgs.msg import ColorRGBA +from derived_object_msgs.msg import Object # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error class Vehicle(TrafficParticipant): diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index f54a6098..20f276e1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -10,9 +10,9 @@ Classes to handle Carla pedestrians """ -from derived_object_msgs.msg import Object +from derived_object_msgs.msg import Object # pylint: disable=import-error from carla import WalkerControl -from carla_msgs.msg import CarlaWalkerControl +from carla_msgs.msg import CarlaWalkerControl # pylint: disable=import-error from carla_ros_bridge.traffic_participant import TrafficParticipant from ros_compatibility import destroy_subscription diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index 0e2ecd39..792fe09c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -10,7 +10,7 @@ Class to handle the carla map """ -from carla_msgs.msg import CarlaWorldInfo +from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error from carla_ros_bridge.pseudo_actor import PseudoActor diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py index dcff47b1..8d2eef64 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -9,7 +9,7 @@ from enum import Enum from threading import Thread, Event from datetime import datetime, timedelta -import pexpect +import pexpect # pylint: disable=import-error class ApplicationStatus(Enum): diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py index af4d5c63..29a702dd 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -16,12 +16,12 @@ import queue except ImportError: import Queue as queue -import rospy -from geometry_msgs.msg import PoseStamped -from nav_msgs.msg import Path -from std_msgs.msg import Float64 -from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse -from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus +import rospy # pylint: disable=import-error +from geometry_msgs.msg import PoseStamped # pylint: disable=import-error +from nav_msgs.msg import Path # pylint: disable=import-error +from std_msgs.msg import Float64 # pylint: disable=import-error +from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse # pylint: disable=import-error +from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus # pylint: disable=import-error from application_runner import ApplicationStatus from scenario_runner_runner import ScenarioRunnerRunner diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index b98f2a24..1c5351b1 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -5,13 +5,13 @@ # This work is licensed under the terms of the MIT license. # For a copy, see . -import rospy -import roslaunch -from std_msgs.msg import Float64 -from geometry_msgs.msg import PoseStamped -from nav_msgs.msg import Path +import rospy # pylint: disable=import-error +import roslaunch # pylint: disable=import-error +from std_msgs.msg import Float64 # pylint: disable=import-error +from geometry_msgs.msg import PoseStamped # pylint: disable=import-error +from nav_msgs.msg import Path # pylint: disable=import-error import carla_common.transforms as trans -from srunner.scenariomanager.actorcontrols.basic_control import BasicControl +from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error class RosVehicleControl(BasicControl): diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index f0f2314b..7e79929b 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -11,16 +11,16 @@ """ from ros_compatibility import CompatibleNode, ros_ok, ROSException, ROSInterruptException import sys -from geometry_msgs.msg import Twist -from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo +from geometry_msgs.msg import Twist # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo # pylint: disable=import-error import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy + import rospy # pylint: disable=import-error elif ROS_VERSION == 2: - import rclpy + import rclpy # pylint: disable=import-error class TwistToVehicleControl(CompatibleNode): # pylint: disable=too-few-public-methods diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 6e7276d0..1f228eba 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -21,14 +21,14 @@ import sys import threading -import rospy -import tf -from tf.transformations import euler_from_quaternion -from nav_msgs.msg import Path -from geometry_msgs.msg import PoseStamped -from carla_msgs.msg import CarlaWorldInfo -from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint -from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint +import rospy # pylint: disable=import-error +import tf # pylint: disable=import-error +from tf.transformations import euler_from_quaternion # pylint: disable=import-error +from nav_msgs.msg import Path # pylint: disable=import-error +from geometry_msgs.msg import PoseStamped # pylint: disable=import-error +from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error +from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint # pylint: disable=import-error +from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint # pylint: disable=import-error import carla diff --git a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py index 2c0afb42..83e5ea4b 100644 --- a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py +++ b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py @@ -9,15 +9,15 @@ RQT Plugin to control CARLA """ import os -import rospy +import rospy # pylint: disable=import-error import rospkg -from qt_gui.plugin import Plugin -from python_qt_binding import loadUi +from qt_gui.plugin import Plugin # pylint: disable=import-error +from python_qt_binding import loadUi # pylint: disable=import-error from python_qt_binding.QtWidgets import QWidget # pylint: disable=no-name-in-module, import-error from python_qt_binding.QtGui import QPixmap, QIcon # pylint: disable=no-name-in-module, import-error -from carla_msgs.msg import CarlaControl, CarlaStatus +from carla_msgs.msg import CarlaControl, CarlaStatus # pylint: disable=import-error class CarlaControlPlugin(Plugin): From 3d5e18a0b0b574cbd9891d35199515cb5b48d739 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 14:39:05 +0200 Subject: [PATCH 247/627] Split up multiple imports for pylint disable; Run autopep8 --- .../carla_ackermann_control_node.py | 8 ++++---- .../carla_control_physics.py | 2 +- carla_ad_agent/src/carla_ad_agent/agent.py | 10 +++++----- carla_ad_agent/src/carla_ad_agent/basic_agent.py | 12 ++++++------ .../src/carla_ad_agent/carla_ad_agent.py | 8 ++++---- .../src/carla_ad_agent/local_planner.py | 6 +++--- .../src/carla_ad_agent/vehicle_pid_controller.py | 8 ++++---- carla_common/src/carla_common/transforms.py | 2 +- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 10 +++++----- carla_ros_bridge/src/carla_ros_bridge/actor.py | 6 +++--- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 8 ++++---- carla_ros_bridge/src/carla_ros_bridge/camera.py | 4 ++-- .../carla_ros_bridge/carla_status_publisher.py | 4 ++-- .../src/carla_ros_bridge/collision_sensor.py | 2 +- .../src/carla_ros_bridge/communication.py | 8 ++++---- .../src/carla_ros_bridge/debug_helper.py | 6 +++--- .../src/carla_ros_bridge/ego_vehicle.py | 12 ++++++------ carla_ros_bridge/src/carla_ros_bridge/gnss.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 +- .../src/carla_ros_bridge/lane_invasion_sensor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 4 ++-- .../src/carla_ros_bridge/object_sensor.py | 2 +- .../src/carla_ros_bridge/pseudo_actor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/radar.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/traffic.py | 2 +- .../carla_ros_bridge/traffic_lights_sensor.py | 4 ++-- .../src/carla_ros_bridge/traffic_participant.py | 6 +++--- carla_ros_bridge/src/carla_ros_bridge/vehicle.py | 4 ++-- carla_ros_bridge/src/carla_ros_bridge/walker.py | 4 ++-- .../src/carla_ros_bridge/world_info.py | 2 +- .../application_runner.py | 2 +- .../carla_ros_scenario_runner.py | 12 ++++++------ .../ros_vehicle_control.py | 12 ++++++------ .../carla_twist_to_control.py | 8 ++++---- .../carla_waypoint_publisher.py | 16 ++++++++-------- .../src/rqt_carla_control/rqt_carla_control.py | 8 ++++---- 36 files changed, 106 insertions(+), 106 deletions(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index 74d39963..36cc5111 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -12,12 +12,12 @@ import sys import datetime import numpy -import rospy # pylint: disable=import-error +import rospy # pylint: disable=import-error -from simple_pid import PID # pylint: disable=import-error +from simple_pid import PID # pylint: disable=import-error -from dynamic_reconfigure.server import Server # pylint: disable=import-error -from ackermann_msgs.msg import AckermannDrive # pylint: disable=import-error +from dynamic_reconfigure.server import Server # pylint: disable=import-error +from ackermann_msgs.msg import AckermannDrive # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module,import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=no-name-in-module,import-error from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module,import-error diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py b/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py index 5d0b8e0b..ad4a80e9 100644 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py @@ -11,7 +11,7 @@ import math -from tf.transformations import euler_from_quaternion # pylint: disable=import-error +from tf.transformations import euler_from_quaternion # pylint: disable=import-error def get_vehicle_lay_off_engine_acceleration(vehicle_info): diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index a9904f7e..68e22280 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -11,12 +11,12 @@ from enum import Enum import math -import rospy # pylint: disable=import-error -from tf.transformations import euler_from_quaternion # pylint: disable=import-error +import rospy # pylint: disable=import-error +from tf.transformations import euler_from_quaternion # pylint: disable=import-error from misc import is_within_distance_ahead, compute_magnitude_angle -from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus,\ - CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error -from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus # pylint: disable=import-error +from carla_msgs.msg import CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error +from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error class AgentState(Enum): diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 688da1b3..9604bfef 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -11,14 +11,14 @@ """ import math -import rospy # pylint: disable=import-error -from nav_msgs.msg import Odometry # pylint: disable=import-error -from geometry_msgs.msg import Pose # pylint: disable=import-error -from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error -from carla_msgs.msg import CarlaActorList # pylint: disable=import-error +import rospy # pylint: disable=import-error +from nav_msgs.msg import Odometry # pylint: disable=import-error +from geometry_msgs.msg import Pose # pylint: disable=import-error +from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error +from carla_msgs.msg import CarlaActorList # pylint: disable=import-error from agent import Agent, AgentState from local_planner import LocalPlanner -from carla_waypoint_types.srv import GetActorWaypoint +from carla_waypoint_types.srv import GetActorWaypoint # pylint: disable=import-error class BasicAgent(Agent): diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index d7612fa3..fecc18b7 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -9,10 +9,10 @@ A basic AD agent using CARLA waypoints """ import sys -import rospy # pylint: disable=import-error -from nav_msgs.msg import Path # pylint: disable=import-error -from std_msgs.msg import Float64 # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl # pylint: disable=import-error +import rospy # pylint: disable=import-error +from nav_msgs.msg import Path # pylint: disable=import-error +from std_msgs.msg import Float64 # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl # pylint: disable=import-error from basic_agent import BasicAgent diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 2865c679..7e2f0da9 100644 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -11,9 +11,9 @@ """ from collections import deque -import rospy # pylint: disable=import-error -from geometry_msgs.msg import PointStamped # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error +import rospy # pylint: disable=import-error +from geometry_msgs.msg import PointStamped # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error from vehicle_pid_controller import VehiclePIDController from misc import distance_vehicle diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index 5c1d9da6..6ff034c8 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -11,10 +11,10 @@ from collections import deque import math import numpy as np -import rospy # pylint: disable=import-error -from tf.transformations import euler_from_quaternion # pylint: disable=import-error -from geometry_msgs.msg import Point # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error +import rospy # pylint: disable=import-error +from tf.transformations import euler_from_quaternion # pylint: disable=import-error +from geometry_msgs.msg import Point # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error class VehiclePIDController(object): # pylint: disable=too-few-public-methods diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index 3d6a15c1..1d9adaad 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -14,7 +14,7 @@ import math import numpy -from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel # pylint: disable=import-error +from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel # pylint: disable=import-error import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 2f39c527..71b66ecd 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -18,8 +18,8 @@ """ import sys import carla -from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error +from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error +from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler import json import math @@ -30,11 +30,11 @@ ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: - import rospy # pylint: disable=import-error + import rospy # pylint: disable=import-error elif ROS_VERSION == 2: - import rclpy # pylint: disable=import-error - from ament_index_python.packages import get_package_share_directory # pylint: disable=import-error + import rclpy # pylint: disable=import-error + from ament_index_python.packages import get_package_share_directory # pylint: disable=import-error secure_random = random.SystemRandom() diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 78348dfd..ec08a989 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -13,9 +13,9 @@ import carla_common.transforms as trans import numpy as np from carla_ros_bridge.pseudo_actor import PseudoActor -from geometry_msgs.msg import TransformStamped # pylint: disable=import-error -from std_msgs.msg import ColorRGBA # pylint: disable=import-error -from visualization_msgs.msg import Marker # pylint: disable=import-error +from geometry_msgs.msg import TransformStamped # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error +from visualization_msgs.msg import Marker # pylint: disable=import-error class Actor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 9fffcb13..8ca6192c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -46,17 +46,17 @@ from carla_ros_bridge.walker import Walker from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor -from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters # pylint: disable=import-error +from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters # pylint: disable=import-error import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy # pylint: disable=import-error + import rospy # pylint: disable=import-error elif ROS_VERSION == 2: - import rclpy # pylint: disable=import-error - from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error + import rclpy # pylint: disable=import-error + from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 637a8dca..d6756914 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -17,8 +17,8 @@ import carla_common.transforms as trans import numpy from carla_ros_bridge.sensor import Sensor -from cv_bridge import CvBridge # pylint: disable=import-error -from sensor_msgs.msg import CameraInfo # pylint: disable=import-error +from cv_bridge import CvBridge # pylint: disable=import-error +from sensor_msgs.msg import CameraInfo # pylint: disable=import-error from ros_compatibility import quaternion_from_matrix, quaternion_multiply diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index eac17e34..8697fab8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -11,7 +11,7 @@ """ import os -from carla_msgs.msg import CarlaStatus # pylint: disable=import-error +from carla_msgs.msg import CarlaStatus # pylint: disable=import-error from ros_compatibility import * @@ -21,7 +21,7 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error + from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error class CarlaStatusPublisher(CompatibleNode): diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index 3077f12a..bbb9a356 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -10,7 +10,7 @@ Classes to handle collision events """ -from carla_msgs.msg import CarlaCollisionEvent # pylint: disable=import-error +from carla_msgs.msg import CarlaCollisionEvent # pylint: disable=import-error from carla_ros_bridge.sensor import Sensor diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py index ced564e9..7ce9df73 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ b/carla_ros_bridge/src/carla_ros_bridge/communication.py @@ -11,8 +11,8 @@ """ import os -from rosgraph_msgs.msg import Clock # pylint: disable=import-error -from tf2_msgs.msg import TFMessage # pylint: disable=import-error +from rosgraph_msgs.msg import Clock # pylint: disable=import-error +from tf2_msgs.msg import TFMessage # pylint: disable=import-error from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile, latch_on @@ -22,8 +22,8 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error - from builtin_interfaces.msg import Time # pylint: disable=import-error + from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error + from builtin_interfaces.msg import Time # pylint: disable=import-error class Communication(CompatibleNode): diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 1921ff4d..15b3123d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -12,16 +12,16 @@ import os import carla -from visualization_msgs.msg import Marker, MarkerArray # pylint: disable=import-error +from visualization_msgs.msg import Marker, MarkerArray # pylint: disable=import-error from ros_compatibility import * ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from tf.transformations import euler_from_quaternion # pylint: disable=import-error + from tf.transformations import euler_from_quaternion # pylint: disable=import-error elif ROS_VERSION == 2: - from transformations.transformations import euler_from_quaternion # pylint: disable=import-error + from transformations.transformations import euler_from_quaternion # pylint: disable=import-error else: raise NotImplementedError( 'Make sure you have valid ' + 'ROS_VERSION env variable') diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 14a1c3ef..278fe29c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -15,12 +15,12 @@ import numpy from carla import Vector3D from carla import VehicleControl -from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel, \ - CarlaEgoVehicleControl, CarlaEgoVehicleStatus # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleStatus # pylint: disable=import-error from carla_ros_bridge.vehicle import Vehicle -from geometry_msgs.msg import Twist, Transform # pylint: disable=import-error -from std_msgs.msg import Bool # pylint: disable=import-error -from std_msgs.msg import ColorRGBA # pylint: disable=import-error +from geometry_msgs.msg import Twist, Transform # pylint: disable=import-error +from std_msgs.msg import Bool # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error from ros_compatibility import * @@ -30,7 +30,7 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error + from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error class EgoVehicle(Vehicle, CompatibleNode): diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index 7a43746f..b1ec2934 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -11,7 +11,7 @@ """ from carla_ros_bridge.sensor import Sensor -from sensor_msgs.msg import NavSatFix # pylint: disable=import-error +from sensor_msgs.msg import NavSatFix # pylint: disable=import-error class Gnss(Sensor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 95856aec..8b09944c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -12,7 +12,7 @@ import carla_common.transforms as trans from carla_ros_bridge.sensor import Sensor -from sensor_msgs.msg import Imu # pylint: disable=import-error +from sensor_msgs.msg import Imu # pylint: disable=import-error from ros_compatibility import quaternion_from_euler diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 48c8e592..318c42b0 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -10,7 +10,7 @@ Classes to handle lane invasion events """ -from carla_msgs.msg import CarlaLaneInvasionEvent # pylint: disable=import-error +from carla_msgs.msg import CarlaLaneInvasionEvent # pylint: disable=import-error from carla_ros_bridge.sensor import Sensor diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index fed30f54..63300c2a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -20,14 +20,14 @@ import carla_common.transforms as trans import numpy from carla_ros_bridge.sensor import Sensor -from sensor_msgs.msg import PointCloud2, PointField # pylint: disable=import-error +from sensor_msgs.msg import PointCloud2, PointField # pylint: disable=import-error from ros_compatibility import quaternion_from_euler, euler_from_quaternion ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from sensor_msgs.point_cloud2 import create_cloud_xyz32 # pylint: disable=import-error + from sensor_msgs.point_cloud2 import create_cloud_xyz32 # pylint: disable=import-error _DATATYPES = {} _DATATYPES[PointField.FLOAT32] = ('f', 4) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 4942868c..b338a7d9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -12,7 +12,7 @@ from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.walker import Walker -from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error +from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error class ObjectSensor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 4d67f27b..bf25d6e3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -11,7 +11,7 @@ import os -from std_msgs.msg import Header # pylint: disable=import-error +from std_msgs.msg import Header # pylint: disable=import-error from ros_compatibility import CompatibleNode, ros_timestamp diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 421d6ae7..3ea673d3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -10,7 +10,7 @@ Classes to handle Carla Radar """ -from carla_msgs.msg import CarlaRadarMeasurement, CarlaRadarDetection # pylint: disable=import-error +from carla_msgs.msg import CarlaRadarMeasurement, CarlaRadarDetection # pylint: disable=import-error from carla_ros_bridge.sensor import Sensor diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 44779eec..77b4e66e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -12,7 +12,7 @@ import carla_common.transforms as trans from carla import TrafficLightState -from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo # pylint: disable=import-error +from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo # pylint: disable=import-error from carla_ros_bridge.actor import Actor diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 1e1c6f04..f1359261 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -9,8 +9,8 @@ a sensor that reports the state of all traffic lights """ -from carla_msgs.msg import CarlaTrafficLightStatusList, \ - CarlaTrafficLightInfoList # pylint: disable=import-error +from carla_msgs.msg import CarlaTrafficLightStatusList # pylint: disable=import-error +from carla_msgs.msg import CarlaTrafficLightInfoList # pylint: disable=import-error from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.traffic import TrafficLight diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 62dfaeb5..51d7941f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -11,9 +11,9 @@ """ from carla_ros_bridge.actor import Actor -from derived_object_msgs.msg import Object # pylint: disable=import-error -from nav_msgs.msg import Odometry # pylint: disable=import-error -from shape_msgs.msg import SolidPrimitive # pylint: disable=import-error +from derived_object_msgs.msg import Object # pylint: disable=import-error +from nav_msgs.msg import Odometry # pylint: disable=import-error +from shape_msgs.msg import SolidPrimitive # pylint: disable=import-error class TrafficParticipant(Actor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 9025bcd9..d564c050 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -11,8 +11,8 @@ """ from carla_ros_bridge.traffic_participant import TrafficParticipant -from derived_object_msgs.msg import Object # pylint: disable=import-error -from std_msgs.msg import ColorRGBA # pylint: disable=import-error +from derived_object_msgs.msg import Object # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error class Vehicle(TrafficParticipant): diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index 20f276e1..d389e0d6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -10,9 +10,9 @@ Classes to handle Carla pedestrians """ -from derived_object_msgs.msg import Object # pylint: disable=import-error +from derived_object_msgs.msg import Object # pylint: disable=import-error from carla import WalkerControl -from carla_msgs.msg import CarlaWalkerControl # pylint: disable=import-error +from carla_msgs.msg import CarlaWalkerControl # pylint: disable=import-error from carla_ros_bridge.traffic_participant import TrafficParticipant from ros_compatibility import destroy_subscription diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index 792fe09c..84b1ce49 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -10,7 +10,7 @@ Class to handle the carla map """ -from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error +from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error from carla_ros_bridge.pseudo_actor import PseudoActor diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py index 8d2eef64..8a72617b 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -9,7 +9,7 @@ from enum import Enum from threading import Thread, Event from datetime import datetime, timedelta -import pexpect # pylint: disable=import-error +import pexpect # pylint: disable=import-error class ApplicationStatus(Enum): diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py index 29a702dd..25d07046 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -16,12 +16,12 @@ import queue except ImportError: import Queue as queue -import rospy # pylint: disable=import-error -from geometry_msgs.msg import PoseStamped # pylint: disable=import-error -from nav_msgs.msg import Path # pylint: disable=import-error -from std_msgs.msg import Float64 # pylint: disable=import-error -from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse # pylint: disable=import-error -from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus # pylint: disable=import-error +import rospy # pylint: disable=import-error +from geometry_msgs.msg import PoseStamped # pylint: disable=import-error +from nav_msgs.msg import Path # pylint: disable=import-error +from std_msgs.msg import Float64 # pylint: disable=import-error +from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse # pylint: disable=import-error +from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus # pylint: disable=import-error from application_runner import ApplicationStatus from scenario_runner_runner import ScenarioRunnerRunner diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 1c5351b1..6761371a 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -5,13 +5,13 @@ # This work is licensed under the terms of the MIT license. # For a copy, see . -import rospy # pylint: disable=import-error -import roslaunch # pylint: disable=import-error -from std_msgs.msg import Float64 # pylint: disable=import-error -from geometry_msgs.msg import PoseStamped # pylint: disable=import-error -from nav_msgs.msg import Path # pylint: disable=import-error +import rospy # pylint: disable=import-error +import roslaunch # pylint: disable=import-error +from std_msgs.msg import Float64 # pylint: disable=import-error +from geometry_msgs.msg import PoseStamped # pylint: disable=import-error +from nav_msgs.msg import Path # pylint: disable=import-error import carla_common.transforms as trans -from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error +from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error class RosVehicleControl(BasicControl): diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index 7e79929b..cebd2260 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -11,16 +11,16 @@ """ from ros_compatibility import CompatibleNode, ros_ok, ROSException, ROSInterruptException import sys -from geometry_msgs.msg import Twist # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo # pylint: disable=import-error +from geometry_msgs.msg import Twist # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo # pylint: disable=import-error import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - import rospy # pylint: disable=import-error + import rospy # pylint: disable=import-error elif ROS_VERSION == 2: - import rclpy # pylint: disable=import-error + import rclpy # pylint: disable=import-error class TwistToVehicleControl(CompatibleNode): # pylint: disable=too-few-public-methods diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 1f228eba..bd966e8a 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -21,14 +21,14 @@ import sys import threading -import rospy # pylint: disable=import-error -import tf # pylint: disable=import-error -from tf.transformations import euler_from_quaternion # pylint: disable=import-error -from nav_msgs.msg import Path # pylint: disable=import-error -from geometry_msgs.msg import PoseStamped # pylint: disable=import-error -from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error -from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint # pylint: disable=import-error -from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint # pylint: disable=import-error +import rospy # pylint: disable=import-error +import tf # pylint: disable=import-error +from tf.transformations import euler_from_quaternion # pylint: disable=import-error +from nav_msgs.msg import Path # pylint: disable=import-error +from geometry_msgs.msg import PoseStamped # pylint: disable=import-error +from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error +from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint # pylint: disable=import-error +from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint # pylint: disable=import-error import carla diff --git a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py index 83e5ea4b..59e9a799 100644 --- a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py +++ b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py @@ -9,15 +9,15 @@ RQT Plugin to control CARLA """ import os -import rospy # pylint: disable=import-error +import rospy # pylint: disable=import-error import rospkg -from qt_gui.plugin import Plugin # pylint: disable=import-error -from python_qt_binding import loadUi # pylint: disable=import-error +from qt_gui.plugin import Plugin # pylint: disable=import-error +from python_qt_binding import loadUi # pylint: disable=import-error from python_qt_binding.QtWidgets import QWidget # pylint: disable=no-name-in-module, import-error from python_qt_binding.QtGui import QPixmap, QIcon # pylint: disable=no-name-in-module, import-error -from carla_msgs.msg import CarlaControl, CarlaStatus # pylint: disable=import-error +from carla_msgs.msg import CarlaControl, CarlaStatus # pylint: disable=import-error class CarlaControlPlugin(Plugin): From 5f64f1563f58fb9aa9b07f74adf7f76a848f8ef4 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 14:58:31 +0200 Subject: [PATCH 248/627] Remove wildcard import from ros_compatibility; Add missing import --- carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/debug_helper.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 1 + 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 8697fab8..aad96b77 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -13,7 +13,7 @@ from carla_msgs.msg import CarlaStatus # pylint: disable=import-error -from ros_compatibility import * +from ros_compatibility import CompatibleNode ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 15b3123d..99cc6bb1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -14,7 +14,7 @@ import carla from visualization_msgs.msg import Marker, MarkerArray # pylint: disable=import-error -from ros_compatibility import * +from ros_compatibility import CompatibleNode ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 278fe29c..5bc21cd3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -10,6 +10,7 @@ Classes to handle Carla vehicles """ import math +import os import carla_common.transforms as transforms import numpy From 99bef977574a598a3f85279c4cc6c7510b909151 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 15:02:26 +0200 Subject: [PATCH 249/627] Reorder imports --- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 71b66ecd..ed20698c 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -17,16 +17,17 @@ /initialpose might be published via RVIZ '2D Pose Estimate" button. """ import sys -import carla -from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error -from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler import json import math import os import random from abc import abstractmethod +import carla +from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error +from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error +from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler + ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: From 61ce6e07737588670eb446278c817b2421466a39 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 15:37:25 +0200 Subject: [PATCH 250/627] Reorder imports --- carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 51d7941f..f5ab96e6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -10,11 +10,12 @@ Classes to handle Carla traffic participants """ -from carla_ros_bridge.actor import Actor from derived_object_msgs.msg import Object # pylint: disable=import-error from nav_msgs.msg import Odometry # pylint: disable=import-error from shape_msgs.msg import SolidPrimitive # pylint: disable=import-error +from carla_ros_bridge.actor import Actor + class TrafficParticipant(Actor): """ From 2d8439b1d975b4e2a420cf67c7025911a5951c90 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 15:40:09 +0200 Subject: [PATCH 251/627] Remove comment --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index d6756914..e369fe02 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -69,8 +69,7 @@ def _build_camera_info(self): camera info doesn't change over time """ camera_info = CameraInfo() - # store info without header - # camera_info.header = None # TODO uncomment for ros 1 (?) + camera_info.width = int(self.carla_actor.attributes['image_size_x']) camera_info.height = int(self.carla_actor.attributes['image_size_y']) camera_info.distortion_model = 'plumb_bob' From b12514b45e7f0e9c739a47deccb5bb0c033d7f81 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 15:41:22 +0200 Subject: [PATCH 252/627] Reorder imports --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index e369fe02..b44525a4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -12,13 +12,13 @@ import math import os from abc import abstractmethod +import numpy +from cv_bridge import CvBridge # pylint: disable=import-error +from sensor_msgs.msg import CameraInfo # pylint: disable=import-error import carla import carla_common.transforms as trans -import numpy from carla_ros_bridge.sensor import Sensor -from cv_bridge import CvBridge # pylint: disable=import-error -from sensor_msgs.msg import CameraInfo # pylint: disable=import-error from ros_compatibility import quaternion_from_matrix, quaternion_multiply From 98f048d53cfa3b57eda90656ccaa435f0a3f5628 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 15:44:53 +0200 Subject: [PATCH 253/627] Move pylint disable before init due to issues with linebreaks --- carla_ros_bridge/src/carla_ros_bridge/camera.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index b44525a4..49e7e078 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -33,8 +33,9 @@ class Camera(Sensor): # global cv bridge to convert image between opencv and ros cv_bridge = CvBridge() + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix=None, - sensor_name="Camera"): # pylint: disable=too-many-arguments + sensor_name="Camera"): """ Constructor @@ -175,6 +176,7 @@ class RgbCamera(Camera): Camera implementation details for rgb camera """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="RGBCamera"): """ @@ -228,6 +230,7 @@ class DepthCamera(Camera): Camera implementation details for depth camera """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="DepthCamera"): """ @@ -303,6 +306,7 @@ class SemanticSegmentationCamera(Camera): Camera implementation details for segmentation camera """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="SemanticSegmentationCamera"): """ From 8075b24adc0b1a3c665fcb7ecf8c5b9b2ba883f9 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 15:46:14 +0200 Subject: [PATCH 254/627] Reorder imports --- carla_ros_bridge/src/carla_ros_bridge/debug_helper.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 99cc6bb1..f552a719 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -11,9 +11,10 @@ import math import os -import carla from visualization_msgs.msg import Marker, MarkerArray # pylint: disable=import-error +import carla + from ros_compatibility import CompatibleNode ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) From 492bdbc81fa9ce5a0f909c8481c43105e989d1f1 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 15:48:14 +0200 Subject: [PATCH 255/627] Pylint whims --- .../carla_ackermann_control_node.py | 4 ++-- carla_common/src/carla_common/transforms.py | 4 ++-- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 12 ++++-------- carla_ros_bridge/src/carla_ros_bridge/actor.py | 6 +++--- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 10 +++++++--- .../src/carla_ros_bridge/collision_sensor.py | 1 + .../src/carla_ros_bridge/debug_helper.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 12 ++++++------ carla_ros_bridge/src/carla_ros_bridge/imu.py | 3 ++- .../src/carla_ros_bridge/object_sensor.py | 2 +- .../src/carla_ros_bridge/pseudo_actor.py | 6 ++---- carla_ros_bridge/src/carla_ros_bridge/radar.py | 1 + carla_ros_bridge/src/carla_ros_bridge/sensor.py | 1 + 13 files changed, 33 insertions(+), 31 deletions(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index 36cc5111..d56d6826 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -14,8 +14,6 @@ import numpy import rospy # pylint: disable=import-error -from simple_pid import PID # pylint: disable=import-error - from dynamic_reconfigure.server import Server # pylint: disable=import-error from ackermann_msgs.msg import AckermannDrive # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module,import-error @@ -25,6 +23,8 @@ from carla_ackermann_control.cfg import EgoVehicleControlParameterConfig # pylint: disable=no-name-in-module,import-error import carla_control_physics as phys # pylint: disable=relative-import +from simple_pid import PID # pylint: disable=import-error + class CarlaAckermannControl(object): diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index 1d9adaad..83561d20 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -10,13 +10,13 @@ Tool functions to convert transforms from carla to ROS coordinate system """ -from ros_compatibility import euler_matrix, quaternion_from_euler +import os import math import numpy from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel # pylint: disable=import-error +from ros_compatibility import euler_matrix, quaternion_from_euler -import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index ed20698c..e5900edb 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -17,17 +17,16 @@ /initialpose might be published via RVIZ '2D Pose Estimate" button. """ import sys +import carla +from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error +from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error +from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler import json import math import os import random from abc import abstractmethod -import carla -from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error -from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler - ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: @@ -40,9 +39,6 @@ secure_random = random.SystemRandom() - -# TODO: Add launch files. - # ============================================================================== # -- CarlaEgoVehicle ------------------------------------------------------------ # ============================================================================== diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index ec08a989..63330af6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -10,12 +10,12 @@ Base Classes to handle Actor objects """ -import carla_common.transforms as trans import numpy as np -from carla_ros_bridge.pseudo_actor import PseudoActor from geometry_msgs.msg import TransformStamped # pylint: disable=import-error -from std_msgs.msg import ColorRGBA # pylint: disable=import-error from visualization_msgs.msg import Marker # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error +from carla_ros_bridge.pseudo_actor import PseudoActor +import carla_common.transforms as trans class Actor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 8ca6192c..3291704b 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -11,18 +11,19 @@ Class that handle communication between CARLA and ROS """ -from ros_compatibility import CompatibleNode, ros_ok, destroy_subscription try: import queue except ImportError: import Queue as queue +import os import sys from distutils.version import LooseVersion from threading import Thread, Lock, Event import pkg_resources +from ros_compatibility import CompatibleNode, ros_ok, destroy_subscription import carla from carla_ros_bridge.actor import Actor @@ -48,7 +49,6 @@ from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters # pylint: disable=import-error -import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -80,7 +80,11 @@ def __init__(self, rospy_init=True, executor=None): super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) self.executor = executor + # pylint: disable=attribute-defined-outside-init def initialize_bridge(self, carla_world, params): + """ + Initialize the bridge + """ self.parameters = params self.actors = {} self.pseudo_actors = [] @@ -558,7 +562,7 @@ def main(): ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) parameters["ego_vehicle"] = {"role_name": role_name} - print(parameters) + print(parameters) # pylint: disable=superfluous-parens carla_bridge.loginfo("Trying to connect to {host}:{port}".format( host=parameters['host'], port=parameters['port'])) diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index bbb9a356..426fbc1f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -18,6 +18,7 @@ class CollisionSensor(Sensor): """ Actor implementation details for a collision sensor """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="CollisionSensor"): diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index f552a719..3203305f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -15,7 +15,7 @@ import carla -from ros_compatibility import CompatibleNode +from ros_compatibility import CompatibleNode, destroy_subscription ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 5bc21cd3..c4fe52ac 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -12,18 +12,18 @@ import math import os -import carla_common.transforms as transforms import numpy +from geometry_msgs.msg import Twist, Transform # pylint: disable=import-error +from std_msgs.msg import Bool # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error +import carla_common.transforms as transforms from carla import Vector3D from carla import VehicleControl from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleStatus # pylint: disable=import-error from carla_ros_bridge.vehicle import Vehicle -from geometry_msgs.msg import Twist, Transform # pylint: disable=import-error -from std_msgs.msg import Bool # pylint: disable=import-error -from std_msgs.msg import ColorRGBA # pylint: disable=import-error -from ros_compatibility import * +from ros_compatibility import CompatibleNode, destroy_subscription ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -125,7 +125,7 @@ def send_vehicle_msgs(self): self.publish_message(self.get_topic_prefix() + "/vehicle_status", vehicle_status) # only send vehicle once (in latched-mode) - # TODO: Make latching work reliably in ROS2 + # TODO: Make latching work reliably in ROS2 # pylint: disable=fixme if not self.vehicle_info_published: self.vehicle_info_published = True vehicle_info = CarlaEgoVehicleInfo() diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 8b09944c..e1582039 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -10,9 +10,9 @@ import math import os +from sensor_msgs.msg import Imu # pylint: disable=import-error import carla_common.transforms as trans from carla_ros_bridge.sensor import Sensor -from sensor_msgs.msg import Imu # pylint: disable=import-error from ros_compatibility import quaternion_from_euler @@ -23,6 +23,7 @@ class ImuSensor(Sensor): """ Actor implementation details for imu sensor """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="IMU"): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index b338a7d9..e7141da4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -9,10 +9,10 @@ handle a object sensor """ +from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.walker import Walker -from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error class ObjectSensor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index bf25d6e3..d78b6b6a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -13,7 +13,7 @@ from std_msgs.msg import Header # pylint: disable=import-error -from ros_compatibility import CompatibleNode, ros_timestamp +from ros_compatibility import ros_timestamp ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -21,7 +21,7 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -class PseudoActor(CompatibleNode): +class PseudoActor(object): """ Generic base class for Pseudo actors (that are not existing in Carla world) """ @@ -37,8 +37,6 @@ def __init__(self, parent, communication, prefix=None): :type communication: carla_ros_bridge.communication """ - # super(PseudoActor, self).__init__("pseudo_actor_node") - self.parent = parent if self.parent: self.parent_id = parent.get_id() diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 3ea673d3..ff7c5c75 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -19,6 +19,7 @@ class Radar(Sensor): """ Actor implementation details of Carla RADAR """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="Radar"): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 3ba182d4..a802882f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -33,6 +33,7 @@ class Sensor(Actor, CompatibleNode): """ Actor implementation details for sensors """ + # pylint: disable=too-many-arguments def __init__( self, # pylint: disable=too-many-arguments From 8d69193261faaff535ffd751d2f44c2e41c5a1ea Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 15:57:16 +0200 Subject: [PATCH 256/627] Pylint whims x2 --- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 3 ++- .../src/carla_ros_bridge/lane_invasion_sensor.py | 1 + carla_ros_bridge/src/carla_ros_bridge/lidar.py | 11 +++++++---- carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py | 5 +++-- carla_ros_bridge/src/carla_ros_bridge/vehicle.py | 2 +- 5 files changed, 14 insertions(+), 8 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index b1ec2934..edca6e1a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -10,8 +10,8 @@ Classes to handle Carla gnsss """ -from carla_ros_bridge.sensor import Sensor from sensor_msgs.msg import NavSatFix # pylint: disable=import-error +from carla_ros_bridge.sensor import Sensor class Gnss(Sensor): @@ -19,6 +19,7 @@ class Gnss(Sensor): Actor implementation details for gnss sensor """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="GNSS"): """ Constructor diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 318c42b0..d30a9710 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -19,6 +19,7 @@ class LaneInvasionSensor(Sensor): Actor implementation details for a lane invasion sensor """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="LaneInvasionSensor"): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 63300c2a..ff7166b1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -16,18 +16,19 @@ import ctypes import os import struct +import numpy +from sensor_msgs.msg import PointCloud2, PointField # pylint: disable=import-error import carla_common.transforms as trans -import numpy from carla_ros_bridge.sensor import Sensor -from sensor_msgs.msg import PointCloud2, PointField # pylint: disable=import-error from ros_compatibility import quaternion_from_euler, euler_from_quaternion ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: - from sensor_msgs.point_cloud2 import create_cloud_xyz32 # pylint: disable=import-error + # pylint: disable=import-error,ungrouped-imports + from sensor_msgs.point_cloud2 import create_cloud_xyz32 _DATATYPES = {} _DATATYPES[PointField.FLOAT32] = ('f', 4) @@ -37,6 +38,7 @@ class Lidar(Sensor): """ Actor implementation details for lidars """ + # pylint: disable=too-many-arguments def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="Lidar"): """ @@ -99,7 +101,8 @@ def sensor_data_updated(self, carla_lidar_measurement): if ROS_VERSION == 1: point_cloud_msg = create_cloud_xyz32(header, lidar_data) - # -- taken from http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html + # -- taken from + # http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html elif ROS_VERSION == 2: point_field_x_msg = PointField() point_field_x_msg.name = "x" diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index d78b6b6a..c33c3883 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -13,7 +13,7 @@ from std_msgs.msg import Header # pylint: disable=import-error -from ros_compatibility import ros_timestamp +from ros_compatibility import CompatibleNode, ros_timestamp ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -21,11 +21,12 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -class PseudoActor(object): +class PseudoActor(CompatibleNode): """ Generic base class for Pseudo actors (that are not existing in Carla world) """ + # pylint: disable=super-init-not-called def __init__(self, parent, communication, prefix=None): """ Constructor diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index d564c050..67b27822 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -10,9 +10,9 @@ Classes to handle Carla vehicles """ -from carla_ros_bridge.traffic_participant import TrafficParticipant from derived_object_msgs.msg import Object # pylint: disable=import-error from std_msgs.msg import ColorRGBA # pylint: disable=import-error +from carla_ros_bridge.traffic_participant import TrafficParticipant class Vehicle(TrafficParticipant): From cbfbcb792a38d6773060dcae962e7e1a80d5098a Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 16:04:57 +0200 Subject: [PATCH 257/627] Add docstring to a helper method --- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index e5900edb..2f8305f8 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -107,6 +107,9 @@ def __init__(self): self.loginfo("using vehicle filter: {}".format(self.actor_filter)) def spawn_ego_vehicle(self): + """ + Helper method for condition-checking in self.restart(). + """ if ROS_VERSION == 1: return self.get_param('~spawn_ego_vehicle') elif ROS_VERSION == 2: @@ -401,7 +404,8 @@ def run(self): def run_ego_vehicle(msg): """ Callback function: - Called when bridge started - indicated by published /carla/status topic and runs CarlaEgoVehicle afterwards + Called when bridge started - indicated by published /carla/status topic + and runs CarlaEgoVehicle afterwards """ ego_vehicle = CarlaEgoVehicle() try: From 528c1d7d96d43a9e1dc87d18f424ef1bd5191a1b Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 16:07:05 +0200 Subject: [PATCH 258/627] Reorder imports --- .../src/carla_ackermann_control/carla_ackermann_control_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index d56d6826..24b5a071 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -23,7 +23,7 @@ from carla_ackermann_control.cfg import EgoVehicleControlParameterConfig # pylint: disable=no-name-in-module,import-error import carla_control_physics as phys # pylint: disable=relative-import -from simple_pid import PID # pylint: disable=import-error +from simple_pid import PID # pylint: disable=import-error,wrong-import-order class CarlaAckermannControl(object): From 811b8a8dcbbed5417dd3da2cdf55aff86d60ca43 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 16:22:12 +0200 Subject: [PATCH 259/627] Pylint whims --- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 2f8305f8..ff5b30cc 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -17,16 +17,18 @@ /initialpose might be published via RVIZ '2D Pose Estimate" button. """ import sys -import carla -from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error -from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler import json import math import os import random from abc import abstractmethod +from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error +from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error +from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler + +import carla + ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: @@ -106,6 +108,7 @@ def __init__(self): self.loginfo("listening to server {}:{}".format(self.host, self.port)) self.loginfo("using vehicle filter: {}".format(self.actor_filter)) + # pylint: disable=inconsistent-return-statements def spawn_ego_vehicle(self): """ Helper method for condition-checking in self.restart(). @@ -397,11 +400,11 @@ def run(self): self.loginfo("Ego spawned.") try: self.spin() - except: + except Exception: # pylint: disable=broad-except self.shutdown() -def run_ego_vehicle(msg): +def run_ego_vehicle(msg): # pylint: disable=unused-argument """ Callback function: Called when bridge started - indicated by published /carla/status topic From c4b02b36699ca103ae7512e157ac49807e8347a8 Mon Sep 17 00:00:00 2001 From: Arkadiy Telegin Date: Thu, 25 Jun 2020 16:37:26 +0200 Subject: [PATCH 260/627] Fix TravisCI docker instuctions for eloquent --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 3c829a53..cf4b6f79 100644 --- a/.travis.yml +++ b/.travis.yml @@ -55,7 +55,7 @@ jobs: services: docker before_install: skip install: skip - script: docker build -t carla-ros-bridge -f Dockerfile.eloquent ./.. + script: cd docker && docker build -t carla-ros-bridge -f Dockerfile.eloquent ./.. before_install: - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' From 9dfe26afa481a1e70f971e4728d8465ceee81cf0 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Thu, 25 Jun 2020 17:02:06 +0200 Subject: [PATCH 261/627] Do not change directory but change file path --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index cf4b6f79..f4a9eae6 100644 --- a/.travis.yml +++ b/.travis.yml @@ -55,7 +55,7 @@ jobs: services: docker before_install: skip install: skip - script: cd docker && docker build -t carla-ros-bridge -f Dockerfile.eloquent ./.. + script: docker build -t carla-ros-bridge -f docker/Dockerfile.eloquent ./.. before_install: - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' From 898ce0a014a116612e63f163b3f95402a9557f11 Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Mon, 29 Jun 2020 09:19:12 +0200 Subject: [PATCH 262/627] Update doc (#318) * Fix links to carla_msgs * Add documentation --- README.md | 32 ++++++++++++++--------------- carla_ad_agent/README.md | 2 +- carla_ros_scenario_runner/README.md | 16 ++++++++++++++- carla_twist_to_control/README.md | 6 +++--- carla_walker_agent/README.md | 2 +- rviz_carla_plugin/README.md | 6 +++--- 6 files changed, 39 insertions(+), 25 deletions(-) diff --git a/README.md b/README.md index 78639e54..63a73345 100644 --- a/README.md +++ b/README.md @@ -150,7 +150,7 @@ The following topic allows to control the stepping. | Topic | Type | | ---------------- | ---------------------------------------------------------- | -| `/carla/control` | [carla_msgs.CarlaControl](carla_msgs/msg/CarlaControl.msg) | +| `/carla/control` | [carla_msgs.CarlaControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaControl.msg) | A [CARLA Control rqt plugin](rqt_carla_control/README.md) is available to publish to the topic. @@ -181,7 +181,7 @@ Currently the following sensors are supported: | Topic | Type | | --------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | -| `/carla//radar//radar` | [carla_msgs.CarlaRadarMeasurement](carla_msgs/msg/CarlaRadarMeasurement.msg) | +| `/carla//radar//radar` | [carla_msgs.CarlaRadarMeasurement](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaRadarMeasurement.msg) | ##### IMU @@ -199,13 +199,13 @@ Currently the following sensors are supported: | Topic | Type | Description | | ------------------------------ | ------------------------------------------------------------------------ | ------------------------ | -| `/carla//collision` | [carla_msgs.CarlaCollisionEvent](carla_msgs/msg/CarlaCollisionEvent.msg) | publish collision events | +| `/carla//collision` | [carla_msgs.CarlaCollisionEvent](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaCollisionEvent.msg) | publish collision events | ##### Lane Invasion Sensor | Topic | Type | Description | | ---------------------------------- | ------------------------------------------------------------------------------ | ------------------------------- | -| `/carla//lane_invasion` | [carla_msgs.CarlaLaneInvasionEvent](carla_msgs/msg/CarlaLaneInvasionEvent.msg) | publish events on lane-invasion | +| `/carla//lane_invasion` | [carla_msgs.CarlaLaneInvasionEvent](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaLaneInvasionEvent.msg) | publish events on lane-invasion | #### Object Sensor @@ -217,11 +217,11 @@ Currently the following sensors are supported: | Topic | Type | | ----------------------------------------------------------------- | ------------------------------------------------------------------------------ | -| `/carla//vehicle_control_cmd` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](carla_msgs/msg/CarlaEgoVehicleControl.msg) | -| `/carla//vehicle_control_cmd_manual` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](carla_msgs/msg/CarlaEgoVehicleControl.msg) | +| `/carla//vehicle_control_cmd` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | +| `/carla//vehicle_control_cmd_manual` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | | `/carla//vehicle_control_manual_override` (subscriber) | [std_msgs.Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html) | -| `/carla//vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](carla_msgs/msg/CarlaEgoVehicleStatus.msg) | -| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](carla_msgs/msg/CarlaEgoVehicleInfo.msg) | +| `/carla//vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleStatus.msg) | +| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleInfo.msg) | There are two modes to control the vehicle. @@ -261,7 +261,7 @@ Currently this method applies the complete linear vector, but only the yaw from ##### Carla Ackermann Control -In certain cases, the [Carla Control Command](carla_msgs/msg/CarlaEgoVehicleControl.msg) is not ideal to connect to an AD stack. +In certain cases, the [Carla Control Command](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) is not ideal to connect to an AD stack. Therefore a ROS-based node `carla_ackermann_control` is provided which reads [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) messages. You can find further documentation [here](carla_ackermann_control/README.md). @@ -273,23 +273,23 @@ You can find further documentation [here](carla_ackermann_control/README.md). | ------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------- | | `/carla/objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers | | `/carla/marker` | [visualization_msgs.Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) | visualization of vehicles and walkers | -| `/carla/actor_list` | [carla_msgs.CarlaActorList](carla_msgs/msg/CarlaActorList.msg) | list of all carla actors | -| `/carla/traffic_lights` | [carla_msgs.CarlaTrafficLightStatusList](carla_msgs/msg/CarlaTrafficLightStatusList.msg) | list of all traffic lights with their status | -| `/carla/traffic_lights_info` | [carla_msgs.CarlaTrafficLightInfoList](carla_msgs/msg/CarlaTrafficLightInfoList.msg) | static information for all traffic lights (e.g. position)| -| `/carla/weather_control` | [carla_msgs.CarlaWeatherParameters](carla_msgs/msg/CarlaWeatherParameters.msg) | set the CARLA weather parameters| +| `/carla/actor_list` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaActorList.msg) | list of all carla actors | +| `/carla/traffic_lights` | [carla_msgs.CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightStatusList.msg) | list of all traffic lights with their status | +| `/carla/traffic_lights_info` | [carla_msgs.CarlaTrafficLightInfoList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightInfoList.msg) | static information for all traffic lights (e.g. position)| +| `/carla/weather_control` | [carla_msgs.CarlaWeatherParameters](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWeatherParameters.msg) | set the CARLA weather parameters| #### Status of CARLA | Topic | Type | Description | | ------------------- | -------------------------------------------------------------- | ------------------------------------------------------ | -| `/carla/status` | [carla_msgs.CarlaStatus](carla_msgs/msg/CarlaStatus.msg) | | -| `/carla/world_info` | [carla_msgs.CarlaWorldInfo](carla_msgs/msg/CarlaWorldInfo.msg) | Info about the CARLA world/level (e.g. OPEN Drive map) | +| `/carla/status` | [carla_msgs.CarlaStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaStatus.msg) | | +| `/carla/world_info` | [carla_msgs.CarlaWorldInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWorldInfo.msg) | Info about the CARLA world/level (e.g. OPEN Drive map) | ### Walker | Topic | Type | Description | | ---------------------------------------------------- | ---------------------------------------------------------------------------- | ------------------ | -| `/carla/walker//walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](carla_msgs/msg/CarlaWalkerControl.msg) | Control a walker | +| `/carla/walker//walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWalkerControl.msg) | Control a walker | | `/carla/walker//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of walker | ### Other Vehicles diff --git a/carla_ad_agent/README.md b/carla_ad_agent/README.md index 63ee8ffd..15fa228e 100644 --- a/carla_ad_agent/README.md +++ b/carla_ad_agent/README.md @@ -10,4 +10,4 @@ For a more comprehensive solution, have a look at [Autoware](https://www.autowar | Topic | Type | Description | | ---------------------------------- | ------------------- | --------------------------- | -| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) | Vehicle control command | +| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | Vehicle control command | diff --git a/carla_ros_scenario_runner/README.md b/carla_ros_scenario_runner/README.md index fbadac39..716f486f 100644 --- a/carla_ros_scenario_runner/README.md +++ b/carla_ros_scenario_runner/README.md @@ -4,7 +4,19 @@ This is a wrapper to execute OpenScenarios with the CARLA [scenario runner](http It is best used from within the [rviz_carla_plugin](../rviz_carla_plugin). -Currently it is not supported to switch the Carla Town. Therefore the scenario needs to use the currently active Town. +Currently it is not supported to switch the CARLA Town. Therefore the scenario needs to use the currently active Town. + +Please have a look at the [example scenario](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ad_demo/config/FollowLeadingVehicle.xosc), especially at the way the ros-controller is set up. + + + + + + + + + +By this section within the openscenario definition, an instance of `carla_ad_agent` is launched (i.e. `roslaunch ..` is executed). Any aditional `` is appened as ros parameter (name:=value). ## Setup @@ -43,3 +55,5 @@ To run a scenario from commandline: | ------------------------------------- | ----------- | -------------------------------------------------------------------- | | `/scenario_runner/status` | The current status of the scenario runner execution (e.g. used by the [rviz_carla_plugin](../rviz_carla_plugin)) | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | + + diff --git a/carla_twist_to_control/README.md b/carla_twist_to_control/README.md index 4fcfd7d0..81b6aa4e 100644 --- a/carla_twist_to_control/README.md +++ b/carla_twist_to_control/README.md @@ -1,17 +1,17 @@ # Twist to Vehicle Control conversion -This node converts a [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) to [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) +This node converts a [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) to [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) ## Subscriptions | Topic | Type | Description | | ---------------------------------- | ------------------- | --------------------------- | -| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](../carla_msgs/msg/CarlaEgoVehicleInfo.msg) | Ego vehicle info, to receive max steering angle | +| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleInfo.msg) | Ego vehicle info, to receive max steering angle | | `/carla//twist` | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | Twist to convert | ## Publications | Topic | Type | Description | | ---------------------------------- | ------------------- | --------------------------- | -| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) | Converted vehicle control command | +| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | Converted vehicle control command | diff --git a/carla_walker_agent/README.md b/carla_walker_agent/README.md index 5eb7f315..a9307df7 100644 --- a/carla_walker_agent/README.md +++ b/carla_walker_agent/README.md @@ -6,4 +6,4 @@ An simple walker agent that can follow a given route. | Topic | Type | Description | | ---------------------------------- | ------------------- | --------------------------- | -| `/carla//walker_control_cmd` | [carla_msgs.CarlaWalkerControl](../carla_msgs/msg/CarlaWalkerControl.msg) | Walker control command | +| `/carla//walker_control_cmd` | [carla_msgs.CarlaWalkerControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWalkerControl.msg) | Walker control command | diff --git a/rviz_carla_plugin/README.md b/rviz_carla_plugin/README.md index c1db4887..0a54dc75 100644 --- a/rviz_carla_plugin/README.md +++ b/rviz_carla_plugin/README.md @@ -42,8 +42,8 @@ Similar to the [rqt CARLA plugin](../rqt_carla_plugin), it's possible to control | Topic | Type | Description | | ------------------- | ------------------------- | ------------------------------------------------------ | -| `/carla/status` | [carla_msgs.CarlaStatus](../carla_msgs/msg/CarlaStatus.msg) | Read the status of CARLA, to enable/disable the UI | -| `/carla/ego_vehicle/vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](../carla_msgs/msg/CarlaEgoVehicleStatus.msg) | To display the current state of the ego vehicle | +| `/carla/status` | [carla_msgs.CarlaStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaStatus.msg) | Read the status of CARLA, to enable/disable the UI | +| `/carla/ego_vehicle/vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleStatus.msg) | To display the current state of the ego vehicle | | `/carla/ego_vehicle/odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | To display the current pose of the ego vehicle | | `/scenario_runner/status` | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | To visualize the scenario runner status | | `/carla/available_scenarios` | [carla_ros_scenario_runner_types.CarlaScenarioList](../carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg) | For providing a list of scenarios to execute (disabled in combo box) | @@ -52,7 +52,7 @@ Similar to the [rqt CARLA plugin](../rqt_carla_plugin), it's possible to control | Topic | Type | Description | | ------------------- | ------------------------- | ------------------------------------------------------ | -| `/carla/control` | [carla_msgs.CarlaControl](../carla_msgs/msg/CarlaControl.msg) | Start/pause CARLA | +| `/carla/control` | [carla_msgs.CarlaControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaControl.msg) | Start/pause CARLA | | `/carla/ego_vehicle/spectator_pose` | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | Publish the current pose of the RVIZ camera view. | | `/carla/ego_vehicle/vehicle_control_manual_override` | [std_msgs.Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html) | To enable/disable the overriding of the vehicle control | | `/carla/ego_vehicle/twist` | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | The twist command, created via mouse | From 59b688e69f97c062bc5bee7f8979135c0190d104 Mon Sep 17 00:00:00 2001 From: Timothy Scott Date: Mon, 29 Jun 2020 09:33:52 +0200 Subject: [PATCH 263/627] Change frame of IMU measurements to right-handed ROS convention (#267) * Change frame of IMU measurements to right-handed ROS convention * Fixed frame of IMU orientation * Merge branch 'master' into imu-frame-fix --- carla_ros_bridge/src/carla_ros_bridge/imu.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 8582a0ef..093a6829 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -52,19 +52,20 @@ def sensor_data_updated(self, carla_imu_measurement): imu_msg = Imu() imu_msg.header = self.get_msg_header(timestamp=carla_imu_measurement.timestamp) - imu_msg.angular_velocity.x = carla_imu_measurement.gyroscope.x + # Carla uses a left-handed coordinate convention (X forward, Y right, Z up). + # Here, these measurements are converted to the right-handed ROS convention + # (X forward, Y left, Z up). + imu_msg.angular_velocity.x = -carla_imu_measurement.gyroscope.x imu_msg.angular_velocity.y = carla_imu_measurement.gyroscope.y - imu_msg.angular_velocity.z = carla_imu_measurement.gyroscope.z + imu_msg.angular_velocity.z = -carla_imu_measurement.gyroscope.z imu_msg.linear_acceleration.x = carla_imu_measurement.accelerometer.x - imu_msg.linear_acceleration.y = carla_imu_measurement.accelerometer.y + imu_msg.linear_acceleration.y = -carla_imu_measurement.accelerometer.y imu_msg.linear_acceleration.z = carla_imu_measurement.accelerometer.z imu_rotation = carla_imu_measurement.transform.rotation - quat = tf.transformations.quaternion_from_euler(math.radians(imu_rotation.roll), - math.radians(imu_rotation.pitch), - math.radians(imu_rotation.yaw)) + quat = trans.carla_rotation_to_numpy_quaternion(imu_rotation) imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) self.publish_message( self.get_topic_prefix(), imu_msg) From 101abad566620f785d3a72b705f1c70a9ed28485 Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Mon, 29 Jun 2020 10:18:21 +0200 Subject: [PATCH 264/627] Cleanup imports (#328) --- carla_ros_bridge/src/carla_ros_bridge/imu.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 093a6829..abb7a0a5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -6,9 +6,6 @@ """ Classes to handle Carla imu sensor """ -import math - -import tf from sensor_msgs.msg import Imu From d7bcff5ffa2f8280179e30801810f0ae34201b57 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Mon, 13 Jul 2020 08:43:03 +0200 Subject: [PATCH 265/627] Use transforms3d in debug_helper --- carla_ros_bridge/src/carla_ros_bridge/debug_helper.py | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 3203305f..242e9290 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -15,18 +15,10 @@ import carla -from ros_compatibility import CompatibleNode, destroy_subscription +from ros_compatibility import CompatibleNode, destroy_subscription, euler_from_quaternion ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - from tf.transformations import euler_from_quaternion # pylint: disable=import-error -elif ROS_VERSION == 2: - from transformations.transformations import euler_from_quaternion # pylint: disable=import-error -else: - raise NotImplementedError( - 'Make sure you have valid ' + 'ROS_VERSION env variable') - class DebugHelper(CompatibleNode): """ From 7ad475421aa51731198f539b229a2c33689845df Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 13 Jul 2020 19:02:24 +0200 Subject: [PATCH 266/627] add intensity value to point cloud --- CHANGELOG.md | 1 + .../src/carla_ros_bridge/lidar.py | 46 ++++++------------- 2 files changed, 14 insertions(+), 33 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 3af64edc..c3db8d88 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Add intensity value to point cloud message * Fixed wrong TF for ego_vehicle * Improve version check * Fix cleanup diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 0e04d1d7..3cdce79d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -14,7 +14,8 @@ import tf -from sensor_msgs.point_cloud2 import create_cloud_xyz32 +from sensor_msgs.point_cloud2 import create_cloud +from sensor_msgs.msg import PointField from carla_ros_bridge.sensor import Sensor import carla_common.transforms as trans @@ -43,29 +44,6 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): synchronous_mode=synchronous_mode, prefix='lidar/' + carla_actor.attributes.get('role_name')) - def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): - """ - Function (override) to modify the tf messages sent by this lidar. - - The lidar transformation has to be altered: - for some reasons lidar sends already a rotated cloud, - so herein, we need to ignore pitch and roll - - :return: the filled tf message - :rtype: geometry_msgs.msg.TransformStamped - """ - tf_msg = super(Lidar, self).get_ros_transform(transform, frame_id, child_frame_id) - - rotation = tf_msg.transform.rotation - quat = [rotation.x, rotation.y, rotation.z, rotation.w] - dummy_roll, dummy_pitch, yaw = tf.transformations.euler_from_quaternion( - quat) - # set roll and pitch to zero - quat = tf.transformations.quaternion_from_euler(0, 0, yaw) - tf_msg.transform.rotation = trans.numpy_quaternion_to_ros_quaternion( - quat) - return tf_msg - # pylint: disable=arguments-differ def sensor_data_updated(self, carla_lidar_measurement): """ @@ -75,18 +53,20 @@ def sensor_data_updated(self, carla_lidar_measurement): :type carla_lidar_measurement: carla.LidarMeasurement """ header = self.get_msg_header() - - lidar_data = numpy.frombuffer( + fields = [ + PointField('x', 0, PointField.FLOAT32, 1), + PointField('y', 4, PointField.FLOAT32, 1), + PointField('z', 8, PointField.FLOAT32, 1), + PointField('intensity', 12, PointField.FLOAT32, 1), + ] + + lidar_data = numpy.fromstring( carla_lidar_measurement.raw_data, dtype=numpy.float32) lidar_data = numpy.reshape( - lidar_data, (int(lidar_data.shape[0] / 3), 3)) + lidar_data, (int(lidar_data.shape[0] / 4), 4)) # we take the oposite of y axis # (as lidar point are express in left handed coordinate system, and ros need right handed) - # we need a copy here, because the data are read only in carla numpy - # array - lidar_data = -lidar_data - # we also need to permute x and y - lidar_data = lidar_data[..., [1, 0, 2]] - point_cloud_msg = create_cloud_xyz32(header, lidar_data) + lidar_data[:, 1] *= -1 + point_cloud_msg = create_cloud(header, fields, lidar_data) self.publish_message( self.get_topic_prefix() + "/point_cloud", point_cloud_msg) From 7154754eafee2f6669bff6801e47d787412d4a19 Mon Sep 17 00:00:00 2001 From: Dennis Maier Date: Tue, 14 Jul 2020 08:55:34 +0200 Subject: [PATCH 267/627] Reorder import --- ros_compatibility/src/ros_compatibility/ros_compatible_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 52d932c7..8eec8c52 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -99,9 +99,9 @@ def shutdown(self): rospy.signal_shutdown("") elif ROS_VERSION == 2: + from rclpy import Parameter from rclpy.exceptions import ROSInterruptException from rclpy.node import Node - from rclpy import Parameter from rclpy.qos import QoSProfile, QoSDurabilityPolicy import rclpy from builtin_interfaces.msg import Time From 9b64fd681284949f946a48c9959de61a56b98bf8 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Mon, 4 May 2020 17:24:58 +0200 Subject: [PATCH 268/627] replace code format check script with makefile, search for files and add cmake format --- .travis.yml | 11 +++-------- Makefile | 17 +++++++++++++++++ check.sh | 14 -------------- requirements.txt | 4 ++++ 4 files changed, 24 insertions(+), 22 deletions(-) create mode 100644 Makefile delete mode 100755 check.sh create mode 100644 requirements.txt diff --git a/.travis.yml b/.travis.yml index 53fe44a3..71db76a6 100644 --- a/.travis.yml +++ b/.travis.yml @@ -25,14 +25,9 @@ jobs: - name: "Check code formatting" stage: check before_install: skip - install: pip install --user pep8 autopep8 + install: pip install --user -r requirements.txt script: - - autopep8 carla_ros_bridge/src/carla_common/*.py --in-place --max-line-length=100 - - autopep8 carla_ros_bridge/src/carla_ros_bridge/*.py --in-place --max-line-length=100 - - autopep8 carla_ackermann_control/src/carla_ackermann_control/*.py --in-place --max-line-length=100 - - autopep8 carla_ego_vehicle/src/carla_ego_vehicle/*.py --in-place --max-line-length=100 - - autopep8 carla_waypoint_publisher/src/carla_waypoint_publisher/*.py --in-place --max-line-length=100 - - git diff --quiet HEAD --; if [ ! $? -eq 0 ]; then echo "Code is not autopep8 compliant. Please run check.sh"; git diff HEAD --; exit 1; fi + - make check_format - name: "Xenial Kinetic" stage: test dist: xenial @@ -80,7 +75,7 @@ script: - catkin config --install - source devel/setup.bash - cd src/ros-bridge - - pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ + - make pylint after_failure: - tail --lines=2000 build.log diff --git a/Makefile b/Makefile new file mode 100644 index 00000000..79d045f4 --- /dev/null +++ b/Makefile @@ -0,0 +1,17 @@ +file_finder = find . -type f $(1) -not \( -path './venv/*' -o -path './carla_msgs/*' \) + +CMAKE_FILES = $(call file_finder,-name "*.cmake" -o -name "CMakeLists.txt") +PY_FILES = $(call file_finder,-name "*.py") + +check: check_format pylint + +format: + $(PY_FILES) | xargs autopep8 --in-place --max-line-length=100 + $(CMAKE_FILES) | xargs cmake-format -i + +check_format: + $(PY_FILES) | xargs autopep8 --diff --max-line-length=100 + $(CMAKE_FILES) | xargs cmake-format --check + +pylint: + $(PY_FILES) | xargs pylint --rcfile=.pylintrc diff --git a/check.sh b/check.sh deleted file mode 100755 index f69f8988..00000000 --- a/check.sh +++ /dev/null @@ -1,14 +0,0 @@ -#!/bin/bash -autopep8 carla_common/src/carla_common/*.py --in-place --max-line-length=100 -autopep8 carla_ros_bridge/src/carla_ros_bridge/*.py --in-place --max-line-length=100 -autopep8 carla_ackermann_control/src/carla_ackermann_control/*.py --in-place --max-line-length=100 -autopep8 carla_ego_vehicle/src/carla_ego_vehicle/*.py --in-place --max-line-length=100 -autopep8 carla_waypoint_publisher/src/carla_waypoint_publisher/*.py --in-place --max-line-length=100 -autopep8 rqt_carla_control/src/rqt_carla_control/*.py --in-place --max-line-length=100 -autopep8 carla_ad_agent/src/carla_ad_agent/*.py --in-place --max-line-length=100 -autopep8 carla_ros_scenario_runner/src/carla_ros_scenario_runner/*.py --in-place --max-line-length=100 -autopep8 carla_twist_to_control/src/carla_twist_to_control/*.py --in-place --max-line-length=100 -autopep8 carla_spectator_camera/src/carla_spectator_camera/*.py --in-place --max-line-length=100 -autopep8 carla_infrastructure/src/carla_infrastructure/*.py --in-place --max-line-length=100 - -pylint --rcfile=.pylintrc carla_common/src/carla_common/ carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ diff --git a/requirements.txt b/requirements.txt new file mode 100644 index 00000000..16970a62 --- /dev/null +++ b/requirements.txt @@ -0,0 +1,4 @@ +pep8 +autopep8 +cmake_format +pylint From 417c943b24a653a4c9a1db9358f158e62df5536f Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Mon, 4 May 2020 17:28:10 +0200 Subject: [PATCH 269/627] apply autopep to all python files --- carla_ad_agent/setup.py | 1 - carla_ros_bridge/test/ros_bridge_client.py | 1 + carla_walker_agent/setup.py | 1 - .../src/carla_walker_agent/carla_walker_agent.py | 12 +++++++----- 4 files changed, 8 insertions(+), 7 deletions(-) diff --git a/carla_ad_agent/setup.py b/carla_ad_agent/setup.py index 0af8e3a7..5c5592b0 100644 --- a/carla_ad_agent/setup.py +++ b/carla_ad_agent/setup.py @@ -7,4 +7,3 @@ ) setup(**d) - diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 7a016ab2..ab781c97 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -27,6 +27,7 @@ PKG = 'test_roslaunch' TIMEOUT = 20 + class TestClock(unittest.TestCase): """ diff --git a/carla_walker_agent/setup.py b/carla_walker_agent/setup.py index d6185015..baa9d977 100644 --- a/carla_walker_agent/setup.py +++ b/carla_walker_agent/setup.py @@ -7,4 +7,3 @@ ) setup(**d) - diff --git a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py index df57ffc6..381e1342 100755 --- a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py +++ b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py @@ -33,10 +33,10 @@ def __init__(self, role_name, target_speed): self._current_pose = Pose() rospy.on_shutdown(self.on_shutdown) - #wait for ros bridge to create relevant topics + # wait for ros bridge to create relevant topics try: rospy.wait_for_message( - "/carla/{}/odometry".format(role_name), Odometry) + "/carla/{}/odometry".format(role_name), Odometry) except rospy.ROSInterruptException as e: if not rospy.is_shutdown(): raise e @@ -58,7 +58,7 @@ def on_shutdown(self): callback on shutdown """ rospy.loginfo("Shutting down, stopping walker...") - self.control_publisher.publish(CarlaWalkerControl()) #stop + self.control_publisher.publish(CarlaWalkerControl()) # stop def target_speed_updated(self, target_speed): """ @@ -72,7 +72,7 @@ def path_updated(self, path): callback on new route """ rospy.loginfo("New plan with {} waypoints received. Assigning plan...".format(len(path.poses))) - self.control_publisher.publish(CarlaWalkerControl()) #stop + self.control_publisher.publish(CarlaWalkerControl()) # stop self._waypoints = [] for elem in path.poses: self._waypoints.append(elem.pose) @@ -105,7 +105,8 @@ def run(self): else: self._waypoints = self._waypoints[1:] if self._waypoints: - rospy.loginfo("next waypoint: {} {}".format(self._waypoints[0].position.x, self._waypoints[0].position.y)) + rospy.loginfo("next waypoint: {} {}".format( + self._waypoints[0].position.x, self._waypoints[0].position.y)) else: rospy.loginfo("Route finished.") self.control_publisher.publish(control) @@ -114,6 +115,7 @@ def run(self): except rospy.ROSInterruptException: pass + def main(): """ From 9516e4414a80d6c76ea6da3b003baa3d60431ff3 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Mon, 4 May 2020 17:28:52 +0200 Subject: [PATCH 270/627] apply cmake format --- carla_ackermann_control/CMakeLists.txt | 58 +++++++------------ carla_ad_agent/CMakeLists.txt | 21 +++---- carla_ad_demo/CMakeLists.txt | 11 +--- carla_common/CMakeLists.txt | 6 +- carla_ego_vehicle/CMakeLists.txt | 22 ++----- carla_infrastructure/CMakeLists.txt | 22 ++----- carla_manual_control/CMakeLists.txt | 19 ++---- carla_ros_bridge/CMakeLists.txt | 36 ++++-------- carla_ros_scenario_runner/CMakeLists.txt | 14 ++--- .../CMakeLists.txt | 16 ++--- carla_spectator_camera/CMakeLists.txt | 21 ++----- carla_twist_to_control/CMakeLists.txt | 20 ++----- carla_walker_agent/CMakeLists.txt | 23 +++----- carla_waypoint_publisher/CMakeLists.txt | 20 ++----- carla_waypoint_types/CMakeLists.txt | 19 ++---- pcl_recorder/CMakeLists.txt | 39 ++++--------- rqt_carla_control/CMakeLists.txt | 26 ++------- rviz_carla_plugin/CMakeLists.txt | 30 ++++------ 18 files changed, 128 insertions(+), 295 deletions(-) diff --git a/carla_ackermann_control/CMakeLists.txt b/carla_ackermann_control/CMakeLists.txt index c8d7e77b..1cbe1d28 100644 --- a/carla_ackermann_control/CMakeLists.txt +++ b/carla_ackermann_control/CMakeLists.txt @@ -1,52 +1,38 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ackermann_control) -## Find catkin macros and libraries -find_package(catkin REQUIRED COMPONENTS - message_generation - rospy - std_msgs - ackermann_msgs - dynamic_reconfigure - carla_msgs - roslaunch -) +# Find catkin macros and libraries +find_package( + catkin REQUIRED + COMPONENTS message_generation + rospy + std_msgs + ackermann_msgs + dynamic_reconfigure + carla_msgs + roslaunch) catkin_python_setup() add_message_files( - FILES - EgoVehicleControlCurrent.msg - EgoVehicleControlInfo.msg - EgoVehicleControlMaxima.msg - EgoVehicleControlStatus.msg - EgoVehicleControlTarget.msg -) - -generate_messages( - DEPENDENCIES - std_msgs - carla_msgs -) - -generate_dynamic_reconfigure_options( - config/EgoVehicleControlParameter.cfg -) + FILES EgoVehicleControlCurrent.msg EgoVehicleControlInfo.msg + EgoVehicleControlMaxima.msg EgoVehicleControlStatus.msg + EgoVehicleControlTarget.msg) + +generate_messages(DEPENDENCIES std_msgs carla_msgs) + +generate_dynamic_reconfigure_options(config/EgoVehicleControlParameter.cfg) roslaunch_add_file_check(launch) catkin_package() -install(PROGRAMS - src/carla_ackermann_control/carla_ackermann_control_node.py - src/carla_ackermann_control/carla_control_physics.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +install(PROGRAMS src/carla_ackermann_control/carla_ackermann_control_node.py + src/carla_ackermann_control/carla_control_physics.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index 8f5a7216..ac90c3e6 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -1,21 +1,16 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ad_agent) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() roslaunch_add_file_check(launch) -catkin_package( - CATKIN_DEPENDS - rospy -) +catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS +catkin_install_python( + PROGRAMS src/carla_ad_agent/carla_ad_agent.py src/carla_ad_agent/basic_agent.py src/carla_ad_agent/agent.py @@ -23,10 +18,8 @@ catkin_install_python(PROGRAMS src/carla_ad_agent/vehicle_pid_controller.py src/carla_ad_agent/misc.py src/carla_ad_agent/__init__.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) + DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) - + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 56b4a771..2a6504fb 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -1,19 +1,14 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ad_demo) -find_package(catkin REQUIRED COMPONENTS - roslaunch -) - +find_package(catkin REQUIRED COMPONENTS roslaunch) roslaunch_add_file_check(launch) catkin_package() install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) diff --git a/carla_common/CMakeLists.txt b/carla_common/CMakeLists.txt index 75e71fe3..a6db3c20 100644 --- a/carla_common/CMakeLists.txt +++ b/carla_common/CMakeLists.txt @@ -7,7 +7,5 @@ catkin_python_setup() catkin_package() -catkin_install_python(PROGRAMS - src/carla_common/transforms.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python(PROGRAMS src/carla_common/transforms.py DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) diff --git a/carla_ego_vehicle/CMakeLists.txt b/carla_ego_vehicle/CMakeLists.txt index 7573b76b..caae5a98 100644 --- a/carla_ego_vehicle/CMakeLists.txt +++ b/carla_ego_vehicle/CMakeLists.txt @@ -1,29 +1,19 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ego_vehicle) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) -catkin_package( - CATKIN_DEPENDS - rospy -) +catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS - src/carla_ego_vehicle/carla_ego_vehicle.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python(PROGRAMS src/carla_ego_vehicle/carla_ego_vehicle.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) diff --git a/carla_infrastructure/CMakeLists.txt b/carla_infrastructure/CMakeLists.txt index 91b6ca33..925b4159 100644 --- a/carla_infrastructure/CMakeLists.txt +++ b/carla_infrastructure/CMakeLists.txt @@ -1,29 +1,19 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_infrastructure) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) -catkin_package( - CATKIN_DEPENDS - rospy -) +catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS - src/carla_infrastructure/carla_infrastructure.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python(PROGRAMS src/carla_infrastructure/carla_infrastructure.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index 8a43818a..03c6a55a 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -1,25 +1,16 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_manual_control) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() roslaunch_add_file_check(launch) -catkin_package( - CATKIN_DEPENDS - rospy -) +catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS - src/carla_manual_control/carla_manual_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python(PROGRAMS src/carla_manual_control/carla_manual_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 46b147a2..c5ff0e04 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -1,15 +1,9 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_bridge) -## Find catkin macros and libraries -find_package(catkin REQUIRED COMPONENTS - rospy - sensor_msgs - geometry_msgs - derived_object_msgs - tf - roslaunch -) +# Find catkin macros and libraries +find_package(catkin REQUIRED COMPONENTS rospy sensor_msgs geometry_msgs + derived_object_msgs tf roslaunch) catkin_python_setup() @@ -18,28 +12,18 @@ catkin_package() roslaunch_add_file_check(launch) roslaunch_add_file_check(test) -include_directories( - ${catkin_INCLUDE_DIRS} -) +include_directories(${catkin_INCLUDE_DIRS}) -install(PROGRAMS - src/carla_ros_bridge/bridge.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +install(PROGRAMS src/carla_ros_bridge/bridge.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) -install(FILES - test/ros_bridge_client.test - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) +install(FILES test/ros_bridge_client.test + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) -install(DIRECTORY - config - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) if(CATKIN_ENABLE_TESTING AND NOT $ENV{CI}) find_package(rostest REQUIRED) diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt index f62a0ff1..90bfe9a0 100644 --- a/carla_ros_scenario_runner/CMakeLists.txt +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -1,9 +1,7 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_scenario_runner) -find_package(catkin REQUIRED COMPONENTS - roslaunch -) +find_package(catkin REQUIRED COMPONENTS roslaunch) catkin_python_setup() @@ -11,14 +9,14 @@ roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) catkin_package() -catkin_install_python(PROGRAMS +catkin_install_python( + PROGRAMS src/carla_ros_scenario_runner/carla_ros_scenario_runner.py src/carla_ros_scenario_runner/application_runner.py src/carla_ros_scenario_runner/scenario_runner_runner.py src/carla_ros_scenario_runner/ros_vehicle_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) + DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_ros_scenario_runner_types/CMakeLists.txt b/carla_ros_scenario_runner_types/CMakeLists.txt index 8184efef..bfe8b33a 100644 --- a/carla_ros_scenario_runner_types/CMakeLists.txt +++ b/carla_ros_scenario_runner_types/CMakeLists.txt @@ -1,20 +1,12 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_scenario_runner_types) -find_package(catkin REQUIRED COMPONENTS - message_generation - geometry_msgs -) +find_package(catkin REQUIRED COMPONENTS message_generation geometry_msgs) -add_service_files(DIRECTORY srv FILES - ExecuteScenario.srv -) +add_service_files(DIRECTORY srv FILES ExecuteScenario.srv) -add_message_files(DIRECTORY msg FILES - CarlaScenario.msg - CarlaScenarioList.msg - CarlaScenarioRunnerStatus.msg -) +add_message_files(DIRECTORY msg FILES CarlaScenario.msg CarlaScenarioList.msg + CarlaScenarioRunnerStatus.msg) generate_messages(DEPENDENCIES geometry_msgs) diff --git a/carla_spectator_camera/CMakeLists.txt b/carla_spectator_camera/CMakeLists.txt index da537577..dbc2c555 100644 --- a/carla_spectator_camera/CMakeLists.txt +++ b/carla_spectator_camera/CMakeLists.txt @@ -1,26 +1,17 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_spectator_camera) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch - geometry_msgs -) +find_package(catkin REQUIRED COMPONENTS rospy roslaunch geometry_msgs) catkin_python_setup() roslaunch_add_file_check(launch) -catkin_package( - CATKIN_DEPENDS - rospy -) +catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS - src/carla_spectator_camera/carla_spectator_camera.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python( + PROGRAMS src/carla_spectator_camera/carla_spectator_camera.py DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_twist_to_control/CMakeLists.txt b/carla_twist_to_control/CMakeLists.txt index f219cafc..c4878e70 100644 --- a/carla_twist_to_control/CMakeLists.txt +++ b/carla_twist_to_control/CMakeLists.txt @@ -1,25 +1,17 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_twist_to_control) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() roslaunch_add_file_check(launch) -catkin_package( - CATKIN_DEPENDS - rospy -) +catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS - src/carla_twist_to_control/carla_twist_to_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python( + PROGRAMS src/carla_twist_to_control/carla_twist_to_control.py DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_walker_agent/CMakeLists.txt b/carla_walker_agent/CMakeLists.txt index 8d29bb89..f59f0cc6 100644 --- a/carla_walker_agent/CMakeLists.txt +++ b/carla_walker_agent/CMakeLists.txt @@ -1,27 +1,18 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_walker_agent) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() roslaunch_add_file_check(launch) -catkin_package( - CATKIN_DEPENDS - rospy -) +catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS - src/carla_walker_agent/carla_walker_agent.py - src/carla_walker_agent/__init__.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python( + PROGRAMS src/carla_walker_agent/carla_walker_agent.py + src/carla_walker_agent/__init__.py DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) - + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_waypoint_publisher/CMakeLists.txt b/carla_waypoint_publisher/CMakeLists.txt index d5d91276..6f2a336a 100644 --- a/carla_waypoint_publisher/CMakeLists.txt +++ b/carla_waypoint_publisher/CMakeLists.txt @@ -1,25 +1,17 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_waypoint_publisher) -find_package(catkin REQUIRED COMPONENTS - rospy - roslaunch -) +find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() roslaunch_add_file_check(launch) -catkin_package( - CATKIN_DEPENDS - rospy -) +catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS - src/carla_waypoint_publisher/carla_waypoint_publisher.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python( + PROGRAMS src/carla_waypoint_publisher/carla_waypoint_publisher.py DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_waypoint_types/CMakeLists.txt b/carla_waypoint_types/CMakeLists.txt index 6d0320d3..8b3d4c23 100644 --- a/carla_waypoint_types/CMakeLists.txt +++ b/carla_waypoint_types/CMakeLists.txt @@ -1,23 +1,12 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_waypoint_types) -find_package(catkin REQUIRED COMPONENTS - message_generation - nav_msgs -) +find_package(catkin REQUIRED COMPONENTS message_generation nav_msgs) -add_service_files(DIRECTORY srv FILES - GetWaypoint.srv - GetActorWaypoint.srv -) +add_service_files(DIRECTORY srv FILES GetWaypoint.srv GetActorWaypoint.srv) -add_message_files(DIRECTORY msg FILES - CarlaWaypoint.msg -) +add_message_files(DIRECTORY msg FILES CarlaWaypoint.msg) generate_messages(DEPENDENCIES nav_msgs) -catkin_package( - CATKIN_DEPENDS - nav_msgs -) +catkin_package(CATKIN_DEPENDS nav_msgs) diff --git a/pcl_recorder/CMakeLists.txt b/pcl_recorder/CMakeLists.txt index 64be9a4c..068ed8b3 100644 --- a/pcl_recorder/CMakeLists.txt +++ b/pcl_recorder/CMakeLists.txt @@ -3,39 +3,24 @@ project(pcl_recorder) add_compile_options(-std=c++11) -find_package(catkin REQUIRED COMPONENTS - pcl_conversions - pcl_ros - roscpp - sensor_msgs - roslaunch -) +find_package(catkin REQUIRED COMPONENTS pcl_conversions pcl_ros roscpp + sensor_msgs roslaunch) catkin_package() -roslaunch_add_file_check(launch DEPENDENCIES - ${PROJECT_NAME}_node -) +roslaunch_add_file_check(launch DEPENDENCIES ${PROJECT_NAME}_node) -include_directories( - include - ${catkin_INCLUDE_DIRS} -) +include_directories(include ${catkin_INCLUDE_DIRS}) -add_executable(${PROJECT_NAME}_node - src/PclRecorder.cpp - src/main.cpp -) +add_executable(${PROJECT_NAME}_node src/PclRecorder.cpp src/main.cpp) -target_link_libraries(${PROJECT_NAME}_node - ${catkin_LIBRARIES} -) +target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES}) -install(TARGETS ${PROJECT_NAME}_node - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +install( + TARGETS ${PROJECT_NAME}_node + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/rqt_carla_control/CMakeLists.txt b/rqt_carla_control/CMakeLists.txt index 80f1539c..6246dac9 100644 --- a/rqt_carla_control/CMakeLists.txt +++ b/rqt_carla_control/CMakeLists.txt @@ -1,30 +1,16 @@ cmake_minimum_required(VERSION 2.8.3) project(rqt_carla_control) -find_package(catkin REQUIRED COMPONENTS - rospy - rqt_gui_py - roslaunch -) +find_package(catkin REQUIRED COMPONENTS rospy rqt_gui_py roslaunch) catkin_python_setup() -catkin_package( - CATKIN_DEPENDS - rospy - rqt_gui_py -) +catkin_package(CATKIN_DEPENDS rospy rqt_gui_py) -catkin_install_python(PROGRAMS - src/rqt_carla_control/rqt_carla_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) +catkin_install_python(PROGRAMS src/rqt_carla_control/rqt_carla_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY resource/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/resource -) + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/resource) -install(FILES - plugin.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) +install(FILES plugin.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/rviz_carla_plugin/CMakeLists.txt b/rviz_carla_plugin/CMakeLists.txt index ba6c616d..14d2e9e3 100644 --- a/rviz_carla_plugin/CMakeLists.txt +++ b/rviz_carla_plugin/CMakeLists.txt @@ -4,12 +4,8 @@ project(rviz_carla_plugin) set(CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_STANDARD 14) -find_package(catkin REQUIRED COMPONENTS - rviz - carla_msgs - nav_msgs - carla_ros_scenario_runner_types -) +find_package(catkin REQUIRED COMPONENTS rviz carla_msgs nav_msgs + carla_ros_scenario_runner_types) catkin_package() include_directories(${catkin_INCLUDE_DIRS}) @@ -21,11 +17,8 @@ message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) set(QT_LIBRARIES Qt5::Widgets) -set(SRC_FILES - src/drive_widget.cpp - src/indicator_widget.cpp - src/carla_control_panel.cpp -) +set(SRC_FILES src/drive_widget.cpp src/indicator_widget.cpp + src/carla_control_panel.cpp) qt5_add_resources(SRC_FILES rviz_carla_plugin.qrc) @@ -33,16 +26,13 @@ add_library(${PROJECT_NAME} ${SRC_FILES}) target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) -install(TARGETS - ${PROJECT_NAME} +install( + TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) -install(FILES - plugin_description.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(FILES plugin_description.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) -install(DIRECTORY icons/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) +install(DIRECTORY icons/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) From d5583e733f84d98242cd88ee1f99ed34882ef383 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Tue, 5 May 2020 10:43:49 +0200 Subject: [PATCH 271/627] disable pylint because of issues from before unlinted files --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 71db76a6..3ed9ee0b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -75,7 +75,7 @@ script: - catkin config --install - source devel/setup.bash - cd src/ros-bridge - - make pylint + # - make pylint after_failure: - tail --lines=2000 build.log From 158e43bf326c20838c9c09545627f6d69ff88bcc Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 12:29:32 +0200 Subject: [PATCH 272/627] carla_manual_control: Remove dependency to transformations --- .../src/carla_manual_control/carla_manual_control.py | 1 - 1 file changed, 1 deletion(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 8f3d056e..ba9e1813 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -55,7 +55,6 @@ elif ROS_VERSION == 2: import rclpy from rclpy.callback_groups import ReentrantCallbackGroup - import transformations as tf from tf2_ros import LookupException from tf2_ros import ConnectivityException from tf2_ros import ExtrapolationException From 3f4cf3ecb9d4905f29ecaaeaed649b1681d1f42b Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 11:22:17 +0200 Subject: [PATCH 273/627] Initial ros2 launch files --- carla_ego_vehicle/CMakeLists.txt | 6 + .../launch/carla_ego_vehicle.launch.py | 120 ++++++++++++++++++ .../carla_example_ego_vehicle.launch.py | 65 ++++++++++ carla_ego_vehicle/setup.py | 6 +- carla_manual_control/CMakeLists.txt | 7 + .../launch/carla_manual_control.launch.py | 30 +++++ carla_manual_control/setup.py | 4 +- carla_ros_bridge/CMakeLists.txt | 7 + .../launch/carla_ros_bridge.launch | 45 +++---- .../launch/carla_ros_bridge.launch.py | 84 ++++++++++++ ..._bridge_with_example_ego_vehicle.launch.py | 94 ++++++++++++++ 11 files changed, 443 insertions(+), 25 deletions(-) create mode 100644 carla_ego_vehicle/launch/carla_ego_vehicle.launch.py create mode 100644 carla_ego_vehicle/launch/carla_example_ego_vehicle.launch.py create mode 100644 carla_manual_control/launch/carla_manual_control.launch.py create mode 100644 carla_ros_bridge/launch/carla_ros_bridge.launch.py create mode 100644 carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py diff --git a/carla_ego_vehicle/CMakeLists.txt b/carla_ego_vehicle/CMakeLists.txt index 8f9d53e6..165ce99d 100644 --- a/carla_ego_vehicle/CMakeLists.txt +++ b/carla_ego_vehicle/CMakeLists.txt @@ -27,6 +27,12 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(ament_cmake REQUIRED) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY + launch + DESTINATION share/${PROJECT_NAME}/ + ) ament_package() endif() diff --git a/carla_ego_vehicle/launch/carla_ego_vehicle.launch.py b/carla_ego_vehicle/launch/carla_ego_vehicle.launch.py new file mode 100644 index 00000000..3256dbc4 --- /dev/null +++ b/carla_ego_vehicle/launch/carla_ego_vehicle.launch.py @@ -0,0 +1,120 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='vehicle_filter', + default_value='vehicle.*' + ), + launch.actions.DeclareLaunchArgument( + name='sensor_definition_file' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='spawn_point', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='remap_rviz_initialpose_goal', + default_value='True' + ), + launch.actions.DeclareLaunchArgument( + name='spawn_ego_vehicle', + default_value='True' + ), + + # TODO: topic_tools not yet available in ROS2 + # launch_ros.actions.Node( + # package='topic_tools', + # node_executable='relay', + # name=launch.substitutions.LaunchConfiguration('role_name'), + # parameters=[ + # { + # '/carla/host': launch.substitutions.LaunchConfiguration('host') + # }, + # { + # '/carla/port': launch.substitutions.LaunchConfiguration('port') + # }, + # { + # '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + # } + # ], + # condition=launch.conditions.IfCondition( + # launch.substitutions.LaunchConfiguration('remap_rviz_initialpose_goal')) + # ), + # launch_ros.actions.Node( + # package='topic_tools', + # node_executable='relay', + # name=launch.substitutions.LaunchConfiguration('role_name'), + # parameters=[ + # { + # '/carla/host': launch.substitutions.LaunchConfiguration('host') + # }, + # { + # '/carla/port': launch.substitutions.LaunchConfiguration('port') + # }, + # { + # '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + # } + # ], + # condition=launch.conditions.IfCondition( + # launch.substitutions.LaunchConfiguration('remap_rviz_initialpose_goal')) + # ), + launch_ros.actions.Node( + package='carla_ego_vehicle', + node_executable='carla_ego_vehicle', + name=launch.substitutions.LaunchConfiguration('role_name'), + output='screen', + parameters=[ + { + '/carla/host': launch.substitutions.LaunchConfiguration('host') + }, + { + '/carla/port': launch.substitutions.LaunchConfiguration('port') + }, + { + '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + }, + { + 'sensor_definition_file': launch.substitutions.LaunchConfiguration('sensor_definition_file') + }, + { + 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter') + }, + { + 'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point') + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'spawn_ego_vehicle': launch.substitutions.LaunchConfiguration('spawn_ego_vehicle') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch.py b/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch.py new file mode 100644 index 00000000..81244779 --- /dev/null +++ b/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch.py @@ -0,0 +1,65 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='vehicle_filter', + default_value='vehicle.*' + ), + launch.actions.DeclareLaunchArgument( + name='sensor_definition_file', + default_value=get_package_share_directory( + 'carla_ego_vehicle') + '/config/sensors.json' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='spawn_point', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='spawn_ego_vehicle', + default_value='True' + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ego_vehicle'), 'carla_ego_vehicle.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'), + 'sensor_definition_file': launch.substitutions.LaunchConfiguration('sensor_definition_file'), + 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point'), + 'spawn_ego_vehicle': launch.substitutions.LaunchConfiguration('spawn_ego_vehicle') + }.items() + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ego_vehicle/setup.py b/carla_ego_vehicle/setup.py index b4a0b071..7adfe828 100644 --- a/carla_ego_vehicle/setup.py +++ b/carla_ego_vehicle/setup.py @@ -2,6 +2,7 @@ Setup for carla_ego_vehicle """ import os +from glob import glob ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: @@ -28,7 +29,8 @@ ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ('share/' + package_name + '/config', - ['config/settings.yaml', 'config/sensors.json']) + ['config/settings.yaml', 'config/sensors.json']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], zip_safe=True, @@ -39,7 +41,7 @@ tests_require=['pytest'], entry_points={ 'console_scripts': [ - 'ego_vehicle = src.carla_ego_vehicle.carla_ego_vehicle:main' + 'carla_ego_vehicle = src.carla_ego_vehicle.carla_ego_vehicle:main' ], }, ) diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index 510d2c29..e817b211 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -25,6 +25,13 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(ament_cmake REQUIRED) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY + launch + DESTINATION share/${PROJECT_NAME}/ + ) + ament_package() endif() diff --git a/carla_manual_control/launch/carla_manual_control.launch.py b/carla_manual_control/launch/carla_manual_control.launch.py new file mode 100644 index 00000000..332404c8 --- /dev/null +++ b/carla_manual_control/launch/carla_manual_control.launch.py @@ -0,0 +1,30 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch_ros.actions.Node( + package='carla_manual_control', + node_executable='carla_manual_control', + name=launch.substitutions.LaunchConfiguration('role_name'), + output='screen', + parameters=[ + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_manual_control/setup.py b/carla_manual_control/setup.py index bb0b9d96..0c264345 100644 --- a/carla_manual_control/setup.py +++ b/carla_manual_control/setup.py @@ -2,6 +2,7 @@ Setup for carla_manual_control """ import os +from glob import glob ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: @@ -23,6 +24,7 @@ data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], zip_safe=True, @@ -32,7 +34,7 @@ license='MIT', tests_require=['pytest'], entry_points={ - 'console_scripts': ['manual_control = carla_manual_control.carla_manual_control:main'], + 'console_scripts': ['carla_manual_control = carla_manual_control.carla_manual_control:main'], }, package_dir={'': 'src'}, ) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index eafdaed6..8212885c 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -38,6 +38,13 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(ament_cmake REQUIRED) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY + launch + DESTINATION share/${PROJECT_NAME}/ + ) + ament_package() endif() diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index b7a5707a..0e25f078 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -8,28 +8,29 @@ - - - - - - - - - - + + + + + + + + + + + diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch.py b/carla_ros_bridge/launch/carla_ros_bridge.launch.py new file mode 100644 index 00000000..aef5c7ae --- /dev/null +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch.py @@ -0,0 +1,84 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode_wait_for_vehicle_control_command', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='fixed_delta_seconds', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='town', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='ego_vehicle_role_names', + default_value=["hero", "ego_vehicle", "hero0", "hero1", "hero2", "hero3", "hero4", "hero5", "hero6", "hero7", "hero8", "hero9"] + ), + launch_ros.actions.Node( + package='carla_ros_bridge', + node_executable='bridge', + name='carla_ros_bridge', + output='screen', + on_exit=launch.actions.Shutdown(), + parameters=[ + { + 'use_sim_time': True + }, + { + 'carla/host': launch.substitutions.LaunchConfiguration('host') + }, + { + 'carla/port': launch.substitutions.LaunchConfiguration('port') + }, + { + 'carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + }, + { + 'carla/synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode') + }, + { + 'carla/synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command') + }, + { + 'carla/fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') + }, + { + 'carla/town': launch.substitutions.LaunchConfiguration('town') + }, + { + 'carla/ego_vehicle/role_name': launch.substitutions.LaunchConfiguration('ego_vehicle_role_names') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py new file mode 100644 index 00000000..7141bad5 --- /dev/null +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py @@ -0,0 +1,94 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='vehicle_filter', + default_value='vehicle.*' + ), + launch.actions.DeclareLaunchArgument( + name='spawn_point', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='town', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode_wait_for_vehicle_control_command', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='fixed_delta_seconds', + default_value='' + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ros_bridge'), 'carla_ros_bridge.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'town': launch.substitutions.LaunchConfiguration('town'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode'), + 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), + 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ego_vehicle'), 'carla_example_ego_vehicle.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'), + 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_manual_control'), 'carla_manual_control.launch.py') + ), + launch_arguments={ + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }.items() + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() From 6bad5d906430d0b58e19aa00787a29580dbdeda1 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 11:29:56 +0200 Subject: [PATCH 274/627] Initial conversion of other launch files, untested --- .../launch/carla_ackermann_control.launch.py | 30 ++++ ...os_bridge_with_ackermann_control.launch.py | 28 +++ .../launch/carla_ad_agent.launch.py | 44 +++++ carla_ad_demo/launch/carla_ad_demo.launch.py | 131 ++++++++++++++ .../carla_ad_demo_with_scenario.launch.py | 163 ++++++++++++++++++ .../launch/carla_infrastructure.launch.py | 50 ++++++ .../carla_ros_bridge_with_rviz.launch.py | 27 +++ .../carla_ros_scenario_runner.launch.py | 58 +++++++ .../launch/carla_spectator_camera.launch.py | 72 ++++++++ .../launch/carla_twist_to_control.launch.py | 30 ++++ .../launch/carla_walker_agent.launch.py | 44 +++++ .../launch/carla_waypoint_publisher.launch.py | 51 ++++++ pcl_recorder/launch/pcl_recorder.launch.py | 55 ++++++ 13 files changed, 783 insertions(+) create mode 100644 carla_ackermann_control/launch/carla_ackermann_control.launch.py create mode 100644 carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py create mode 100644 carla_ad_agent/launch/carla_ad_agent.launch.py create mode 100644 carla_ad_demo/launch/carla_ad_demo.launch.py create mode 100644 carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py create mode 100644 carla_infrastructure/launch/carla_infrastructure.launch.py create mode 100644 carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py create mode 100644 carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py create mode 100644 carla_spectator_camera/launch/carla_spectator_camera.launch.py create mode 100644 carla_twist_to_control/launch/carla_twist_to_control.launch.py create mode 100644 carla_walker_agent/launch/carla_walker_agent.launch.py create mode 100644 carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py create mode 100644 pcl_recorder/launch/pcl_recorder.launch.py diff --git a/carla_ackermann_control/launch/carla_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ackermann_control.launch.py new file mode 100644 index 00000000..806f79bf --- /dev/null +++ b/carla_ackermann_control/launch/carla_ackermann_control.launch.py @@ -0,0 +1,30 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch_ros.actions.Node( + package='carla_ackermann_control', + executable='carla_ackermann_control_node.py', + name=launch.substitutions.LaunchConfiguration('role_name'), + output='screen', + parameters=[ + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py new file mode 100644 index 00000000..9f388fc8 --- /dev/null +++ b/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py @@ -0,0 +1,28 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ros_bridge'), 'launch/carla_ros_bridge.launch.py') + ) + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ackermann_control'), 'launch/carla_ackermann_control.launch.py') + ) + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py new file mode 100644 index 00000000..472f75f5 --- /dev/null +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -0,0 +1,44 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='target_speed', + default_value='20' + ), + launch.actions.DeclareLaunchArgument( + name='avoid_risk', + default_value='True' + ), + launch_ros.actions.Node( + package='carla_ad_agent', + node_executable='carla_ad_agent.py', + name=launch.substitutions.LaunchConfiguration('role_name'), + output='screen', + parameters=[ + { + 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'avoid_risk': launch.substitutions.LaunchConfiguration('avoid_risk') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py new file mode 100644 index 00000000..afe599fc --- /dev/null +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -0,0 +1,131 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='town', + default_value='Town01' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode', + default_value='True' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode_wait_for_vehicle_control_command', + default_value='False' + ), + launch.actions.DeclareLaunchArgument( + name='fixed_delta_seconds', + default_value='0.05' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='vehicle_filter', + default_value='vehicle.tesla.model3' + ), + launch.actions.DeclareLaunchArgument( + name='spawn_point', + default_value='127.4,195.4,0,0,0,180' + ), + launch.actions.DeclareLaunchArgument( + name='target_speed', + default_value='30' + ), + launch.actions.DeclareLaunchArgument( + name='avoid_risk', + default_value='True' + ), + launch_ros.actions.Node( + package='rostopic', + node_executable='rostopic', + name='publish_goal' + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ros_bridge'), 'carla_ros_bridge.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'town': launch.substitutions.LaunchConfiguration('town'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode'), + 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), + 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ego_vehicle'), 'carla_example_ego_vehicle.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'), + 'sensor_definition_file': get_package_share_directory('carla_ad_demo') + '/config/sensors.json', + 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ad_agent'), 'carla_ad_agent.launch.py') + ), + launch_arguments={ + 'target_speed': launch.substitutions.LaunchConfiguration('target_speed'), + 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'avoid_risk': launch.substitutions.LaunchConfiguration('avoid_risk') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_waypoint_publisher'), 'carla_waypoint_publisher.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_manual_control'), 'carla_manual_control.launch.py') + ), + launch_arguments={ + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }.items() + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py new file mode 100644 index 00000000..aa22211f --- /dev/null +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -0,0 +1,163 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='town', + default_value='Town01' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode', + default_value='True' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode_wait_for_vehicle_control_command', + default_value='False' + ), + launch.actions.DeclareLaunchArgument( + name='fixed_delta_seconds', + default_value='0.05' + ), + launch.actions.DeclareLaunchArgument( + name='scenario_runner_path', + default_value=os.environ.get('SCENARIO_RUNNER_PATH') + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='vehicle_filter', + default_value='vehicle.tesla.model3' + ), + launch.actions.DeclareLaunchArgument( + name='avoid_risk', + default_value='True' + ), + launch.actions.DeclareLaunchArgument( + name='resolution_x', + default_value='800' + ), + launch.actions.DeclareLaunchArgument( + name='resolution_y', + default_value='600' + ), + launch.actions.DeclareLaunchArgument( + name='fov', + default_value='50' + ), + launch_ros.actions.Node( + package='carla_twist_to_control', + node_executable='carla_twist_to_control.py', + name='carla_twist_to_control', + parameters=[ + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] + ), + launch_ros.actions.Node( + package='rostopic', + node_executable='rostopic', + name='publish_scenarios' + ), + launch_ros.actions.Node( + package='rviz', + node_executable='rviz', + name='rviz', + output='screen', + on_exit=launch.actions.Shutdown() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ros_bridge'), 'carla_ros_bridge.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'town': launch.substitutions.LaunchConfiguration('town'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode'), + 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), + 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ego_vehicle'), 'carla_example_ego_vehicle.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'), + 'sensor_definition_file': get_package_share_directory('carla_ad_demo') + '/config/sensors.json', + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_waypoint_publisher'), 'carla_waypoint_publisher.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_spectator_camera'), 'carla_spectator_camera.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'resolution_x': launch.substitutions.LaunchConfiguration('resolution_x'), + 'resolution_y': launch.substitutions.LaunchConfiguration('resolution_y'), + 'fov': launch.substitutions.LaunchConfiguration('fov') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ros_scenario_runner'), 'carla_ros_scenario_runner.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'scenario_runner_path': launch.substitutions.LaunchConfiguration('scenario_runner_path'), + 'wait_for_ego': 'True' + }.items() + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_infrastructure/launch/carla_infrastructure.launch.py b/carla_infrastructure/launch/carla_infrastructure.launch.py new file mode 100644 index 00000000..36242603 --- /dev/null +++ b/carla_infrastructure/launch/carla_infrastructure.launch.py @@ -0,0 +1,50 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='infrastructure_sensor_definition_file' + ), + launch_ros.actions.Node( + package='carla_infrastructure', + executable='carla_infrastructure.py', + name='carla_infrastructure', + output='screen', + parameters=[ + { + '/carla/host': launch.substitutions.LaunchConfiguration('host') + }, + { + '/carla/port': launch.substitutions.LaunchConfiguration('port') + }, + { + '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + }, + { + 'infrastructure_sensor_definition_file': launch.substitutions.LaunchConfiguration('infrastructure_sensor_definition_file') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py new file mode 100644 index 00000000..f9a46fa2 --- /dev/null +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py @@ -0,0 +1,27 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch_ros.actions.Node( + package='rviz', + node_executable='rviz', + name='rviz' + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ros_bridge'), 'carla_ros_bridge.launch.py') + ) + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py new file mode 100644 index 00000000..43f6d6a6 --- /dev/null +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py @@ -0,0 +1,58 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='scenario_runner_path' + ), + launch.actions.DeclareLaunchArgument( + name='wait_for_ego', + default_value='True' + ), + launch_ros.actions.Node( + package='carla_ros_scenario_runner', + node_executable='carla_ros_scenario_runner', + name='carla_ros_scenario_runner', + output='screen', + on_exit=launch.actions.Shutdown(), + parameters=[ + { + 'host': launch.substitutions.LaunchConfiguration('host') + }, + { + 'port': launch.substitutions.LaunchConfiguration('port') + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'scenario_runner_path': launch.substitutions.LaunchConfiguration('scenario_runner_path') + }, + { + 'wait_for_ego': launch.substitutions.LaunchConfiguration('wait_for_ego') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_spectator_camera/launch/carla_spectator_camera.launch.py b/carla_spectator_camera/launch/carla_spectator_camera.launch.py new file mode 100644 index 00000000..a7dfa804 --- /dev/null +++ b/carla_spectator_camera/launch/carla_spectator_camera.launch.py @@ -0,0 +1,72 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='resolution_x', + default_value='800' + ), + launch.actions.DeclareLaunchArgument( + name='resolution_y', + default_value='600' + ), + launch.actions.DeclareLaunchArgument( + name='fov', + default_value='50' + ), + launch_ros.actions.Node( + package='carla_spectator_camera', + node_executable='carla_spectator_camera', + name='carla_spectator_camera', + output='screen', + parameters=[ + { + '/carla/host': launch.substitutions.LaunchConfiguration('host') + }, + { + '/carla/port': launch.substitutions.LaunchConfiguration('port') + }, + { + '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'resolution_x': launch.substitutions.LaunchConfiguration('resolution_x') + }, + { + 'resolution_y': launch.substitutions.LaunchConfiguration('resolution_y') + }, + { + 'fov': launch.substitutions.LaunchConfiguration('fov') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_twist_to_control/launch/carla_twist_to_control.launch.py b/carla_twist_to_control/launch/carla_twist_to_control.launch.py new file mode 100644 index 00000000..a7f151b6 --- /dev/null +++ b/carla_twist_to_control/launch/carla_twist_to_control.launch.py @@ -0,0 +1,30 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch_ros.actions.Node( + package='carla_twist_to_control', + executable='carla_twist_to_control.py', + name=launch.substitutions.LaunchConfiguration('role_name'), + output='screen', + parameters=[ + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_walker_agent/launch/carla_walker_agent.launch.py b/carla_walker_agent/launch/carla_walker_agent.launch.py new file mode 100644 index 00000000..1488864b --- /dev/null +++ b/carla_walker_agent/launch/carla_walker_agent.launch.py @@ -0,0 +1,44 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='target_speed', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='mode', + default_value='vehicle' + ), + launch_ros.actions.Node( + package='carla_walker_agent', + node_executable='carla_walker_agent', + name=launch.substitutions.LaunchConfiguration('role_name'), + output='screen', + parameters=[ + { + 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'mode': launch.substitutions.LaunchConfiguration('mode') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py new file mode 100644 index 00000000..acff582c --- /dev/null +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py @@ -0,0 +1,51 @@ +import os +import sys + +import launch +import launch_ros.actions + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch_ros.actions.Node( + package='carla_waypoint_publisher', + node_executable='carla_waypoint_publisher.py', + name='carla_waypoint_publisher', + output='screen', + parameters=[ + { + '/carla/host': launch.substitutions.LaunchConfiguration('host') + }, + { + '/carla/port': launch.substitutions.LaunchConfiguration('port') + }, + { + '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/pcl_recorder/launch/pcl_recorder.launch.py b/pcl_recorder/launch/pcl_recorder.launch.py new file mode 100644 index 00000000..4440f51e --- /dev/null +++ b/pcl_recorder/launch/pcl_recorder.launch.py @@ -0,0 +1,55 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch_ros.actions.Node( + package='rostopic', + executable='rostopic', + name='enable_autopilot_rostopic' + ), + launch_ros.actions.Node( + package='pcl_recorder', + executable='pcl_recorder_node', + name='pcl_recorder_node', + output='screen', + parameters=[ + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ros_bridge'), 'carla_ros_bridge_with_example_ego_vehicle.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }.items() + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() From 99591214743afd8b581dd542dc9f6e324406cbe1 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 12:52:18 +0200 Subject: [PATCH 275/627] Cleanup --- carla_ego_vehicle/CMakeLists.txt | 8 +++----- carla_manual_control/CMakeLists.txt | 7 ++----- carla_ros_bridge/CMakeLists.txt | 7 ++----- carla_ros_bridge/launch/carla_ros_bridge.launch.py | 3 ++- 4 files changed, 9 insertions(+), 16 deletions(-) diff --git a/carla_ego_vehicle/CMakeLists.txt b/carla_ego_vehicle/CMakeLists.txt index 165ce99d..f36055c6 100644 --- a/carla_ego_vehicle/CMakeLists.txt +++ b/carla_ego_vehicle/CMakeLists.txt @@ -28,11 +28,9 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) - # Install launch files. - install(DIRECTORY - launch - DESTINATION share/${PROJECT_NAME}/ - ) + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + ament_package() endif() diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index e817b211..fd9da428 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -26,11 +26,8 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) - # Install launch files. - install(DIRECTORY - launch - DESTINATION share/${PROJECT_NAME}/ - ) + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) ament_package() diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 8212885c..fe812112 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -39,11 +39,8 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) - # Install launch files. - install(DIRECTORY - launch - DESTINATION share/${PROJECT_NAME}/ - ) + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) ament_package() diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch.py b/carla_ros_bridge/launch/carla_ros_bridge.launch.py index aef5c7ae..161617f2 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch.py @@ -38,7 +38,8 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='ego_vehicle_role_names', - default_value=["hero", "ego_vehicle", "hero0", "hero1", "hero2", "hero3", "hero4", "hero5", "hero6", "hero7", "hero8", "hero9"] + default_value=["hero", "ego_vehicle", "hero0", "hero1", "hero2", + "hero3", "hero4", "hero5", "hero6", "hero7", "hero8", "hero9"] ), launch_ros.actions.Node( package='carla_ros_bridge', From 4d8b7b2ff0ec065b5488869609d8d8e293b12a1e Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 17:18:02 +0200 Subject: [PATCH 276/627] Cleanup communication --- .../carla_ego_vehicle/carla_ego_vehicle.py | 13 +- .../carla_manual_control.py | 12 +- carla_ros_bridge/config/settings.yaml | 19 -- .../launch/carla_ros_bridge.launch | 32 ++- .../src/carla_ros_bridge/actor.py | 12 +- .../src/carla_ros_bridge/bridge.py | 192 ++++++++++-------- .../src/carla_ros_bridge/camera.py | 49 +++-- .../carla_status_publisher.py | 10 +- .../src/carla_ros_bridge/collision_sensor.py | 13 +- .../src/carla_ros_bridge/communication.py | 135 ------------ .../src/carla_ros_bridge/debug_helper.py | 28 +-- .../src/carla_ros_bridge/ego_vehicle.py | 20 +- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 11 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 13 +- .../carla_ros_bridge/lane_invasion_sensor.py | 12 +- .../src/carla_ros_bridge/lidar.py | 17 +- .../src/carla_ros_bridge/object_sensor.py | 11 +- .../src/carla_ros_bridge/pseudo_actor.py | 23 +-- .../src/carla_ros_bridge/radar.py | 12 +- .../src/carla_ros_bridge/sensor.py | 12 +- .../src/carla_ros_bridge/spectator.py | 8 +- .../src/carla_ros_bridge/traffic.py | 16 +- .../carla_ros_bridge/traffic_lights_sensor.py | 18 +- .../carla_ros_bridge/traffic_participant.py | 11 +- .../src/carla_ros_bridge/vehicle.py | 8 +- .../src/carla_ros_bridge/walker.py | 8 +- .../src/carla_ros_bridge/world_info.py | 13 +- .../ros_compatibility/ros_compatible_node.py | 6 + 28 files changed, 318 insertions(+), 416 deletions(-) delete mode 100644 carla_ros_bridge/config/settings.yaml delete mode 100644 carla_ros_bridge/src/carla_ros_bridge/communication.py diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index ff5b30cc..9336c49d 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -377,6 +377,7 @@ def destroy(self): if self.player and self.player.is_alive: self.player.destroy() self.player = None + super(CarlaEgoVehicle, self).destroy() def run(self): """ @@ -432,13 +433,21 @@ def main(): executor = rclpy.executors.MultiThreadedExecutor() init_node = rclpy.create_node("init_ego") init_node.create_subscription(CarlaStatus, - '/carla/status', + '/carla/world_info', run_ego_vehicle, 1) executor.add_node(init_node) init_node.get_logger().info("Waiting for carla_bridge to start...") - executor.spin() + + try: + executor.spin() + except KeyboardInterrupt: + pass + + init_node.destroy_node() + rclpy.shutdown() if __name__ == '__main__': main() + diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index ba9e1813..02880e3f 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -36,7 +36,7 @@ from sensor_msgs.msg import Image from sensor_msgs.msg import NavSatFix from std_msgs.msg import Bool -from ros_compatibility import CompatibleNode, latch_on, euler_from_quaternion +from ros_compatibility import CompatibleNode, latch_on, euler_from_quaternion, ros_ok import os import datetime import math @@ -725,7 +725,7 @@ def main(args=None): thread = Thread(target=run, args=(executer,)) thread.start() - while not_shutdown(): + while ros_ok(): clock.tick_busy_loop(60) if controller.parse_events(clock): return @@ -740,13 +740,5 @@ def main(args=None): thread.join() pygame.quit() - -def not_shutdown(): - if ROS_VERSION == 1: - return not rospy.core.is_shutdown() - elif ROS_VERSION == 2: - return rclpy.ok() - - if __name__ == '__main__': main() diff --git a/carla_ros_bridge/config/settings.yaml b/carla_ros_bridge/config/settings.yaml deleted file mode 100644 index 103d6a66..00000000 --- a/carla_ros_bridge/config/settings.yaml +++ /dev/null @@ -1,19 +0,0 @@ -use_sim_time: true -carla: - # the network connection for the python connection to CARLA - host: localhost - port: 2000 - timeout: 2 - # enable/disable synchronous mode. If enabled ros-bridge waits until - # expected data is received for all sensors - synchronous_mode: false - # within synchronous mode: wait for a vehicle control command before next tick? - synchronous_mode_wait_for_vehicle_control_command: true - # set the fixed timestep length - fixed_delta_seconds: 0.05 - # configuration values for the ego vehicle - ego_vehicle: - # the role name of the vehicles that acts as ego vehicle for this ros bridge instance - # Only the vehicles within this list are controllable from within ROS. - # (the vehicle from CARLA is selected which has the attribute 'role_name' set to this value) - role_name: ["hero", "ego_vehicle", "hero0", "hero1", "hero2", "hero3", "hero4", "hero5", "hero6", "hero7", "hero8", "hero9", ] diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index 0e25f078..42b306dd 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -1,18 +1,28 @@ - - - - - - - + + + + + + + + + - + + + - - - + + np.iinfo(np.uint32).max: @@ -129,7 +129,7 @@ def publish_transform(self, ros_transform_msg): :return: """ - self.publish_message('tf', ros_transform_msg) + self.node.publish_tf_message(ros_transform_msg) def get_marker_color(self): # pylint: disable=no-self-use """ @@ -171,4 +171,4 @@ def publish_marker(self): marker.scale.x = self.carla_actor.bounding_box.extent.x * 2.0 marker.scale.y = self.carla_actor.bounding_box.extent.y * 2.0 marker.scale.z = self.carla_actor.bounding_box.extent.z * 2.0 - self.publish_message('/carla/marker', marker) + self.node.marker_publisher.publish(marker) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 3291704b..1f319266 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -23,7 +23,11 @@ from threading import Thread, Lock, Event import pkg_resources -from ros_compatibility import CompatibleNode, ros_ok, destroy_subscription +from rosgraph_msgs.msg import Clock +from tf2_msgs.msg import TFMessage +from visualization_msgs.msg import Marker # pylint: disable=import-error + +from ros_compatibility import CompatibleNode, ros_ok, destroy_subscription, ros_shutdown, ros_timestamp import carla from carla_ros_bridge.actor import Actor @@ -77,6 +81,13 @@ def __init__(self, rospy_init=True, executor=None): :param params: dict of parameters, see settings.yaml :type params: dict """ + self.debug_helper = None + self.carla_weather_subscriber = None + self.update_lock = Lock() + self.carla_control_queue = queue.Queue() + self.on_tick_id = None + self.update_actor_thread = None + self.carla_settings = None super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) self.executor = executor @@ -85,6 +96,7 @@ def initialize_bridge(self, carla_world, params): """ Initialize the bridge """ + self.ros_timestamp = None self.parameters = params self.actors = {} self.pseudo_actors = [] @@ -112,12 +124,12 @@ def initialize_bridge(self, carla_world, params): carla_world.apply_settings(self.carla_settings) self.comm = Communication() - self.update_lock = Lock() - - self.carla_control_queue = queue.Queue() + self.marker_publisher = self.new_publisher(Marker, '/carla/marker') + self.tf_publisher = self.new_publisher(TFMessage, 'tf') self.status_publisher = CarlaStatusPublisher(self.carla_settings.synchronous_mode, - self.carla_settings.fixed_delta_seconds) + self.carla_settings.fixed_delta_seconds, + self) # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. @@ -159,17 +171,17 @@ def initialize_bridge(self, carla_world, params): self.on_weather_changed, callback_group=self.callback_group) # add world info - self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, communication=self.comm)) + self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, node=self)) # add global object sensor self.pseudo_actors.append( - ObjectSensor(parent=None, communication=self.comm, actor_list=self.actors, + ObjectSensor(parent=None, node=self, actor_list=self.actors, filtered_id=None)) - self.debug_helper = DebugHelper(carla_world.debug) + self.debug_helper = DebugHelper(carla_world.debug, self) # add traffic light pseudo sensor self.pseudo_actors.append( - TrafficLightsSensor(parent=None, communication=self.comm, actor_list=self.actors)) + TrafficLightsSensor(parent=None, node=self, actor_list=self.actors)) def destroy(self): """ @@ -177,18 +189,20 @@ def destroy(self): :return: """ - self.shutdown("") - self.debug_helper.destroy() + if self.debug_helper: + self.debug_helper.destroy() self.shutdown.set() - destroy_subscription(self.carla_weather_subscriber) self.carla_control_queue.put(CarlaControl.STEP_ONCE) - if not self.carla_settings.synchronous_mode: - if self.on_tick_id: - self.carla_world.remove_on_tick(self.on_tick_id) - self.update_actor_thread.join() + if self.carla_settings: + if not self.carla_settings.synchronous_mode: + if self.on_tick_id: + self.carla_world.remove_on_tick(self.on_tick_id) + if self.update_actor_thread: + self.update_actor_thread.join() self._update_actors(set()) self.loginfo("Exiting Bridge") + super(CarlaRosBridge, self).destroy() def on_weather_changed(self, weather_parameters): """ @@ -257,11 +271,10 @@ def _synchronous_mode_update(self): world_snapshot = self.carla_world.get_snapshot() self.status_publisher.set_frame(frame) - self.comm.update_clock(world_snapshot.timestamp) + self.update_clock(world_snapshot.timestamp) self.logdebug("Tick for frame {} returned. Waiting for sensor data...".format(frame)) self._update(frame, world_snapshot.timestamp.elapsed_seconds) self.logdebug("Waiting for sensor data finished.") - self.comm.send_msgs() self._update_actors(set([x.id for x in world_snapshot])) if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: @@ -291,10 +304,10 @@ def _carla_time_tick(self, carla_snapshot): if self.update_lock.acquire(False): if self.timestamp_last_run < carla_snapshot.timestamp.elapsed_seconds: self.timestamp_last_run = carla_snapshot.timestamp.elapsed_seconds - self.comm.update_clock(carla_snapshot.timestamp) + self.update_clock(carla_snapshot.timestamp) self.status_publisher.set_frame(carla_snapshot.frame) + self._update(carla_snapshot.frame, carla_snapshot.timestamp.elapsed_seconds) - self.comm.send_msgs() self.update_lock.release() # if possible push current snapshot to update-actors-thread @@ -303,6 +316,20 @@ def _carla_time_tick(self, carla_snapshot): except queue.Full: pass + def update_clock(self, carla_timestamp): + """ + perform the update of the clock + + :param carla_timestamp: the current carla time + :type carla_timestamp: carla.Timestamp + :return: + """ + self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) + if ROS_VERSION == 1: + self.comm.publish_message('clock', Clock(self.ros_timestamp)) + elif ROS_VERSION == 2: + self.comm.publish_message('clock', self.ros_timestamp) + def _update_actors_thread(self): """ execution loop for async mode actor list updates @@ -398,59 +425,59 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m pseudo_actors = [] if carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": - actor = TrafficLight(carla_actor, parent, self.comm) + actor = TrafficLight(carla_actor, parent, node=self) else: - actor = Traffic(carla_actor, parent, self.comm) + actor = Traffic(carla_actor, parent, node=self) elif carla_actor.type_id.startswith("vehicle"): if carla_actor.attributes.get('role_name') \ in self.parameters['ego_vehicle']['role_name']: - actor = EgoVehicle(carla_actor, parent, self.comm, + actor = EgoVehicle(carla_actor, parent, self, self._ego_vehicle_control_applied_callback) pseudo_actors.append( - ObjectSensor(parent=actor, communication=self.comm, actor_list=self.actors, + ObjectSensor(parent=actor, node=self, actor_list=self.actors, filtered_id=carla_actor.id)) if ROS_VERSION == 2: self.executor.add_node(actor) else: - actor = Vehicle(carla_actor, parent, self.comm) + actor = Vehicle(carla_actor, parent, self) elif carla_actor.type_id.startswith("sensor"): if carla_actor.type_id.startswith("sensor.camera"): if carla_actor.type_id.startswith("sensor.camera.rgb"): - actor = RgbCamera(carla_actor, parent, self.comm, + actor = RgbCamera(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.camera.depth"): - actor = DepthCamera(carla_actor, parent, self.comm, + actor = DepthCamera(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.camera.semantic_segmentation"): - actor = SemanticSegmentationCamera(carla_actor, parent, self.comm, + actor = SemanticSegmentationCamera(carla_actor, parent, self, self.carla_settings.synchronous_mode) else: - actor = Camera(carla_actor, parent, self.comm, + actor = Camera(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.lidar"): - actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Lidar(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): - actor = Radar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Radar(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): - actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Gnss(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): - actor = ImuSensor(carla_actor, parent, self.comm, + actor = ImuSensor(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): - actor = CollisionSensor(carla_actor, parent, self.comm, + actor = CollisionSensor(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): - actor = LaneInvasionSensor(carla_actor, parent, self.comm, + actor = LaneInvasionSensor(carla_actor, parent, self, self.carla_settings.synchronous_mode) else: - actor = Sensor(carla_actor, parent, self.comm, + actor = Sensor(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("spectator"): - actor = Spectator(carla_actor, parent, self.comm) + actor = Spectator(carla_actor, parent, node=self) elif carla_actor.type_id.startswith("walker"): - actor = Walker(carla_actor, parent, self.comm) + actor = Walker(carla_actor, parent, node=self) else: - actor = Actor(carla_actor, parent, self.comm) + actor = Actor(carla_actor, parent, node=self) self.loginfo("Created {}(id={}, parent_id={}," " type={}, prefix={}, attributes={})".format(actor.__class__.__name__, @@ -471,31 +498,6 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m return actor - def run(self, executor=None): - """ - Run the bridge functionality. - - Registers on shutdown callback at rospy and spins ROS. - - :return: - """ - if ROS_VERSION == 1: - rospy.on_shutdown(self.on_shutdown) - self.spin() - elif ROS_VERSION == 2: - rclpy.get_default_context().on_shutdown(self.on_shutdown) - executor.spin() - - def on_shutdown(self): - """ - Function to be called on shutdown. - - This function is registered at rospy as shutdown handler. - - """ - self.loginfo("Shutdown requested") - self.destroy() - def _update(self, frame_id, timestamp): """ update all actors @@ -527,6 +529,24 @@ def _ego_vehicle_control_applied_callback(self, ego_vehicle_id): if not self._expected_ego_vehicle_control_command_ids: self._all_vehicle_control_commands_received.set() + def publish_tf_message(self, msg): + """ + Function to publish ROS TF message. + """ + + # prepare tf message + tf_msg = None + tf_to_publish = [] + tf_to_publish.append(msg) + if ROS_VERSION == 1: + tf_msg = TFMessage(tf_to_publish) + elif ROS_VERSION == 2: + tf_msg = TFMessage() + tf_msg.transforms = tf_to_publish + try: + self.tf_publisher.publish(tf_msg) + except Exception as error: # pylint: disable=broad-except + self.logwarn("Failed to publish message: {}".format(error)) def main(): """ @@ -541,7 +561,6 @@ def main(): if ROS_VERSION == 1: carla_bridge = CarlaRosBridge() # rospy.init_node('carla_ros_bridge', anonymous=True) - parameters = rospy.get_param('carla') elif ROS_VERSION == 2: rclpy.init(args=None) @@ -550,19 +569,18 @@ def main(): # init_node = rclpy.create_node("init_ros_bridge") executor.add_node(carla_bridge) - parameters['host'] = carla_bridge.get_param('carla.host', 'localhost') - parameters['port'] = carla_bridge.get_param('carla.port', 2000) - parameters['timeout'] = carla_bridge.get_param('carla.timeout', 2) - parameters['synchronous_mode'] = carla_bridge.get_param('carla.synchronous_mode', True) - parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( - 'carla.synchronous_mode_wait_for_vehicle_control_command', True) - parameters['fixed_delta_seconds'] = carla_bridge.get_param('carla.fixed_delta_seconds', - 0.05) - role_name = carla_bridge.get_param('carla.ego_vehicle.role_name', - ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) - parameters["ego_vehicle"] = {"role_name": role_name} - - print(parameters) # pylint: disable=superfluous-parens + parameters['host'] = carla_bridge.get_param('host', 'localhost') + parameters['port'] = carla_bridge.get_param('port', 2000) + parameters['timeout'] = carla_bridge.get_param('timeout', 2) + parameters['synchronous_mode'] = carla_bridge.get_param('synchronous_mode', False) + parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( + 'carla.synchronous_mode_wait_for_vehicle_control_command', True) + parameters['fixed_delta_seconds'] = carla_bridge.get_param('fixed_delta_seconds', + 0.05) + role_name = carla_bridge.get_param('ego_vehicle_role_name', + ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) + parameters["ego_vehicle"] = {"role_name": role_name} + carla_bridge.loginfo("Trying to connect to {host}:{port}".format( host=parameters['host'], port=parameters['port'])) @@ -573,15 +591,13 @@ def main(): # check carla version dist = pkg_resources.get_distribution("carla") if LooseVersion(dist.version) < LooseVersion(CarlaRosBridge.CARLA_VERSION): - carla_bridge.logfatal("CARLA python module version {} required. Found: {}".format( - CarlaRosBridge.CARLA_VERSION, dist.version)) - sys.exit(1) + raise RuntimeError("CARLA Server version {} required. Found: {}".format( + CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) if LooseVersion(carla_client.get_server_version()) < \ LooseVersion(CarlaRosBridge.CARLA_VERSION): - carla_bridge.logfatal("CARLA Server version {} required. Found: {}".format( + raise RuntimeError("CARLA Server version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) - sys.exit(1) carla_world = carla_client.get_world() @@ -601,10 +617,18 @@ def main(): carla_world.tick() carla_bridge.initialize_bridge(carla_client.get_world(), parameters) - carla_bridge.run(executor=executor) + + if ROS_VERSION == 1: + rospy.spin() + elif ROS_VERSION == 2: + executor.spin() except (IOError, RuntimeError) as e: carla_bridge.logerr("Error: {}".format(e)) + except KeyboardInterrupt: + pass finally: + carla_bridge.destroy() + ros_shutdown() del carla_world del carla_client diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 49e7e078..381ad841 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -14,7 +14,7 @@ from abc import abstractmethod import numpy from cv_bridge import CvBridge # pylint: disable=import-error -from sensor_msgs.msg import CameraInfo # pylint: disable=import-error +from sensor_msgs.msg import CameraInfo, Image # pylint: disable=import-error import carla import carla_common.transforms as trans @@ -34,7 +34,7 @@ class Camera(Sensor): cv_bridge = CvBridge() # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix=None, + def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None, sensor_name="Camera"): """ Constructor @@ -43,15 +43,16 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param prefix: the topic prefix to be used for this actor :type prefix: string """ if not prefix: prefix = 'camera' + super(Camera, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix=prefix, sensor_name=sensor_name) @@ -62,6 +63,14 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= self.carla_actor.attributes)) else: self._build_camera_info() + + self.camera_info_publisher = node.new_publisher(CameraInfo, self.get_topic_prefix() + + '/camera_info') + self.camera_publisher = node.new_publisher(Image, self.get_topic_prefix() + + '/' + self.get_image_topic_name()) + + self.listen() + def _build_camera_info(self): """ @@ -115,10 +124,8 @@ def sensor_data_updated(self, carla_image): cam_info = self._camera_info cam_info.header = img_msg.header - self.publish_message(self.get_topic_prefix() + - '/camera_info', cam_info) - self.publish_message(self.get_topic_prefix() + - '/' + self.get_image_topic_name(), img_msg) + self.camera_info_publisher.publish(cam_info) + self.camera_publisher.publish(img_msg) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ @@ -177,7 +184,7 @@ class RgbCamera(Camera): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="RGBCamera"): """ Constructor @@ -186,13 +193,13 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(RgbCamera, - self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + self).__init__(carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, prefix='camera/rgb/' + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) @@ -231,7 +238,7 @@ class DepthCamera(Camera): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="DepthCamera"): """ Constructor @@ -240,13 +247,13 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(DepthCamera, - self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + self).__init__(carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, prefix='camera/depth/' + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) @@ -307,7 +314,7 @@ class SemanticSegmentationCamera(Camera): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="SemanticSegmentationCamera"): """ Constructor @@ -316,13 +323,13 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(SemanticSegmentationCamera, self).__init__( - carla_actor=carla_actor, parent=parent, communication=communication, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, prefix='camera/semantic_segmentation/' + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index aad96b77..78f8374a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -13,8 +13,6 @@ from carla_msgs.msg import CarlaStatus # pylint: disable=import-error -from ros_compatibility import CompatibleNode - ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION not in (1, 2): @@ -24,18 +22,16 @@ from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error -class CarlaStatusPublisher(CompatibleNode): +class CarlaStatusPublisher(object): """ report the carla status """ - def __init__(self, synchronous_mode, fixed_delta_seconds): + def __init__(self, synchronous_mode, fixed_delta_seconds, node): """ Constructor """ - super(CarlaStatusPublisher, self).__init__("carla_status_publisher", latch=True, - rospy_init=False) self.synchronous_mode = synchronous_mode self.synchronous_mode_running = True self.fixed_delta_seconds = fixed_delta_seconds @@ -44,7 +40,7 @@ def __init__(self, synchronous_mode, fixed_delta_seconds): callback_group = None elif ROS_VERSION == 2: callback_group = ReentrantCallbackGroup() - self.carla_status_publisher = self.new_publisher(CarlaStatus, "/carla/status", + self.carla_status_publisher = node.new_publisher(CarlaStatus, "/carla/status", callback_group=callback_group) self.publish() diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index 426fbc1f..dcdb5887 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -20,7 +20,7 @@ class CollisionSensor(Sensor): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="CollisionSensor"): """ Constructor @@ -29,15 +29,18 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(CollisionSensor, - self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + self).__init__(carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, is_event_sensor=True, prefix="collision", sensor_name=sensor_name) + + self.collision_publisher = node.new_publisher(CarlaCollisionEvent, self.get_topic_prefix()) + self.listen() # pylint: disable=arguments-differ def sensor_data_updated(self, collision_event): @@ -54,4 +57,4 @@ def sensor_data_updated(self, collision_event): collision_msg.normal_impulse.y = collision_event.normal_impulse.y collision_msg.normal_impulse.z = collision_event.normal_impulse.z - self.publish_message(self.get_topic_prefix(), collision_msg) + self.collision_publisher.publish(collision_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py deleted file mode 100644 index 7ce9df73..00000000 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ /dev/null @@ -1,135 +0,0 @@ -#!/usr/bin/env python - -# -# Copyright (c) 2019 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -""" -Handle communication of ROS topics -""" -import os - -from rosgraph_msgs.msg import Clock # pylint: disable=import-error -from tf2_msgs.msg import TFMessage # pylint: disable=import-error - -from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile, latch_on - -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION not in (1, 2): - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") - -if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error - from builtin_interfaces.msg import Time # pylint: disable=import-error - - -class Communication(CompatibleNode): - """ - Handle communication of ROS topics - """ - - def __init__(self): - """ - Constructor - """ - super(Communication, self).__init__("communication", rospy_init=False) - self.tf_to_publish = [] - self.msgs_to_publish = [] - self.pub = {} - self.subscribers = {} - self.ros_timestamp = ros_timestamp() - - if ROS_VERSION == 1: - self.callback_group = None - self.pub['clock'] = self.new_publisher(Clock, 'clock') - elif ROS_VERSION == 2: - self.callback_group = ReentrantCallbackGroup() - self.pub['clock'] = self.new_publisher(Time, 'clock') - - # needed? - self.pub['tf'] = self.new_publisher(TFMessage, 'tf', qos_profile=QoSProfile(depth=100)) - - def send_msgs(self): - """ - Function to actually send the collected ROS messages out via the publisher - - :return: - """ - - # prepare tf message - tf_msg = None - - if ROS_VERSION == 1: - tf_msg = TFMessage(self.tf_to_publish) - elif ROS_VERSION == 2: - tf_msg = TFMessage() - tf_msg.transforms = self.tf_to_publish - try: - self.pub['tf'].publish(tf_msg) - except Exception as error: # pylint: disable=broad-except - self.logwarn("Failed to publish message: {}".format(error)) - - for publisher, msg in self.msgs_to_publish: - try: - publisher.publish(msg) - except Exception as error: # pylint: disable=broad-except - self.logwarn("Failed to publish message: {}".format(error)) - self.msgs_to_publish = [] - self.tf_to_publish = [] - - def publish_message(self, topic, msg, is_latched=False): - """ - Function to publish ROS messages. - - Store the message in a list (waiting for their publication) - with their associated publisher. - If required corresponding publishers are created automatically. - - Messages for /tf topics are handle differently - in order to publish all transforms, objects in the same message - - :param topic: ROS topic to publish the message on - :type topic: string - :param msg: the ROS message to be published - :type msg: a valid ROS message type - :return: - """ - if topic == 'tf': - # transform are merged in same message - self.tf_to_publish.append(msg) - else: - if topic not in self.pub: - if is_latched: - latched_profile = QoSProfile(depth=10, durability=latch_on) - self.pub[topic] = self.new_publisher( - type(msg), topic, qos_profile=latched_profile) - else: - # Use default QoS profile. - self.pub[topic] = self.new_publisher(type(msg), topic) - self.msgs_to_publish.append((self.pub[topic], msg)) - - def update_clock(self, carla_timestamp): - """ - perform the update of the clock - - :param carla_timestamp: the current carla time - :type carla_timestamp: carla.Timestamp - :return: - """ - self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) - if ROS_VERSION == 1: - self.publish_message('clock', Clock(self.ros_timestamp)) - elif ROS_VERSION == 2: - self.publish_message('clock', self.ros_timestamp) - - def get_current_ros_time(self): - """ - get the current ros time - - :return: the current ros time - :rtype ros.Time - """ - return self.ros_timestamp diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 242e9290..1d255078 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -20,21 +20,21 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -class DebugHelper(CompatibleNode): +class DebugHelper(object): """ Helper to draw markers in CARLA """ - def __init__(self, carla_debug_helper): + def __init__(self, carla_debug_helper, node): """ Constructor :param carla_debug_helper: carla debug helper :type carla_debug_helper: carla.DebugHelper """ - super(DebugHelper, self).__init__("debug_helper", rospy_init=False) self.debug = carla_debug_helper - self.marker_subscriber = self.create_subscriber(MarkerArray, "/carla/debug_marker", + self.node = node + self.marker_subscriber = self.node.create_subscriber(MarkerArray, "/carla/debug_marker", self.on_marker) def destroy(self): @@ -45,7 +45,7 @@ def destroy(self): :return: """ - self.logdebug("Destroy DebugHelper") + self.node.logdebug("Destroy DebugHelper") self.debug = None destroy_subscription(self.marker_subscriber) self.marker_subscriber = None @@ -56,7 +56,7 @@ def on_marker(self, marker_array): """ for marker in marker_array.markers: if marker.header.frame_id != "map": - self.logwarn("Could not draw marker in frame '{}'. Only 'map' supported.".format( + self.node.logwarn("Could not draw marker in frame '{}'. Only 'map' supported.".format( marker.header.frame_id)) continue lifetime = -1. @@ -74,7 +74,7 @@ def on_marker(self, marker_array): elif marker.type == Marker.CUBE: self.draw_box(marker, lifetime, color) else: - self.logwarn( + self.node.logwarn( "Marker type '{}' not supported.".format(marker.type)) def draw_arrow(self, marker, lifetime, color): @@ -83,7 +83,7 @@ def draw_arrow(self, marker, lifetime, color): """ if marker.points: if not len(marker.points) == 2: - self.logwarn("Drawing arrow from points requires two points. Received {}".format( + self.node.logwarn("Drawing arrow from points requires two points. Received {}".format( len(marker.points))) return thickness = marker.scale.x @@ -91,14 +91,14 @@ def draw_arrow(self, marker, lifetime, color): start = carla.Location(x=marker.points[0].x, y=-marker.points[0].y, z=marker.points[0].z) end = carla.Location(x=marker.points[1].x, y=-marker.points[1].y, z=marker.points[1].z) - self.loginfo("Draw Arrow from {} to {} (color: {}, lifetime: {}, " + self.node.loginfo("Draw Arrow from {} to {} (color: {}, lifetime: {}, " "thickness: {}, arrow_size: {})".format(start, end, color, lifetime, thickness, arrow_size)) self.debug.draw_arrow(start, end, thickness=thickness, arrow_size=arrow_size, color=color, life_time=lifetime) else: - self.logwarn("Drawing arrow from Position/Orientation not yet supported. " + self.node.logwarn("Drawing arrow from Position/Orientation not yet supported. " "Please use points.") def draw_points(self, marker, lifetime, color): @@ -108,7 +108,7 @@ def draw_points(self, marker, lifetime, color): for point in marker.points: location = carla.Location(x=point.x, y=-point.y, z=point.z) size = marker.scale.x - self.loginfo("Draw Point {} (color: {}, lifetime: {}, size: {})".format( + self.node.loginfo("Draw Point {} (color: {}, lifetime: {}, size: {})".format( location, color, lifetime, size)) self.debug.draw_point(location, size=size, color=color, life_time=lifetime) @@ -117,7 +117,7 @@ def draw_line_strips(self, marker, lifetime, color): draw lines from ros marker """ if len(marker.points) < 2: - self.logwarn("Drawing line-strip requires at least two points. Received {}".format( + self.node.logwarn("Drawing line-strip requires at least two points. Received {}".format( len(marker.points))) return last_point = None @@ -126,7 +126,7 @@ def draw_line_strips(self, marker, lifetime, color): if last_point: start = carla.Location(x=last_point.x, y=-last_point.y, z=last_point.z) end = carla.Location(x=point.x, y=-point.y, z=point.z) - self.loginfo("Draw Line from {} to {} (color: {}, lifetime: {}, " + self.node.loginfo("Draw Line from {} to {} (color: {}, lifetime: {}, " "thickness: {})".format(start, end, color, lifetime, thickness)) self.debug.draw_line(start, end, thickness=thickness, color=color, life_time=lifetime) @@ -152,6 +152,6 @@ def draw_box(self, marker, lifetime, color): rotation.roll = math.degrees(roll) rotation.pitch = math.degrees(pitch) rotation.yaw = -math.degrees(yaw) - self.loginfo("Draw Box {} (rotation: {}, color: {}, lifetime: {})".format( + self.node.loginfo("Draw Box {} (rotation: {}, color: {}, lifetime: {})".format( box, rotation, color, lifetime)) self.debug.draw_box(box, rotation, thickness=0.1, color=color, life_time=lifetime) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index c4fe52ac..7735109a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -23,7 +23,7 @@ from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleStatus # pylint: disable=import-error from carla_ros_bridge.vehicle import Vehicle -from ros_compatibility import CompatibleNode, destroy_subscription +from ros_compatibility import CompatibleNode, destroy_subscription, QoSProfile, latch_on ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -39,7 +39,7 @@ class EgoVehicle(Vehicle, CompatibleNode): Vehicle implementation details for the ego vehicle """ - def __init__(self, carla_actor, parent, communication, vehicle_control_applied_callback): + def __init__(self, carla_actor, parent, node, vehicle_control_applied_callback): """ Constructor @@ -47,11 +47,13 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode """ - Vehicle.__init__(self, carla_actor=carla_actor, parent=parent, communication=communication, + Vehicle.__init__(self, carla_actor=carla_actor, parent=parent, node=node, prefix=carla_actor.attributes.get('role_name')) + self.vehicle_status_publisher = node.new_publisher(CarlaEgoVehicleStatus, self.get_topic_prefix() + "/vehicle_status") + self.vehicle_info_publisher = node.new_publisher(CarlaEgoVehicleInfo, self.get_topic_prefix() + "/vehicle_info", qos_profile=QoSProfile(depth=10, durability=latch_on)) if ROS_VERSION == 1: self.callback_group = None @@ -122,7 +124,7 @@ def send_vehicle_msgs(self): vehicle_status.control.reverse = self.carla_actor.get_control().reverse vehicle_status.control.gear = self.carla_actor.get_control().gear vehicle_status.control.manual_gear_shift = self.carla_actor.get_control().manual_gear_shift - self.publish_message(self.get_topic_prefix() + "/vehicle_status", vehicle_status) + self.vehicle_status_publisher.publish(vehicle_status) # only send vehicle once (in latched-mode) # TODO: Make latching work reliably in ROS2 # pylint: disable=fixme @@ -167,11 +169,7 @@ def send_vehicle_msgs(self): vehicle_info.center_of_mass.y = vehicle_physics.center_of_mass.y vehicle_info.center_of_mass.z = vehicle_physics.center_of_mass.z self.vehicle_info = vehicle_info - self.publish_message(self.get_topic_prefix() + "/vehicle_info", - vehicle_info, is_latched=True) - if ROS_VERSION == 2: - self.publish_message(self.get_topic_prefix() + "/vehicle_info", - self.vehicle_info, is_latched=True) + self.vehicle_info_publisher.publish(vehicle_info) def update(self, frame, timestamp): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index edca6e1a..4cce87bb 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -20,7 +20,7 @@ class Gnss(Sensor): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="GNSS"): + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="GNSS"): """ Constructor @@ -28,15 +28,16 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_ :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(Gnss, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, synchronous_mode=synchronous_mode, + node=node, synchronous_mode=synchronous_mode, prefix="gnss/" + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) + self.gnss_publisher = node.new_publisher(NavSatFix, self.get_topic_prefix() + "/fix") # pylint: disable=arguments-differ def sensor_data_updated(self, carla_gnss_measurement): @@ -51,4 +52,4 @@ def sensor_data_updated(self, carla_gnss_measurement): navsatfix_msg.latitude = carla_gnss_measurement.latitude navsatfix_msg.longitude = carla_gnss_measurement.longitude navsatfix_msg.altitude = carla_gnss_measurement.altitude - self.publish_message(self.get_topic_prefix() + "/fix", navsatfix_msg) + self.gnss_publisher.publish(navsatfix_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index b60130af..b44dee85 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -25,7 +25,7 @@ class ImuSensor(Sensor): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="IMU"): + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="IMU"): """ Constructor @@ -33,16 +33,18 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_ :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(ImuSensor, - self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + self).__init__(carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, prefix="imu/" + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) + self.imu_publisher = node.new_publisher(Imu, self.get_topic_prefix()) + self.listen() # pylint: disable=arguments-differ def sensor_data_updated(self, carla_imu_measurement): @@ -70,5 +72,4 @@ def sensor_data_updated(self, carla_imu_measurement): quat = trans.carla_rotation_to_numpy_quaternion(imu_rotation) imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) - self.publish_message( - self.get_topic_prefix(), imu_msg) + self.imu_publisher.publish(imu_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index d30a9710..960525d9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -20,7 +20,7 @@ class LaneInvasionSensor(Sensor): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="LaneInvasionSensor"): """ Constructor @@ -29,15 +29,17 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(LaneInvasionSensor, - self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + self).__init__(carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, is_event_sensor=True, prefix="lane_invasion", sensor_name=sensor_name) + self.lane_invasion_publisher = node.new_publisher(CarlaLaneInvasionEvent, self.get_topic_prefix()) + self.listen() # pylint: disable=arguments-differ def sensor_data_updated(self, lane_invasion_event): @@ -51,4 +53,4 @@ def sensor_data_updated(self, lane_invasion_event): lane_invasion_msg.header = self.get_msg_header() for marking in lane_invasion_event.crossed_lane_markings: lane_invasion_msg.crossed_lane_markings.append(marking.type) - self.publish_message(self.get_topic_prefix(), lane_invasion_msg) + self.lane_invasion_publisher.publish(lane_invasion_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 1d10a8f9..b0105c1e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -1,6 +1,6 @@ #!/usr/bin/env python - # +# Copyright (c) 2018, Willow Garage, Inc. # Copyright (c) 2018-2019 Intel Corporation # # This work is licensed under the terms of the MIT license. @@ -40,7 +40,7 @@ class Lidar(Sensor): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="Lidar"): + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="Lidar"): """ Constructor @@ -48,13 +48,17 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_ :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode """ super(Lidar, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, synchronous_mode=synchronous_mode, + node=node, synchronous_mode=synchronous_mode, prefix='lidar/' + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) + + self.lidar_publisher = node.new_publisher(PointCloud2, self.get_topic_prefix() + + "/point_cloud") + self.listen() # pylint: disable=arguments-differ def sensor_data_updated(self, carla_lidar_measurement): @@ -109,8 +113,7 @@ def sensor_data_updated(self, carla_lidar_measurement): # -- - self.publish_message(self.get_topic_prefix() + - "/point_cloud", point_cloud_msg) + self.lidar_publisher.publish(point_cloud_msg) # http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index e7141da4..a34bfebd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -20,25 +20,26 @@ class ObjectSensor(PseudoActor): Pseudo object sensor """ - def __init__(self, parent, communication, actor_list, filtered_id): + def __init__(self, parent, node, actor_list, filtered_id): """ Constructor :param carla_world: carla world object :type carla_world: carla.World :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param actor_list: current list of actors :type actor_list: map(carla-actor-id -> python-actor-object) :param filtered_id: id to filter from actor_list :type filtered_id: int """ - super(ObjectSensor, self).__init__(parent=parent, communication=communication, + super(ObjectSensor, self).__init__(parent=parent, node=node, prefix='objects') self.actor_list = actor_list self.filtered_id = filtered_id + self.object_publisher = node.new_publisher(ObjectArray, self.get_topic_prefix()) def destroy(self): """ @@ -64,4 +65,4 @@ def update(self, frame, timestamp): ros_objects.objects.append(actor.get_object_info()) elif isinstance(actor, Walker): ros_objects.objects.append(actor.get_object_info()) - self.publish_message(self.get_topic_prefix(), ros_objects) + self.object_publisher.publish(ros_objects) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index c33c3883..f66ebc1d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -13,7 +13,7 @@ from std_msgs.msg import Header # pylint: disable=import-error -from ros_compatibility import CompatibleNode, ros_timestamp +from ros_compatibility import CompatibleNode, ros_timestamp, QoSProfile, latch_on ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -21,22 +21,23 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -class PseudoActor(CompatibleNode): +class PseudoActor(object): """ Generic base class for Pseudo actors (that are not existing in Carla world) """ # pylint: disable=super-init-not-called - def __init__(self, parent, communication, prefix=None): + def __init__(self, parent, node, prefix=None): """ Constructor :param parent: the parent of this :type parent: carla_ros_bridge.PseudoActor :param prefix: the topic prefix to be used for this actor :type prefix: string - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode """ + self.pub ={}#TODO self.parent = parent if self.parent: @@ -44,7 +45,7 @@ def __init__(self, parent, communication, prefix=None): else: self.parent_id = None - self.communication = communication + self.node = node # Concatenate the onw prefix to the the parent topic name if not empty. self.prefix = "" @@ -61,13 +62,6 @@ def destroy(self): :return: """ self.parent = None - self.communication = None - - def publish_message(self, topic, msg, is_latched=False): - """ - hand message over to communication layer - """ - return self.communication.publish_message(topic, msg, is_latched) def get_msg_header(self, frame_id=None, timestamp=None): """ @@ -80,10 +74,11 @@ def get_msg_header(self, frame_id=None, timestamp=None): header.frame_id = frame_id else: header.frame_id = self.get_prefix() + if timestamp: header.stamp = ros_timestamp(sec=timestamp, from_sec=True) else: - header.stamp = self.communication.get_current_ros_time() + header.stamp = self.node.ros_timestamp return header def get_parent_id(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index ff7c5c75..97dd056d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -21,22 +21,24 @@ class Radar(Sensor): """ # pylint: disable=too-many-arguments - def __init__(self, carla_actor, parent, communication, synchronous_mode, sensor_name="Radar"): + def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="Radar"): """ Constructor :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(Radar, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, synchronous_mode=synchronous_mode, + node=node, synchronous_mode=synchronous_mode, prefix="radar/" + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) + self.radar_publisher = node.new_publisher(CarlaRadarMeasurement, self.get_topic_prefix() + "/radar") + self.listen() # pylint: disable=arguments-differ def sensor_data_updated(self, carla_radar_measurement): @@ -55,4 +57,4 @@ def sensor_data_updated(self, carla_radar_measurement): radar_detection.depth = detection.depth radar_detection.velocity = detection.velocity radar_msg.detections.append(radar_detection) - self.publish_message(self.get_topic_prefix() + "/radar", radar_msg) + self.radar_publisher.publish(radar_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index a802882f..50b2ec71 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -39,7 +39,7 @@ def __init__( self, # pylint: disable=too-many-arguments carla_actor, parent, - communication, + node, synchronous_mode, is_event_sensor=False, # only relevant in synchronous_mode: # if a sensor only delivers data on special events, @@ -54,8 +54,8 @@ def __init__( :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool :param prefix: the topic prefix to be used for this actor @@ -65,7 +65,7 @@ def __init__( """ if prefix is None: prefix = 'sensor' - Actor.__init__(self, carla_actor=carla_actor, parent=parent, communication=communication, + Actor.__init__(self, carla_actor=carla_actor, parent=parent, node=node, prefix=prefix) if sensor_name is None: sensor_name = "Sensor" @@ -83,8 +83,8 @@ def __init__( except (KeyError, ValueError): self.sensor_tick_time = None - if self.__class__.__name__ != "Sensor": - self.carla_actor.listen(self._callback_sensor_data) + def listen(self): + self.carla_actor.listen(self._callback_sensor_data) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/spectator.py b/carla_ros_bridge/src/carla_ros_bridge/spectator.py index f2be7019..aff2772e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/spectator.py +++ b/carla_ros_bridge/src/carla_ros_bridge/spectator.py @@ -18,7 +18,7 @@ class Spectator(Actor): Actor implementation details for spectators """ - def __init__(self, carla_actor, parent, communication): + def __init__(self, carla_actor, parent, node): """ Constructor @@ -26,8 +26,8 @@ def __init__(self, carla_actor, parent, communication): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode """ super(Spectator, self).__init__(carla_actor=carla_actor, parent=parent, prefix='spectator', - communication=communication) + node=node) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 77b4e66e..9de8946a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -21,7 +21,7 @@ class Traffic(Actor): Actor implementation details for traffic objects """ - def __init__(self, carla_actor, parent, communication): + def __init__(self, carla_actor, parent, node): """ Constructor @@ -29,11 +29,11 @@ def __init__(self, carla_actor, parent, communication): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode """ super(Traffic, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, prefix='traffic') + node=node, prefix='traffic') class TrafficLight(Actor): @@ -41,7 +41,7 @@ class TrafficLight(Actor): Traffic implementation details for traffic lights """ - def __init__(self, carla_actor, parent, communication): + def __init__(self, carla_actor, parent, node): """ Constructor @@ -49,11 +49,11 @@ def __init__(self, carla_actor, parent, communication): :type carla_actor: carla.TrafficLight :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode """ super(TrafficLight, - self).__init__(carla_actor=carla_actor, parent=parent, communication=communication, + self).__init__(carla_actor=carla_actor, parent=parent, node=node, prefix='traffic.traffic_light') def get_status(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index f1359261..2107b4f8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -14,29 +14,33 @@ from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.traffic import TrafficLight +from ros_compatibility import QoSProfile, latch_on class TrafficLightsSensor(PseudoActor): """ a sensor that reports the state of all traffic lights """ - def __init__(self, parent, communication, actor_list): + def __init__(self, parent, node, actor_list): """ Constructor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param actor_list: current list of actors :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(TrafficLightsSensor, self).__init__(parent=parent, communication=communication, + super(TrafficLightsSensor, self).__init__(parent=parent, node=node, prefix="") self.actor_list = actor_list self.traffic_light_status = CarlaTrafficLightStatusList() self.traffic_light_actors = [] + self.traffic_lights_info_publisher = node.new_publisher(CarlaTrafficLightInfoList, self.get_topic_prefix() + "traffic_lights_info", qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.traffic_light_status_publisher = node.new_publisher(CarlaTrafficLightStatusList, self.get_topic_prefix() + "traffic_lights", qos_profile=QoSProfile(depth=10, durability=latch_on)) + def destroy(self): """ Function to destroy this object. @@ -62,10 +66,8 @@ def update(self, frame, timestamp): traffic_light_info_list = CarlaTrafficLightInfoList() for traffic_light in traffic_light_actors: traffic_light_info_list.traffic_lights.append(traffic_light.get_info()) - self.publish_message(self.get_topic_prefix() + "traffic_lights_info", - traffic_light_info_list, is_latched=True) + self.traffic_lights_info_publisher.publish(traffic_light_info_list) if traffic_light_status != self.traffic_light_status: self.traffic_light_status = traffic_light_status - self.publish_message(self.get_topic_prefix() + "traffic_lights", traffic_light_status, - is_latched=True) + self.traffic_light_status_publisher.publish(traffic_light_status) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index f5ab96e6..0d9f3243 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -22,7 +22,7 @@ class TrafficParticipant(Actor): actor implementation details for traffic participant """ - def __init__(self, carla_actor, parent, communication, prefix): + def __init__(self, carla_actor, parent, node, prefix): """ Constructor @@ -30,14 +30,15 @@ def __init__(self, carla_actor, parent, communication, prefix): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param prefix: the topic prefix to be used for this actor :type prefix: string """ self.classification_age = 0 super(TrafficParticipant, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, prefix=prefix) + node=node, prefix=prefix) + self.odometry_publisher = node.new_publisher(Odometry, self.get_topic_prefix() + "/odometry") def update(self, frame, timestamp): """ @@ -66,7 +67,7 @@ def send_odometry(self): odometry.child_frame_id = self.get_prefix() odometry.pose.pose = self.get_current_ros_pose() odometry.twist.twist = self.get_current_ros_twist_rotated() - self.publish_message(self.get_topic_prefix() + "/odometry", odometry) + self.odometry_publisher.publish(odometry) def get_object_info(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 67b27822..4a8133de 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -20,7 +20,7 @@ class Vehicle(TrafficParticipant): Actor implementation details for vehicles """ - def __init__(self, carla_actor, parent, communication, prefix=None): + def __init__(self, carla_actor, parent, node, prefix=None): """ Constructor @@ -28,8 +28,8 @@ def __init__(self, carla_actor, parent, communication, prefix=None): :type carla_actor: carla.Vehicle :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param prefix: the topic prefix to be used for this actor :type prefix: string """ @@ -50,7 +50,7 @@ def __init__(self, carla_actor, parent, communication, prefix=None): self.classification = Object.CLASSIFICATION_OTHER_VEHICLE super(Vehicle, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, prefix=prefix) + node=node, prefix=prefix) def get_marker_color(self): # pylint: disable=no-self-use """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index d389e0d6..b550ace7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -23,7 +23,7 @@ class Walker(TrafficParticipant): Actor implementation details for pedestrians """ - def __init__(self, carla_actor, parent, communication): + def __init__(self, carla_actor, parent, node): """ Constructor @@ -31,8 +31,8 @@ def __init__(self, carla_actor, parent, communication): :type carla_actor: carla.Walker :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode :param prefix: the topic prefix to be used for this actor :type prefix: string """ @@ -42,7 +42,7 @@ def __init__(self, carla_actor, parent, communication): prefix = "walker/{:03}".format(carla_actor.id) super(Walker, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, prefix=prefix) + node=node, prefix=prefix) self.control_subscriber = self.create_subscriber( CarlaWalkerControl, diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index 84b1ce49..c6dfa111 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -13,27 +13,30 @@ from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error from carla_ros_bridge.pseudo_actor import PseudoActor +from ros_compatibility import QoSProfile, latch_on class WorldInfo(PseudoActor): """ Publish the map """ - def __init__(self, carla_world, communication): + def __init__(self, carla_world, node): """ Constructor :param carla_world: carla world object :type carla_world: carla.World - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode """ - super(WorldInfo, self).__init__(parent=None, communication=communication, + super(WorldInfo, self).__init__(parent=None, node=node, prefix="world_info") self.carla_map = carla_world.get_map() + self.world_info_publisher = node.new_publisher(CarlaWorldInfo, self.get_topic_prefix(), qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.map_published = False def destroy(self): @@ -59,5 +62,5 @@ def update(self, frame, timestamp): open_drive_msg = CarlaWorldInfo() open_drive_msg.map_name = self.carla_map.name open_drive_msg.opendrive = self.carla_map.to_opendrive() - self.publish_message(self.get_topic_prefix(), open_drive_msg, is_latched=True) + self.world_info_publisher.publish(open_drive_msg) self.map_published = True diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 8eec8c52..9a92a909 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -56,6 +56,9 @@ def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwa self.qos_profile = QoSProfile(depth=queue_size, durability=latch) self.callback_group = None + def destroy(self): + pass + def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_value is None: return rospy.get_param(name) @@ -168,6 +171,9 @@ def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwa self.qos_profile = QoSProfile(depth=queue_size) self.callback_group = None + def destroy(self): + self.destroy_node() + def get_param(self, name, alternative_value=None, alternative_name=None): if alternative_value is None: return self.get_parameter(name).value From 816e9d7b1db8de376d6eb867fe2adb2093af790e Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 19:07:16 +0200 Subject: [PATCH 277/627] Enable use_sim_time for all nodes - works now with ros1 and ros2 --- .../carla_ego_vehicle/carla_ego_vehicle.py | 2 +- .../carla_manual_control.py | 10 ++---- .../launch/carla_ros_bridge.launch | 4 ++- carla_ros_bridge/setup.py | 1 - .../src/carla_ros_bridge/bridge.py | 31 ++++++++++++------- .../ros_compatibility/ros_compatible_node.py | 3 +- 6 files changed, 28 insertions(+), 23 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 9336c49d..e5112227 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -432,7 +432,7 @@ def main(): rclpy.init(args=None) executor = rclpy.executors.MultiThreadedExecutor() init_node = rclpy.create_node("init_ego") - init_node.create_subscription(CarlaStatus, + init_node.create_subscription(CarlaWorldInfo, '/carla/world_info', run_ego_vehicle, 1) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 02880e3f..3031f7b9 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -394,7 +394,6 @@ def __init__(self, role_name, width, height): self.manual_control_override_updated, callback_group=self.callback_group) self.carla_status = CarlaStatus() - self.start_frame = None self.status_subscriber = self.create_subscriber(CarlaStatus, "/carla/status", self.carla_status_updated, callback_group=self.callback_group) @@ -428,8 +427,6 @@ def carla_status_updated(self, data): Callback on carla status """ self.carla_status = data - if self.start_frame is None: - self.start_frame = self.carla_status.frame self.update_info_text() def manual_control_override_updated(self, data): @@ -500,16 +497,15 @@ def update_info_text(self): fps = 0 if ROS_VERSION == 1: - time = int(rospy.get_rostime().to_sec()) + time = str(datetime.timedelta(seconds=float(rospy.get_rostime().to_sec())))[:10] elif ROS_VERSION == 2: - time = float((self.carla_status.frame - self.start_frame) * - self.carla_status.fixed_delta_seconds) + time = str(datetime.timedelta(seconds=float(self.get_clock().now().nanoseconds)/10**9))[:10] if self.carla_status.fixed_delta_seconds: fps = 1 / self.carla_status.fixed_delta_seconds self._info_text = [ 'Frame: % 22s' % self.carla_status.frame, - 'Simulation time: % 12s' % datetime.timedelta(seconds=time), + 'Simulation time: % 12s' % time, 'FPS: % 24.1f' % fps, '', 'Vehicle: % 20s' % ' '.join(self.vehicle_info.type.title().split('.')[1:]), 'Speed: % 15.0f km/h' % (3.6 * self.vehicle_status.velocity), diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index 42b306dd..17d30f7a 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -1,5 +1,8 @@ + + + @@ -21,7 +24,6 @@ - diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index 11801552..91691d43 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -23,7 +23,6 @@ packages=[package_name], data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - ('share/' + package_name + '/config', ['config/settings.yaml']), (os.path.join('share', package_name), glob('launch/*.launch.py'))], install_requires=['setuptools'], zip_safe=True, diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 1f319266..091fe68c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -23,15 +23,14 @@ from threading import Thread, Lock, Event import pkg_resources -from rosgraph_msgs.msg import Clock from tf2_msgs.msg import TFMessage from visualization_msgs.msg import Marker # pylint: disable=import-error -from ros_compatibility import CompatibleNode, ros_ok, destroy_subscription, ros_shutdown, ros_timestamp +from ros_compatibility import CompatibleNode, ros_ok, destroy_subscription, ros_shutdown, ros_timestamp, QoSProfile, latch_on import carla + from carla_ros_bridge.actor import Actor -from carla_ros_bridge.communication import Communication from carla_ros_bridge.sensor import Sensor from carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher @@ -56,11 +55,13 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +from rosgraph_msgs.msg import Clock if ROS_VERSION == 1: import rospy # pylint: disable=import-error elif ROS_VERSION == 2: import rclpy # pylint: disable=import-error from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error + from builtin_interfaces.msg import Time else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") @@ -88,6 +89,9 @@ def __init__(self, rospy_init=True, executor=None): self.on_tick_id = None self.update_actor_thread = None self.carla_settings = None + self.shutdown = None + self.actors = {} + self.pseudo_actors = [] super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) self.executor = executor @@ -96,15 +100,14 @@ def initialize_bridge(self, carla_world, params): """ Initialize the bridge """ - self.ros_timestamp = None self.parameters = params - self.actors = {} - self.pseudo_actors = [] self.carla_world = carla_world if ROS_VERSION == 1: + self.ros_timestamp = 0 self.callback_group = None elif ROS_VERSION == 2: + self.ros_timestamp = Time() self.callback_group = ReentrantCallbackGroup() self.synchronous_mode_update_thread = None @@ -123,10 +126,13 @@ def initialize_bridge(self, carla_world, params): self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) - self.comm = Communication() - self.marker_publisher = self.new_publisher(Marker, '/carla/marker') self.tf_publisher = self.new_publisher(TFMessage, 'tf') + if ROS_VERSION == 1: + self.clock_publisher = self.new_publisher(Clock, 'clock') + elif ROS_VERSION == 2: + self.clock_publisher = self.new_publisher(Clock, 'clock') + self.actor_list_publisher = self.new_publisher(CarlaActorList, "/carla/actor_list", qos_profile=QoSProfile(depth=10, durability=latch_on)) self.status_publisher = CarlaStatusPublisher(self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds, self) @@ -191,7 +197,8 @@ def destroy(self): """ if self.debug_helper: self.debug_helper.destroy() - self.shutdown.set() + if self.shutdown: + self.shutdown.set() self.carla_control_queue.put(CarlaControl.STEP_ONCE) if self.carla_settings: if not self.carla_settings.synchronous_mode: @@ -326,9 +333,9 @@ def update_clock(self, carla_timestamp): """ self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) if ROS_VERSION == 1: - self.comm.publish_message('clock', Clock(self.ros_timestamp)) + self.clock_publisher.publish(Clock(self.ros_timestamp)) elif ROS_VERSION == 2: - self.comm.publish_message('clock', self.ros_timestamp) + self.clock_publisher.publish(Clock(clock=self.ros_timestamp)) def _update_actors_thread(self): """ @@ -408,7 +415,7 @@ def publish_actor_list(self): ros_actor_list.actors.append(ros_actor) - self.comm.publish_message("/carla/actor_list", ros_actor_list, is_latched=True) + self.actor_list_publisher.publish(ros_actor_list) def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-many-statements """ diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 9a92a909..4fbb82f8 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -161,8 +161,9 @@ class ROSInterruptException(ROSInterruptException): class CompatibleNode(Node): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): + param = Parameter('use_sim_time', Parameter.Type.BOOL, True) super(CompatibleNode, self).__init__(node_name, allow_undeclared_parameters=True, - automatically_declare_parameters_from_overrides=True, **kwargs) + automatically_declare_parameters_from_overrides=True, parameter_overrides=[param],**kwargs) if latch: self.qos_profile = QoSProfile( depth=queue_size, From 0669a7b5266420630765960060795d5010882069 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 19:10:26 +0200 Subject: [PATCH 278/627] Fix naming in some launch files --- carla_infrastructure/launch/carla_infrastructure.launch.py | 2 +- .../launch/carla_twist_to_control.launch.py | 2 +- pcl_recorder/launch/pcl_recorder.launch.py | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/carla_infrastructure/launch/carla_infrastructure.launch.py b/carla_infrastructure/launch/carla_infrastructure.launch.py index 36242603..2501b575 100644 --- a/carla_infrastructure/launch/carla_infrastructure.launch.py +++ b/carla_infrastructure/launch/carla_infrastructure.launch.py @@ -24,7 +24,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_infrastructure', - executable='carla_infrastructure.py', + node_executable='carla_infrastructure.py', name='carla_infrastructure', output='screen', parameters=[ diff --git a/carla_twist_to_control/launch/carla_twist_to_control.launch.py b/carla_twist_to_control/launch/carla_twist_to_control.launch.py index a7f151b6..f39bb088 100644 --- a/carla_twist_to_control/launch/carla_twist_to_control.launch.py +++ b/carla_twist_to_control/launch/carla_twist_to_control.launch.py @@ -13,7 +13,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_twist_to_control', - executable='carla_twist_to_control.py', + node_executable='carla_twist_to_control.py', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', parameters=[ diff --git a/pcl_recorder/launch/pcl_recorder.launch.py b/pcl_recorder/launch/pcl_recorder.launch.py index 4440f51e..347e270f 100644 --- a/pcl_recorder/launch/pcl_recorder.launch.py +++ b/pcl_recorder/launch/pcl_recorder.launch.py @@ -22,12 +22,12 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='rostopic', - executable='rostopic', + node_executable='rostopic', name='enable_autopilot_rostopic' ), launch_ros.actions.Node( package='pcl_recorder', - executable='pcl_recorder_node', + node_executable='pcl_recorder_node', name='pcl_recorder_node', output='screen', parameters=[ From 10f3c45e18a196b5bb5bc3a8b3dbf0f3349aa3e4 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 19:14:42 +0200 Subject: [PATCH 279/627] Fix more launch files --- .../launch/carla_ackermann_control.launch.py | 2 +- .../launch/carla_ros_bridge_with_ackermann_control.launch.py | 4 ++-- carla_ad_agent/launch/carla_ad_agent.launch.py | 2 +- carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py | 2 +- carla_infrastructure/launch/carla_infrastructure.launch.py | 2 +- .../launch/carla_twist_to_control.launch.py | 2 +- .../launch/carla_waypoint_publisher.launch.py | 2 +- 7 files changed, 8 insertions(+), 8 deletions(-) diff --git a/carla_ackermann_control/launch/carla_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ackermann_control.launch.py index 806f79bf..69bceb7a 100644 --- a/carla_ackermann_control/launch/carla_ackermann_control.launch.py +++ b/carla_ackermann_control/launch/carla_ackermann_control.launch.py @@ -13,7 +13,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_ackermann_control', - executable='carla_ackermann_control_node.py', + node_executable='carla_ackermann_control_node', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', parameters=[ diff --git a/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py index 9f388fc8..60526c54 100644 --- a/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py +++ b/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py @@ -11,13 +11,13 @@ def generate_launch_description(): launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( - 'carla_ros_bridge'), 'launch/carla_ros_bridge.launch.py') + 'carla_ros_bridge'), 'carla_ros_bridge.launch.py') ) ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( - 'carla_ackermann_control'), 'launch/carla_ackermann_control.launch.py') + 'carla_ackermann_control'), 'carla_ackermann_control.launch.py') ) ) ]) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 472f75f5..5660d837 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -21,7 +21,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_ad_agent', - node_executable='carla_ad_agent.py', + node_executable='carla_ad_agent', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', parameters=[ diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index aa22211f..25b55912 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -66,7 +66,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_twist_to_control', - node_executable='carla_twist_to_control.py', + node_executable='carla_twist_to_control', name='carla_twist_to_control', parameters=[ { diff --git a/carla_infrastructure/launch/carla_infrastructure.launch.py b/carla_infrastructure/launch/carla_infrastructure.launch.py index 2501b575..045796bf 100644 --- a/carla_infrastructure/launch/carla_infrastructure.launch.py +++ b/carla_infrastructure/launch/carla_infrastructure.launch.py @@ -24,7 +24,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_infrastructure', - node_executable='carla_infrastructure.py', + node_executable='carla_infrastructure', name='carla_infrastructure', output='screen', parameters=[ diff --git a/carla_twist_to_control/launch/carla_twist_to_control.launch.py b/carla_twist_to_control/launch/carla_twist_to_control.launch.py index f39bb088..9842719f 100644 --- a/carla_twist_to_control/launch/carla_twist_to_control.launch.py +++ b/carla_twist_to_control/launch/carla_twist_to_control.launch.py @@ -13,7 +13,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_twist_to_control', - node_executable='carla_twist_to_control.py', + node_executable='carla_twist_to_control', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', parameters=[ diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py index acff582c..45e6e3ce 100644 --- a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py @@ -25,7 +25,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_waypoint_publisher', - node_executable='carla_waypoint_publisher.py', + node_executable='carla_waypoint_publisher', name='carla_waypoint_publisher', output='screen', parameters=[ From 618e6c2de9ae362c8a618a5d01fd7a67eee1d9d1 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 17 Jul 2020 19:18:31 +0200 Subject: [PATCH 280/627] Fix formatting --- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 5 ++--- .../carla_manual_control.py | 4 +++- .../src/carla_ros_bridge/bridge.py | 18 ++++++++++-------- .../src/carla_ros_bridge/camera.py | 7 +++---- .../src/carla_ros_bridge/collision_sensor.py | 2 +- .../src/carla_ros_bridge/debug_helper.py | 10 +++++----- .../src/carla_ros_bridge/ego_vehicle.py | 6 ++++-- .../carla_ros_bridge/lane_invasion_sensor.py | 3 ++- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 4 ++-- .../src/carla_ros_bridge/pseudo_actor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/radar.py | 3 ++- .../carla_ros_bridge/traffic_lights_sensor.py | 7 +++++-- .../carla_ros_bridge/traffic_participant.py | 3 ++- .../src/carla_ros_bridge/world_info.py | 6 ++++-- .../ros_compatibility/ros_compatible_node.py | 2 +- 15 files changed, 47 insertions(+), 35 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index e5112227..22e3bc96 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -438,16 +438,15 @@ def main(): 1) executor.add_node(init_node) init_node.get_logger().info("Waiting for carla_bridge to start...") - + try: executor.spin() except KeyboardInterrupt: pass - + init_node.destroy_node() rclpy.shutdown() if __name__ == '__main__': main() - diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 3031f7b9..e957752c 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -499,7 +499,8 @@ def update_info_text(self): if ROS_VERSION == 1: time = str(datetime.timedelta(seconds=float(rospy.get_rostime().to_sec())))[:10] elif ROS_VERSION == 2: - time = str(datetime.timedelta(seconds=float(self.get_clock().now().nanoseconds)/10**9))[:10] + time = str(datetime.timedelta(seconds=float( + self.get_clock().now().nanoseconds)/10**9))[:10] if self.carla_status.fixed_delta_seconds: fps = 1 / self.carla_status.fixed_delta_seconds @@ -736,5 +737,6 @@ def main(args=None): thread.join() pygame.quit() + if __name__ == '__main__': main() diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 091fe68c..8377ec00 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -13,7 +13,8 @@ try: - import queue +from rosgraph_msgs.msg import Clock +import queue except ImportError: import Queue as queue @@ -55,7 +56,6 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -from rosgraph_msgs.msg import Clock if ROS_VERSION == 1: import rospy # pylint: disable=import-error elif ROS_VERSION == 2: @@ -132,7 +132,8 @@ def initialize_bridge(self, carla_world, params): self.clock_publisher = self.new_publisher(Clock, 'clock') elif ROS_VERSION == 2: self.clock_publisher = self.new_publisher(Clock, 'clock') - self.actor_list_publisher = self.new_publisher(CarlaActorList, "/carla/actor_list", qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.actor_list_publisher = self.new_publisher( + CarlaActorList, "/carla/actor_list", qos_profile=QoSProfile(depth=10, durability=latch_on)) self.status_publisher = CarlaStatusPublisher(self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds, self) @@ -313,7 +314,7 @@ def _carla_time_tick(self, carla_snapshot): self.timestamp_last_run = carla_snapshot.timestamp.elapsed_seconds self.update_clock(carla_snapshot.timestamp) self.status_publisher.set_frame(carla_snapshot.frame) - + self._update(carla_snapshot.frame, carla_snapshot.timestamp.elapsed_seconds) self.update_lock.release() @@ -540,7 +541,7 @@ def publish_tf_message(self, msg): """ Function to publish ROS TF message. """ - + # prepare tf message tf_msg = None tf_to_publish = [] @@ -555,6 +556,7 @@ def publish_tf_message(self, msg): except Exception as error: # pylint: disable=broad-except self.logwarn("Failed to publish message: {}".format(error)) + def main(): """ main function for carla simulator ROS bridge @@ -583,9 +585,9 @@ def main(): parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( 'carla.synchronous_mode_wait_for_vehicle_control_command', True) parameters['fixed_delta_seconds'] = carla_bridge.get_param('fixed_delta_seconds', - 0.05) + 0.05) role_name = carla_bridge.get_param('ego_vehicle_role_name', - ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) + ["hero", "ego_vehicle", "hero1", "hero2", "hero3"]) parameters["ego_vehicle"] = {"role_name": role_name} carla_bridge.loginfo("Trying to connect to {host}:{port}".format( @@ -624,7 +626,7 @@ def main(): carla_world.tick() carla_bridge.initialize_bridge(carla_client.get_world(), parameters) - + if ROS_VERSION == 1: rospy.spin() elif ROS_VERSION == 2: diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 381ad841..9abbdbf0 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -63,15 +63,14 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None, self.carla_actor.attributes)) else: self._build_camera_info() - + self.camera_info_publisher = node.new_publisher(CameraInfo, self.get_topic_prefix() + - '/camera_info') + '/camera_info') self.camera_publisher = node.new_publisher(Image, self.get_topic_prefix() + - '/' + self.get_image_topic_name()) + '/' + self.get_image_topic_name()) self.listen() - def _build_camera_info(self): """ Private function to compute camera info diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index dcdb5887..511cb73d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -38,7 +38,7 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, self).__init__(carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, is_event_sensor=True, prefix="collision", sensor_name=sensor_name) - + self.collision_publisher = node.new_publisher(CarlaCollisionEvent, self.get_topic_prefix()) self.listen() diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 1d255078..321fc789 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -35,7 +35,7 @@ def __init__(self, carla_debug_helper, node): self.debug = carla_debug_helper self.node = node self.marker_subscriber = self.node.create_subscriber(MarkerArray, "/carla/debug_marker", - self.on_marker) + self.on_marker) def destroy(self): """ @@ -92,14 +92,14 @@ def draw_arrow(self, marker, lifetime, color): z=marker.points[0].z) end = carla.Location(x=marker.points[1].x, y=-marker.points[1].y, z=marker.points[1].z) self.node.loginfo("Draw Arrow from {} to {} (color: {}, lifetime: {}, " - "thickness: {}, arrow_size: {})".format(start, end, color, lifetime, - thickness, arrow_size)) + "thickness: {}, arrow_size: {})".format(start, end, color, lifetime, + thickness, arrow_size)) self.debug.draw_arrow(start, end, thickness=thickness, arrow_size=arrow_size, color=color, life_time=lifetime) else: self.node.logwarn("Drawing arrow from Position/Orientation not yet supported. " - "Please use points.") + "Please use points.") def draw_points(self, marker, lifetime, color): """ @@ -127,7 +127,7 @@ def draw_line_strips(self, marker, lifetime, color): start = carla.Location(x=last_point.x, y=-last_point.y, z=last_point.z) end = carla.Location(x=point.x, y=-point.y, z=point.z) self.node.loginfo("Draw Line from {} to {} (color: {}, lifetime: {}, " - "thickness: {})".format(start, end, color, lifetime, thickness)) + "thickness: {})".format(start, end, color, lifetime, thickness)) self.debug.draw_line(start, end, thickness=thickness, color=color, life_time=lifetime) last_point = point diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 7735109a..3bddcb49 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -52,8 +52,10 @@ def __init__(self, carla_actor, parent, node, vehicle_control_applied_callback): """ Vehicle.__init__(self, carla_actor=carla_actor, parent=parent, node=node, prefix=carla_actor.attributes.get('role_name')) - self.vehicle_status_publisher = node.new_publisher(CarlaEgoVehicleStatus, self.get_topic_prefix() + "/vehicle_status") - self.vehicle_info_publisher = node.new_publisher(CarlaEgoVehicleInfo, self.get_topic_prefix() + "/vehicle_info", qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.vehicle_status_publisher = node.new_publisher( + CarlaEgoVehicleStatus, self.get_topic_prefix() + "/vehicle_status") + self.vehicle_info_publisher = node.new_publisher(CarlaEgoVehicleInfo, self.get_topic_prefix( + ) + "/vehicle_info", qos_profile=QoSProfile(depth=10, durability=latch_on)) if ROS_VERSION == 1: self.callback_group = None diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 960525d9..3fe9ace1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -38,7 +38,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, self).__init__(carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, is_event_sensor=True, prefix="lane_invasion", sensor_name=sensor_name) - self.lane_invasion_publisher = node.new_publisher(CarlaLaneInvasionEvent, self.get_topic_prefix()) + self.lane_invasion_publisher = node.new_publisher( + CarlaLaneInvasionEvent, self.get_topic_prefix()) self.listen() # pylint: disable=arguments-differ diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index b0105c1e..130cbe07 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -55,9 +55,9 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="Lid node=node, synchronous_mode=synchronous_mode, prefix='lidar/' + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) - + self.lidar_publisher = node.new_publisher(PointCloud2, self.get_topic_prefix() + - "/point_cloud") + "/point_cloud") self.listen() # pylint: disable=arguments-differ diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index f66ebc1d..6109d616 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -37,7 +37,7 @@ def __init__(self, parent, node, prefix=None): :param node: node-handle :type node: CompatibleNode """ - self.pub ={}#TODO + self.pub = {} # TODO self.parent = parent if self.parent: diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 97dd056d..5dfe5b71 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -37,7 +37,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="Rad node=node, synchronous_mode=synchronous_mode, prefix="radar/" + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) - self.radar_publisher = node.new_publisher(CarlaRadarMeasurement, self.get_topic_prefix() + "/radar") + self.radar_publisher = node.new_publisher( + CarlaRadarMeasurement, self.get_topic_prefix() + "/radar") self.listen() # pylint: disable=arguments-differ diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 2107b4f8..faef1ba1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -16,6 +16,7 @@ from ros_compatibility import QoSProfile, latch_on + class TrafficLightsSensor(PseudoActor): """ a sensor that reports the state of all traffic lights @@ -38,8 +39,10 @@ def __init__(self, parent, node, actor_list): self.traffic_light_status = CarlaTrafficLightStatusList() self.traffic_light_actors = [] - self.traffic_lights_info_publisher = node.new_publisher(CarlaTrafficLightInfoList, self.get_topic_prefix() + "traffic_lights_info", qos_profile=QoSProfile(depth=10, durability=latch_on)) - self.traffic_light_status_publisher = node.new_publisher(CarlaTrafficLightStatusList, self.get_topic_prefix() + "traffic_lights", qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.traffic_lights_info_publisher = node.new_publisher(CarlaTrafficLightInfoList, self.get_topic_prefix( + ) + "traffic_lights_info", qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.traffic_light_status_publisher = node.new_publisher(CarlaTrafficLightStatusList, self.get_topic_prefix( + ) + "traffic_lights", qos_profile=QoSProfile(depth=10, durability=latch_on)) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 0d9f3243..4132c4bf 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -38,7 +38,8 @@ def __init__(self, carla_actor, parent, node, prefix): self.classification_age = 0 super(TrafficParticipant, self).__init__(carla_actor=carla_actor, parent=parent, node=node, prefix=prefix) - self.odometry_publisher = node.new_publisher(Odometry, self.get_topic_prefix() + "/odometry") + self.odometry_publisher = node.new_publisher( + Odometry, self.get_topic_prefix() + "/odometry") def update(self, frame, timestamp): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index c6dfa111..42f66f2f 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -15,6 +15,7 @@ from ros_compatibility import QoSProfile, latch_on + class WorldInfo(PseudoActor): """ Publish the map @@ -35,8 +36,9 @@ def __init__(self, carla_world, node): self.carla_map = carla_world.get_map() - self.world_info_publisher = node.new_publisher(CarlaWorldInfo, self.get_topic_prefix(), qos_profile=QoSProfile(depth=10, durability=latch_on)) - + self.world_info_publisher = node.new_publisher( + CarlaWorldInfo, self.get_topic_prefix(), qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.map_published = False def destroy(self): diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 4fbb82f8..907d333a 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -163,7 +163,7 @@ class CompatibleNode(Node): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): param = Parameter('use_sim_time', Parameter.Type.BOOL, True) super(CompatibleNode, self).__init__(node_name, allow_undeclared_parameters=True, - automatically_declare_parameters_from_overrides=True, parameter_overrides=[param],**kwargs) + automatically_declare_parameters_from_overrides=True, parameter_overrides=[param], **kwargs) if latch: self.qos_profile = QoSProfile( depth=queue_size, From d27dfb92165e3729ae3fe88e4dcfcf364b4eb24c Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 22 Jul 2020 09:50:46 +0200 Subject: [PATCH 281/627] Fix import --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 8377ec00..2143cadd 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -12,9 +12,9 @@ """ -try: from rosgraph_msgs.msg import Clock -import queue +try: + import queue except ImportError: import Queue as queue From 20edac35da2cbab1a8ccc22f8db4e7bf1a9c47c1 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 22 Jul 2020 09:37:10 +0200 Subject: [PATCH 282/627] Add rss sensor --- .../src/carla_ros_bridge/bridge.py | 4 ++ .../src/carla_ros_bridge/rss_sensor.py | 40 +++++++++++++++++++ 2 files changed, 44 insertions(+) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index c667982f..dd7838b6 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -41,6 +41,7 @@ from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera from carla_ros_bridge.object_sensor import ObjectSensor +from carla_ros_bridge.rss_sensor import RssSensor from carla_ros_bridge.walker import Walker from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor @@ -418,6 +419,9 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m elif carla_actor.type_id.startswith("sensor.other.collision"): actor = CollisionSensor( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + elif carla_actor.type_id.startswith("sensor.other.rss"): + actor = RssSensor( + carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): actor = LaneInvasionSensor( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py new file mode 100644 index 00000000..5f3b0117 --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +Class to handle rss sensor +""" + +from carla_ros_bridge.actor import Actor + + +class RssSensor(Actor): + + """ + Actor implementation details for a RSS sensor + + As the RSS sensor in CARLA requires additional + utilization it's not handled as a sensor here. + """ + + def __init__(self, carla_actor, parent, communication, _): + """ + Constructor + + :param carla_actor: carla actor object + :type carla_actor: carla.Actor + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param communication: communication-handle + :type communication: carla_ros_bridge.communication + """ + + super(RssSensor, self).__init__(carla_actor=carla_actor, + parent=parent, + communication=communication, + prefix="rss") From d9ac47820a23e8fb4faea76a665da1a9d3bd18e7 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 22 Jul 2020 10:36:13 +0200 Subject: [PATCH 283/627] Fix rss-sensor, fix ros1 parameter reading --- .../launch/carla_ros_bridge.launch | 24 +++++-------------- ...ros_bridge_with_example_ego_vehicle.launch | 6 ++--- .../src/carla_ros_bridge/rss_sensor.py | 8 +++---- .../ros_compatibility/ros_compatible_node.py | 6 +++-- 4 files changed, 17 insertions(+), 27 deletions(-) diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index 17d30f7a..7a5d07ba 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -25,24 +25,12 @@ - - - - - - + + + + + + diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index d8f31704..8eb53550 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -14,9 +14,9 @@ - - - + + + diff --git a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py index 5f3b0117..0db442ec 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py @@ -22,7 +22,7 @@ class RssSensor(Actor): utilization it's not handled as a sensor here. """ - def __init__(self, carla_actor, parent, communication, _): + def __init__(self, carla_actor, parent, node, _): """ Constructor @@ -30,11 +30,11 @@ def __init__(self, carla_actor, parent, communication, _): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: CompatibleNode """ super(RssSensor, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix="rss") diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 907d333a..a439bc0c 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -60,9 +60,11 @@ def destroy(self): pass def get_param(self, name, alternative_value=None, alternative_name=None): + if name.startswith('/'): + raise RuntimeError("Only private parameters are supported.") if alternative_value is None: - return rospy.get_param(name) - return rospy.get_param(name, alternative_value) + return rospy.get_param("~" + name) + return rospy.get_param("~" + name, alternative_value) def logdebug(self, text): rospy.logdebug(text) From 1ba49c3fd1bb379da439502adb0bd31792e39cd1 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 22 Jul 2020 10:53:52 +0200 Subject: [PATCH 284/627] Fix walker and ego_vehicle --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- .../src/carla_ros_bridge/ego_vehicle.py | 14 ++++++-------- carla_ros_bridge/src/carla_ros_bridge/walker.py | 2 +- 3 files changed, 8 insertions(+), 10 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 5f61eeaa..eacac8db 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -474,7 +474,7 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): actor = CollisionSensor( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.rss"): actor = RssSensor( carla_actor, parent, self, self.carla_settings.synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 3bddcb49..674a283e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -34,7 +34,7 @@ from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error -class EgoVehicle(Vehicle, CompatibleNode): +class EgoVehicle(Vehicle): """ Vehicle implementation details for the ego vehicle """ @@ -62,33 +62,31 @@ def __init__(self, carla_actor, parent, node, vehicle_control_applied_callback): elif ROS_VERSION == 2: self.callback_group = ReentrantCallbackGroup() - CompatibleNode.__init__(self, "ego_vehicle", rospy_init=False) - self.vehicle_info = None self.vehicle_info_published = False self.vehicle_control_override = False self._vehicle_control_applied_callback = vehicle_control_applied_callback - self.control_subscriber = self.create_subscriber( + self.control_subscriber = self.node.create_subscriber( CarlaEgoVehicleControl, self.get_topic_prefix() + "/vehicle_control_cmd", lambda data: self.control_command_updated(data, manual_override=False)) - self.manual_control_subscriber = self.create_subscriber( + self.manual_control_subscriber = self.node.create_subscriber( CarlaEgoVehicleControl, self.get_topic_prefix() + "/vehicle_control_cmd_manual", lambda data: self.control_command_updated(data, manual_override=True)) - self.control_override_subscriber = self.create_subscriber( + self.control_override_subscriber = self.node.create_subscriber( Bool, self.get_topic_prefix() + "/vehicle_control_manual_override", self.control_command_override) - self.enable_autopilot_subscriber = self.create_subscriber( + self.enable_autopilot_subscriber = self.node.create_subscriber( Bool, self.get_topic_prefix() + "/enable_autopilot", self.enable_autopilot_updated) - self.twist_control_subscriber = self.create_subscriber( + self.twist_control_subscriber = self.node.create_subscriber( Twist, self.get_topic_prefix() + "/twist_cmd", self.twist_command_updated) diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index b550ace7..473f2590 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -44,7 +44,7 @@ def __init__(self, carla_actor, parent, node): super(Walker, self).__init__(carla_actor=carla_actor, parent=parent, node=node, prefix=prefix) - self.control_subscriber = self.create_subscriber( + self.control_subscriber = self.node.create_subscriber( CarlaWalkerControl, self.get_topic_prefix() + "/walker_control_cmd", self.control_command_updated) From 5b762125eee5c348734e2312b22a972cb019c65b Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 22 Jul 2020 11:10:46 +0200 Subject: [PATCH 285/627] Fix some parameters --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index eacac8db..2a6bd7a1 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -121,9 +121,10 @@ def initialize_bridge(self, carla_world, params): self.carla_settings.synchronous_mode = False carla_world.apply_settings(self.carla_settings) - self.loginfo("synchronous_mode: {}".format(self.parameters["synchronous_mode"])) + self.loginfo("Parameters:") + for key in self.parameters: + self.loginfo(" {}: {}".format(key, self.parameters[key])) self.carla_settings.synchronous_mode = self.parameters["synchronous_mode"] - self.loginfo("fixed_delta_seconds: {}".format(self.parameters["fixed_delta_seconds"])) self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) @@ -587,7 +588,7 @@ def main(): parameters['timeout'] = carla_bridge.get_param('timeout', 2) parameters['synchronous_mode'] = carla_bridge.get_param('synchronous_mode', False) parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( - 'carla.synchronous_mode_wait_for_vehicle_control_command', True) + 'synchronous_mode_wait_for_vehicle_control_command', True) parameters['fixed_delta_seconds'] = carla_bridge.get_param('fixed_delta_seconds', 0.05) role_name = carla_bridge.get_param('ego_vehicle_role_name', From 26c8c3505602f5da94217619c6e6bffe8b86b2a4 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 22 Jul 2020 11:21:10 +0200 Subject: [PATCH 286/627] Fix logging in bridge/ego-vehicle --- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 674a283e..e0bc373b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -23,7 +23,7 @@ from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleStatus # pylint: disable=import-error from carla_ros_bridge.vehicle import Vehicle -from ros_compatibility import CompatibleNode, destroy_subscription, QoSProfile, latch_on +from ros_compatibility import destroy_subscription, QoSProfile, latch_on ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -195,7 +195,7 @@ def destroy(self): :return: """ - self.logdebug("Destroy Vehicle(id={})".format(self.get_id())) + self.node.logdebug("Destroy Vehicle(id={})".format(self.get_id())) destroy_subscription(self.control_subscriber) self.control_subscriber = None destroy_subscription(self.enable_autopilot_subscriber) @@ -225,7 +225,7 @@ def twist_command_updated(self, twist): linear_velocity.y = -rotated_linear_vector[1] linear_velocity.z = rotated_linear_vector[2] - self.logdebug("Set velocity linear: {}, angular: {}".format( + self.node.logdebug("Set velocity linear: {}, angular: {}".format( linear_velocity, angular_velocity)) self.carla_actor.set_velocity(linear_velocity) self.carla_actor.set_angular_velocity(angular_velocity) @@ -269,7 +269,7 @@ def enable_autopilot_updated(self, enable_auto_pilot): :type enable_auto_pilot: std_msgs.Bool :return: """ - self.logdebug("Ego vehicle: Set autopilot to {}".format(enable_auto_pilot.data)) + self.node.logdebug("Ego vehicle: Set autopilot to {}".format(enable_auto_pilot.data)) self.carla_actor.set_autopilot(enable_auto_pilot.data) @staticmethod From c350cd1cf524c99f16b772de5f5dd7683581d856 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 22 Jul 2020 11:27:21 +0200 Subject: [PATCH 287/627] Fix log --- carla_ros_bridge/src/carla_ros_bridge/walker.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index 473f2590..bf4d4c00 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -57,7 +57,7 @@ def destroy(self): :return: """ - self.logdebug("Destroy Walker(id={})".format(self.get_id())) + self.node.logdebug("Destroy Walker(id={})".format(self.get_id())) destroy_subscription(self.control_subscriber) self.control_subscriber = None super(Walker, self).destroy() From 507cbf91fd047e0a910ae3310a11bfec8db97221 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 29 Jul 2020 10:33:58 +0200 Subject: [PATCH 288/627] Use new attributes for rgb camera --- carla_ego_vehicle/config/sensors.json | 26 +++++++++++-------- .../carla_ego_vehicle/carla_ego_vehicle.py | 2 ++ 2 files changed, 17 insertions(+), 11 deletions(-) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 0a465c4d..df1cb36d 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -7,15 +7,15 @@ "width": 800, "height": 600, "fov": 100, - "^": 0.05, + "sensor_tick": 0.05, "gamma": 2.2, - "shutter_speed": 60.0, - "iso": 1200.0, - "fstop": 1.4, + "shutter_speed": 200.0, + "iso": 200.0, + "fstop": 8.0, "min_fstop": 1.2, "blade_count": 5, "exposure_mode": "manual", - "exposure_compensation": 3.0, + "exposure_compensation": 0.0, "exposure_min_bright": 0.1, "exposure_max_bright": 2.0, "exposure_speed_up": 3.0, @@ -42,7 +42,9 @@ "lens_k": -1.0, "lens_kcube": 0.0, "lens_x_size": 0.08, - "lens_y_size": 0.08 + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 }, { "type": "sensor.camera.rgb", @@ -53,13 +55,13 @@ "fov": 100, "sensor_tick": 0.05, "gamma": 2.2, - "shutter_speed": 60.0, - "iso": 1200.0, - "fstop": 1.4, + "shutter_speed": 200.0, + "iso": 200.0, + "fstop": 8.0, "min_fstop": 1.2, "blade_count": 5, "exposure_mode": "manual", - "exposure_compensation": 3.0, + "exposure_compensation": 0.0, "exposure_min_bright": 0.1, "exposure_max_bright": 2.0, "exposure_speed_up": 3.0, @@ -86,7 +88,9 @@ "lens_k": -1.0, "lens_kcube": 0.0, "lens_x_size": 0.08, - "lens_y_size": 0.08 + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 }, { "type": "sensor.lidar.ray_cast", diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 22e3bc96..3bbad722 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -289,6 +289,8 @@ def setup_sensors(self, sensors): bp.set_attribute('lens_kcube', str(sensor_spec['lens_kcube'])) bp.set_attribute('lens_x_size', str(sensor_spec['lens_x_size'])) bp.set_attribute('lens_y_size', str(sensor_spec['lens_y_size'])) + bp.set_attribute('bloom_intensity', str(sensor_spec['bloom_intensity'])) + bp.set_attribute('lens_flare_intensity', str(sensor_spec['lens_flare_intensity'])) elif sensor_spec['type'].startswith('sensor.lidar'): bp.set_attribute('range', str(sensor_spec['range'])) bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) From 9fae680625f489bc8083f27c2d3f06be53282025 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 29 Jul 2020 10:36:52 +0200 Subject: [PATCH 289/627] Fix default fov of rgb camera --- carla_ego_vehicle/config/sensors.json | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index df1cb36d..add0f1fe 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -6,7 +6,7 @@ "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "width": 800, "height": 600, - "fov": 100, + "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, "shutter_speed": 200.0, @@ -52,7 +52,7 @@ "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, "width": 800, "height": 600, - "fov": 100, + "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, "shutter_speed": 200.0, From e5f75cecb01f9563a00b6ca665d8ce6f086ad140 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 29 Jul 2020 10:39:36 +0200 Subject: [PATCH 290/627] Fix rgb camera attributes --- CHANGELOG.md | 1 + README.md | 2 +- carla_ego_vehicle/config/sensors.json | 28 +++++++++++-------- .../carla_ego_vehicle/carla_ego_vehicle.py | 2 ++ 4 files changed, 20 insertions(+), 13 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index c3db8d88..30c56366 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Fix rgb camera attributes * Add intensity value to point cloud message * Fixed wrong TF for ego_vehicle * Improve version check diff --git a/README.md b/README.md index 63a73345..8f0dc472 100644 --- a/README.md +++ b/README.md @@ -4,7 +4,7 @@ This ROS package aims at providing a simple ROS bridge for CARLA simulator. ![rviz setup](./docs/images/rviz_carla_default.png "rviz") -**This version requires CARLA 0.9.9** +**This version requires CARLA 0.9.9.5** ## Features diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index c0e8e0f7..add0f1fe 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -6,16 +6,16 @@ "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "width": 800, "height": 600, - "fov": 100, + "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, - "shutter_speed": 60.0, - "iso": 1200.0, - "fstop": 1.4, + "shutter_speed": 200.0, + "iso": 200.0, + "fstop": 8.0, "min_fstop": 1.2, "blade_count": 5, "exposure_mode": "manual", - "exposure_compensation": 3.0, + "exposure_compensation": 0.0, "exposure_min_bright": 0.1, "exposure_max_bright": 2.0, "exposure_speed_up": 3.0, @@ -42,7 +42,9 @@ "lens_k": -1.0, "lens_kcube": 0.0, "lens_x_size": 0.08, - "lens_y_size": 0.08 + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 }, { "type": "sensor.camera.rgb", @@ -50,16 +52,16 @@ "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, "width": 800, "height": 600, - "fov": 100, + "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, - "shutter_speed": 60.0, - "iso": 1200.0, - "fstop": 1.4, + "shutter_speed": 200.0, + "iso": 200.0, + "fstop": 8.0, "min_fstop": 1.2, "blade_count": 5, "exposure_mode": "manual", - "exposure_compensation": 3.0, + "exposure_compensation": 0.0, "exposure_min_bright": 0.1, "exposure_max_bright": 2.0, "exposure_speed_up": 3.0, @@ -86,7 +88,9 @@ "lens_k": -1.0, "lens_kcube": 0.0, "lens_x_size": 0.08, - "lens_y_size": 0.08 + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 }, { "type": "sensor.lidar.ray_cast", diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index dc9abcce..030dd47a 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -258,6 +258,8 @@ def setup_sensors(self, sensors): bp.set_attribute('lens_kcube', str(sensor_spec['lens_kcube'])) bp.set_attribute('lens_x_size', str(sensor_spec['lens_x_size'])) bp.set_attribute('lens_y_size', str(sensor_spec['lens_y_size'])) + bp.set_attribute('bloom_intensity', str(sensor_spec['bloom_intensity'])) + bp.set_attribute('lens_flare_intensity', str(sensor_spec['lens_flare_intensity'])) elif sensor_spec['type'].startswith('sensor.lidar'): bp.set_attribute('range', str(sensor_spec['range'])) bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) From 18a19f90e79d1631f9c36a118c89307d915b7e1e Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 29 Jul 2020 10:43:13 +0200 Subject: [PATCH 291/627] Read town parameter --- carla_msgs | 2 +- carla_ros_bridge/launch/carla_ros_bridge.launch | 2 +- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 1 + 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/carla_msgs b/carla_msgs index 06bf63d0..c89458b3 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 06bf63d0d959feed73c427857c030269f3d79620 +Subproject commit c89458b34aefbe7e12cefe3241c3b48f4a9b35d7 diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index 7a5d07ba..8d8ab1bb 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -15,7 +15,7 @@ - + - + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index 9c618993..6d258869 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -4,7 +4,7 @@ - + diff --git a/carla_ego_vehicle/launch/carla_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_ego_vehicle.launch index 3b12e060..ecc6be22 100644 --- a/carla_ego_vehicle/launch/carla_ego_vehicle.launch +++ b/carla_ego_vehicle/launch/carla_ego_vehicle.launch @@ -2,7 +2,7 @@ - + diff --git a/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch index e3072989..9026a127 100644 --- a/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch +++ b/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch @@ -2,7 +2,7 @@ - + diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 77373033..c0975be0 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -49,8 +49,8 @@ class CarlaEgoVehicle(object): def __init__(self): rospy.init_node('ego_vehicle', anonymous=True) self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', '2000') - self.timeout = rospy.get_param('/carla/timeout', '2') + self.port = rospy.get_param('/carla/port', 2000) + self.timeout = rospy.get_param('/carla/timeout', 10) self.sensor_definition_file = rospy.get_param('~sensor_definition_file') self.world = None self.player = None diff --git a/carla_infrastructure/launch/carla_infrastructure.launch b/carla_infrastructure/launch/carla_infrastructure.launch index 74849f4a..6fa4dddd 100644 --- a/carla_infrastructure/launch/carla_infrastructure.launch +++ b/carla_infrastructure/launch/carla_infrastructure.launch @@ -2,7 +2,7 @@ - + diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 64d0ac7e..a2dc6669 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -32,8 +32,8 @@ class CarlaInfrastructure(object): def __init__(self): rospy.init_node('infrastructure', anonymous=True) self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', '2000') - self.timeout = rospy.get_param('/carla/timeout', '2') + self.port = rospy.get_param('/carla/port', 2000) + self.timeout = rospy.get_param('/carla/timeout', 10) self.sensor_definition_file = rospy.get_param('~infrastructure_sensor_definition_file') self.world = None self.sensor_actors = [] diff --git a/carla_ros_bridge/config/settings.yaml b/carla_ros_bridge/config/settings.yaml index 103d6a66..991fd791 100644 --- a/carla_ros_bridge/config/settings.yaml +++ b/carla_ros_bridge/config/settings.yaml @@ -3,7 +3,7 @@ carla: # the network connection for the python connection to CARLA host: localhost port: 2000 - timeout: 2 + timeout: 10 # enable/disable synchronous mode. If enabled ros-bridge waits until # expected data is received for all sensors synchronous_mode: false diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index d8f31704..e96a7e37 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -3,7 +3,7 @@ - + diff --git a/carla_spectator_camera/launch/carla_spectator_camera.launch b/carla_spectator_camera/launch/carla_spectator_camera.launch index 16c10aec..4da884a4 100644 --- a/carla_spectator_camera/launch/carla_spectator_camera.launch +++ b/carla_spectator_camera/launch/carla_spectator_camera.launch @@ -2,7 +2,7 @@ - + diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 898fac23..b9f3e332 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -45,8 +45,8 @@ def __init__(self): self.camera_resolution_y = rospy.get_param("~resolution_y", 600) self.camera_fov = rospy.get_param("~fov", 50) self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', '2000') - self.timeout = rospy.get_param("/carla/timeout", 2) + self.port = rospy.get_param('/carla/port', 2000) + self.timeout = rospy.get_param("/carla/timeout", 10) self.world = None self.pose = None self.camera_actor = None diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch index c33ca134..2f7a9614 100644 --- a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch @@ -2,7 +2,7 @@ - + diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 6e7276d0..fce5b3a7 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -266,7 +266,7 @@ def main(): host = rospy.get_param("/carla/host", "127.0.0.1") port = rospy.get_param("/carla/port", 2000) - timeout = rospy.get_param("/carla/timeout", 2) + timeout = rospy.get_param("/carla/timeout", 10) rospy.loginfo("CARLA world available. Trying to connect to {host}:{port}".format( host=host, port=port)) From a279461d7cde8f6d85bd0013ba201b78a53c24b6 Mon Sep 17 00:00:00 2001 From: "Kai A. Hiller" Date: Wed, 12 Aug 2020 08:01:45 +0200 Subject: [PATCH 295/627] [ROS2] Fix crash when using an ego vehicle (#346) * Fix crash when using EgoVehicle --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 95594892..4db38f23 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -446,8 +446,6 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m pseudo_actors.append( ObjectSensor(parent=actor, node=self, actor_list=self.actors, filtered_id=carla_actor.id)) - if ROS_VERSION == 2: - self.executor.add_node(actor) else: actor = Vehicle(carla_actor, parent, self) elif carla_actor.type_id.startswith("sensor"): From bb45a08f65b28e2334713a13499eca2fa6c9bd1b Mon Sep 17 00:00:00 2001 From: "Kai A. Hiller" Date: Tue, 18 Aug 2020 08:03:25 +0200 Subject: [PATCH 296/627] [ROS2] Make Vehicle conform to topic naming rules (#349) * Make Vehicle conform to ROS2 topic naming rules --- carla_ros_bridge/src/carla_ros_bridge/vehicle.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 4a8133de..b615042b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -34,7 +34,7 @@ def __init__(self, carla_actor, parent, node, prefix=None): :type prefix: string """ if not prefix: - prefix = "vehicle/{:03}".format(carla_actor.id) + prefix = "vehicle/v{:03}".format(carla_actor.id) self.classification = Object.CLASSIFICATION_CAR if 'object_type' in carla_actor.attributes: From 0fa31358c8218cff3b0570feb52b8c232eeb2f5f Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 18 Aug 2020 08:13:02 +0200 Subject: [PATCH 297/627] walker: add prefix + update doc/format --- Makefile | 2 +- README.md | 6 +++--- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 3 ++- carla_ros_bridge/src/carla_ros_bridge/walker.py | 2 +- ros_compatibility/__init__.py | 3 ++- ros_compatibility/src/ros_compatibility/__init__.py | 3 ++- 6 files changed, 11 insertions(+), 8 deletions(-) diff --git a/Makefile b/Makefile index 79d045f4..df30d6a2 100644 --- a/Makefile +++ b/Makefile @@ -1,4 +1,4 @@ -file_finder = find . -type f $(1) -not \( -path './venv/*' -o -path './carla_msgs/*' \) +file_finder = find . -type f $(1) -not \( -path './venv/*' -o -path './carla_msgs/*' -o -path './astuff_sensor_msgs/*' \) CMAKE_FILES = $(call file_finder,-name "*.cmake" -o -name "CMakeLists.txt") PY_FILES = $(call file_finder,-name "*.py") diff --git a/README.md b/README.md index 8f0dc472..29638b7b 100644 --- a/README.md +++ b/README.md @@ -289,14 +289,14 @@ You can find further documentation [here](carla_ackermann_control/README.md). | Topic | Type | Description | | ---------------------------------------------------- | ---------------------------------------------------------------------------- | ------------------ | -| `/carla/walker//walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWalkerControl.msg) | Control a walker | -| `/carla/walker//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of walker | +| `/carla/walker/w/walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWalkerControl.msg) | Control a walker | +| `/carla/walker/w/odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of walker | ### Other Vehicles | Topic | Type | Description | | ------------------------------ | ---------------------------------------------------------------------------- | ------------------- | -| `/carla/vehicle//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of vehicle | +| `/carla/vehicle/v/odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of vehicle | ### TF diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 3bbad722..c92f7d0a 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -290,7 +290,8 @@ def setup_sensors(self, sensors): bp.set_attribute('lens_x_size', str(sensor_spec['lens_x_size'])) bp.set_attribute('lens_y_size', str(sensor_spec['lens_y_size'])) bp.set_attribute('bloom_intensity', str(sensor_spec['bloom_intensity'])) - bp.set_attribute('lens_flare_intensity', str(sensor_spec['lens_flare_intensity'])) + bp.set_attribute('lens_flare_intensity', str( + sensor_spec['lens_flare_intensity'])) elif sensor_spec['type'].startswith('sensor.lidar'): bp.set_attribute('range', str(sensor_spec['range'])) bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index bf4d4c00..4eed1d90 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -39,7 +39,7 @@ def __init__(self, carla_actor, parent, node): if carla_actor.attributes.get('role_name'): prefix = carla_actor.attributes.get('role_name') else: - prefix = "walker/{:03}".format(carla_actor.id) + prefix = "walker/w{:03}".format(carla_actor.id) super(Walker, self).__init__(carla_actor=carla_actor, parent=parent, node=node, prefix=prefix) diff --git a/ros_compatibility/__init__.py b/ros_compatibility/__init__.py index 0c1cfee4..40ee4640 100644 --- a/ros_compatibility/__init__.py +++ b/ros_compatibility/__init__.py @@ -1 +1,2 @@ -from ros_compatibility.src.ros_compatibility.ros_compatible_node import * \ No newline at end of file +from ros_compatibility.src.ros_compatibility.ros_compatible_node import * + diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py index acb7f1fe..4aa29b2a 100644 --- a/ros_compatibility/src/ros_compatibility/__init__.py +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -1,2 +1,3 @@ # pylint: disable=no-name-in-module,import-error -from ros_compatibility.ros_compatible_node import * \ No newline at end of file +from ros_compatibility.ros_compatible_node import * + From daa65e24d3d7f27e255cc82f9d846d16f50764aa Mon Sep 17 00:00:00 2001 From: "Kai A. Hiller" Date: Tue, 18 Aug 2020 09:51:06 +0200 Subject: [PATCH 298/627] [ROS2] Fix attribute types of ColorRGBA instances (#350) * Fix ColorRGBA initialization --- carla_ros_bridge/src/carla_ros_bridge/actor.py | 6 +++--- carla_ros_bridge/src/carla_ros_bridge/vehicle.py | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 64f37a61..f9933d48 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -139,9 +139,9 @@ def get_marker_color(self): # pylint: disable=no-self-use :rtpye : std_msgs.msg.ColorRGBA """ color = ColorRGBA() - color.r = 0 - color.g = 0 - color.b = 255 + color.r = 0.0 + color.g = 0.0 + color.b = 255.0 return color def get_marker(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index b615042b..cd97437b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -60,9 +60,9 @@ def get_marker_color(self): # pylint: disable=no-self-use :rtpye : std_msgs.msg.ColorRGBA """ color = ColorRGBA() - color.r = 255 - color.g = 0 - color.b = 0 + color.r = 255.0 + color.g = 0.0 + color.b = 0.0 return color def get_classification(self): From 09ff422ff3ad2a857a87bef5aa062a5f91281416 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 20 Aug 2020 09:01:57 +0200 Subject: [PATCH 299/627] Freeze cmake-format version --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index f4d928b5..40b81a82 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,6 +1,6 @@ pep8 autopep8 -cmake_format +cmake_format==0.6.11 pylint pexpect simple-pid From 02e0981b6ddc97a3b4966a6a78924c82a8d61f25 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Thu, 20 Aug 2020 10:18:49 +0200 Subject: [PATCH 300/627] add some editor config folders to the gitignore (#353) * add some editor config folders to the gitignore * Merge branch 'master' into editor_ignores --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index 1f93b7e8..cef1d6ac 100644 --- a/.gitignore +++ b/.gitignore @@ -2,3 +2,6 @@ build.gradle /CMakeLists.txt .catkin_workspace + +.vscode +.idea From f4e1b5cc701082b9e9d07e870f5420736e24e4ee Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Wed, 2 Sep 2020 11:02:44 +0200 Subject: [PATCH 301/627] Python 3 Support (#352) * replace iteritems with items * run code format --- carla_ad_agent/src/carla_ad_agent/agent.py | 2 +- .../src/carla_ad_agent/basic_agent.py | 4 +- .../src/carla_ad_agent/carla_ad_agent.py | 2 +- .../src/carla_ad_agent/local_planner.py | 4 +- .../carla_manual_control.py | 9 ++-- .../src/carla_ros_bridge/bridge.py | 47 ++++++++++++------- .../src/carla_ros_bridge/lidar.py | 1 + .../carla_ros_scenario_runner.py | 4 +- .../ros_vehicle_control.py | 2 +- .../scenario_runner_runner.py | 4 +- 10 files changed, 48 insertions(+), 31 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 170f7914..610cafe9 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -13,7 +13,7 @@ import math import rospy from tf.transformations import euler_from_quaternion -from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import +from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus,\ CarlaTrafficLightStatusList, CarlaWorldInfo from carla_waypoint_types.srv import GetWaypoint diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index acded855..ba0cec6c 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -16,8 +16,8 @@ from geometry_msgs.msg import Pose from derived_object_msgs.msg import ObjectArray from carla_msgs.msg import CarlaActorList -from agent import Agent, AgentState # pylint: disable=relative-import -from local_planner import LocalPlanner # pylint: disable=relative-import +from agent import Agent, AgentState # pylint: disable=relative-import +from local_planner import LocalPlanner # pylint: disable=relative-import from carla_waypoint_types.srv import GetActorWaypoint diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 94b9e9a5..6136f994 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -13,7 +13,7 @@ from nav_msgs.msg import Path from std_msgs.msg import Float64 from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl -from basic_agent import BasicAgent # pylint: disable=relative-import +from basic_agent import BasicAgent # pylint: disable=relative-import class CarlaAdAgent(object): diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 2b59514d..dcb2e511 100644 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -14,8 +14,8 @@ import rospy from geometry_msgs.msg import PointStamped from carla_msgs.msg import CarlaEgoVehicleControl -from vehicle_pid_controller import VehiclePIDController # pylint: disable=relative-import -from misc import distance_vehicle # pylint: disable=relative-import +from vehicle_pid_controller import VehiclePIDController # pylint: disable=relative-import +from misc import distance_vehicle # pylint: disable=relative-import class LocalPlanner(object): diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 6ac9061f..57eb4107 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -441,7 +441,8 @@ def render(self, display): render the display """ if self._show_info: - info_surface = pygame.Surface((220, self.dim[1])) # pylint: disable=too-many-function-args + info_surface = pygame.Surface( + (220, self.dim[1])) # pylint: disable=too-many-function-args info_surface.set_alpha(100) display.blit(info_surface, (0, 0)) v_offset = 4 @@ -495,14 +496,14 @@ def __init__(self, font, dim, pos): self.dim = dim self.pos = pos self.seconds_left = 0 - self.surface = pygame.Surface(self.dim) # pylint: disable=too-many-function-args + self.surface = pygame.Surface(self.dim) # pylint: disable=too-many-function-args def set_text(self, text, color=(255, 255, 255), seconds=2.0): """ set the text """ text_texture = self.font.render(text, True, color) - self.surface = pygame.Surface(self.dim) # pylint: disable=too-many-function-args + self.surface = pygame.Surface(self.dim) # pylint: disable=too-many-function-args self.seconds_left = seconds self.surface.fill((0, 0, 0, 0)) self.surface.blit(text_texture, (10, 11)) @@ -537,7 +538,7 @@ def __init__(self, font, width, height): self.dim = (680, len(lines) * 22 + 12) self.pos = (0.5 * width - 0.5 * self.dim[0], 0.5 * height - 0.5 * self.dim[1]) self.seconds_left = 0 - self.surface = pygame.Surface(self.dim) # pylint: disable=too-many-function-args + self.surface = pygame.Surface(self.dim) # pylint: disable=too-many-function-args self.surface.fill((0, 0, 0, 0)) for n, line in enumerate(lines): text_texture = self.font.render(line, True, (255, 255, 255)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index dd7838b6..62f29abc 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -80,9 +80,11 @@ def __init__(self, carla_world, params): self.carla_settings.synchronous_mode = False carla_world.apply_settings(self.carla_settings) - rospy.loginfo("synchronous_mode: {}".format(self.parameters["synchronous_mode"])) + rospy.loginfo("synchronous_mode: {}".format( + self.parameters["synchronous_mode"])) self.carla_settings.synchronous_mode = self.parameters["synchronous_mode"] - rospy.loginfo("fixed_delta_seconds: {}".format(self.parameters["fixed_delta_seconds"])) + rospy.loginfo("fixed_delta_seconds: {}".format( + self.parameters["fixed_delta_seconds"])) self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) @@ -109,7 +111,8 @@ def __init__(self, carla_world, params): rospy.Subscriber("/carla/control", CarlaControl, lambda control: self.carla_control_queue.put(control.command)) - self.synchronous_mode_update_thread = Thread(target=self._synchronous_mode_update) + self.synchronous_mode_update_thread = Thread( + target=self._synchronous_mode_update) self.synchronous_mode_update_thread.start() else: self.timestamp_last_run = 0.0 @@ -117,11 +120,13 @@ def __init__(self, carla_world, params): self.update_actors_queue = queue.Queue(maxsize=1) # start thread to update actors - self.update_actor_thread = Thread(target=self._update_actors_thread) + self.update_actor_thread = Thread( + target=self._update_actors_thread) self.update_actor_thread.start() # create initially existing actors - self.update_actors_queue.put(set([x.id for x in self.carla_world.get_snapshot()])) + self.update_actors_queue.put( + set([x.id for x in self.carla_world.get_snapshot()])) # wait for first actors creation to be finished self.update_actors_queue.join() @@ -227,9 +232,10 @@ def _synchronous_mode_update(self): # fill list of available ego vehicles self._expected_ego_vehicle_control_command_ids = [] with self._expected_ego_vehicle_control_command_ids_lock: - for actor_id, actor in self.actors.iteritems(): + for actor_id, actor in self.actors.items(): if isinstance(actor, EgoVehicle): - self._expected_ego_vehicle_control_command_ids.append(actor_id) + self._expected_ego_vehicle_control_command_ids.append( + actor_id) frame = self.carla_world.tick() world_snapshot = self.carla_world.get_snapshot() @@ -272,13 +278,15 @@ def _carla_time_tick(self, carla_snapshot): self.timestamp_last_run = carla_snapshot.timestamp.elapsed_seconds self.comm.update_clock(carla_snapshot.timestamp) self.status_publisher.set_frame(carla_snapshot.frame) - self._update(carla_snapshot.frame, carla_snapshot.timestamp.elapsed_seconds) + self._update(carla_snapshot.frame, + carla_snapshot.timestamp.elapsed_seconds) self.comm.send_msgs() self.update_lock.release() # if possible push current snapshot to update-actors-thread try: - self.update_actors_queue.put_nowait(set([x.id for x in carla_snapshot])) + self.update_actors_queue.put_nowait( + set([x.id for x in carla_snapshot])) except queue.Full: pass @@ -362,7 +370,8 @@ def publish_actor_list(self): ros_actor_list.actors.append(ros_actor) - self.comm.publish_message("/carla/actor_list", ros_actor_list, is_latched=True) + self.comm.publish_message( + "/carla/actor_list", ros_actor_list, is_latched=True) def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-many-statements """ @@ -408,11 +417,14 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m actor = Camera( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.lidar"): - actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Lidar(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): - actor = Radar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Radar(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): - actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Gnss(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): actor = ImuSensor( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) @@ -426,7 +438,8 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m actor = LaneInvasionSensor( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) else: - actor = Sensor(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + actor = Sensor(carla_actor, parent, self.comm, + self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("spectator"): actor = Spectator(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("walker"): @@ -497,7 +510,8 @@ def _ego_vehicle_control_applied_callback(self, ego_vehicle_id): return with self._expected_ego_vehicle_control_command_ids_lock: if ego_vehicle_id in self._expected_ego_vehicle_control_command_ids: - self._expected_ego_vehicle_control_command_ids.remove(ego_vehicle_id) + self._expected_ego_vehicle_control_command_ids.remove( + ego_vehicle_id) else: rospy.logwarn( "Unexpected vehicle control command received from {}".format(ego_vehicle_id)) @@ -541,7 +555,8 @@ def main(): if "town" in parameters: if parameters["town"].endswith(".xodr"): - rospy.loginfo("Loading opendrive world from file '{}'".format(parameters["town"])) + rospy.loginfo( + "Loading opendrive world from file '{}'".format(parameters["town"])) with open(parameters["town"]) as od_file: data = od_file.read() carla_world = carla_client.generate_opendrive_world(str(data)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index cd920d19..12810f8a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -17,6 +17,7 @@ from carla_ros_bridge.sensor import Sensor + class Lidar(Sensor): """ diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py index 8aaa1ad9..a23e83d6 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -19,8 +19,8 @@ import rospy from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus -from application_runner import ApplicationStatus # pylint: disable=relative-import -from scenario_runner_runner import ScenarioRunnerRunner # pylint: disable=relative-import +from application_runner import ApplicationStatus # pylint: disable=relative-import +from scenario_runner_runner import ScenarioRunnerRunner # pylint: disable=relative-import # Check Python dependencies of scenario runner try: diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 4bf8b3c4..50b07fd1 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -15,7 +15,7 @@ from geometry_msgs.msg import PoseStamped from nav_msgs.msg import Path import carla_common.transforms as trans -from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error +from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error class RosVehicleControl(BasicControl): diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py index 3767983e..dae0a416 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py @@ -6,7 +6,7 @@ Executes scenario runner """ import os -from application_runner import ApplicationRunner # pylint: disable=relative-import +from application_runner import ApplicationRunner # pylint: disable=relative-import class ScenarioRunnerRunner(ApplicationRunner): @@ -14,7 +14,7 @@ class ScenarioRunnerRunner(ApplicationRunner): Executes scenario runner """ - def __init__(self, path, host, port, wait_for_ego, status_updated_fct, log_fct): # pylint: disable=too-many-arguments + def __init__(self, path, host, port, wait_for_ego, status_updated_fct, log_fct): # pylint: disable=too-many-arguments self._path = path self._host = host self._port = port From 51d3a6c5c19d72532c9f48c423d27cb219d891d7 Mon Sep 17 00:00:00 2001 From: jbmag Date: Thu, 3 Sep 2020 09:01:48 +0200 Subject: [PATCH 302/627] added networkx in requirements.txt --- requirements.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/requirements.txt b/requirements.txt index 40b81a82..fadd0e5e 100644 --- a/requirements.txt +++ b/requirements.txt @@ -4,3 +4,4 @@ cmake_format==0.6.11 pylint pexpect simple-pid +networkx \ No newline at end of file From 0556f05d086b6d43c6f91f073d116654b3c84969 Mon Sep 17 00:00:00 2001 From: jbmag <47941074+jbmag@users.noreply.github.com> Date: Thu, 3 Sep 2020 17:47:56 +0200 Subject: [PATCH 303/627] Fix params sensor for carla_ad_demo * fix 'bloom_intensity' error, corresponding parameter was missing from sensors.json * corrected camera parameters in sensors.json of carla_ad_demo, to the recommended values from 'ActorBlueprintFunctionLibrary.cpp' --- carla_ad_demo/config/sensors.json | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json index 3d8fe104..92b99b04 100644 --- a/carla_ad_demo/config/sensors.json +++ b/carla_ad_demo/config/sensors.json @@ -6,16 +6,16 @@ "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, "width": 800, "height": 600, - "fov": 100, + "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, - "shutter_speed": 60.0, - "iso": 1200.0, - "fstop": 1.4, + "shutter_speed": 200.0, + "iso": 200.0, + "fstop": 8.0, "min_fstop": 1.2, "blade_count": 5, "exposure_mode": "manual", - "exposure_compensation": 3.0, + "exposure_compensation": -2.2, "exposure_min_bright": 0.1, "exposure_max_bright": 2.0, "exposure_speed_up": 3.0, @@ -42,7 +42,9 @@ "lens_k": -1.0, "lens_kcube": 0.0, "lens_x_size": 0.08, - "lens_y_size": 0.08 + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 } ] } From 69aee669ae7181fc8e1e2c8fb3dddcda83a43ef8 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Sun, 6 Sep 2020 11:57:49 +0200 Subject: [PATCH 304/627] Updated user installtion process (#363) * Updated user installtion process * Developer installation process updated * Merge branch 'master' into joel-mb/docs_debian_package --- README.md | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/README.md b/README.md index 8f0dc472..5f397626 100644 --- a/README.md +++ b/README.md @@ -39,20 +39,15 @@ For a quick overview, after following the [Setup section](#setup), please run th First add the apt repository: -##### For ROS Melodic Users - sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 81061A1A042F527D && - sudo add-apt-repository "deb [arch=amd64 trusted=yes] http://dist.carla.org/carla-ros-bridge-melodic/ bionic main" - -##### For ROS Kinetic Users - sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 9BE2A0CDC0161D6C && - sudo add-apt-repository "deb [arch=amd64 trusted=yes] http://dist.carla.org/carla-ros-bridge-kinetic xenial main" + sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 1AF1527DE64CB8D9 + sudo add-apt-repository "deb [arch=amd64] http://dist.carla.org/carla $(lsb_release -sc) main" Then simply install the ROS bridge: - sudo apt update && - sudo apt install carla-ros-bridge- + sudo apt-get update + sudo apt-get install carla-ros-bridge -This will install carla-ros-bridge- in /opt/carla-ros-bridge +This will install carla-ros-bridge in /opt/carla-ros-bridge ### For Developers @@ -66,7 +61,7 @@ This will install carla-ros-bridge- in /opt/carla-ros-bridge git submodule update --init cd ../catkin_ws/src ln -s ../../ros-bridge - source /opt/ros/kinetic/setup.bash + source /opt/ros//setup.bash cd .. #install required ros-dependencies From d40488aab09f4e6ecd88e23f731ac5db9a174e91 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 21 Sep 2020 09:52:02 +0200 Subject: [PATCH 305/627] Fix codacy issue --- docker/run.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docker/run.sh b/docker/run.sh index 1f0499a2..9fd597dc 100755 --- a/docker/run.sh +++ b/docker/run.sh @@ -32,4 +32,4 @@ shift $((OPTIND-1)) echo "Using $DOCKER_IMAGE_NAME:$TAG" -docker run -it --rm $DOCKER_IMAGE_NAME:$TAG "$@" +docker run -it --rm "$DOCKER_IMAGE_NAME:$TAG" "$@" From 4b6c82c4222f3d37cae4e59d5657944401cf4ba3 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Mon, 21 Sep 2020 10:29:04 +0200 Subject: [PATCH 306/627] Supporting ros noetic (#323) - use cpp 14 - replace easyinstall with pythonpath in dockerfile - disable pylint for python 3 - fix travis build - fix catkin build - trigger travis Co-authored-by: fpasch <46815108+fpasch@users.noreply.github.com> --- .travis.yml | 47 ++++++++++++++++++++------------ docker/Dockerfile | 25 ++++++++++++----- pcl_recorder/CMakeLists.txt | 6 ++-- rviz_carla_plugin/CMakeLists.txt | 4 ++- 4 files changed, 54 insertions(+), 28 deletions(-) diff --git a/.travis.yml b/.travis.yml index 44f453dc..eaf1fb28 100644 --- a/.travis.yml +++ b/.travis.yml @@ -8,17 +8,17 @@ os: linux stages: - - check - - test - - docker + - check + - test + - docker cache: - - apt + - apt addons: - apt: - packages: - - python-pip + apt: + packages: + - python-pip jobs: include: @@ -31,30 +31,43 @@ jobs: - name: "Xenial Kinetic" stage: test dist: xenial - env: ROS_DISTRO=kinetic + env: + - ROS_DISTRO=kinetic + - PYTHON_SUFFIX="" - name: "Bionic Melodic" dist: bionic - env: ROS_DISTRO=melodic - - name: "Docker Kinetic" + env: + - ROS_DISTRO=melodic + - PYTHON_SUFFIX="" + - name: "Focal Noetic" + dist: focal + env: + - ROS_DISTRO=noetic + - PYTHON_SUFFIX=3 + addons: + apt: + packages: + - python3-pip + - name: "Docker Melodic" stage: docker services: docker before_install: skip install: skip - script: cd docker && ./build.sh --build-arg ROS_VERSION=kinetic - - name: "Docker Melodic" + script: cd docker && ./build.sh --build-arg ROS_VERSION=melodic + - name: "Docker Noetic" services: docker before_install: skip install: skip - script: cd docker && ./build.sh --build-arg ROS_VERSION=melodic + script: cd docker && ./build.sh --build-arg ROS_VERSION=noetic --build-arg PYTHON_VERSION=3.7 before_install: - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' - sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 - sudo apt update - - sudo apt install -y ros-$ROS_DISTRO-desktop-full python-catkin-tools python-catkin-pkg python-catkin-pkg-modules python-rosdep python-wstool + - sudo apt install -y ros-$ROS_DISTRO-desktop-full python$PYTHON_SUFFIX-osrf-pycommon python$PYTHON_SUFFIX-catkin-tools python$PYTHON_SUFFIX-catkin-pkg python$PYTHON_SUFFIX-catkin-pkg-modules python$PYTHON_SUFFIX-rosdep python$PYTHON_SUFFIX-wstool install: - - pip install --user -r requirements.txt + - pip$PYTHON_SUFFIX install --user -r requirements.txt - mkdir ros-bridge/ - shopt -s dotglob - shopt -s extglob @@ -70,12 +83,12 @@ install: script: - catkin build - - export SCENARIO_RUNNER_PATH="" # the env var needs to be set for testing + - export SCENARIO_RUNNER_PATH="" # the env var needs to be set for testing - if [ ! $ROS_DISTRO -eq kinetic ]; then catkin test; fi; - catkin config --install - source devel/setup.bash - cd src/ros-bridge - - make pylint + - if [ ! $ROS_DISTRO -eq noetic ]; then make pylint; fi; after_failure: - tail --lines=2000 build.log diff --git a/docker/Dockerfile b/docker/Dockerfile index 49e024f0..ec5476b3 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -1,6 +1,7 @@ -ARG CARLA_VERSION='0.9.6' -ARG ROS_VERSION='kinetic' +ARG CARLA_VERSION='0.9.9' +ARG ROS_VERSION='melodic' ARG CARLA_BUILD='' +ARG PYTHON_VERSION='2.7' FROM carlasim/carla:$CARLA_VERSION$CARLA_BUILD as carla @@ -8,30 +9,40 @@ FROM ros:$ROS_VERSION-ros-base ARG ROS_VERSION -RUN apt-get update \ - && apt-get install -y --no-install-recommends \ +RUN apt-get update && \ + if [ "$ROS_VERSION" = "noetic" ] ; then export PYTHON_SUFFIX=3 ; else export PYTHON_SUFFIX="" ; fi && \ + apt-get install -y --no-install-recommends \ libpng16-16 \ ros-$ROS_VERSION-ackermann-msgs \ - ros-$ROS_VERSION-derived-object-msgs \ ros-$ROS_VERSION-tf \ + ros-$ROS_VERSION-derived-object-msgs \ ros-$ROS_VERSION-cv-bridge \ ros-$ROS_VERSION-pcl-conversions \ ros-$ROS_VERSION-pcl-ros \ - python-catkin-tools \ + python$PYTHON_SUFFIX-osrf-pycommon \ + python$PYTHON_SUFFIX-catkin-tools \ && rm -rf /var/lib/apt/lists/* ARG CARLA_VERSION +ARG PYTHON_VERSION COPY --from=carla --chown=root /home/carla/PythonAPI /opt/carla/PythonAPI -RUN python -m easy_install /opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py2.7-linux-x86_64.egg +ENV PYTHONPATH=/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py$PYTHON_VERSION-linux-x86_64.egg COPY carla_ackermann_control /opt/carla-ros-bridge/src/carla_ackermann_control +COPY carla_common /opt/carla-ros-bridge/src/carla_common COPY carla_ego_vehicle /opt/carla-ros-bridge/src/carla_ego_vehicle COPY carla_infrastructure /opt/carla-ros-bridge/src/carla_infrastructure COPY carla_manual_control /opt/carla-ros-bridge/src/carla_manual_control COPY carla_msgs /opt/carla-ros-bridge/src/carla_msgs COPY carla_ros_bridge /opt/carla-ros-bridge/src/carla_ros_bridge +COPY carla_ros_scenario_runner /opt/carla-ros-bridge/src/carla_ros_scenario_runner +COPY carla_ros_scenario_runner_types /opt/carla-ros-bridge/src/carla_ros_scenario_runner_types +COPY carla_spectator_camera /opt/carla-ros-bridge/src/carla_spectator_camera +COPY carla_twist_to_control /opt/carla-ros-bridge/src/carla_twist_to_control +COPY carla_walker_agent /opt/carla-ros-bridge/src/carla_walker_agent COPY carla_waypoint_publisher /opt/carla-ros-bridge/src/carla_waypoint_publisher +COPY carla_waypoint_types /opt/carla-ros-bridge/src/carla_waypoint_types COPY pcl_recorder /opt/carla-ros-bridge/src/pcl_recorder RUN /bin/bash -c 'source /opt/ros/$ROS_VERSION/setup.bash; cd /opt/carla-ros-bridge; catkin config --install; catkin build --cmake-args -DCMAKE_BUILD_TYPE=Release' diff --git a/pcl_recorder/CMakeLists.txt b/pcl_recorder/CMakeLists.txt index 068ed8b3..fe8b16bf 100644 --- a/pcl_recorder/CMakeLists.txt +++ b/pcl_recorder/CMakeLists.txt @@ -1,8 +1,6 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.1) project(pcl_recorder) -add_compile_options(-std=c++11) - find_package(catkin REQUIRED COMPONENTS pcl_conversions pcl_ros roscpp sensor_msgs roslaunch) @@ -16,6 +14,8 @@ add_executable(${PROJECT_NAME}_node src/PclRecorder.cpp src/main.cpp) target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES}) +target_compile_features(${PROJECT_NAME}_node PRIVATE cxx_std_14) + install( TARGETS ${PROJECT_NAME}_node ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} diff --git a/rviz_carla_plugin/CMakeLists.txt b/rviz_carla_plugin/CMakeLists.txt index 14d2e9e3..8ff69656 100644 --- a/rviz_carla_plugin/CMakeLists.txt +++ b/rviz_carla_plugin/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.3) +cmake_minimum_required(VERSION 3.1) project(rviz_carla_plugin) set(CXX_STANDARD_REQUIRED ON) @@ -26,6 +26,8 @@ add_library(${PROJECT_NAME} ${SRC_FILES}) target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) +target_compile_features(${PROJECT_NAME} PRIVATE cxx_std_14) + install( TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} From e5d6e00fa1cce4545afbf1accdffd23b439ba4da Mon Sep 17 00:00:00 2001 From: jbmag <47941074+jbmag@users.noreply.github.com> Date: Mon, 21 Sep 2020 17:33:51 +0200 Subject: [PATCH 307/627] =?UTF-8?q?added=20some=20required=20default=20val?= =?UTF-8?q?ues=20in=20ros2=20launch=20files,=20and=20correcte=E2=80=A6=20(?= =?UTF-8?q?#367)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * added some required default values in ros2 launch files, and corrected carla_ego_vehicle that was using global parameters * fixed code formatting --- .../launch/carla_ego_vehicle.launch | 7 +++-- .../launch/carla_ego_vehicle.launch.py | 9 +++--- .../carla_ego_vehicle/carla_ego_vehicle.py | 24 +++++---------- .../launch/carla_ros_bridge.launch.py | 30 +++++++++---------- ..._bridge_with_example_ego_vehicle.launch.py | 8 ++--- 5 files changed, 36 insertions(+), 42 deletions(-) diff --git a/carla_ego_vehicle/launch/carla_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_ego_vehicle.launch index ecc6be22..19e2ebef 100644 --- a/carla_ego_vehicle/launch/carla_ego_vehicle.launch +++ b/carla_ego_vehicle/launch/carla_ego_vehicle.launch @@ -11,9 +11,6 @@ - - - + catkin + roslaunch + rospy + rospy + + + rclpy + ament_python + + + + catkin + ament_python diff --git a/carla_waypoint_publisher/resource/carla_waypoint_publisher b/carla_waypoint_publisher/resource/carla_waypoint_publisher new file mode 100644 index 00000000..e69de29b diff --git a/carla_waypoint_publisher/setup.cfg b/carla_waypoint_publisher/setup.cfg new file mode 100644 index 00000000..80a8263a --- /dev/null +++ b/carla_waypoint_publisher/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_waypoint_publisher +[install] +install-scripts=$base/lib/carla_waypoint_publisher \ No newline at end of file diff --git a/carla_waypoint_publisher/setup.py b/carla_waypoint_publisher/setup.py index a2742691..184ab78f 100755 --- a/carla_waypoint_publisher/setup.py +++ b/carla_waypoint_publisher/setup.py @@ -3,13 +3,44 @@ """ Setup for carla_waypoint_publisher """ +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( + d = generate_distutils_setup( packages=['carla_waypoint_publisher'], package_dir={'': 'src'}, -) + ) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_waypoint_publisher' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA waypoint publisher for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': ['carla_waypoint_publisher = carla_waypoint_publisher.carla_waypoint_publisher:main'], + }, + package_dir={'': 'src'}, + ) -setup(**d) diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 2cd653c6..a5a410ab 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -20,23 +20,34 @@ import math import sys import threading - -import rospy # pylint: disable=import-error -import tf # pylint: disable=import-error -from tf.transformations import euler_from_quaternion # pylint: disable=import-error +import os + +from ros_compatibility import ( euler_from_quaternion, + quaternion_from_euler, + CompatibleNode, + QoSProfile, + get_time, + ROSException, + ros_timestamp) from nav_msgs.msg import Path # pylint: disable=import-error from geometry_msgs.msg import PoseStamped # pylint: disable=import-error from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error -from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint # pylint: disable=import-error -from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint # pylint: disable=import-error +# from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint # pylint: disable=import-error +# from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint # pylint: disable=import-error +from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error +from carla_waypoint_types.srv import GetActorWaypoint # pylint: disable=import-error import carla from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 2: + import rclpy # pylint: disable=import-error -class CarlaToRosWaypointConverter(object): +class CarlaToRosWaypointConverter(CompatibleNode): """ This class generates a plan of waypoints to follow. @@ -47,38 +58,41 @@ class CarlaToRosWaypointConverter(object): """ WAYPOINT_DISTANCE = 2.0 - def __init__(self, carla_world): + def __init__(self): """ Constructor """ - self.world = carla_world - self.map = carla_world.get_map() + super(CarlaToRosWaypointConverter, self).__init__('carla_waypoint_publisher') + self.connect_to_carla() + self.map = self.world.get_map() self.ego_vehicle = None self.ego_vehicle_location = None self.on_tick = None - self.role_name = rospy.get_param("~role_name", 'ego_vehicle') - self.waypoint_publisher = rospy.Publisher( - '/carla/{}/waypoints'.format(self.role_name), Path, queue_size=1, latch=True) - + self.role_name = self.get_param("role_name", 'ego_vehicle') + self.waypoint_publisher = self.new_publisher( + Path, '/carla/{}/waypoints'.format(self.role_name), QoSProfile(depth=1, durability=True)) + # initialize ros services - self.getWaypointService = rospy.Service( + self.getWaypointService = self.new_service( + GetWaypoint, '/carla_waypoint_publisher/{}/get_waypoint'.format(self.role_name), - GetWaypoint, self.get_waypoint) - self.getActorWaypointService = rospy.Service( - '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(self.role_name), - GetActorWaypoint, self.get_actor_waypoint) + self.get_waypoint) + self.getActorWaypointService = self.new_service( + GetActorWaypoint, + '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(self.role_name), + self.get_actor_waypoint) # set initial goal self.goal = self.world.get_map().get_spawn_points()[0] self.current_route = None - self.goal_subscriber = rospy.Subscriber( - "/carla/{}/goal".format(self.role_name), PoseStamped, self.on_goal) + self.goal_subscriber = self.create_subscriber( + PoseStamped, "/carla/{}/goal".format(self.role_name), self.on_goal) self._update_lock = threading.Lock() # use callback to wait for ego vehicle - rospy.loginfo("Waiting for ego vehicle...") + self.loginfo("Waiting for ego vehicle...") self.on_tick = self.world.on_tick(self.find_ego_vehicle_actor) def destroy(self): @@ -89,7 +103,7 @@ def destroy(self): if self.on_tick: self.world.remove_on_tick(self.on_tick) - def get_waypoint(self, req): + def get_waypoint(self, req, response): """ Get the waypoint for a location """ @@ -100,7 +114,7 @@ def get_waypoint(self, req): carla_waypoint = self.map.get_waypoint(carla_position) - response = GetWaypointResponse() + # response = GetWaypointResponse() response.waypoint.pose.position.x = carla_waypoint.transform.location.x response.waypoint.pose.position.y = -carla_waypoint.transform.location.y response.waypoint.pose.position.z = carla_waypoint.transform.location.z @@ -108,17 +122,17 @@ def get_waypoint(self, req): response.waypoint.road_id = carla_waypoint.road_id response.waypoint.section_id = carla_waypoint.section_id response.waypoint.lane_id = carla_waypoint.lane_id - #rospy.logwarn("Get waypoint {}".format(response.waypoint.pose.position)) + #self.logwarn("Get waypoint {}".format(response.waypoint.pose.position)) return response - def get_actor_waypoint(self, req): + def get_actor_waypoint(self, req, response): """ Convenience method to get the waypoint for an actor """ - rospy.loginfo("get_actor_waypoint(): Get waypoint of actor {}".format(req.id)) + self.loginfo("get_actor_waypoint(): Get waypoint of actor {}".format(req.id)) actor = self.world.get_actors().find(req.id) - response = GetActorWaypointResponse() + # response = GetActorWaypointResponse() if actor: carla_waypoint = self.map.get_waypoint(actor.get_location()) response.waypoint.pose.position.x = carla_waypoint.transform.location.x @@ -129,7 +143,7 @@ def get_actor_waypoint(self, req): response.waypoint.section_id = carla_waypoint.section_id response.waypoint.lane_id = carla_waypoint.lane_id else: - rospy.logwarn("get_actor_waypoint(): Actor {} not valid.".format(req.id)) + self.logwarn("get_actor_waypoint(): Actor {} not valid.".format(req.id)) return response def on_goal(self, goal): @@ -140,7 +154,7 @@ def on_goal(self, goal): :return: """ - rospy.loginfo("Received goal, trigger rerouting...") + self.loginfo("Received goal, trigger rerouting...") carla_goal = carla.Transform() carla_goal.location.x = goal.pose.position.x carla_goal.location.y = -goal.pose.position.y @@ -192,7 +206,7 @@ def find_ego_vehicle_actor(self, _): ego_vehicle_changed = True if ego_vehicle_changed: - rospy.loginfo("Ego vehicle changed.") + self.loginfo("Ego vehicle changed.") self.ego_vehicle = hero self.reroute() elif self.ego_vehicle: @@ -202,7 +216,7 @@ def find_ego_vehicle_actor(self, _): dy = self.ego_vehicle_location.y - current_location.y distance = math.sqrt(dx * dx + dy * dy) if distance > self.WAYPOINT_DISTANCE: - rospy.loginfo("Ego vehicle was repositioned.") + self.loginfo("Ego vehicle was repositioned.") self.reroute() self.ego_vehicle_location = current_location @@ -210,7 +224,7 @@ def calculate_route(self, goal): """ Calculate a route from the current location to 'goal' """ - rospy.loginfo("Calculating route to x={}, y={}, z={}".format( + self.loginfo("Calculating route to x={}, y={}, z={}".format( goal.location.x, goal.location.y, goal.location.z)) @@ -231,7 +245,8 @@ def publish_waypoints(self): """ msg = Path() msg.header.frame_id = "map" - msg.header.stamp = rospy.Time.now() + time_stamp = get_time(self).seconds_nanoseconds() + msg.header.stamp = ros_timestamp(time_stamp[0], time_stamp[1]) if self.current_route is not None: for wp in self.current_route: pose = PoseStamped() @@ -239,7 +254,7 @@ def publish_waypoints(self): pose.pose.position.y = -wp[0].transform.location.y pose.pose.position.z = wp[0].transform.location.z - quaternion = tf.transformations.quaternion_from_euler( + quaternion = quaternion_from_euler( 0, 0, -math.radians(wp[0].transform.rotation.yaw)) pose.pose.orientation.x = quaternion[0] pose.pose.orientation.y = quaternion[1] @@ -248,47 +263,47 @@ def publish_waypoints(self): msg.poses.append(pose) self.waypoint_publisher.publish(msg) - rospy.loginfo("Published {} waypoints.".format(len(msg.poses))) + self.loginfo("Published {} waypoints.".format(len(msg.poses))) -def main(): - """ - main function - """ - try: - rospy.init_node("carla_waypoint_publisher", anonymous=True) - # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException: - rospy.logerr("Error while waiting for world info!") - sys.exit(1) - - host = rospy.get_param("/carla/host", "127.0.0.1") - port = rospy.get_param("/carla/port", 2000) - timeout = rospy.get_param("/carla/timeout", 10) - - rospy.loginfo("CARLA world available. Trying to connect to {host}:{port}".format( + def connect_to_carla(self): + + self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") + try: + self.wait_for_one_message("/carla/world_info", CarlaWorldInfo)#, timeout=10.0) + except ROSException: + self.logerr("Error while waiting for world info!") + sys.exit(1) + + host = self.get_param("carla/host", "127.0.0.1") + port = self.get_param("carla/port", 2000) + timeout = self.get_param("carla/timeout", 10) + self.loginfo("CARLA world available. Trying to connect to {host}:{port}".format( host=host, port=port)) - try: carla_client = carla.Client(host=host, port=port) carla_client.set_timeout(timeout) - carla_world = carla_client.get_world() + self.world = carla_client.get_world() - rospy.loginfo("Connected to Carla.") + self.loginfo("Connected to Carla.") - waypointConverter = CarlaToRosWaypointConverter(carla_world) - rospy.spin() - waypointConverter.destroy() - del waypointConverter - del carla_world - del carla_client +def main(args=None): + """ + main function + """ + if ROS_VERSION == 2: + rclpy.init(args=None) + try: + waypointConverter = CarlaToRosWaypointConverter() + waypointConverter.spin() + del waypointConverter + finally: - rospy.loginfo("Done") + # self.loginfo("Done") + print("Done") if __name__ == "__main__": From 8b8adb156755c669b378d9930b05697576ff5cdf Mon Sep 17 00:00:00 2001 From: jbmag Date: Mon, 28 Sep 2020 16:33:40 +0200 Subject: [PATCH 317/627] updated carla_ad_agent to work with ros2 --- carla_ad_agent/CMakeLists.txt | 47 +++++--- carla_ad_agent/package.xml | 25 ++-- carla_ad_agent/resource/carla_ad_agent | 0 carla_ad_agent/setup.cfg | 4 + carla_ad_agent/setup.py | 42 +++++-- carla_ad_agent/src/carla_ad_agent/agent.py | 92 ++++++++------- .../src/carla_ad_agent/basic_agent.py | 64 +++++----- .../src/carla_ad_agent/carla_ad_agent.py | 109 +++++++++++------- .../src/carla_ad_agent/local_planner.py | 21 ++-- .../carla_ad_agent/vehicle_pid_controller.py | 11 +- 10 files changed, 260 insertions(+), 155 deletions(-) create mode 100644 carla_ad_agent/resource/carla_ad_agent create mode 100644 carla_ad_agent/setup.cfg diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index ac90c3e6..91fc840d 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -1,25 +1,38 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ad_agent) -find_package(catkin REQUIRED COMPONENTS rospy roslaunch) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if(${ROS_VERSION} EQUAL 1) -roslaunch_add_file_check(launch) + find_package(catkin REQUIRED COMPONENTS rospy roslaunch) -catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python( - PROGRAMS - src/carla_ad_agent/carla_ad_agent.py - src/carla_ad_agent/basic_agent.py - src/carla_ad_agent/agent.py - src/carla_ad_agent/local_planner.py - src/carla_ad_agent/vehicle_pid_controller.py - src/carla_ad_agent/misc.py - src/carla_ad_agent/__init__.py - DESTINATION - ${CATKIN_PACKAGE_BIN_DESTINATION}) + catkin_python_setup() -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + catkin_package(CATKIN_DEPENDS rospy) + + roslaunch_add_file_check(launch) + + + include_directories(${catkin_INCLUDE_DIRS}) + + install( + PROGRAMS src/carla_ad_agent/carla_ad_agent.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + +elseif(${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + + ament_package() + +endif() \ No newline at end of file diff --git a/carla_ad_agent/package.xml b/carla_ad_agent/package.xml index d2b3d2a5..503f5bea 100644 --- a/carla_ad_agent/package.xml +++ b/carla_ad_agent/package.xml @@ -1,18 +1,29 @@ - + carla_ad_agent 0.0.1 The carla_ad_agent package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy - topic_tools + carla_waypoint_types carla_msgs + ros_compatibility + + + catkin + rospy + roslaunch + rospy + rospy + topic_tools + + + rclpy + ament_python + + catkin + ament_python diff --git a/carla_ad_agent/resource/carla_ad_agent b/carla_ad_agent/resource/carla_ad_agent new file mode 100644 index 00000000..e69de29b diff --git a/carla_ad_agent/setup.cfg b/carla_ad_agent/setup.cfg new file mode 100644 index 00000000..ddf4d548 --- /dev/null +++ b/carla_ad_agent/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_ad_agent +[install] +install-scripts=$base/lib/carla_ad_agent \ No newline at end of file diff --git a/carla_ad_agent/setup.py b/carla_ad_agent/setup.py index eca8be1c..a37bb28b 100644 --- a/carla_ad_agent/setup.py +++ b/carla_ad_agent/setup.py @@ -1,12 +1,40 @@ """ Setup for carla_ad_agent """ -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) -d = generate_distutils_setup( - packages=['carla_ad_agent'], - package_dir={'': 'src'} -) +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -setup(**d) + d = generate_distutils_setup(packages=['carla_ad_agent'], package_dir={'': 'src'}) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_ad_agent' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ROS2 AD agent', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': ['carla_ad_agent = carla_ad_agent.carla_ad_agent:main'], + }, + package_dir={'': 'src'}, + ) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 7d3ff224..0cd460be 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -9,21 +9,19 @@ Base class for agent """ -from carla_waypoint_types.srv import GetWaypoint -from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus,\ - CarlaTrafficLightStatusList, CarlaWorldInfo -from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import -from tf.transformations import euler_from_quaternion -import rospy +from carla_ad_agent.misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error from carla_msgs.msg import CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus # pylint: disable=import-error -from misc import is_within_distance_ahead, compute_magnitude_angle -from tf.transformations import euler_from_quaternion -import rospy from enum import Enum import math +from ros_compatibility import ( + euler_from_quaternion, + ros_ok, + ServiceException, + ROSInterruptException) + class AgentState(Enum): """ @@ -39,9 +37,10 @@ class Agent(object): Base class for agent """ - def __init__(self, role_name, vehicle_id, avoid_risk): + def __init__(self, role_name, vehicle_id, avoid_risk, node): """ """ + self.node = node self._proximity_threshold = 10.0 # meters self._local_planner = None self._map_name = None @@ -51,17 +50,15 @@ def __init__(self, role_name, vehicle_id, avoid_risk): self._last_traffic_light = None if avoid_risk: - rospy.wait_for_service('/carla_waypoint_publisher/{}/get_waypoint'.format(role_name)) - - self._get_waypoint_client = rospy.ServiceProxy( + self._get_waypoint_client = node.create_service_client( '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) self._traffic_lights = [] - self._traffic_light_status_subscriber = rospy.Subscriber( - "/carla/traffic_lights", CarlaTrafficLightStatusList, self.traffic_lights_updated) + self._traffic_light_status_subscriber = node.create_subscriber(CarlaTrafficLightStatusList, + "/carla/traffic_lights", self.traffic_lights_updated) - self._world_info_subscriber = rospy.Subscriber( - "/carla/world_info", CarlaWorldInfo, self.world_info_updated) + node.create_subscriber(CarlaWorldInfo, + "/carla/world_info", self.world_info_updated) def traffic_lights_updated(self, traffic_lights): """ @@ -118,11 +115,12 @@ def _is_light_red_europe_style(self, lights_list): - traffic_light is the object itself or None if there is no red traffic light affecting us """ - ego_vehicle_location = self._vehicle_location + ego_vehicle_location = GetWaypoint.Request() + ego_vehicle_location.location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) if not ego_vehicle_waypoint: - if not rospy.is_shutdown(): - rospy.logwarn("Could not get waypoint for ego vehicle.") + if ros_ok(): + self.node.logwarn("Could not get waypoint for ego vehicle.1") return (False, None) for traffic_light in lights_list: @@ -148,14 +146,14 @@ def get_waypoint(self, location): Helper to get waypoint for location via ros service. Only used if risk should be avoided. """ - if rospy.is_shutdown(): + if not ros_ok(): return None try: - response = self._get_waypoint_client(location) + response = self.node.call_service(self._get_waypoint_client, location) return response.waypoint - except (rospy.ServiceException, rospy.ROSInterruptException) as e: - if not rospy.is_shutdown(): - rospy.logwarn("Service call 'get_waypoint' failed: {}".format(e)) + except (ServiceException, ROSInterruptException, TypeError) as e: + if ros_ok(): + self.node.logwarn("Service call 'get_waypoint' failed: {}".format(e)) def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branches """ @@ -168,11 +166,15 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc - traffic_light is the object itself or None if there is no red traffic light affecting us """ - ego_vehicle_location = self._vehicle_location + if self._vehicle_location is not None: + ego_vehicle_location = GetWaypoint.Request() + ego_vehicle_location.location = self._vehicle_location + else: + ego_vehicle_location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) if not ego_vehicle_waypoint: - if not rospy.is_shutdown(): - rospy.logwarn("Could not get waypoint for ego vehicle.") + if ros_ok(): + self.node.logwarn("Could not get waypoint for ego vehicle.") return (False, None) if ego_vehicle_waypoint.is_junction: @@ -180,10 +182,12 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc return (False, None) if self._local_planner.target_route_point is not None: - target_waypoint = self.get_waypoint(self._local_planner.target_route_point.position) + request = GetWaypoint.Request() + request.location = self._local_planner.target_route_point.position + target_waypoint = self.get_waypoint(request) if not target_waypoint: - if not rospy.is_shutdown(): - rospy.logwarn("Could not get waypoint for target route point.") + if ros_ok(): + self.node.logwarn("Could not get waypoint for target route point.") return (False, None) if target_waypoint.is_junction: min_angle = 180.0 @@ -192,7 +196,7 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc for traffic_light in lights_list: loc = traffic_light[1] magnitude, angle = compute_magnitude_angle(loc.pose.position, - ego_vehicle_location, + ego_vehicle_location.location, math.degrees(self._vehicle_yaw)) if magnitude < 60.0 and angle < min(25.0, min_angle): sel_magnitude = magnitude @@ -212,7 +216,7 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc state = status.state break if state is None: - rospy.logwarn( + self.node.logwarn( "Couldn't get state of traffic light {}".format( sel_traffic_light)) return (False, None) @@ -242,12 +246,16 @@ def _is_vehicle_hazard(self, vehicle_list, objects): - vehicle is the blocker object itself """ - ego_vehicle_location = self._vehicle_location + if self._vehicle_location is not None: + ego_vehicle_location = GetWaypoint.Request() + ego_vehicle_location.location = self._vehicle_location + else: + ego_vehicle_location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) if not ego_vehicle_waypoint: - if not rospy.is_shutdown(): - rospy.logwarn("Could not get waypoint for ego vehicle.") + if ros_ok(): + self.node.logwarn("Could not get waypoint for ego vehicle.3") return (False, None) for target_vehicle_id in vehicle_list: @@ -262,18 +270,18 @@ def _is_vehicle_hazard(self, vehicle_list, objects): break if not target_vehicle_location: - rospy.logwarn("Location of vehicle {} not found".format(target_vehicle_id)) + self.node.logwarn("Location of vehicle {} not found".format(target_vehicle_id)) continue - + request = GetWaypoint.Request() + request.location = target_vehicle_location.position # if the object is not in our lane it's not an obstacle - target_vehicle_waypoint = self.get_waypoint(target_vehicle_location.position) + target_vehicle_waypoint = self.get_waypoint(request) if not target_vehicle_waypoint: - if not rospy.is_shutdown(): - rospy.logwarn("Could not get waypoint for target vehicle.") + if ros_ok(): + self.node.logwarn("Could not get waypoint for target vehicle.") return (False, None) if target_vehicle_waypoint.road_id != ego_vehicle_waypoint.road_id or \ target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id: - #rospy.loginfo("Vehicle {} is not in our lane".format(target_vehicle_id)) continue if is_within_distance_ahead(target_vehicle_location.position, self._vehicle_location, diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 39f25710..b508b412 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -10,24 +10,23 @@ target destination. This agent respects traffic lights and other vehicles. """ -from carla_waypoint_types.srv import GetActorWaypoint -from local_planner import LocalPlanner # pylint: disable=relative-import -from agent import Agent, AgentState # pylint: disable=relative-import -from carla_msgs.msg import CarlaActorList -from derived_object_msgs.msg import ObjectArray -from geometry_msgs.msg import Pose -from nav_msgs.msg import Odometry -import rospy +from carla_ad_agent.local_planner import LocalPlanner # pylint: disable=relative-import +from carla_ad_agent.agent import Agent, AgentState # pylint: disable=relative-import from carla_waypoint_types.srv import GetActorWaypoint # pylint: disable=import-error -from local_planner import LocalPlanner -from agent import Agent, AgentState from carla_msgs.msg import CarlaActorList # pylint: disable=import-error from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error from geometry_msgs.msg import Pose # pylint: disable=import-error from nav_msgs.msg import Odometry # pylint: disable=import-error -import rospy # pylint: disable=import-error import math +from ros_compatibility import ( + ros_ok, + ServiceException, + ROSInterruptException) +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) +if ROS_VERSION == 2: + from rclpy.callback_groups import ReentrantCallbackGroup class BasicAgent(Agent): """ @@ -35,11 +34,11 @@ class BasicAgent(Agent): target destination. This agent respects traffic lights and other vehicles. """ - def __init__(self, role_name, ego_vehicle_id, avoid_risk=True): + def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): """ """ - super(BasicAgent, self).__init__(role_name, ego_vehicle_id, avoid_risk) - + super(BasicAgent, self).__init__(role_name, ego_vehicle_id, avoid_risk, node) + self.node = node self._avoid_risk = avoid_risk self._current_speed = 0.0 # Km/h self._current_pose = Pose() @@ -49,22 +48,29 @@ def __init__(self, role_name, ego_vehicle_id, avoid_risk=True): 'K_P': 0.9, 'K_D': 0.0, 'K_I': 0.1} - self._local_planner = LocalPlanner(opt_dict={'lateral_control_dict': args_lateral_dict}) + self._local_planner = LocalPlanner(node=self.node, opt_dict={'lateral_control_dict': args_lateral_dict}) + + if ROS_VERSION == 1: + cb_group = None + elif ROS_VERSION == 2: + cb_group = ReentrantCallbackGroup() + if self._avoid_risk: self._vehicle_id_list = [] self._lights_id_list = [] - self._actors_subscriber = rospy.Subscriber( - "/carla/actor_list", CarlaActorList, self.actors_updated) + self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", + self.actors_updated, callback_group=cb_group) self._objects = [] - self._objects_subscriber = rospy.Subscriber( - "/carla/{}/objects".format(role_name), ObjectArray, self.objects_updated) - self._get_actor_waypoint_client = rospy.ServiceProxy( + + self._objects_subscriber = self.node.create_subscriber(ObjectArray, + "/carla/{}/objects".format(role_name), self.objects_updated) + self._get_actor_waypoint_client = self.node.create_service_client( '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), - GetActorWaypoint) - - self._odometry_subscriber = rospy.Subscriber( - "/carla/{}/odometry".format(role_name), Odometry, self.odometry_updated) + GetActorWaypoint, callback_group=cb_group) + + self._odometry_subscriber = self.node.create_subscriber(Odometry, + "/carla/{}/odometry".format(role_name), self.odometry_updated) def get_actor_waypoint(self, actor_id): """ @@ -72,11 +78,13 @@ def get_actor_waypoint(self, actor_id): Only used if risk should be avoided. """ try: - response = self._get_actor_waypoint_client(actor_id) + request = GetActorWaypoint.Request() + request.id = actor_id + response = self.node.call_service(self._get_actor_waypoint_client, request) return response.waypoint - except (rospy.ServiceException, rospy.ROSInterruptException) as e: - if not rospy.is_shutdown: - rospy.logwarn("Service call failed: {}".format(e)) + except (ServiceException, ROSInterruptException, TypeError) as e: + if ros_ok(): + self.node.logwarn("Service call failed: {}".format(e)) def odometry_updated(self, odo): """ diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 6136f994..14270c87 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -9,54 +9,71 @@ A basic AD agent using CARLA waypoints """ import sys -import rospy -from nav_msgs.msg import Path -from std_msgs.msg import Float64 -from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl -from basic_agent import BasicAgent # pylint: disable=relative-import - - -class CarlaAdAgent(object): +import time +from nav_msgs.msg import Path # pylint: disable=import-error +from std_msgs.msg import Float64 # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl # pylint: disable=import-error +from carla_ad_agent.basic_agent import BasicAgent +from ros_compatibility import CompatibleNode, ROSInterruptException, ros_ok, QoSProfile, ROSException +import threading + +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + import rospy +elif ROS_VERSION == 2: + import rclpy + +class CarlaAdAgent(CompatibleNode): """ A basic AD agent using CARLA waypoints """ - def __init__(self, role_name, target_speed, avoid_risk): + def __init__(self): """ Constructor """ + super(CarlaAdAgent, self).__init__('carla_ad_agent') + + role_name = self.get_param("role_name", "ego_vehicle") + avoid_risk = self.get_param("avoid_risk", True) + + self._target_speed = self.get_param("target_speed", 20) self._route_assigned = False self._global_plan = None self._agent = None - self._target_speed = target_speed - rospy.on_shutdown(self.on_shutdown) + self.on_shutdown(self._on_shutdown) + # wait for ego vehicle vehicle_info = None try: - vehicle_info = rospy.wait_for_message( + self.loginfo("Wait for vehicle info ...") + vehicle_info = self.wait_for_one_message( "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) - except rospy.ROSException: - rospy.logerr("Timeout while waiting for world info!") + self.loginfo("Vehicle info recieved.") + except ROSException: + self.logerr("Timeout while waiting for vehicle info!") sys.exit(1) - self._route_subscriber = rospy.Subscriber( - "/carla/{}/waypoints".format(role_name), Path, self.path_updated) - - self._target_speed_subscriber = rospy.Subscriber( - "/carla/{}/target_speed".format(role_name), Float64, self.target_speed_updated) + self._route_subscriber =self.create_subscriber( + Path, "/carla/{}/waypoints".format(role_name), self.path_updated) - self.vehicle_control_publisher = rospy.Publisher( - "/carla/{}/vehicle_control_cmd".format(role_name), CarlaEgoVehicleControl, queue_size=1) + self._target_speed_subscriber = self.create_subscriber( + Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated) + self.vehicle_control_publisher = self.new_publisher( + CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), + QoSProfile(depth=1, durability=False)) self._agent = BasicAgent(role_name, vehicle_info.id, # pylint: disable=no-member - avoid_risk) + self, avoid_risk) - def on_shutdown(self): + def _on_shutdown(self): """ callback on shutdown """ - rospy.loginfo("Shutting down, stopping ego vehicle...") + self.loginfo("Shutting down, stopping ego vehicle...") if self._agent: self.vehicle_control_publisher.publish(self._agent.emergency_stop()) @@ -64,14 +81,14 @@ def target_speed_updated(self, target_speed): """ callback on new target speed """ - rospy.loginfo("New target speed received: {}".format(target_speed.data)) + self.loginfo("New target speed received: {}".format(target_speed.data)) self._target_speed = target_speed.data def path_updated(self, path): """ callback on new route """ - rospy.loginfo("New plan with {} waypoints received.".format(len(path.poses))) + self.loginfo("New plan with {} waypoints received.".format(len(path.poses))) if self._agent: self.vehicle_control_publisher.publish(self._agent.emergency_stop()) self._global_plan = path @@ -88,11 +105,11 @@ def run_step(self): control.hand_brake = False if not self._agent: - rospy.loginfo("Waiting for ego vehicle...") + self.loginfo("Waiting for ego vehicle...") return control if not self._route_assigned and self._global_plan: - rospy.loginfo("Assigning plan...") + self.loginfo("Assigning plan...") self._agent._local_planner.set_global_plan( # pylint: disable=protected-access self._global_plan.poses) self._route_assigned = True @@ -103,6 +120,10 @@ def run_step(self): self._route_assigned = False return control + + def spin_loop(self): + while ros_ok: + self.spin_once() def run(self): """ @@ -111,8 +132,13 @@ def run(self): :return: """ - r = rospy.Rate(10) - while not rospy.is_shutdown(): + loop_frequency = 10 + + if ROS_VERSION == 1: + r = rospy.Rate(loop_frequency) + + while ros_ok(): + self.spin_once() if self._global_plan: control = self.run_step() if control: @@ -120,28 +146,33 @@ def run(self): self.vehicle_control_publisher.publish(control) else: try: - r.sleep() - except rospy.ROSInterruptException: + if ROS_VERSION == 1: + r.sleep() + elif ROS_VERSION == 2: + #TODO: use rclpy.Rate, not working yet + time.sleep(1 / loop_frequency) + except ROSInterruptException: pass + -def main(): +def main(args=None): """ main function :return: """ - rospy.init_node('carla_ad_agent', anonymous=True) - role_name = rospy.get_param("~role_name", "ego_vehicle") - target_speed = rospy.get_param("~target_speed", 20) - avoid_risk = rospy.get_param("~avoid_risk", True) - controller = CarlaAdAgent(role_name, target_speed, avoid_risk) + if ROS_VERSION == 2: + rclpy.init() + + controller = CarlaAdAgent() try: controller.run() + finally: del controller - rospy.loginfo("Done") + print("Done") if __name__ == "__main__": diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index dcb2e511..24bb3283 100644 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -11,11 +11,11 @@ """ from collections import deque -import rospy -from geometry_msgs.msg import PointStamped -from carla_msgs.msg import CarlaEgoVehicleControl -from vehicle_pid_controller import VehiclePIDController # pylint: disable=relative-import -from misc import distance_vehicle # pylint: disable=relative-import +from geometry_msgs.msg import PointStamped # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error +from carla_ad_agent.vehicle_pid_controller import VehiclePIDController +from carla_ad_agent.misc import distance_vehicle +from ros_compatibility import QoSProfile class LocalPlanner(object): @@ -32,7 +32,7 @@ class LocalPlanner(object): # total distance) MIN_DISTANCE_PERCENTAGE = 0.9 - def __init__(self, opt_dict=None): + def __init__(self, node, opt_dict=None): """ :param vehicle: actor to apply to local planner logic onto :param opt_dict: dictionary of arguments with the following semantics: @@ -53,9 +53,10 @@ def __init__(self, opt_dict=None): self._waypoints_queue = deque(maxlen=20000) self._buffer_size = 5 self._waypoint_buffer = deque(maxlen=self._buffer_size) + self.node = node - self._target_point_publisher = rospy.Publisher( - "/next_target", PointStamped, queue_size=1) + self._target_point_publisher = self.node.new_publisher( + PointStamped, "/next_target", QoSProfile(depth=1, durability=False)) # initializing controller self._init_controller(opt_dict) @@ -84,7 +85,7 @@ def _init_controller(self, opt_dict): if 'longitudinal_control_dict' in opt_dict: args_longitudinal_dict = opt_dict['longitudinal_control_dict'] - self._vehicle_controller = VehiclePIDController(args_lateral=args_lateral_dict, + self._vehicle_controller = VehiclePIDController(self.node, args_lateral=args_lateral_dict, args_longitudinal=args_longitudinal_dict) def set_global_plan(self, current_plan): @@ -110,7 +111,7 @@ def run_step(self, target_speed, current_speed, current_pose): control.hand_brake = False control.manual_gear_shift = False - rospy.loginfo("Route finished.") + self.node.logwarn("Route finished.") return control, True # Buffering the waypoints diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index 6ff034c8..41ac0fbb 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -11,8 +11,8 @@ from collections import deque import math import numpy as np -import rospy # pylint: disable=import-error -from tf.transformations import euler_from_quaternion # pylint: disable=import-error +import rclpy +from ros_compatibility import euler_from_quaternion, get_time # pylint: disable=import-error from geometry_msgs.msg import Point # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error @@ -23,7 +23,7 @@ class VehiclePIDController(object): # pylint: disable=too-few-public-methods to perform the low level control a vehicle from client side """ - def __init__(self, args_lateral=None, args_longitudinal=None): + def __init__(self, node, args_lateral=None, args_longitudinal=None): """ :param vehicle: actor to apply to local planner logic onto :param args_lateral: dictionary of arguments to set the lateral PID controller using @@ -42,9 +42,10 @@ def __init__(self, args_lateral=None, args_longitudinal=None): if not args_longitudinal: args_longitudinal = {'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0} + self.node = node self._lon_controller = PIDLongitudinalController(**args_longitudinal) self._lat_controller = PIDLateralController(**args_lateral) - self._last_control_time = rospy.get_time() + self._last_control_time = float(get_time(self.node).nanoseconds/10**9) def run_step(self, target_speed, current_speed, current_pose, waypoint): """ @@ -55,7 +56,7 @@ def run_step(self, target_speed, current_speed, current_pose, waypoint): :param waypoint: target location encoded as a waypoint :return: distance (in meters) to the waypoint """ - current_time = rospy.get_time() + current_time = float(get_time(self.node).nanoseconds/10**9) dt = current_time-self._last_control_time if dt == 0.0: dt = 0.000001 From 6c2a46e2e91aa1af3600cad72d4dd99c34425198 Mon Sep 17 00:00:00 2001 From: jbmag Date: Mon, 28 Sep 2020 16:35:17 +0200 Subject: [PATCH 318/627] updated carla_ad_demo to work with ros2. at the moment only the launch file carla_ad_demo.launch.py works --- carla_ad_demo/CMakeLists.txt | 29 ++++++++++---- carla_ad_demo/launch/carla_ad_demo.launch.py | 10 ++--- carla_ad_demo/package.xml | 24 +++++++++--- carla_ad_demo/resource/carla_ad_demo | 0 carla_ad_demo/setup.cfg | 0 carla_ad_demo/setup.py | 40 ++++++++++++++++++++ 6 files changed, 85 insertions(+), 18 deletions(-) create mode 100644 carla_ad_demo/resource/carla_ad_demo create mode 100644 carla_ad_demo/setup.cfg create mode 100644 carla_ad_demo/setup.py diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 2a6504fb..75a50506 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -1,14 +1,29 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ad_demo) -find_package(catkin REQUIRED COMPONENTS roslaunch) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -roslaunch_add_file_check(launch) +if(${ROS_VERSION} EQUAL 1) -catkin_package() + find_package(catkin REQUIRED COMPONENTS roslaunch) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + roslaunch_add_file_check(launch) -install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) + catkin_package() + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + + install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) + +elseif(${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + + ament_package() + +endif() diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index afe599fc..184c1a8e 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -56,11 +56,11 @@ def generate_launch_description(): name='avoid_risk', default_value='True' ), - launch_ros.actions.Node( - package='rostopic', - node_executable='rostopic', - name='publish_goal' - ), + # launch_ros.actions.Node( + # package='rostopic', + # node_executable='rostopic', + # name='publish_goal' + # ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 050c468e..45d6d559 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -1,22 +1,34 @@ - + carla_ad_demo 0.0.1 The carla_ad_demo package CARLA Simulator Team MIT - catkin + + carla_ros_bridge carla_ego_vehicle carla_waypoint_publisher carla_ad_agent carla_manual_control - rviz_carla_plugin + carla_twist_to_control - carla_spectator_camera - carla_ros_scenario_runner + + rostopic - rviz + + + + ament_python + rviz2 + + + catkin + rviz + + catkin + ament_python diff --git a/carla_ad_demo/resource/carla_ad_demo b/carla_ad_demo/resource/carla_ad_demo new file mode 100644 index 00000000..e69de29b diff --git a/carla_ad_demo/setup.cfg b/carla_ad_demo/setup.cfg new file mode 100644 index 00000000..e69de29b diff --git a/carla_ad_demo/setup.py b/carla_ad_demo/setup.py new file mode 100644 index 00000000..d5eb90aa --- /dev/null +++ b/carla_ad_demo/setup.py @@ -0,0 +1,40 @@ +""" +Setup for carla_ego_vehicle +""" +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup + + d = generate_distutils_setup( + packages=['carla_ad_demo'], + ) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_ad_demo' + setup( + name=package_name, + version='0.0.0', + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', + ['config/sensors.json']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ad demo for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + ) From c8a0c30b8d7b32faa075bf2fefe236a5486184bc Mon Sep 17 00:00:00 2001 From: jbmag Date: Tue, 29 Sep 2020 17:53:34 +0200 Subject: [PATCH 319/627] carla_ad_agent works with both ros1 and ros2 --- carla_ad_agent/CMakeLists.txt | 9 +-- carla_ad_agent/setup.py | 3 +- carla_ad_agent/src/carla_ad_agent/agent.py | 65 ++++++++++++++----- .../src/carla_ad_agent/basic_agent.py | 49 +++++++++----- .../src/carla_ad_agent/carla_ad_agent.py | 25 +++---- .../src/carla_ad_agent/local_planner.py | 12 +++- .../carla_ad_agent/vehicle_pid_controller.py | 5 +- carla_ad_demo/CMakeLists.txt | 24 +++---- carla_waypoint_publisher/CMakeLists.txt | 8 +-- carla_waypoint_publisher/setup.py | 5 +- .../carla_waypoint_publisher.py | 53 ++++++++------- carla_waypoint_types/CMakeLists.txt | 57 ++++++++-------- .../ros_compatibility/ros_compatible_node.py | 37 ++++++----- 13 files changed, 205 insertions(+), 147 deletions(-) diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index 91fc840d..6b3426e6 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -8,19 +8,16 @@ if(${ROS_VERSION} EQUAL 1) find_package(catkin REQUIRED COMPONENTS rospy roslaunch) - catkin_python_setup() catkin_package(CATKIN_DEPENDS rospy) roslaunch_add_file_check(launch) - include_directories(${catkin_INCLUDE_DIRS}) - install( - PROGRAMS src/carla_ad_agent/carla_ad_agent.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(PROGRAMS src/carla_ad_agent/carla_ad_agent.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) @@ -35,4 +32,4 @@ elseif(${ROS_VERSION} EQUAL 2) ament_package() -endif() \ No newline at end of file +endif() diff --git a/carla_ad_agent/setup.py b/carla_ad_agent/setup.py index a37bb28b..85f414fc 100644 --- a/carla_ad_agent/setup.py +++ b/carla_ad_agent/setup.py @@ -23,7 +23,7 @@ packages=[package_name], data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name), ['package.xml']), (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], @@ -32,7 +32,6 @@ maintainer_email='carla.simulator@gmail.com', description='CARLA ROS2 AD agent', license='MIT', - tests_require=['pytest'], entry_points={ 'console_scripts': ['carla_ad_agent = carla_ad_agent.carla_ad_agent:main'], }, diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 0cd460be..3e5aa320 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -9,18 +9,26 @@ Base class for agent """ -from carla_ad_agent.misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error from carla_msgs.msg import CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus # pylint: disable=import-error from enum import Enum import math -from ros_compatibility import ( - euler_from_quaternion, - ros_ok, - ServiceException, - ROSInterruptException) +from ros_compatibility import ( + euler_from_quaternion, + ros_ok, + ServiceException, + ROSInterruptException) + +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + from carla_waypoint_types.srv import GetWaypointRequest + from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import +elif ROS_VERSION == 2: + from carla_ad_agent.misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import class AgentState(Enum): @@ -55,10 +63,10 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): self._traffic_lights = [] self._traffic_light_status_subscriber = node.create_subscriber(CarlaTrafficLightStatusList, - "/carla/traffic_lights", self.traffic_lights_updated) + "/carla/traffic_lights", self.traffic_lights_updated) node.create_subscriber(CarlaWorldInfo, - "/carla/world_info", self.world_info_updated) + "/carla/world_info", self.world_info_updated) def traffic_lights_updated(self, traffic_lights): """ @@ -115,8 +123,14 @@ def _is_light_red_europe_style(self, lights_list): - traffic_light is the object itself or None if there is no red traffic light affecting us """ - ego_vehicle_location = GetWaypoint.Request() - ego_vehicle_location.location = self._vehicle_location + if self._vehicle_location is not None and ROS_VERSION == 2: + ego_vehicle_location = GetWaypoint.Request() + ego_vehicle_location.location = self._vehicle_location + elif self._vehicle_location is not None and ROS_VERSION == 1: + ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location.location = self._vehicle_location + else: + ego_vehicle_location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) if not ego_vehicle_waypoint: if ros_ok(): @@ -128,7 +142,7 @@ def _is_light_red_europe_style(self, lights_list): if object_waypoint.road_id != ego_vehicle_waypoint.road_id or \ object_waypoint.lane_id != ego_vehicle_waypoint.lane_id: continue - if is_within_distance_ahead(object_waypoint.pose.position, ego_vehicle_location, + if is_within_distance_ahead(object_waypoint.pose.position, ego_vehicle_location.location, math.degrees(self._vehicle_yaw), self._proximity_threshold): traffic_light_state = CarlaTrafficLightStatus.RED @@ -166,9 +180,12 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc - traffic_light is the object itself or None if there is no red traffic light affecting us """ - if self._vehicle_location is not None: + if self._vehicle_location is not None and ROS_VERSION == 2: ego_vehicle_location = GetWaypoint.Request() ego_vehicle_location.location = self._vehicle_location + elif self._vehicle_location is not None and ROS_VERSION == 1: + ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) @@ -182,8 +199,12 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc return (False, None) if self._local_planner.target_route_point is not None: - request = GetWaypoint.Request() - request.location = self._local_planner.target_route_point.position + if ROS_VERSION == 2: + request = GetWaypoint.Request() + request.location = self._local_planner.target_route_point.position + elif ROS_VERSION == 1: + request = GetWaypointRequest() + request.location = self._local_planner.target_route_point.position target_waypoint = self.get_waypoint(request) if not target_waypoint: if ros_ok(): @@ -246,9 +267,12 @@ def _is_vehicle_hazard(self, vehicle_list, objects): - vehicle is the blocker object itself """ - if self._vehicle_location is not None: + if self._vehicle_location is not None and ROS_VERSION == 2: ego_vehicle_location = GetWaypoint.Request() ego_vehicle_location.location = self._vehicle_location + elif self._vehicle_location is not None and ROS_VERSION == 1: + ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location @@ -272,13 +296,18 @@ def _is_vehicle_hazard(self, vehicle_list, objects): if not target_vehicle_location: self.node.logwarn("Location of vehicle {} not found".format(target_vehicle_id)) continue - request = GetWaypoint.Request() - request.location = target_vehicle_location.position + # if the object is not in our lane it's not an obstacle + if ROS_VERSION == 2: + request = GetWaypoint.Request() + request.location = target_vehicle_location.position + elif ROS_VERSION == 1: + request = GetWaypointRequest() + request.location = target_vehicle_location.position target_vehicle_waypoint = self.get_waypoint(request) if not target_vehicle_waypoint: if ros_ok(): - self.node.logwarn("Could not get waypoint for target vehicle.") + self.node.logwarn("Could not get waypoint for target vehicle.") return (False, None) if target_vehicle_waypoint.road_id != ego_vehicle_waypoint.road_id or \ target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id: diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index b508b412..7b2f0ade 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -10,23 +10,36 @@ target destination. This agent respects traffic lights and other vehicles. """ -from carla_ad_agent.local_planner import LocalPlanner # pylint: disable=relative-import -from carla_ad_agent.agent import Agent, AgentState # pylint: disable=relative-import from carla_waypoint_types.srv import GetActorWaypoint # pylint: disable=import-error from carla_msgs.msg import CarlaActorList # pylint: disable=import-error from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error from geometry_msgs.msg import Pose # pylint: disable=import-error from nav_msgs.msg import Odometry # pylint: disable=import-error import math -from ros_compatibility import ( - ros_ok, - ServiceException, - ROSInterruptException) +from ros_compatibility import ( + ros_ok, + ros_ok, + ros_ok, + ros_ok, + ros_ok, + ServiceException, + ServiceException, + ServiceException, + ServiceException, + ServiceException, + ROSInterruptException) import os ROS_VERSION = int(os.environ['ROS_VERSION']) -if ROS_VERSION == 2: +if ROS_VERSION == 1: + from carla_waypoint_types.srv import GetActorWaypointRequest + from local_planner import LocalPlanner # pylint: disable=relative-import + from agent import Agent, AgentState # pylint: disable=relative-import +elif ROS_VERSION == 2: from rclpy.callback_groups import ReentrantCallbackGroup + from carla_ad_agent.local_planner import LocalPlanner # pylint: disable=relative-import + from carla_ad_agent.agent import Agent, AgentState # pylint: disable=relative-import + class BasicAgent(Agent): """ @@ -48,29 +61,29 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): 'K_P': 0.9, 'K_D': 0.0, 'K_I': 0.1} - self._local_planner = LocalPlanner(node=self.node, opt_dict={'lateral_control_dict': args_lateral_dict}) + self._local_planner = LocalPlanner(node=self.node, opt_dict={ + 'lateral_control_dict': args_lateral_dict}) if ROS_VERSION == 1: cb_group = None elif ROS_VERSION == 2: cb_group = ReentrantCallbackGroup() - if self._avoid_risk: self._vehicle_id_list = [] self._lights_id_list = [] self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", - self.actors_updated, callback_group=cb_group) + self.actors_updated, callback_group=cb_group) self._objects = [] - + self._objects_subscriber = self.node.create_subscriber(ObjectArray, - "/carla/{}/objects".format(role_name), self.objects_updated) + "/carla/{}/objects".format(role_name), self.objects_updated) self._get_actor_waypoint_client = self.node.create_service_client( '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), GetActorWaypoint, callback_group=cb_group) - + self._odometry_subscriber = self.node.create_subscriber(Odometry, - "/carla/{}/odometry".format(role_name), self.odometry_updated) + "/carla/{}/odometry".format(role_name), self.odometry_updated) def get_actor_waypoint(self, actor_id): """ @@ -78,8 +91,12 @@ def get_actor_waypoint(self, actor_id): Only used if risk should be avoided. """ try: - request = GetActorWaypoint.Request() - request.id = actor_id + if ROS_VERSION == 1: + request = GetActorWaypointRequest() + request.id = actor_id + elif ROS_VERSION == 2: + request = GetActorWaypoint.Request() + request.id = actor_id response = self.node.call_service(self._get_actor_waypoint_client, request) return response.waypoint except (ServiceException, ROSInterruptException, TypeError) as e: diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 14270c87..2ef2e858 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -13,17 +13,19 @@ from nav_msgs.msg import Path # pylint: disable=import-error from std_msgs.msg import Float64 # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl # pylint: disable=import-error -from carla_ad_agent.basic_agent import BasicAgent from ros_compatibility import CompatibleNode, ROSInterruptException, ros_ok, QoSProfile, ROSException -import threading import os ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: import rospy + # TODO: shouldn't be necessary + from basic_agent import BasicAgent elif ROS_VERSION == 2: import rclpy + from carla_ad_agent.basic_agent import BasicAgent + class CarlaAdAgent(CompatibleNode): """ @@ -35,7 +37,7 @@ def __init__(self): Constructor """ super(CarlaAdAgent, self).__init__('carla_ad_agent') - + role_name = self.get_param("role_name", "ego_vehicle") avoid_risk = self.get_param("avoid_risk", True) @@ -45,7 +47,6 @@ def __init__(self): self._agent = None self.on_shutdown(self._on_shutdown) - # wait for ego vehicle vehicle_info = None try: @@ -53,19 +54,19 @@ def __init__(self): vehicle_info = self.wait_for_one_message( "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) self.loginfo("Vehicle info recieved.") - except ROSException: + except ROSException: self.logerr("Timeout while waiting for vehicle info!") sys.exit(1) - self._route_subscriber =self.create_subscriber( + self._route_subscriber = self.create_subscriber( Path, "/carla/{}/waypoints".format(role_name), self.path_updated) self._target_speed_subscriber = self.create_subscriber( Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated) self.vehicle_control_publisher = self.new_publisher( - CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), - QoSProfile(depth=1, durability=False)) + CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), + QoSProfile(depth=1, durability=False)) self._agent = BasicAgent(role_name, vehicle_info.id, # pylint: disable=no-member self, avoid_risk) @@ -120,7 +121,7 @@ def run_step(self): self._route_assigned = False return control - + def spin_loop(self): while ros_ok: self.spin_once() @@ -138,7 +139,8 @@ def run(self): r = rospy.Rate(loop_frequency) while ros_ok(): - self.spin_once() + if ROS_VERSION == 2: + rclpy.spin_once(self) if self._global_plan: control = self.run_step() if control: @@ -149,11 +151,10 @@ def run(self): if ROS_VERSION == 1: r.sleep() elif ROS_VERSION == 2: - #TODO: use rclpy.Rate, not working yet + # TODO: use rclpy.Rate, not working yet time.sleep(1 / loop_frequency) except ROSInterruptException: pass - def main(args=None): diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 24bb3283..2bb4c8e2 100644 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -13,10 +13,18 @@ from collections import deque from geometry_msgs.msg import PointStamped # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error -from carla_ad_agent.vehicle_pid_controller import VehiclePIDController -from carla_ad_agent.misc import distance_vehicle from ros_compatibility import QoSProfile +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 1: + from vehicle_pid_controller import VehiclePIDController + from misc import distance_vehicle +elif ROS_VERSION == 2: + from carla_ad_agent.vehicle_pid_controller import VehiclePIDController + from carla_ad_agent.misc import distance_vehicle + class LocalPlanner(object): """ diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index 41ac0fbb..d0074f9e 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -11,7 +11,6 @@ from collections import deque import math import numpy as np -import rclpy from ros_compatibility import euler_from_quaternion, get_time # pylint: disable=import-error from geometry_msgs.msg import Point # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error @@ -45,7 +44,7 @@ def __init__(self, node, args_lateral=None, args_longitudinal=None): self.node = node self._lon_controller = PIDLongitudinalController(**args_longitudinal) self._lat_controller = PIDLateralController(**args_lateral) - self._last_control_time = float(get_time(self.node).nanoseconds/10**9) + self._last_control_time = get_time(self.node) def run_step(self, target_speed, current_speed, current_pose, waypoint): """ @@ -56,7 +55,7 @@ def run_step(self, target_speed, current_speed, current_pose, waypoint): :param waypoint: target location encoded as a waypoint :return: distance (in meters) to the waypoint """ - current_time = float(get_time(self.node).nanoseconds/10**9) + current_time = get_time(self.node) dt = current_time-self._last_control_time if dt == 0.0: dt = 0.000001 diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 75a50506..f41dce20 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -6,24 +6,24 @@ set(ROS_VERSION $ENV{ROS_VERSION}) if(${ROS_VERSION} EQUAL 1) - find_package(catkin REQUIRED COMPONENTS roslaunch) + find_package(catkin REQUIRED COMPONENTS roslaunch) - roslaunch_add_file_check(launch) + roslaunch_add_file_check(launch) - catkin_package() + catkin_package() - install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) - install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) + install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + find_package(ament_cmake REQUIRED) - ament_package() + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + + ament_package() endif() diff --git a/carla_waypoint_publisher/CMakeLists.txt b/carla_waypoint_publisher/CMakeLists.txt index b05e016a..7ac5d003 100644 --- a/carla_waypoint_publisher/CMakeLists.txt +++ b/carla_waypoint_publisher/CMakeLists.txt @@ -5,7 +5,7 @@ find_package(ros_environment REQUIRED) set(ROS_VERSION $ENV{ROS_VERSION}) -if (${ROS_VERSION} EQUAL 1) +if(${ROS_VERSION} EQUAL 1) find_package(catkin REQUIRED COMPONENTS rospy roslaunch) @@ -16,8 +16,8 @@ if (${ROS_VERSION} EQUAL 1) catkin_package(CATKIN_DEPENDS rospy) catkin_install_python( - PROGRAMS src/carla_waypoint_publisher/carla_waypoint_publisher.py DESTINATION - ${CATKIN_PACKAGE_BIN_DESTINATION}) + PROGRAMS src/carla_waypoint_publisher/carla_waypoint_publisher.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) @@ -32,4 +32,4 @@ elseif(${ROS_VERSION} EQUAL 2) ament_package() -endif() \ No newline at end of file +endif() diff --git a/carla_waypoint_publisher/setup.py b/carla_waypoint_publisher/setup.py index 184ab78f..894f9cae 100755 --- a/carla_waypoint_publisher/setup.py +++ b/carla_waypoint_publisher/setup.py @@ -12,8 +12,8 @@ from catkin_pkg.python_setup import generate_distutils_setup d = generate_distutils_setup( - packages=['carla_waypoint_publisher'], - package_dir={'': 'src'}, + packages=['carla_waypoint_publisher'], + package_dir={'': 'src'}, ) setup(**d) @@ -43,4 +43,3 @@ }, package_dir={'': 'src'}, ) - diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index a5a410ab..3ab7e482 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -22,19 +22,19 @@ import threading import os -from ros_compatibility import ( euler_from_quaternion, - quaternion_from_euler, - CompatibleNode, - QoSProfile, - get_time, - ROSException, - ros_timestamp) +from ros_compatibility import (euler_from_quaternion, + quaternion_from_euler, + CompatibleNode, + QoSProfile, + get_time, + ROSException, + ros_timestamp) from nav_msgs.msg import Path # pylint: disable=import-error from geometry_msgs.msg import PoseStamped # pylint: disable=import-error from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error # from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint # pylint: disable=import-error # from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint # pylint: disable=import-error -from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error +from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error from carla_waypoint_types.srv import GetActorWaypoint # pylint: disable=import-error import carla @@ -44,9 +44,13 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 2: +if ROS_VERSION == 1: + from carla_waypoint_types.srv import GetWaypointResponse # pylint: disable=import-error + from carla_waypoint_types.srv import GetActorWaypointResponse +elif ROS_VERSION == 2: import rclpy # pylint: disable=import-error + class CarlaToRosWaypointConverter(CompatibleNode): """ @@ -71,15 +75,15 @@ def __init__(self): self.role_name = self.get_param("role_name", 'ego_vehicle') self.waypoint_publisher = self.new_publisher( Path, '/carla/{}/waypoints'.format(self.role_name), QoSProfile(depth=1, durability=True)) - + # initialize ros services self.getWaypointService = self.new_service( - GetWaypoint, + GetWaypoint, '/carla_waypoint_publisher/{}/get_waypoint'.format(self.role_name), self.get_waypoint) self.getActorWaypointService = self.new_service( - GetActorWaypoint, - '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(self.role_name), + GetActorWaypoint, + '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(self.role_name), self.get_actor_waypoint) # set initial goal @@ -103,7 +107,7 @@ def destroy(self): if self.on_tick: self.world.remove_on_tick(self.on_tick) - def get_waypoint(self, req, response): + def get_waypoint(self, req, response=None): """ Get the waypoint for a location """ @@ -114,7 +118,8 @@ def get_waypoint(self, req, response): carla_waypoint = self.map.get_waypoint(carla_position) - # response = GetWaypointResponse() + if ROS_VERSION == 1: + response = GetWaypointResponse() response.waypoint.pose.position.x = carla_waypoint.transform.location.x response.waypoint.pose.position.y = -carla_waypoint.transform.location.y response.waypoint.pose.position.z = carla_waypoint.transform.location.z @@ -125,14 +130,15 @@ def get_waypoint(self, req, response): #self.logwarn("Get waypoint {}".format(response.waypoint.pose.position)) return response - def get_actor_waypoint(self, req, response): + def get_actor_waypoint(self, req, response=None): """ Convenience method to get the waypoint for an actor """ - self.loginfo("get_actor_waypoint(): Get waypoint of actor {}".format(req.id)) + # self.loginfo("get_actor_waypoint(): Get waypoint of actor {}".format(req.id)) actor = self.world.get_actors().find(req.id) - # response = GetActorWaypointResponse() + if ROS_VERSION == 1: + response = GetActorWaypointResponse() if actor: carla_waypoint = self.map.get_waypoint(actor.get_location()) response.waypoint.pose.position.x = carla_waypoint.transform.location.x @@ -245,8 +251,8 @@ def publish_waypoints(self): """ msg = Path() msg.header.frame_id = "map" - time_stamp = get_time(self).seconds_nanoseconds() - msg.header.stamp = ros_timestamp(time_stamp[0], time_stamp[1]) + time_stamp = get_time(self) + msg.header.stamp = ros_timestamp(time_stamp, from_sec=True) if self.current_route is not None: for wp in self.current_route: pose = PoseStamped() @@ -265,12 +271,11 @@ def publish_waypoints(self): self.waypoint_publisher.publish(msg) self.loginfo("Published {} waypoints.".format(len(msg.poses))) - def connect_to_carla(self): self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: - self.wait_for_one_message("/carla/world_info", CarlaWorldInfo)#, timeout=10.0) + self.wait_for_one_message("/carla/world_info", CarlaWorldInfo) # , timeout=10.0) except ROSException: self.logerr("Error while waiting for world info!") sys.exit(1) @@ -279,7 +284,7 @@ def connect_to_carla(self): port = self.get_param("carla/port", 2000) timeout = self.get_param("carla/timeout", 10) self.loginfo("CARLA world available. Trying to connect to {host}:{port}".format( - host=host, port=port)) + host=host, port=port)) carla_client = carla.Client(host=host, port=port) carla_client.set_timeout(timeout) @@ -300,7 +305,7 @@ def main(args=None): waypointConverter = CarlaToRosWaypointConverter() waypointConverter.spin() del waypointConverter - + finally: # self.loginfo("Done") print("Done") diff --git a/carla_waypoint_types/CMakeLists.txt b/carla_waypoint_types/CMakeLists.txt index ef4b4a04..3cad5ade 100644 --- a/carla_waypoint_types/CMakeLists.txt +++ b/carla_waypoint_types/CMakeLists.txt @@ -4,53 +4,52 @@ find_package(ros_environment REQUIRED) set(ROS_VERSION $ENV{ROS_VERSION}) -if (${ROS_VERSION} EQUAL 1) - cmake_minimum_required(VERSION 2.8.3) +if(${ROS_VERSION} EQUAL 1) + cmake_minimum_required(VERSION 2.8.3) - find_package(catkin REQUIRED COMPONENTS message_generation nav_msgs) + find_package(catkin REQUIRED COMPONENTS message_generation nav_msgs) - add_service_files(DIRECTORY srv FILES GetWaypoint.srv GetActorWaypoint.srv) + add_service_files(DIRECTORY srv FILES GetWaypoint.srv GetActorWaypoint.srv) - add_message_files(DIRECTORY msg FILES CarlaWaypoint.msg) + add_message_files(DIRECTORY msg FILES CarlaWaypoint.msg) - generate_messages(DEPENDENCIES nav_msgs) - - catkin_package(CATKIN_DEPENDS nav_msgs) + generate_messages(DEPENDENCIES nav_msgs) + catkin_package(CATKIN_DEPENDS nav_msgs) elseif(${ROS_VERSION} EQUAL 2) - cmake_minimum_required(VERSION 3.5) + cmake_minimum_required(VERSION 3.5) - if(NOT CMAKE_CXX_STANDARD) + if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_STANDARD 14) - endif() + endif() - if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) - endif() - - find_package(ament_cmake REQUIRED) - find_package(nav_msgs REQUIRED) - find_package(rosidl_default_generators REQUIRED) + endif() + find_package(ament_cmake REQUIRED) + find_package(nav_msgs REQUIRED) + find_package(rosidl_default_generators REQUIRED) - rosidl_generate_interfaces(${PROJECT_NAME} + rosidl_generate_interfaces( + ${PROJECT_NAME} msg/CarlaWaypoint.msg - srv/GetWaypoint.srv + srv/GetWaypoint.srv srv/GetActorWaypoint.srv - DEPENDENCIES nav_msgs - ADD_LINTER_TESTS - ) + DEPENDENCIES + nav_msgs + ADD_LINTER_TESTS) - ament_export_dependencies(rosidl_default_runtime) + ament_export_dependencies(rosidl_default_runtime) - if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() - endif() + if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + endif() - ament_package() + ament_package() -endif() \ No newline at end of file +endif() diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 2926c496..42df880e 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -37,9 +37,9 @@ def quaternion_from_matrix(matrix): def quaternion_multiply(q1, q2): return trans.quaternion_multiply(q1, q2) - + def get_time(node): - return rospy.Time.now() + return rospy.get_time() class ROSException(rospy.ROSException): pass @@ -103,19 +103,25 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile=None, qos_profile = self.qos_profile return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) - def wait_for_one_message(self, topic, topic_type, timeout = None): + def wait_for_one_message(self, topic, topic_type, timeout=None): return rospy.wait_for_message(topic, topic_type, timeout) def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): return rospy.Service(srv_name, srv_type, callback) - def create_service_client(service_name, service): + def create_service_client(self, service_name, service, callback_group=None): rospy.wait_for_service(service_name) - client = rospy.ServiceProxy(service_name, service) + try: + client = rospy.ServiceProxy(service_name, service) + except rospy.ServiceException as e: + print("Service call failed: %s" % e) return client - def call_service(curr_node, client, req): - return client(req) + def call_service(self, client, req): + try: + return client(req) + except rospy.ServiceException as e: + print("Service call failed: %s" % e) def spin(self, executor=None): rospy.spin() @@ -179,11 +185,14 @@ def quaternion_multiply(q1, q2): return [quat[1], quat[2], quat[3], quat[0]] def get_time(node): - return node.get_clock().now() + t = node.get_clock().now() + t = t.seconds_nanoseconds() + return float(t[0] + (t[1] / 10**9)) class WaitForMessageHelper(object): def __init__(self): self.msg = None + def callback(self, msg): if self.msg is None: self.msg = msg @@ -254,7 +263,7 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile=None, return self.create_subscription(msg_type, topic, callback, qos_profile, callback_group=callback_group) - def wait_for_one_message(self, topic, topic_type, timeout = None): + def wait_for_one_message(self, topic, topic_type, timeout=None): s = None spin_timeout = 0.5 loop_reps = -1 @@ -264,13 +273,13 @@ def wait_for_one_message(self, topic, topic_type, timeout = None): try: s = self.create_subscriber(topic_type, topic, wfm.callback) while ros_ok() and wfm.msg is None: - rclpy.spin_once(self, timeout_sec = spin_timeout) + rclpy.spin_once(self, timeout_sec=spin_timeout) loop_reps = loop_reps - 1 if loop_reps == 0: raise ROSException finally: if s is not None: - self.destroy_subscription(s) + self.destroy_subscription(s) return wfm.msg def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): @@ -289,16 +298,12 @@ def call_service(self, client, req): result = resp.result() except Exception as e: node.get_logger().info('Service call failed %r' % (e,)) - else: + else: return result - def spin(self, executor=None): rclpy.spin(self) - def spin_once(self, executor=None): - rclpy.spin_once(self) - def shutdown(self): rclpy.shutdown() From 4470926e915d29be11129c468de86dce6df9c80a Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 30 Sep 2020 10:12:04 +0200 Subject: [PATCH 320/627] some subscribers were not taking latched topics into account in carla_ad_demo, ros2 --- carla_ad_agent/src/carla_ad_agent/agent.py | 6 ++++-- carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py | 5 +++-- .../carla_waypoint_publisher/carla_waypoint_publisher.py | 7 +++---- .../src/ros_compatibility/ros_compatible_node.py | 6 +++--- 4 files changed, 13 insertions(+), 11 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 3e5aa320..bb4f9a9a 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -19,7 +19,9 @@ euler_from_quaternion, ros_ok, ServiceException, - ROSInterruptException) + ROSInterruptException, + QoSProfile, + latch_on) import os ROS_VERSION = int(os.environ['ROS_VERSION']) @@ -66,7 +68,7 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): "/carla/traffic_lights", self.traffic_lights_updated) node.create_subscriber(CarlaWorldInfo, - "/carla/world_info", self.world_info_updated) + "/carla/world_info", self.world_info_updated, qos_profile=QoSProfile(depth=1, durability=latch_on)) def traffic_lights_updated(self, traffic_lights): """ diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 2ef2e858..3593117d 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -13,7 +13,7 @@ from nav_msgs.msg import Path # pylint: disable=import-error from std_msgs.msg import Float64 # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl # pylint: disable=import-error -from ros_compatibility import CompatibleNode, ROSInterruptException, ros_ok, QoSProfile, ROSException +from ros_compatibility import CompatibleNode, ROSInterruptException, ros_ok, QoSProfile, ROSException, latch_on import os ROS_VERSION = int(os.environ['ROS_VERSION']) @@ -52,7 +52,8 @@ def __init__(self): try: self.loginfo("Wait for vehicle info ...") vehicle_info = self.wait_for_one_message( - "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) + "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, + qos_profile=QoSProfile(depth=1, durability=latch_on)) self.loginfo("Vehicle info recieved.") except ROSException: self.logerr("Timeout while waiting for vehicle info!") diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 3ab7e482..1a28ba2e 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -28,12 +28,11 @@ QoSProfile, get_time, ROSException, - ros_timestamp) + ros_timestamp, + latch_on) from nav_msgs.msg import Path # pylint: disable=import-error from geometry_msgs.msg import PoseStamped # pylint: disable=import-error from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error -# from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint # pylint: disable=import-error -# from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint # pylint: disable=import-error from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error from carla_waypoint_types.srv import GetActorWaypoint # pylint: disable=import-error @@ -275,7 +274,7 @@ def connect_to_carla(self): self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: - self.wait_for_one_message("/carla/world_info", CarlaWorldInfo) # , timeout=10.0) + self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) # , timeout=10.0) except ROSException: self.logerr("Error while waiting for world info!") sys.exit(1) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 42df880e..53622b74 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -103,7 +103,7 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile=None, qos_profile = self.qos_profile return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) - def wait_for_one_message(self, topic, topic_type, timeout=None): + def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None): return rospy.wait_for_message(topic, topic_type, timeout) def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): @@ -263,7 +263,7 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile=None, return self.create_subscription(msg_type, topic, callback, qos_profile, callback_group=callback_group) - def wait_for_one_message(self, topic, topic_type, timeout=None): + def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None): s = None spin_timeout = 0.5 loop_reps = -1 @@ -271,7 +271,7 @@ def wait_for_one_message(self, topic, topic_type, timeout=None): loop_reps = timeout // spin_timeout + 1 wfm = WaitForMessageHelper() try: - s = self.create_subscriber(topic_type, topic, wfm.callback) + s = self.create_subscriber(topic_type, topic, wfm.callback, qos_profile=qos_profile) while ros_ok() and wfm.msg is None: rclpy.spin_once(self, timeout_sec=spin_timeout) loop_reps = loop_reps - 1 From a20e27d8d13124093d89871cc06c75347f7a7c85 Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 30 Sep 2020 10:13:30 +0200 Subject: [PATCH 321/627] formatting --- .../src/carla_waypoint_publisher/carla_waypoint_publisher.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 1a28ba2e..60076c3d 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -274,7 +274,8 @@ def connect_to_carla(self): self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: - self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) # , timeout=10.0) + self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, + qos_profile=QoSProfile(depth=1, durability=latch_on)) # , timeout=10.0) except ROSException: self.logerr("Error while waiting for world info!") sys.exit(1) From ea52a3a3b9aa888967a7fc94bc8d82949e354975 Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 30 Sep 2020 12:31:27 +0200 Subject: [PATCH 322/627] fixes problems for review --- carla_ad_agent/src/carla_ad_agent/agent.py | 39 ++++++++++--------- .../src/carla_ad_agent/basic_agent.py | 8 ---- .../src/carla_ad_agent/carla_ad_agent.py | 6 +-- .../src/carla_ad_agent/local_planner.py | 2 +- .../carla_ad_agent/vehicle_pid_controller.py | 6 +-- carla_ad_demo/launch/carla_ad_demo.launch.py | 1 + .../carla_waypoint_publisher.py | 5 +-- mixin/skip.mixin | 4 -- .../ros_compatibility/ros_compatible_node.py | 16 ++++---- 9 files changed, 37 insertions(+), 50 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index bb4f9a9a..7c1ca724 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -125,12 +125,13 @@ def _is_light_red_europe_style(self, lights_list): - traffic_light is the object itself or None if there is no red traffic light affecting us """ - if self._vehicle_location is not None and ROS_VERSION == 2: - ego_vehicle_location = GetWaypoint.Request() - ego_vehicle_location.location = self._vehicle_location - elif self._vehicle_location is not None and ROS_VERSION == 1: - ego_vehicle_location = GetWaypointRequest() - ego_vehicle_location.location = self._vehicle_location + if self._vehicle_location is not None: + if ROS_VERSION == 2: + ego_vehicle_location = GetWaypoint.Request() + ego_vehicle_location.location = self._vehicle_location + elif ROS_VERSION == 1: + ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) @@ -182,12 +183,13 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc - traffic_light is the object itself or None if there is no red traffic light affecting us """ - if self._vehicle_location is not None and ROS_VERSION == 2: - ego_vehicle_location = GetWaypoint.Request() - ego_vehicle_location.location = self._vehicle_location - elif self._vehicle_location is not None and ROS_VERSION == 1: - ego_vehicle_location = GetWaypointRequest() - ego_vehicle_location.location = self._vehicle_location + if self._vehicle_location is not None: + if ROS_VERSION == 2: + ego_vehicle_location = GetWaypoint.Request() + ego_vehicle_location.location = self._vehicle_location + elif ROS_VERSION == 1: + ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) @@ -269,12 +271,13 @@ def _is_vehicle_hazard(self, vehicle_list, objects): - vehicle is the blocker object itself """ - if self._vehicle_location is not None and ROS_VERSION == 2: - ego_vehicle_location = GetWaypoint.Request() - ego_vehicle_location.location = self._vehicle_location - elif self._vehicle_location is not None and ROS_VERSION == 1: - ego_vehicle_location = GetWaypointRequest() - ego_vehicle_location.location = self._vehicle_location + if self._vehicle_location is not None: + if ROS_VERSION == 2: + ego_vehicle_location = GetWaypoint.Request() + ego_vehicle_location.location = self._vehicle_location + elif ROS_VERSION == 1: + ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 7b2f0ade..70ec9d63 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -18,14 +18,6 @@ import math from ros_compatibility import ( ros_ok, - ros_ok, - ros_ok, - ros_ok, - ros_ok, - ServiceException, - ServiceException, - ServiceException, - ServiceException, ServiceException, ROSInterruptException) diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 3593117d..e64f9ec2 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -20,7 +20,7 @@ if ROS_VERSION == 1: import rospy - # TODO: shouldn't be necessary + # TODO: different ways to import the carla_ad_agent submodules (e.g. carla_ad_agent.basic_agent) between ros1 and ros2 shouldn't be necessary from basic_agent import BasicAgent elif ROS_VERSION == 2: import rclpy @@ -123,10 +123,6 @@ def run_step(self): return control - def spin_loop(self): - while ros_ok: - self.spin_once() - def run(self): """ diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 2bb4c8e2..1599382a 100644 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -119,7 +119,7 @@ def run_step(self, target_speed, current_speed, current_pose): control.hand_brake = False control.manual_gear_shift = False - self.node.logwarn("Route finished.") + self.node.loginfo("Route finished.") return control, True # Buffering the waypoints diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index d0074f9e..f7811c39 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -11,7 +11,7 @@ from collections import deque import math import numpy as np -from ros_compatibility import euler_from_quaternion, get_time # pylint: disable=import-error +from ros_compatibility import euler_from_quaternion # pylint: disable=import-error from geometry_msgs.msg import Point # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error @@ -44,7 +44,7 @@ def __init__(self, node, args_lateral=None, args_longitudinal=None): self.node = node self._lon_controller = PIDLongitudinalController(**args_longitudinal) self._lat_controller = PIDLateralController(**args_lateral) - self._last_control_time = get_time(self.node) + self._last_control_time = self.node.get_time() def run_step(self, target_speed, current_speed, current_pose, waypoint): """ @@ -55,7 +55,7 @@ def run_step(self, target_speed, current_speed, current_pose, waypoint): :param waypoint: target location encoded as a waypoint :return: distance (in meters) to the waypoint """ - current_time = get_time(self.node) + current_time = self.node.get_time() dt = current_time-self._last_control_time if dt == 0.0: dt = 0.000001 diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 184c1a8e..96466e96 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -56,6 +56,7 @@ def generate_launch_description(): name='avoid_risk', default_value='True' ), + # TODO: adapt this to ROS2 # launch_ros.actions.Node( # package='rostopic', # node_executable='rostopic', diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 60076c3d..eb2d689d 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -26,7 +26,6 @@ quaternion_from_euler, CompatibleNode, QoSProfile, - get_time, ROSException, ros_timestamp, latch_on) @@ -250,7 +249,7 @@ def publish_waypoints(self): """ msg = Path() msg.header.frame_id = "map" - time_stamp = get_time(self) + time_stamp = self.get_time() msg.header.stamp = ros_timestamp(time_stamp, from_sec=True) if self.current_route is not None: for wp in self.current_route: @@ -275,7 +274,7 @@ def connect_to_carla(self): self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, - qos_profile=QoSProfile(depth=1, durability=latch_on)) # , timeout=10.0) + qos_profile=QoSProfile(depth=1, durability=latch_on), timeout=10.0) except ROSException: self.logerr("Error while waiting for world info!") sys.exit(1) diff --git a/mixin/skip.mixin b/mixin/skip.mixin index 83500eb9..2128a67f 100644 --- a/mixin/skip.mixin +++ b/mixin/skip.mixin @@ -2,15 +2,11 @@ "build": { "skip": { "packages-skip": ["carla_ackermann_control", - "carla_ad_agent", - "carla_ad_demo", "carla_infrastructure", "carla_ros_scenario_runner", "carla_ros_scenario_runner_types", "carla_spectator_camera", "carla_walker_agent", - "carla_waypoint_publisher", - "carla_waypoint_types", "pcl_recorder", "rqt_carla_control", "rviz_carla_plugin", diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 53622b74..4dfe8639 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -38,9 +38,6 @@ def quaternion_from_matrix(matrix): def quaternion_multiply(q1, q2): return trans.quaternion_multiply(q1, q2) - def get_time(node): - return rospy.get_time() - class ROSException(rospy.ROSException): pass @@ -126,6 +123,9 @@ def call_service(self, client, req): def spin(self, executor=None): rospy.spin() + def get_time(self): + return rospy.get_time() + def shutdown(self): rospy.signal_shutdown("") @@ -184,11 +184,6 @@ def quaternion_multiply(q1, q2): quat = qmult(q1, q2) return [quat[1], quat[2], quat[3], quat[0]] - def get_time(node): - t = node.get_clock().now() - t = t.seconds_nanoseconds() - return float(t[0] + (t[1] / 10**9)) - class WaitForMessageHelper(object): def __init__(self): self.msg = None @@ -304,6 +299,11 @@ def call_service(self, client, req): def spin(self, executor=None): rclpy.spin(self) + def get_time(self): + t = self.get_clock().now() + t = t.seconds_nanoseconds() + return float(t[0] + (t[1] / 10**9)) + def shutdown(self): rclpy.shutdown() From a58628942e6e27292ad8f3fab467f78a31a55f0a Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 30 Sep 2020 13:32:15 +0200 Subject: [PATCH 323/627] corrected one more code mistake --- carla_ad_agent/src/carla_ad_agent/agent.py | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 7c1ca724..96fa2710 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -128,10 +128,9 @@ def _is_light_red_europe_style(self, lights_list): if self._vehicle_location is not None: if ROS_VERSION == 2: ego_vehicle_location = GetWaypoint.Request() - ego_vehicle_location.location = self._vehicle_location elif ROS_VERSION == 1: ego_vehicle_location = GetWaypointRequest() - ego_vehicle_location.location = self._vehicle_location + ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) @@ -186,10 +185,9 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc if self._vehicle_location is not None: if ROS_VERSION == 2: ego_vehicle_location = GetWaypoint.Request() - ego_vehicle_location.location = self._vehicle_location elif ROS_VERSION == 1: ego_vehicle_location = GetWaypointRequest() - ego_vehicle_location.location = self._vehicle_location + ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) @@ -274,10 +272,9 @@ def _is_vehicle_hazard(self, vehicle_list, objects): if self._vehicle_location is not None: if ROS_VERSION == 2: ego_vehicle_location = GetWaypoint.Request() - ego_vehicle_location.location = self._vehicle_location elif ROS_VERSION == 1: ego_vehicle_location = GetWaypointRequest() - ego_vehicle_location.location = self._vehicle_location + ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location From a9f52f3091e9380c62eee6e565bb15b8857a21e3 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 30 Sep 2020 14:55:29 +0200 Subject: [PATCH 324/627] Disable rosdep install for eloquent --- docker/Dockerfile.eloquent | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent index 49fd92c0..3bb4e158 100644 --- a/docker/Dockerfile.eloquent +++ b/docker/Dockerfile.eloquent @@ -40,7 +40,7 @@ SHELL ["/bin/bash", "-c" , "-l"] RUN echo "source /opt/ros/$ROS_VERSION/setup.bash" >> /etc/profile RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment -RUN rosdep install --from-paths src -r -y +#RUN rosdep install --from-paths src -r -y RUN colcon info carla_msgs # .bashrc does not seem to do the source RUN colcon mixin add skip file:///carla_ws/src/ros-bridge/mixin/index.yaml From 81f5ed74712a90ef2c0a342e3ba31c61d81ef1ab Mon Sep 17 00:00:00 2001 From: "Kai A. Hiller" Date: Mon, 5 Oct 2020 17:36:15 +0200 Subject: [PATCH 325/627] [ROS2] Port carla_ackermann_control (#377) * Add compatibility functions * Move carla_ackermann_control messages to separate package This is required because carla_ackermann_control is a pure ament python package. Currently this package type does not support building of messages. As a workaround we move the messages to a new package and build them via ament cmake. * Port carla_ackermann_control to ROS2 * Adapt to ROS2 parameter handling * Enable build of carla_ackermann_control * some modifications to work with ros1 and eloquent * fix formating * uses the new get_time function from ros_compatibility * added comments about python3 functions * added instructions on ackermann_msgs in readme, fixed formating Co-authored-by: jbmag Co-authored-by: jbmag <47941074+jbmag@users.noreply.github.com> --- carla_ackermann_control/CMakeLists.txt | 17 +- carla_ackermann_control/README.md | 9 + .../config/settings.ros1.yaml | 16 + carla_ackermann_control/config/settings.yaml | 10 +- .../launch/carla_ackermann_control.launch | 4 +- .../launch/carla_ackermann_control.launch.py | 7 +- carla_ackermann_control/package.xml | 32 +- .../resource/carla_ackermann_control | 0 carla_ackermann_control/setup.cfg | 4 + carla_ackermann_control/setup.py | 47 ++- .../carla_ackermann_control_node.py | 311 +++++++++++------- .../carla_control_physics.py | 2 +- carla_ackermann_msgs/CMakeLists.txt | 69 ++++ .../msg/EgoVehicleControlCurrent.msg | 0 .../msg/EgoVehicleControlInfo.msg | 2 +- .../msg/EgoVehicleControlMaxima.msg | 0 .../msg/EgoVehicleControlStatus.msg | 0 .../msg/EgoVehicleControlTarget.msg | 0 carla_ackermann_msgs/package.xml | 37 +++ mixin/skip.mixin | 4 +- .../ros_compatibility/ros_compatible_node.py | 12 + 21 files changed, 421 insertions(+), 162 deletions(-) create mode 100644 carla_ackermann_control/config/settings.ros1.yaml create mode 100644 carla_ackermann_control/resource/carla_ackermann_control create mode 100644 carla_ackermann_control/setup.cfg create mode 100644 carla_ackermann_msgs/CMakeLists.txt rename {carla_ackermann_control => carla_ackermann_msgs}/msg/EgoVehicleControlCurrent.msg (100%) rename {carla_ackermann_control => carla_ackermann_msgs}/msg/EgoVehicleControlInfo.msg (95%) rename {carla_ackermann_control => carla_ackermann_msgs}/msg/EgoVehicleControlMaxima.msg (100%) rename {carla_ackermann_control => carla_ackermann_msgs}/msg/EgoVehicleControlStatus.msg (100%) rename {carla_ackermann_control => carla_ackermann_msgs}/msg/EgoVehicleControlTarget.msg (100%) create mode 100644 carla_ackermann_msgs/package.xml diff --git a/carla_ackermann_control/CMakeLists.txt b/carla_ackermann_control/CMakeLists.txt index 1cbe1d28..e818ddb1 100644 --- a/carla_ackermann_control/CMakeLists.txt +++ b/carla_ackermann_control/CMakeLists.txt @@ -3,24 +3,11 @@ project(carla_ackermann_control) # Find catkin macros and libraries find_package( - catkin REQUIRED - COMPONENTS message_generation - rospy - std_msgs - ackermann_msgs - dynamic_reconfigure - carla_msgs - roslaunch) + catkin REQUIRED COMPONENTS rospy std_msgs ackermann_msgs dynamic_reconfigure + carla_msgs roslaunch) catkin_python_setup() -add_message_files( - FILES EgoVehicleControlCurrent.msg EgoVehicleControlInfo.msg - EgoVehicleControlMaxima.msg EgoVehicleControlStatus.msg - EgoVehicleControlTarget.msg) - -generate_messages(DEPENDENCIES std_msgs carla_msgs) - generate_dynamic_reconfigure_options(config/EgoVehicleControlParameter.cfg) roslaunch_add_file_check(launch) diff --git a/carla_ackermann_control/README.md b/carla_ackermann_control/README.md index 71fc8464..777cbb51 100644 --- a/carla_ackermann_control/README.md +++ b/carla_ackermann_control/README.md @@ -10,6 +10,15 @@ ROS Node to convert [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html #install python simple-pid pip install --user simple-pid +### Using with ROS2 +There is currently no package release of _ackeramnn_msgs_ for ROS2 eloquent. A simple solution is to clone the source from github into your ros workspace. The following commands can be used: + + # In your ros workspace do: + git clone https://github.com/ros-drivers/ackermann_msgs.git + git fetch + git checkout ros2 + + ### Configuration Initial parameters can be set via [configuration file](config/settings.yaml). diff --git a/carla_ackermann_control/config/settings.ros1.yaml b/carla_ackermann_control/config/settings.ros1.yaml new file mode 100644 index 00000000..036568db --- /dev/null +++ b/carla_ackermann_control/config/settings.ros1.yaml @@ -0,0 +1,16 @@ +# override the default values of the pid speed controller +# (only relevant for ackermann control mode) +speed_Kp: 0.05 +speed_Ki: 0.00 +speed_Kd: 0.50 +# override the default values of the pid acceleration controller +# (only relevant for ackermann control mode) +accel_Kp: 0.02 +accel_Ki: 0.00 +accel_Kd: 0.05 +# set the minimum acceleration in (m/s^2) +# This border value is used to enable the speed controller which is used to control driving +# at more or less constant speed. +# If the absolute value of the ackermann drive target acceleration exceeds this value, +# directly the input acceleration is controlled +min_accel: 1.0 diff --git a/carla_ackermann_control/config/settings.yaml b/carla_ackermann_control/config/settings.yaml index b2a1047d..4b3abc1a 100644 --- a/carla_ackermann_control/config/settings.yaml +++ b/carla_ackermann_control/config/settings.yaml @@ -1,7 +1,7 @@ -carla: - ackermann_control: +carla_ackermann_control: + ros__parameters: # override the default values of the pid speed controller - # (only relevant for ackermann control mode) + # (only relevant for ackermann control mode) speed_Kp: 0.05 speed_Ki: 0.00 speed_Kd: 0.50 @@ -11,8 +11,8 @@ carla: accel_Ki: 0.00 accel_Kd: 0.05 # set the minimum acceleration in (m/s^2) - # This border value is used to enable the speed controller which is used to control driving + # This border value is used to enable the speed controller which is used to control driving # at more or less constant speed. # If the absolute value of the ackermann drive target acceleration exceeds this value, - # directly the input acceleration is controlled + # directly the input acceleration is controlled min_accel: 1.0 diff --git a/carla_ackermann_control/launch/carla_ackermann_control.launch b/carla_ackermann_control/launch/carla_ackermann_control.launch index 6056499e..491ff7e6 100644 --- a/carla_ackermann_control/launch/carla_ackermann_control.launch +++ b/carla_ackermann_control/launch/carla_ackermann_control.launch @@ -1,9 +1,9 @@ - - + + diff --git a/carla_ackermann_control/launch/carla_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ackermann_control.launch.py index 69bceb7a..d1ff9238 100644 --- a/carla_ackermann_control/launch/carla_ackermann_control.launch.py +++ b/carla_ackermann_control/launch/carla_ackermann_control.launch.py @@ -1,8 +1,8 @@ -import os -import sys +from pathlib import Path import launch import launch_ros.actions +from ament_index_python.packages import get_package_share_directory def generate_launch_description(): @@ -14,9 +14,10 @@ def generate_launch_description(): launch_ros.actions.Node( package='carla_ackermann_control', node_executable='carla_ackermann_control_node', - name=launch.substitutions.LaunchConfiguration('role_name'), + node_name='carla_ackermann_control', output='screen', parameters=[ + Path(get_package_share_directory('carla_ackermann_control'), "settings.yaml"), { 'role_name': launch.substitutions.LaunchConfiguration('role_name') } diff --git a/carla_ackermann_control/package.xml b/carla_ackermann_control/package.xml index 3e66f8b5..823eed0b 100644 --- a/carla_ackermann_control/package.xml +++ b/carla_ackermann_control/package.xml @@ -1,21 +1,35 @@ - + carla_ackermann_control 0.0.0 The carla_ackermann_control package CARLA Simulator Team MIT - catkin - rospy - carla_msgs - roslaunch - rospy - rospy + ackermann_msgs + carla_ackermann_msgs + carla_msgs carla_ros_bridge + ros_compatibility std_msgs - dynamic_reconfigure - carla_msgs + + + rclpy + ament_python + tf2_ros + + + catkin + rospy + roslaunch + rospy + dynamic_reconfigure + rospy + + rosidl_interface_packages + + catkin + ament_python diff --git a/carla_ackermann_control/resource/carla_ackermann_control b/carla_ackermann_control/resource/carla_ackermann_control new file mode 100644 index 00000000..e69de29b diff --git a/carla_ackermann_control/setup.cfg b/carla_ackermann_control/setup.cfg new file mode 100644 index 00000000..5cfd1ab5 --- /dev/null +++ b/carla_ackermann_control/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_ackermann_control +[install] +install-scripts=$base/lib/carla_ackermann_control diff --git a/carla_ackermann_control/setup.py b/carla_ackermann_control/setup.py index 7fa6e39e..e7a840f1 100644 --- a/carla_ackermann_control/setup.py +++ b/carla_ackermann_control/setup.py @@ -1,13 +1,46 @@ """ Setup for carla_ackermann_control """ +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_ackermann_control'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_ackermann_control'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_ackermann_control' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + (os.path.join('share', package_name), ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.py')), + (os.path.join('share', package_name), ['config/settings.yaml']), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='The carla_ackermann_control package', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + '{}_node = {}.{}_node:main'.format(package_name, package_name, package_name) + ], + }, + package_dir={'': 'src'}, + ) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index 24b5a071..6a28b68f 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -9,24 +9,36 @@ """ Control Carla ego vehicle by using AckermannDrive messages """ +import os import sys import datetime import numpy -import rospy # pylint: disable=import-error -from dynamic_reconfigure.server import Server # pylint: disable=import-error from ackermann_msgs.msg import AckermannDrive # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module,import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=no-name-in-module,import-error from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module,import-error -from carla_ackermann_control.msg import EgoVehicleControlInfo # pylint: disable=no-name-in-module,import-error -from carla_ackermann_control.cfg import EgoVehicleControlParameterConfig # pylint: disable=no-name-in-module,import-error -import carla_control_physics as phys # pylint: disable=relative-import +from carla_ackermann_msgs.msg import EgoVehicleControlInfo # pylint: disable=no-name-in-module,import-error + +from ros_compatibility import CompatibleNode, QoSProfile +from carla_ackermann_control import carla_control_physics as phys from simple_pid import PID # pylint: disable=import-error,wrong-import-order -class CarlaAckermannControl(object): +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + from carla_ackermann_control.cfg import EgoVehicleControlParameterConfig + from dynamic_reconfigure.server import Server +if ROS_VERSION == 2: + import rclpy + from rclpy.parameter import Parameter + from rcl_interfaces.msg import SetParametersResult + from typing import Sequence + + +class CarlaAckermannControl(CompatibleNode): """ Convert ackermann_drive messages to carla VehicleCommand with a PID controller @@ -37,11 +49,70 @@ def __init__(self): Constructor """ - self.control_loop_rate = rospy.Rate(10) # 10Hz + super(CarlaAckermannControl, self).__init__( + "carla_ackermann_control", rospy_init=True + ) + + # PID controller + # the controller has to run with the simulation time, not with real-time + # + # To prevent "float division by zero" within PID controller initialize it with + # a previous point in time (the error happens because the time doesn't + # change between initialization and first call, therefore dt is 0) + sys.modules['simple_pid.PID']._current_time = ( # pylint: disable=protected-access + lambda: self.get_time() - 0.1) + + # we might want to use a PID controller to reach the final target speed + self.speed_controller = PID(Kp=self.get_param("speed_Kp", alternative_value=0.05), + Ki=self.get_param("speed_Ki", alternative_value=0.), + Kd=self.get_param("speed_Kd", alternative_value=0.5), + sample_time=0.05, + output_limits=(-1., 1.)) + self.accel_controller = PID(Kp=self.get_param("accel_Kp", alternative_value=0.05), + Ki=self.get_param("accel_Ki", alternative_value=0.), + Kd=self.get_param("accel_Kd", alternative_value=0.05), + sample_time=0.05, + output_limits=(-1, 1)) + + # use the correct time for further calculations + sys.modules['simple_pid.PID']._current_time = ( # pylint: disable=protected-access + lambda: self.get_time()) + + if ROS_VERSION == 1: + self.reconfigure_server = Server( + EgoVehicleControlParameterConfig, + namespace="", + callback=self.reconfigure_pid_parameters, + ) + if ROS_VERSION == 2: + # self.add_on_set_parameters_callback(self.reconfigure_pid_parameters) # works with ros2 foxy + # for ros2 eloquent, deprecated in ros2 foxy + self.set_parameters_callback(self.reconfigure_pid_parameters) + # TODO(hillekia@schaeffler.com): Enable stricter handling of node + # parameters, so they must be explicitly listed. This can be done by + # disabling the `automatically_declare_parameters_from_overrides` + # and `allow_undeclared_parameters` flags of `Node` and will prevent + # mistakes in the future. + # + # self.declare_parameters( + # namespace="", + # parameters=[ + # ("speed_Kp",), + # ("speed_Ki",), + # ("speed_Kd",), + # ("accel_Kp",), + # ("accel_Ki",), + # ("accel_Kd",), + # ("min_accel",), + # ("role_name",), + # ] + # ) + + self.control_loop_rate = 1.0 / 10 # 10Hz self.lastAckermannMsgReceived = datetime.datetime(datetime.MINYEAR, 1, 1) self.vehicle_status = CarlaEgoVehicleStatus() self.vehicle_info = CarlaEgoVehicleInfo() - self.role_name = rospy.get_param('~role_name', 'ego_vehicle') + self.role_name = self.get_param('role_name', 'ego_vehicle') # control info self.info = EgoVehicleControlInfo() @@ -56,7 +127,7 @@ def __init__(self): self.info.target.jerk = 0. # current values - self.info.current.time_sec = rospy.get_rostime().to_sec() + self.info.current.time_sec = self.get_time() self.info.current.speed = 0. self.info.current.speed_abs = 0. self.info.current.accel = 0. @@ -78,103 +149,112 @@ def __init__(self): self.info.output.reverse = False self.info.output.hand_brake = True - # PID controller - # the controller has to run with the simulation time, not with real-time - # - # To prevent "float division by zero" within PID controller initialize it with - # a previous point in time (the error happens because the time doesn't - # change between initialization and first call, therefore dt is 0) - sys.modules['simple_pid.PID']._current_time = ( # pylint: disable=protected-access - lambda: rospy.get_rostime().to_sec() - 0.1) - - # we might want to use a PID controller to reach the final target speed - self.speed_controller = PID(Kp=0.0, - Ki=0.0, - Kd=0.0, - sample_time=0.05, - output_limits=(-1., 1.)) - self.accel_controller = PID(Kp=0.0, - Ki=0.0, - Kd=0.0, - sample_time=0.05, - output_limits=(-1, 1)) - - # use the correct time for further calculations - sys.modules['simple_pid.PID']._current_time = ( # pylint: disable=protected-access - lambda: rospy.get_rostime().to_sec()) - - self.reconfigure_server = Server( - EgoVehicleControlParameterConfig, - namespace="/carla/" + self.role_name + "/ackermann_control", - callback=(lambda config, level: CarlaAckermannControl.reconfigure_pid_parameters( - self, config, level))) - # ackermann drive commands - self.control_subscriber = rospy.Subscriber( + self.control_subscriber = self.create_subscriber( + AckermannDrive, "/carla/" + self.role_name + "/ackermann_cmd", - AckermannDrive, self.ackermann_command_updated) + self.ackermann_command_updated + ) # current status of the vehicle - self.vehicle_status_subscriber = rospy.Subscriber( + self.vehicle_status_subscriber = self.create_subscriber( + CarlaEgoVehicleStatus, "/carla/" + self.role_name + "/vehicle_status", - CarlaEgoVehicleStatus, self.vehicle_status_updated) + self.vehicle_status_updated, + ) # vehicle info - self.vehicle_info_subscriber = rospy.Subscriber( + self.vehicle_info_subscriber = self.create_subscriber( + CarlaEgoVehicleInfo, "/carla/" + self.role_name + "/vehicle_info", - CarlaEgoVehicleInfo, self.vehicle_info_updated) + self.vehicle_info_updated, + ) # to send command to carla - self.carla_control_publisher = rospy.Publisher( + self.carla_control_publisher = self.new_publisher( + CarlaEgoVehicleControl, "/carla/" + self.role_name + "/vehicle_control_cmd", - CarlaEgoVehicleControl, queue_size=1) + qos_profile=QoSProfile(depth=1)) # report controller info - self.control_info_publisher = rospy.Publisher( + self.control_info_publisher = self.new_publisher( + EgoVehicleControlInfo, "/carla/" + self.role_name + "/ackermann_control/control_info", - EgoVehicleControlInfo, queue_size=1) - - def destroy(self): - """ - Function (override) to destroy this object. - - Terminate ROS subscription on AckermannDrive commands. - Finish the PID controllers. - Destroy the reconfiguration server - - :return: - """ - self.control_subscriber = None - self.speed_controller = None - self.accel_controller = None - # first cleanup the server (otherwise leaves a mess behind ;-) - self.reconfigure_server.set_service.shutdown() - self.reconfigure_server = None - - def reconfigure_pid_parameters(self, ego_vehicle_control_parameter, _level): - """ - Callback for dynamic reconfigure call to set the PID parameters - - :param ego_vehicle_control_parameter: - :type ego_vehicle_control_parameter: \ - carla_ackermann_control.cfg.EgoVehicleControlParameterConfig - - """ - rospy.loginfo("Reconfigure Request: " - "speed ({speed_Kp}, {speed_Ki}, {speed_Kd})," - "accel ({accel_Kp}, {accel_Ki}, {accel_Kd})," - "".format(**ego_vehicle_control_parameter)) - self.speed_controller.tunings = ( - ego_vehicle_control_parameter['speed_Kp'], - ego_vehicle_control_parameter['speed_Ki'], - ego_vehicle_control_parameter['speed_Kd'] - ) - self.accel_controller.tunings = ( - ego_vehicle_control_parameter['accel_Kp'], - ego_vehicle_control_parameter['accel_Ki'], - ego_vehicle_control_parameter['accel_Kd'] - ) - return ego_vehicle_control_parameter + qos_profile=QoSProfile(depth=1)) + + if ROS_VERSION == 1: + + def reconfigure_pid_parameters(self, ego_vehicle_control_parameter, _level): + """ + Callback for dynamic reconfigure call to set the PID parameters + + :param ego_vehicle_control_parameter: + :type ego_vehicle_control_parameter: \ + carla_ackermann_control.cfg.EgoVehicleControlParameterConfig + + """ + self.loginfo("Reconfigure Request: " + "speed ({speed_Kp}, {speed_Ki}, {speed_Kd}), " + "accel ({accel_Kp}, {accel_Ki}, {accel_Kd})" + "".format(**ego_vehicle_control_parameter)) + self.speed_controller.tunings = ( + ego_vehicle_control_parameter['speed_Kp'], + ego_vehicle_control_parameter['speed_Ki'], + ego_vehicle_control_parameter['speed_Kd'], + ) + self.accel_controller.tunings = ( + ego_vehicle_control_parameter['accel_Kp'], + ego_vehicle_control_parameter['accel_Ki'], + ego_vehicle_control_parameter['accel_Kd'], + ) + return ego_vehicle_control_parameter + + if ROS_VERSION == 2: + # annotations not supported in Python 2 (ROS1) + # def reconfigure_pid_parameters( # pylint: disable=function-redefined def reconfigure_pid_parameters(self, params): # pylint: disable=function-redefined + # self, params: Sequence[Parameter] + # ) -> SetParametersResult: + def reconfigure_pid_parameters(self, params): # pylint: disable=function-redefined + """Check and update the node's parameters.""" + param_values = {p.name: p.value for p in params} + + pid_param_names = { + "speed_Kp", + "speed_Ki", + "speed_Kd", + "accel_Kp", + "accel_Ki", + "accel_Kd", + } + common_names = pid_param_names.intersection(param_values.keys()) + if not common_names: + # No work do to + return SetParametersResult(successful=True) + + if any(p.value is None for p in params): + return SetParametersResult( + successful=False, reason="Parameter must have a value assigned" + ) + + self.speed_controller.tunings = ( + param_values.get("speed_Kp", self.speed_controller.Kp), + param_values.get("speed_Ki", self.speed_controller.Ki), + param_values.get("speed_Kd", self.speed_controller.Kd), + ) + self.accel_controller.tunings = ( + param_values.get("accel_Kp", self.accel_controller.Kp), + param_values.get("accel_Ki", self.accel_controller.Ki), + param_values.get("accel_Kd", self.accel_controller.Kd), + ) + + self.loginfo( + "Reconfigure Request: speed ({}, {}, {}), accel ({}, {}, {})".format( + self.speed_controller.tunings[0], self.speed_controller.tunings[1], self.speed_controller.tunings[2], + self.accel_controller.tunings[0], self.accel_controller.tunings[1], self.accel_controller.tunings[2] + ) + ) + + return SetParametersResult(successful=True) def vehicle_status_updated(self, vehicle_status): """ @@ -208,7 +288,7 @@ def vehicle_info_updated(self, vehicle_info): self.vehicle_info) self.info.restrictions.max_decel = phys.get_vehicle_max_deceleration( self.vehicle_info) - self.info.restrictions.min_accel = rospy.get_param('/carla/ackermann_control/min_accel', 1.) + self.info.restrictions.min_accel = self.get_param('min_accel', 1.) # clipping the pedal in both directions to the same range using the usual lower # border: the max_accel to ensure the the pedal target is in symmetry to zero self.info.restrictions.max_pedal = min( @@ -235,7 +315,7 @@ def set_target_steering_angle(self, target_steering_angle): """ self.info.target.steering_angle = -target_steering_angle if abs(self.info.target.steering_angle) > self.info.restrictions.max_steering_angle: - rospy.logerr("Max steering angle reached, clipping value") + self.logerr("Max steering angle reached, clipping value") self.info.target.steering_angle = numpy.clip( self.info.target.steering_angle, -self.info.restrictions.max_steering_angle, @@ -246,7 +326,7 @@ def set_target_speed(self, target_speed): set target speed """ if abs(target_speed) > self.info.restrictions.max_speed: - rospy.logerr("Max speed reached, clipping value") + self.logerr("Max speed reached, clipping value") self.info.target.speed = numpy.clip( target_speed, -self.info.restrictions.max_speed, self.info.restrictions.max_speed) else: @@ -312,12 +392,12 @@ def control_stop_and_reverse(self): self.info.status.status = "standing" if self.info.target.speed < 0: if not self.info.output.reverse: - rospy.loginfo( + self.loginfo( "VehicleControl: Change of driving direction to reverse") self.info.output.reverse = True elif self.info.target.speed > 0: if self.info.output.reverse: - rospy.loginfo( + self.loginfo( "VehicleControl: Change of driving direction to forward") self.info.output.reverse = False if self.info.target.speed_abs < full_stop_epsilon: @@ -336,10 +416,10 @@ def control_stop_and_reverse(self): # requrest for change of driving direction # first we have to come to full stop before changing driving # direction - rospy.loginfo("VehicleControl: Request change of driving direction." - " v_current={} v_desired={}" - " Set desired speed to 0".format(self.info.current.speed, - self.info.target.speed)) + self.loginfo("VehicleControl: Request change of driving direction." + " v_current={} v_desired={}" + " Set desired speed to 0".format(self.info.current.speed, + self.info.target.speed)) self.set_target_speed(0.) def run_speed_control_loop(self): @@ -374,8 +454,8 @@ def run_speed_control_loop(self): if self.speed_controller.auto_mode: self.speed_controller.setpoint = self.info.target.speed_abs - self.info.status.speed_control_accel_delta = self.speed_controller( - self.info.current.speed_abs) + self.info.status.speed_control_accel_delta = float(self.speed_controller( + self.info.current.speed_abs)) # clipping borders clipping_lower_border = -target_accel_abs @@ -398,8 +478,8 @@ def run_accel_control_loop(self): """ # setpoint of the acceleration controller is the output of the speed controller self.accel_controller.setpoint = self.info.status.speed_control_accel_target - self.info.status.accel_control_pedal_delta = self.accel_controller( - self.info.current.accel) + self.info.status.accel_control_pedal_delta = float(self.accel_controller( + self.info.current.accel)) # @todo: we might want to scale by making use of the the abs-jerk value # If the jerk input is big, then the trajectory input expects already quick changes # in the acceleration; to respect this we put an additional proportional factor on top @@ -477,7 +557,7 @@ def update_current_values(self): :return: """ - current_time_sec = rospy.get_rostime().to_sec() + current_time_sec = self.get_time() delta_time = current_time_sec - self.info.current.time_sec current_speed = self.vehicle_status.velocity if delta_time > 0: @@ -497,14 +577,13 @@ def run(self): :return: """ - while not rospy.is_shutdown(): + def loop(timer_event=None): self.update_current_values() self.vehicle_control_cycle() self.send_ego_vehicle_control_info_msg() - try: - self.control_loop_rate.sleep() - except rospy.ROSInterruptException: - pass + + self.new_timer(self.control_loop_rate, loop) + self.spin() def main(): @@ -514,13 +593,11 @@ def main(): :return: """ - rospy.init_node('carla_ackermann_control', anonymous=True) + if ROS_VERSION == 2: + rclpy.init() + controller = CarlaAckermannControl() - try: - controller.run() - finally: - del controller - rospy.loginfo("Done") + controller.run() if __name__ == "__main__": diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py b/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py index ad4a80e9..c4bfc1e6 100644 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py @@ -11,7 +11,7 @@ import math -from tf.transformations import euler_from_quaternion # pylint: disable=import-error +from ros_compatibility import euler_from_quaternion def get_vehicle_lay_off_engine_acceleration(vehicle_info): diff --git a/carla_ackermann_msgs/CMakeLists.txt b/carla_ackermann_msgs/CMakeLists.txt new file mode 100644 index 00000000..69398ae9 --- /dev/null +++ b/carla_ackermann_msgs/CMakeLists.txt @@ -0,0 +1,69 @@ +project(carla_ackermann_msgs) + +find_package(ros_environment REQUIRED) + +set(ROS_VERSION $ENV{ROS_VERSION}) + +set(MSG_FILES + EgoVehicleControlInfo.msg EgoVehicleControlCurrent.msg + EgoVehicleControlMaxima.msg EgoVehicleControlStatus.msg + EgoVehicleControlTarget.msg) + +if(${ROS_VERSION} EQUAL 1) + cmake_minimum_required(VERSION 2.8.3) + + # Find catkin macros and libraries + find_package(catkin REQUIRED COMPONENTS message_generation std_msgs + carla_msgs) + + add_message_files(DIRECTORY msg FILES ${MSG_FILES}) + + generate_messages(DEPENDENCIES std_msgs carla_msgs) + + catkin_package(CATKIN_DEPENDS message_runtime std_msgs carla_msgs) + +elseif(${ROS_VERSION} EQUAL 2) + + cmake_minimum_required(VERSION 3.5) + + if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_STANDARD 14) + endif() + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + + find_package(ament_cmake REQUIRED) + find_package(builtin_interfaces REQUIRED) + find_package(std_msgs REQUIRED) + find_package(carla_msgs REQUIRED) + find_package(rosidl_default_generators REQUIRED) + + # Apend "msg/" to each file name + set(TEMP_LIST "") + foreach(MSG_FILE ${MSG_FILES}) + list(APPEND TEMP_LIST "msg/${MSG_FILE}") + endforeach() + set(MSG_FILES ${TEMP_LIST}) + + rosidl_generate_interfaces( + ${PROJECT_NAME} + ${MSG_FILES} + DEPENDENCIES + builtin_interfaces + std_msgs + carla_msgs + ADD_LINTER_TESTS) + + ament_export_dependencies(rosidl_default_runtime) + + if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + endif() + + ament_package() + +endif() diff --git a/carla_ackermann_control/msg/EgoVehicleControlCurrent.msg b/carla_ackermann_msgs/msg/EgoVehicleControlCurrent.msg similarity index 100% rename from carla_ackermann_control/msg/EgoVehicleControlCurrent.msg rename to carla_ackermann_msgs/msg/EgoVehicleControlCurrent.msg diff --git a/carla_ackermann_control/msg/EgoVehicleControlInfo.msg b/carla_ackermann_msgs/msg/EgoVehicleControlInfo.msg similarity index 95% rename from carla_ackermann_control/msg/EgoVehicleControlInfo.msg rename to carla_ackermann_msgs/msg/EgoVehicleControlInfo.msg index c0d3f25e..2533ebe1 100644 --- a/carla_ackermann_control/msg/EgoVehicleControlInfo.msg +++ b/carla_ackermann_msgs/msg/EgoVehicleControlInfo.msg @@ -6,7 +6,7 @@ # # This represents an info message of the ego vehicle -Header header +std_msgs/Header header # the restrictions EgoVehicleControlMaxima restrictions diff --git a/carla_ackermann_control/msg/EgoVehicleControlMaxima.msg b/carla_ackermann_msgs/msg/EgoVehicleControlMaxima.msg similarity index 100% rename from carla_ackermann_control/msg/EgoVehicleControlMaxima.msg rename to carla_ackermann_msgs/msg/EgoVehicleControlMaxima.msg diff --git a/carla_ackermann_control/msg/EgoVehicleControlStatus.msg b/carla_ackermann_msgs/msg/EgoVehicleControlStatus.msg similarity index 100% rename from carla_ackermann_control/msg/EgoVehicleControlStatus.msg rename to carla_ackermann_msgs/msg/EgoVehicleControlStatus.msg diff --git a/carla_ackermann_control/msg/EgoVehicleControlTarget.msg b/carla_ackermann_msgs/msg/EgoVehicleControlTarget.msg similarity index 100% rename from carla_ackermann_control/msg/EgoVehicleControlTarget.msg rename to carla_ackermann_msgs/msg/EgoVehicleControlTarget.msg diff --git a/carla_ackermann_msgs/package.xml b/carla_ackermann_msgs/package.xml new file mode 100644 index 00000000..7379ac92 --- /dev/null +++ b/carla_ackermann_msgs/package.xml @@ -0,0 +1,37 @@ + + + + carla_ackermann_msgs + 1.0.0 + The carla_ackermann_msgs package + CARLA Simulator Team + MIT + http://carla.org/ + https://github.com/carla-simulator/ros-bridge + https://github.com/carla-simulator/ros-bridge/issues + CARLA Simulator Team + + catkin + ament_cmake + + message_generation + rosidl_default_generators + ros_environment + + builtin_interfaces + std_msgs + carla_msgs + + message_runtime + rosidl_default_runtime + + ament_lint_auto + ament_lint_common + + rosidl_interface_packages + + + catkin + ament_cmake + + diff --git a/mixin/skip.mixin b/mixin/skip.mixin index 2128a67f..2fe3f04d 100644 --- a/mixin/skip.mixin +++ b/mixin/skip.mixin @@ -1,7 +1,7 @@ { "build": { "skip": { - "packages-skip": ["carla_ackermann_control", + "packages-skip": [ "carla_infrastructure", "carla_ros_scenario_runner", "carla_ros_scenario_runner_types", @@ -22,4 +22,4 @@ ], } } -} \ No newline at end of file +} diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 4dfe8639..73de50b7 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -100,6 +100,12 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile=None, qos_profile = self.qos_profile return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) + def new_rate(self, rate): + return rospy.Rate(rate) + + def new_timer(self, timer_period_sec, callback): + return rospy.Timer(rospy.Duration(timer_period_sec), callback) + def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None): return rospy.wait_for_message(topic, topic_type, timeout) @@ -258,6 +264,12 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile=None, return self.create_subscription(msg_type, topic, callback, qos_profile, callback_group=callback_group) + def new_rate(self, rate): + return self.create_rate(rate) + + def new_timer(self, timer_period_sec, callback): + return self.create_timer(timer_period_sec, callback) + def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None): s = None spin_timeout = 0.5 From 2d34b35a5510e5367075829e14591483d7c26702 Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 7 Oct 2020 16:26:50 +0200 Subject: [PATCH 326/627] fixed typo in followingvehicle scenario --- carla_ad_demo/config/FollowLeadingVehicle.xosc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_demo/config/FollowLeadingVehicle.xosc b/carla_ad_demo/config/FollowLeadingVehicle.xosc index 904557b7..885ed1ab 100644 --- a/carla_ad_demo/config/FollowLeadingVehicle.xosc +++ b/carla_ad_demo/config/FollowLeadingVehicle.xosc @@ -2,7 +2,7 @@ - + From e13d08801390af64c8936d032c4f5c531378ef2b Mon Sep 17 00:00:00 2001 From: jbmag Date: Tue, 13 Oct 2020 19:40:41 +0200 Subject: [PATCH 327/627] fixed error in basic agent ROS2, subscriber to actor list should be declared with durability True in QoSProfile --- carla_ad_agent/src/carla_ad_agent/basic_agent.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 70ec9d63..9b349684 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -19,7 +19,9 @@ from ros_compatibility import ( ros_ok, ServiceException, - ROSInterruptException) + ROSInterruptException, + QoSProfile, + latch_on) import os ROS_VERSION = int(os.environ['ROS_VERSION']) @@ -65,7 +67,7 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): self._vehicle_id_list = [] self._lights_id_list = [] self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", - self.actors_updated, callback_group=cb_group) + self.actors_updated, qos_profile=QoSProfile(depth=1, durability=latch_on), callback_group=cb_group) self._objects = [] self._objects_subscriber = self.node.create_subscriber(ObjectArray, From 8a7050367910cdf1e5e059b977190791a472a3c8 Mon Sep 17 00:00:00 2001 From: jbmag Date: Tue, 13 Oct 2020 19:42:51 +0200 Subject: [PATCH 328/627] port of carla_ros_scenario_runner_types to ROS2 --- .../CMakeLists.txt | 57 +++++++++++++++++-- carla_ros_scenario_runner_types/package.xml | 29 +++++++++- 2 files changed, 77 insertions(+), 9 deletions(-) diff --git a/carla_ros_scenario_runner_types/CMakeLists.txt b/carla_ros_scenario_runner_types/CMakeLists.txt index bfe8b33a..c4e4574e 100644 --- a/carla_ros_scenario_runner_types/CMakeLists.txt +++ b/carla_ros_scenario_runner_types/CMakeLists.txt @@ -1,13 +1,58 @@ -cmake_minimum_required(VERSION 2.8.3) project(carla_ros_scenario_runner_types) -find_package(catkin REQUIRED COMPONENTS message_generation geometry_msgs) +find_package(ros_environment REQUIRED) -add_service_files(DIRECTORY srv FILES ExecuteScenario.srv) +set(ROS_VERSION $ENV{ROS_VERSION}) -add_message_files(DIRECTORY msg FILES CarlaScenario.msg CarlaScenarioList.msg +if (${ROS_VERSION} EQUAL 1) + cmake_minimum_required(VERSION 2.8.3) + + find_package(catkin REQUIRED COMPONENTS message_generation geometry_msgs) + + add_service_files(DIRECTORY srv FILES ExecuteScenario.srv) + + add_message_files(DIRECTORY msg FILES CarlaScenario.msg CarlaScenarioList.msg CarlaScenarioRunnerStatus.msg) -generate_messages(DEPENDENCIES geometry_msgs) + generate_messages(DEPENDENCIES geometry_msgs) + + catkin_package() + + +elseif(${ROS_VERSION} EQUAL 2) + + cmake_minimum_required(VERSION 3.5) + + if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_STANDARD 14) + endif() + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + + find_package(ament_cmake REQUIRED) + find_package(builtin_interfaces REQUIRED) + find_package(geometry_msgs REQUIRED) + find_package(rosidl_default_generators REQUIRED) + + rosidl_generate_interfaces(${PROJECT_NAME} + msg/CarlaScenario.msg + msg/CarlaScenarioList.msg + msg/CarlaScenarioRunnerStatus.msg + srv/ExecuteScenario.srv + DEPENDENCIES builtin_interfaces geometry_msgs + ADD_LINTER_TESTS + ) + + ament_export_dependencies(rosidl_default_runtime) + + if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + endif() + + ament_package() -catkin_package() +endif() diff --git a/carla_ros_scenario_runner_types/package.xml b/carla_ros_scenario_runner_types/package.xml index 5df0ef5a..d87561d9 100644 --- a/carla_ros_scenario_runner_types/package.xml +++ b/carla_ros_scenario_runner_types/package.xml @@ -1,14 +1,37 @@ - + carla_ros_scenario_runner_types 0.1.0 The carla_ros_scenario_runner_types package CARLA Simulator Team MIT - catkin - message_generation + + catkin + ament_cmake + + message_generation + rosidl_default_generators + ros_environment geometry_msgs + + builtin_interfaces + message_runtime geometry_msgs + + message_runtime + rosidl_default_runtime + + ament_lint_auto + ament_lint_common + + rosidl_interface_packages + + + + catkin + ament_cmake + + From b6d024c07e833f08f5fe7b5022109ea137ef6fd5 Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 14 Oct 2020 09:04:58 +0200 Subject: [PATCH 329/627] port of carla_ros_scenario_runner to ROS2 --- carla_ros_scenario_runner/CMakeLists.txt | 42 +++++--- .../launch/carla_ros_scenario_runner.launch | 2 +- .../carla_ros_scenario_runner.launch.py | 1 + carla_ros_scenario_runner/package.xml | 22 +++-- .../resource/carla_ros_scenario_runner | 0 carla_ros_scenario_runner/setup.cfg | 4 + carla_ros_scenario_runner/setup.py | 43 ++++++-- .../application_runner.py | 6 +- ...r.py => carla_ros_scenario_runner_node.py} | 95 +++++++++++------- .../ros_vehicle_control.py | 98 ++++++++++++++----- .../scenario_runner_runner.py | 10 +- .../CMakeLists.txt | 17 ++-- 12 files changed, 240 insertions(+), 100 deletions(-) create mode 100644 carla_ros_scenario_runner/resource/carla_ros_scenario_runner create mode 100644 carla_ros_scenario_runner/setup.cfg rename carla_ros_scenario_runner/src/carla_ros_scenario_runner/{carla_ros_scenario_runner.py => carla_ros_scenario_runner_node.py} (58%) diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt index 90bfe9a0..028e8663 100644 --- a/carla_ros_scenario_runner/CMakeLists.txt +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -1,22 +1,36 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ros_scenario_runner) -find_package(catkin REQUIRED COMPONENTS roslaunch) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if(${ROS_VERSION} EQUAL 1) -roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) + find_package(catkin REQUIRED COMPONENTS roslaunch) -catkin_package() + catkin_python_setup() -catkin_install_python( - PROGRAMS - src/carla_ros_scenario_runner/carla_ros_scenario_runner.py - src/carla_ros_scenario_runner/application_runner.py - src/carla_ros_scenario_runner/scenario_runner_runner.py - src/carla_ros_scenario_runner/ros_vehicle_control.py - DESTINATION - ${CATKIN_PACKAGE_BIN_DESTINATION}) + roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + catkin_package() + + install( + PROGRAMS src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py + src/carla_ros_scenario_runner/ros_vehicle_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + +elseif(${ROS_VERSION} EQUAL 2) + + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + + ament_package() + +endif() diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch index d5d66068..8015648f 100644 --- a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch @@ -6,7 +6,7 @@ - + diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py index 43f6d6a6..99e75571 100644 --- a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py @@ -31,6 +31,7 @@ def generate_launch_description(): node_executable='carla_ros_scenario_runner', name='carla_ros_scenario_runner', output='screen', + emulate_tty='True', on_exit=launch.actions.Shutdown(), parameters=[ { diff --git a/carla_ros_scenario_runner/package.xml b/carla_ros_scenario_runner/package.xml index 271ac958..c337ed80 100644 --- a/carla_ros_scenario_runner/package.xml +++ b/carla_ros_scenario_runner/package.xml @@ -1,20 +1,30 @@ - + carla_ros_scenario_runner 0.0.0 The carla_ros_scenario_runner package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy + carla_msgs carla_ros_scenario_runner_types std_msgs carla_common + + catkin + rospy + roslaunch + rospy + rospy + + + + rclpy + ament_python + + catkin + ament_python diff --git a/carla_ros_scenario_runner/resource/carla_ros_scenario_runner b/carla_ros_scenario_runner/resource/carla_ros_scenario_runner new file mode 100644 index 00000000..e69de29b diff --git a/carla_ros_scenario_runner/setup.cfg b/carla_ros_scenario_runner/setup.cfg new file mode 100644 index 00000000..90722478 --- /dev/null +++ b/carla_ros_scenario_runner/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_ros_scenario_runner +[install] +install-scripts=$base/lib/carla_ros_scenario_runner \ No newline at end of file diff --git a/carla_ros_scenario_runner/setup.py b/carla_ros_scenario_runner/setup.py index 1204b037..744c967c 100644 --- a/carla_ros_scenario_runner/setup.py +++ b/carla_ros_scenario_runner/setup.py @@ -1,13 +1,42 @@ """ Setup for carla_ros_scenario_runner """ +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_ros_scenario_runner'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_ros_scenario_runner'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_ros_scenario_runner' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + (os.path.join('share', package_name), ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ROS2 scenario runner', + license='MIT', + entry_points={ + 'console_scripts': ['carla_ros_scenario_runner = carla_ros_scenario_runner.carla_ros_scenario_runner_node:main'], + }, + package_dir={'': 'src'}, + ) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py index 8a72617b..f4744311 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -101,8 +101,8 @@ def start_process(self, argument_list, log_fct, env=None, cwd=None): # pylint: if not argument_list: raise KeyError("No arguments given!") executable = argument_list[0] - if not os.path.isfile(executable): - raise KeyError("The executable {} does not exist".format(executable)) + # if not os.path.isfile(executable): + # raise KeyError("The executable {} does not exist".format(executable)) log_fct("Executing: {}".format(" ".join(argument_list))) process = pexpect.spawn(" ".join(argument_list), env=env, cwd=cwd) #process.logfile_read = sys.stdout @@ -132,7 +132,7 @@ def run(self, process, shutdown_requested_event, ready_string, status_updated_fc process.expect(".*\n", timeout=0.1) log_fct(process.after.strip()) if not signaled_running: - if process.after.find(ready_string) != -1: + if str(process.after).find(ready_string) != -1: status_updated_fct(ApplicationStatus.RUNNING) log_fct("Application is ready.") signaled_running = True diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py similarity index 58% rename from carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py rename to carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py index e083eb3d..7ecf7ab4 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py @@ -12,47 +12,66 @@ """ import sys import os +import logging try: import queue except ImportError: import Queue as queue -import rospy from geometry_msgs.msg import PoseStamped from nav_msgs.msg import Path from std_msgs.msg import Float64 -from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse +from carla_ros_scenario_runner_types.srv import ExecuteScenario from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus -from application_runner import ApplicationStatus # pylint: disable=relative-import -from scenario_runner_runner import ScenarioRunnerRunner # pylint: disable=relative-import +from carla_ros_scenario_runner.application_runner import ApplicationStatus # pylint: disable=relative-import +from carla_ros_scenario_runner.scenario_runner_runner import ScenarioRunnerRunner # pylint: disable=relative-import + +from ros_compatibility import CompatibleNode, QoSProfile, ros_ok # Check Python dependencies of scenario runner try: import carla # pylint: disable=unused-import except ImportError: - print "ERROR: CARLA Python Egg not available. Please add \ + print("ERROR: CARLA Python Egg not available. Please add \ /PythonAPI/carla/dist/carla--\ - py-linux-x86_64.egg to your PYTHONPATH." + py-linux-x86_64.egg to your PYTHONPATH.") sys.exit(1) try: from agents.navigation.local_planner import LocalPlanner # pylint: disable=unused-import except ImportError: - print "ERROR: CARLA Python Agents not available. \ - Please add /PythonAPI/carla to your PYTHONPATH." + print("ERROR: CARLA Python Agents not available. \ + Please add /PythonAPI/carla to your PYTHONPATH.") sys.exit(1) +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + from carla_ros_scenario_runner_types.srv import ExecuteScenarioResponse +elif ROS_VERSION == 2: + import rclpy + import threading + -class CarlaRosScenarioRunner(object): +class CarlaRosScenarioRunner(CompatibleNode): """ Execute scenarios via ros service """ - def __init__(self, role_name, host, port, scenario_runner_path, wait_for_ego): + def __init__(self): """ Constructor """ - self._status_publisher = rospy.Publisher( - "/scenario_runner/status", CarlaScenarioRunnerStatus, queue_size=1, latch=True) + super(CarlaRosScenarioRunner, self).__init__('carla_ros_scenario_runner') + + role_name = self.get_param("role_name", "ego_vehicle") + scenario_runner_path = self.get_param("scenario_runner_path", "") + wait_for_ego = self.get_param("wait_for_ego", "True") + host = self.get_param("host", "localhost") + port = self.get_param("port", 2000) + + self._status_publisher = self.new_publisher( + CarlaScenarioRunnerStatus, "/scenario_runner/status", + qos_profile=QoSProfile(depth=1, durability=1)) self.scenario_runner_status_updated(ApplicationStatus.STOPPED) self._scenario_runner = ScenarioRunnerRunner( scenario_runner_path, @@ -62,20 +81,20 @@ def __init__(self, role_name, host, port, scenario_runner_path, wait_for_ego): self.scenario_runner_status_updated, self.scenario_runner_log) self._request_queue = queue.Queue() - self._execute_scenario_service = rospy.Service( - '/scenario_runner/execute_scenario', ExecuteScenario, self.execute_scenario) + self._execute_scenario_service = self.new_service( + ExecuteScenario, '/scenario_runner/execute_scenario', self.execute_scenario) def scenario_runner_log(self, log): # pylint: disable=no-self-use """ Callback for application logs """ - rospy.logwarn("[SC]{}".format(log)) + self.logwarn("[SC]{}".format(log)) def scenario_runner_status_updated(self, status): """ Executed from application runner whenever the status changed """ - rospy.loginfo("Status updated to {}".format(status)) + self.loginfo("Status updated to {}".format(status)) val = CarlaScenarioRunnerStatus.STOPPED if status == ApplicationStatus.STOPPED: val = CarlaScenarioRunnerStatus.STOPPED @@ -91,16 +110,17 @@ def scenario_runner_status_updated(self, status): status.status = val self._status_publisher.publish(status) - def execute_scenario(self, req): + def execute_scenario(self, req, response=None): """ Execute a scenario """ - rospy.loginfo("Scenario Execution requested...") + self.loginfo("Scenario Execution requested...") - response = ExecuteScenarioResponse() + if ROS_VERSION == 1: + response = ExecuteScenarioResponse() response.result = True if not os.path.isfile(req.scenario.scenario_file): - rospy.logwarn("Requested scenario file not existing {}".format( + self.logwarn("Requested scenario file not existing {}".format( req.scenario.scenario_file)) response.result = False else: @@ -114,19 +134,19 @@ def run(self): :return: """ current_req = None - while not rospy.is_shutdown(): + while ros_ok(): if current_req: if self._scenario_runner.is_running(): - rospy.loginfo("Scenario Runner currently running. Shutting down.") + self.loginfo("Scenario Runner currently running. Shutting down.") self._scenario_runner.shutdown() - rospy.loginfo("Scenario Runner stopped.") - rospy.loginfo("Executing scenario {}...".format(current_req.name)) + self.loginfo("Scenario Runner stopped.") + self.loginfo("Executing scenario {}...".format(current_req.name)) # execute scenario scenario_executed = self._scenario_runner.execute_scenario( current_req.scenario_file) if not scenario_executed: - rospy.logwarn("Unable to execute scenario.") + self.logwarn("Unable to execute scenario.") current_req = None else: try: @@ -134,8 +154,9 @@ def run(self): except queue.Empty: # no new request pass + if self._scenario_runner.is_running(): - rospy.loginfo("Scenario Runner currently running. Shutting down.") + self.loginfo("Scenario Runner currently running. Shutting down.") self._scenario_runner.shutdown() @@ -146,19 +167,23 @@ def main(): :return: """ - rospy.init_node('carla_ros_scenario_runner', anonymous=True) - role_name = rospy.get_param("~role_name", "ego_vehicle") - scenario_runner_path = rospy.get_param("~scenario_runner_path", "") - wait_for_ego = rospy.get_param("~wait_for_ego", "True") - host = rospy.get_param("~host", "localhost") - port = rospy.get_param("~port", 2000) - scenario_runner = CarlaRosScenarioRunner( - role_name, host, port, scenario_runner_path, wait_for_ego) + if ROS_VERSION == 2: + rclpy.init() + + scenario_runner = CarlaRosScenarioRunner() + + if ROS_VERSION == 2: + spin_thread = threading.Thread(target=scenario_runner.spin, daemon=True) + spin_thread.start() + try: scenario_runner.run() finally: + if scenario_runner._scenario_runner.is_running(): + scenario_runner.loginfo("Scenario Runner still running. Shutting down.") + scenario_runner._scenario_runner.shutdown() del scenario_runner - rospy.loginfo("Done.") + logging.info("Done.") if __name__ == "__main__": diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 498dd118..104aeea5 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -9,41 +9,62 @@ ROS Vehicle Control usable by scenario-runner """ -import rospy -import roslaunch from std_msgs.msg import Float64 from geometry_msgs.msg import PoseStamped from nav_msgs.msg import Path import carla_common.transforms as trans from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error +from ros_compatibility import CompatibleNode, QoSProfile, ros_timestamp, destroy_subscription +import os + +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + import rospy + import roslaunch +elif ROS_VERSION == 2: + from carla_ros_scenario_runner.application_runner import ApplicationRunner + import rclpy + class RosVehicleControl(BasicControl): def __init__(self, actor, args=None): super(RosVehicleControl, self).__init__(actor) + if ROS_VERSION == 2: + rclpy.init() + self._carla_actor = actor self._role_name = actor.attributes["role_name"] if not self._role_name: - rospy.logerr("Invalid role_name!") + if ROS_VERSION == 1: + rospy.logerr("Invalid role_name!") + elif ROS_VERSION == 2: + logging.get_logger("pre_logger").error("Invalid role_name!") + + self.node = CompatibleNode('ros_agent_{}'.format(self._role_name)) - rospy.init_node('ros_agent_{}'.format(self._role_name)) self._current_target_speed = None self._current_path = None - self._target_speed_publisher = rospy.Publisher( - "/carla/{}/target_speed".format(self._role_name), Float64, queue_size=1, latch=True) + self._target_speed_publisher = self.node.new_publisher( + Float64, "/carla/{}/target_speed".format(self._role_name), + QoSProfile(depth=1, durability=True)) - self._path_publisher = rospy.Publisher( - "/carla/{}/waypoints".format(self._role_name), Path, queue_size=1, latch=True) + self._path_publisher = self.node.new_publisher( + Path, "/carla/{}/waypoints".format(self._role_name), + QoSProfile(depth=1, durability=True)) if "launch" in args and "launch-package" in args: - uuid = roslaunch.rlutil.get_or_generate_uuid(None, False) - roslaunch.configure_logging(uuid) + launch_file = args["launch"] launch_package = args["launch-package"] - cli_args = [launch_package, launch_file] + if ROS_VERSION == 1: + cli_args = [launch_package, launch_file] + elif ROS_VERSION == 2: + cli_args = [launch_package, launch_file + '.py'] cli_args.append('role_name:={}'.format(self._role_name)) # add additional launch parameters @@ -53,28 +74,52 @@ def __init__(self, actor, args=None): launch_parameters.append('{}:={}'.format(key, value)) cli_args.append('{}:={}'.format(key, value)) - rospy.loginfo("{}: Launching {} from package {} (parameters: {})...".format( + self.node.loginfo("{}: Launching {} from package {} (parameters: {})...".format( self._role_name, launch_file, launch_package, launch_parameters)) - roslaunch_file = roslaunch.rlutil.resolve_launch_arguments(cli_args) - roslaunch_args = cli_args[2:] - launch_files = [(roslaunch_file[0], roslaunch_args)] - parent = roslaunch.parent.ROSLaunchParent(uuid, launch_files) - parent.start() - rospy.loginfo("{}: Successfully started ros vehicle control".format(self._role_name)) + + if ROS_VERSION == 1: + uuid = roslaunch.rlutil.get_or_generate_uuid(None, False) + roslaunch.configure_logging(uuid) + roslaunch_file = roslaunch.rlutil.resolve_launch_arguments(cli_args) + roslaunch_args = cli_args[2:] + launch_files = [(roslaunch_file[0], roslaunch_args)] + parent = roslaunch.parent.ROSLaunchParent(uuid, launch_files) + parent.start() + + elif ROS_VERSION == 2: + cmdline = ['ros2 launch'] + cli_args + self.controller_launch = ApplicationRunner( + self.controller_runner_status_updated, self.controller_runner_log, 'RosVehicleControl: launching controller node') + self.controller_launch.execute(cmdline, env=os.environ,) + + self.node.loginfo( + "{}: Successfully started ros vehicle control".format(self._role_name)) else: - rospy.logerr( + self.node.logerr( "{}: Missing value for 'launch' and/or 'launch-package'.".format(self._role_name)) + def controller_runner_log(self, log): # pylint: disable=no-self-use + """ + Callback for application logs + """ + self.node.logwarn("[Controller]{}".format(log)) + + def controller_runner_status_updated(self, status): + """ + Executed from application runner whenever the status changed + """ + self.node.loginfo("Controller status is: {}".format(status)) + def update_target_speed(self, speed): super(RosVehicleControl, self).update_target_speed(speed) - rospy.loginfo("{}: Target speed changed to {}".format(self._role_name, speed)) + self.node.loginfo("{}: Target speed changed to {}".format(self._role_name, speed)) self._target_speed_publisher.publish(Float64(data=speed)) def update_waypoints(self, waypoints, start_time=None): super(RosVehicleControl, self).update_waypoints(waypoints, start_time) - rospy.loginfo("{}: Waypoints changed.".format(self._role_name)) + self.node.loginfo("{}: Waypoints changed.".format(self._role_name)) path = Path() - path.header.stamp = rospy.get_rostime() + path.header.stamp = ros_timestamp(sec=self.node.get_time, from_sec=True) path.header.frame_id = "map" for wpt in waypoints: print(wpt) @@ -82,13 +127,18 @@ def update_waypoints(self, waypoints, start_time=None): self._path_publisher.publish(path) def reset(self): + # set target speed to zero before closing as the controller can take time to shutdown + if ROS_VERSION == 2: + self.update_target_speed(0.) + if self.controller_launch.is_running(): + self.controller_launch.shutdown() if self._carla_actor and self._carla_actor.is_alive: self._carla_actor = None if self._target_speed_publisher: - self._target_speed_publisher.unregister() + destroy_subscription(self._target_speed_publisher) self._target_speed_publisher = None if self._path_publisher: - self._path_publisher.unregister() + destroy_subscription(self._path_publisher) self._path_publisher = None def run_step(self): diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py index dae0a416..3dc540ba 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py @@ -6,7 +6,9 @@ Executes scenario runner """ import os -from application_runner import ApplicationRunner # pylint: disable=relative-import +from carla_ros_scenario_runner.application_runner import ApplicationRunner # pylint: disable=relative-import + +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) class ScenarioRunnerRunner(ApplicationRunner): @@ -28,7 +30,11 @@ def execute_scenario(self, scenario_file): """ Executes scenario """ - cmdline = ["/usr/bin/python", "{}/scenario_runner.py".format(self._path), + if ROS_VERSION == 1: + python_path = "/usr/bin/python" + elif ROS_VERSION == 2: + python_path = "/usr/bin/python3" + cmdline = [python_path, "{}/scenario_runner.py".format(self._path), "--openscenario", "{}".format(scenario_file), "--timeout", "1000000", "--host", self._host, diff --git a/carla_ros_scenario_runner_types/CMakeLists.txt b/carla_ros_scenario_runner_types/CMakeLists.txt index c4e4574e..7b976487 100644 --- a/carla_ros_scenario_runner_types/CMakeLists.txt +++ b/carla_ros_scenario_runner_types/CMakeLists.txt @@ -4,7 +4,7 @@ find_package(ros_environment REQUIRED) set(ROS_VERSION $ENV{ROS_VERSION}) -if (${ROS_VERSION} EQUAL 1) +if(${ROS_VERSION} EQUAL 1) cmake_minimum_required(VERSION 2.8.3) find_package(catkin REQUIRED COMPONENTS message_generation geometry_msgs) @@ -12,13 +12,12 @@ if (${ROS_VERSION} EQUAL 1) add_service_files(DIRECTORY srv FILES ExecuteScenario.srv) add_message_files(DIRECTORY msg FILES CarlaScenario.msg CarlaScenarioList.msg - CarlaScenarioRunnerStatus.msg) + CarlaScenarioRunnerStatus.msg) generate_messages(DEPENDENCIES geometry_msgs) catkin_package() - elseif(${ROS_VERSION} EQUAL 2) cmake_minimum_required(VERSION 3.5) @@ -37,14 +36,16 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(geometry_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) - rosidl_generate_interfaces(${PROJECT_NAME} - msg/CarlaScenario.msg + rosidl_generate_interfaces( + ${PROJECT_NAME} + msg/CarlaScenario.msg msg/CarlaScenarioList.msg msg/CarlaScenarioRunnerStatus.msg srv/ExecuteScenario.srv - DEPENDENCIES builtin_interfaces geometry_msgs - ADD_LINTER_TESTS - ) + DEPENDENCIES + builtin_interfaces + geometry_msgs + ADD_LINTER_TESTS) ament_export_dependencies(rosidl_default_runtime) From 6788c6526f2d47ce4176e7977906d23fa4aad3a9 Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 14 Oct 2020 09:53:10 +0200 Subject: [PATCH 330/627] removed commented line --- .../src/carla_ros_scenario_runner/application_runner.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py index f4744311..7de9f973 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -101,8 +101,6 @@ def start_process(self, argument_list, log_fct, env=None, cwd=None): # pylint: if not argument_list: raise KeyError("No arguments given!") executable = argument_list[0] - # if not os.path.isfile(executable): - # raise KeyError("The executable {} does not exist".format(executable)) log_fct("Executing: {}".format(" ".join(argument_list))) process = pexpect.spawn(" ".join(argument_list), env=env, cwd=cwd) #process.logfile_read = sys.stdout From c9e71274a696c952309ec956a9d772ef760b620f Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 14 Oct 2020 12:14:47 +0200 Subject: [PATCH 331/627] another subscriber was not considering latching in ad_agent --- carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index e64f9ec2..bd7be1c3 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -60,10 +60,12 @@ def __init__(self): sys.exit(1) self._route_subscriber = self.create_subscriber( - Path, "/carla/{}/waypoints".format(role_name), self.path_updated) + Path, "/carla/{}/waypoints".format(role_name), self.path_updated, + QoSProfile(depth=1, durability=True)) self._target_speed_subscriber = self.create_subscriber( - Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated) + Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, + QoSProfile(depth=1, durability=True)) self.vehicle_control_publisher = self.new_publisher( CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), From 8844d8de2b7e60bc7c200865af467edb85dd0000 Mon Sep 17 00:00:00 2001 From: jbmag Date: Wed, 14 Oct 2020 14:43:22 +0200 Subject: [PATCH 332/627] added ros2 part in scenario_runner readme --- carla_ros_scenario_runner/README.md | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/carla_ros_scenario_runner/README.md b/carla_ros_scenario_runner/README.md index 716f486f..137dcda1 100644 --- a/carla_ros_scenario_runner/README.md +++ b/carla_ros_scenario_runner/README.md @@ -32,6 +32,7 @@ The environment variables are forwarded to scenario_runner, therefore set them t export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ +### Using ROS1 To run the ROS node: roslaunch carla_ros_scenario_runner carla_ros_scenario_runner.launch scenario_runner_path:= @@ -40,6 +41,16 @@ To run a scenario from commandline: rosservice call /scenario_runner/execute_scenario "{ 'scenario': { 'scenario_file': '' } }" +### Using ROS2 +To run the ROS node: + + ros2 launch carla_ros_scenario_runner carla_ros_scenario_runner.launch.py scenario_runner_path:= + +To run a scenario from commandline: + + ros2 service call /scenario_runner/execute_scenario carla_ros_scenario_runner_types/srv/ExecuteScenario "{ 'scenario': { 'scenario_file': '' } }" + + ## Available services From a944eac4a9af11e3724a2de8c07ebe9f60755f09 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 14 Oct 2020 22:41:53 +0200 Subject: [PATCH 333/627] listen call added --- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 1 + 1 file changed, 1 insertion(+) diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index 4cce87bb..08fcf652 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -38,6 +38,7 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="GNS prefix="gnss/" + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) self.gnss_publisher = node.new_publisher(NavSatFix, self.get_topic_prefix() + "/fix") + self.listen() # pylint: disable=arguments-differ def sensor_data_updated(self, carla_gnss_measurement): From 66391325f502583e08d4b283ec00032439b7a870 Mon Sep 17 00:00:00 2001 From: "Kai A. Hiller" Date: Thu, 15 Oct 2020 10:39:22 +0200 Subject: [PATCH 334/627] [ROS2] Fix error handling in carla_ego_vehicle (#381) * Fix spelling * Enable compat spin method to use custom executor * Improve error handling * Improve error propagation for loading the sensor-defintion file * removed python3 specific syntax for ros melodic compatibility * remove some comments --- .../carla_ego_vehicle/carla_ego_vehicle.py | 104 +++++++----------- .../ros_compatibility/ros_compatible_node.py | 10 +- 2 files changed, 45 insertions(+), 69 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 82f87d06..03d2ebf7 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -16,25 +16,28 @@ /initialpose might be published via RVIZ '2D Pose Estimate" button. """ -import sys import json import math import os import random +import traceback from abc import abstractmethod from geometry_msgs.msg import PoseWithCovarianceStamped, Pose # pylint: disable=import-error -from carla_msgs.msg import CarlaStatus, CarlaWorldInfo # pylint: disable=import-error -from ros_compatibility import CompatibleNode, euler_from_quaternion, quaternion_from_euler +from carla_msgs.msg import CarlaWorldInfo # pylint: disable=import-error +from ros_compatibility import ( + CompatibleNode, + destroy_subscription, + euler_from_quaternion, + quaternion_from_euler, + QoSProfile +) import carla ROS_VERSION = int(os.environ['ROS_VERSION']) -if ROS_VERSION == 1: - import rospy # pylint: disable=import-error - -elif ROS_VERSION == 2: +if ROS_VERSION == 2: import rclpy # pylint: disable=import-error from ament_index_python.packages import get_package_share_directory # pylint: disable=import-error @@ -100,6 +103,14 @@ def __init__(self): self.loginfo("listening to server {}:{}".format(self.host, self.port)) self.loginfo("using vehicle filter: {}".format(self.actor_filter)) + self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") + self.startup_subscription = self.create_subscriber( + CarlaWorldInfo, + '/carla/world_info', + self.run, + QoSProfile(depth=1, durability=False) + ) + # pylint: disable=inconsistent-return-statements def spawn_ego_vehicle(self): """ @@ -185,15 +196,15 @@ def restart(self): if self.player_created: # Read sensors from file - if not os.path.exists(self.sensor_definition_file): + try: + with open(self.sensor_definition_file) as f: + json_sensors = json.load(f)["sensors"] + except (OSError, json.JSONDecodeError, KeyError) as e: raise RuntimeError( - "Could not read sensor-definition from {}".format(self.sensor_definition_file)) - json_sensors = None - with open(self.sensor_definition_file) as handle: - json_sensors = json.loads(handle.read()) + "Could not read sensor-definition from '{}' error is: {}".format(self.sensor_definition_file, e)) # Set up the sensors - self.sensor_actors = self.setup_sensors(json_sensors["sensors"]) + self.sensor_actors = self.setup_sensors(json_sensors) self.player_created = False @@ -386,73 +397,38 @@ def destroy(self): self.player = None super(CarlaEgoVehicle, self).destroy() - def run(self): + def run(self, _msg): """ - main loop + Called after the Carla world was loaded; spawns the ego vehicle. """ - if ROS_VERSION == 1: - # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") - try: - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException: - rospy.logerr("Timeout while waiting for world info!") - sys.exit(1) - self.loginfo("CARLA world available. Spawn ego vehicle...") + # The subscription should only call this function once + destroy_subscription(self.startup_subscription) - client = carla.Client(self.host, self.port) - client.set_timeout(self.timeout) - self.world = client.get_world() - self.restart() - self.loginfo("Ego spawned.") try: - self.spin() + client = carla.Client(self.host, self.port) + client.set_timeout(self.timeout) + self.world = client.get_world() + self.restart() except Exception: # pylint: disable=broad-except + self.logerr("Could not run node: {}".format(traceback.format_exc())) self.shutdown() + return - -def run_ego_vehicle(msg): # pylint: disable=unused-argument - """ - Callback function: - Called when bridge started - indicated by published /carla/status topic - and runs CarlaEgoVehicle afterwards - """ - ego_vehicle = CarlaEgoVehicle() - try: - ego_vehicle.run() - finally: - if ego_vehicle is not None: - ego_vehicle.destroy() + self.loginfo("Ego spawned.") def main(): """ main function """ - - if ROS_VERSION == 1: - run_ego_vehicle(None) - - elif ROS_VERSION == 2: - # Setup init_ego node. - rclpy.init(args=None) + executor = None + if ROS_VERSION == 2: + rclpy.init() executor = rclpy.executors.MultiThreadedExecutor() - init_node = rclpy.create_node("init_ego") - init_node.create_subscription(CarlaWorldInfo, - '/carla/world_info', - run_ego_vehicle, - 1) - executor.add_node(init_node) - init_node.get_logger().info("Waiting for carla_bridge to start...") - - try: - executor.spin() - except KeyboardInterrupt: - pass - init_node.destroy_node() - rclpy.shutdown() + ego_vehicle = CarlaEgoVehicle() + ego_vehicle.spin(executor) if __name__ == '__main__': diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 73de50b7..8e88dd01 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -20,8 +20,8 @@ def ros_ok(): def ros_shutdown(): pass - def destroy_subscription(subsription): - subsription.unregister() + def destroy_subscription(subscription): + subscription.unregister() def euler_matrix(roll, pitch, yaw): return trans.euler_matrix(roll, pitch, yaw) @@ -167,8 +167,8 @@ def ros_ok(): def ros_shutdown(): rclpy.shutdown() - def destroy_subscription(subsription): - subsription.destroy() + def destroy_subscription(subscription): + subscription.destroy() def euler_matrix(roll, pitch, yaw): return euler2mat(roll, pitch, yaw) @@ -309,7 +309,7 @@ def call_service(self, client, req): return result def spin(self, executor=None): - rclpy.spin(self) + rclpy.spin(self, executor) def get_time(self): t = self.get_clock().now() From e0dddf85975ab77148df6d41278098c8ab4c4d78 Mon Sep 17 00:00:00 2001 From: jbmag <47941074+jbmag@users.noreply.github.com> Date: Thu, 15 Oct 2020 14:05:55 +0200 Subject: [PATCH 335/627] remove inheritance on CompatibleNode for sensor in carla_ros_bridge (#391) * remove inheritance on CompatibleNode for sensor in carla_ros_bridge --- .../src/carla_ros_bridge/camera.py | 6 ++++-- .../src/carla_ros_bridge/sensor.py | 21 +++++++++---------- 2 files changed, 14 insertions(+), 13 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 9abbdbf0..69341a27 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -56,8 +56,10 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None, synchronous_mode=synchronous_mode, prefix=prefix, sensor_name=sensor_name) + self.node = node + if self.__class__.__name__ == "Camera": - self.logwarn("Created Unsupported Camera Actor" + self.node.logwarn("Created Unsupported Camera Actor" "(id={}, parent_id={}, type={}, attributes={})".format( self.get_id(), self.get_parent_id(), self.carla_actor.type_id, self.carla_actor.attributes)) @@ -111,7 +113,7 @@ def sensor_data_updated(self, carla_image): """ if ((carla_image.height != self._camera_info.height) or (carla_image.width != self._camera_info.width)): - self.logerr("Camera{} received image not matching configuration".format( + self.node.logerr("Camera{} received image not matching configuration".format( self.get_prefix())) image_data_array, encoding = self.get_carla_image_data_array( carla_image=carla_image) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 50b2ec71..f7a46056 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -15,7 +15,7 @@ import carla_common.transforms as trans from carla_ros_bridge.actor import Actor -from ros_compatibility import CompatibleNode, ros_ok +from ros_compatibility import ros_ok try: import queue @@ -29,7 +29,7 @@ raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") -class Sensor(Actor, CompatibleNode): +class Sensor(Actor): """ Actor implementation details for sensors """ @@ -70,8 +70,7 @@ def __init__( if sensor_name is None: sensor_name = "Sensor" - CompatibleNode.__init__(self, sensor_name, rospy_init=False) - + self.node = node self.synchronous_mode = synchronous_mode self.queue = queue.Queue() self.next_data_expected_time = None @@ -79,7 +78,7 @@ def __init__( self.is_event_sensor = is_event_sensor try: self.sensor_tick_time = float(carla_actor.attributes["sensor_tick"]) - self.logdebug("Sensor tick time is {}".format(self.sensor_tick_time)) + self.node.logdebug("Sensor tick time is {}".format(self.sensor_tick_time)) except (KeyError, ValueError): self.sensor_tick_time = None @@ -95,7 +94,7 @@ def destroy(self): :return: """ - self.logdebug("Destroy Sensor(id={})".format(self.get_id())) + self.node.logdebug("Destroy Sensor(id={})".format(self.get_id())) if self.carla_actor.is_listening: self.carla_actor.stop() super(Sensor, self).destroy() @@ -136,11 +135,11 @@ def _update_synchronous_event_sensor(self, frame): try: carla_sensor_data = self.queue.get(block=False) if carla_sensor_data.frame != frame: - self.logwarn("{}({}): Received event for frame {}" + self.node.logwarn("{}({}): Received event for frame {}" " (expected {}). Process it anyways.".format( self.__class__.__name__, self.get_id(), carla_sensor_data.frame, frame)) - self.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), + self.node.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), frame)) self.publish_transform( self.get_ros_transform( @@ -158,7 +157,7 @@ def _update_synchronous_sensor(self, frame, timestamp): try: carla_sensor_data = self.queue.get(timeout=1.0) if carla_sensor_data.frame == frame: - self.logdebug("{}({}): process {}".format(self.__class__.__name__, + self.node.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), frame)) self.publish_transform( self.get_ros_transform( @@ -167,7 +166,7 @@ def _update_synchronous_sensor(self, frame, timestamp): self.sensor_data_updated(carla_sensor_data) return elif carla_sensor_data.frame < frame: - self.logwarn("{}({}): skipping old frame {}, expected {}".format( + self.node.logwarn("{}({}): skipping old frame {}, expected {}".format( self.__class__.__name__, self.get_id(), carla_sensor_data.frame, @@ -175,7 +174,7 @@ def _update_synchronous_sensor(self, frame, timestamp): except queue.Empty: # if not rospy.is_shutdown(): if ros_ok(): - self.logwarn("{}({}): Expected Frame {} not received".format( + self.node.logwarn("{}({}): Expected Frame {} not received".format( self.__class__.__name__, self.get_id(), frame)) return From e51590e2869e50c20b0882644893304f3693c94b Mon Sep 17 00:00:00 2001 From: jbmag <47941074+jbmag@users.noreply.github.com> Date: Thu, 15 Oct 2020 15:37:54 +0200 Subject: [PATCH 336/627] Carla infrastructure ros2 (#392) * port carla_infrastructure to ros2 * format --- carla_infrastructure/CMakeLists.txt | 38 +++++++++++---- .../launch/carla_infrastructure.launch | 7 ++- .../launch/carla_infrastructure.launch.py | 7 +-- carla_infrastructure/package.xml | 21 +++++--- .../resource/carla_infrastructure | 0 carla_infrastructure/setup.cfg | 4 ++ carla_infrastructure/setup.py | 48 ++++++++++++++++--- .../carla_infrastructure.py | 41 ++++++++++------ 8 files changed, 121 insertions(+), 45 deletions(-) create mode 100644 carla_infrastructure/resource/carla_infrastructure create mode 100644 carla_infrastructure/setup.cfg diff --git a/carla_infrastructure/CMakeLists.txt b/carla_infrastructure/CMakeLists.txt index 925b4159..d7875349 100644 --- a/carla_infrastructure/CMakeLists.txt +++ b/carla_infrastructure/CMakeLists.txt @@ -1,19 +1,37 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_infrastructure) -find_package(catkin REQUIRED COMPONENTS rospy roslaunch) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if(${ROS_VERSION} EQUAL 1) -roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) + find_package(catkin REQUIRED COMPONENTS rospy roslaunch) -catkin_package(CATKIN_DEPENDS rospy) + catkin_python_setup() -catkin_install_python(PROGRAMS src/carla_infrastructure/carla_infrastructure.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + catkin_package(CATKIN_DEPENDS rospy) -install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) + catkin_install_python( + PROGRAMS src/carla_infrastructure/carla_infrastructure.py DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + + install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) + +elseif(${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + + ament_package() + +endif() diff --git a/carla_infrastructure/launch/carla_infrastructure.launch b/carla_infrastructure/launch/carla_infrastructure.launch index 6fa4dddd..8b963168 100644 --- a/carla_infrastructure/launch/carla_infrastructure.launch +++ b/carla_infrastructure/launch/carla_infrastructure.launch @@ -5,12 +5,11 @@ - - - - + + + diff --git a/carla_infrastructure/launch/carla_infrastructure.launch.py b/carla_infrastructure/launch/carla_infrastructure.launch.py index 045796bf..3ceadfef 100644 --- a/carla_infrastructure/launch/carla_infrastructure.launch.py +++ b/carla_infrastructure/launch/carla_infrastructure.launch.py @@ -27,15 +27,16 @@ def generate_launch_description(): node_executable='carla_infrastructure', name='carla_infrastructure', output='screen', + emulate_tty='True', parameters=[ { - '/carla/host': launch.substitutions.LaunchConfiguration('host') + 'carla/host': launch.substitutions.LaunchConfiguration('host') }, { - '/carla/port': launch.substitutions.LaunchConfiguration('port') + 'carla/port': launch.substitutions.LaunchConfiguration('port') }, { - '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + 'carla/timeout': launch.substitutions.LaunchConfiguration('timeout') }, { 'infrastructure_sensor_definition_file': launch.substitutions.LaunchConfiguration('infrastructure_sensor_definition_file') diff --git a/carla_infrastructure/package.xml b/carla_infrastructure/package.xml index 988f63e7..7e4ba143 100644 --- a/carla_infrastructure/package.xml +++ b/carla_infrastructure/package.xml @@ -1,15 +1,24 @@ - + carla_infrastructure 0.0.0 The carla_infrastructure package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy + + + rclpy + ament_python + + + catkin + rospy + roslaunch + rospy + rospy + + catkin + ament_python diff --git a/carla_infrastructure/resource/carla_infrastructure b/carla_infrastructure/resource/carla_infrastructure new file mode 100644 index 00000000..e69de29b diff --git a/carla_infrastructure/setup.cfg b/carla_infrastructure/setup.cfg new file mode 100644 index 00000000..ac855152 --- /dev/null +++ b/carla_infrastructure/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_infrastructure +[install] +install-scripts=$base/lib/carla_infrastructure \ No newline at end of file diff --git a/carla_infrastructure/setup.py b/carla_infrastructure/setup.py index 611caca2..6ff621f8 100644 --- a/carla_infrastructure/setup.py +++ b/carla_infrastructure/setup.py @@ -1,13 +1,47 @@ """ Setup for carla_infrastructure """ +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_infrastructure'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_infrastructure'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_infrastructure' + setup( + name=package_name, + version='0.0.0', + packages=['src/' + package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', + ['config/sensors.json']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA infrastructure for ROS2 bridge', + license='MIT', + tests_require=['pytest'], + entry_points={ + 'console_scripts': [ + 'carla_infrastructure = src.carla_infrastructure.carla_infrastructure:main' + ], + }, + ) diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 525a163d..6d058f24 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -13,28 +13,33 @@ import os import json -import rospy from carla_msgs.msg import CarlaWorldInfo import carla +from ros_compatibility import CompatibleNode, QoSProfile, ROSException, ROSInterruptException +ROS_VERSION = int(os.environ['ROS_VERSION']) + +if ROS_VERSION == 2: + import rclpy + # ============================================================================== # -- CarlaInfrastructure ------------------------------------------------------------ # ============================================================================== -class CarlaInfrastructure(object): +class CarlaInfrastructure(CompatibleNode): """ Handles the spawning of the infrastructure sensors """ def __init__(self): - rospy.init_node('infrastructure', anonymous=True) - self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', 2000) - self.timeout = rospy.get_param('/carla/timeout', 10) - self.sensor_definition_file = rospy.get_param('~infrastructure_sensor_definition_file') + super(CarlaInfrastructure, self).__init__('infrastructure') + self.host = self.get_param('carla/host', '127.0.0.1') + self.port = self.get_param('carla/port', 2000) + self.timeout = self.get_param('carla/timeout', 10) + self.sensor_definition_file = self.get_param('infrastructure_sensor_definition_file') self.world = None self.sensor_actors = [] @@ -45,6 +50,9 @@ def restart(self): :return: """ # Read sensors from file + if self.sensor_definition_file is None: + raise RuntimeError( + "The parameter sensor_definition_file doesn't exist") if not os.path.exists(self.sensor_definition_file): raise RuntimeError( "Could not read sensor-definition from {}".format(self.sensor_definition_file)) @@ -170,7 +178,7 @@ def setup_sensors(self, sensors): bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) bp.set_attribute('range', str(sensor_spec['range'])) except KeyError as e: - rospy.logfatal( + self.logfatal( "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) continue @@ -195,20 +203,21 @@ def run(self): main loop """ # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") + self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException as e: - rospy.logerr("Timeout while waiting for world info!") + self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, timeout=10.0, + qos_profile=QoSProfile(depth=1, durability=True)) + except ROSException as e: + self.logerr("Timeout while waiting for world info!") raise e - rospy.loginfo("CARLA world available. Spawn infrastructure...") + self.loginfo("CARLA world available. Spawn infrastructure...") client = carla.Client(self.host, self.port) client.set_timeout(self.timeout) self.world = client.get_world() self.restart() try: - rospy.spin() - except rospy.ROSInterruptException: + self.spin() + except ROSInterruptException: pass # ============================================================================== @@ -220,6 +229,8 @@ def main(): """ main function """ + if ROS_VERSION == 2: + rclpy.init(args=None) infrastructure = CarlaInfrastructure() try: infrastructure.run() From 0b4030701681fb316f2732311a6ca0d57f929c65 Mon Sep 17 00:00:00 2001 From: jbmag <47941074+jbmag@users.noreply.github.com> Date: Fri, 16 Oct 2020 10:09:16 +0200 Subject: [PATCH 337/627] Walker agent ros2 (#393) * fix format * added parameter in waypoint pusblisher launchfile to fix log printing * port carla_walker_agent to ROS2 --- .../carla_ego_vehicle/carla_ego_vehicle.py | 2 +- .../src/carla_ros_bridge/camera.py | 6 +- .../src/carla_ros_bridge/sensor.py | 10 +-- carla_walker_agent/CMakeLists.txt | 37 +++++--- .../launch/carla_walker_agent.launch.py | 3 +- carla_walker_agent/package.xml | 24 +++-- .../resource/carla_walker_agent | 0 carla_walker_agent/setup.cfg | 4 + carla_walker_agent/setup.py | 44 +++++++-- .../carla_walker_agent/carla_walker_agent.py | 89 ++++++++++++------- .../launch/carla_waypoint_publisher.launch.py | 1 + 11 files changed, 155 insertions(+), 65 deletions(-) create mode 100644 carla_walker_agent/resource/carla_walker_agent create mode 100644 carla_walker_agent/setup.cfg diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 03d2ebf7..53cb388a 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -201,7 +201,7 @@ def restart(self): json_sensors = json.load(f)["sensors"] except (OSError, json.JSONDecodeError, KeyError) as e: raise RuntimeError( - "Could not read sensor-definition from '{}' error is: {}".format(self.sensor_definition_file, e)) + "Could not read sensor-definition from '{}' error is: {}".format(self.sensor_definition_file, e)) # Set up the sensors self.sensor_actors = self.setup_sensors(json_sensors) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 69341a27..bf08a4de 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -60,9 +60,9 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None, if self.__class__.__name__ == "Camera": self.node.logwarn("Created Unsupported Camera Actor" - "(id={}, parent_id={}, type={}, attributes={})".format( - self.get_id(), self.get_parent_id(), self.carla_actor.type_id, - self.carla_actor.attributes)) + "(id={}, parent_id={}, type={}, attributes={})".format( + self.get_id(), self.get_parent_id(), self.carla_actor.type_id, + self.carla_actor.attributes)) else: self._build_camera_info() diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index f7a46056..93cd5093 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -136,11 +136,11 @@ def _update_synchronous_event_sensor(self, frame): carla_sensor_data = self.queue.get(block=False) if carla_sensor_data.frame != frame: self.node.logwarn("{}({}): Received event for frame {}" - " (expected {}). Process it anyways.".format( - self.__class__.__name__, self.get_id(), - carla_sensor_data.frame, frame)) + " (expected {}). Process it anyways.".format( + self.__class__.__name__, self.get_id(), + carla_sensor_data.frame, frame)) self.node.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), - frame)) + frame)) self.publish_transform( self.get_ros_transform( trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) @@ -158,7 +158,7 @@ def _update_synchronous_sensor(self, frame, timestamp): carla_sensor_data = self.queue.get(timeout=1.0) if carla_sensor_data.frame == frame: self.node.logdebug("{}({}): process {}".format(self.__class__.__name__, - self.get_id(), frame)) + self.get_id(), frame)) self.publish_transform( self.get_ros_transform( trans.carla_transform_to_ros_transform( diff --git a/carla_walker_agent/CMakeLists.txt b/carla_walker_agent/CMakeLists.txt index f59f0cc6..7ca684f0 100644 --- a/carla_walker_agent/CMakeLists.txt +++ b/carla_walker_agent/CMakeLists.txt @@ -1,18 +1,35 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_walker_agent) -find_package(catkin REQUIRED COMPONENTS rospy roslaunch) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if(${ROS_VERSION} EQUAL 1) -roslaunch_add_file_check(launch) + find_package(catkin REQUIRED COMPONENTS rospy roslaunch) -catkin_package(CATKIN_DEPENDS rospy) + catkin_python_setup() -catkin_install_python( - PROGRAMS src/carla_walker_agent/carla_walker_agent.py - src/carla_walker_agent/__init__.py DESTINATION - ${CATKIN_PACKAGE_BIN_DESTINATION}) + roslaunch_add_file_check(launch) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + catkin_package(CATKIN_DEPENDS rospy) + + catkin_install_python( + PROGRAMS src/carla_walker_agent/carla_walker_agent.py + src/carla_walker_agent/__init__.py DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + +elseif(${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + + ament_package() + +endif() diff --git a/carla_walker_agent/launch/carla_walker_agent.launch.py b/carla_walker_agent/launch/carla_walker_agent.launch.py index 1488864b..f45a26f6 100644 --- a/carla_walker_agent/launch/carla_walker_agent.launch.py +++ b/carla_walker_agent/launch/carla_walker_agent.launch.py @@ -13,7 +13,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='target_speed', - default_value='2' + default_value='2.0' ), launch.actions.DeclareLaunchArgument( name='mode', @@ -24,6 +24,7 @@ def generate_launch_description(): node_executable='carla_walker_agent', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', + emulate_tty='True', parameters=[ { 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') diff --git a/carla_walker_agent/package.xml b/carla_walker_agent/package.xml index 9e8d6653..e8e538d4 100644 --- a/carla_walker_agent/package.xml +++ b/carla_walker_agent/package.xml @@ -1,18 +1,28 @@ - + carla_walker_agent 0.0.1 The carla_walker_agent package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy - topic_tools + nav_msgs carla_msgs + + + catkin + rospy + roslaunch + rospy + rospy + topic_tools + + + rclpy + ament_python + + catkin + ament_python diff --git a/carla_walker_agent/resource/carla_walker_agent b/carla_walker_agent/resource/carla_walker_agent new file mode 100644 index 00000000..e69de29b diff --git a/carla_walker_agent/setup.cfg b/carla_walker_agent/setup.cfg new file mode 100644 index 00000000..0031b079 --- /dev/null +++ b/carla_walker_agent/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_walker_agent +[install] +install-scripts=$base/lib/carla_walker_agent \ No newline at end of file diff --git a/carla_walker_agent/setup.py b/carla_walker_agent/setup.py index 15d7c93e..87d06cd0 100644 --- a/carla_walker_agent/setup.py +++ b/carla_walker_agent/setup.py @@ -1,12 +1,42 @@ """ Setup for carla_walker_agent """ -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) -d = generate_distutils_setup( - packages=['carla_walker_agent'], - package_dir={'': 'src'} -) +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -setup(**d) + d = generate_distutils_setup( + packages=['carla_walker_agent'], + package_dir={'': 'src'} + ) + + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_walker_agent' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + (os.path.join('share', package_name), ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ROS2 walker agent', + license='MIT', + entry_points={ + 'console_scripts': ['carla_walker_agent = carla_walker_agent.carla_walker_agent:main'], + }, + package_dir={'': 'src'}, + ) diff --git a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py index 705ba8f5..014db1cf 100755 --- a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py +++ b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py @@ -9,69 +9,84 @@ Agent for Walker """ import math -import rospy from nav_msgs.msg import Path, Odometry from std_msgs.msg import Float64 from geometry_msgs.msg import Pose, Vector3 from carla_msgs.msg import CarlaWalkerControl +from ros_compatibility import CompatibleNode, QoSProfile, ros_ok, ROSInterruptException +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) -class CarlaWalkerAgent(object): +if ROS_VERSION == 1: + import rospy +elif ROS_VERSION == 2: + import time + import rclpy + import threading + + +class CarlaWalkerAgent(CompatibleNode): """ walker agent """ # minimum distance to target waypoint before switching to next MIN_DISTANCE = 0.5 - def __init__(self, role_name, target_speed): + def __init__(self): """ Constructor """ + super(CarlaWalkerAgent, self).__init__('carla_walker_agent') + + role_name = self.get_param("role_name", "ego_vehicle") + self._target_speed = self.get_param("target_speed", 2.0) + self._route_assigned = False - self._target_speed = target_speed self._waypoints = [] self._current_pose = Pose() - rospy.on_shutdown(self.on_shutdown) + self.on_shutdown(self._on_shutdown) # wait for ros bridge to create relevant topics try: - rospy.wait_for_message( + self.wait_for_one_message( "/carla/{}/odometry".format(role_name), Odometry) - except rospy.ROSInterruptException as e: - if not rospy.is_shutdown(): + except ROSInterruptException as e: + if not ros_ok: raise e - self._odometry_subscriber = rospy.Subscriber( - "/carla/{}/odometry".format(role_name), Odometry, self.odometry_updated) + self._odometry_subscriber = self.create_subscriber( + Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) - self.control_publisher = rospy.Publisher( - "/carla/{}/walker_control_cmd".format(role_name), CarlaWalkerControl, queue_size=1) + self.control_publisher = self.new_publisher( + CarlaWalkerControl, "/carla/{}/walker_control_cmd".format(role_name), + QoSProfile(depth=1, durability=False)) - self._route_subscriber = rospy.Subscriber( - "/carla/{}/waypoints".format(role_name), Path, self.path_updated) + self._route_subscriber = self.create_subscriber( + Path, "/carla/{}/waypoints".format(role_name), self.path_updated) - self._target_speed_subscriber = rospy.Subscriber( - "/carla/{}/target_speed".format(role_name), Float64, self.target_speed_updated) + self._target_speed_subscriber = self.create_subscriber( + Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated) - def on_shutdown(self): + def _on_shutdown(self): """ callback on shutdown """ - rospy.loginfo("Shutting down, stopping walker...") + self.loginfo("Shutting down, stopping walker...") self.control_publisher.publish(CarlaWalkerControl()) # stop def target_speed_updated(self, target_speed): """ callback on new target speed """ - rospy.loginfo("New target speed received: {}".format(target_speed.data)) + self.loginfo("New target speed received: {}".format(target_speed.data)) self._target_speed = target_speed.data def path_updated(self, path): """ callback on new route """ - rospy.loginfo("New plan with {} waypoints received. Assigning plan...".format( + self.loginfo("New plan with {} waypoints received. Assigning plan...".format( len(path.poses))) self.control_publisher.publish(CarlaWalkerControl()) # stop self._waypoints = [] @@ -91,8 +106,11 @@ def run(self): :return: """ - r = rospy.Rate(20) - while not rospy.is_shutdown(): + loop_frequency = 20 + if ROS_VERSION == 1: + r = rospy.Rate(loop_frequency) + self.loginfo("Starting run loop") + while ros_ok(): if self._waypoints: control = CarlaWalkerControl() direction = Vector3() @@ -106,14 +124,18 @@ def run(self): else: self._waypoints = self._waypoints[1:] if self._waypoints: - rospy.loginfo("next waypoint: {} {}".format( + self.loginfo("next waypoint: {} {}".format( self._waypoints[0].position.x, self._waypoints[0].position.y)) else: - rospy.loginfo("Route finished.") + self.loginfo("Route finished.") self.control_publisher.publish(control) try: - r.sleep() - except rospy.ROSInterruptException: + if ROS_VERSION == 1: + r.sleep() + elif ROS_VERSION == 2: + # TODO: use rclpy.Rate, not working yet + time.sleep(1 / loop_frequency) + except ROSInterruptException: pass @@ -124,15 +146,20 @@ def main(): :return: """ - rospy.init_node('carla_walker_agent', anonymous=True) - role_name = rospy.get_param("~role_name", "ego_vehicle") - target_speed = rospy.get_param("~target_speed", 20) - controller = CarlaWalkerAgent(role_name, target_speed) + if ROS_VERSION == 2: + rclpy.init() + + controller = CarlaWalkerAgent() + + if ROS_VERSION == 2: + spin_thread = threading.Thread(target=controller.spin, daemon=True) + spin_thread.start() + try: controller.run() finally: del controller - rospy.loginfo("Done") + print("Done") if __name__ == "__main__": diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py index 45e6e3ce..9d738afb 100644 --- a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py @@ -28,6 +28,7 @@ def generate_launch_description(): node_executable='carla_waypoint_publisher', name='carla_waypoint_publisher', output='screen', + emulate_tty='True', parameters=[ { '/carla/host': launch.substitutions.LaunchConfiguration('host') From 1e245530c1656a3fcc50631703a1424cd048a80f Mon Sep 17 00:00:00 2001 From: jbmag <47941074+jbmag@users.noreply.github.com> Date: Mon, 19 Oct 2020 19:17:01 +0200 Subject: [PATCH 338/627] ported pcl_recorder to ros2 (#395) * ported pcl_recorder to ros2 * remove unnecessary includes * added ros1 comdition on some commented depend tags --- pcl_recorder/CMakeLists.txt | 91 +++++++++++++++++----- pcl_recorder/include/PclRecorderROS2.h | 30 +++++++ pcl_recorder/launch/pcl_recorder.launch.py | 10 +-- pcl_recorder/package.xml | 31 +++++--- pcl_recorder/src/PclRecorderROS2.cpp | 65 ++++++++++++++++ pcl_recorder/src/mainROS2.cpp | 16 ++++ 6 files changed, 209 insertions(+), 34 deletions(-) create mode 100644 pcl_recorder/include/PclRecorderROS2.h create mode 100644 pcl_recorder/src/PclRecorderROS2.cpp create mode 100644 pcl_recorder/src/mainROS2.cpp diff --git a/pcl_recorder/CMakeLists.txt b/pcl_recorder/CMakeLists.txt index c6e4ae85..8dd8ea04 100644 --- a/pcl_recorder/CMakeLists.txt +++ b/pcl_recorder/CMakeLists.txt @@ -1,29 +1,82 @@ -cmake_minimum_required(VERSION 3.1) +cmake_minimum_required(VERSION 3.3) project(pcl_recorder) -find_package(catkin REQUIRED COMPONENTS pcl_conversions pcl_ros roscpp - sensor_msgs roslaunch) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_package() +if(${ROS_VERSION} EQUAL 1) -roslaunch_add_file_check(launch DEPENDENCIES ${PROJECT_NAME}_node) + find_package(catkin REQUIRED COMPONENTS pcl_conversions pcl_ros roscpp + sensor_msgs roslaunch) -include_directories(include ${catkin_INCLUDE_DIRS}) + catkin_package() -add_executable(${PROJECT_NAME}_node src/PclRecorder.cpp src/main.cpp) + roslaunch_add_file_check(launch DEPENDENCIES ${PROJECT_NAME}_node) -target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES}) + include_directories(include ${catkin_INCLUDE_DIRS}) -target_compile_features( - ${PROJECT_NAME}_node - PRIVATE cxx_inheriting_constructors cxx_lambdas cxx_auto_type - cxx_variadic_templates cxx_variable_templates) + add_executable(${PROJECT_NAME}_node src/PclRecorder.cpp src/main.cpp) -install( - TARGETS ${PROJECT_NAME}_node - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES}) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + target_compile_features( + ${PROJECT_NAME}_node + PRIVATE cxx_inheriting_constructors cxx_lambdas cxx_auto_type + cxx_variadic_templates cxx_variable_templates) + + install( + TARGETS ${PROJECT_NAME}_node + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + +elseif(${ROS_VERSION} EQUAL 2) + # Default to C++14 + if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) + endif() + + if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) + endif() + + find_package(ament_cmake REQUIRED) + find_package(rclcpp REQUIRED) + find_package(rclcpp_components REQUIRED) + find_package(sensor_msgs COMPONENTS) + find_package(tf2 REQUIRED) + find_package(tf2_geometry_msgs REQUIRED) + find_package(tf2_ros REQUIRED) + find_package(pcl_conversions REQUIRED) + + find_package( + Boost + COMPONENTS system + REQUIRED) + find_package(PCL REQUIRED COMPONENTS common io) + + include_directories(include ${PCL_INCLUDE_DIRS}) + + add_executable(${PROJECT_NAME}_node src/PclRecorderROS2.cpp src/mainROS2.cpp) + + ament_target_dependencies(${PROJECT_NAME}_node rclcpp sensor_msgs + pcl_conversions tf2_ros tf2) + + target_link_libraries(${PROJECT_NAME}_node ${Boost_SYSTEM_LIBRARY} + ${PCL_LIBRARIES}) + + target_compile_features( + ${PROJECT_NAME}_node + PRIVATE cxx_inheriting_constructors cxx_lambdas cxx_auto_type + cxx_variadic_templates cxx_variable_templates) + + install(TARGETS ${PROJECT_NAME}_node DESTINATION lib/${PROJECT_NAME}) + + install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/) + + ament_package() + +endif() diff --git a/pcl_recorder/include/PclRecorderROS2.h b/pcl_recorder/include/PclRecorderROS2.h new file mode 100644 index 00000000..2cb0029a --- /dev/null +++ b/pcl_recorder/include/PclRecorderROS2.h @@ -0,0 +1,30 @@ +/* + * Copyright (c) 2019-2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#pragma once + +#include "rclcpp/rclcpp.hpp" +#include +#include +#include +#include +#include + +class PclRecorderROS2 : public rclcpp::Node +{ +public: + + PclRecorderROS2(); + + void callback(const sensor_msgs::msg::PointCloud2::SharedPtr cloud); + +private: + rclcpp::Subscription::SharedPtr sub; + std::unique_ptr tf_buffer_ = nullptr; + tf2_ros::TransformListener *tfListener; + static constexpr const char* fixed_frame_ = "map"; + +}; diff --git a/pcl_recorder/launch/pcl_recorder.launch.py b/pcl_recorder/launch/pcl_recorder.launch.py index 347e270f..2ccf22bb 100644 --- a/pcl_recorder/launch/pcl_recorder.launch.py +++ b/pcl_recorder/launch/pcl_recorder.launch.py @@ -20,11 +20,11 @@ def generate_launch_description(): name='role_name', default_value='ego_vehicle' ), - launch_ros.actions.Node( - package='rostopic', - node_executable='rostopic', - name='enable_autopilot_rostopic' - ), + # launch_ros.actions.Node( + # package='rostopic', + # node_executable='rostopic', + # name='enable_autopilot_rostopic' + # ), launch_ros.actions.Node( package='pcl_recorder', node_executable='pcl_recorder_node', diff --git a/pcl_recorder/package.xml b/pcl_recorder/package.xml index 525bf566..1473499d 100644 --- a/pcl_recorder/package.xml +++ b/pcl_recorder/package.xml @@ -1,26 +1,37 @@ - + pcl_recorder 0.0.0 The pcl_recorder package CARLA Simulator Team MIT - catkin + + + + catkin + roscpp + roslaunch + roscpp + roscpp + rostopic + pcl_ros + pcl_ros + pcl_ros + + + rclcpp + ament_cmake + pcl_conversions - pcl_ros - roscpp sensor_msgs - roslaunch pcl_conversions - pcl_ros - roscpp sensor_msgs pcl_conversions - pcl_ros - roscpp sensor_msgs - rostopic carla_ros_bridge + + catkin + ament_cmake diff --git a/pcl_recorder/src/PclRecorderROS2.cpp b/pcl_recorder/src/PclRecorderROS2.cpp new file mode 100644 index 00000000..075a2f6c --- /dev/null +++ b/pcl_recorder/src/PclRecorderROS2.cpp @@ -0,0 +1,65 @@ +/* + * Copyright (c) 2019-2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include "PclRecorderROS2.h" +#include +#include +#include +#include + +PclRecorderROS2::PclRecorderROS2() : Node("pcl_recorder") +{ + rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_ROS_TIME); + rclcpp::TimeSource timesource; + timesource.attachClock(clock); + tf_buffer_ = std::make_unique(clock); + + tfListener = new tf2_ros::TransformListener(*tf_buffer_); + + if (mkdir("/tmp/pcl_capture", 0777) == -1) { + RCLCPP_WARN(this->get_logger(), "Could not create directory!"); + } + + // Create a ROS subscriber for the input point cloud + std::string roleName; + if (!this->get_parameter("role_name", roleName)) { + roleName = "ego_vehicle"; + } + sub = this->create_subscription("/carla/" + roleName + "/lidar/lidar1/point_cloud", 100, std::bind(&PclRecorderROS2::callback, this, std::placeholders::_1)); +} + +void PclRecorderROS2::callback(const sensor_msgs::msg::PointCloud2::SharedPtr cloud) +{ + if ((cloud->width * cloud->height) == 0) { + return; + } + + std::stringstream ss; + ss << "/tmp/pcl_capture/capture" << cloud->header.stamp.sec << cloud->header.stamp.nanosec << ".pcd"; + + + RCLCPP_INFO (this->get_logger(), "Received %d data points. Storing in %s", + (int)cloud->width * cloud->height, + ss.str().c_str()); + + Eigen::Affine3d transform; + try { + transform = tf2::transformToEigen (tf_buffer_->lookupTransform(fixed_frame_, cloud->header.frame_id, cloud->header.stamp, rclcpp::Duration(1))); + + pcl::PointCloud pclCloud; + pcl::fromROSMsg(*cloud, pclCloud); + + pcl::PointCloud transformedCloud; + pcl::transformPointCloud (pclCloud, transformedCloud, transform); + + pcl::PCDWriter writer; + writer.writeBinary(ss.str(), transformedCloud); + } + catch (tf2::TransformException &ex) + { + RCLCPP_WARN(this->get_logger(), "Could NOT transform: %s", ex.what()); + } +} diff --git a/pcl_recorder/src/mainROS2.cpp b/pcl_recorder/src/mainROS2.cpp new file mode 100644 index 00000000..c4451fe9 --- /dev/null +++ b/pcl_recorder/src/mainROS2.cpp @@ -0,0 +1,16 @@ +/* + * Copyright (c) 2019 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include "rclcpp/rclcpp.hpp" +#include "PclRecorderROS2.h" + +int main(int argc, char** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} From 36c6d6dd3bc77f0087567132f74c9593069e962c Mon Sep 17 00:00:00 2001 From: jbmag <47941074+jbmag@users.noreply.github.com> Date: Tue, 20 Oct 2020 17:27:37 +0200 Subject: [PATCH 339/627] port of rqt plugin to ros2 (#397) * port of rqt plugin to ros2 * modified default value in launchfile and bridge.py, added option in ros_bridge launchfile to see info log messages --- .../launch/carla_ros_bridge.launch.py | 1 + ...ros_bridge_with_example_ego_vehicle.launch | 2 +- ..._bridge_with_example_ego_vehicle.launch.py | 2 +- .../src/carla_ros_bridge/bridge.py | 2 +- rqt_carla_control/CMakeLists.txt | 34 ++++++++++---- rqt_carla_control/package.xml | 13 ++++-- rqt_carla_control/resource/rqt_carla_control | 0 rqt_carla_control/setup.cfg | 4 ++ rqt_carla_control/setup.py | 45 +++++++++++++++--- .../rqt_carla_control/rqt_carla_control.py | 46 ++++++++++++++----- 10 files changed, 115 insertions(+), 34 deletions(-) create mode 100644 rqt_carla_control/resource/rqt_carla_control create mode 100644 rqt_carla_control/setup.cfg diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch.py b/carla_ros_bridge/launch/carla_ros_bridge.launch.py index 0599a1e6..7c825af9 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch.py @@ -46,6 +46,7 @@ def generate_launch_description(): node_executable='bridge', name='carla_ros_bridge', output='screen', + emulate_tty='True', on_exit=launch.actions.Shutdown(), parameters=[ { diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index 33decdff..bc830b1f 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -15,7 +15,7 @@ - + diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py index e75d3e70..7a6f5495 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py @@ -42,7 +42,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='synchronous_mode_wait_for_vehicle_control_command', - default_value='True' + default_value='False' ), launch.actions.DeclareLaunchArgument( name='fixed_delta_seconds', diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 4db38f23..192d3071 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -586,7 +586,7 @@ def main(): parameters['timeout'] = carla_bridge.get_param('timeout', 2) parameters['synchronous_mode'] = carla_bridge.get_param('synchronous_mode', False) parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( - 'synchronous_mode_wait_for_vehicle_control_command', True) + 'synchronous_mode_wait_for_vehicle_control_command', False) parameters['fixed_delta_seconds'] = carla_bridge.get_param('fixed_delta_seconds', 0.05) parameters['town'] = carla_bridge.get_param('town', 'Town01') diff --git a/rqt_carla_control/CMakeLists.txt b/rqt_carla_control/CMakeLists.txt index 6246dac9..0fa711cc 100644 --- a/rqt_carla_control/CMakeLists.txt +++ b/rqt_carla_control/CMakeLists.txt @@ -1,16 +1,34 @@ cmake_minimum_required(VERSION 2.8.3) project(rqt_carla_control) -find_package(catkin REQUIRED COMPONENTS rospy rqt_gui_py roslaunch) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if(${ROS_VERSION} EQUAL 1) -catkin_package(CATKIN_DEPENDS rospy rqt_gui_py) + find_package(catkin REQUIRED COMPONENTS rospy rqt_gui_py roslaunch) -catkin_install_python(PROGRAMS src/rqt_carla_control/rqt_carla_control.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + catkin_python_setup() -install(DIRECTORY resource/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/resource) + catkin_package(CATKIN_DEPENDS rospy rqt_gui_py) -install(FILES plugin.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + catkin_install_python(PROGRAMS src/rqt_carla_control/rqt_carla_control.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + + install(DIRECTORY resource/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/resource) + + install(FILES plugin.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +elseif(${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + + install(DIRECTORY resource/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/resource) + + install(FILES plugin.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + + ament_package() +endif() diff --git a/rqt_carla_control/package.xml b/rqt_carla_control/package.xml index 10568d8d..394ef62d 100644 --- a/rqt_carla_control/package.xml +++ b/rqt_carla_control/package.xml @@ -1,16 +1,21 @@ - + rqt_carla_control 0.0.0 The rqt_carla_control package CARLA Simulator Team MIT - catkin - rospy + + catkin + rospy rqt_gui_py - rospy + rospy rqt_gui_py + ament_index_python + python_qt_binding + catkin + ament_python diff --git a/rqt_carla_control/resource/rqt_carla_control b/rqt_carla_control/resource/rqt_carla_control new file mode 100644 index 00000000..e69de29b diff --git a/rqt_carla_control/setup.cfg b/rqt_carla_control/setup.cfg new file mode 100644 index 00000000..f9045d9a --- /dev/null +++ b/rqt_carla_control/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/rqt_carla_control +[install] +install-scripts=$base/lib/rqt_carla_control diff --git a/rqt_carla_control/setup.py b/rqt_carla_control/setup.py index 7b519cfe..3a9c2b47 100755 --- a/rqt_carla_control/setup.py +++ b/rqt_carla_control/setup.py @@ -1,15 +1,46 @@ +#!/usr/bin/env python # -*- coding: utf-8 -*- """ Setup for rqt_carla_control """ +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['rqt_carla_control'], - package_dir={'': 'src'}, -) + d = generate_distutils_setup( + packages=['rqt_carla_control'], + package_dir={'': 'src'}, + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'rqt_carla_control' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + package_dir={'': 'src'}, + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + (os.path.join('share', package_name), ['package.xml']), + (os.path.join('share', package_name), ['plugin.xml']), + ('share/' + package_name + '/resource', + ['resource/CarlaControl.ui', 'resource/pause.png', 'resource/play.png', 'resource/step_once.png']), + ('lib/' + package_name, ['scripts/rqt_carla_control']) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ROS2 RQT CONTROL', + license='MIT', + scripts=['scripts/rqt_carla_control'], + ) diff --git a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py index 59e9a799..9e199b65 100644 --- a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py +++ b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py @@ -9,8 +9,15 @@ RQT Plugin to control CARLA """ import os -import rospy # pylint: disable=import-error -import rospkg + +ROS_VERSION = int(os.environ['ROS_VERSION']) +if ROS_VERSION == 1: + import rospkg +elif ROS_VERSION == 2: + from rclpy.callback_groups import ReentrantCallbackGroup + from ament_index_python.packages import get_package_share_directory + import threading +from ros_compatibility import CompatibleNode, QoSProfile from qt_gui.plugin import Plugin # pylint: disable=import-error from python_qt_binding import loadUi # pylint: disable=import-error @@ -34,8 +41,18 @@ def __init__(self, context): self.setObjectName('CARLA Control') self._widget = QWidget() - ui_file = os.path.join(rospkg.RosPack().get_path( - 'rqt_carla_control'), 'resource', 'CarlaControl.ui') + + self._node = CompatibleNode('rqt_carla_control_node', rospy_init=False) + + if ROS_VERSION == 1: + package_share_dir = rospkg.RosPack().get_path('rqt_carla_control') + self.callback_group = None + elif ROS_VERSION == 2: + package_share_dir = get_package_share_directory('rqt_carla_control') + self.callback_group = ReentrantCallbackGroup() + + ui_file = os.path.join(package_share_dir, 'resource', 'CarlaControl.ui') + loadUi(ui_file, self._widget) self._widget.setObjectName('CarlaControl') if context.serial_number() > 1: @@ -44,19 +61,20 @@ def __init__(self, context): self.pause_icon = QIcon( QPixmap(os.path.join( - rospkg.RosPack().get_path('rqt_carla_control'), 'resource', 'pause.png'))) + package_share_dir, 'resource', 'pause.png'))) self.play_icon = QIcon( QPixmap(os.path.join( - rospkg.RosPack().get_path('rqt_carla_control'), 'resource', 'play.png'))) + package_share_dir, 'resource', 'play.png'))) self._widget.pushButtonStepOnce.setIcon( QIcon(QPixmap(os.path.join( - rospkg.RosPack().get_path('rqt_carla_control'), 'resource', 'step_once.png')))) + package_share_dir, 'resource', 'step_once.png')))) self.carla_status = None - self.carla_status_subscriber = rospy.Subscriber( - "/carla/status", CarlaStatus, self.carla_status_changed) - self.carla_control_publisher = rospy.Publisher( - "/carla/control", CarlaControl, queue_size=10) + self.carla_status_subscriber = self._node.create_subscriber( + CarlaStatus, "/carla/status", self.carla_status_changed, callback_group=self.callback_group) + + self.carla_control_publisher = self._node.new_publisher( + CarlaControl, "/carla/control", QoSProfile(depth=10, durability=False)) self._widget.pushButtonPlayPause.setDisabled(True) self._widget.pushButtonStepOnce.setDisabled(True) @@ -66,6 +84,10 @@ def __init__(self, context): context.add_widget(self._widget) + if ROS_VERSION == 2: + spin_thread = threading.Thread(target=self._node.spin, daemon=True) + spin_thread.start() + def toggle_play_pause(self): """ toggle play/pause @@ -102,4 +124,4 @@ def shutdown_plugin(self): """ shutdown plugin """ - self.carla_control_publisher.unregister() + self._node.destroy_subscription(self.carla_control_publisher) From d991747cb4c473704f1a623c7757978753e7ff13 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Wed, 21 Oct 2020 14:30:52 +0200 Subject: [PATCH 340/627] Semantic lidar + New communication pipeline (#389) * added semantic lidar sensor * Fixed topic prefix semantic lidar * Updated publishing pipeline * removed communication class * added semantic lidar to test configuration * lidar data converted to list * added semantic lidar test * removed trailing whitespace * semantic lidar prefix updated * semantic lidar expected frame_id fixed --- .../src/carla_ros_bridge/actor.py | 14 +-- .../src/carla_ros_bridge/bridge.py | 107 ++++++++++++----- .../src/carla_ros_bridge/camera.py | 50 ++++---- .../src/carla_ros_bridge/collision_sensor.py | 18 ++- .../src/carla_ros_bridge/communication.py | 110 ------------------ .../src/carla_ros_bridge/ego_vehicle.py | 22 +++- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 18 ++- carla_ros_bridge/src/carla_ros_bridge/imu.py | 16 ++- .../carla_ros_bridge/lane_invasion_sensor.py | 18 ++- .../src/carla_ros_bridge/lidar.py | 85 ++++++++++++-- .../src/carla_ros_bridge/object_sensor.py | 15 ++- .../src/carla_ros_bridge/pseudo_actor.py | 17 +-- .../src/carla_ros_bridge/radar.py | 18 ++- .../src/carla_ros_bridge/rss_sensor.py | 8 +- .../src/carla_ros_bridge/sensor.py | 12 +- .../src/carla_ros_bridge/spectator.py | 8 +- .../src/carla_ros_bridge/traffic.py | 16 +-- .../carla_ros_bridge/traffic_lights_sensor.py | 27 +++-- .../carla_ros_bridge/traffic_participant.py | 17 ++- .../src/carla_ros_bridge/vehicle.py | 8 +- .../src/carla_ros_bridge/walker.py | 8 +- .../src/carla_ros_bridge/world_info.py | 15 ++- carla_ros_bridge/test/ros_bridge_client.py | 9 ++ carla_ros_bridge/test/test_sensors.json | 17 +++ 24 files changed, 376 insertions(+), 277 deletions(-) delete mode 100644 carla_ros_bridge/src/carla_ros_bridge/communication.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 262d1375..479fd9d9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -25,21 +25,19 @@ class Actor(PseudoActor): Generic base class for all carla actors """ - def __init__(self, carla_actor, parent, communication, prefix=None): + def __init__(self, carla_actor, parent, node, prefix=None): """ Constructor :param carla_actor: carla vehicle actor object :type carla_actor: carla.Vehicle :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param prefix: the topic prefix to be used for this actor :type prefix: string """ - super(Actor, self).__init__(parent=parent, - prefix=prefix, - communication=communication) + super(Actor, self).__init__(parent=parent, prefix=prefix, node=node) self.carla_actor = carla_actor if carla_actor.id > np.iinfo(np.uint32).max: @@ -136,7 +134,7 @@ def publish_transform(self, ros_transform_msg): :return: """ - self.publish_message('tf', ros_transform_msg) + self.node.publish_tf_message(ros_transform_msg) def get_marker_color(self): # pylint: disable=no-self-use """ @@ -180,4 +178,4 @@ def publish_marker(self): marker.scale.x = self.carla_actor.bounding_box.extent.x * 2.0 marker.scale.y = self.carla_actor.bounding_box.extent.y * 2.0 marker.scale.z = self.carla_actor.bounding_box.extent.z * 2.0 - self.publish_message('/carla/marker', marker) + self.node.marker_publisher.publish(marker) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 62f29abc..64c69ccb 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -21,10 +21,13 @@ import pkg_resources import rospy +from rosgraph_msgs.msg import Clock +from tf2_msgs.msg import TFMessage +from visualization_msgs.msg import Marker + import carla from carla_ros_bridge.actor import Actor -from carla_ros_bridge.communication import Communication from carla_ros_bridge.sensor import Sensor from carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher @@ -32,7 +35,7 @@ from carla_ros_bridge.spectator import Spectator from carla_ros_bridge.traffic import Traffic, TrafficLight from carla_ros_bridge.vehicle import Vehicle -from carla_ros_bridge.lidar import Lidar +from carla_ros_bridge.lidar import Lidar, SemanticLidar from carla_ros_bridge.radar import Radar from carla_ros_bridge.gnss import Gnss from carla_ros_bridge.imu import ImuSensor @@ -88,11 +91,21 @@ def __init__(self, carla_world, params): self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) - self.comm = Communication() self.update_lock = Lock() self.carla_control_queue = queue.Queue() + # Communication topics + self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10) + self.tf_publisher = rospy.Publisher('tf', TFMessage, queue_size=100) + self.marker_publisher = rospy.Publisher('/carla/marker', + Marker, + queue_size=10) + self.actor_list_publisher = rospy.Publisher('/carla/actor_list', + CarlaActorList, + queue_size=10, + latch=True) + self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds) @@ -140,18 +153,18 @@ def __init__(self, carla_world, params): # add world info self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, - communication=self.comm)) + node=self)) # add global object sensor self.pseudo_actors.append(ObjectSensor(parent=None, - communication=self.comm, + node=self, actor_list=self.actors, filtered_id=None)) self.debug_helper = DebugHelper(carla_world.debug) # add traffic light pseudo sensor self.pseudo_actors.append(TrafficLightsSensor(parent=None, - communication=self.comm, + node=self, actor_list=self.actors)) def destroy(self): @@ -241,12 +254,11 @@ def _synchronous_mode_update(self): world_snapshot = self.carla_world.get_snapshot() self.status_publisher.set_frame(frame) - self.comm.update_clock(world_snapshot.timestamp) + self.update_clock(world_snapshot.timestamp) rospy.logdebug("Tick for frame {} returned. Waiting for sensor data...".format( frame)) self._update(frame, world_snapshot.timestamp.elapsed_seconds) rospy.logdebug("Waiting for sensor data finished.") - self.comm.send_msgs() self._update_actors(set([x.id for x in world_snapshot])) if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: @@ -276,11 +288,10 @@ def _carla_time_tick(self, carla_snapshot): if self.update_lock.acquire(False): if self.timestamp_last_run < carla_snapshot.timestamp.elapsed_seconds: self.timestamp_last_run = carla_snapshot.timestamp.elapsed_seconds - self.comm.update_clock(carla_snapshot.timestamp) + self.update_clock(carla_snapshot.timestamp) self.status_publisher.set_frame(carla_snapshot.frame) self._update(carla_snapshot.frame, carla_snapshot.timestamp.elapsed_seconds) - self.comm.send_msgs() self.update_lock.release() # if possible push current snapshot to update-actors-thread @@ -370,8 +381,7 @@ def publish_actor_list(self): ros_actor_list.actors.append(ros_actor) - self.comm.publish_message( - "/carla/actor_list", ros_actor_list, is_latched=True) + self.actor_list_publisher.publish(ros_actor_list) def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-many-statements """ @@ -388,64 +398,71 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m pseudo_actors = [] if carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": - actor = TrafficLight(carla_actor, parent, self.comm) + actor = TrafficLight(carla_actor, parent, node=self) else: - actor = Traffic(carla_actor, parent, self.comm) + actor = Traffic(carla_actor, parent, node=self) elif carla_actor.type_id.startswith("vehicle"): if carla_actor.attributes.get('role_name')\ in self.parameters['ego_vehicle']['role_name']: actor = EgoVehicle( - carla_actor, parent, self.comm, self._ego_vehicle_control_applied_callback) + carla_actor, parent, self, self._ego_vehicle_control_applied_callback) pseudo_actors.append(ObjectSensor(parent=actor, - communication=self.comm, + node=self, actor_list=self.actors, filtered_id=carla_actor.id)) else: - actor = Vehicle(carla_actor, parent, self.comm) + actor = Vehicle(carla_actor, parent, self) elif carla_actor.type_id.startswith("sensor"): if carla_actor.type_id.startswith("sensor.camera"): if carla_actor.type_id.startswith("sensor.camera.rgb"): actor = RgbCamera( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.camera.depth"): actor = DepthCamera( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.camera.semantic_segmentation"): actor = SemanticSegmentationCamera( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) else: actor = Camera( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.lidar"): - actor = Lidar(carla_actor, parent, self.comm, + if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): + actor = Lidar(carla_actor, parent, self, + self.carla_settings.synchronous_mode) + elif carla_actor.type_id.endswith("sensor.lidar.ray_cast_semantic"): + actor = SemanticLidar(carla_actor, parent, self, + self.carla_settings.synchronous_mode) + elif carla_actor.type_id.startswith("sensor.lidar"): + actor = Lidar(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): - actor = Radar(carla_actor, parent, self.comm, + actor = Radar(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): - actor = Gnss(carla_actor, parent, self.comm, + actor = Gnss(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): actor = ImuSensor( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): actor = CollisionSensor( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.rss"): actor = RssSensor( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): actor = LaneInvasionSensor( - carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) + carla_actor, parent, self, self.carla_settings.synchronous_mode) else: - actor = Sensor(carla_actor, parent, self.comm, + actor = Sensor(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("spectator"): - actor = Spectator(carla_actor, parent, self.comm) + actor = Spectator(carla_actor, parent, self) elif carla_actor.type_id.startswith("walker"): - actor = Walker(carla_actor, parent, self.comm) + actor = Walker(carla_actor, parent, self) else: - actor = Actor(carla_actor, parent, self.comm) + actor = Actor(carla_actor, parent, self) rospy.loginfo("Created {}(id={}, parent_id={}," " type={}, prefix={}, attributes={})".format( @@ -518,6 +535,32 @@ def _ego_vehicle_control_applied_callback(self, ego_vehicle_id): if not self._expected_ego_vehicle_control_command_ids: self._all_vehicle_control_commands_received.set() + def update_clock(self, carla_timestamp): + """ + perform the update of the clock + + :param carla_timestamp: the current carla time + :type carla_timestamp: carla.Timestamp + :return: + """ + self.ros_timestamp = rospy.Time.from_sec( + carla_timestamp.elapsed_seconds) + self.clock_publisher.publish(Clock(self.ros_timestamp)) + + def publish_tf_message(self, msg): + """ + Function to publish ROS TF message. + """ + # prepare tf message + tf_msg = None + tf_to_publish = [] + tf_to_publish.append(msg) + tf_msg = TFMessage(tf_to_publish) + try: + self.tf_publisher.publish(tf_msg) + except Exception as error: # pylint: disable=broad-except + self.logwarn("Failed to publish message: {}".format(error)) + def main(): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 20464479..3de2ee63 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -17,7 +17,7 @@ import rospy import tf from cv_bridge import CvBridge -from sensor_msgs.msg import CameraInfo +from sensor_msgs.msg import CameraInfo, Image import carla from carla_ros_bridge.sensor import Sensor @@ -33,7 +33,7 @@ class Camera(Sensor): # global cv bridge to convert image between opencv and ros cv_bridge = CvBridge() - def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments + def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments """ Constructor @@ -41,8 +41,8 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param prefix: the topic prefix to be used for this actor :type prefix: string """ @@ -50,7 +50,7 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= prefix = 'camera' super(Camera, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix=prefix) @@ -62,6 +62,17 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode, prefix= else: self._build_camera_info() + self.camera_info_publisher = rospy.Publisher(self.get_topic_prefix() + + '/camera_info', + CameraInfo, + queue_size=10) + self.camera_publisher = rospy.Publisher(self.get_topic_prefix() + '/' + + self.get_image_topic_name(), + Image, + queue_size=10) + + self.listen() + def _build_camera_info(self): """ Private function to compute camera info @@ -107,9 +118,8 @@ def sensor_data_updated(self, carla_image): cam_info = self._camera_info cam_info.header = img_msg.header - self.publish_message(self.get_topic_prefix() + '/camera_info', cam_info) - self.publish_message( - self.get_topic_prefix() + '/' + self.get_image_topic_name(), img_msg) + self.camera_info_publisher.publish(cam_info) + self.camera_publisher.publish(img_msg) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ @@ -167,7 +177,7 @@ class RgbCamera(Camera): Camera implementation details for rgb camera """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor @@ -175,14 +185,14 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(RgbCamera, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix='camera/rgb/' + carla_actor.attributes.get('role_name')) @@ -222,7 +232,7 @@ class DepthCamera(Camera): Camera implementation details for depth camera """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor @@ -230,14 +240,14 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(DepthCamera, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix='camera/depth/' + carla_actor.attributes.get('role_name')) @@ -299,7 +309,7 @@ class SemanticSegmentationCamera(Camera): Camera implementation details for segmentation camera """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor @@ -307,15 +317,15 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super( SemanticSegmentationCamera, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix='camera/semantic_segmentation/' + carla_actor.attributes.get('role_name')) diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index 36c349a0..edc824fb 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -10,6 +10,8 @@ Classes to handle collision events """ +import rospy + from carla_ros_bridge.sensor import Sensor from carla_msgs.msg import CarlaCollisionEvent @@ -20,7 +22,7 @@ class CollisionSensor(Sensor): Actor implementation details for a collision sensor """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor @@ -28,18 +30,23 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(CollisionSensor, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, is_event_sensor=True, prefix="collision") + self.collision_publisher = rospy.Publisher(self.get_topic_prefix(), + CarlaCollisionEvent, + queue_size=10) + self.listen() + # pylint: disable=arguments-differ def sensor_data_updated(self, collision_event): """ @@ -55,5 +62,4 @@ def sensor_data_updated(self, collision_event): collision_msg.normal_impulse.y = collision_event.normal_impulse.y collision_msg.normal_impulse.z = collision_event.normal_impulse.z - self.publish_message( - self.get_topic_prefix(), collision_msg) + self.collision_publisher.publish(collision_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/communication.py b/carla_ros_bridge/src/carla_ros_bridge/communication.py deleted file mode 100644 index 08fe7ca2..00000000 --- a/carla_ros_bridge/src/carla_ros_bridge/communication.py +++ /dev/null @@ -1,110 +0,0 @@ -#!/usr/bin/env python - -# -# Copyright (c) 2019 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -""" -Handle communication of ROS topics -""" -import rospy - -from rosgraph_msgs.msg import Clock -from tf2_msgs.msg import TFMessage - - -class Communication(object): - - """ - Handle communication of ROS topics - """ - - def __init__(self): - """ - Constructor - """ - self.tf_to_publish = [] - self.msgs_to_publish = [] - self.publishers = {} - self.subscribers = {} - self.ros_timestamp = rospy.Time() - - # needed? - self.publishers['clock'] = rospy.Publisher( - 'clock', Clock, queue_size=10) - self.publishers['tf'] = rospy.Publisher( - 'tf', TFMessage, queue_size=100) - - def send_msgs(self): - """ - Function to actually send the collected ROS messages out via the publisher - - :return: - """ - # prepare tf message - tf_msg = TFMessage(self.tf_to_publish) - try: - self.publishers['tf'].publish(tf_msg) - except rospy.ROSSerializationException as error: - rospy.logwarn("Failed to serialize message on publishing: {}".format(error)) - except Exception as error: # pylint: disable=broad-except - rospy.logwarn("Failed to publish message: {}".format(error)) - - for publisher, msg in self.msgs_to_publish: - try: - publisher.publish(msg) - except rospy.ROSSerializationException as error: # pylint: disable=broad-except - rospy.logwarn("Failed to serialize message on publishing: {}".format(error)) - except Exception as error: # pylint: disable=broad-except - rospy.logwarn("Failed to publish message: {}".format(error)) - self.msgs_to_publish = [] - self.tf_to_publish = [] - - def publish_message(self, topic, msg, is_latched=False): - """ - Function to publish ROS messages. - - Store the message in a list (waiting for their publication) - with their associated publisher. - If required corresponding publishers are created automatically. - - Messages for /tf topics are handle differently - in order to publish all transforms, objects in the same message - - :param topic: ROS topic to publish the message on - :type topic: string - :param msg: the ROS message to be published - :type msg: a valid ROS message type - :return: - """ - if topic == 'tf': - # transform are merged in same message - self.tf_to_publish.append(msg) - else: - if topic not in self.publishers: - self.publishers[topic] = rospy.Publisher( - topic, type(msg), queue_size=10, latch=is_latched) - self.msgs_to_publish.append((self.publishers[topic], msg)) - - def update_clock(self, carla_timestamp): - """ - perform the update of the clock - - :param carla_timestamp: the current carla time - :type carla_timestamp: carla.Timestamp - :return: - """ - self.ros_timestamp = rospy.Time.from_sec( - carla_timestamp.elapsed_seconds) - self.publish_message('clock', Clock(self.ros_timestamp)) - - def get_current_ros_time(self): - """ - get the current ros time - - :return: the current ros time - :rtype ros.Time - """ - return self.ros_timestamp diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index e5e50ba0..8ab8525c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -34,7 +34,7 @@ class EgoVehicle(Vehicle): Vehicle implementation details for the ego vehicle """ - def __init__(self, carla_actor, parent, communication, vehicle_control_applied_callback): + def __init__(self, carla_actor, parent, node, vehicle_control_applied_callback): """ Constructor @@ -42,18 +42,28 @@ def __init__(self, carla_actor, parent, communication, vehicle_control_applied_c :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge """ super(EgoVehicle, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix=carla_actor.attributes.get('role_name')) self.vehicle_info_published = False self.vehicle_control_override = False self._vehicle_control_applied_callback = vehicle_control_applied_callback + self.vehicle_status_publisher = rospy.Publisher( + self.get_topic_prefix() + "/vehicle_status", + CarlaEgoVehicleStatus, + queue_size=10) + self.vehicle_info_publisher = rospy.Publisher(self.get_topic_prefix() + + "/vehicle_info", + CarlaEgoVehicleInfo, + queue_size=10, + latch=True) + self.control_subscriber = rospy.Subscriber( self.get_topic_prefix() + "/vehicle_control_cmd", CarlaEgoVehicleControl, @@ -109,7 +119,7 @@ def send_vehicle_msgs(self): vehicle_status.control.reverse = self.carla_actor.get_control().reverse vehicle_status.control.gear = self.carla_actor.get_control().gear vehicle_status.control.manual_gear_shift = self.carla_actor.get_control().manual_gear_shift - self.publish_message(self.get_topic_prefix() + "/vehicle_status", vehicle_status) + self.vehicle_status_publisher.publish(vehicle_status) # only send vehicle once (in latched-mode) if not self.vehicle_info_published: @@ -153,7 +163,7 @@ def send_vehicle_msgs(self): vehicle_info.center_of_mass.y = vehicle_physics.center_of_mass.y vehicle_info.center_of_mass.z = vehicle_physics.center_of_mass.z - self.publish_message(self.get_topic_prefix() + "/vehicle_info", vehicle_info, True) + self.vehicle_info_publisher.publish(vehicle_info) def update(self, frame, timestamp): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index 49a8cc52..cae3de6b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -10,6 +10,8 @@ Classes to handle Carla gnsss """ +import rospy + from sensor_msgs.msg import NavSatFix from carla_ros_bridge.sensor import Sensor @@ -21,7 +23,7 @@ class Gnss(Sensor): Actor implementation details for gnss sensor """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor @@ -29,17 +31,22 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(Gnss, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix="gnss/" + carla_actor.attributes.get('role_name')) + self.gnss_publisher = rospy.Publisher(self.get_topic_prefix() + '/fix', + NavSatFix, + queue_size=10) + self.listen() + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_gnss_measurement): """ @@ -53,5 +60,4 @@ def sensor_data_updated(self, carla_gnss_measurement): navsatfix_msg.latitude = carla_gnss_measurement.latitude navsatfix_msg.longitude = carla_gnss_measurement.longitude navsatfix_msg.altitude = carla_gnss_measurement.altitude - self.publish_message( - self.get_topic_prefix() + "/fix", navsatfix_msg) + self.gnss_publisher.publish(navsatfix_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index abb7a0a5..33de5bf6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -7,6 +7,8 @@ Classes to handle Carla imu sensor """ +import rospy + from sensor_msgs.msg import Imu from carla_ros_bridge.sensor import Sensor @@ -19,7 +21,7 @@ class ImuSensor(Sensor): Actor implementation details for imu sensor """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor @@ -27,17 +29,20 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(ImuSensor, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix="imu/" + carla_actor.attributes.get('role_name')) + self.imu_publisher = rospy.Publisher(self.get_topic_prefix(), Imu, queue_size=10) + self.listen() + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_imu_measurement): """ @@ -64,5 +69,4 @@ def sensor_data_updated(self, carla_imu_measurement): quat = trans.carla_rotation_to_numpy_quaternion(imu_rotation) imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) - self.publish_message( - self.get_topic_prefix(), imu_msg) + self.imu_publisher.publish(imu_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 9f3317f5..9d2b8f2e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -10,6 +10,8 @@ Classes to handle lane invasion events """ +import rospy + from carla_ros_bridge.sensor import Sensor from carla_msgs.msg import CarlaLaneInvasionEvent @@ -20,7 +22,7 @@ class LaneInvasionSensor(Sensor): Actor implementation details for a lane invasion sensor """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor @@ -28,18 +30,23 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(LaneInvasionSensor, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, is_event_sensor=True, prefix="lane_invasion") + self.lane_invasion_publisher = rospy.Publisher(self.get_topic_prefix(), + CarlaLaneInvasionEvent, + queue_size=10) + self.listen() + # pylint: disable=arguments-differ def sensor_data_updated(self, lane_invasion_event): """ @@ -52,5 +59,4 @@ def sensor_data_updated(self, lane_invasion_event): lane_invasion_msg.header = self.get_msg_header() for marking in lane_invasion_event.crossed_lane_markings: lane_invasion_msg.crossed_lane_markings.append(marking.type) - self.publish_message( - self.get_topic_prefix(), lane_invasion_msg) + self.lane_invasion_publisher.publish(lane_invasion_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 12810f8a..9423578e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -10,10 +10,12 @@ Classes to handle Carla lidars """ +import rospy + import numpy from sensor_msgs.point_cloud2 import create_cloud -from sensor_msgs.msg import PointField +from sensor_msgs.msg import PointCloud2, PointField from carla_ros_bridge.sensor import Sensor @@ -24,7 +26,7 @@ class Lidar(Sensor): Actor implementation details for lidars """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor @@ -32,15 +34,21 @@ def __init__(self, carla_actor, parent, communication, synchronous_mode): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge """ super(Lidar, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix='lidar/' + carla_actor.attributes.get('role_name')) + self.lidar_publisher = rospy.Publisher(self.get_topic_prefix() + + "/point_cloud", + PointCloud2, + queue_size=10) + self.listen() + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_lidar_measurement): """ @@ -65,5 +73,68 @@ def sensor_data_updated(self, carla_lidar_measurement): # (as lidar point are express in left handed coordinate system, and ros need right handed) lidar_data[:, 1] *= -1 point_cloud_msg = create_cloud(header, fields, lidar_data) - self.publish_message( - self.get_topic_prefix() + "/point_cloud", point_cloud_msg) + self.lidar_publisher.publish(point_cloud_msg) + + +class SemanticLidar(Sensor): + + """ + Actor implementation details for semantic lidars + """ + + def __init__(self, carla_actor, parent, node, synchronous_mode): + """ + Constructor + + :param carla_actor: carla actor object + :type carla_actor: carla.Actor + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + """ + super(SemanticLidar, self).__init__(carla_actor=carla_actor, + parent=parent, + node=node, + synchronous_mode=synchronous_mode, + prefix='semantic_lidar/' + carla_actor.attributes.get('role_name')) + + self.semantic_lidar_publisher = rospy.Publisher( + self.get_topic_prefix() + "/point_cloud", + PointCloud2, + queue_size=10) + self.listen() + + # pylint: disable=arguments-differ + def sensor_data_updated(self, carla_lidar_measurement): + """ + Function to transform a received semantic lidar measurement into a ROS point cloud message + + :param carla_lidar_measurement: carla semantic lidar measurement object + :type carla_lidar_measurement: carla.SemanticLidarMeasurement + """ + header = self.get_msg_header() + fields = [ + PointField('x', 0, PointField.FLOAT32, 1), + PointField('y', 4, PointField.FLOAT32, 1), + PointField('z', 8, PointField.FLOAT32, 1), + PointField('CosAngle', 12, PointField.FLOAT32, 1), + PointField('ObjIdx', 16, PointField.UINT32, 1), + PointField('ObjTag', 20, PointField.UINT32, 1), + ] + + lidar_data = numpy.fromstring(carla_lidar_measurement.raw_data, + dtype=numpy.dtype([ + ('x', numpy.float32), + ('y', numpy.float32), + ('z', numpy.float32), + ('CosAngle', numpy.float32), + ('ObjIdx', numpy.uint32), + ('ObjTag', numpy.uint32) + ])) + + # we take the oposite of y axis + # (as lidar point are express in left handed coordinate system, and ros need right handed) + lidar_data['y'] *= -1 + point_cloud_msg = create_cloud(header, fields, lidar_data.tolist()) + self.semantic_lidar_publisher.publish(point_cloud_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 7eb803c3..c808c37b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -9,6 +9,8 @@ handle a object sensor """ +import rospy + from derived_object_msgs.msg import ObjectArray from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.walker import Walker @@ -21,15 +23,15 @@ class ObjectSensor(PseudoActor): Pseudo object sensor """ - def __init__(self, parent, communication, actor_list, filtered_id): + def __init__(self, parent, node, actor_list, filtered_id): """ Constructor :param carla_world: carla world object :type carla_world: carla.World :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param actor_list: current list of actors :type actor_list: map(carla-actor-id -> python-actor-object) :param filtered_id: id to filter from actor_list @@ -37,10 +39,13 @@ def __init__(self, parent, communication, actor_list, filtered_id): """ super(ObjectSensor, self).__init__(parent=parent, - communication=communication, + node=node, prefix='objects') self.actor_list = actor_list self.filtered_id = filtered_id + self.object_publisher = rospy.Publisher(self.get_topic_prefix(), + ObjectArray, + queue_size=10) def destroy(self): """ @@ -66,4 +71,4 @@ def update(self, frame, timestamp): ros_objects.objects.append(actor.get_object_info()) elif isinstance(actor, Walker): ros_objects.objects.append(actor.get_object_info()) - self.publish_message(self.get_topic_prefix(), ros_objects) + self.object_publisher.publish(ros_objects) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 18fa9c02..0a9b2c6c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -19,15 +19,15 @@ class PseudoActor(object): Generic base class for Pseudo actors (that are not existing in Carla world) """ - def __init__(self, parent, communication, prefix=None): + def __init__(self, parent, node, prefix=None): """ Constructor :param parent: the parent of this :type parent: carla_ros_bridge.PseudoActor :param prefix: the topic prefix to be used for this actor :type prefix: string - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge """ self.parent = parent if self.parent: @@ -35,7 +35,7 @@ def __init__(self, parent, communication, prefix=None): else: self.parent_id = None - self.communication = communication + self.node = node # Concatenate the onw prefix to the the parent topic name if not empty. self.prefix = "" @@ -52,13 +52,6 @@ def destroy(self): :return: """ self.parent = None - self.communication = None - - def publish_message(self, topic, msg, is_latched=False): - """ - hand message over to communication layer - """ - return self.communication.publish_message(topic, msg, is_latched) def get_msg_header(self, frame_id=None, timestamp=None): """ @@ -74,7 +67,7 @@ def get_msg_header(self, frame_id=None, timestamp=None): if timestamp: header.stamp = rospy.Time.from_sec(timestamp) else: - header.stamp = self.communication.get_current_ros_time() + header.stamp = self.node.ros_timestamp return header def get_parent_id(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 4cfa93e4..7971bea4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -10,6 +10,8 @@ Classes to handle Carla Radar """ +import rospy + from carla_msgs.msg import CarlaRadarMeasurement, CarlaRadarDetection from carla_ros_bridge.sensor import Sensor @@ -21,24 +23,30 @@ class Radar(Sensor): Actor implementation details of Carla RADAR """ - def __init__(self, carla_actor, parent, communication, synchronous_mode): + def __init__(self, carla_actor, parent, node, synchronous_mode): """ Constructor :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(Radar, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, synchronous_mode=synchronous_mode, prefix="radar/" + carla_actor.attributes.get('role_name')) + self.radar_publisher = rospy.Publisher(self.get_topic_prefix() + + "/radar", + CarlaRadarMeasurement, + queue_size=10) + self.listen() + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_radar_measurement): """ @@ -56,4 +64,4 @@ def sensor_data_updated(self, carla_radar_measurement): radar_detection.depth = detection.depth radar_detection.velocity = detection.velocity radar_msg.detections.append(radar_detection) - self.publish_message(self.get_topic_prefix() + "/radar", radar_msg) + self.radar_publisher.publish(radar_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py index 5f3b0117..98ee4b63 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py @@ -22,7 +22,7 @@ class RssSensor(Actor): utilization it's not handled as a sensor here. """ - def __init__(self, carla_actor, parent, communication, _): + def __init__(self, carla_actor, parent, node, _): """ Constructor @@ -30,11 +30,11 @@ def __init__(self, carla_actor, parent, communication, _): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge """ super(RssSensor, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix="rss") diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index ded88160..15d03d15 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -30,7 +30,7 @@ class Sensor(Actor): def __init__(self, # pylint: disable=too-many-arguments carla_actor, parent, - communication, + node, synchronous_mode, is_event_sensor=False, # only relevant in synchronous_mode: # if a sensor only delivers data on special events, @@ -44,8 +44,8 @@ def __init__(self, # pylint: disable=too-many-arguments :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool :param prefix: the topic prefix to be used for this actor @@ -55,7 +55,7 @@ def __init__(self, # pylint: disable=too-many-arguments prefix = 'sensor' super(Sensor, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix=prefix) self.synchronous_mode = synchronous_mode @@ -69,8 +69,8 @@ def __init__(self, # pylint: disable=too-many-arguments except (KeyError, ValueError): self.sensor_tick_time = None - if self.__class__.__name__ != "Sensor": - self.carla_actor.listen(self._callback_sensor_data) + def listen(self): + self.carla_actor.listen(self._callback_sensor_data) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/spectator.py b/carla_ros_bridge/src/carla_ros_bridge/spectator.py index 92ddfa31..46df6046 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/spectator.py +++ b/carla_ros_bridge/src/carla_ros_bridge/spectator.py @@ -19,7 +19,7 @@ class Spectator(Actor): Actor implementation details for spectators """ - def __init__(self, carla_actor, parent, communication): + def __init__(self, carla_actor, parent, node): """ Constructor @@ -27,10 +27,10 @@ def __init__(self, carla_actor, parent, communication): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge """ super(Spectator, self).__init__(carla_actor=carla_actor, parent=parent, prefix='spectator', - communication=communication) + node=node) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index ead18d86..043069be 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -22,7 +22,7 @@ class Traffic(Actor): Actor implementation details for traffic objects """ - def __init__(self, carla_actor, parent, communication): + def __init__(self, carla_actor, parent, node): """ Constructor @@ -30,12 +30,12 @@ def __init__(self, carla_actor, parent, communication): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge """ super(Traffic, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix='traffic') @@ -45,7 +45,7 @@ class TrafficLight(Actor): Traffic implementation details for traffic lights """ - def __init__(self, carla_actor, parent, communication): + def __init__(self, carla_actor, parent, node): """ Constructor @@ -53,12 +53,12 @@ def __init__(self, carla_actor, parent, communication): :type carla_actor: carla.TrafficLight :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge """ super(TrafficLight, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix='traffic.traffic_light') def get_status(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 32221482..7151e36c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -9,6 +9,8 @@ a sensor that reports the state of all traffic lights """ +import rospy + from carla_msgs.msg import CarlaTrafficLightStatusList,\ CarlaTrafficLightInfoList from carla_ros_bridge.traffic import TrafficLight @@ -20,24 +22,35 @@ class TrafficLightsSensor(PseudoActor): a sensor that reports the state of all traffic lights """ - def __init__(self, parent, communication, actor_list): + def __init__(self, parent, node, actor_list): """ Constructor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param actor_list: current list of actors :type actor_list: map(carla-actor-id -> python-actor-object) """ super(TrafficLightsSensor, self).__init__(parent=parent, - communication=communication, + node=node, prefix="") self.actor_list = actor_list self.traffic_light_status = CarlaTrafficLightStatusList() self.traffic_light_actors = [] + self.traffic_lights_info_publisher = rospy.Publisher( + self.get_topic_prefix() + "traffic_lights_info", + CarlaTrafficLightInfoList, + queue_size=10, + latch=True) + self.traffic_lights_status_publisher = rospy.Publisher( + self.get_topic_prefix() + "traffic_lights", + CarlaTrafficLightStatusList, + queue_size=10, + latch=True) + def destroy(self): """ Function to destroy this object. @@ -63,10 +76,8 @@ def update(self, frame, timestamp): traffic_light_info_list = CarlaTrafficLightInfoList() for traffic_light in traffic_light_actors: traffic_light_info_list.traffic_lights.append(traffic_light.get_info()) - self.publish_message(self.get_topic_prefix() + "traffic_lights_info", - traffic_light_info_list, is_latched=True) + self.traffic_lights_info_publisher.publish(traffic_light_info_list) if traffic_light_status != self.traffic_light_status: self.traffic_light_status = traffic_light_status - self.publish_message(self.get_topic_prefix() + "traffic_lights", - traffic_light_status, is_latched=True) + self.traffic_lights_status_publisher.publish(traffic_light_status) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 1d4d2dfe..a1821201 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -10,6 +10,8 @@ Classes to handle Carla traffic participants """ +import rospy + from derived_object_msgs.msg import Object from nav_msgs.msg import Odometry from shape_msgs.msg import SolidPrimitive @@ -23,7 +25,7 @@ class TrafficParticipant(Actor): actor implementation details for traffic participant """ - def __init__(self, carla_actor, parent, communication, prefix): + def __init__(self, carla_actor, parent, node, prefix): """ Constructor @@ -31,17 +33,22 @@ def __init__(self, carla_actor, parent, communication, prefix): :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param prefix: the topic prefix to be used for this actor :type prefix: string """ self.classification_age = 0 super(TrafficParticipant, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix=prefix) + self.odometry_publisher = rospy.Publisher(self.get_topic_prefix() + + "/odometry", + Odometry, + queue_size=10) + def update(self, frame, timestamp): """ Function (override) to update this object. @@ -69,7 +76,7 @@ def send_odometry(self): odometry.child_frame_id = self.get_prefix() odometry.pose.pose = self.get_current_ros_pose() odometry.twist.twist = self.get_current_ros_twist_rotated() - self.publish_message(self.get_topic_prefix() + "/odometry", odometry) + self.odometry_publisher.publish(odometry) def get_object_info(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index cc83b34b..ae3bef93 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -22,7 +22,7 @@ class Vehicle(TrafficParticipant): Actor implementation details for vehicles """ - def __init__(self, carla_actor, parent, communication, prefix=None): + def __init__(self, carla_actor, parent, node, prefix=None): """ Constructor @@ -30,8 +30,8 @@ def __init__(self, carla_actor, parent, communication, prefix=None): :type carla_actor: carla.Vehicle :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param prefix: the topic prefix to be used for this actor :type prefix: string """ @@ -53,7 +53,7 @@ def __init__(self, carla_actor, parent, communication, prefix=None): super(Vehicle, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix=prefix) def get_marker_color(self): # pylint: disable=no-self-use diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index b6c2e98f..090859ef 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -23,7 +23,7 @@ class Walker(TrafficParticipant): Actor implementation details for pedestrians """ - def __init__(self, carla_actor, parent, communication): + def __init__(self, carla_actor, parent, node): """ Constructor @@ -31,8 +31,8 @@ def __init__(self, carla_actor, parent, communication): :type carla_actor: carla.Walker :param parent: the parent of this :type parent: carla_ros_bridge.Parent - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge :param prefix: the topic prefix to be used for this actor :type prefix: string """ @@ -43,7 +43,7 @@ def __init__(self, carla_actor, parent, communication): super(Walker, self).__init__(carla_actor=carla_actor, parent=parent, - communication=communication, + node=node, prefix=prefix) self.control_subscriber = rospy.Subscriber( diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index c341fc02..91be9d84 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -22,24 +22,29 @@ class WorldInfo(PseudoActor): Publish the map """ - def __init__(self, carla_world, communication): + def __init__(self, carla_world, node): """ Constructor :param carla_world: carla world object :type carla_world: carla.World - :param communication: communication-handle - :type communication: carla_ros_bridge.communication + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge """ super(WorldInfo, self).__init__(parent=None, - communication=communication, + node=node, prefix="world_info") self.carla_map = carla_world.get_map() self.map_published = False + self.world_info_publisher = rospy.Publisher(self.get_topic_prefix(), + CarlaWorldInfo, + queue_size=10, + latch=True) + def destroy(self): """ Function (override) to destroy this object. @@ -63,5 +68,5 @@ def update(self, frame, timestamp): open_drive_msg = CarlaWorldInfo() open_drive_msg.map_name = self.carla_map.name open_drive_msg.opendrive = self.carla_map.to_opendrive() - self.publish_message(self.get_topic_prefix(), open_drive_msg, is_latched=True) + self.world_info_publisher.publish(open_drive_msg) self.map_published = True diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index d1c812e9..a157958b 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -143,6 +143,15 @@ def test_lidar(self): "/carla/ego_vehicle/lidar/lidar1/point_cloud", PointCloud2, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/lidar/lidar1") + def test_semantic_lidar(self): + """ + Tests semantic_lidar sensor node + """ + rospy.init_node('test_node', anonymous=True) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/semantic_lidar/lidar1/point_cloud", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/semantic_lidar/lidar1") + def test_radar(self): """ Tests Radar sensor node diff --git a/carla_ros_bridge/test/test_sensors.json b/carla_ros_bridge/test/test_sensors.json index 069b56db..dbcb6abe 100644 --- a/carla_ros_bridge/test/test_sensors.json +++ b/carla_ros_bridge/test/test_sensors.json @@ -94,6 +94,23 @@ "rotation_frequency": 20, "sensor_tick": 0.05 }, + { + "type": "sensor.lidar.ray_cast_semantic", + "id": "lidar1", + "x": 0.0, + "y": 0.0, + "z": 2.4, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05 + }, { "type": "sensor.other.radar", "id": "front", From a203f3571e57877fd4ac329fbe5f2c30199f016b Mon Sep 17 00:00:00 2001 From: joel-mb Date: Mon, 26 Oct 2020 16:32:20 +0100 Subject: [PATCH 341/627] DVS camera + New spawn sensor pipeline (#399) * added semantic lidar sensor * Fixed topic prefix semantic lidar * Updated publishing pipeline * removed communication class * added semantic lidar to test configuration * lidar data converted to list * added semantic lidar test * removed trailing whitespace * semantic lidar prefix updated * semantic lidar expected frame_id fixed * spawn sensors pipeline updated * dvs camera sensor integrated * Merge branch 'master' of https://github.com/carla-simulator/ros-bridge into joel-mb/dvs_camera * renamed width/height attributes to image_size_x/y * removed default sensor definition file * dvs camera integration * Added publishing DVS events as images. * Using PointCloud2 messages instead of custom DVS messages to publish the DVSEventArray data. * removed trailing whitespace * CHANGELOG updated * dvs camera tests fixed * added missing sensor descriptions --- CHANGELOG.md | 1 + README.md | 32 +++- carla_ad_demo/config/sensors.json | 4 +- carla_ego_vehicle/config/sensors.json | 8 +- .../carla_ego_vehicle/carla_ego_vehicle.py | 165 +++--------------- carla_infrastructure/config/sensors.json | 4 +- .../carla_infrastructure.py | 143 ++++----------- .../src/carla_ros_bridge/bridge.py | 5 +- .../src/carla_ros_bridge/camera.py | 152 +++++++++++++--- carla_ros_bridge/test/ros_bridge_client.py | 32 ++++ carla_ros_bridge/test/test_sensors.json | 68 +++++++- 11 files changed, 326 insertions(+), 288 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 30c56366..08470728 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Add DVS camera sensor * Fix rgb camera attributes * Add intensity value to point cloud message * Fixed wrong TF for ego_vehicle diff --git a/README.md b/README.md index 5f397626..54b0c27e 100644 --- a/README.md +++ b/README.md @@ -8,7 +8,7 @@ This ROS package aims at providing a simple ROS bridge for CARLA simulator. ## Features -- Provide Sensor Data (Lidar, Cameras (depth, segmentation, rgb), GNSS, Radar, IMU) +- Provide Sensor Data (Lidar, Semantic lidar, Cameras (depth, segmentation, rgb, dvs), GNSS, Radar, IMU) - Provide Object Data (Transforms (via [tf](http://wiki.ros.org/tf)), Traffic light status, Visualization markers, Collision, Lane invasion) - Control AD Agents (Steer/Throttle/Brake) - Control CARLA (Support synchronous mode, Play/pause simulation, Set simulation parameters) @@ -159,19 +159,47 @@ The ego vehicle sensors are provided via topics with prefix /carla/ego_vehicle/& Currently the following sensors are supported: -##### Camera +##### RGB camera | Topic | Type | | -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | | `/carla//camera/rgb//image_color` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | | `/carla//camera/rgb//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | +##### Depth camera + +| Topic | Type | +| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | +| `/carla//camera/depth//image_depth` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | +| `/carla//camera/depth//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | + +##### Semantic segmentation camera + +| Topic | Type | +| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | +| `/carla//camera/semantic_segmentation//image_segmentation` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | +| `/carla//camera/semantic_segmentation//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | + +##### DVS camera + +| Topic | Type | +| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | +| `/carla//camera/dvs//events` | [sensor_msgs.PointCloud2](http://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla//camera/dvs//image_events` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | +| `/carla//camera/dvs//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | + ##### Lidar | Topic | Type | | --------------------------------------------------------- | ---------------------------------------------------------------------------------------- | | `/carla//lidar//point_cloud` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | +##### Semantic lidar + +| Topic | Type | +| --------------------------------------------------------- | ---------------------------------------------------------------------------------------- | +| `/carla//semantic_lidar//point_cloud` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | + ##### Radar | Topic | Type | diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json index 4c46bbba..d64223bc 100644 --- a/carla_ad_demo/config/sensors.json +++ b/carla_ad_demo/config/sensors.json @@ -4,8 +4,8 @@ "type": "sensor.camera.rgb", "id": "view", "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, - "width": 800, - "height": 600, + "image_size_x": 800, + "image_size_y": 600, "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index e3a6ba98..225895cb 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -4,8 +4,8 @@ "type": "sensor.camera.rgb", "id": "front", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "width": 800, - "height": 600, + "image_size_x": 800, + "image_size_y": 600, "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, @@ -50,8 +50,8 @@ "type": "sensor.camera.rgb", "id": "view", "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, - "width": 800, - "height": 600, + "image_size_x": 800, + "image_size_y": 600, "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 7392043f..af992762 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -185,7 +185,10 @@ def setup_sensors(self, sensors): sensor_names = [] for sensor_spec in sensors: try: - sensor_name = str(sensor_spec['type']) + "/" + str(sensor_spec['id']) + sensor_type = str(sensor_spec.pop("type")) + sensor_id = str(sensor_spec.pop("id")) + + sensor_name = sensor_type + "/" + sensor_id if sensor_name in sensor_names: rospy.logfatal( "Sensor rolename '{}' is only allowed to be used once.".format( @@ -194,149 +197,33 @@ def setup_sensors(self, sensors): "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) sensor_names.append(sensor_name) - bp = bp_library.find(str(sensor_spec['type'])) - bp.set_attribute('role_name', str(sensor_spec['id'])) - if sensor_spec['type'].startswith('sensor.camera'): - bp.set_attribute('image_size_x', str(sensor_spec['width'])) - bp.set_attribute('image_size_y', str(sensor_spec['height'])) - bp.set_attribute('fov', str(sensor_spec['fov'])) - try: - bp.set_attribute('sensor_tick', str(sensor_spec['sensor_tick'])) - except KeyError: - pass - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], - roll=sensor_spec['roll'], - yaw=sensor_spec['yaw']) - if sensor_spec['type'].startswith('sensor.camera.rgb'): - bp.set_attribute('gamma', str(sensor_spec['gamma'])) - bp.set_attribute('shutter_speed', str(sensor_spec['shutter_speed'])) - bp.set_attribute('iso', str(sensor_spec['iso'])) - bp.set_attribute('fstop', str(sensor_spec['fstop'])) - bp.set_attribute('min_fstop', str(sensor_spec['min_fstop'])) - bp.set_attribute('blade_count', str(sensor_spec['blade_count'])) - bp.set_attribute('exposure_mode', str(sensor_spec['exposure_mode'])) - bp.set_attribute('exposure_compensation', str( - sensor_spec['exposure_compensation'])) - bp.set_attribute('exposure_min_bright', str( - sensor_spec['exposure_min_bright'])) - bp.set_attribute('exposure_max_bright', str( - sensor_spec['exposure_max_bright'])) - bp.set_attribute('exposure_speed_up', str( - sensor_spec['exposure_speed_up'])) - bp.set_attribute('exposure_speed_down', str( - sensor_spec['exposure_speed_down'])) - bp.set_attribute('calibration_constant', str( - sensor_spec['calibration_constant'])) - bp.set_attribute('focal_distance', str(sensor_spec['focal_distance'])) - bp.set_attribute('blur_amount', str(sensor_spec['blur_amount'])) - bp.set_attribute('blur_radius', str(sensor_spec['blur_radius'])) - bp.set_attribute('motion_blur_intensity', str( - sensor_spec['motion_blur_intensity'])) - bp.set_attribute('motion_blur_max_distortion', str( - sensor_spec['motion_blur_max_distortion'])) - bp.set_attribute('motion_blur_min_object_screen_size', str( - sensor_spec['motion_blur_min_object_screen_size'])) - bp.set_attribute('slope', str(sensor_spec['slope'])) - bp.set_attribute('toe', str(sensor_spec['toe'])) - bp.set_attribute('shoulder', str(sensor_spec['shoulder'])) - bp.set_attribute('black_clip', str(sensor_spec['black_clip'])) - bp.set_attribute('white_clip', str(sensor_spec['white_clip'])) - bp.set_attribute('temp', str(sensor_spec['temp'])) - bp.set_attribute('tint', str(sensor_spec['tint'])) - bp.set_attribute('chromatic_aberration_intensity', str( - sensor_spec['chromatic_aberration_intensity'])) - bp.set_attribute('chromatic_aberration_offset', str( - sensor_spec['chromatic_aberration_offset'])) - bp.set_attribute('enable_postprocess_effects', str( - sensor_spec['enable_postprocess_effects'])) - bp.set_attribute('lens_circle_falloff', str( - sensor_spec['lens_circle_falloff'])) - bp.set_attribute('lens_circle_multiplier', str( - sensor_spec['lens_circle_multiplier'])) - bp.set_attribute('lens_k', str(sensor_spec['lens_k'])) - bp.set_attribute('lens_kcube', str(sensor_spec['lens_kcube'])) - bp.set_attribute('lens_x_size', str(sensor_spec['lens_x_size'])) - bp.set_attribute('lens_y_size', str(sensor_spec['lens_y_size'])) - bp.set_attribute('bloom_intensity', str(sensor_spec['bloom_intensity'])) - bp.set_attribute('lens_flare_intensity', str( - sensor_spec['lens_flare_intensity'])) - elif sensor_spec['type'].startswith('sensor.lidar'): - bp.set_attribute('range', str(sensor_spec['range'])) - bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) - bp.set_attribute('channels', str(sensor_spec['channels'])) - bp.set_attribute('upper_fov', str(sensor_spec['upper_fov'])) - bp.set_attribute('lower_fov', str(sensor_spec['lower_fov'])) - bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) - try: - bp.set_attribute('sensor_tick', str(sensor_spec['sensor_tick'])) - except KeyError: - pass - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], - roll=sensor_spec['roll'], - yaw=sensor_spec['yaw']) - elif sensor_spec['type'].startswith('sensor.other.gnss'): - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation() - bp.set_attribute('noise_alt_stddev', str(sensor_spec['noise_alt_stddev'])) - bp.set_attribute('noise_lat_stddev', str(sensor_spec['noise_lat_stddev'])) - bp.set_attribute('noise_lon_stddev', str(sensor_spec['noise_lon_stddev'])) - bp.set_attribute('noise_alt_bias', str(sensor_spec['noise_alt_bias'])) - bp.set_attribute('noise_lat_bias', str(sensor_spec['noise_lat_bias'])) - bp.set_attribute('noise_lon_bias', str(sensor_spec['noise_lon_bias'])) - try: - bp.set_attribute('sensor_tick', str(sensor_spec['sensor_tick'])) - except KeyError: - pass - elif sensor_spec['type'].startswith('sensor.other.imu'): - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], - roll=sensor_spec['roll'], - yaw=sensor_spec['yaw']) - bp.set_attribute('noise_accel_stddev_x', - str(sensor_spec['noise_accel_stddev_x'])) - bp.set_attribute('noise_accel_stddev_y', - str(sensor_spec['noise_accel_stddev_y'])) - bp.set_attribute('noise_accel_stddev_z', - str(sensor_spec['noise_accel_stddev_z'])) - - bp.set_attribute('noise_gyro_stddev_x', str(sensor_spec['noise_gyro_stddev_x'])) - bp.set_attribute('noise_gyro_stddev_y', str(sensor_spec['noise_gyro_stddev_y'])) - bp.set_attribute('noise_gyro_stddev_z', str(sensor_spec['noise_gyro_stddev_z'])) - bp.set_attribute('noise_gyro_bias_x', str(sensor_spec['noise_gyro_bias_x'])) - bp.set_attribute('noise_gyro_bias_y', str(sensor_spec['noise_gyro_bias_y'])) - bp.set_attribute('noise_gyro_bias_z', str(sensor_spec['noise_gyro_bias_z'])) - try: - bp.set_attribute('sensor_tick', str(sensor_spec['sensor_tick'])) - except KeyError: - pass - elif sensor_spec['type'].startswith('sensor.other.radar'): - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], - roll=sensor_spec['roll'], - yaw=sensor_spec['yaw']) - - bp.set_attribute('horizontal_fov', str(sensor_spec['horizontal_fov'])) - bp.set_attribute('vertical_fov', str(sensor_spec['vertical_fov'])) - bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) - bp.set_attribute('range', str(sensor_spec['range'])) - try: - bp.set_attribute('sensor_tick', str(sensor_spec['sensor_tick'])) - except KeyError: - pass + + sensor_location = carla.Location(x=sensor_spec.pop("x"), + y=sensor_spec.pop("y"), + z=sensor_spec.pop("z")) + sensor_rotation = carla.Rotation( + pitch=sensor_spec.pop('pitch', 0.0), + roll=sensor_spec.pop('roll', 0.0), + yaw=sensor_spec.pop('yaw', 0.0)) + sensor_transform = carla.Transform(sensor_location, sensor_rotation) + + bp = bp_library.find(sensor_type) + bp.set_attribute('role_name', sensor_id) + for attribute, value in sensor_spec.items(): + bp.set_attribute(str(attribute), str(value)) + except KeyError as e: rospy.logfatal( - "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) + "Sensor will not be spawned, the mandatory attribute {} is missing" + .format(e)) + raise e + + except IndexError as e: + rospy.logfatal( + "Sensor {} will not be spawned, {}".format(sensor_name, e)) raise e # create sensor - sensor_transform = carla.Transform(sensor_location, sensor_rotation) sensor = self.world.spawn_actor(bp, sensor_transform, attach_to=self.player) actors.append(sensor) diff --git a/carla_infrastructure/config/sensors.json b/carla_infrastructure/config/sensors.json index ee9b10fa..b7ad0b92 100644 --- a/carla_infrastructure/config/sensors.json +++ b/carla_infrastructure/config/sensors.json @@ -4,8 +4,8 @@ "type": "sensor.camera.rgb", "id": "camera01", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "width": 800, - "height": 600, + "image_size_x": 800, + "image_size_y": 600, "fov": 100, "gamma": 2.2, "shutter_speed": 60.0, diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index a2dc6669..9e3a978e 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -63,119 +63,48 @@ def setup_sensors(self, sensors): """ actors = [] bp_library = self.world.get_blueprint_library() + sensor_names = [] for sensor_spec in sensors: try: - bp = bp_library.find(str(sensor_spec['type'])) - bp.set_attribute('role_name', str(sensor_spec['id'])) - if sensor_spec['type'].startswith('sensor.camera'): - bp.set_attribute('image_size_x', str(sensor_spec['width'])) - bp.set_attribute( - 'image_size_y', str(sensor_spec['height'])) - bp.set_attribute('fov', str(sensor_spec['fov'])) - bp.set_attribute('gamma', str(sensor_spec['gamma'])) - bp.set_attribute('shutter_speed', str( - sensor_spec['shutter_speed'])) - bp.set_attribute('iso', str(sensor_spec['iso'])) - bp.set_attribute('fstop', str(sensor_spec['fstop'])) - bp.set_attribute('min_fstop', str( - sensor_spec['min_fstop'])) - bp.set_attribute('blade_count', str( - sensor_spec['blade_count'])) - bp.set_attribute('exposure_mode', str( - sensor_spec['exposure_mode'])) - bp.set_attribute('exposure_compensation', str( - sensor_spec['exposure_compensation'])) - bp.set_attribute('exposure_min_bright', str( - sensor_spec['exposure_min_bright'])) - bp.set_attribute('exposure_max_bright', str( - sensor_spec['exposure_max_bright'])) - bp.set_attribute('exposure_speed_up', str( - sensor_spec['exposure_speed_up'])) - bp.set_attribute('exposure_speed_down', str( - sensor_spec['exposure_speed_down'])) - bp.set_attribute('calibration_constant', str( - sensor_spec['calibration_constant'])) - bp.set_attribute('focal_distance', str( - sensor_spec['focal_distance'])) - bp.set_attribute('blur_amount', str( - sensor_spec['blur_amount'])) - bp.set_attribute('blur_radius', str( - sensor_spec['blur_radius'])) - bp.set_attribute('motion_blur_intensity', str( - sensor_spec['motion_blur_intensity'])) - bp.set_attribute('motion_blur_max_distortion', str( - sensor_spec['motion_blur_max_distortion'])) - bp.set_attribute('motion_blur_min_object_screen_size', str( - sensor_spec['motion_blur_min_object_screen_size'])) - bp.set_attribute('slope', str(sensor_spec['slope'])) - bp.set_attribute('toe', str(sensor_spec['toe'])) - bp.set_attribute('shoulder', str(sensor_spec['shoulder'])) - bp.set_attribute('black_clip', str( - sensor_spec['black_clip'])) - bp.set_attribute('white_clip', str( - sensor_spec['white_clip'])) - bp.set_attribute('temp', str(sensor_spec['temp'])) - bp.set_attribute('tint', str(sensor_spec['tint'])) - bp.set_attribute('chromatic_aberration_intensity', str( - sensor_spec['chromatic_aberration_intensity'])) - bp.set_attribute('chromatic_aberration_offset', str( - sensor_spec['chromatic_aberration_offset'])) - bp.set_attribute('enable_postprocess_effects', str( - sensor_spec['enable_postprocess_effects'])) - bp.set_attribute('lens_circle_falloff', str( - sensor_spec['lens_circle_falloff'])) - bp.set_attribute('lens_circle_multiplier', str( - sensor_spec['lens_circle_multiplier'])) - bp.set_attribute('lens_k', str(sensor_spec['lens_k'])) - bp.set_attribute('lens_kcube', str( - sensor_spec['lens_kcube'])) - bp.set_attribute('lens_x_size', str( - sensor_spec['lens_x_size'])) - bp.set_attribute('lens_y_size', str( - sensor_spec['lens_y_size'])) - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], - roll=sensor_spec['roll'], - yaw=sensor_spec['yaw']) - elif sensor_spec['type'].startswith('sensor.lidar'): - bp.set_attribute('range', str(sensor_spec['range'])) - bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) - bp.set_attribute('channels', str(sensor_spec['channels'])) - bp.set_attribute('upper_fov', str(sensor_spec['upper_fov'])) - bp.set_attribute('lower_fov', str(sensor_spec['lower_fov'])) - bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], - roll=sensor_spec['roll'], - yaw=sensor_spec['yaw']) - elif sensor_spec['type'].startswith('sensor.other.gnss'): - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation() - elif sensor_spec['type'].startswith('sensor.other.imu'): - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation() - elif sensor_spec['type'].startswith('sensor.other.radar'): - sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], - z=sensor_spec['z']) - sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], - roll=sensor_spec['roll'], - yaw=sensor_spec['yaw']) - - bp.set_attribute('horizontal_fov', str(sensor_spec['horizontal_fov'])) - bp.set_attribute('vertical_fov', str(sensor_spec['vertical_fov'])) - bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) - bp.set_attribute('range', str(sensor_spec['range'])) + sensor_type = str(sensor_spec.pop("type")) + sensor_id = str(sensor_spec.pop("id")) + + sensor_name = sensor_type + "/" + sensor_id + if sensor_name in sensor_names: + rospy.logfatal( + "Sensor rolename '{}' is only allowed to be used once.".format( + sensor_spec['id'])) + raise NameError( + "Sensor rolename '{}' is only allowed to be used once.".format( + sensor_spec['id'])) + sensor_names.append(sensor_name) + + sensor_location = carla.Location(x=sensor_spec.pop("x"), + y=sensor_spec.pop("y"), + z=sensor_spec.pop("z")) + sensor_rotation = carla.Rotation( + pitch=sensor_spec.pop('pitch', 0.0), + roll=sensor_spec.pop('roll', 0.0), + yaw=sensor_spec.pop('yaw', 0.0)) + sensor_transform = carla.Transform(sensor_location, sensor_rotation) + + bp = bp_library.find(sensor_type) + bp.set_attribute('role_name', sensor_id) + for attribute, value in sensor_spec.items(): + bp.set_attribute(str(attribute), str(value)) + except KeyError as e: rospy.logfatal( - "Sensor will not be spawned, because sensor spec is invalid: '{}'".format(e)) - continue + "Sensor will not be spawned, the mandatory attribute {} is missing" + .format(e)) + raise e + + except IndexError as e: + rospy.logfatal( + "Sensor {} will not be spawned, {}".format(sensor_name, e)) + raise e # create sensor - sensor_transform = carla.Transform(sensor_location, sensor_rotation) sensor = self.world.spawn_actor(bp, sensor_transform) actors.append(sensor) return actors diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 64c69ccb..10e003a4 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -42,7 +42,7 @@ from carla_ros_bridge.ego_vehicle import EgoVehicle from carla_ros_bridge.collision_sensor import CollisionSensor from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera +from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera from carla_ros_bridge.object_sensor import ObjectSensor from carla_ros_bridge.rss_sensor import RssSensor from carla_ros_bridge.walker import Walker @@ -423,6 +423,9 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m elif carla_actor.type_id.startswith("sensor.camera.semantic_segmentation"): actor = SemanticSegmentationCamera( carla_actor, parent, self, self.carla_settings.synchronous_mode) + elif carla_actor.type_id.startswith("sensor.camera.dvs"): + actor = DVSCamera(carla_actor, parent, self, + self.carla_settings.synchronous_mode) else: actor = Camera( carla_actor, parent, self, self.carla_settings.synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 3de2ee63..f3bbfade 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -17,7 +17,8 @@ import rospy import tf from cv_bridge import CvBridge -from sensor_msgs.msg import CameraInfo, Image +from sensor_msgs.point_cloud2 import create_cloud +from sensor_msgs.msg import CameraInfo, Image, PointCloud2, PointField import carla from carla_ros_bridge.sensor import Sensor @@ -66,12 +67,11 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # '/camera_info', CameraInfo, queue_size=10) - self.camera_publisher = rospy.Publisher(self.get_topic_prefix() + '/' + - self.get_image_topic_name(), - Image, - queue_size=10) - self.listen() + self.camera_image_publisher = rospy.Publisher(self.get_topic_prefix() + '/' + + self.get_image_topic_name(), + Image, + queue_size=10) def _build_camera_info(self): """ @@ -97,29 +97,18 @@ def _build_camera_info(self): self._camera_info = camera_info # pylint: disable=arguments-differ - def sensor_data_updated(self, carla_image): + def sensor_data_updated(self, carla_camera_data): """ - Function (override) to transform the received carla image data + Function (override) to transform the received carla camera data into a ROS image message - - :param carla_image: carla image object - :type carla_image: carla.Image """ - if ((carla_image.height != self._camera_info.height) or - (carla_image.width != self._camera_info.width)): - rospy.logerr( - "Camera{} received image not matching configuration".format(self.get_prefix())) - image_data_array, encoding = self.get_carla_image_data_array( - carla_image=carla_image) - img_msg = Camera.cv_bridge.cv2_to_imgmsg(image_data_array, encoding=encoding) - # the camera data is in respect to the camera's own frame - img_msg.header = self.get_msg_header() + img_msg = self.get_ros_image(carla_camera_data) cam_info = self._camera_info cam_info.header = img_msg.header self.camera_info_publisher.publish(cam_info) - self.camera_publisher.publish(img_msg) + self.camera_image_publisher.publish(img_msg) def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): """ @@ -145,14 +134,28 @@ def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): quat) return tf_msg + def get_ros_image(self, carla_camera_data): + """ + Function to transform the received carla camera data into a ROS image message + """ + if ((carla_camera_data.height != self._camera_info.height) or + (carla_camera_data.width != self._camera_info.width)): + rospy.logerr( + "Camera{} received image not matching configuration".format(self.get_prefix())) + image_data_array, encoding = self.get_carla_image_data_array( + carla_camera_data) + img_msg = Camera.cv_bridge.cv2_to_imgmsg(image_data_array, encoding=encoding) + # the camera data is in respect to the camera's own frame + img_msg.header = self.get_msg_header(timestamp=carla_camera_data.timestamp) + + return img_msg + @abstractmethod - def get_carla_image_data_array(self, carla_image): + def get_carla_image_data_array(self, carla_camera_data): """ - Virtual function to convert the carla image to a numpy data array + Virtual function to convert the carla camera data to a numpy data array as input for the cv_bridge.cv2_to_imgmsg() function - :param carla_image: carla image object - :type carla_image: carla.Image :return tuple (numpy data array containing the image information, encoding) :rtype tuple(numpy.ndarray, string) """ @@ -197,6 +200,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): prefix='camera/rgb/' + carla_actor.attributes.get('role_name')) + self.listen() + def get_carla_image_data_array(self, carla_image): """ Function (override) to convert the carla image to a numpy data array @@ -252,6 +257,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): prefix='camera/depth/' + carla_actor.attributes.get('role_name')) + self.listen() + def get_carla_image_data_array(self, carla_image): """ Function (override) to convert the carla image to a numpy data array @@ -330,6 +337,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): prefix='camera/semantic_segmentation/' + carla_actor.attributes.get('role_name')) + self.listen() + def get_carla_image_data_array(self, carla_image): """ Function (override) to convert the carla image to a numpy data array @@ -358,3 +367,96 @@ def get_image_topic_name(self): :rtype string """ return "image_segmentation" + + +class DVSCamera(Camera): + + """ + Sensor implementation details for dvs cameras + """ + + def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments + """ + Constructor + + :param carla_actor: carla actor object + :type carla_actor: carla.Actor + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + :param prefix: the topic prefix to be used for this actor + :type prefix: string + """ + super(DVSCamera, self).__init__(carla_actor=carla_actor, + parent=parent, + node=node, + synchronous_mode=synchronous_mode, + prefix='camera/dvs/' + carla_actor.attributes.get('role_name')) + + self._dvs_events = None + self.dvs_camera_publisher = rospy.Publisher(self.get_topic_prefix() + + '/events', + PointCloud2, + queue_size=10) + + self.listen() + + # pylint: disable=arguments-differ + def sensor_data_updated(self, carla_dvs_event_array): + """ + Function to transform the received DVS event array into a ROS message + + :param carla_dvs_event_array: dvs event array object + :type carla_image: carla.DVSEventArray + """ + super(DVSCamera, self).sensor_data_updated(carla_dvs_event_array) + + header = self.get_msg_header(timestamp=carla_dvs_event_array.timestamp) + fields = [ + PointField('x', 0, PointField.UINT16, 1), + PointField('y', 2, PointField.UINT16, 1), + PointField('t', 4, PointField.FLOAT64, 1), + PointField('pol', 12, PointField.INT8, 1), + ] + + dvs_events_msg = create_cloud(header, fields, self._dvs_events.tolist()) + self.dvs_camera_publisher.publish(dvs_events_msg) + + # pylint: disable=arguments-differ + def get_carla_image_data_array(self, carla_dvs_event_array): + """ + Function (override) to convert the carla dvs event array to a numpy data array + as input for the cv_bridge.cv2_to_imgmsg() function + + The carla.DVSEventArray is converted into a 3-channel int8 color image format (bgr). + + :param carla_dvs_event_array: dvs event array object + :type carla_dvs_event_array: carla.DVSEventArray + :return tuple (numpy data array containing the image information, encoding) + :rtype tuple(numpy.ndarray, string) + """ + self._dvs_events = numpy.frombuffer(carla_dvs_event_array.raw_data, + dtype=numpy.dtype([ + ('x', numpy.uint16), + ('y', numpy.uint16), + ('t', numpy.int64), + ('pol', numpy.bool) + ])) + carla_image_data_array = numpy.zeros( + (carla_dvs_event_array.height, carla_dvs_event_array.width, 3), + dtype=numpy.uint8) + # Blue is positive, red is negative + carla_image_data_array[self._dvs_events[:]['y'], self._dvs_events[:]['x'], + self._dvs_events[:]['pol'] * 2] = 255 + + return carla_image_data_array, 'bgr8' + + def get_image_topic_name(self): + """ + Function (override) to provide the actual image topic name + + :return image topic name + :rtype string + """ + return "image_events" diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index a157958b..2ca4104c 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -134,6 +134,38 @@ def test_camera_image(self): self.assertEqual(msg.width, 800) self.assertEqual(msg.encoding, "bgra8") + def test_dvs_camera_info(self): + """ + Tests dvs camera info + """ + rospy.init_node('test_node', anonymous=True) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/camera/dvs/front/camera_info", CameraInfo, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/dvs/front") + self.assertEqual(msg.height, 600) + self.assertEqual(msg.width, 800) + + def test_dvs_camera_image(self): + """ + Tests dvs camera images + """ + rospy.init_node('test_node', anonymous=True) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/camera/dvs/front/image_events", Image, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/dvs/front") + self.assertEqual(msg.height, 600) + self.assertEqual(msg.width, 800) + self.assertEqual(msg.encoding, "bgr8") + + def test_dvs_camera_events(self): + """ + Tests dvs camera events + """ + rospy.init_node('test_node', anonymous=True) + msg = rospy.wait_for_message( + "/carla/ego_vehicle/camera/dvs/front/events", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/dvs/front") + def test_lidar(self): """ Tests Lidar sensor node diff --git a/carla_ros_bridge/test/test_sensors.json b/carla_ros_bridge/test/test_sensors.json index dbcb6abe..27999671 100644 --- a/carla_ros_bridge/test/test_sensors.json +++ b/carla_ros_bridge/test/test_sensors.json @@ -9,8 +9,8 @@ "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "width": 800, - "height": 600, + "image_size_x": 800, + "image_size_y": 600, "fov": 100, "sensor_tick": 0.05, "gamma": 2.2, @@ -58,8 +58,8 @@ "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "width": 800, - "height": 600, + "image_size_x": 800, + "image_size_y": 600, "fov": 100, "sensor_tick": 0.05 }, @@ -72,11 +72,67 @@ "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "width": 800, - "height": 600, + "image_size_x": 800, + "image_size_y": 600, "fov": 100, "sensor_tick": 0.05 }, + { + "type": "sensor.camera.dvs", + "id": "front", + "x": 2.0, + "y": 0.0, + "z": 2.0, + "roll": 0.0, + "pitch": 0.0, + "yaw": 0.0, + "image_size_x": 800, + "image_size_y": 600, + "fov": 100, + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 60.0, + "iso": 100.0, + "fstop": 1.4, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "histogram", + "exposure_compensation": 0.0, + "exposure_min_bright": 7.0, + "exposure_max_bright": 9.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08, + "positive_threshold": 0.3, + "negative_threshold": 0.3, + "sigma_positive_threshold": 0, + "sigma_negative_threshold": 0, + "refractory_period_ns": 0, + "use_log": "True", + "log_eps": 0.001 + }, { "type": "sensor.lidar.ray_cast", "id": "lidar1", From 96c3afc1d26efa1fadcd231faae466f658d48a44 Mon Sep 17 00:00:00 2001 From: Ved Thakur Date: Mon, 26 Oct 2020 21:34:59 +0530 Subject: [PATCH 342/627] Added Lidar Sensor in carla_ad_demo (#385) * Updated carla_ad_demo.rviz file to visualize lidar sensor with appropriate topic * Added lidar sensor with appropriate id in sensors.json file in carla-ad-demo config * Made changes as requested in #385 * Merge branch 'master' into master --- carla_ad_demo/config/carla_ad_demo.rviz | 30 +++++++++++++++++++++++++ carla_ad_demo/config/sensors.json | 12 ++++++++++ 2 files changed, 42 insertions(+) diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index 35fd2f9d..88ab572c 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -93,6 +93,36 @@ Visualization Manager: Path: true Value: true Zoom Factor: 1 + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /carla/ego_vehicle/lidar/lidar1/point_cloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true - Class: rviz/Marker Enabled: true Marker Topic: /carla/marker diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json index d64223bc..a4a3f14f 100644 --- a/carla_ad_demo/config/sensors.json +++ b/carla_ad_demo/config/sensors.json @@ -45,6 +45,18 @@ "lens_y_size": 0.08, "bloom_intensity": 0.675, "lens_flare_intensity": 0.1 + }, + { + "type": "sensor.lidar.ray_cast", + "id": "lidar1", + "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05 } ] } From 1cd7dbf6e7dd2bc34586d82529079ada232f747c Mon Sep 17 00:00:00 2001 From: joel-mb Date: Mon, 26 Oct 2020 17:14:37 +0100 Subject: [PATCH 343/627] Fixed camera topic name (#401) * fixed camera topic name --- carla_ad_demo/config/carla_ad_demo.rviz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index 88ab572c..abfd7c2d 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -80,7 +80,7 @@ Visualization Manager: - Class: rviz/Camera Enabled: true Image Rendering: background and overlay - Image Topic: /carla/ego_vehicle/camera/rgb/spectator_view/image_color + Image Topic: /carla/ego_vehicle/camera/rgb/view/image_color Name: Camera Overlay Alpha: 0.5 Queue Size: 2 From f5ef6a8f9f4f7bd01731a53144dcf68a69aec30d Mon Sep 17 00:00:00 2001 From: joel-mb Date: Mon, 26 Oct 2020 17:27:51 +0100 Subject: [PATCH 344/627] fixed camera topic name (#402) * fixed camera topic name --- carla_ad_demo/config/carla_ad_demo.rviz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index abfd7c2d..88ab572c 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -80,7 +80,7 @@ Visualization Manager: - Class: rviz/Camera Enabled: true Image Rendering: background and overlay - Image Topic: /carla/ego_vehicle/camera/rgb/view/image_color + Image Topic: /carla/ego_vehicle/camera/rgb/spectator_view/image_color Name: Camera Overlay Alpha: 0.5 Queue Size: 2 From 1e41597e5427a1404a94a468f1500eeba75c44a2 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 27 Oct 2020 08:07:02 +0100 Subject: [PATCH 345/627] Fixes ackermann parameters not being applied (#380) Co-authored-by: fpasch <46815108+fpasch@users.noreply.github.com> --- carla_ackermann_control/config/settings.yaml | 12 ++++++------ .../carla_ackermann_control_node.py | 19 +++++++++++++++++++ 2 files changed, 25 insertions(+), 6 deletions(-) diff --git a/carla_ackermann_control/config/settings.yaml b/carla_ackermann_control/config/settings.yaml index b2a1047d..53b86633 100644 --- a/carla_ackermann_control/config/settings.yaml +++ b/carla_ackermann_control/config/settings.yaml @@ -2,14 +2,14 @@ carla: ackermann_control: # override the default values of the pid speed controller # (only relevant for ackermann control mode) - speed_Kp: 0.05 - speed_Ki: 0.00 - speed_Kd: 0.50 + speed_Kp: 0.05 # min: 0, max: 1. + speed_Ki: 0.00 # min: 0, max: 1. + speed_Kd: 0.50 # min: 0, max: 10. # override the default values of the pid acceleration controller # (only relevant for ackermann control mode) - accel_Kp: 0.02 - accel_Ki: 0.00 - accel_Kd: 0.05 + accel_Kp: 0.05 # min: 0, max: 10. + accel_Ki: 0.00 # min: 0, max: 10. + accel_Kd: 0.05 # min: 0, max: 10. # set the minimum acceleration in (m/s^2) # This border value is used to enable the speed controller which is used to control driving # at more or less constant speed. diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index b3722618..a51c5c96 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -103,6 +103,25 @@ def __init__(self): sys.modules['simple_pid.PID']._current_time = ( # pylint: disable=protected-access lambda: rospy.get_rostime().to_sec()) + rospy.set_param( + "/carla/" + self.role_name + "/ackermann_control/speed_Kp", + rospy.get_param("/carla/ackermann_control/speed_Kp", 0.05)) + rospy.set_param( + "/carla/" + self.role_name + "/ackermann_control/speed_Ki", + rospy.get_param("/carla/ackermann_control/speed_Ki", 0.00)) + rospy.set_param( + "/carla/" + self.role_name + "/ackermann_control/speed_Kd", + rospy.get_param("/carla/ackermann_control/speed_Kd", 0.50)) + rospy.set_param( + "/carla/" + self.role_name + "/ackermann_control/accel_Kp", + rospy.get_param("/carla/ackermann_control/accel_Kp", 0.05)) + rospy.set_param( + "/carla/" + self.role_name + "/ackermann_control/accel_Ki", + rospy.get_param("/carla/ackermann_control/accel_Ki", 0.00)) + rospy.set_param( + "/carla/" + self.role_name + "/ackermann_control/accel_Kd", + rospy.get_param("/carla/ackermann_control/accel_Kd", 0.05)) + self.reconfigure_server = Server( EgoVehicleControlParameterConfig, namespace="/carla/" + self.role_name + "/ackermann_control", From 3b8f00d00cd144f72175a49a4d23cc4d3dfbca67 Mon Sep 17 00:00:00 2001 From: jbmag <47941074+jbmag@users.noreply.github.com> Date: Wed, 28 Oct 2020 09:03:49 +0100 Subject: [PATCH 346/627] rviz_carla_plugin port to rviz2/ros2 (#403) * copy of carla_control_panel to use as base for ros2 version * port carla_spectator_camera to ros2 for use with rviz2 plugin * corrected some problems in carla_twist_to_control ros2 implementation * correct bug in subscriber for ego_vehicle manual control * port of rviz carla plugin to rviz2 and ros2 * configure carla_ad_demo package to launch the rviz2 carla plugin * make class CarlaSpectatorCamera inherit from CompatibleNode --- carla_ad_demo/config/carla_ad_demo_ros2.rviz | 168 +++++++ .../carla_ad_demo_with_scenario.launch.py | 36 +- carla_ad_demo/package.xml | 8 +- carla_ad_demo/setup.py | 2 +- .../src/carla_ros_bridge/ego_vehicle.py | 2 +- carla_spectator_camera/CMakeLists.txt | 35 +- .../launch/carla_spectator_camera.launch.py | 7 +- carla_spectator_camera/package.xml | 26 +- .../resource/carla_spectator_camera | 0 carla_spectator_camera/setup.cfg | 4 + carla_spectator_camera/setup.py | 43 +- .../carla_spectator_camera.py | 73 +-- carla_twist_to_control/CMakeLists.txt | 4 + .../launch/carla_twist_to_control.launch.py | 1 + carla_twist_to_control/setup.py | 4 +- rviz_carla_plugin/CMakeLists.txt | 105 ++++- rviz_carla_plugin/package.xml | 25 +- rviz_carla_plugin/plugin_description_ros2.xml | 9 + .../src/carla_control_panel_ROS2.cpp | 417 ++++++++++++++++++ .../src/carla_control_panel_ROS2.h | 112 +++++ 20 files changed, 974 insertions(+), 107 deletions(-) create mode 100644 carla_ad_demo/config/carla_ad_demo_ros2.rviz create mode 100644 carla_spectator_camera/resource/carla_spectator_camera create mode 100644 carla_spectator_camera/setup.cfg create mode 100644 rviz_carla_plugin/plugin_description_ros2.xml create mode 100644 rviz_carla_plugin/src/carla_control_panel_ROS2.cpp create mode 100644 rviz_carla_plugin/src/carla_control_panel_ROS2.h diff --git a/carla_ad_demo/config/carla_ad_demo_ros2.rviz b/carla_ad_demo/config/carla_ad_demo_ros2.rviz new file mode 100644 index 00000000..eefb8f34 --- /dev/null +++ b/carla_ad_demo/config/carla_ad_demo_ros2.rviz @@ -0,0 +1,168 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 78 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz_carla_plugin/CarlaControl + Name: CarlaControl +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz_default_plugins/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /carla/ego_vehicle/waypoints + Unreliable: false + Value: true + - Class: rviz_default_plugins/Camera + Enabled: true + Image Rendering: background and overlay + Topic: /carla/ego_vehicle/camera/rgb/spectator_view/image_color + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Visibility: + Grid: true + Marker: true + Path: true + Value: true + Zoom Factor: 1 + - Class: rviz_default_plugins/Marker + Enabled: true + Topic: /carla/marker + Name: Marker + Namespaces: + "": true + Queue Size: 100 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + - Class: rviz_default_plugins/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz_default_plugins/SetGoal + Topic: /move_base_simple/goal + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz_default_plugins/ThirdPersonFollower + Distance: 13.610654830932617 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.49539870023727417 + Target Frame: ego_vehicle + Value: ThirdPersonFollower (rviz_default_plugins) + Yaw: 3.1504008769989014 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + CarlaControl: + collapsed: false + Displays: + collapsed: false + Height: 1050 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001fe00000367fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000046000000e6000000e600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002870000001a0000000000000000fb0000000a0049006d00610067006501000002a70000001a0000000000000000fb0000000a0049006d00610067006501000002c70000001a0000000000000000fb0000000c00430061006d0065007200610100000132000001960000001a00fffffffb00000018004300610072006c00610043006f006e00740072006f006c01000002ce000000df000000df00ffffff000000010000010f00000367fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004600000367000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077e00000044fc0100000002fb0000000800540069006d006501000000000000077e000002e400fffffffb0000000800540069006d00650100000000000004500000000000000000000004650000036700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1918 + X: 0 + Y: 27 diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index 25b55912..0d8bc0ef 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -5,6 +5,10 @@ import launch_ros.actions from ament_index_python.packages import get_package_share_directory +# string with message to publish on topic /carla/available/scenarios +ros_topic_msg_string = "{{ 'scenarios': [{{ 'name': 'FollowLeadingVehicle', 'scenario_file': '{}'}}] }}".format( + os.path.join(get_package_share_directory('carla_ad_demo'), 'config/FollowLeadingVehicle.xosc')) + def generate_launch_description(): ld = launch.LaunchDescription([ @@ -68,23 +72,24 @@ def generate_launch_description(): package='carla_twist_to_control', node_executable='carla_twist_to_control', name='carla_twist_to_control', + remappings=[ + ( + ["/carla/", + launch.substitutions.LaunchConfiguration('role_name'), "/vehicle_control_cmd"], + ["/carla/", + launch.substitutions.LaunchConfiguration('role_name'), "/vehicle_control_cmd_manual"] + ) + ], parameters=[ { 'role_name': launch.substitutions.LaunchConfiguration('role_name') } ] ), - launch_ros.actions.Node( - package='rostopic', - node_executable='rostopic', - name='publish_scenarios' - ), - launch_ros.actions.Node( - package='rviz', - node_executable='rviz', - name='rviz', - output='screen', - on_exit=launch.actions.Shutdown() + launch.actions.ExecuteProcess( + cmd=["ros2", "topic", "pub", "/carla/available_scenarios", + "carla_ros_scenario_runner_types/CarlaScenarioList", ros_topic_msg_string], + name='topic_pub_vailable_scenarios', ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( @@ -154,6 +159,15 @@ def generate_launch_description(): 'scenario_runner_path': launch.substitutions.LaunchConfiguration('scenario_runner_path'), 'wait_for_ego': 'True' }.items() + ), + launch_ros.actions.Node( + package='rviz2', + node_executable='rviz2', + name='rviz2', + output='screen', + arguments=[ + '-d', os.path.join(get_package_share_directory('carla_ad_demo'), 'config/carla_ad_demo_ros2.rviz')], + on_exit=launch.actions.Shutdown() ) ]) return ld diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 45d6d559..60a5d2d0 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -12,11 +12,10 @@ carla_waypoint_publisher carla_ad_agent carla_manual_control - + rviz_carla_plugin carla_twist_to_control - - - rostopic + carla_spectator_camera + carla_ros_scenario_runner @@ -26,6 +25,7 @@ catkin rviz + rostopic catkin diff --git a/carla_ad_demo/setup.py b/carla_ad_demo/setup.py index d5eb90aa..810ba194 100644 --- a/carla_ad_demo/setup.py +++ b/carla_ad_demo/setup.py @@ -27,7 +27,7 @@ ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ('share/' + package_name + '/config', - ['config/sensors.json']), + ['config/sensors.json', 'config/FollowLeadingVehicle.xosc', 'config/carla_ad_demo_ros2.rviz']), (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 0d91afa2..c0a3a730 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -80,7 +80,7 @@ def __init__(self, carla_actor, parent, node, vehicle_control_applied_callback): self.control_override_subscriber = self.node.create_subscriber( Bool, self.get_topic_prefix() + "/vehicle_control_manual_override", - self.control_command_override) + self.control_command_override, QoSProfile(depth=1, durability=True)) self.enable_autopilot_subscriber = self.node.create_subscriber( Bool, diff --git a/carla_spectator_camera/CMakeLists.txt b/carla_spectator_camera/CMakeLists.txt index dbc2c555..9f2205a3 100644 --- a/carla_spectator_camera/CMakeLists.txt +++ b/carla_spectator_camera/CMakeLists.txt @@ -1,17 +1,34 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_spectator_camera) -find_package(catkin REQUIRED COMPONENTS rospy roslaunch geometry_msgs) +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -catkin_python_setup() +if(${ROS_VERSION} EQUAL 1) -roslaunch_add_file_check(launch) + find_package(catkin REQUIRED COMPONENTS rospy roslaunch geometry_msgs) -catkin_package(CATKIN_DEPENDS rospy) + catkin_python_setup() -catkin_install_python( - PROGRAMS src/carla_spectator_camera/carla_spectator_camera.py DESTINATION - ${CATKIN_PACKAGE_BIN_DESTINATION}) + roslaunch_add_file_check(launch) -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + catkin_package(CATKIN_DEPENDS rospy) + + catkin_install_python( + PROGRAMS src/carla_spectator_camera/carla_spectator_camera.py DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION}) + + install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + +elseif(${ROS_VERSION} EQUAL 2) + find_package(ament_cmake REQUIRED) + find_package(rclpy REQUIRED) + ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + + ament_package() + +endif() diff --git a/carla_spectator_camera/launch/carla_spectator_camera.launch.py b/carla_spectator_camera/launch/carla_spectator_camera.launch.py index a7dfa804..cc6745b4 100644 --- a/carla_spectator_camera/launch/carla_spectator_camera.launch.py +++ b/carla_spectator_camera/launch/carla_spectator_camera.launch.py @@ -40,15 +40,16 @@ def generate_launch_description(): node_executable='carla_spectator_camera', name='carla_spectator_camera', output='screen', + emulate_tty='True', parameters=[ { - '/carla/host': launch.substitutions.LaunchConfiguration('host') + 'carla/host': launch.substitutions.LaunchConfiguration('host') }, { - '/carla/port': launch.substitutions.LaunchConfiguration('port') + 'carla/port': launch.substitutions.LaunchConfiguration('port') }, { - '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + 'carla/timeout': launch.substitutions.LaunchConfiguration('timeout') }, { 'role_name': launch.substitutions.LaunchConfiguration('role_name') diff --git a/carla_spectator_camera/package.xml b/carla_spectator_camera/package.xml index c30a4490..5643395b 100644 --- a/carla_spectator_camera/package.xml +++ b/carla_spectator_camera/package.xml @@ -1,17 +1,27 @@ - + carla_spectator_camera 0.0.0 The carla_spectator_camera package CARLA Simulator Team MIT - catkin - rospy - roslaunch - rospy - rospy - topic_tools + geometry_msgs - + + + catkin + rospy + roslaunch + rospy + rospy + topic_tools + + + rclpy + ament_python + + + catkin + ament_python diff --git a/carla_spectator_camera/resource/carla_spectator_camera b/carla_spectator_camera/resource/carla_spectator_camera new file mode 100644 index 00000000..e69de29b diff --git a/carla_spectator_camera/setup.cfg b/carla_spectator_camera/setup.cfg new file mode 100644 index 00000000..5dfa44b9 --- /dev/null +++ b/carla_spectator_camera/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script-dir=$base/lib/carla_spectator_camera +[install] +install-scripts=$base/lib/carla_spectator_camera \ No newline at end of file diff --git a/carla_spectator_camera/setup.py b/carla_spectator_camera/setup.py index b0dae9aa..806f8284 100644 --- a/carla_spectator_camera/setup.py +++ b/carla_spectator_camera/setup.py @@ -1,13 +1,42 @@ """ Setup for carla_spectator_camera """ +import os +from glob import glob +ROS_VERSION = int(os.environ['ROS_VERSION']) -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup +if ROS_VERSION == 1: + from distutils.core import setup + from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( - packages=['carla_spectator_camera'], - package_dir={'': 'src'} -) + d = generate_distutils_setup( + packages=['carla_spectator_camera'], + package_dir={'': 'src'} + ) -setup(**d) + setup(**d) + +elif ROS_VERSION == 2: + from setuptools import setup + + package_name = 'carla_spectator_camera' + setup( + name=package_name, + version='0.0.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), + (os.path.join('share', package_name), ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='CARLA Simulator Team', + maintainer_email='carla.simulator@gmail.com', + description='CARLA ROS2 Spectator Camera', + license='MIT', + entry_points={ + 'console_scripts': ['carla_spectator_camera = carla_spectator_camera.carla_spectator_camera:main'], + }, + package_dir={'': 'src'}, + ) diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index a491f199..41883e07 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -13,12 +13,21 @@ # pylint: disable=import-error import sys import math -import rospy -from tf.transformations import euler_from_quaternion -import tf from geometry_msgs.msg import PoseStamped from carla_msgs.msg import CarlaWorldInfo +from ros_compatibility import ( + CompatibleNode, + euler_from_quaternion, + QoSProfile, + ROSException, + ROSInterruptException +) +import os +ROS_VERSION = int(os.environ['ROS_VERSION']) +if ROS_VERSION == 2: + import rclpy + import carla # ============================================================================== @@ -26,7 +35,7 @@ # ============================================================================== -class CarlaSpectatorCamera(object): +class CarlaSpectatorCamera(CompatibleNode): """ Spawns a camera, attached to an ego vehicle. @@ -38,28 +47,27 @@ def __init__(self): """ Constructor """ - rospy.init_node('spectator_camera', anonymous=True) - self.listener = tf.TransformListener() - self.role_name = rospy.get_param("/role_name", "ego_vehicle") - self.camera_resolution_x = rospy.get_param("~resolution_x", 800) - self.camera_resolution_y = rospy.get_param("~resolution_y", 600) - self.camera_fov = rospy.get_param("~fov", 50) - self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', 2000) - self.timeout = rospy.get_param("/carla/timeout", 10) + super(CarlaSpectatorCamera, self).__init__('spectator_camera') + self.role_name = self.get_param("role_name", "ego_vehicle") + self.camera_resolution_x = self.get_param("resolution_x", 800) + self.camera_resolution_y = self.get_param("resolution_y", 600) + self.camera_fov = self.get_param("fov", 50) + self.host = self.get_param('carla/host', '127.0.0.1') + self.port = self.get_param('carla/port', 2000) + self.timeout = self.get_param("carla/timeout", 10) self.world = None self.pose = None self.camera_actor = None self.ego_vehicle = None - rospy.Subscriber("/carla/{}/spectator_pose".format(self.role_name), - PoseStamped, self.pose_received) + self.create_subscriber(PoseStamped, + "/carla/{}/spectator_pose".format(self.role_name), self.pose_received) def pose_received(self, pose): """ Move the camera """ if self.pose != pose: - rospy.logdebug("Camera pose changed. Updating carla camera") + self.logdebug("Camera pose changed. Updating carla camera") self.pose = pose transform = self.get_camera_transform() if transform and self.camera_actor: @@ -70,10 +78,10 @@ def get_camera_transform(self): Calculate the CARLA camera transform """ if not self.pose: - rospy.loginfo("no pose!") + self.loginfo("no pose!") return None if self.pose.header.frame_id != self.role_name: - rospy.logwarn("Unsupported frame received. Supported {}, received {}".format( + self.logwarn("Unsupported frame received. Supported {}, received {}".format( self.role_name, self.pose.header.frame_id)) return None sensor_location = carla.Location(x=self.pose.pose.position.x, @@ -100,7 +108,7 @@ def create_camera(self, ego_actor): try: bp = bp_library.find("sensor.camera.rgb") bp.set_attribute('role_name', "spectator_view") - rospy.loginfo("Creating camera with resolution {}x{}, fov {}".format( + self.loginfo("Creating camera with resolution {}x{}, fov {}".format( self.camera_resolution_x, self.camera_resolution_y, self.camera_fov)) @@ -108,7 +116,7 @@ def create_camera(self, ego_actor): bp.set_attribute('image_size_y', str(self.camera_resolution_y)) bp.set_attribute('fov', str(self.camera_fov)) except KeyError as e: - rospy.logfatal("Camera could not be spawned: '{}'".format(e)) + self.logfatal("Camera could not be spawned: '{}'".format(e)) transform = self.get_camera_transform() if not transform: transform = carla.Transform() @@ -137,7 +145,7 @@ def find_ego_vehicle_actor(self): if ego_vehicle_changed: self.destroy() - rospy.loginfo("Ego vehicle changed.") + self.loginfo("Ego vehicle changed.") self.ego_vehicle = hero if self.ego_vehicle: self.create_camera(self.ego_vehicle) @@ -155,24 +163,24 @@ def run(self): main loop """ # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") + self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException: - rospy.logerr("Error while waiting for world info!") + self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, timeout=10.0, + qos_profile=QoSProfile(depth=10, durability=True)) + except ROSException: + self.logerr("Error while waiting for world info!") sys.exit(1) - rospy.loginfo("CARLA world available. Waiting for ego vehicle...") + self.loginfo("CARLA world available. Waiting for ego vehicle...") client = carla.Client(self.host, self.port) client.set_timeout(self.timeout) self.world = client.get_world() + period = 0.1 try: - r = rospy.Rate(10) # 10hz - while not rospy.is_shutdown(): - self.find_ego_vehicle_actor() - r.sleep() - except rospy.ROSInterruptException: + self.new_timer(period, lambda timer_event=None: self.find_ego_vehicle_actor()) + self.spin() + except ROSInterruptException: pass # ============================================================================== @@ -184,6 +192,9 @@ def main(): """ main function """ + if ROS_VERSION == 2: + rclpy.init() + carla_spectator_camera = CarlaSpectatorCamera() try: carla_spectator_camera.run() diff --git a/carla_twist_to_control/CMakeLists.txt b/carla_twist_to_control/CMakeLists.txt index 3bfd9752..95a33849 100644 --- a/carla_twist_to_control/CMakeLists.txt +++ b/carla_twist_to_control/CMakeLists.txt @@ -25,6 +25,10 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(ament_cmake REQUIRED) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) + + # Install launch files. + install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) + ament_package() endif() diff --git a/carla_twist_to_control/launch/carla_twist_to_control.launch.py b/carla_twist_to_control/launch/carla_twist_to_control.launch.py index 9842719f..d2142c59 100644 --- a/carla_twist_to_control/launch/carla_twist_to_control.launch.py +++ b/carla_twist_to_control/launch/carla_twist_to_control.launch.py @@ -16,6 +16,7 @@ def generate_launch_description(): node_executable='carla_twist_to_control', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', + emulate_tty='True', parameters=[ { 'role_name': launch.substitutions.LaunchConfiguration('role_name') diff --git a/carla_twist_to_control/setup.py b/carla_twist_to_control/setup.py index 17bbcd30..c08d685d 100644 --- a/carla_twist_to_control/setup.py +++ b/carla_twist_to_control/setup.py @@ -3,6 +3,7 @@ """ import os +from glob import glob ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: @@ -26,6 +27,7 @@ packages=[package_name], data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), + (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], zip_safe=True, @@ -35,7 +37,7 @@ license='MIT', tests_require=['pytest'], entry_points={ - 'console_scripts': ['twist_to_control = carla_twist_to_control.carla_twist_to_control:main'], + 'console_scripts': ['carla_twist_to_control = carla_twist_to_control.carla_twist_to_control:main'], }, package_dir={'': 'src'}, ) diff --git a/rviz_carla_plugin/CMakeLists.txt b/rviz_carla_plugin/CMakeLists.txt index 8ff69656..7c0d8785 100644 --- a/rviz_carla_plugin/CMakeLists.txt +++ b/rviz_carla_plugin/CMakeLists.txt @@ -1,40 +1,97 @@ -cmake_minimum_required(VERSION 3.1) +cmake_minimum_required(VERSION 3.3) project(rviz_carla_plugin) set(CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_STANDARD 14) -find_package(catkin REQUIRED COMPONENTS rviz carla_msgs nav_msgs - carla_ros_scenario_runner_types) -catkin_package() +find_package(ros_environment REQUIRED) +set(ROS_VERSION $ENV{ROS_VERSION}) -include_directories(${catkin_INCLUDE_DIRS}) -link_directories(${catkin_LIBRARY_DIRS}) +if(${ROS_VERSION} EQUAL 1) -set(CMAKE_AUTOMOC ON) + find_package(catkin REQUIRED COMPONENTS rviz carla_msgs nav_msgs + carla_ros_scenario_runner_types) + catkin_package() -message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") -find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) -set(QT_LIBRARIES Qt5::Widgets) + include_directories(${catkin_INCLUDE_DIRS}) + link_directories(${catkin_LIBRARY_DIRS}) -set(SRC_FILES src/drive_widget.cpp src/indicator_widget.cpp - src/carla_control_panel.cpp) + set(CMAKE_AUTOMOC ON) -qt5_add_resources(SRC_FILES rviz_carla_plugin.qrc) + message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") + find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) + set(QT_LIBRARIES Qt5::Widgets) -add_library(${PROJECT_NAME} ${SRC_FILES}) + set(SRC_FILES src/drive_widget.cpp src/indicator_widget.cpp + src/carla_control_panel.cpp) -target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) + qt5_add_resources(SRC_FILES rviz_carla_plugin.qrc) -target_compile_features(${PROJECT_NAME} PRIVATE cxx_std_14) + add_library(${PROJECT_NAME} ${SRC_FILES}) -install( - TARGETS ${PROJECT_NAME} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) -install(FILES plugin_description.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + target_compile_features(${PROJECT_NAME} PRIVATE cxx_std_14) -install(DIRECTORY icons/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) + install( + TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + + install(FILES plugin_description.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + + install(DIRECTORY icons/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) + +elseif(${ROS_VERSION} EQUAL 2) + + find_package(ament_cmake REQUIRED) + find_package(rviz_common REQUIRED) + find_package(carla_msgs REQUIRED) + find_package(nav_msgs COMPONENTS) + find_package(carla_ros_scenario_runner_types COMPONENTS) + find_package(pluginlib REQUIRED) + find_package(rviz_ogre_vendor REQUIRED) + + set(CMAKE_AUTOMOC ON) + + message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") + find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) + set(QT_LIBRARIES Qt5::Widgets) + + set(SRC_FILES src/drive_widget.cpp src/indicator_widget.cpp + src/carla_control_panel_ROS2.cpp) + + qt5_add_resources(SRC_FILES rviz_carla_plugin.qrc) + + add_library(${PROJECT_NAME} SHARED ${SRC_FILES}) + + target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} + rviz_ogre_vendor::OgreMain) + + target_compile_features(${PROJECT_NAME} PRIVATE cxx_std_14) + + pluginlib_export_plugin_description_file(rviz_common + plugin_description_ros2.xml) + + ament_target_dependencies(rviz_carla_plugin rclcpp carla_msgs nav_msgs + carla_ros_scenario_runner_types) + + ament_export_libraries(${PROJECT_NAME}) + + install( + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin) + + install(FILES plugin_description_ros2.xml DESTINATION "share/${PROJECT_NAME}") + + install(DIRECTORY icons/ DESTINATION "share/${PROJECT_NAME}") + + ament_package() + +endif() diff --git a/rviz_carla_plugin/package.xml b/rviz_carla_plugin/package.xml index c1a0d791..ec2d88c9 100644 --- a/rviz_carla_plugin/package.xml +++ b/rviz_carla_plugin/package.xml @@ -1,26 +1,37 @@ - + rviz_carla_plugin 0.0.1 The carla_ros_bridge package CARLA Simulator Team MIT - catkin + + + catkin + rviz + rviz + + + rclcpp + ament_cmake + rviz_common + qtbase5-dev - rviz - carla_msgs + carla_msgs nav_msgs geometry_msgs carla_ros_scenario_runner_types - carla_msgs nav_msgs geometry_msgs carla_ros_scenario_runner_types libqt5-core libqt5-gui libqt5-widgets - rviz + - + + + catkin + ament_cmake diff --git a/rviz_carla_plugin/plugin_description_ros2.xml b/rviz_carla_plugin/plugin_description_ros2.xml new file mode 100644 index 00000000..bcc4f71a --- /dev/null +++ b/rviz_carla_plugin/plugin_description_ros2.xml @@ -0,0 +1,9 @@ + + + + A panel widget for controlling carla nodes + + + diff --git a/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp b/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp new file mode 100644 index 00000000..d1f2efdd --- /dev/null +++ b/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp @@ -0,0 +1,417 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include +#include "rviz_common/display_context.hpp" + +#include "carla_control_panel_ROS2.h" +#include "drive_widget.h" +#include "indicator_widget.h" + +using std::placeholders::_1; +namespace rviz_carla_plugin { + +CarlaControlPanel::CarlaControlPanel(QWidget *parent) + : rviz_common::Panel(parent) +{ + QVBoxLayout *layout = new QVBoxLayout; + QHBoxLayout *vehicleLayout = new QHBoxLayout; + + QFormLayout *egoCtrlStatusLayout = new QFormLayout; + + mThrottleBar = new QProgressBar(); + mThrottleBar->setRange(0, 100); + egoCtrlStatusLayout->addRow("Throttle", mThrottleBar); + mBrakeBar = new QProgressBar(); + mBrakeBar->setRange(0, 100); + egoCtrlStatusLayout->addRow("Brake", mBrakeBar); + mSteerBar = new QProgressBar(); + mSteerBar->setRange(-100, 100); + egoCtrlStatusLayout->addRow("Steer", mSteerBar); + vehicleLayout->addLayout(egoCtrlStatusLayout); + + QFormLayout *egoStatusLayout = new QFormLayout; + mPosLabel = new QLineEdit(); + mPosLabel->setDisabled(true); + egoStatusLayout->addRow("Position", mPosLabel); + + mSpeedLabel = new QLineEdit(); + mSpeedLabel->setDisabled(true); + egoStatusLayout->addRow("Speed", mSpeedLabel); + + mHeadingLabel = new QLineEdit(); + mHeadingLabel->setDisabled(true); + egoStatusLayout->addRow("Heading", mHeadingLabel); + + vehicleLayout->addLayout(egoStatusLayout); + + QVBoxLayout *egoCtrlLayout = new QVBoxLayout; + mOverrideVehicleControl = new QCheckBox("Manual control"); + mOverrideVehicleControl->setDisabled(true); + egoCtrlLayout->addWidget(mOverrideVehicleControl); + mDriveWidget = new DriveWidget; + mDriveWidget->setDisabled(true); + egoCtrlLayout->addWidget(mDriveWidget); + connect(mOverrideVehicleControl, SIGNAL(stateChanged(int)), this, SLOT(overrideVehicleControl(int))); + + vehicleLayout->addLayout(egoCtrlLayout); + + layout->addLayout(vehicleLayout); + + QFormLayout *carlaLayout = new QFormLayout; + + // row1 + QHBoxLayout *carlaRow1Layout = new QHBoxLayout; + + mScenarioSelection = new QComboBox(); + carlaRow1Layout->addWidget(mScenarioSelection, 10); + + mTriggerScenarioButton = new QPushButton("Execute"); + carlaRow1Layout->addWidget(mTriggerScenarioButton); + + mIndicatorWidget = new IndicatorWidget(); + carlaRow1Layout->addWidget(mIndicatorWidget); + connect(mTriggerScenarioButton, SIGNAL(released()), this, SLOT(executeScenario())); + + carlaLayout->addRow("Scenario Execution", carlaRow1Layout); + + QHBoxLayout *synchronous_layout = new QHBoxLayout; + QPixmap pixmap(":/icons/play.png"); + QIcon iconPlay(pixmap); + mPlayPauseButton = new QPushButton(iconPlay, ""); + synchronous_layout->addWidget(mPlayPauseButton); + connect(mPlayPauseButton, SIGNAL(released()), this, SLOT(carlaTogglePlayPause())); + + QPixmap pixmapStepOnce(":/icons/step_once.png"); + QIcon iconStepOnce(pixmapStepOnce); + mStepOnceButton = new QPushButton(iconStepOnce, ""); + connect(mStepOnceButton, SIGNAL(released()), this, SLOT(carlaStepOnce())); + + synchronous_layout->addWidget(mStepOnceButton); + carlaLayout->addRow("Carla Control", synchronous_layout); + + layout->addLayout(carlaLayout); + + setLayout(layout); + + QTimer *outputTimer = new QTimer(this); + connect(outputTimer, SIGNAL(timeout()), this, SLOT(sendVel())); + outputTimer->start(100); + + connect(mDriveWidget, SIGNAL(outputVelocity(float, float)), this, SLOT(setVel(float, float))); + mDriveWidget->setEnabled(false); + + setSimulationButtonStatus(false); + setScenarioRunnerStatus(false); + + // //initially set the camera + QTimer::singleShot(1000, this, SLOT(updateCameraPos())); +} + +void CarlaControlPanel::cameraPreRenderScene(Ogre::Camera *cam) +{ + double epsilon = 0.001; + if ((std::fabs(cam->getParentSceneNode()->getPosition().x - mCameraCurrentPosition.x) > epsilon) + || (std::fabs(cam->getParentSceneNode()->getPosition().y - mCameraCurrentPosition.y) > epsilon) + || (std::fabs(cam->getParentSceneNode()->getPosition().z - mCameraCurrentPosition.z) > epsilon) + || (std::fabs(cam->getParentSceneNode()->getOrientation().x - mCameraCurrentOrientation.x) > epsilon) + || (std::fabs(cam->getParentSceneNode()->getOrientation().y - mCameraCurrentOrientation.y) > epsilon) + || (std::fabs(cam->getParentSceneNode()->getOrientation().z - mCameraCurrentOrientation.z) > epsilon) + || (std::fabs(cam->getParentSceneNode()->getOrientation().w - mCameraCurrentOrientation.w) > epsilon)) + { + mCameraCurrentPosition = cam->getParentSceneNode()->getPosition(); + mCameraCurrentOrientation = cam->getParentSceneNode()->getOrientation(); + QTimer::singleShot(0, this, SLOT(updateCameraPos())); + } +} + +void CarlaControlPanel::updateCameraPos() +{ + auto frame = mViewController->subProp("Target Frame")->getValue(); + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = frame.toString().toStdString(); + pose.header.stamp = _node->now(); + pose.pose.position.x = mCameraCurrentPosition.x; + pose.pose.position.y = mCameraCurrentPosition.y; + pose.pose.position.z = mCameraCurrentPosition.z; + pose.pose.orientation.x = mCameraCurrentOrientation.x; + pose.pose.orientation.y = mCameraCurrentOrientation.y; + pose.pose.orientation.z = mCameraCurrentOrientation.z; + pose.pose.orientation.w = mCameraCurrentOrientation.w; + + mCameraPosePublisher->publish(pose); +} + +void CarlaControlPanel::onInitialize() +{ + currentViewControllerChanged(); + connect(getDisplayContext()->getViewManager(), SIGNAL(currentChanged()), this, SLOT(currentViewControllerChanged())); + _node = getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node(); + + // set up ros subscriber and publishers + mCarlaStatusSubscriber = _node->create_subscription("/carla/status", 1000, std::bind(&CarlaControlPanel::carlaStatusChanged, this, _1)); + mCarlaControlPublisher = _node->create_publisher("/carla/control", 10); + mEgoVehicleStatusSubscriber + = _node->create_subscription("/carla/ego_vehicle/vehicle_status", 1000, std::bind(&CarlaControlPanel::egoVehicleStatusChanged, this, _1)); + mEgoVehicleOdometrySubscriber + = _node->create_subscription("/carla/ego_vehicle/odometry", 1000, std::bind(&CarlaControlPanel::egoVehicleOdometryChanged, this, _1)); + + auto qos_latch_10 = rclcpp::QoS( rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, 10)); + qos_latch_10.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); + mCameraPosePublisher + = _node->create_publisher("/carla/ego_vehicle/spectator_pose", qos_latch_10); + + auto qos_latch_1 = rclcpp::QoS( rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, 1)); + qos_latch_1.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); + mEgoVehicleControlManualOverridePublisher + = _node->create_publisher("/carla/ego_vehicle/vehicle_control_manual_override", qos_latch_1); + + mExecuteScenarioClient + = _node->create_client("/scenario_runner/execute_scenario"); + mScenarioRunnerStatusSubscriber + = _node->create_subscription("/scenario_runner/status", 10, std::bind(&CarlaControlPanel::scenarioRunnerStatusChanged, this, _1)); + + mTwistPublisher = _node->create_publisher("/carla/ego_vehicle/twist", 1); + + mScenarioSubscriber + = _node->create_subscription("/carla/available_scenarios", 1, std::bind(&CarlaControlPanel::carlaScenariosChanged, this, _1)); +} + +void CarlaControlPanel::currentViewControllerChanged() +{ + mViewController + = dynamic_cast(getDisplayContext()->getViewManager()->getCurrent()); + if (!mViewController) + { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Invalid view controller!"); + return; + } + + auto camera = mViewController->getCamera(); + camera->addListener(this); +} + +void CarlaControlPanel::executeScenario() +{ + for (auto const &scenario : mCarlaScenarios->scenarios) + { + if (QString::fromStdString(scenario.name) == mScenarioSelection->currentText()) + { + auto request = std::make_shared(); + request->scenario = scenario; + // Check if service is available + if (!mExecuteScenarioClient->wait_for_service(std::chrono::seconds(1))) { + RCLCPP_WARN(rclcpp::get_logger("rclcpp"), "Failed to call service executeScenario1"); + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } + auto result = mExecuteScenarioClient->async_send_request(request); + break; + } + } +} + +void CarlaControlPanel::overrideVehicleControl(int state) +{ + std_msgs::msg::Bool boolMsg; + if (state == Qt::Checked) + { + boolMsg.data = true; + mDriveWidget->setEnabled(true); + } + else + { + boolMsg.data = false; + mDriveWidget->setEnabled(false); + } + mEgoVehicleControlManualOverridePublisher->publish(boolMsg); +} + +void CarlaControlPanel::scenarioRunnerStatusChanged( + const carla_ros_scenario_runner_types::msg::CarlaScenarioRunnerStatus::SharedPtr msg) +{ + if (msg->status == carla_ros_scenario_runner_types::msg::CarlaScenarioRunnerStatus::STOPPED) + { + mIndicatorWidget->setState(IndicatorWidget::State::Stopped); + } + else if (msg->status == carla_ros_scenario_runner_types::msg::CarlaScenarioRunnerStatus::STARTING) + { + mIndicatorWidget->setState(IndicatorWidget::State::Starting); + } + else if (msg->status == carla_ros_scenario_runner_types::msg::CarlaScenarioRunnerStatus::RUNNING) + { + mIndicatorWidget->setState(IndicatorWidget::State::Running); + } + else if (msg->status == carla_ros_scenario_runner_types::msg::CarlaScenarioRunnerStatus::SHUTTINGDOWN) + { + mIndicatorWidget->setState(IndicatorWidget::State::ShuttingDown); + } + else + { + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } +} + +void CarlaControlPanel::setScenarioRunnerStatus(bool active) +{ + mScenarioSelection->setEnabled(active); + mTriggerScenarioButton->setEnabled(active); + mIndicatorWidget->setEnabled(active); +} + +void CarlaControlPanel::carlaScenariosChanged(const carla_ros_scenario_runner_types::msg::CarlaScenarioList::SharedPtr msg) +{ + auto currentSelection = mScenarioSelection->currentText(); + mCarlaScenarios = msg; + mScenarioSelection->clear(); + int idx = 0; + for (auto const &scenario : msg->scenarios) + { + auto name = QString::fromStdString(scenario.name); + mScenarioSelection->addItem(name); + if (name == currentSelection) + { // switch to previously selected item + mScenarioSelection->setCurrentIndex(idx); + } + ++idx; + } + setScenarioRunnerStatus(mScenarioSelection->count() > 0); +} + +void CarlaControlPanel::egoVehicleStatusChanged(const carla_msgs::msg::CarlaEgoVehicleStatus::SharedPtr msg) +{ + mOverrideVehicleControl->setEnabled(true); + mSteerBar->setValue(msg->control.steer * 100); + mThrottleBar->setValue(msg->control.throttle * 100); + mBrakeBar->setValue(msg->control.brake * 100); + + std::stringstream speedStream; + speedStream << std::fixed << std::setprecision(2) << msg->velocity * 3.6; + mSpeedLabel->setText(speedStream.str().c_str()); +} + +void CarlaControlPanel::egoVehicleOdometryChanged(const nav_msgs::msg::Odometry::SharedPtr msg) +{ + std::stringstream posStream; + posStream << std::fixed << std::setprecision(2) << msg->pose.pose.position.x << ", " << msg->pose.pose.position.y; + mPosLabel->setText(posStream.str().c_str()); + + std::stringstream headingStream; + headingStream << std::fixed << std::setprecision(2) << tf2::getYaw(msg->pose.pose.orientation); + mHeadingLabel->setText(headingStream.str().c_str()); +} + +void CarlaControlPanel::setSimulationButtonStatus(bool active) +{ + if (active) + { + mPlayPauseButton->setDisabled(false); + mPlayPauseButton->setToolTip("Play/Pause the CARLA world."); + mStepOnceButton->setDisabled(false); + mStepOnceButton->setToolTip("Execute on tick within the CARLA world."); + } + else + { + mPlayPauseButton->setDisabled(true); + mPlayPauseButton->setToolTip("Disabled due to CARLA running in non-synchronous mode."); + mStepOnceButton->setDisabled(true); + mStepOnceButton->setToolTip("Disabled due to CARLA running in non-synchronous mode."); + } +} + +void CarlaControlPanel::carlaStatusChanged(const carla_msgs::msg::CarlaStatus::SharedPtr msg) +{ + mCarlaStatus = msg; + setSimulationButtonStatus(mCarlaStatus->synchronous_mode); + + if (mCarlaStatus->synchronous_mode) + { + if (mCarlaStatus->synchronous_mode_running) + { + QPixmap pixmap(":/icons/pause.png"); + QIcon iconPause(pixmap); + mPlayPauseButton->setIcon(iconPause); + } + else + { + QPixmap pixmap(":/icons/play.png"); + QIcon iconPlay(pixmap); + mPlayPauseButton->setIcon(iconPlay); + } + } +} + +void CarlaControlPanel::carlaStepOnce() +{ + carla_msgs::msg::CarlaControl ctrl; + ctrl.command = carla_msgs::msg::CarlaControl::STEP_ONCE; + mCarlaControlPublisher->publish(ctrl); +} + +void CarlaControlPanel::carlaTogglePlayPause() +{ + if (mCarlaStatus) + { + carla_msgs::msg::CarlaControl ctrl; + if (mCarlaStatus->synchronous_mode_running) + { + ctrl.command = carla_msgs::msg::CarlaControl::PAUSE; + } + else + { + ctrl.command = carla_msgs::msg::CarlaControl::PLAY; + } + mCarlaControlPublisher->publish(ctrl); + } +} + +void CarlaControlPanel::setVel(float linearVelocity, float angularVelocity) +{ + mLinearVelocity = linearVelocity; + mAngularVelocity = angularVelocity; +} + +void CarlaControlPanel::sendVel() +{ + if (rclcpp::ok() && mTwistPublisher && (mOverrideVehicleControl->checkState() == Qt::Checked)) + { + geometry_msgs::msg::Twist msg; + msg.linear.x = mLinearVelocity; + msg.linear.y = 0; + msg.linear.z = 0; + msg.angular.x = 0; + msg.angular.y = 0; + msg.angular.z = mAngularVelocity; + mTwistPublisher->publish(msg); + } +} + +} // end namespace rviz_carla_plugin + +#include +PLUGINLIB_EXPORT_CLASS(rviz_carla_plugin::CarlaControlPanel, rviz_common::Panel) diff --git a/rviz_carla_plugin/src/carla_control_panel_ROS2.h b/rviz_carla_plugin/src/carla_control_panel_ROS2.h new file mode 100644 index 00000000..4f544d0b --- /dev/null +++ b/rviz_carla_plugin/src/carla_control_panel_ROS2.h @@ -0,0 +1,112 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include "rclcpp/rclcpp.hpp" +#include +#include +#include +#include +#include +#include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp" +#include + +class QLineEdit; +class QPushButton; +class QProgressBar; +class QCheckBox; +class QComboBox; + +namespace rviz { +class ViewController; +class FramePositionTrackingViewController; +} + +namespace rviz_carla_plugin { + +class DriveWidget; +class IndicatorWidget; + +class CarlaControlPanel : public rviz_common::Panel, public Ogre::Camera::Listener +{ + Q_OBJECT +public: + CarlaControlPanel(QWidget *parent = 0); + +public Q_SLOTS: + void setVel(float linearVelocity, float angularVelocity); + +protected Q_SLOTS: + void sendVel(); + + void carlaStepOnce(); + void carlaTogglePlayPause(); + void overrideVehicleControl(int state); + void executeScenario(); + + void updateCameraPos(); + void currentViewControllerChanged(); + +protected: + virtual void cameraPreRenderScene(Ogre::Camera *cam) override; + + virtual void onInitialize() override; + void setSimulationButtonStatus(bool active); + void setScenarioRunnerStatus(bool active); + + void scenarioRunnerStatusChanged(const carla_ros_scenario_runner_types::msg::CarlaScenarioRunnerStatus::SharedPtr msg); + void carlaStatusChanged(const carla_msgs::msg::CarlaStatus::SharedPtr msg); + void egoVehicleStatusChanged(const carla_msgs::msg::CarlaEgoVehicleStatus::SharedPtr msg); + void egoVehicleOdometryChanged(const nav_msgs::msg::Odometry::SharedPtr msg); + void carlaScenariosChanged(const carla_ros_scenario_runner_types::msg::CarlaScenarioList::SharedPtr msg); + carla_msgs::msg::CarlaStatus::SharedPtr mCarlaStatus{nullptr}; + + rclcpp::Node::SharedPtr _node; + + DriveWidget *mDriveWidget; + QPushButton *mTriggerScenarioButton; + QPushButton *mPlayPauseButton; + QPushButton *mStepOnceButton; + QProgressBar *mThrottleBar; + QProgressBar *mBrakeBar; + QProgressBar *mSteerBar; + QLineEdit *mPosLabel; + QLineEdit *mSpeedLabel; + QLineEdit *mHeadingLabel; + QCheckBox *mOverrideVehicleControl; + QComboBox *mScenarioSelection; + IndicatorWidget *mIndicatorWidget; + rclcpp::Publisher::SharedPtr mTwistPublisher; + rclcpp::Publisher::SharedPtr mCarlaControlPublisher; + rclcpp::Publisher::SharedPtr mEgoVehicleControlManualOverridePublisher; + rclcpp::Subscription::SharedPtr mCarlaStatusSubscriber; + rclcpp::Subscription::SharedPtr mEgoVehicleStatusSubscriber; + rclcpp::Subscription::SharedPtr mEgoVehicleOdometrySubscriber; + rclcpp::Client::SharedPtr mExecuteScenarioClient; + rclcpp::Subscription::SharedPtr mScenarioSubscriber; + rclcpp::Subscription::SharedPtr mScenarioRunnerStatusSubscriber; + rclcpp::Publisher::SharedPtr mCameraPosePublisher; + + carla_ros_scenario_runner_types::msg::CarlaScenarioList::SharedPtr mCarlaScenarios; + + + float mLinearVelocity{0.0}; + float mAngularVelocity{0.0}; + bool mVehicleControlManualOverride{false}; + rviz_common::FramePositionTrackingViewController *mViewController{nullptr}; + Ogre::Vector3 mCameraCurrentPosition; + Ogre::Quaternion mCameraCurrentOrientation; +}; + +} // end namespace rviz_carla_plugin From d1c8ced9f85a07aacf9fa0570847be06b595cf3b Mon Sep 17 00:00:00 2001 From: Roosstef <43417803+Roosstef@users.noreply.github.com> Date: Wed, 28 Oct 2020 09:05:26 +0100 Subject: [PATCH 347/627] Update radar node to publish pc2 (#379) * Update radar node to publish pc2 * Update radar node to publish pc2 * Revert "Update radar node to publish pc2" This reverts commit 00d09b0c160646c51bc207b67c7623210d5931c6. * Update Whitespaces * Update one last whitespace * Change Topic name of PC2 * Update radar PC publisher to new communication pipeline. * Update whitespaces * Update CHANGELOG and README * Add radar pc test to ros_bridge_clinet.py Co-authored-by: Stefan Roos --- CHANGELOG.md | 1 + README.md | 5 ++-- .../src/carla_ros_bridge/radar.py | 26 ++++++++++++++++++- carla_ros_bridge/test/ros_bridge_client.py | 3 +++ 4 files changed, 32 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 08470728..76b41a28 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Add radar PointCloud2 publisher * Add DVS camera sensor * Fix rgb camera attributes * Add intensity value to point cloud message diff --git a/README.md b/README.md index 54b0c27e..e96d324d 100644 --- a/README.md +++ b/README.md @@ -202,9 +202,10 @@ Currently the following sensors are supported: ##### Radar -| Topic | Type | -| --------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------- | +| Topic | Type | +| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | | `/carla//radar//radar` | [carla_msgs.CarlaRadarMeasurement](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaRadarMeasurement.msg) | +| `/carla//radar//radar_points` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | ##### IMU diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 7971bea4..1d2e6418 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -12,6 +12,12 @@ import rospy +import numpy as np + +from sensor_msgs.msg import PointCloud2, PointField + +from sensor_msgs.point_cloud2 import create_cloud + from carla_msgs.msg import CarlaRadarMeasurement, CarlaRadarDetection from carla_ros_bridge.sensor import Sensor @@ -45,18 +51,30 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): "/radar", CarlaRadarMeasurement, queue_size=10) + + self.radar_pc_publisher = rospy.Publisher(self.get_topic_prefix() + + "/radar_points", + PointCloud2, + queue_size=10) self.listen() # pylint: disable=arguments-differ def sensor_data_updated(self, carla_radar_measurement): """ Function to transform the a received Radar measurement into a ROS message - :param carla_radar_measurement: carla Radar measurement object :type carla_radar_measurement: carla.RadarMeasurement """ radar_msg = CarlaRadarMeasurement() radar_msg.header = self.get_msg_header(timestamp=carla_radar_measurement.timestamp) + fields = [PointField('x', 0, PointField.FLOAT32, 1), + PointField('y', 4, PointField.FLOAT32, 1), + PointField('z', 8, PointField.FLOAT32, 1), + PointField('Range', 12, PointField.FLOAT32, 1), + PointField('Velocity', 16, PointField.FLOAT32, 1), + PointField('AzimuthAngle', 20, PointField.FLOAT32, 1), + PointField('ElevationAngle', 28, PointField.FLOAT32, 1)] + points = [] for detection in carla_radar_measurement: radar_detection = CarlaRadarDetection() radar_detection.altitude = detection.altitude @@ -64,4 +82,10 @@ def sensor_data_updated(self, carla_radar_measurement): radar_detection.depth = detection.depth radar_detection.velocity = detection.velocity radar_msg.detections.append(radar_detection) + points.append([detection.depth * np.cos(-detection.azimuth) * np.cos(detection.altitude), + detection.depth * np.sin(-detection.azimuth) * np.cos(detection.altitude), + detection.depth * np.sin(detection.altitude), + detection.depth, detection.velocity, detection.azimuth, detection.altitude]) + radar_msg_pc = create_cloud(radar_msg.header, fields, points) self.radar_publisher.publish(radar_msg) + self.radar_pc_publisher.publish(radar_msg_pc) \ No newline at end of file diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 2ca4104c..93dde3ac 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -191,7 +191,10 @@ def test_radar(self): rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( "/carla/ego_vehicle/radar/front/radar", CarlaRadarMeasurement, timeout=TIMEOUT) + msg_points = rospy.wait_for_message( + "/carla/ego_vehicle/radar/front/radar_points", PointCloud2, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/radar/front") + self.assertEqual(msg_points.header.frame_id, "ego_vehicle/radar/front") def test_ego_vehicle_objects(self): """ From c8be729f1cb6b3eb1a463dcc2d21c35ae91dd6a8 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 28 Oct 2020 09:24:39 +0100 Subject: [PATCH 348/627] Remove publishing of CarlaRadar* datatypes --- README.md | 1 - carla_msgs | 2 +- carla_ros_bridge/src/carla_ros_bridge/radar.py | 18 +----------------- carla_ros_bridge/test/ros_bridge_client.py | 5 +---- 4 files changed, 3 insertions(+), 23 deletions(-) diff --git a/README.md b/README.md index e96d324d..75f38828 100644 --- a/README.md +++ b/README.md @@ -204,7 +204,6 @@ Currently the following sensors are supported: | Topic | Type | | -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla//radar//radar` | [carla_msgs.CarlaRadarMeasurement](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaRadarMeasurement.msg) | | `/carla//radar//radar_points` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | ##### IMU diff --git a/carla_msgs b/carla_msgs index c89458b3..7c33619b 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit c89458b34aefbe7e12cefe3241c3b48f4a9b35d7 +Subproject commit 7c33619b535131a46723bc2979abd2c4a6bfc720 diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 1d2e6418..93da1260 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -18,8 +18,6 @@ from sensor_msgs.point_cloud2 import create_cloud -from carla_msgs.msg import CarlaRadarMeasurement, CarlaRadarDetection - from carla_ros_bridge.sensor import Sensor @@ -48,11 +46,6 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): prefix="radar/" + carla_actor.attributes.get('role_name')) self.radar_publisher = rospy.Publisher(self.get_topic_prefix() + - "/radar", - CarlaRadarMeasurement, - queue_size=10) - - self.radar_pc_publisher = rospy.Publisher(self.get_topic_prefix() + "/radar_points", PointCloud2, queue_size=10) @@ -65,8 +58,6 @@ def sensor_data_updated(self, carla_radar_measurement): :param carla_radar_measurement: carla Radar measurement object :type carla_radar_measurement: carla.RadarMeasurement """ - radar_msg = CarlaRadarMeasurement() - radar_msg.header = self.get_msg_header(timestamp=carla_radar_measurement.timestamp) fields = [PointField('x', 0, PointField.FLOAT32, 1), PointField('y', 4, PointField.FLOAT32, 1), PointField('z', 8, PointField.FLOAT32, 1), @@ -76,16 +67,9 @@ def sensor_data_updated(self, carla_radar_measurement): PointField('ElevationAngle', 28, PointField.FLOAT32, 1)] points = [] for detection in carla_radar_measurement: - radar_detection = CarlaRadarDetection() - radar_detection.altitude = detection.altitude - radar_detection.azimuth = detection.azimuth - radar_detection.depth = detection.depth - radar_detection.velocity = detection.velocity - radar_msg.detections.append(radar_detection) points.append([detection.depth * np.cos(-detection.azimuth) * np.cos(detection.altitude), detection.depth * np.sin(-detection.azimuth) * np.cos(detection.altitude), detection.depth * np.sin(detection.altitude), detection.depth, detection.velocity, detection.azimuth, detection.altitude]) - radar_msg_pc = create_cloud(radar_msg.header, fields, points) + radar_msg = create_cloud(self.get_msg_header(timestamp=carla_radar_measurement.timestamp), fields, points) self.radar_publisher.publish(radar_msg) - self.radar_pc_publisher.publish(radar_msg_pc) \ No newline at end of file diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 93dde3ac..889f3589 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -23,7 +23,7 @@ from visualization_msgs.msg import Marker from carla_msgs.msg import (CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, CarlaActorList, CarlaTrafficLightStatusList, - CarlaTrafficLightInfoList, CarlaRadarMeasurement) + CarlaTrafficLightInfoList) PKG = 'test_roslaunch' TIMEOUT = 20 @@ -190,11 +190,8 @@ def test_radar(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/radar/front/radar", CarlaRadarMeasurement, timeout=TIMEOUT) - msg_points = rospy.wait_for_message( "/carla/ego_vehicle/radar/front/radar_points", PointCloud2, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/radar/front") - self.assertEqual(msg_points.header.frame_id, "ego_vehicle/radar/front") def test_ego_vehicle_objects(self): """ From 789193f46f0017932d1df51f0d4b254a0d240fcd Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 28 Oct 2020 09:41:21 +0100 Subject: [PATCH 349/627] Update sensors.json files --- carla_ad_demo/config/sensors.json | 62 ------------------- .../launch/carla_ad_demo_with_scenario.launch | 2 +- carla_ego_vehicle/config/sensors.json | 3 +- 3 files changed, 3 insertions(+), 64 deletions(-) delete mode 100644 carla_ad_demo/config/sensors.json diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json deleted file mode 100644 index a4a3f14f..00000000 --- a/carla_ad_demo/config/sensors.json +++ /dev/null @@ -1,62 +0,0 @@ -{ - "sensors": [ - { - "type": "sensor.camera.rgb", - "id": "view", - "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, - "image_size_x": 800, - "image_size_y": 600, - "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 - }, - { - "type": "sensor.lidar.ray_cast", - "id": "lidar1", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, - "rotation_frequency": 20, - "sensor_tick": 0.05 - } - ] -} diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index 6d258869..bd489866 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -41,7 +41,7 @@ - + diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 225895cb..66c8df6e 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -102,7 +102,8 @@ "upper_fov": 2.0, "lower_fov": -26.8, "rotation_frequency": 20, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "noise_stddev": 0.0 }, { "type": "sensor.other.radar", From b3fbb52afa169fa17b997215d9608faa4678e793 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 28 Oct 2020 09:44:58 +0100 Subject: [PATCH 350/627] Update changelog --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 76b41a28..e29ff71c 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Remove sensors.json from carla_ad_demo. Use example from carla_ego_vehicle instead * Add radar PointCloud2 publisher * Add DVS camera sensor * Fix rgb camera attributes From c7ce3425e6927f1ebd0b8a5cc91f351a68ca350f Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 28 Oct 2020 13:20:27 +0100 Subject: [PATCH 351/627] update sensor configuration file --- carla_ad_demo/launch/carla_ad_demo.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 7e6c2581..ce4ad9fe 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -42,7 +42,7 @@ - + From 323436c36b4e17aa3e5083dd52a2d890f5a0e0c0 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 28 Oct 2020 13:37:07 +0100 Subject: [PATCH 352/627] Update submodule, code formatting, changelog --- CHANGELOG.md | 1 + carla_msgs | 2 +- .../src/carla_ros_bridge/camera.py | 8 +++--- .../src/carla_ros_bridge/lidar.py | 8 +++--- .../src/carla_ros_bridge/radar.py | 28 ++++++++++--------- 5 files changed, 25 insertions(+), 22 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index e29ff71c..64e83549 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Remove CarlaRadarMeasurement message publishing (radar data is published as PointCloud2 only) * Remove sensors.json from carla_ad_demo. Use example from carla_ego_vehicle instead * Add radar PointCloud2 publisher * Add DVS camera sensor diff --git a/carla_msgs b/carla_msgs index 7c33619b..cbb02a44 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 7c33619b535131a46723bc2979abd2c4a6bfc720 +Subproject commit cbb02a44638df43236c12be169c3a19a87bdddc8 diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index f3bbfade..600943de 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -389,10 +389,10 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # :type prefix: string """ super(DVSCamera, self).__init__(carla_actor=carla_actor, - parent=parent, - node=node, - synchronous_mode=synchronous_mode, - prefix='camera/dvs/' + carla_actor.attributes.get('role_name')) + parent=parent, + node=node, + synchronous_mode=synchronous_mode, + prefix='camera/dvs/' + carla_actor.attributes.get('role_name')) self._dvs_events = None self.dvs_camera_publisher = rospy.Publisher(self.get_topic_prefix() + diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 9423578e..d5ee9a29 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -94,10 +94,10 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :type node: carla_ros_bridge.CarlaRosBridge """ super(SemanticLidar, self).__init__(carla_actor=carla_actor, - parent=parent, - node=node, - synchronous_mode=synchronous_mode, - prefix='semantic_lidar/' + carla_actor.attributes.get('role_name')) + parent=parent, + node=node, + synchronous_mode=synchronous_mode, + prefix='semantic_lidar/' + carla_actor.attributes.get('role_name')) self.semantic_lidar_publisher = rospy.Publisher( self.get_topic_prefix() + "/point_cloud", diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 93da1260..00320166 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -46,9 +46,9 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): prefix="radar/" + carla_actor.attributes.get('role_name')) self.radar_publisher = rospy.Publisher(self.get_topic_prefix() + - "/radar_points", - PointCloud2, - queue_size=10) + "/radar_points", + PointCloud2, + queue_size=10) self.listen() # pylint: disable=arguments-differ @@ -59,17 +59,19 @@ def sensor_data_updated(self, carla_radar_measurement): :type carla_radar_measurement: carla.RadarMeasurement """ fields = [PointField('x', 0, PointField.FLOAT32, 1), - PointField('y', 4, PointField.FLOAT32, 1), - PointField('z', 8, PointField.FLOAT32, 1), - PointField('Range', 12, PointField.FLOAT32, 1), - PointField('Velocity', 16, PointField.FLOAT32, 1), - PointField('AzimuthAngle', 20, PointField.FLOAT32, 1), - PointField('ElevationAngle', 28, PointField.FLOAT32, 1)] + PointField('y', 4, PointField.FLOAT32, 1), + PointField('z', 8, PointField.FLOAT32, 1), + PointField('Range', 12, PointField.FLOAT32, 1), + PointField('Velocity', 16, PointField.FLOAT32, 1), + PointField('AzimuthAngle', 20, PointField.FLOAT32, 1), + PointField('ElevationAngle', 28, PointField.FLOAT32, 1)] points = [] for detection in carla_radar_measurement: points.append([detection.depth * np.cos(-detection.azimuth) * np.cos(detection.altitude), - detection.depth * np.sin(-detection.azimuth) * np.cos(detection.altitude), - detection.depth * np.sin(detection.altitude), - detection.depth, detection.velocity, detection.azimuth, detection.altitude]) - radar_msg = create_cloud(self.get_msg_header(timestamp=carla_radar_measurement.timestamp), fields, points) + detection.depth * np.sin(-detection.azimuth) * + np.cos(detection.altitude), + detection.depth * np.sin(detection.altitude), + detection.depth, detection.velocity, detection.azimuth, detection.altitude]) + radar_msg = create_cloud(self.get_msg_header( + timestamp=carla_radar_measurement.timestamp), fields, points) self.radar_publisher.publish(radar_msg) From 0e685add7f1ea1d164895ec6ef2833938c318b08 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 28 Oct 2020 17:15:36 +0100 Subject: [PATCH 353/627] Code format --- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 2 ++ .../carla_spectator_camera.py | 6 +++--- pcl_recorder/CMakeLists.txt | 5 +---- .../src/rqt_carla_control/rqt_carla_control.py | 14 ++++++-------- 4 files changed, 12 insertions(+), 15 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 9a8ef5cd..c8f3148e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -180,6 +180,8 @@ def sensor_data_updated(self, carla_lidar_measurement): self.semantic_lidar_publisher.publish(point_cloud_msg) # http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html + + def _get_struct_fmt(is_bigendian, fields, field_names=None): fmt = '>' if is_bigendian else '<' diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 41883e07..d09f92a3 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -11,6 +11,7 @@ to /carla//spectator_position. """ # pylint: disable=import-error +import carla import sys import math from geometry_msgs.msg import PoseStamped @@ -28,7 +29,6 @@ if ROS_VERSION == 2: import rclpy -import carla # ============================================================================== # -- CarlaSpectatorCamera ------------------------------------------------------------ @@ -60,7 +60,7 @@ def __init__(self): self.camera_actor = None self.ego_vehicle = None self.create_subscriber(PoseStamped, - "/carla/{}/spectator_pose".format(self.role_name), self.pose_received) + "/carla/{}/spectator_pose".format(self.role_name), self.pose_received) def pose_received(self, pose): """ @@ -166,7 +166,7 @@ def run(self): self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, timeout=10.0, - qos_profile=QoSProfile(depth=10, durability=True)) + qos_profile=QoSProfile(depth=10, durability=True)) except ROSException: self.logerr("Error while waiting for world info!") sys.exit(1) diff --git a/pcl_recorder/CMakeLists.txt b/pcl_recorder/CMakeLists.txt index 8dd8ea04..7abd5472 100644 --- a/pcl_recorder/CMakeLists.txt +++ b/pcl_recorder/CMakeLists.txt @@ -52,10 +52,7 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(tf2_ros REQUIRED) find_package(pcl_conversions REQUIRED) - find_package( - Boost - COMPONENTS system - REQUIRED) + find_package(Boost COMPONENTS system REQUIRED) find_package(PCL REQUIRED COMPONENTS common io) include_directories(include ${PCL_INCLUDE_DIRS}) diff --git a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py index 9e199b65..c582ec64 100644 --- a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py +++ b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py @@ -8,6 +8,12 @@ """ RQT Plugin to control CARLA """ +from carla_msgs.msg import CarlaControl, CarlaStatus # pylint: disable=import-error +from python_qt_binding.QtGui import QPixmap, QIcon # pylint: disable=no-name-in-module, import-error +from python_qt_binding.QtWidgets import QWidget # pylint: disable=no-name-in-module, import-error +from python_qt_binding import loadUi # pylint: disable=import-error +from qt_gui.plugin import Plugin # pylint: disable=import-error +from ros_compatibility import CompatibleNode, QoSProfile import os ROS_VERSION = int(os.environ['ROS_VERSION']) @@ -17,14 +23,6 @@ from rclpy.callback_groups import ReentrantCallbackGroup from ament_index_python.packages import get_package_share_directory import threading -from ros_compatibility import CompatibleNode, QoSProfile - -from qt_gui.plugin import Plugin # pylint: disable=import-error -from python_qt_binding import loadUi # pylint: disable=import-error -from python_qt_binding.QtWidgets import QWidget # pylint: disable=no-name-in-module, import-error -from python_qt_binding.QtGui import QPixmap, QIcon # pylint: disable=no-name-in-module, import-error - -from carla_msgs.msg import CarlaControl, CarlaStatus # pylint: disable=import-error class CarlaControlPlugin(Plugin): From f213384b5d450c8787822b9473eb284ca9c9bdab Mon Sep 17 00:00:00 2001 From: jbmag Date: Thu, 29 Oct 2020 09:54:28 +0100 Subject: [PATCH 354/627] fix after master merge --- carla_ad_demo/config/carla_ad_demo_ros2.rviz | 30 ++++++++++++++ carla_ad_demo/launch/carla_ad_demo.launch.py | 2 +- .../carla_ad_demo_with_scenario.launch.py | 2 +- carla_ad_demo/setup.py | 2 +- .../src/carla_ros_bridge/bridge.py | 14 +++++-- .../src/carla_ros_bridge/camera.py | 7 ++-- .../src/carla_ros_bridge/lidar.py | 5 +-- .../src/carla_ros_bridge/radar.py | 40 ++++++++++++++++++- 8 files changed, 88 insertions(+), 14 deletions(-) diff --git a/carla_ad_demo/config/carla_ad_demo_ros2.rviz b/carla_ad_demo/config/carla_ad_demo_ros2.rviz index eefb8f34..1b457181 100644 --- a/carla_ad_demo/config/carla_ad_demo_ros2.rviz +++ b/carla_ad_demo/config/carla_ad_demo_ros2.rviz @@ -88,6 +88,36 @@ Visualization Manager: Path: true Value: true Zoom Factor: 1 + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /carla/ego_vehicle/lidar/lidar1/point_cloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true - Class: rviz_default_plugins/Marker Enabled: true Topic: /carla/marker diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 96466e96..f46b104c 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -87,7 +87,7 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'), - 'sensor_definition_file': get_package_share_directory('carla_ad_demo') + '/config/sensors.json', + 'sensor_definition_file': get_package_share_directory('carla_ego_vehicle') + '/config/sensors.json', 'role_name': launch.substitutions.LaunchConfiguration('role_name'), 'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point') }.items() diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index 0d8bc0ef..4fca23d7 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -116,7 +116,7 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'), - 'sensor_definition_file': get_package_share_directory('carla_ad_demo') + '/config/sensors.json', + 'sensor_definition_file': get_package_share_directory('carla_ego_vehicle') + '/config/sensors.json', 'role_name': launch.substitutions.LaunchConfiguration('role_name') }.items() ), diff --git a/carla_ad_demo/setup.py b/carla_ad_demo/setup.py index 810ba194..b2bdad70 100644 --- a/carla_ad_demo/setup.py +++ b/carla_ad_demo/setup.py @@ -27,7 +27,7 @@ ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ('share/' + package_name + '/config', - ['config/sensors.json', 'config/FollowLeadingVehicle.xosc', 'config/carla_ad_demo_ros2.rviz']), + ['config/FollowLeadingVehicle.xosc', 'config/carla_ad_demo_ros2.rviz']), (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index de341150..a5b047e9 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -24,6 +24,9 @@ from threading import Thread, Lock, Event import pkg_resources +from tf2_msgs.msg import TFMessage +from visualization_msgs.msg import Marker + import carla @@ -50,6 +53,14 @@ from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters # pylint: disable=import-error +from ros_compatibility import ( + CompatibleNode, + ros_ok, + destroy_subscription, + ros_shutdown, + ros_timestamp, + QoSProfile, + latch_on) ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -468,9 +479,6 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m elif carla_actor.type_id.endswith("sensor.lidar.ray_cast_semantic"): actor = SemanticLidar(carla_actor, parent, self, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.lidar"): - actor = Lidar(carla_actor, parent, self, - self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): actor = Radar(carla_actor, parent, self, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index a3eba85b..1f18610a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -390,10 +390,9 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # prefix='camera/dvs/' + carla_actor.attributes.get('role_name')) self._dvs_events = None - self.dvs_camera_publisher = rospy.Publisher(self.get_topic_prefix() + - '/events', - PointCloud2, - queue_size=10) + self.dvs_camera_publisher = node.new_publisher( + PointCloud2, + self.get_topic_prefix() + '/events') self.listen() diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index c8f3148e..31dc0fb7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -139,10 +139,9 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): synchronous_mode=synchronous_mode, prefix='semantic_lidar/' + carla_actor.attributes.get('role_name')) - self.semantic_lidar_publisher = rospy.Publisher( - self.get_topic_prefix() + "/point_cloud", + self.semantic_lidar_publisher = node.new_publisher( PointCloud2, - queue_size=10) + self.get_topic_prefix() + "/point_cloud") self.listen() # pylint: disable=arguments-differ diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 84adca2e..a8d8c6c4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -12,7 +12,7 @@ from sensor_msgs.msg import PointCloud2, PointField -from sensor_msgs.point_cloud2 import create_cloud +# from sensor_msgs.point_cloud2 import create_cloud from carla_ros_bridge.sensor import Sensor @@ -68,3 +68,41 @@ def sensor_data_updated(self, carla_radar_measurement): radar_msg = create_cloud(self.get_msg_header( timestamp=carla_radar_measurement.timestamp), fields, points) self.radar_publisher.publish(radar_msg) + + +# https://github.com/ros/common_msgs/blob/noetic-devel/sensor_msgs/src/sensor_msgs/point_cloud2.p + +def create_cloud(header, fields, points): + """ + Create a L{sensor_msgs.msg.PointCloud2} message. + @param header: The point cloud header. + @type header: L{std_msgs.msg.Header} + @param fields: The point cloud fields. + @type fields: iterable of L{sensor_msgs.msg.PointField} + @param points: The point cloud points. + @type points: list of iterables, i.e. one iterable for each point, with the + elements of each iterable being the values of the fields for + that point (in the same order as the fields parameter) + @return: The point cloud. + @rtype: L{sensor_msgs.msg.PointCloud2} + """ + + cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) + + buff = ctypes.create_string_buffer(cloud_struct.size * len(points)) + + point_step, pack_into = cloud_struct.size, cloud_struct.pack_into + offset = 0 + for p in points: + pack_into(buff, offset, *p) + offset += point_step + + return PointCloud2(header=header, + height=1, + width=len(points), + is_dense=False, + is_bigendian=False, + fields=fields, + point_step=cloud_struct.size, + row_step=cloud_struct.size * len(points), + data=buff.raw) \ No newline at end of file From db3e403bfdcfa159bdb4237058a47806c2d58e05 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 29 Oct 2020 10:25:59 +0100 Subject: [PATCH 355/627] Fixes after merge --- .../carla_ego_vehicle/carla_ego_vehicle.py | 5 ++- .../src/carla_ros_bridge/radar.py | 33 +++++++++++++++++-- 2 files changed, 35 insertions(+), 3 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index b9be0108..cb741c33 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -218,8 +218,11 @@ def setup_sensors(self, sensors): bp_library = self.world.get_blueprint_library() sensor_names = [] for sensor_spec in sensors: + print(sensor_spec) try: - sensor_name = str(sensor_spec['type']) + "/" + str(sensor_spec['id']) + sensor_type = str(sensor_spec.pop("type")) + sensor_id = str(sensor_spec.pop("id")) + sensor_name = sensor_type + "/" + sensor_id if sensor_name in sensor_names: self.logfatal( "Sensor rolename '{}' is only allowed to be used once.".format( diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index a8d8c6c4..f02c4405 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -12,8 +12,17 @@ from sensor_msgs.msg import PointCloud2, PointField +import sys +import ctypes +import os +import struct +import numpy as np + # from sensor_msgs.point_cloud2 import create_cloud +_DATATYPES = {} +_DATATYPES[PointField.FLOAT32] = ('f', 4) + from carla_ros_bridge.sensor import Sensor @@ -40,7 +49,7 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, sensor_name="Rad prefix="radar/" + carla_actor.attributes.get('role_name'), sensor_name=sensor_name) self.radar_publisher = node.new_publisher( - CarlaRadarMeasurement, self.get_topic_prefix() + "/radar") + PointCloud2, self.get_topic_prefix() + "/radar") self.listen() # pylint: disable=arguments-differ @@ -70,6 +79,26 @@ def sensor_data_updated(self, carla_radar_measurement): self.radar_publisher.publish(radar_msg) +# http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html + +def _get_struct_fmt(is_bigendian, fields, field_names=None): + fmt = '>' if is_bigendian else '<' + + offset = 0 + for field in (f for f in sorted(fields, key=lambda f: f.offset) + if field_names is None or f.name in field_names): + if offset < field.offset: + fmt += 'x' * (field.offset - offset) + offset = field.offset + if field.datatype not in _DATATYPES: + print('Skipping unknown PointField datatype [%d]' % field.datatype) + else: + datatype_fmt, datatype_length = _DATATYPES[field.datatype] + fmt += field.count * datatype_fmt + offset += field.count * datatype_length + + return fmt + # https://github.com/ros/common_msgs/blob/noetic-devel/sensor_msgs/src/sensor_msgs/point_cloud2.p def create_cloud(header, fields, points): @@ -105,4 +134,4 @@ def create_cloud(header, fields, points): fields=fields, point_step=cloud_struct.size, row_step=cloud_struct.size * len(points), - data=buff.raw) \ No newline at end of file + data=buff.raw) From 5aff2eaa070b9909bf42db13813050eaafd96ecc Mon Sep 17 00:00:00 2001 From: jbmag Date: Thu, 29 Oct 2020 13:53:16 +0100 Subject: [PATCH 356/627] fix lidar and radar after merge --- .../src/carla_ros_bridge/bridge.py | 15 ++-- .../src/carla_ros_bridge/camera.py | 4 +- .../src/carla_ros_bridge/lidar.py | 76 ++--------------- .../src/carla_ros_bridge/radar.py | 84 ++----------------- .../src/carla_ros_bridge/sensor.py | 67 ++++++++++++++- pcl_recorder/CMakeLists.txt | 5 +- 6 files changed, 98 insertions(+), 153 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index a5b047e9..0740a9f1 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -39,6 +39,7 @@ from carla_ros_bridge.traffic import Traffic, TrafficLight from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.lidar import Lidar +from carla_ros_bridge.lidar import SemanticLidar from carla_ros_bridge.radar import Radar from carla_ros_bridge.gnss import Gnss from carla_ros_bridge.imu import ImuSensor @@ -54,13 +55,13 @@ from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters # pylint: disable=import-error from ros_compatibility import ( - CompatibleNode, - ros_ok, - destroy_subscription, - ros_shutdown, - ros_timestamp, - QoSProfile, - latch_on) + CompatibleNode, + ros_ok, + destroy_subscription, + ros_shutdown, + ros_timestamp, + QoSProfile, + latch_on) ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 1f18610a..b5fc0cfd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -391,8 +391,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # self._dvs_events = None self.dvs_camera_publisher = node.new_publisher( - PointCloud2, - self.get_topic_prefix() + '/events') + PointCloud2, + self.get_topic_prefix() + '/events') self.listen() diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 31dc0fb7..f5b51a93 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -19,20 +19,10 @@ import numpy from sensor_msgs.msg import PointCloud2, PointField # pylint: disable=import-error -import carla_common.transforms as trans -from carla_ros_bridge.sensor import Sensor +from carla_ros_bridge.sensor import Sensor, create_cloud from ros_compatibility import quaternion_from_euler, euler_from_quaternion -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION == 1: - # pylint: disable=import-error,ungrouped-imports - from sensor_msgs.point_cloud2 import create_cloud - -_DATATYPES = {} -_DATATYPES[PointField.FLOAT32] = ('f', 4) - class Lidar(Sensor): """ @@ -85,34 +75,7 @@ def sensor_data_updated(self, carla_lidar_measurement): PointField(name='intensity', offset=12, datatype=PointField.FLOAT32, count=1) ] - if ROS_VERSION == 1: - point_cloud_msg = create_cloud(header, fields, lidar_data) - - # -- taken from - # http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html - elif ROS_VERSION == 2: - cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) - - buff = ctypes.create_string_buffer(cloud_struct.size * len(lidar_data)) - - point_step, pack_into = cloud_struct.size, cloud_struct.pack_into - offset = 0 - for p in lidar_data: - pack_into(buff, offset, *p) - offset += point_step - - point_cloud_msg = PointCloud2(header=header, - height=1, - width=len(lidar_data), - is_dense=False, - is_bigendian=False, - fields=fields, - point_step=cloud_struct.size, - row_step=cloud_struct.size * len(lidar_data), - data=buff.raw) - - # -- - + point_cloud_msg = create_cloud(header, fields, lidar_data) self.lidar_publisher.publish(point_cloud_msg) @@ -154,15 +117,15 @@ def sensor_data_updated(self, carla_lidar_measurement): """ header = self.get_msg_header() fields = [ - PointField('x', 0, PointField.FLOAT32, 1), - PointField('y', 4, PointField.FLOAT32, 1), - PointField('z', 8, PointField.FLOAT32, 1), - PointField('CosAngle', 12, PointField.FLOAT32, 1), - PointField('ObjIdx', 16, PointField.UINT32, 1), - PointField('ObjTag', 20, PointField.UINT32, 1), + PointField(name='x', offset=0, datatype=PointField.FLOAT32, count=1), + PointField(name='y', offset=4, datatype=PointField.FLOAT32, count=1), + PointField(name='z', offset=8, datatype=PointField.FLOAT32, count=1), + PointField(name='CosAngle', offset=12, datatype=PointField.FLOAT32, count=1), + PointField(name='ObjIdx', offset=16, datatype=PointField.UINT32, count=1), + PointField(name='ObjTag', offset=20, datatype=PointField.UINT32, count=1) ] - lidar_data = numpy.fromstring(carla_lidar_measurement.raw_data, + lidar_data = numpy.fromstring(bytes(carla_lidar_measurement.raw_data), dtype=numpy.dtype([ ('x', numpy.float32), ('y', numpy.float32), @@ -177,24 +140,3 @@ def sensor_data_updated(self, carla_lidar_measurement): lidar_data['y'] *= -1 point_cloud_msg = create_cloud(header, fields, lidar_data.tolist()) self.semantic_lidar_publisher.publish(point_cloud_msg) - -# http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html - - -def _get_struct_fmt(is_bigendian, fields, field_names=None): - fmt = '>' if is_bigendian else '<' - - offset = 0 - for field in (f for f in sorted(fields, key=lambda f: f.offset) - if field_names is None or f.name in field_names): - if offset < field.offset: - fmt += 'x' * (field.offset - offset) - offset = field.offset - if field.datatype not in _DATATYPES: - print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr) - else: - datatype_fmt, datatype_length = _DATATYPES[field.datatype] - fmt += field.count * datatype_fmt - offset += field.count * datatype_length - - return fmt diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index f02c4405..030f1cfb 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -12,18 +12,9 @@ from sensor_msgs.msg import PointCloud2, PointField -import sys -import ctypes -import os -import struct import numpy as np -# from sensor_msgs.point_cloud2 import create_cloud - -_DATATYPES = {} -_DATATYPES[PointField.FLOAT32] = ('f', 4) - -from carla_ros_bridge.sensor import Sensor +from carla_ros_bridge.sensor import Sensor, create_cloud class Radar(Sensor): @@ -60,13 +51,14 @@ def sensor_data_updated(self, carla_radar_measurement): :param carla_radar_measurement: carla Radar measurement object :type carla_radar_measurement: carla.RadarMeasurement """ - fields = [PointField('x', 0, PointField.FLOAT32, 1), - PointField('y', 4, PointField.FLOAT32, 1), - PointField('z', 8, PointField.FLOAT32, 1), - PointField('Range', 12, PointField.FLOAT32, 1), - PointField('Velocity', 16, PointField.FLOAT32, 1), - PointField('AzimuthAngle', 20, PointField.FLOAT32, 1), - PointField('ElevationAngle', 28, PointField.FLOAT32, 1)] + fields = [ + PointField(name='x', offset=0, datatype=PointField.FLOAT32, count=1), + PointField(name='y', offset=4, datatype=PointField.FLOAT32, count=1), + PointField(name='z', offset=8, datatype=PointField.FLOAT32, count=1), + PointField(name='Range', offset=12, datatype=PointField.FLOAT32, count=1), + PointField(name='Velocity', offset=16, datatype=PointField.FLOAT32, count=1), + PointField(name='AzimuthAngle', offset=20, datatype=PointField.FLOAT32, count=1), + PointField(name='ElevationAngle', offset=28, datatype=PointField.FLOAT32, count=1)] points = [] for detection in carla_radar_measurement: points.append([detection.depth * np.cos(-detection.azimuth) * np.cos(detection.altitude), @@ -77,61 +69,3 @@ def sensor_data_updated(self, carla_radar_measurement): radar_msg = create_cloud(self.get_msg_header( timestamp=carla_radar_measurement.timestamp), fields, points) self.radar_publisher.publish(radar_msg) - - -# http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html - -def _get_struct_fmt(is_bigendian, fields, field_names=None): - fmt = '>' if is_bigendian else '<' - - offset = 0 - for field in (f for f in sorted(fields, key=lambda f: f.offset) - if field_names is None or f.name in field_names): - if offset < field.offset: - fmt += 'x' * (field.offset - offset) - offset = field.offset - if field.datatype not in _DATATYPES: - print('Skipping unknown PointField datatype [%d]' % field.datatype) - else: - datatype_fmt, datatype_length = _DATATYPES[field.datatype] - fmt += field.count * datatype_fmt - offset += field.count * datatype_length - - return fmt - -# https://github.com/ros/common_msgs/blob/noetic-devel/sensor_msgs/src/sensor_msgs/point_cloud2.p - -def create_cloud(header, fields, points): - """ - Create a L{sensor_msgs.msg.PointCloud2} message. - @param header: The point cloud header. - @type header: L{std_msgs.msg.Header} - @param fields: The point cloud fields. - @type fields: iterable of L{sensor_msgs.msg.PointField} - @param points: The point cloud points. - @type points: list of iterables, i.e. one iterable for each point, with the - elements of each iterable being the values of the fields for - that point (in the same order as the fields parameter) - @return: The point cloud. - @rtype: L{sensor_msgs.msg.PointCloud2} - """ - - cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) - - buff = ctypes.create_string_buffer(cloud_struct.size * len(points)) - - point_step, pack_into = cloud_struct.size, cloud_struct.pack_into - offset = 0 - for p in points: - pack_into(buff, offset, *p) - offset += point_step - - return PointCloud2(header=header, - height=1, - width=len(points), - is_dense=False, - is_bigendian=False, - fields=fields, - point_step=cloud_struct.size, - row_step=cloud_struct.size * len(points), - data=buff.raw) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 93cd5093..d3fed010 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -8,8 +8,11 @@ """ Classes to handle Carla sensors """ - +from __future__ import print_function +import ctypes import os +import struct +import sys from abc import abstractmethod import carla_common.transforms as trans @@ -28,6 +31,11 @@ if ROS_VERSION not in (1, 2): raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +from sensor_msgs.msg import PointCloud2, PointField +_DATATYPES = {} +_DATATYPES[PointField.FLOAT32] = ('f', 4) +_DATATYPES[PointField.UINT32] = ('I', 4) + class Sensor(Actor): """ @@ -186,3 +194,60 @@ def update(self, frame, timestamp): self._update_synchronous_sensor(frame, timestamp) Actor.update(self, frame, timestamp) + + +# http://docs.ros.org/indigo/api/sensor_msgs/html/point__cloud2_8py_source.html + +def _get_struct_fmt(is_bigendian, fields, field_names=None): + fmt = '>' if is_bigendian else '<' + + offset = 0 + for field in (f for f in sorted(fields, key=lambda f: f.offset) + if field_names is None or f.name in field_names): + if offset < field.offset: + fmt += 'x' * (field.offset - offset) + offset = field.offset + if field.datatype not in _DATATYPES: + print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr) + else: + datatype_fmt, datatype_length = _DATATYPES[field.datatype] + fmt += field.count * datatype_fmt + offset += field.count * datatype_length + + return fmt + + +def create_cloud(header, fields, points): + """ + Create a L{sensor_msgs.msg.PointCloud2} message. + @param header: The point cloud header. + @type header: L{std_msgs.msg.Header} + @param fields: The point cloud fields. + @type fields: iterable of L{sensor_msgs.msg.PointField} + @param points: The point cloud points. + @type points: list of iterables, i.e. one iterable for each point, with the + elements of each iterable being the values of the fields for + that point (in the same order as the fields parameter) + @return: The point cloud. + @rtype: L{sensor_msgs.msg.PointCloud2} + """ + + cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) + + buff = ctypes.create_string_buffer(cloud_struct.size * len(points)) + + point_step, pack_into = cloud_struct.size, cloud_struct.pack_into + offset = 0 + for p in points: + pack_into(buff, offset, *p) + offset += point_step + + return PointCloud2(header=header, + height=1, + width=len(points), + is_dense=False, + is_bigendian=False, + fields=fields, + point_step=cloud_struct.size, + row_step=cloud_struct.size * len(points), + data=buff.raw) diff --git a/pcl_recorder/CMakeLists.txt b/pcl_recorder/CMakeLists.txt index 7abd5472..8dd8ea04 100644 --- a/pcl_recorder/CMakeLists.txt +++ b/pcl_recorder/CMakeLists.txt @@ -52,7 +52,10 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(tf2_ros REQUIRED) find_package(pcl_conversions REQUIRED) - find_package(Boost COMPONENTS system REQUIRED) + find_package( + Boost + COMPONENTS system + REQUIRED) find_package(PCL REQUIRED COMPONENTS common io) include_directories(include ${PCL_INCLUDE_DIRS}) From 3fb5d8840a5c521e907927130bd8643b9fe4f780 Mon Sep 17 00:00:00 2001 From: jbmag Date: Thu, 29 Oct 2020 14:11:21 +0100 Subject: [PATCH 357/627] removed sensor_spec["id"] --- carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py | 4 ++-- .../src/carla_infrastructure/carla_infrastructure.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index cb741c33..f4b277f0 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -226,10 +226,10 @@ def setup_sensors(self, sensors): if sensor_name in sensor_names: self.logfatal( "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) + sensor_id)) raise NameError( "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) + sensor_id)) sensor_names.append(sensor_name) sensor_location = carla.Location(x=sensor_spec.pop("x"), diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 9cbaf2b7..b4c84cd9 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -81,10 +81,10 @@ def setup_sensors(self, sensors): if sensor_name in sensor_names: rospy.logfatal( "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) + sensor_id)) raise NameError( "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) + sensor_id)) sensor_names.append(sensor_name) sensor_location = carla.Location(x=sensor_spec.pop("x"), From 0ba2628284bf64ca32609ce23cba01b7aa9caed8 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 30 Oct 2020 11:43:10 +0100 Subject: [PATCH 358/627] Add all sensors types to sensors.json. Update ad demo rviz config. Cleanup --- CHANGELOG.md | 2 + README.md | 2 +- .../config/FollowLeadingVehicle.xosc | 2 +- carla_ad_demo/config/carla_ad_demo.rviz | 173 +++++++++++++----- carla_common/src/carla_common/transforms.py | 1 + carla_ego_vehicle/config/sensors.json | 57 ++++++ .../src/carla_ros_bridge/actor.py | 1 - docs/images/ad_demo.png | Bin 277185 -> 1426731 bytes 8 files changed, 192 insertions(+), 46 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 64e83549..6a0c8aa4 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,7 @@ ## Latest changed +* Have all sensor types in sensors.json +* Update ad-demo rviz config to visualize more sensor types * Remove CarlaRadarMeasurement message publishing (radar data is published as PointCloud2 only) * Remove sensors.json from carla_ad_demo. Use example from carla_ego_vehicle instead * Add radar PointCloud2 publisher diff --git a/README.md b/README.md index 75f38828..01b74782 100644 --- a/README.md +++ b/README.md @@ -2,7 +2,7 @@ This ROS package aims at providing a simple ROS bridge for CARLA simulator. -![rviz setup](./docs/images/rviz_carla_default.png "rviz") +![rviz setup](./docs/images/ad_demo.png "AD Demo") **This version requires CARLA 0.9.9.5** diff --git a/carla_ad_demo/config/FollowLeadingVehicle.xosc b/carla_ad_demo/config/FollowLeadingVehicle.xosc index 904557b7..885ed1ab 100644 --- a/carla_ad_demo/config/FollowLeadingVehicle.xosc +++ b/carla_ad_demo/config/FollowLeadingVehicle.xosc @@ -2,7 +2,7 @@ - + diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index 88ab572c..c37a00f4 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -1,13 +1,11 @@ Panels: - Class: rviz/Displays - Help Height: 78 + Help Height: 104 Name: Displays Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 + Expanded: ~ Splitter Ratio: 0.5 - Tree Height: 78 + Tree Height: 420 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -26,7 +24,7 @@ Panels: Experimental: false Name: Time SyncMode: 0 - SyncSource: Camera + SyncSource: RGB Camera - Class: rviz_carla_plugin/CarlaControl Name: CarlaControl Preferences: @@ -36,24 +34,6 @@ Toolbars: Visualization Manager: Class: "" Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path @@ -77,20 +57,33 @@ Visualization Manager: Topic: /carla/ego_vehicle/waypoints Unreliable: false Value: true + - Class: rviz/Marker + Enabled: true + Marker Topic: /carla/marker + Name: Marker + Namespaces: + "": true + Queue Size: 100 + Value: true - Class: rviz/Camera Enabled: true Image Rendering: background and overlay Image Topic: /carla/ego_vehicle/camera/rgb/spectator_view/image_color - Name: Camera + Name: RGB Camera Overlay Alpha: 0.5 Queue Size: 2 Transport Hint: raw Unreliable: false Value: true Visibility: - Grid: true + DVS Camera: true + Depth Camera: true + Lidar: true Marker: true Path: true + Radar: true + Semantic Camera: true + Semantic Lidar: true Value: true Zoom Factor: 1 - Alpha: 1 @@ -105,13 +98,13 @@ Visualization Manager: Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 - Enabled: true + Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 + Max Intensity: 0.9843747615814209 Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 + Min Intensity: 0.8187852501869202 + Name: Lidar Position Transformer: XYZ Queue Size: 10 Selectable: true @@ -122,14 +115,102 @@ Visualization Manager: Unreliable: false Use Fixed Frame: true Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: ObjTag + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 20 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Semantic Lidar + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /carla/ego_vehicle/semantic_lidar/lidar1/point_cloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: Range + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 93.02222442626953 + Min Color: 0; 0; 0 + Min Intensity: 18.348487854003906 + Name: Radar + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Flat Squares + Topic: /carla/ego_vehicle/radar/front/radar_points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz/Image + Enabled: true + Image Topic: /carla/ego_vehicle/camera/dvs/front/image_events + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: DVS Camera + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false Value: true - - Class: rviz/Marker + - Class: rviz/Image Enabled: true - Marker Topic: /carla/marker - Name: Marker - Namespaces: - "": true - Queue Size: 100 + Image Topic: /carla/ego_vehicle/camera/semantic_segmentation/front/image_segmentation + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Semantic Camera + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /carla/ego_vehicle/camera/depth/front/image_depth + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Depth Camera + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false Value: true Enabled: true Global Options: @@ -159,7 +240,7 @@ Visualization Manager: Views: Current: Class: rviz/ThirdPersonFollower - Distance: 13.610654830932617 + Distance: 15.07965087890625 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -174,24 +255,30 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.49539870023727417 + Pitch: 0.17539866268634796 Target Frame: ego_vehicle Value: ThirdPersonFollower (rviz) - Yaw: 3.1504008769989014 + Yaw: 3.155400276184082 Saved: ~ Window Geometry: - Camera: - collapsed: false CarlaControl: collapsed: false + DVS Camera: + collapsed: false + Depth Camera: + collapsed: false Displays: collapsed: false Height: 1050 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd0000000400000000000001fe00000367fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000046000000e6000000e600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002870000001a0000000000000000fb0000000a0049006d00610067006501000002a70000001a0000000000000000fb0000000a0049006d00610067006501000002c70000001a0000000000000000fb0000000c00430061006d0065007200610100000132000001960000001a00fffffffb00000018004300610072006c00610043006f006e00740072006f006c01000002ce000000df000000df00ffffff000000010000010f00000367fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004600000367000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077e00000044fc0100000002fb0000000800540069006d006501000000000000077e000002e400fffffffb0000000800540069006d00650100000000000004500000000000000000000004650000036700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 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 + RGB Camera: + collapsed: false Selection: collapsed: false + Semantic Camera: + collapsed: false Time: collapsed: false Tool Properties: @@ -200,4 +287,4 @@ Window Geometry: collapsed: false Width: 1918 X: 0 - Y: 27 + Y: 29 diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index 8b6ee7be..d27f9181 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -330,4 +330,5 @@ def carla_location_to_pose(carla_location): """ ros_pose = Pose() ros_pose.position = carla_location_to_ros_point(carla_location) + ros_pose.orientation.w = 1.0 return ros_pose diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 66c8df6e..160f6114 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -105,6 +105,18 @@ "sensor_tick": 0.05, "noise_stddev": 0.0 }, + { + "type": "sensor.lidar.ray_cast_semantic", + "id": "lidar1", + "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05 + }, { "type": "sensor.other.radar", "id": "front", @@ -114,6 +126,51 @@ "points_per_second": 1500, "range": 100.0 }, + { + "type": "sensor.camera.semantic_segmentation", + "id": "front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.depth", + "id": "front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.dvs", + "id": "front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "positive_threshold": 0.3, + "negative_threshold": 0.3, + "sigma_positive_threshold": 0.0, + "sigma_negative_threshold": 0.0, + "use_log": true, + "log_eps": 0.001 + }, { "type": "sensor.other.gnss", "id": "gnss1", diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 479fd9d9..35ce9f8b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -161,7 +161,6 @@ def get_marker(self): marker.color = self.get_marker_color() marker.color.a = 0.3 marker.id = self.get_id() - marker.text = "id = {}".format(marker.id) return marker def publish_marker(self): diff --git a/docs/images/ad_demo.png b/docs/images/ad_demo.png index 3b6a1801beb28beefb6cf14989ae9bdbc5adb2c8..5c05a5b6bae16514ed25fdfc93e16ad7e8a15cbc 100644 GIT binary patch literal 1426731 zcmZsB1yEFN+dtg`($XMOl8VyZAk8A(-7O8$(j_Pz(hbtxl1neWba&Un|MQ=DIV>lx`?`L0pKr>F(l0PbG2r0fUdYNwsKUXa`oX~=UZJ4?M`FShqv7Bv^S#tH zT~&>~P&+z1m|NMJQM-CNno*m1See7Yc`THtStXD+xQ9HO5b7gr8}X8`(Y7M8L!qLC zZ&Y$G%g{>uj*Z>S=+Ch&8qxV4vYy+IJ8moUll0iiAu6Ri9Rla!iNwqPPh=o z&mS(19*&hxT6BE8Drp_|K=+g!!ooe9u=59a;fj~D;FFdon8G0x-`D?aBUtuxOe>GS zF5Srh_<_b>iR ze~maH|ALhrZ@GKjRhxqJKyQbc6FIa$N)0y~g*X0K<4U4WXG1XF`!-*HSmElx9Zce0 zjpcw_s`Yk@UF^>7)FAxXaqV(3VjbL3l+ycj=icsrEC|zoSXv(W9zN?J>3Q>-k1rI* zIU#+;=zC>_7~gVZ<@0EsNha`A1$~KbYjpr<1l! zZE`1uEvAFFOLLPl3~tU%dA!caYL9lTYkFT=501v0&e46iP!x%HHXS;agkk4UpC<1H zF#>{5s#HSgF(tamIU{@gS+q23eis`00scO|Qzy^Lnn}#BSlCB0$kP3M6|3cL+v+EW zUDjPfva*OUDl$&c(OyE>SVC*SU644rqOJxK9kkx+#O%Q#lOd=0ugY=)Ebq*587gdq{-2-Sn^^%-jkS&?a~vcrrVs~4f4OO_-2&GH`MvSt^w+_2Im1qbfuTOw3J>ul|Af%3%l&nd1994OQ$-=e&D5NCWng4XSJ1e|DklX{U_mfJ2J}#7uS(x6lY6*uO3`; zjQ8=EzeKWX5XA23F3l>uO*a2fZa3IaD+Xmq8T$U2r2MFipMC8(foGVaYjW8auV}vc zK*Bg*!FGtp_qxqmE_iXQ@iHuRWP8cGl1B^lN$rcp(Qkfvp|+QbM4HPb7LJzn$-CnD z1kFM&3AgGDM$H@+q%B*+c5}=hPNuv0Z^&uv7%$CLu64hnvHBhsl+QR<>+vrMm8y`u zNrta3S*9Yov3YT^!SE4JVV70O`+mYVF`~$CWMT}HnAdidf$0z;B*j9Xg5MPgK%S^PA^YO zJ8Ms(!v0HaLoyG#eutgfIpMg&+q+S8dIk9yCT@PFs5Au8^>!Ww&S(2EmoB})cpX@q zmLKPfH~7f6C!tI9Xm>>A;&)A$j7N}FbsF|8rhE@Y=>@E(&8gqU>-BbOlhD#OAN)gM z-DAC|507`omjf-6Cy-+0!=YuyUUK=97F5W$O~$I@?>?IE<27YThNg-n{OnpPDEwY= zg&Zb4>5cUHU0`Sr296qtbs=JZ3ey+51Y1XM3m(u>i-vvo+umIq(!GuuFV?L#$Yh48 z%?@q%w)f95aF!Gvr|P1zx+CTCb@owISfA=iuiLS6dX0NJx0$pj0W-PciXfyLjC9?%I>Z8IIKn&rMf+3xx-1 zGb$L}_~ov$f)TW)hx-Q$6%o8njy){*{oTK7nEymQxS6Ye#`buxG1G2TzNu7 z1Hp^4@GqOclL`&<{q72l?I~!dUbK`dpa~@)%Ycl+d#%^>Sj8#}lV_JHq*ZFu_u0>? z)v;Fpe5>v((*O^JKRnpBApH@xj=d8?i-i&P8GgyVqU=qt$a|brf3$`TG2}_^8*yQrq;K~$ zE92Bj;M{#lODBF7chc=uShEP|V;)zeu?V>*VL^hcAcP% zP6UIenXbxITR0eAg5!(+*$SHZ(3QdsEGvhT)?H!-|ySG!~=cxTV! zL>q^{hPXNOOXP;L_^c_8PsA_Zy{xaS3k|lPvAkX=fn%*^CcYF_z$?R6CTO0^FlvRH zWm7cE>-Jj0ll{DUe0L5-W1n+Ci$OvsL00^CdGM$5SHFvABtV_XIX6S`nglszuX+RbmDg-1#@zaYwMVh7jc-$wW+E2^vVTYI$nH!P}ZtBIB492O6ippkv$7J!6 zG487YiQ0$XjSLCVq^jNd@Jx($2gH z?@ofXw&0A(K}c-Q9^`U53Y}S!J~>|gFK3_c3Ljw6Z~Csdn9t|$)hvyjvw!1jCU?=c zVsQsY3^i#ls(HO%i_zqWMuBQ`1pZj8$W)$SA>I~W_0rCxhkHROm^49fV;6w-j`(Ic zB1E6uyg5qbGnQvm_)bL*+Bi$x(TD=51Z6qPB?7nqO4 zt%rdr6Lx`ZSk(K?ohb<|MZ+*LW}xX%a)Dt}CUIZ{GPeYB5ouZdxxQDnZ=A9+NyCcKdl?I=v% z@bI=8^S2n%z_m3O3E*+cV1*4DmT~Q67nPS+6DPADPQGY%Yf2=2&*sOUA-KRjx3&N%2x_9el^MoTWl2hRHTT#yZh zS67Tq%y?Px5Etom`BZ;v6sJtA-iOu$gcK6#3VCVJp5<@$PU!{6M|&K49V+jmcX5$? zBCGQj*CJVXUPJc=5hztnnJi=M+({fgpaIAKhwSZ?Z^ zIzemD@wW*A$V}cdC)=D70oDG9_-<9dglR5SoT@rrMZDs5G-*5L?){Ic^|(EJ0%HYa zR}=8D~XxMa#>0&6St-5*{Wt$;V;4aL}`O333kIt zR1k=HdWGw;laiR3aMWfKya&Q-8pUv5`mSUYaMH)8S~?4ooSq89cUZJq37a{)QT4)a zhMg9fNf*i|}H18|l#ItLm>Q>dI2DF2PmF0D`h_ zQrQWddMJ@&HfR~pa~kEt5|!;|3W zs`w9piq1LB0F1;4>-9rtj04-28;IV-h!(62>;wf&)6 zul2dAMUp;xpf*vwtac>Bs+in2LN?8CqU1pGl-d$E?1SN7$5*rAa0ly!=8EzgnT2Fv zT8b;TRcBb;ZwB+CZkCGAsw;;Q=dh9fal2(SPFWz2bKB5YPYx>$7KHaTji{@N;!jh& zc#d-toK{=9B7$2XAUyoOos2`wIH*W5X@s_*IrYN`A!(h=jKFOl%{Iqhz8A!Z`9?kSuhyazAE#^QMtr%6LdWF8lrki6cYUywW^_{)X}V>8q2(cgEiBxSBj)f{ zPU+sj&N^Q08fvM--?P)Y;Yvu_BK2S?M2hgW%1w|%?WJk4IrybNv5RtHQOJ>k@IY(3 zPqfjYcHwi=ioDfc5-&n}L9gEgX7X8jjvuRkLEB80?~*kA#%j3pekKS*|0w3+=Yakx zZCg{lROqkkw#abb-YpbmLs@q!hSWub?SO-3=xyka``VQL_X< z{mAQ+GvT?4VvTQ zzkV;dD`Tx7Gew`wUI*qki7zEMl{J5-BOfqwRY>gobbp822G5PN!h%MjF3r?jm!P9@ z+Qi~01QM`5<9%rZS6Y^`6&%SiEmIdYM1qHkEL#t^j*lJ|#3u^>f|3ghN_&BRpOZJC z`I6mC4iu zMey(6Di*oybR1mWDj-3M5NSH{)axm{TRBzq?}7}`)~VL)JTFJJ8tWENhLd;qSI1B^ zO4(T1C;~h!!{4fH(#>{$X~b+oWQ%_nQ}c~N5HddBbHc(cM)i8IhiR@9dnBNUhf&a2 z)bSpis4i)sbe+8^F1p%7^i@)j@=IHK5}F=9J)w72W0>?Rg*ivlx)F^PCZ_YnSfUC< zN9oV_5C_V52$Lh{c<8CXD2~`rlt^(fD){Y7tO%OHos+^Vf8O#;lCtAz8co~q-LDA7 zl=0tOMKeF~aVUUj;#OZSP8UljbUiQI+!v~rlQzQ$*w9$;WDYbVDABwmp4bW)(8tpP31X6g0 zZsLh1EcB5PjI3wZG%RqaO8t_;|Av`rxgt1X(j&TsOf*uTbWS!MM5?9i6#k5?8=HQ! z%fTurtOHRx%qx58g`8vXGi?t&=047@s<9 zcySA558J~^rL1VLjSfX>yOWL`eL1Kk=}v;`7tA;L#m`<5PC_vAmEkbY)at6!yJS4# zl^l?`TPN{55z;{)T{~nH5Z4?bqSP-Y5xNoNaES(l8ZH{+mk7&7sDeM?YZ-FV%P+%Y zp%-qQRquoOeMj)n!0cE99k=(>C;xOc|8>K@bkjIxIoN zo{+pKMmZ5gd)r3J-gUii_S<*_A~Y2T4`>?gsviQ!7Y8Hc(RoDq6a@_vI^VIOf&-v$ zXX38t;M=i~QyP6{^VEYkc_?-%hQ&>Yb&qFqGFO8Ain(z4hpP}oR72ZJ~+B0;XvBedH1>(OyCm4eY%8W z9jKlINY3_)Ux|L7-H9QqgG*OlDyob7E&1jyk(WOm7iP;8x~@JxXK9UBhi^iMsj2(Z zkU-)G3SoI|u{ms9BF-bLCc6c`Kj|V=GASQl@P*)_M8#)8Oey5N(IN!RnVb7p{xTV| zPz$@RVfe$Kk}aG!q9vg+Y^+$D61&^!k`T9?X1@Eh@*`)w)IL2- zz=Q4-w`~~(>pZ?ov?zpRT}oag_u+-f8WOrCsh6r)uWRCO^+mRvQbtBJ%+~DnT8bi# z9PE?5sE;OHE5*hkO&JmL5(#IeZi8zx9M9(qdBv{VVCmp9cJ9+&f zeuW@E!_swCCd;lu&gddHM=>q;+tQgJtdW0m;hXa3)rvrPV)VRPecmrfuewo|MKWZ~ z!Y~Gs&Aq7x?rPm$Fa@ZZ{yOAUwsY-0|1(L`qBr~tc>oi%0Xh~q7aH~S%F(yQW$Z(j1u zd>j4gS43GEgv_t&TcupUu>T|FDJ(?n43-$4zm<;X-w&kbxV%uKe}Os+ zKk{DLOGI~m`o+2~*emB}lBk@#E5;@5&4{tV&%^|g8yvLcRHg+?qDzj;J^T?GvuuWH zIIr3e)yAb3>d3Tg67yM}$;J4+!Kvi}3f5A*3tEO)GR@z=3Q+3|{Sphh@MUz3*K5?a zZCgUOCh866lRR}e8?o|45%3L)T%BiM^OfN5h;Lao2ffV6Np@B3il@~J_-tn*MWBi& z`603}TG|~?iSRLvORO9XFX|m71-DcSY8C4-7Nslb6QsSiG@8Xy^oN!jL+>t@SFdan zyCa8%;D@i*d}DHH?>rNyR=chj=b~80ya?`IF$#Q(;7IFKao<@(Mei@q{MJ5>xLA^e zytbrYqi{~hJwdr36%yJT*NKU)#mTFaqT%%BqZ!p&<^10CHJko=Ol+%Vgl1Vj%3wm) zLfDmIHM^kj6p?b3O}@a{@B4DoD_^y|mJi=rz2xMy6i9Y0#m8v!4L&c|F_r{bhgJ;q zwZFi2MD4FTogj8*Z<2e?%g?&TS@I81;xbwcph0-yEBO*mpa@=2qd`xJ);C<$rKj z);Nr3=vPk(W(-oy5G!dRNBfj-;U2&(v-E8;scmV2uT-#PVYJ_S;`hl8#$}w-E}CEl z#@GOvoXGhi8;KR|UYy2;m7f;Pc)37n&hwW|hV zj0}sp6NCxF-QUmH3yH{KR@ zciK{bi_f00$%QfsUUQ?j<=JJFo^hx1C6$kolD^qc2{LD7S7G-m}8D#lQ+EQO1NKG0Bld#)SS*9)$GBLgLEURh3Aita2}2&b@T zF(eXb-$&ty+W14I*gUePl%n}}mH zY2=wgF2kp>d28MADp!~~CWvC{lj+G)b{ts@j&)F#khVvwU5)G___v9aK!lvvwsM;C z&aM62Oh@_TM@bsq^u@rCU!(7wvRT#$qcN0e+IT_aDRXgZ@?yly$eBy)wx2Lju-L-O zrAU6g)_{|{5>id?{ZTLeQX}ar|DW25SNxtIwW?2q3^u>qmSJ8pK9m!*T0(sXl3tp+ zt!0NK3EI#~wOD;baNW(q5B}`hC=vJIDa*{Qs#Ns0`Fl(THKJf%d^rZ(3q}!CDG9b! zPHefxxy1e?B#XU?u^HhHy9;j$$~_2;3mGTwFlS^o*hxP(`($%PM3VGxzE5S^L4rIq zd^cYy8pzPnj6Cnf%SL44O~pctk)Mj|w7JzY5Z+w>bTLye1WtWd!@jxT_)9cM3<=em z+Q!irt|?b9>DE?o-S~*GI(i=Ro{Wpmw0+Gn{r*y^Vc&Jag>Us9-`Kk1bqLqx4jXPF zl~rk5dEU(CK=#@xEpZ&tcN#WZpKGwA#VHO$OkNggs4nvNP_2t_5mS!IBMHzg)55h< zW4hIW{ro2S zn&;2)DVh^WyLx*^;jTJX*g-hk(JchJO8r)F(q8Q{r7fo?5|3M4ix#iAwG=j&_3Cpo zDaVB#_yPw`@@y!(#oxOV>bnA4M0~o6z({?5Q^aceO2y!fLerWX*y8gAQx!9bvcxR@aZoRkA3xSMU3) znc}P0kiQ1dkO+KtrjchYc58mnz4jG`)NS{zfG79retqt{eiioOK9!O6xY`2X`DtWvIqzS$FnngBDksTJoXX^UMqRRzTxL5 zdRqsF_oUI`xoA~9JLB5#DPws(&*{R#!sukz8yr*!elOaU)v*v^q6EQT+>w`mkb4!3 zD~3k%zyDKW_pL+43KL)F>F1SBHk)=+P$4kYLMaP0+94m~&1KAmo|u%siJ;xS;Dz~R zxwk0jL4c>HdS|XBrImd70JFJA8Q9>IP2iZDTU}iZC@GOi=tXTEwP7AkC@I;!dEnXk z@rhojOfaUcP4FW(H*6<`4qX%%7YV*i|0LC6_0C6;e882DqJM)ks4E~S2$4SV8x(t1 z`&^(9dh$MPv}*PpW$d0SA7j4E6oF>QtO`N3CW~dmVy_d6blkt61q}E3g&z(!wogcf z>JVy*98>c$n-h6$N5@I2%+1Zso_ouuLN%bqEiHdP7+CSAjdJu?Rac9q7JQ;l1fFDy zE1wagV1u)tWRk0oSDGYL=&)`UFO7;p0MR?3?>a_lgmq(qU(kn*w}?GgIp712Q{a}fZ0Srl ziFgOp0JMaSlFt7nh9_q5BE6?aJR-Mo+kpd1JdnDRcc56U@X>XQjEpQw>NU`MX$1VF=;3tpcH^YBokApq6z%v2*l?k5?`5;w`S|f8ux9F@5Y-6xmLqY4 zd;&8qyaCS0zHX(j%O^KX!;_z3V>>QDM*wYja?|8-MjP2D7DN4i`U+^XO!$gafsZq7 zW4r}ZOtte-Tnez}_GNpBQrgm9$m;gYuN0GTS&@zF&^MYSxSpPS2O#3-u+Ca9*&oP$Icc*-dSZlm(8G5(XyWF7mQ3Y!GF zwe`M8#{BTy@LCJ7^Zlh2Fl-j~Ezy1*;NxSq48?)UlU7}}!J4R&lDYZ$yBdWM*8hzV ze*uH1y|kdhP48hJVqUVUSSStxNyM*HoOqxzD5e_U#r#VaILci4;?x@6GZ++s(=_8PtQ}`P|^? zWXW?UBL%rl+oq(Xo5bbt^oxs2A^-~MF2AhyAp|IoUIUOxpb|g>(8>O}NT)_CDv1DE z;rHw(di?tOdbGd*E(OoqCEk0OP+D3VaMj!|&{y_vn*{-$eEW^27jbO2;W=n4wrm zVzTSrq7HH!UCCCB@as@&Sll|CuLXc5mvNoJ|D3^drc}R={jr<<^d8cYY2R@0);W<5 zSdZVc({8?HP=61PKiAhEH_m?a8H<+AoOd~-7C?M5HtZWP%eoKgWJzNG;^Obw5%c$a z8Q8%10CS&Oz?jd&!?QYFtmX&X&?xP5XB9;gW0K2wPIFu+46{NBvU^&^d4jWHm18<@z3y^MphFVvJb8XP zxtL68PfBxW|C!Rd`KI+i@1(h`gexM~q+_tT0w@H4IKUA8gCCV1eQ$q&G2Op>`8jI- zI8^zF!R|E?NrL_5Hq_x3#qXTKKY?W!Se`BC!H(yf=S+v^Yloea$Bd4i*;%H{o7SDP zspoSGO}2NFze36>zM|hP89e*99{b-J@K(D-=r}Y*^ZVb9PJe&HL4%=CKeFehGh%_+ zp>f`_a>bVU{J7(CzR9G2nM-{36~||FSoMWKh9Y_o?hd(`)}(bE<8T5{yq4vH3YN&b z1dRprcbU20jZ7K`vmVd=?eoEvexu`8Mqrb8@io{*F`Y-W64GJ|gA^Fg@d9nlfyFeOpya!+ z_SlKj8nfu|?A^Nkp>pl5$_Y&WxM_z{|GFmSE@G{@0zgQ^ zCS54W8?RE_zup@&Q{ryR%Nj9nUUI{qQREU+wh-NfykS+G5e+qnUu{EWmWvGhY2a5KYOlS(hy{)=WZ0XQDx?dG@yW&TIF05Ypkv0QAC8tn&ohcW-Qx$=Rp zqUD(H=@I;#UJ|HL3W${E3UqNz79zj%KVaTur{vYN#)gxO#T-;Oe%( z;htXTaSaEMM}YRJRMI6t26`EILVei&=Zp56HXIYIS#6=yuQ;dO#6GXt{mvqJ{htH? zS@^l*erCx9EckbP0J<;hwr#`c^KPTG7)xJE%zC7A@Yx{q9M)Os#?(JWFt2^}SM>L+ zoobRbE*{<2B{wvnJ|6hPDgnXz{cmq0CSW zV~m(3oKr*h4f&UbzJ1qZeY%KLDXB7U-vFQxPmI$TCuOYX{IGs#UGhJC%cTGuzw>Fo zM;7fgt`=dE#6=1=3ZG4N*%>opT>>b*^=CR2fCe>f zrdCip7qDp3Jty`*OZm<3`}~lntd^8KXd1|gl21^sF=WY=E4+J_+|Y`gPtfsn&@sj! zd?%}aKbdka-*G9wP3f5}EdVaw1rU>Ae= zht(h)VD%gCM(mzE*Z;)z!kcNSf(ZLb*mN63lFk0HO6F~?@BgEG-e)K_0qPF+5uoe8 z;vBgBg`LQFB{c+qin|bnjL8D9&D|sJdjpRwbJOwoo;K z1IwyT8$cp>M-LB~hD88flZQbZ>2&Bo>loRTf*brF8ZHXB+r9zh0fiQpFauZn`>SeA za_8{zvr;UU0J%zm#bHGI53 zs2m^>*MoerkhgC=liH4)xo>gse^~TfTwLj|ge_E_jeTiPgtQ&I`CR5v3A%%9@qg>s z@bZvUx3wu~B?~z&FE3vm9M><}t@CWxFKT=}seHb#tgWu@0!ELsKW>ND|K{XL572M` z;sf0RxL08Q!Y-W1U4Umwpo0^*92a+OK?e*Y;JHPJ&t>mZwv`#_;z@{9FucHect!1#W6+z zfYa;rNrm8`%0rewQt9r6Vxbz!|HM*x%r zwEqfj{H$9fetz+84kV2n^8~u~z0S8*lT-olOpWz_+z{B|H5dlUiq?ah zPawxs!-B{KbQQv1cFPvtojAAx1k<2t_k68Ilj|Pdi8u5CFw_TGp8G>JmnQ>1W^63= z{Rt$2jtuQl*k4eA#Prc_NV0ozcHE_P47y}J2n15EdV(ML_+UaiR6cR;EzvF!jB)@b z0RFY4gm(B{eFN%KEp}kQp6k$G89vGl9Wk!XUbY8}H{h|Koc`Uw;TtV~(V<}3K80nN zG2(Bx0{{*416TIx5Fi6?(7JBdmCx4R9^tn0r1u*>5#~iNHxVA|v-$e+!B_a|+{v;Wu-Lhbz*5<;0{)yCT2j*JxEAkLM8Qd^1Yo&e67((u zx|Y^)*Y`M%15;DX5*iG`5gGxO;e!w4i!XO%pEcR?Uv#`_JJ}j_@OuvsoNhDMx}AeJ znFTo0tXlK5Sjjg6SUVS=b^Pa8ocq|&4uz}Ae*rY^x<{sZ2`N%(onCnzfn?X%7?76K zu)LPVO9!SLNE?I;e&+I`1-iXCl=ZtW^iMT-+A`RVeZGzL9COL+`Qo?p<$SRN2LCkL zamT&n2GL_7l5f9DGw3dFSlKU?B906($ht1JEHJG&AT9p@xJ|g03LAsbhrdoB3pSs% z<$K~yWdVKy3K={)s_>WEA8sa)3Ka-llg&0IrEoj@`vc~Eh7`D$I~n{>@E;HPp9#M# z!%j$|w|%C#1+yHy@8152jB+pSDShrLz0DGawLNBac;Yxb#q~dG8Zfz7g|UkeQnnF2hSF@^=O!XyQF?kgV++zrPpj@M1Xe z1heA@hprh0K>%A5NB2^e^g<7Mg>!po07L#OQvX)FNf!?ZFxd@fIvrO!K2H}n7j*{S zZ>jG7gf-r6r@@j|Yv)HQ<8_m_s!N*w&5^iot$iH31Sb%?IZT^$0o?o>y1D7qwzLdK zbFcgX2o{h4EIOdpOdcnMd;%bj1B_fmF10M4RNhNq)k#d|mY27h4=PNmHCNMnc%>^L zCQZ8cOyL_m^k@iFv{Z%r4HY)IjK&TQv1)~i)g2v5B%!t$JY4|h04}}DP^1#F@sFjS zTUptTm!`~_+EY%>&#GwBBL2cba@qv;joAUP1u${{@%KtuOTjavuH*eAfQz+C1@0J7 z7C_QRJ`im52N2y7eWL%ZU2bA$Xu}GCEr5yu^v-GnBMO1K;(HUbW!KRw zs9j%Q1L;P$_Auam{5Qa$my~#QqjHJbfzM?(PRNK0Dy4UdFa6|xs0@bU3G2=v+$J@ z{v72^8@CN+!=fEP(SXYb+4P#vvdfYgkMKC~Mo=j!M(gI9kx{(n^*YBYgT? zGk4O3d{YGskgq&5^XmGwhqt#23~qSQ5TZB$^t*-v68UYw`M;;)` z)`LvD9YH3_OCkio-!^WUI=V(j6B&{1VR+G6ZT%&I9KkigZEe#3Fp^j$FPdqx4&Hwu}C7GKxe8&FP-!6 zf(;PN(O-F!E8OyAC;};ler3ab7o2u^(!A{+l?@h29uI&%IyyQeCLDkkY06q@fE-K& zk8YgJeV+ZO_8Q`L^j4vV1K0;JfIX;xFmk{}Vo4#CH7+W-|8w)Xk|BaNfi9Zh#~oQ&9f=8APn=)JNzYLM z9uIJG8X%MVmitG^Zn>=7r}f6Zh*@T8hOgtobFBgD+Ki!x8U&aqJe%_8jr5D0HkYxE zV*zmS!Gh9MSsi@@ZTkj)d(iW}!Sh>SQh*#wE7{Nbz--D+D>~QFQ z@RXlQ0+MDu2ta!VFBg!K0ICN%_jRm5wP9YHBFv6((esC!O(Y?^0Y3&E-d~h7#1S)lwkXE#k@0cQ_^Ww8& zyj;A~&en3CR{)|{6SUCk-`=K&i|j)%iSox$h+8a!Evi3$tYrAhZ7eDB`_0?dg!7+W zF6&r{FekZyp#5*teWJ%gL5#@N44ElZs%>bH1`LqRd+sR#V#zh}2f#Ke7PgBuX@PGp z_ojezl$01(YyOS=lg-+l8(HM32)J|ZoMs*V9S(?<6-_)H5mGf>;uPh8GQ(gTw*w|e7`&3hoXoEs17|JZv+Pc z8I*m4Y(nsv$ERd7o*e)&0F24pp_3IWoLW0Q#SQ2({0r1TVCiSK0EDZVJAN2D^d$D( zBl?xnDg^2vN%DboVgF13_)BM+ZKGG|H|>NLfiJ2M0GLn+vJbQ}8L2MxviAcZpm4_e zKVDpEN;mlp5CdqGZk0L%n<8^dOLSnDvN}KJee={~bLJg$-&OoVB^Sp%JU2ajq|%}F z2}_9%DC(&ZU>`ZKU<+fTN#Oran`Av4T4ZwEmLH@7eF2yRSv;WC0agQo&xl+g*8%jk z>=eOjjk4>9y7L6Ux><4on-xI7391}b?;j=YlzuCo;esS8LK3PTTPJdqX!>`1=`X3Q zto)_F+X5>&l29PerIKRK58oiMVFhx3ph6x3*I z_tlef^_4Jvep`bCd{ZO#=+zx&mF(*y%c|f0E8pm?%^KRyGkN2$@P@Ihgf}f>o;pH= zDPl`iXsb{qsUS&9N`=6WVvYV#@ZRCSlHA%9?J?}w?~fm*U>|MjwQV^2SJQ#;Fqbhw z>CS31y+>Of7YVSCb;$x?`0$O}IW^h;az&Yb%mz`hdS{Dedy9`Ma%<^{){_aASeeGpf{Q;V0<+oP);4aEM76AZ)$!9w&t+U$A1_AZ~`XfWnUO-}n`nKs`u1t)_q=5Iz8U47m8u_ZC3&o#%wJXLyxu%)v*LhP6xYUB%81 zJgpGNUyJ|yyl6?P173lQQCe*8)*06@ZMc4GzQLl!_K)IA)Vp#T+t zpANyd{SJ>(cdflC?U78#v0A>?S|N3xgKIyBHXm~?z!iS}S?#g@Uw1Ey(Vnifoqpk; zq>87Dc1CC-D0x8~()bzOmkQP&?_ZhKBe(+IW%pBjGe!BYz7UAtKtD3IYhG{9C z*hV$c-uku<8T=f&(yo~WGN%fg;!Yx^Bizpz(l5r&`=Ww&QWGk6kWBBdaGO_!5>)-pIs%v z!&Qf%F1ad4o0hkaKrqdh&-K;k$GW_E`kOKq#U8H7ByGgd>`)E#1ufA%9LN887oaS( zdzt_xy#|SB5~G_I4%H29hEq{gu|HYJ_l76{gi^}VU#?9T(pNn5i37U|$x?(@ew8Jj zRiz$5C+K5RfkH7>Dyd|M)7Z05IYHed4;N98d$uEqh03T~>=e%%2nTp!7-uJZwe1i1$1!r)cde})l~pzDN5li56w+J6_xr!pO1NmWdGok2F~#1M>Y zfPpMgukZF)f>C&wcfrgUS%b2{Qr92bR!m??Ktr1Dcj&|?CV)<)P=3W1pv>5S5rnui zUWI|U?8TUZP{^eyT27tRd99^{$P?+VFw)XK>2mOu-tsp>q?kz&LG}x&uM?%pjru3} zrBo0ekb%2k(QH?RU%IVA;Il;o%P;`T<#klqtT4u7pg5Dy# z!`!xRN-bo_N@A9znIf+d4X*B=inQc*COYiiUnF>Y-S{7MmJDd_?{HE<$cNpp8ldL? z!H#enRu5O`7KeoUpRYNfj;E#S^#Z*-n{ z95i5_^;%=)M>xtE=|va6rPaY(z^G;J?cs^mAhqBkj3ABf$EyV2&o-GH`PJ+Q`6dN* z@+RqwvR0M+0hP|lSy`7CO*1#La`BjH%ruoqHNheOAdPaFR?KlqL3JL=(S)7Br??!< z8!UM}@Xupr_Wkqj1XX!m7He74wOw+Q*W-Z+@>m(lcg<**RkqS>w}5V@t6hpvHOsbg$C7Lf)p7^#?sei1Z zP650BquIfOkOpcLu2}e6rk(M6iMNq%%5e62-a7=-3&!6IWtclmqPhGm1c%`JJC{tQ+oAH4GtNC-WYbCl2J#Z0mH{CbUhWy0i~^ zRv7RfD@c;`K*6O~m!m01bYpt%g_G((^_vz(I2F4G?w!2n4Yk|&XdZm;ccWw?hEc&n z;@3|Dr3-@228EB+tzJ0yHQpk;DF310##y>s7_&Wrc#x4_HAG$BLf6bKcdJ)Fg2(iw$a3^j?Ne z2UfZ;$OG2VkOPi^%fHXm&?~Q>Dk}^sq4S_2RpTP4LVi`Tomu*5@6^%?AzgpyfOW^w zRKUOl#u2d;?LUVDKAXR14-*s_db-&#;uAy=JI5s=} zQ*fYoWya@tUPCT_^?Q!_zk!NZIz(P$eI8oRh46G>zVdBpsuP~?tz6f8(80Ja7Z)ED zC9?9NvzE2!N38Awsq5ZZ((Pr&~e4rr=~g_LPcK<^DUe z!|Qx-S@%BM-uqH-n>bs0IX2nz?p@H}P3+|Y_Bh(j6m@&WjoZ&E7@zi>0lgTb{{oNI z6y^Wf^a{=4#GZi%4s8*(f`dGRjy6%Zrol}qU=>G}s1t6#M6`o1|xw>gj2A zR29}d1#W#~nox@g3#Xu7b?Bp2iM#_|15yMI9nlk<7j^|d_( zh}Kbc^)Q0(@Zqa2&64ec{onH61;B<`;|x_%dE12{+Q5(VCRJ3YHES89SeBE8sGy{@ zX)U|z;d}M}`S53HKJ06yccnE4n}o}%zw1sOm4ue#)l|hI-C$um*~f8eAJf`I|33nI zQS&R0XD#_DknO{_Op3l{p*80<&*`j7=iAAhW4jJ@Qljf~o9qg(>-64wOR=*k{{{L^ zTSS8moYG&Gdf#%Zl6m(nBf10zU;{%wrb^GK2^N9PKj+H(!v3&lyzu*E{lA|+Q=`^a zOIr2&vKX1Pqy4z~7snk_S8e`{&6JbZl$Wolf-Q+vQwKu=YNQ{!IA$RTLjpr4!LX{B z{^N_21o-i!O5$-vKi8nBTcwBuI%VXcL?9@sW6T{`b3?E+(AyvuwpH{^&D<^evPz## zjsjAqlhjJIx;S)KRldy~5-jsH(mGX;)^Y?jyvF^iuK8Bg1|jQLFux9dd&X}qD2_d5awce;ly=!v>+m-5Xh^wHIhpv|t z%I8QY-1G{YByGMlT_Mu>)mVnk-w%5Sc2E6PZmMS1JE5zzoW5%+&V^#2{u!iPxqdHNUp}@`J$(IRvPt0Ja7GT$gc0vad-6fNFx^fY3i!*TvE}UyuX} zJYeio#s>9AS9^LeH;ULZ+t>j^WH4|=ZSa0lk-fbP0p=k!C$_3OmM{>?gMqiPb{@D% zYUfq3`>i`>UMzJ6;efYd(q7;I-k^H=$Hs4gX!#i!<74N~Rlf@aBCMuxXJ}q%poRvd z>mFd_d@<}S91LTeLo5YzXO28H=`B9Rm(0kgkD(3M^H3?;V@WElP*9dh>tsB3oFASD zi7(Hm)#f!L?<5K&ume$O^0UM57Ds>m#FNp?7qdCSd-k_Y{|$ns;;zPjL~unM;@3d|`X(r{G(dy0`>qm6 zf>1k;DS_dYb6>*|>rl~|tn##5SwV^b9gy=1nBAVTCbI@J&a>v1y9O&Nlw{+{hs|sz z8B#w!wNfW2E)E9L2XJbA?Xe~a`K zb-Ii)GqbrcNh*!=BSnC}vU$wNU?^G1mva=?&9;?P>>8HF9f=@;{&dam-(-2#wLAmV z75kqM@|rD)(8E~L0xehFfu7+kNQQ9XjTrya;k@vgbBvQNvgdu}m>{5rh4eG+mKvGn zwG+sJ6Y>5Wa_%zb?{z^?vXq-Z{$YeQK;NbsnD>A#x~9N!WHKYjG3Yl#Tx|9CI;5oI zHDh~>MaK~0WrUQgs|Ymd3Oz0=edr|JHSA^ z;ZJ}-#E?WfkS$;*M_`EBMo^QmLM~v>FSE`MYwMPL!T>D`eJolO zI5A-0NYQcFTw8T}>)`o#09f9`BRykoLg*LULPiO&75v93|7tB_#=b>amWAL8kO6>4 zl5h}k_JHgqGM5iG!6|{{|e0GIL>4-)822IDDZUx$N6<4sO zEJZ)%$tOsT?vh0ZakFsKH&sn(JMI6Ga97BtG%yE*Bd3Rg%1(cB*Cpc9bw9B6p@;!< z<~YxLb>L=Li?~m2byCk}S?vz&Kz{pTYHkJpZY#U)=w6HzGw)D7Cw!6`&$Y0zLEg|Dk|QwRT$c637M1Y?pUmIQOG$q5yqMUd2q*n-VNRdDS%@>*&)UX9z@) z*>aphCSmf})i-a&7f$})itDd=x1#{5^GhIs5Pz@z%lv!scL^=h^Y08)Z>Tz`*TOFlq9q5g%Eg4H{MYT zHXwAa@bPUO{QEHB0$l(2UnGmHWC;g#7gsOywa5pw@#vK1g zPKO4vi=d-DZ(FADz9sjn+;ivhv&M&ssaNGoQWkQ}-mNDL~65j(n3WXtGTMOjVmX+d}eJ}%JFk?Pr$yFBE z?-vvU(Q-fvSWpZZlmE$o9du&of;GQV)5>TSGfbIgCAvmQZL=IwKn+~ePloI82_W9K zuU_SUQHks~-ry_GL@#dLvA(L@0Oq>Z-E$t9gqz1s#MWdLAnx6g0BpwT;m*CdV#17f zgI;3Al^IuuUj{DV**>^;$B*NrW2q+7W^yNOdGQyyPBx~C%2ipN|_-m*Bd|M1nDK9Q)7k8I8G3oKni7PU*1G1`6mwChA) zB!S8-R5pYs*1l@~JWa8dq7K=ZW{lYYxBf70ean%CPbJRY#-GH#Sd$rO$ECSNUkCLl#ejZX5hE2qJ`- zS6s@+^e;m7|k--F-XM28WP9ojDx&s`j8}qnm0ylZ@lYSk-SY=G_yOu31=#K?r7h@lR zRKRzn_kGBb`{GDq#$JzyYU2bvtcgfH>6Yqk4hn?ytr%#o1<})nXbC#Qvk{B&3 zdn8-a8%ag0RF&2RMWKk$^{iAeSg2BD-mAn;4|{ou{1Y03ZiKg-*V@Y5yd9j76rgq0 zRl`-4RS@iwuzxU9#-w6VMpsFJ^=cM}31V4X{*$Do!D-O$)3x*9e!)MdJHv?Ea4F2R z_?}1!mm=FgSG~R0R*)*%ILl1HM)O^kS!Y_!34G5b!Px&$Z~GP94mrEOfXD`IcRQ@Vr6KLSud`21X1}SgG&VPlY$x}ICakAqK zz5>di2QLTFi|N9{or`O+wk_R?mm!h-G<#9LNhg7vkeK-HZ)jmQmwfnm9p7>1Xt#sv z_MfcH&imud$CCh|+}lx$Z=m-8G*wLO#W*_IU4)5=nv@@4787=SfqF~q73bj7|J*ky zcolGdx%Q9$_eBZUzxd}H9sb=`i*M)STxa=c&y*8>$5juDI=@HZ1#dEK?Ho?ogwAIk z{?aq0b#E0cMfW?SwxGQB^nk3U zH|jUAqY3PlfTWwL04!>jRr{Cs-`wD*z{h8=X4@}##Bm1g{`F-xw(-f__YRbq;aPc) z;%i}d&M!aM%o28#NCoBj?-y_;^KMt#Whg9Al3T(31}$16B@gzz8ky(9K6)LCpZMg% zyIw@1M=ufs4>@;UqUBXaZz5JRtuW9t^}}3Gd0q{UYqzIxu2yP7aY3669qHeOunV!S z+j9suyjsQQNQHTE;yoJ2fDQL(5ahtmM@dtI_(%l-+0{sm&+0ZNJto1lO z%a*7zV){URQo{yx@s*v0+WZ^QbZ)F|JY$tA?F;~n`42slvxp*i)cu|9RklH zb$wsR=EZI_%9iY&QOioMfTd2snX9Cs8cAaEYq)i>!t=){etL$~alq$hbPT8AOnZGGu= z-x%jgmum#@*%>l}hA7Z~R)gnY{>ri%KeL!J1HGC@KZ@UiH~l8aOMdS6)X~x*@{xV& zu;<|f%oxY|luhrkp)e$+v&yoXuc`^SEe#h!U_slNM9zKWMM;G#Yx?BAt1sW28Z;M7 z9036Lf42%7;Mf`hWSLoZ&`=|aBmz{(0I5T`5D#e7ViMcVu{1OIB^Ypzd z?Z&pmj>q=OoKlf8@kq=R!E)v;BO39iN$?$y|8^Bah% zwO@Q0eH!^YUj9pYB_#~)pcgEYkMGmLdV4vp-7!zK+5I+l9(~jNR`*@3vgVtNgvsQh zIcUAN^v`D#x1&@--CGXFr8?>;U;lJZ1mrxP3TpGTQPsc`8AoMk!*f@aC->t?v}79E z$!OuEkrd4xDQgY7vPwa{I}qs@Yb`?b%}giHIInei=`I9L_*-vbSyh~slWUCy!p%A% zDYTa6v>FRuq~JiX0WIEG!3FEKdB(r!=qvri>E*yPV<|9#{T0r-C>s?V&L_f|@6|iL zv$|32_iCzj9cg3Se!XuhAxR7OURZxQ?-epiT<`pz)2Jf>Y`qBUor_+UDp9qEJ7YhZ zm?=l}KfiQSbE%qE+b}rV;bQs-T^M03zZ@BqL2sZko3d12)a4a<%3nI?z?PG2Y9?R0 zV8WWq_6v^{|4aD-3`<7$YURDNe9l|T!smdi-+ZGLXTR>Bzc#s__)HvHT~r6V(vW_p zChZS?Z6foT04UTV65_&YD5Q~P5eURAk)Pj)n*(6^XFW!57 z%5q7_y8e{5c9MPHHV=!!)^M%AO>^DySgL&D<5BRer&JXjv}7vEfr1S>pqhlz5PohKl53fROJW@1+KV9e1=_HM~5X{?#5Sei5~Gav=lY->q`CFZ?KN>MF9jdyIS+aUmO%s``(}wgJ2w|EO-{Z?lED*bYWA#?ls|N2DX3w% zFuuwUY=fieF33TKah28Ig7MkRCyQ-%n@e||>yTO+4V(AC^bK>BlGY%@$%$#7w=949 zx~Z*mN^|}3dYK)0v-z8Lrp_LZ)`zLolWfuL6ePdk$<^fNy#A3Y(FD_7_-V}FXPaWBCbZ}w__$2CEYl7gh7Xhvn9W+&41)~3!9yJmq7YQd9Vfs~jkS$5<6_MdkL zrZ0|g(<^mr8ygu)%xOVYcA3!C8q05yC9O)hQE=a1k-^r|y~5X9pt#vSza@VKD~(g} zs^5LS>7W=tCJ*!>4$0VtbywjV`T=7We7AM?c8d7nZFekdyM9xZ z;(Cc!8m(u$=<*w`v=kHNO7T1+3tA9)XTj)xV>NYk*~^xSiiGv8>w6i>M3qx=f-2|> zO!pG?%49WK3DWquToK)ou4Z^fY^2%Qc}ym(*L^;WxKZpJ92h8YPAPWGp#*wcbI6zV zuT=XUOR16kyPk!#e4hAHjIo`T^|mmbBE6B?r9L=lSdt8L^&!SvtW+~0VjpHr|Oyb=*6N?~kV_ZcLt<{zR0bi%*q=hcy_s$N4w@esdqCbYD&O*#-Z z^3qe)`B)-{>D0a|^=rz7S^Q_$GMUnuv**5h z%-2+P#LxM%Gmudp*xV6V>o8x&Px<9(wgi+oNTH<4dLr`L2wQr2_xU)ppCSY%0>(?% ze1Fa+r%und)rdpW(2-@^bB%4gIB;gxwd#Hvsc=OJ+1W8CM1?1g4VPp5$eH+o5LH!G zLy9*&=|>jcOg|xhR6jzfs2T(!Ln`bB#@WxSKO`rA`q`zykf;mZMi~|A$u3*KzkrPd zdx#4E=JIlSj4E3}RaKR2?(c@9=CQ@=4?j#1?4+Ll#|yx^aea>%D*A2Jejn~)0e8Jl zS{&0Vw0?H;ln?`-fR+nHko&-7nzpd)mr(=4)W2|v_Z6y4aqwn{qbyK~=njoj`;t$Xg8icvA z@91-=Nk1^BVKBDpu_h0C^AK7ZrF+z=u?q?cM5_&uLZS0_%!9j04i;*5C-Xr&+&Itd z{QS?R;Kg@H36M5^D(?>cTRzZw{%ZlWXa9UGBjLQIqqVfQBvI8L1WVRxj%n@0;z4Cn zNA{V4GxN(p2z)X0UCm}(cTDb3^PV{4fqTNg)`C}Y%;rVI%+Wepm(eO}A% z{Xh8vCoLcN}HZ2>~S8**WFqf?3>NJi(B{?B1=-hGxV6eq=SZY2y7&MVUV zNG?s8m>|MH@QQSWGjmMEz!M^px69SRd(+$fo3I1)QKBGm9kv4_KkiN#iz($RLT z^$|3vJKQq~=Oun5+Wz2}CDRXy;{{gcYIC2AsKF*k9ef`U>~q|jDr|-$DYCl}u2E;) zFYA7Cr=l&0*c3Tr|6ub@%ZQEkRcCM2z*qH3+q=kf5;ex2pNg-@dKlF;uOse{|7D37 zEzk&Av@TJ8M*h>ZdCDDg=7!;J@rR@D8o@_$Dhnqs!EhA0RxXf-Vr1sK?GM5nBAU+# zf86@Kuw*5seqelhUAKh0d-l&)#3|-^E_`BFOatdEET%xKR`Uq^k`PV6lPi)yR5`=3 z&Dc{Hk)70&ke9eU*u3Z;H_ERVeq5<|*9#rO6ncfIalI&es%*K0k#~5Jhb0qt^5%Br^NvK?jy07Q<+^JO;g_u9hezgrWWTO2GU(oM$N^@4>4<|i8`}eT) zcz^w|R*GFdRKC3Wz>}Z2XM?#)UVfUED_db?mp^kXfk~(mHN5aOrVc$Oy&G`or@#Lq zx!nYE26>{)S9LmtQmoP$8XQ{Ek2S@`u%$B*TfD8R8 zrRnk1)YSCKyw58_vJku((=6|=V}H3)IL^o?av=Gvolq$$2US#%kC+s^T0n~x;MRTg zX&fTTw94>O?JtD_s$x>(^y&W^3`KF6{=uS6mn&tQnCw7gF z4GuXJ+PyUKZyWEDG_J57ZE}yY`X;hy(knL939B#t#-H`tc#&Y=xa^N^oxDKyRhkki2cFpaHZkTZ#{lE|{iyDXM0D>Sf9=zYlyd0QV3Y9k{fr_YsguwbQg zN471ktrH?uF>MVT0% zE3&8-H9?)^;d6bwU7V_)aPYdWGg6!sWZ_$S!WSMuc^lP4a_pj?vXh$hk{?xPFl?A(2SfBJy^y%#HR;1t#u?t8mpUr_^W=A~Nf_BC z7xw)Y+Pdh0z*?!q9_416uM{@{da?$O+&9l}7n^L}zT>i|uPQ_%qk7axZ9j*l(WSLL`1Ahw|ly9obgR1>}*bYx#ZN+Tm6w;d{dLo>(kMgP9mUi+6hW0EO^w~N?}`aRB{%hF_z3Y}`Ap7J z&@lKhxGpUhTOz-pUZt}}mr*KD?llG~<-Ti%QhFIQg$Ge!Nl6K2D=%h#eZ5Lda;Ruf zJekxP=)9j=T$JV~PBm>&qYdrd__5(AT_DStYBEzIuOh-YKvrk*BQ)2^m9;*J-lnvN=z(@r6>O_DyvY^{^B^TAq3NAUMJRqnCrZZ(YWqdZwv zl@$^!R)+bYZN2Ky!Ityw^I98o6GZ2Kza9fnZ|2;xe|Pwp(1z6MwY&FQH~FvG-tytl zuq{6Ncd7N^0&L{&GmOd{ANS5xZ{g+nN|(;4=urwcS5(mQy6*j0FbEh+qESub^I&Y% zRWOG~vZ05fM40Q#5%BqT)%K2jMxXrZ6%%1d(+-bCv1z^JfOJS9_LkC2ATE^GjNVzyLoMz2{L*nX@% znr@NvWzKr{mrFojYJ2AvIJO(#%Xd|&_jElsLPxWB67NsCa*IEvvfBURwzjq|g5<0m zQKpWZ?iI#P*O^FN9k0HGu1u?Z+Jnh_n3h%dcj@(_(u=%EuhbVih^q~`b+Z|gL_nnY z_OrF{&oADe&$tFy6;65!h;Si?Pk)e87<2~e28pBQw4r}8wr*keY}CFEkx;$=5d`y^ zmbS>5EOD4HUWZngDxQP-Y)c%gTC7x|zME>+0RYQoy~wcWiIda`VRizF%&|Yttufs1 zg|PX$H0f1lIgq?yA$0|BIqK6@HgU*eXY54CLJCZkhYIrw4fF7LktEoix5)0xk-Td? ziO4ZO?2L9II@A`p>LV4K<5%?DzxVwydp>S)^KS#d)PXPW21l5>qM6XSd+J*>>HoO4 z%2rgd29gu}h0M*>=Tjlz2U~u~7*wys0X5j%gRw0_crU&F_cR2pJgDm1zd%Qs z$3Rgxs^gX^R(V}nX=P>A4f=lM+&4@?0cPf+8odfmB7pDZe;PIEKZ$-2%}2+Ll7J=& zrY0lA?-O7Y7LMPhQDf`!UWcMo$dU%|b#J;Dd2=v!_jK@ms`_2QEn^a=C=2njkE!k;LkJ#hEZIn1zFq`ZfZ+1uxfa zS-Hqia858{2a9{E>+2I7Iv)}?dc)Zqe)DH3P}%3kij#gA6lbwlS5q4btE?TxUQc_a z%ugIk__p8Y?XHfd*}$fgE$2H11_oz65`wdyFl}E!gC%WUQ{G4~9qOm2?2j6*NRmjj z5bY4J-*X;k@265douAsI0{2_hj~1b9?LFu9uVR|9Cf5XJP@$=>64pu2fxTM2|H;uB7CtaG`Vmu3T5v zVH^!z5jQsu{{WoTc8^_vE_c8vf#lIK+y#xra%A*@ZRZVFUbE(wZ>XYv6gyg{O~!RY z`62M9x4y22)1jjI!jB$n7znR_9(2+2=OD%K9dieF^MXav@9-Y>mCGOEcilrbZ_v^{ z)OYH~`TlS=;@qJ|jlDNpjuis;CZR|mevbC623CoB-fhV?MVgv?_d=Rnlp8x?i!;3U zgV2mkO~(Lege$(R^&}P`j(uG&9@bjhcI+W8_3ye-D>~RIIk>n~A(Sy&&OH9-@1MJGPB(dW z(oFV#ckltmCD!%i^Pn*b5ifS?2$&g>51w=uK+ybmdxaqPhp*aOoa6{3SSCu7|GR(8 za$mNJCSsGsL{%-v1~n)kUov8d_%LG!%gZWAQ%5kEbRHsER0GS^!^LRX3a6+QN)xZL zd8cM49s6>I4U|PVGtE}p+@jxc#W3o%tvh<+vzj7&OrZw}=?sB1H*I%%ztNZS^{L#} z52QHNK#)G9M+bwcUA}prTBhXhf<7lE7jmdw3yQIV ze!^@b5`k^@tBz$ztx9xj{-!tRSk`ou4W-X&Uh;7YrArs>Yg5G^--0|Lr>92*V6?^6;nLx+ z*2KSmt+g{ViikQFxgr*vxCuQw^p~4#qy}S%$^qfh#}7d9puE#_+L(Ec@0pDGcoxl| zM&0p!X&=fX+evX3Dc=*B4Vhk$8f{2S@XB_txm&@3VP3u^?yqAc6)kFLbqk8RBvE=h zLpO+u5=k;_>LAlKg0bzRjn8A@&8zs)9V?_k#6h++Tl?=g{-da9k^Mpa$K(*^+HYT} zao>5Zewumv!gW%LDc=F%D$vxZpzv2FwXio8siQn6Z&LnzEtb`wMVVDRsKG*m^skUkE8RpW1Cbg%NK2c#4?KMKUXrFOi!gRr? z?32!1wO+e(VIPgw00#$0pD{}e&lUIGg<#lNCKsFSA~UbY@u*3xz(A2q;*crp_vfek zt#dD=&|p&?4GoP{*5sdoIklGa>~C6D7`SeGBDDiupfv%4E&#L3>X%4uh2Qi7rd-l| z8RS?Hq(C9-(Dj&db+iIQaUhqEi@W4PiYE7pz&Me7mLOeDlJo8prfga9(_H3>Bexvj zbZq0&#?;3Ju63(3IgqhKk;nORK@@pgvoP}h=^wndw)Ui3cCOxoDrF8wMD|Kc-Ci|c zI$waGw^ly`J-!5G!{BCqetwWAe=q1xAF4MSAy-NmHq~sgCz6*p0^1=3lvI9#89&Dw zeFb9|4w556A4?7O`%l{100*n2gRa7ItA!Y88@j;8K3fL5Xf;T2i5_2ceR1xP63T06^2Fiy zrg799)xH$M{kCGNvXM!*=l&7>hZOi$K=TgD&-<%BS%shwp+C@8-->6R8*cgNpOvFc zTN%7}OW3Ll=a83SJe8MU9v{Wn_W5|V-Q}RFMMYV;dtOnn5M+{)u&{&*TD+pu^_S9Q zD0L7feuc*QzH_A|Hb$>an$LI&8vPiRSk;AmnBn?O5#H>9 zgG!Y?XFDr$*@lP4t zV}wz7C72k&4l#?9H1!;zzb6);PI5tmof_FZl~$6W4uA>zfsr0d%BQ;E2581hc+~at z+b6rX4z#egsL55QOkVOU<5Yi%n=L#NWgA)hmLq0jj}#pU8yoIEH-**l3Vb^xXv^s} z<*0jJ7dh^@)-O@$2+S7?uXoy%+!c&iB)ZxBv?!f^$wy78~Ob=^uS7#+7O~XsA|Bm~Y#lzyn|-$C=aC#igOK z4tG5ofNabNX=V-X2EY)O*AsGBV*|{VDr+br38-R1t+q2T+%pfa65di z%|WhxnT~YvcPU&3kIjkw5o{r}^BtV`6 zx5ftI==M&gLkj+Uu~X4&PEIa%bQHMl-y)iv$UPhRFz^5jNCiH_qY~z|wGp)UisXOY zVMhr87`oQ5`zXt4K$F<_p9r9V0`6vV$%p7ZGX#=f6Xg^${&CF6%q*`c|Df+qfEhz% ze3T|zT$C8%xQrqGwQyfsNsYvcCXX)fojEfSbsORrOkz2xp}juT<~&Ly@j{vc2B+^Z zFma62i`b+@UkXfTKB3Nq$b=X}>A{cLhx-ysOby|jAuU6%{F0Tyt~cVjoDWfYXCkCZ*?3M{!*p`?H!lCQ>N4Gv`B0pYOy1 z-psx?j*_v&KyAoxZA}O3gTVyT-Xl{ao-b#& zl%fHW#O(6#+zVRz4h$0)Cu;@?Ca}uO)=fVj9eA_N$1*skDSD0Tlne|ML9%(B3d^Du zIQhqq_&Av2_ZmiX$1~iekPce;qOChpKWSt^{KQ)tJYMx)@q7eXk#5tl0;nl*jHuPv zYU~Kg$h_bR(ayZWl--&H8wq8}V4#{tdT(@j*<}X=ay@f>)cEn^(}+e;aD-a3Fne~d z61$o_Sxty>Qy^S9`PMmwiUesoS*`-sSCqIhNo5}IpHIE_Siuj_6e=#XiB!0XGu2`m zXFScisX1_rB{sCIlWWg+OPjta1KcXYSXp(NLjm$w7r|WjTT%;lO$6 zv^tCE&Ft&nMwfrr9Pf`j&i+I(Ie}R2e9|!js@=DqS4+G5llcv{w8Zvq3%`EJ0cFU% zVG4W@$AWHeo=6Dy)uPG%N(&R6Ms-r2E@Nu1u{yrX-~Gmu$@CG%cDah?9IqYxf!OyG zL-Ay->%qvL=VM$H-0jZWvY>#J0<{;<$@lZcPCq_}&Ra@wo=bhM^|QQo(jRuXx;|($ zkAm#T&dKQvhMPr>kn9C&p0X+BqLe2ZtwrgYXl%*D1AL%}BMMl7RlHi#> zKRsffdtLbEfK!(Nru4+P@-n=`5xoViR|fU2`zoNQPM97u;hX^s;NOFT;<<7q?DxE` zp9THA>&(a4W)~Jd_5&Y*`RSkji^C;}9cQy?D*$e~o-S)%z7q!rM;BDB(+O^O7yBwm_rA>TG01lFd2+VUY`Q0|M zzF^#!cnb(6wKIq_UZ9n zRc|#X2nHTVq_?XhOf#)67BA2*5DG@K)tO?-@&f)H`Jp>st1U+9*cYv);A)kjyaX(%JlU0^KP)QDE1%{;#t0P;M?-!?t>g5dpYDHqrH z1n&=BUIb=;FmE->u?G>*?Rcpp5)u-y7TIpN*K0mZU`G?b_x%?{KD>D3ZsnjypCmjA zQr35UrffbBb0BV_5U_v7Qsj?MRN##O(5~J6$a6bcV{fT}Dx25M_)lMi?d^KVNy8>e zC{O@cw|~9gaK7F5(|wQ2r2T2mxUi%oEY;x7PKF_O{OoLmNmW&kE+}eHqoxE*yjeUV zrj*a<18!F8qd%c@Hx@cAz?FuaCg{ft4vp#A*08SYl*G$`y)3tRtu%RD^{<*DYn%5# z^TzkM!?*qQ4I^qvmNMCR=EPvTAd0a-PtT{K@*vImIQHeySwz1Bv5n&B?{Wjs2B*tW zehUY>()I!ni0?H`4R&ZR{^me~{VFee(`=f-{p?IM5#I|yp8-^rdbO?$H};=po0|U3 z(-}}qfsOXD?CT9iVC*aZpnwQBA9jNNzmAiRWjUfBq#$l_N@bx96FEae%Dt^;6(e|l zKM~9)I%A+hVoZ*IX=O1tGO?LIWT`3$#IM-5rzc9~4rP0cTg<;%IJ?aiqDY;Xtkz@5 zC`qnQNt7Yoz*OEXL~E(FSzzqR$K*~O+xm8Y+`d2G5xMnqa5HHwZzSWhX;PIS92RlhzS)I_^CCgRM!^x&m_nk}hMG0rzkgHs z*=VbKC}D2;&`c=y`#E=uKtuF``*$>4EF%7<3m1=VQxBo1r8r zjEZ*cR}ULwLiL8-&@Zt7R4;(Kh+)uaMn?)Y{UriWV=>*pjH1xk%e<1iOQ!RA9S0(j z1dNp7e&hIz3PO*QHCI>R{_aERUfUCrCx=6ubZf@%oP-LYGk%xin^x1iuo+Tm@!4)5$!MEJ1g|a8#n6qI4N@R$U%H%H-ta z*CB2%#nW3Z+rACQKkmtA>K1FRY#rX0Jx6Dg4Hk;knO+P4J@OSQ3c|(?_9g+A75o}C zvrzyFxp3kK9Dt_=4ysH?(^$T@?Q{4Fz9)`_ublfio^61Ip!Vlf&2jS!m#oh%K%)^a z6ch+#JEQ4hVqzg`*JiBg@5zIO3EPa~G@`H@NpFqArEokWpG>-(%m^P{t0K}Hz;(F+q$?f{tL=!s7{sspGRdG7IMBR_nFZd0$#PFLAexQv8n>fS*qNYo5W{ zQ)6ReoNS8l(_Eznn{gik;P&$8)n!QUw-OaK>rD}bo^SiV-~5RJC=g#RgFOPwbYis_ zC$tKwwjw|iydfdtb0tMD+xm;owp3>VPg#|8e)qRz0guO-9JMkVaA>DnST?f9tP*0? zxv(OTuUxR2E{!L#q;OsmA8M$vlSm~{WDOWdUHBMKu@i|JW_bfY^@t%@4g)`+kmMT zQp~P5b2a|`h#}!|(f!O9(``*Br;k5fT!uLX(xp#la-WijSAA3cz4-* za_w@pWN{7%T@x^Ol9}*LXi>6X{wpx?*!*SR0^$vG$PWx~l_AFj4Dk!g4)XU)sQ>-l zD}nxN1+7>ZiqTvJ1c1EXe%E^7yCv=H7yuIo2-ybnF@kd5=9MGg^D%vTTq=DB3ec!Q zx9_UmM*0}HIVc2u_EeP%xge!Xl%>q3Pwb-qmIbA)ZNmSw)u8Kpi^7;&7ieR_KvkOB zOdTmhrlHolb9dkRr@~A3E~-+qW5+5(RQb>ztzt=(R8Qr1=4kOR>kH#sMHcvXcwuLX zHxEeZ-(&ji^E+w!0{A<_=xTEMlNWvsxp9r{o>lJri=wk|S&HUMb9y8+AM5ynzc8^| zkH66Hci1ALC~EIH>H3sw+{ufcNB5KwL79RIUnsI7LE7BP5-D-ahCC6jH8{-N{q)!Q zJDDORHHgp9&WqznW;&|kG-NHnPHJV!y^-ku|9AS_V|3>esVbqox7H;Dk~QGo%1yDG z+rsp%2O`BZ)KDP3N)T6=yNiPf`1kfAs%q+jZIMdkVI!L*Wny~msA+0%68j}3YBNx? z`HZM1HY>~e4mAGVbZoD|m)oMUW8t>HiCR@RPN$=gI9qY(8Uv_Pti^tHvE75|dM!X` zZf;I4hrczcDtW={4_B-*1VZ5wD|owwW#8cjyFl{OF_ z09*2Yg8!U-B!$5Oh#erP!AK~3f|<@>y_hQ1t4MKU&t{OB$m69aJA6C)FM^Ob~of>-Syxabq=XL~0_Xp%Hf|0q`C2*iswq#<&B`q&qVs47i9jh9yb z^(*=M`R28c*Hx?A#UXDhZ~}%a=*bN9%)aOTVbJVg0I84G{oi)GD$I!*KW1I&Ba7+ej2;rgD3I}W71a^ z-}p)F;q<8Gb7_L@+AVB$o4ZkeMKa(TK!+s=S_8%{`LwkA;=|1bnw3b~8AHr9V2Oa= zWPAD}(>6eyyC5gLun^Jjg>qsAe+5@q7OCJ5o^OSu$X^$hYv7F!%9S@6C6mhpJ2Q&SXMI>U%$XcupZx?T zv5CV>`z(wEH=QB9Itv$6-se6 z+umZ`>WciF5O%9~-H&kU;7i0*ycs~P3 z?LO&bIJOdMex*bqlVYC_o;VR#cCpkZfP6HZPAId+Or!~_=-TjtJ2H<3I8a6Ga@tkWPw>!|7H{ghc zgFhn>+VcC342;I^)ug91pUCO`uCv?Vyj=(Y{N3fdA3vplLb(XA!&Jc+5Om^R(hyu_4Fm}Ym*5LKV~!ED4( zmWFIN1G(@en9DcP{E!n{Xa$D~$zQ@YuE8zXP9vncCK&Q@aLCV`&h}64;1=M9Llco} zgMsC{wS}5fsE|Dxl!tc);B`M7JwiSqAyzz_&1g!K!%Z0GZbLn_%(9wcEU9PxF7K+d7_ndMFt>9^Xl_d& z;Mk_?Tr^%DW=+5)vwCGVxNv5_J4iG>8(erp5%%$9ei-2M)Ft&7Z8`0~ZNPCl{2m3L z4IEBJAglm~6|v7Di%NMCIoFd?ao+l*?G_TE94Ftt9EOW}i1`nsxiNEIjcW_3&9`Z^ z&?w&>xuY*cJ$@vWprht%>y}ZnZ8%0)uAe5)hfpRWHq5DL*GTsCVbXYC{EdhK9M`MJ z5?KqlKu{`Y8ucm|0@x#JHY|10uhVy9~jR535c92P%v5s2ccdEJM3d zgfj=4;A}?DS(~pkAN}$@=fAst*9Xc(wu8H+!{3(_R9VbP#v&FVX@OE*wha|A>K{0gKWN#VSDQ zO?C*`o9vLiSKowW&muD`pHLV{H$wr&=Mf-AHJvQ zm>8mv%6%y0S&C2?jxQB1SG9)5@Ln6>$uI+<$%)@nlPmb-Dzg*fmuLd^eH)b*yKI-*; z;9{sW;}lwV@ev!vCw_t3@$*h9p?O`yD7Sze(_KB9FO?Y5%3Zd#>Vs<)x|(oAbx;!5kx>ee0A;O&ELQ0gK2e_;1;VsmAu%IgznFF zOu>i;Kyk^bo|)8b*89|O%eeNPzC%L-i3*i8Gb&4?XBgrdA=(dkwI5C$1Rw@RZr0#1 z@5Z0?Tq3aJoxV}qzi4!m?V6c!`Uri(3Sa?@3G#>tFh-GSg$8=pTo<34hkp+a4(#Sy z(qR{w)=ld+c{~86gB46%@cgbQp$m$OR~yzcB+&Am&wyO0-(20@PB!=B?>*)_CBa3x zIvaS@Q0YImVON`pt(!X~srym+R!2GK{iNI)ZGJ!(26tIAVQz9qndOfDKC6)@canh@ z!Br_485uPNi*7frKwS-ac80lkVT5y58!X)yzi`ww@pe(iEcZ{WH+ai3MUoWTKCkXM z@2JwVML!wNa>&1uQxHGE@Bo;iUS{ z5H_`(rFQ2L4L$H%D3dyRl-2ujfW6~qMaAicBepiROp-(TRKt?WhgOG`)J=(# z;{9oD`|)#n3p%tCuZ#t9YFLl#^g7M%g8yX|{?2LMLg7YDz(?CWL_0nmVDlA$y$IVNpp-%h87 z%Gmd>pOJWD9#Yf3I7T3~kptj&-5lHFd#0r+eHP>ZI3k~-{S6MHr-2!il-+0$?s35T zd$c|B$*azFee@161oJpj7L(TdsNi%q8n@aAX5wp#fUb(4Hm6>EWswk7v&Sk){HoXHQg_N>GxP z=<|XH2|*w;Y4|&r{(D@-^@W9@0OBcROR$nIA$nM%7-8npf69<_e{t6KKKVBWR;)sYnhl&n!I=Q=5=ZdfEkgP0fg zc_lzLKrVDa%PmW*s&4Rn+ZP{5uJ`Z>V4g?^$!G!_V0&igf62&2UhwRCzJuA^1*U#b zeIo7n@!3AL&rX{V*O8iq&%H4J86)*cP>mGQo!;p;s+9?fQ*r{*wNNt*ULqoU`TK_& z@>)Ph1b}6J#tRlLEiJ_~-bg@aI6QYuUL0*Hl^Zo511njnSBmuiZ#qo<+i-EG;tV~6 zY1r?lPgK~BFYP^C8*UCo;BdrP59dP#K;dzH4CdVtraSX(h!6!S%R{V@S1wc9DsGh z!uyJP1Br2|d7L(181Oq{UIBAq#4INoDw*9`%Mu-LRGy^Bp ztnD)y_N#2C*|+!p{GLwY9_GISf&qRirc9aD@SqM;Sg%2*qczW-@Y;W8u$Svft*EKd z`tHBB?*-MR7s&cfM0+BzrU-hK3ZD}f1SmfrNFpJSp%C+>1MX@S#=sRwykL7>{_x>D zw=c}Zp_t?D?jJ~S{vG#-?fv{VQXp25X~F@r+LiO`vrFSo6l{GL%(9DY3pwr8j=R`> zA2VrmTKJ1!hFT$Z>E2Cp+jqO-D#!X$a*8Hmk$W9~q0Pgi6L z$V>Q~sKa`P+dICG0gxc`uLWudLjW90j*nyH1AV!CRJ~2vJ2-|NsRD5Y2hcG z8irDwN%0gtbh8qdrV%C{j+gr&eQ04I!{{8?coK`=0yrEPt6RKwv?yH2@qQhKOBWl$ zzy<{ZVVgwHb|hc{vlw~$if9*8U*$+EWtOKb9v`lEUIJbThRIl@!3M>%>rosd&?+GW zw|KdHjy>bfC`&$npPhpV>dFN^*|XL_z@ z1@mtV%2`%Dy4O0pa2Urn-JBFc!}!HOIO9WJV^|7zIU^DNmoJmO@Bw#sI-;G%BT|+R z-)nhZ^+^pzv+6-?3lzs)} zp0E*JP;MMW`vUf|>nnM>*ld>d`vN_d;S40Ezc!ART$20pgtF3x3iR}c9shrtx3Mz6 zg8PV$#_5|b$Pa?28eH#o1Yb{T(0v-e;`pz`8e`Q(02bgYa4r-T;et5a(C`5+?%F$7 zQqj!oLl%obY|!awF>)JAVdeHZe4PHxHLX>Ez66L1XtO~b2#6oB4nnWhqp04pj!Ty1 zPi$D8Mj38`YU*x=r@vzDtEoTDB6`sNgk{U#lDO;%&pd5qAPH%p&@C^$54RC{@Es~b zH1Ou99uI*_*7*J>l!_m`HsFCIP>)qfQqIriS~1qzl`Q$dTanyL<}z90flQ5p?!P3N z;uj%B+2m+z#%^*)Tvw_I)ig5#JmDh8>{F8sj@72#OFTs5B z>Gh={0s;`>1i;xg2DLW`pQ0UrH_{kJDkM<^-~tXQNL3Z2{Lv2m?oX zB9X2(X`l->B{`^TfK8qU_{I{79|AbyQ*d3%9O(g;sd8Eg8O7m=3TJfMee1Q5*L|m5 ztTiiEsEM1u@0}3Q>&K116e2v?L*pF*V@;)>Utt@5Z)TldDfBR)CaRpWgAWRy{H{GH zaehg?d`S=KHE=Ur{LnAOcbeKOPw^pSX!ZQ*qm7jpr`1? znQKbd8Jw*DXy2DxtFO4;DB&dt#P2dA%}HJuZd%=K$BUldnW9ZQYq@QP8klOis;Zzp zokGPda8t#Sy1@dGGKInvt7I=@w#yKdWzJ-{5Nzx|3obaipKH%OvGCZBMXoh|2RcNL_R@(53dTLK6o8|VAn@pA6u=_lq1#d ztYUSA$qx*jYuNrh^mpf=P(_Ix>csvovY~{_j8<2YjJtU@N{lb=z_;K_Pya0&*KzIk zrx6fC;{*p-RMYEdU(rh7wAFHJ_Ah$^h#r;i@xo?hk5vjtsQ`>gLV&(EU-(GF$ES} zBI9lsXUpD+NR{AN&o_$44m#7k&-D1g;|7bEkh=KW#b){hW@EhljMV6lyU!d*!CzNU z6tSeEm{N7c`*+PXz(%fJqjI_g6QF34p$E>0=qamobKAOgP~@!%4aa0Ek7FM*wYscs zt&eFS2FTc5>e&aGM78ZW%j}Dd2jCaXv!oxGKPrCb)m>=dJ}$O9VEpesnW5Va`0h`* z)5hDYDBp-*uCuXn;;#MO($i>^)hwdKLzy?mk*Z9!1K_c_ZW&`m+GV>~<-5tkUR-H> zc9UfktppTL7Vyd_C;XjeR#Yg%qzo_LE#*+}jln$$VWPvQq>wJyrxf^Se}2)kzDnFu zG`QxGsbU?Md8Kh}v|ya$9oO$H2A7+tTMTwd@v#QYarvkui_rE-as&k|Z~4n226yCv z7Q`XLf$lN?CfO+kJIVM!-{C4gyTa6TFhx)s@C8Hg^#FUqJW970Sc5V5bkGJTAvC8j zkEGzZbd4T}^L&GXYLOq__iy1lzkerGp7WOx9BeR+FIqh7GvKtBA31JgYL3sO{j9+f z+TJA2%T*7R?@E6HGvYyG2RITKk+x7801;H+zkj}zkyzoR4-iq&CcrKTQ~1tjug`*8 zVko;-vNAc}sQd=*)znBTQHH+9T9$4z@5eYs4{&qUUqe0d^K;bb`)O`rk=)XP!ynZ( zsgr2IHT>Msun+EXv7BhB6}U*r>swzh=)J+7U|@L;^|WxD73uvKNZ)U`+f8fX zMQ#6P`K{>sc7=-3IIjC@{@6*$}r{{FjwVEuIc2iu4NYLoTPsYlLXz3g<0vl>+E##>d zYVLr5)!l8B13w7sn$)*X&w~KfHSjw>fDK852pT`u)ZCGa8H$2?b|fV9>k<7HD2v}H z{aF)z&LI(yCb0hA>kQ)b^40I{!mX?CH<*A^z1>)b7fe{rNgL}l{)d{Hy8Xowd^>Xh zEf9G*6vnCsj9@AkqDq}kdzX}E_IRd4V4j4Aj>BsZX#dlnFA9=5YTrudBtwDjPbEii0{7mDIjm^r6Uhel3G`~W1EymJ}go(rEmuAMr&^62ijwpI=?Qxtp@yq>M zfAdEecVHBIvJ+yPHmhQa$UX{gVpSrGcF>0FQwGLhTtoLSLk=9&p zX?42d(-2kWM>U!zZf>9=R-&Dk(Slq*I-;E=ep267c~K#8eyU}-QE@p7F03_A^ITOZ zVj+om<3tr+>xMDSJLNi}yIDJ323QE^V5V3mP-~O+f2h7M>Pc(}zNpr{LmIxY-v<2S zlxZ-vWJ|@wr99@*X`xWnUYVNjCaZ%sh;U0WQ*`4(obP|M0O?KJEosh6-^t0zO+KFZ zcn|Y{wuPQFJe29HB;A;uCT6n%>4hku?@*^@3pK^nP_U9Y@dIjym8FA&r2=yJMlR^- zDI?WcZdSNmQC;7(>#1NAe|&qc^;Fqb{guDN!gWc3#eL)V?`|(7kQsl_qom&q7Q<9r zT)32K%!nE*NEn#Z4hYK1IYDJfxij#gCmd4K7V4wS_wEv%$xo8Mz|q2^PjmlncE|T% z|8}(l`YEd%BYBu=(btf>B*&-}`CRckX}LMokr~d0Zh4x^{fG8cf4H)me>k(x3DQKz zvnP6Pr$0~O;7Gw~UV6+G+Kutf>tE8&2~YMINA4c;%+hr4(_pXd^ogI_zs&&$2?;j5 z{0Q&C$5HYB`B%mH?vwjh@@%;L{`uf{(30a-65W=JMkn9clk!<|76yt#M}^Feb;zQZXjJox$Z zrAX-jPhqxABbWt!TcdqMRai;kfyNCzm1D}L@;lq5@>-5ve7r%QnPQs3N6pcqk#~ z1>T;`vuD#=Vdc>hXr3(TLpzJp)6;uA+-X-Xr@-BbXf(P5=8FPN7HB(K{^YV(LMS8M zfXP?Gy^^M;H1$Hs92?6g#p7=xKgtl+)YZ8{bL}$I2$ITj zEYbaw1_wou+8Xq1Yk0=T7%MImPEBPZLhE4L2xc{WK>@@!UvqQw*>1GoaaZVA#J zgz|%WfPg#}y8kx5Sxw{A+S7xlmDT*)GiF?CU$HQ{JAH&T>Y=Z03*StcVU4R#-{FnI ze65O+V{5M2kHRHzFmUF+e!iYxCY8+|V!WrumK1B5^7{2<1h_%0ZNq}+RB(N2`OdH6 za-vXcpOXROr(h_Mjg!>Zztvz6H9KpRv58>Bq1t5IY02KjiX~ZGslY~Z8Q($aKPoHbj8$t3vhcZ4xni~ zh~lvSEd|i0-1zwTs^t@bk(PkULIc?5OciHuZ>QIqQCrK)B_RQywo+&L)Bf<%TMcE? zHvg+`9v)Q#Wlbc6!9aQ+9(uq^m2xQj5kbd{!d*O4)w-#K#>NT&U|000A)p=ry1=1y zKF2&E!OjZ^PiwDP02t?KSJ*Vj{DdZL^3y$6Q>^Nj;|7pGpeXc5H@gr{ZC27cZ|>lH zqodPv*(#};Uq!jw2JU1zQ}|hr$fsVLsOD(05fKJ6C)5h!F^666c`dJ-Us@V|FFrr3 z=rY{`$J7sUS%>{$D47EQ4M*qMAdlU^rH>I&hrfGyIHiB9uKjXs!5QV(I? zrSaj?NLEati>w;{+Dk}2&Qimfp3J^!L~={t#g8R!=Hv2ntzQ!ct_0D-d)WU;ls7g= zo+;Jn<*FAh@kdpp*4d|7^YkN32go*l6?vs5HkSSRF2hgtbSyhZ00ui)p3pc4Ka6BJyvcf*oohcQrY_iZ!kKiR0tl_Wn5Nz{Cs3g2Z zN%I@{9ZuuvLq`n;Y#J;H*qA6pm?tB1ZP(La6VZy)+V7w3kL(9rn{Yxa@l^uQ|L?%~ zB7xdt^0j=fG)saw6g(QXq=9U;!2#h3cf-wxBF|&md8bAR(3V$Wxix^;P2l_w`sA># zRjE{aX6l9nlur^NL z0S&wZNB&;g+*w{j^brJeP1QTogNM}SYQW>isZU_;_1RZKfXm*BX&*9d%+WOON*GC? zj|A80)|NvHTpH{0EyZfT)bVAp+;L&2#y!%_Puxvgjm05H{3pxtfy5_Z9bf&v;a~!c zD{>t$tAS^|Q{B!t0mF$YxMWoqWWH@CswFpJEkaFV;tsN(-l|WieY%^P*SAV=3p0hl zX)*L}*o0YXUd8F5Y%&CojE)k8N@D0H-g}r?`l2~1&t^J(GCoZsEa~{lG_g5XfoO?s zpg^Y3+ax2;M8yViK~%OLm$eR|c~IMgvM@yv*297BSRdx9u({ZZUxa;<{(3F`7EP|B zWYNZ*a`~Bxr}b=$eV9vvP0Ud%6th)<;CjKy^>j48JvF8VvL^tiVq;XpTr3S9~07u_vjPWm;Vm5Am;S@Xi;X#l`czOIWSFxl7uKAR(a*i|y zO}9<`;TXSuPtA;G?KIo7)4ojV9;Oc`mFZZa)~~vZ1@RtGF_Isce|-y> z5{76DWAB>Mpgc8!_bF*e>QLnD@xd@O<6(NuZQhE>Tk75Uv zErIvAb|4Ccm-DH4SA?POeepA{Jkz*)QE|$5IVp#G&~kd#S%IYg@4qg#UY;8dU~?;x z3{+LHDxiAnM6j8w{#pf7OjTaR;VCP=lKD$7joN#&a*-COikS^ru0)&c0+y;HJqDcC zJmM%!=th+2y6Mt}zM#<(!Zdfu@gYe((GsVI4|FS}xAFVJF>78h{|s(#K5k zkI_78{11`_ppsUbc3_2d(M2smL=hxnWy*`DE%BE%YgW@P?-%RT7E3#6JtJ*B|LsaH z9RPo$%%qVRsFpD?eC2a7ytk{#+Ehc#xQhpy5}(L|KQAI80y|+J`fcgw&-qk@cNxGa z^-TPn6uSVQkdTXm;}I+A3W%SrVDdJF-3Kf6TbW_cU<&u{iNURp_aPr|d)DI?aysm1 zUI@c-u|elSjNCCuRXY)0f>o<0@>Xy*Gye7Kc;j9$k+%7tAlJqtr_G-~f3UA+Jn@7A z;M)U~>j)h13R$W|S0^pFhR2X=F^wLdOyLBAiT4=U?WNcr+Y_7E7S4OL=xP%+j=n?3; z{Aj?CizsYx1qG?`xqoFPr|9X_2;yW2Uu=*WK0Yt&GR_%u(z2Oig|c=YfZ87m{R%71b85-`sl%aM< z6>rrCAhH$EHCKD>KRujzZj7i2rKP2H{+2rKc07EhQ(JdSeY@tH+U9nGllC%f`00m{(bLizz2RoMxb(-MQz6g7gXPx z-BaNxFeQKJe`kUbkY;tZC!sxYvT=$YA0N>YWjp9$N>JMWB($TltziMg>=ErFp4k6v zM9|`#WnS!qoMnZSN6B?CX}U%YV{5Kwc0j`jME83?-XdH0 zjRz+p2$S@xAKM_cV(vT!nn*!G!DJpA;#VQolP%Zz3wRhM3BNMpNF=CIT^p~(8Gm3F z7CmT<<@zo&66IxauJI|+`?~R9kLUfi6z`X@ING>{-`?~6h%8CwU%`qjQGWj9`qM&O z9san;fPke*{wRXlD>`Rqp~fy3=STZMh{k|@b@Ax*UV=P){ITPOha#S*rGEd`{8qcj zj8~$B9NKE_$1qnOPTa)33eh0FFdr-vzgObAPMe{KOqKg^Sh<|-_TXV0)wP~K07~X= ziXt(7@XtDXhsKkq(C&1M^-zsu{`+$m3k$1&qU;N2f;^}5q9nuA%W~lwM;^+XwM{jt zUDjwL0doAX)ixL=t)BA*8bl$!qopXJD7cPsZ;*RrbZ$fu`!h-8ws{f}sG(_R3S|lZdLC>m^HQaI_G4uq3DAF~rW4*WFFm4ZZlDU(4A+qS zYLJm2Q9A8L6ZBg56L4Vy+-gje1zHU833_dg_2|~xQPeIOZP&nd954wAzTNT$v?1ox zyzpD!riJyx1E|_pMtj0j_JXg5gIaw!z<5MooVJ1Ze`b3Ny;()*KdAZ)8MB zkle^n$FtFy43gwi9ibsH9?KRJx~zE<1ul1)r$7FrpKQK6_u9J~?XS`<&8Yt^rD08& zj{A9*@TaSc#2r-(thdfuF1b&eSSSR&T9gRuzIyL(%8Z8u!PN>ojpe&m)w=(A9@oji z?Cllik}W0x#Q=5qR-)T+`E*1Y%>%7T&eSI-Pe3>opLQ}fq#n5- zx@3d;n4BoVFeGkBz}2eh@Jm(YB`I1si;vzw0$C%P@Hbca2S~gCC2h~}rL_9_mKyOL>`vwb^W;i`hzkqF*S{S{) zlP!_z=dbrA18{RvSc~jPB7<;_Uw-YE`c>=wGW7soCc@1zr^fy4;z{OhCFcUo0iHj^ z>4gk6FQ{98=WDWQJkXP*=k!T@J-6NSm4HR+ie31yW|(a*M%6u|vBOu-yk?1(zTTQ> zGeHVPl-MCZ&BgAB=R$)O^OIZFVbQg3y=#^7mVg^$3#=r7N`yK*-YmoP;fk`kq5Oe) zb)VVyHsSvUibmTHJB<_YfmHI{4L5e`yde`avgQT)qA93gocJ9NT#hgH7-#)1BuoQS z6qzmza_8%d=4E+U2#5YLy|yL~V*Vx&#n`JJt$KArui|O4lKv1D1l>TR`ZfnTscXAB z$%wiJQMJR=gy0oX{EOHQpLV5Nj+(bQy$?Yp`XgkCA8}H(E05nFJvuyW)Ykop$v5Z2 z-9zPy|MKO_^+vY0uVtv5F~yGCuJi8?awAp+#3~4=-x4sprm&iq$y$%EUK~1JNOO=& zYH4}Qy?mbK`!^GlU2F@^JPIJ)SWidNWE|WeL}IPltSb`1#V2c(YSeGo8n9OnY79-) zDpl%y$jOnIG{^*i`>X9ksKXGH0L>CWxF9Hg=qr4U+KmV?v{tcl1GMGwes|4A7_}kTAu%6%J?|X}DUc z_SF=aDT`)np{vzGYmeQBt41I60W(F*o3h--&@&Nqz77%p~pIP%jyDB&1xKKvdIT4E$+0o>i~m#27!>Nl$f)_?vqg_Jl%PY3_UhTz0-RtIHd&@jlE z0VkX}j5%Y6wNujBtf-`f{_&}{u?v3v7#?s3kQf8dWAy%^;9lR_%JV++^o4m=@g2V! z^L-&fLF8@5LV|C^jV~D4HyDxzLdCPoHt-1uI6;O0?+rX03kV1Vtg$&DsAu!n#O5RU zW>;mdi+~q=xsyc2Vx>O;`CyRjQP>`~6C**0gmDN@`cNa(A`r;XuTC_)a!_FHUB~Y_za;Z0fgqSSuInZu z8@ypXJNym777{7**Z@+IdcdH349MglBK7=QsDYrfi7RDleVSngyb49l>3X?zs4vqA z25$}8>4|puZrxVIH5i!jx=s}{v@CR?DBr^pl6&SNj%Mfdtq zh!elR{he=qGF56QIaKCE%Q^4)`8nbgRAi!mn>c2Ts`+VKx*=$M-hYCy9Wb*(tDuSs zMEEcSNd`Ytin{I^uqhS@V$G;2!Lx|GYnVGg_-NJY42%iXS+dz#3&p?ACv2QXF}|I@W3WT1Nuak1gyV^Zpwm)DylChPY$W9blqrv`ms{fR~%rMu&Z~3OrQPUi9tU-4L3s@j)a|RUA5H|Xz!xv$n zVuenjZ{DxYJdZd(noB~|2D*t|%he0f2swu|ftM9GR-6-A`KfZnl7?$rXNL z*ZEHYh|QIPh6ZsW0kY*Z_wop7tS%XOt=zl>qA(!m8H9!=W3LeMzXEn2M@nt7!dWDk z+JjspPw~$9ta6UFxwW;dB#+%>#cL!^3(_k^Gi4Gj5gn(*vv1(JO%}A2$$0VWUXfNh z6cXrGL9o3dBlh=3(`FSOL>XIwk&G!p9_PTs8?9^M>8WE;_hQIy*CMWMD9teLhsUjM z$dU?GtE&eBO90fAh8s_{vegS?WHXB*N4ng7uk@G@2rw!Z@ zx1bgXDo2%BCyuy?cn#a9f>=6R!19E&X( z^NTC8NL8V*rV3h#WTBotVFgcz%+dQ9yGwZ7FpcULPOhn^kS1x56S{PO6*dDF>1w6L;OG;=!@=0JZ6{L3my)HTr3gX4E`(?BV@|D{yr`a}?c{X9) zGP;RV;LLB>X)mub>v{ky9-g@rGLDNJpe|)uqXw$}CoKSIjXwtml|XIh{pL?W8e-^> z{fw^z$H6{sn*fSzAaf-5AMsP=>3sE?Kb=D!B+Tp}V+Cb+0lMz)?&+AdM)}l)M?y>e z1G({_#|*Kb#}o$7f0&+4yN*;iyTugD1(QZ`_>JLAc5&(P1X7K1P$nv{p3wEib=Gg~ z>S(1)H$)T_T0a)cvc~M-ESymCiHcz9i`e+-9O{-i_$622q@ApVmhy^xZd}Oau%0F1 z-A)qd=Kj+og2>Yu#`my1yjMuq26wJshQo;^;lr5q4xqrhkgmZ6y=c`GYkBKGK?u;X zMhkRlUG*;7hqOD|`EDX$Y{Dzo9)?(_4hq5i1c)t5#vDXtF{2idYs{K{*K!+Q{GB-Y zKG7l#(Sv|OFKKgqjD$Vkq3p^>0{o!rBU-Zu~La75-V2^$JqKb=Hmdwk=AmT z@6-`phaV2bFlQyYPx07CE)KIcp!3^xXNG4i3hfKDerHR!r=D#$OYzm4lGAOVew1ik z8ei++ar@j|UcfBNV=MUj(WO?gH*?!o=Rxk09e3h($q90T$~Hb|ID?oIi2c@zJ=bbK zc~E{J0T)R431obvz`ll;$c)5HKu>P~Ztou+rz~-y%pf5k?!OXkLKxfugg4YD#PU92 z_?#NaNena#oW+@eh0e*#i*OHM_nyy7b1;J_8+@y(&4!*Ws+WJp5c~ltRNya!NFZG> zd?S6~cI!n8Gw)gRJpVUd%e82qt4^hsRzs;P--qpIvEwA+?3w_X67-;)92~S^9n-`u z8D`pXKm4EOEUe!5=8ZAFSml$7awyfNPgl-iE*rPKlSFcKnEI^D)RVubJurAbecLA( zLi(ZQqKtHbn!CTABle#&fQpctmp5o+4RK~J6cv{(0u^G?6?PLQ45w}iE5!F=T3*78 z3o*HXKewI@v^pW$eQ>wWdOM2P+dCtT>aPPqB#VRn(+&opZA%-*ts##dS(Z0@kOiCc zIKL76q+NUiHxLrb9TKPOosqjB-iKr#fe|9elpM4zT5shUp(z=wVcNDBtJj2gCHIsZ2EU zKU#pWu5hw_a4{!#g}2IESqYIDdENod)jv(9brTNew@>4iiS077YYo`Y8S*4wFuop8 z^38dYK;M|-C(b@1e82+-7!A@-fx(Due{s_Kn^qTDn56%m{uQo;kYa7PO+oy|@1xV7 z+uQl-h0s_DY*ut286)t#*Pwh^LYfFD0nuh#8GuEOh#XOYWpwpe>Mob_`=qOQq!m!} zt1SA6;V7#=Sxqa{E(X~YA^-d(xC#K;UI3c{ffxa%7m+(5I-rh@4&V#xUcWD_Z~lEa zox*93g=nOYmsIG8$JS~1GLV#Ako0TMIN!SXqjJ#+He8@#cV`?(y|U!oyq8sEWP&S5 z4_xkujKh76OejJ$@UV`4r?=QX?T9N2te}7o01A{VPjJh z3_q?de;BzsI$+w4HFnTt)8&Q93JI>^QCb3@Nsf9U2Q=N_%=5QN-Q;`DHo?{u2J%Vg z8TW}B;a$mGme&wa3g!s7Q^gdt*I#Y10F=58M)+2z^Lpqd{_8wI{14Puy2tm>j65wb zrg&2@1fhg2ZADdR3y_l)aVo+%r`TXuF~EivSdNiMy@5GBqWq+?&8i{L!Z26Yq_#`n zy5B^G=a2l2)>ZQ!RWeJf5FMGg^l2-u3H#6G<`xCn%h*^b#2()ULlP@XZoql986E- zL21Q5c}+h<=1yC7mKgl2{Jf^|*i=f=h=tjMk^R@2wpL#>&V(hHxjW-iG* z+g^Cn)f1B}Laokg{`VSDQZIhg=s0gw$lFd{MgO886+E*^!50m(nt1Q+&>UdAg{_BB z-VqVY;M2REQ}n)QE5jD-Y0%Xz?h^fX78$qttMS#B z^1j_vRUiOGAM?^1tn4q20u_RFi6>?Gs}zT7e{N=W{tJFEUl}~1x?f1;xsK78H)O() zmS0+p*Woe}5mw@FnIniB7^}7z%Pf&{$Bgs2QojXPrx5y>M=bS&dT$hnQ729JED&in zTm3u+VpRh|8(Oq#{%SbLfu%U<=4*Kj$7-zXf3peX1`z+`nNke8&(`_|*~D;^Hl-8= zVkF34ovuY9Q6@ing+v{qAchASZjs^Vc#)qF>LjR#Ao4qeaSz*Tdn3pcJvDVNHJ^2W zcuO|ObO%_dcVM##0QpEdL=b@7c39UcopBKlPSzEdh7`uljL1(|7Spw`1b|Ef&n_~B z!}PugE)GXQng{cfQsI+33&C{We{WO7F)X0{d#jqh-HVGbA0JcjqSBzF2#+85_2+qR z!|pG~B_7aYkG?kgN-=jMOYfekX82nLDY`6<)Kv+bzt&&z`vW-{%JuDqvYP25P07in z$4iqiHDf-zD0Xv|>EBEY3wS=U$FPu+<>Ch;TlaWX=2r~UJc{Y6pJj3lXsK{HvRX6M%O06BCTKUF|RfuAz{^qmB&(g-Nl3uRfS3Tk0IpKA62e!aFgra!5%O*Y|;znMaA_XsY_ z2)p;COL8~Wzs~L-`XLZ*z}E9-*2qOEup!?fjzP}Ca=KQDE*8=abC_{24-F+fEYu6Qn*}Do?Kra5_3UVmQ(+~$V)@V8G|(6ymazr#Ix>;tXWOKz7QoaC!i9O> zNX#pDU~=s3<5tor_$8t*GtxMHn*L++3ohgb4RRVWeJUyvZ(cGS@n&j1Q9|?V`tnc0 zV3I`;|-%P2!u*YmChjH?PkN;Y;qz44iK1Y z`(}plUjtR0I<>J|m%*;;h+@{2NUv~Bg z?)>znE5yt*dVFy2?R_u0-}i8HB(^>=HwbJbF0+KE+kf+;z^Mi%lo1+5SlyvD+(g(R zibjttk`o6kP2H*Ru_!2ALQ`Nq7R|g%6CHlie=0U#IhzR?A@0RZ~C#RTy5NwT4 zh%2Pwm;vHux+ZQEt|>WI>gspMqa354r>AEi#@T%V6FKnBW}jZ1UUIy>+6+`D(;;e> zn=(|gGb3lr8niTT!WD&S$jp1`yG5Q&zGzlvMiJvaVsCHrPSn)8$;KWl+d0#dyw$>! zAP+8R=zYHcEeXD{3P<2zJcpgGRR+CilT7rVK3H-Agy}hO`WfF=8a4};4-7UPV zDACQLaE!fhbgdu_>tWC5+nQ<&;XiZ|!AWeOQEN}gqZALMJYP|6PJkVg1Xl`b--m(t z219FI4+{zxS^hr;za4Dl*iS>Nx$p(TRbyhrsvJS<4TgbOob&T#Y3a_hrK3|R4MBVXb!*eMz0^R?rLe>+)#qi8WdAz%7qgfbl*FsJ3L+Ej=ZMb2c{*wym1}3 z0Bq{5QiS!d_AoQid$b2(Z9Lv_1}sh{Pu}$+a5j?IHJ-hlc8t1d=UV)0_G7HY?I_~+ zn#CkhcRBF+Nc8s$WwoiV;x+3rkbjM_s1p!Rc%Qei^*5*SsMqaBxj=7O+)Qj*A3iZL zt-$bI^|Ms>y2NZ|T!MkeYMK!*(p8!1RwXKSPc_v{d*K+Te>KEbbwogQH4=E^|}0*bAynWWh`cTy~LV0>MNbE z{{O;77C_>7?kfh_Q}|Hi>EU`3pi`=WeX$$58)u>R;ROiBKwv9ku=qqxYD_bZ!Q;E- zlh~IV_oS52k{T};Il#)v9G5V_XykW3cU5;cllWcKpVl+#vvT5Af68NWwfWf#)lsdl z(8*WJ#&!Ch{$3-M9{ekVeUDve{Jz}_79Do;!GZD(O0kR|z1XiGJwolsr1n!x*Gjcb z-giqFu(YkAgdOM5#*Z>9kxTXtM6nBvK2zSo4Kix`%z;nUbK^~A{^q_*+b8k#xoxtP zQJ{5;a*2aX>vdylAiMTa0j-F)W4Y?uiiD$r=!+$|DGQkWz|_x8bzrv#@!1#$h?k)Z zgN~mqi6rq$#usj?aJAkQ%-BO4lM01m!>WnmzAZ%w@;mmfvI$iXBLvTzMWBMzH zJq7xs6GQl;-mIeNJAG_ZsfzBgBcwRNW(7s9a>NO-7EdB+q5{(bH41(b@C-3dTlPqo zYt;>38}fp*NcHjw!=__d$(Z9f1|0t{Y0t993YdRf4QPwDs0tLnqgJu6sc9t9SKHZj z!BY^X!Xtc17`SmHxCw3-s5g?`c=GdEf$Edbu~a^ZN*^7FD_AR(RH;~eZ{gkkCyn2=*JNwj z*BPt$j>&Y>&U|B2ou^8nm-h7%F?ZZjE?Mnp`^7DkLYvizGsCSJtNC8{v)aHBj4o{s zOA13ZPD`Be#N9Nm%V_n|YazktTYHXx9S2gLzI6Bh! zb`CRVX+NAyId?0|>Y)_&3~qi{b+<(6OM4isF;6+q5ZU3dPIbpo53Z_z`2PN5Ub&x+ zXJ`5Imeqn`kXHF7{6{FDrXg%jb8}SGI04c!J5OTcy_tY6l@l1ED0dS!Bocpv_ifqM-avXE&#Jyxo!cT-EQ-c7l8tqq2PxM~2YzGF8W0L9a{fhE8|i z5*QuTKQCZS8W2C%F4cxRZp77a*ldLP`DKsZ;Jn4VO1I13p627rV<#R08Zd7 z(U7)7A4g>T*g43g3)$}`R`Sx9j}Cp6^5Kz-^#!n49djcCc4Be zucRCFK9>h_D)C7a^J`0s=W2ebw12`Ft6Y~e(T^D*+8q}7^vdJ(s6#e+#wRn>f0`0K zAfVc%ffYqMOAeMr@tLK26TnbJc<8dGn=RBlfw6M`QYWn7Cm2 zKkV2un;%E5LGWky7=wd?01SaN%ty>YwRPDa1N}7Z^mnT3d=shuxqk6X^Gg!-jU@e- zIkCtTd*@0K;}t?ub?%KPSUrpnQTpPQmKF9D4=e23Ya{OsBoilxh0Y9ayE8=pnMqWf zX8JHn|I)dfU1*wXWEa6x>+{7!7&!C92MjsVHC^djx$%YkT|4s(yLBaw(5!~fr9$gg%x5O zm-x-9u8#~M7Bhx3Bk~3~DNIKP+Q5;I~ zAj-rwHwT*Zq!Qqc;e{ll|Q~gFugfE_|Gs=$*RE2s)YWaT@1`4XmAg1`>yMWB_RT_Uk8n< zrcsfR4cZmZu=nnDzso1mMg;;mRU*_JF)W>P2h|v=8D@fJ8ltxeXnTJwL|av5H%;pC zIagioY-ZrkfeV%r8Wm`-3Ehzn82S`3bhe)>D z&3+06PnNgUU3u3}UPl^n3~-Bm*&vBf`c^r^uk$GM!uu@<`O0oYj z%k#wUXYj!}M%RqdeCNgO=y&HZ?~-%k{sd(`&`O@keXi-BzWr0?z>esx=E;umy39jW z(l9P_u0Mez+<2qbLaHdH8{h6zOqN@4N#8e8tkGRAR#*4{U4!b5bi?=lvM-f$_VKcD zG14NJtqj{;FP(1Jb;M2Hy6we%->5Z-e7Pb_5eN766V6;=r+}!a>!XGHG)qBb3W*=A zVpvK>q&JDB&ehy{ri^(fZd$H9TtDIMwo_io%tVD0H5#j1xKKGF!ZutH! zaj~+5%HIwHET37TIb77uPCKE`sS-vfF-)(Y2!AOj5{s)XyVdDqX_LOeUPoZk1=6rz zJpy^@O7>m*j^nG=f^0B>I**zXYUtOET4v){tn*Pf>%TcY*&Dlq^}2QUF6p07uFdCg zBRq83Xa69-Fj(|GA-V zhtSOvUjN6}Y#*3h3p#qV^XQMXBikkX_E1Id82Vs+O6G?*-ZDlqD!MC{d@ubnQGZ|Y zW_1+>c_~3Y=MJNJF25zuwMc@X#A<$*q1f#Lm%QbX`LU>JnoTL-rW^`tuEE!X;Luh)W2g+h<&I- z*RdaA-6HBC!~EzWqd&u?=klfkb<+*y3^R0ebiI{NhK2fqTlwHN&)5Fmm0jMw_-FUs z@-D@i?e>np^LAxWE=Tv_-<`v}okOowRK%=UVR3hFFX1xo%2(hhgMZU+(lv32~>HE(=)_O4Sh_0w%7{DN(;X0hfiA!Gl5oD~Gv zvW{RU=J)U4l9zn%a6C{K(QvZzaii9~F#Sk7Ayllp+xM|Jeb~i2OCP0^tSt@2CrxP! zVlEiWawv|fdyX(h#gBiw7isP=o)TH9a;C--3*;Itu0-WHa!kcv$z+X&t|Jp~xly4X zro6=6yXTLN*Ju^BO$C}6WQjvSxenVLIq8z@QKyzW*eO^(E7tFC03WezW&hXnAQ_BI zcSNO-I;9+ZV^@v8fbWD89{O;*gG@oLS~?zW5<6 zF3u*u-+Hg zV;3&{92yUtTb;LI#UJX6$`v8*lV;CiU}aTLbUHg0&nt?_K=V9H2{ftfVHqMH^@^BH zfq50VqB$Vv-1=4F8`~>D9rn!vHkLi*O;a^;obmk$C&k>g(=Au;SNlR{IQD6Ci}y3U zi7zBB&oHK;eu;@RnR@@3N=fZ{cASQqf7$&UxhtV0m^=1;PCpik9<>nLw>&OJ+50Z! zC$SlA?FEi!zaUf84w{)FKIdI81x?bKvK0%ANakW}@5Rj zsK`pZG=6tB)T8bV@7Len4ZdC5C)cA&r-B-6%WEDph15S|$f7?ws(pOM&dBA3E%!*{ z{-SH;;=6W96U_$o-6EIS&F3y1!DtrQG4$r^isnSWxWpn)qHvqaBw0mO8`Z3wxWX%3 zR|woquL%bmVarEO4$Gu}^Nt_Z&K@3i?{-|;NjdYJoSyXpGf`z+US-D|K3g7*VcJ^` zrlMt1N2YAbD4Gwnp6X~Mt2zDTlqnp39krUKIt^372(wB4e z-RK@_#`Sc^fb&Obli~hRbBq+wF^twW8cNr*ZVxJ-k$SBaF(|SUOnYP5Y5n*3J3||P zC9>T7!PUSe+2GTIx!LpriKd{Tqh~qNcd|0ZKVk3jWCb*qIk|V=_jF3@V?$=F$hghH zArjb>i#J~%T#5zWZ3mbj?T;5bn1sD}VP9>C8CMW}+K0Y09K<_+A`)R^q@cKU^sXKj zII{KMxlK3ix{tR6rRqjYzFPDJ@*646Sy)BE0meeRm&rnZMo%&f2KQr-lOd0{5s+0a z9;HBnlY&Z3u3Sr=@fET5feCGW=7pE=3-#H2Z+qn6K+wj=k*HFIarQL1Gb{wfJrFEQ zMxZ?3yo|rm@mDc+d0g{URbl*HJJrD|+NrB*oWaYxUU4$O;&Ek*>qh052XSgBDWhZ4 zW-z7S-`)D#dDnEpaP@Yk?(&=ZM3d9_pk#;2tF34^&aC0JWUeP+aSnD}sJG>50+>os zCSB&ulTiDbF&=H^14q|y2OniSbImHb^6!!<=gT&C->8$ir?(ML*{ug8>7>&*}75Eb?Li3>f>9redV=^ znv*9Ry_Cu50GyH2@hSe4YQvPZTSryNU4qws}oLqbIc6c_qk$O@BtF^{k^zot-@K(lQX-$7m$v<=mGsK0TL|{P#G0_QUqVMM z-{i&w{)rZ<_&;0#Or^?CCoh<%e{Ov2-Y}9gx{_@_F??UmXUNj&v@+o7bSBl#tgGp+ z$4ha4&HguFAg-=q<`GH{B ziSc8WL3~aQY9@62Fh0j-H?}xkCEsOm*Q3TbPr!&nVEq__=F~Bp!I(A6c$42G8UQo0 zzlj79#R?8Ns4F(hIeF3q(h+en9F)oqIcy?+?=0KL$6jqc^mc;V%oLSHZtZEhZf&D zboKA=2WB&zFED!5@~%`ajjKKKoV_0TE$xb-nPd0V{u+_H!|J8H2h1W8B7U3mtJ?QZ zr&a2IYpMKBHa!WnW;PyQEz8>R*ttS#J-oMWdxCnhez*#9NXCA@^BaNul4s1bh-HhK z{rlQAfZ4U&%7Aj)FYqO$8b)v@zE4!C#mc+bCTsEj=l7AGemw4^T3i%-&M&=7p4m^V z*84n=#@3ws90S85BR2 zpwF}-oWaX;x2AIn=K|}XHYt(th}Jy{;aJN(s8N6JHuhmB|(F ztK=6I_rCduVbG$Kn+H{Z?G+-a>B;7Ncc~c;qBD3<# z#q?c*pszh!MTeUwwmC9pq+v|Yo;?cy;#Nlmw_3Bu_(v%qV7Hw}d&_X%ha_G$1@ zvvN6Ew(XlqY^WHx41%YHw3oIefAOhagN5`qKEyd1VO(wd(L=mU?g{usmi6%A!pmz_culQRCT1&)m!%4w}&ThtBbBw zpKwp>F=b9>+lHtJVIEDeDE0WM+`u;!$4D3}+o+cA^aMK;a@tkKHr-bDcKcfHb0S%7 zyIhG$WHH*(2&})>qKUs1L6v7(ey7g(YXx@*BO~59a>cGi;u_L zTTV}cpP=_vAN7iUjW4c}vTt)fiM-jy7-bm*)OCb_iv{9#dUiGwlI?0S)L~2vr2m!u zHSx`pyL=5t!Wpn(CH}n9z?TjAgQKWS=eLUI1cKl1UO%BHwils4=S(>en6~o8qmU)D zw#_{;MLqDku!YvIzORcYr}ygP4*VP>jupqIM>XFyPg0xFnSOy@>7!JEC!vw}>X;9VMlpMKT8_k#X;@VLr_@4J7D-wL{|@ z_7w^YW=JOIm5j2Ezs(<%aA8kKF~fN(-Q}RxN2$jC>`cS8`r<1-(r1_z+P1_eWezT0 zyMXDMKK=QbNxW19hH-;xU3`2}I3i&v$fC@$cOz&wI=mIz@j*UuFIz!lRkggA`cB8})4qQDMh^J7kUHz%8$q_?k3(Oj(^pPD z_c6UQzH@nq{&4TVpBtVrzdEb9LHMr=JRzx(;4&&1!3%lfQv0%OMNLf&q=Ud4_7sEl z|G{>(#pqu7XliPzxtp7oQp11o@c;gLygDkDeijYavyL}EqwIejO2fb&HT)YqjxN?u z^2~ccw(3 z?7v6meT{UF0{Mx1&&K}fpq1lbP9R4@(!n2Q9>aofPED$KB@HFjQZ9S0#YmSY88|F^ z&6;T_IFWQ6XW;K~ESsGF{~z_&1($~NE!yNi#V#wy4XkVrAo@mUPh{m3tzS$XMVpW- z=Gm)Mjzc!eT@iPuBMZw;2%`MIPwL;l{Zf>-S98AG#@8$OXjn*bSO^x~@j{$!R+Zet ztqtJ&<5+wt?Wx0->QCNCD)&?@c{jAXzp^$cERJ->Kr~Qmn^<-R=xcNZeha{>5pEtI z3!%b&T}AE3n^zd~MV^!VipH+oQpa-9xYNP#TRAQU#fh?C7@^Gsl*)JIIkfWD2A<;d zP{B~1WyL)BBcop7O^mXK839R{ZxEB%X&_6n)y-LiYHp z3~#pbS-H9Kl`|G{U_@o|ISAxPw74np+xW7Ezj@IsYKP~RvKPSmQu*ll|7xicy5eG$ zG?gL;6_);vC`Wq7tN8O@^n-WfV#t>)e7X=M;XKlb<}M=}@qu-5BgE-ie3S>J16 z=5IL&V6!}o$v({m8{w=<*Wr87z2(LGMPGPP`8uB;9Xn55tBC7>rpth`Y-Is0{3;|P zz)E@M0h}`GR1_pP2nWT*h;&Y|(UFT$2xBMZElz?F2a4%k_{e%C&rz;sGr|OxLqhrY zxy;kp}5)pVqcFZ#b`fx}jXj;YqFtoMq@2;S!?hrl!v4!hgW-akf_HwE|-l#=$zi z8-r);ke0Mtv&Mi^Uj}>9TyW!ugLG zmzzv^vtDphzBI6SvFJR?46l}4aj!Xxy<)3`^s9SgU*yx{mBZ%f^+TY5q3k&#H@W+r z|3#OeXy&}NH>cIk>3oFP3y#g}wjI2+M`(5Xf^qYYS_;Dy;vZD4IIDChSgSb;z~Wc! zR-q*;{q@O$lA>Py^Py?a|J3q*BUiYG*A}CbeV6*HXBxfIodtn=>lXSN-UIn897-zG zes(q?>xblh1Wy^@Uc*iqBOctF1eN?F#XH&wEpEWbkR(Q9LGuPf$ZeFAsP0BZU}VKc z8y0ITjSnv;*p6UM!WE6>vo*T9Wpw4t_+^=>&CP4}Y5$^xHa8_=iVNhw{7DzGFeXcY z+}R7>J4@WSB;N`m1v`?OKRM_gAC=4z{fjsx@=hbpGL7@T!LO#l5i`_01OJRc!^}w(2SsMHw8`iBH8C|$ z-}yyc<^yV4qaQAM7oQ?azDTKH(L9yQ9L*el@4AJj3DY3c$bE7}1$BzZ=LE`2mPQvd zc9h}@&&vW`WW+(6I|0oQax~>>*`YG zN>s^Itb(|$Hr(z`$KB(nSJV%$T{D@7oM5Rw^VF!j3gYRQ_CYD(kdWf&c0ks*>A}Yh zCY~l8-zrv|Ov}`Ug%F_8(h?d2(24Uh5zn|>ji~p>o+@Vn*d-;9msc+1K&q34ctpyG2}U z&bi`Zi*!oXj=a$|^Dur^BUVN^ZA*DpR-NmlH<<<)b%nou`}8RA$W+!&DM9s_U2#Zp zh^2V%x6xcX%C|WyTxm8WDCy#2(mPk`%LMssV{DjjV2nZgrY(jMFMKuy5>B?(+ew#r z6eqNmMq8skBDg?he~5Gy^yF85FHi$QF0~YImYk#h{EgXi}lXtV^CHJa@u%9DIBjOs;PyDF3?+$VYsy_96SxZ z?g|H>^C#_fJm?mBuUZ#RwO7zNvG+VAXkd!@<$D%YH2m5R3JjF}mY)=$SkPpZY}QY@ zT>A)X6V^617l(zQTY+4lHvD7x5^)>fy68I&0^mY|Zxj@)=F}=k0B*lLxGu+la~AS+ zOd^$IwV_XD2T&NoR_gb(Q_3fX{$-1taQGfXDZYGE0bzQZgQHs&tvYazWyU}K_prh< z;;aqY-QPUWLkfdePi)I*?5MdiG=P|TyXby9He`JN_A|a$5!Z`oI3VzZF9ME}qt7iU zEc|6|js=c6jIe}gzByDov+Y3F|D)~^_PHZsr>Lv2)xlt-ny-)SWVXvC@3t(`OP+KZ zhT!Nho(W(SI7>9pbuwc>qH7Zz`;ZI&rFTZhgO*KALPDaUm6}3PT0%lS{E!%zTJ|&KB>PvAc+?B3#DMu5X4#W2j|LT~{vELoZCg}qirP38;oMKCqmwhyw{-FxX}>R*Fht)QeNH!ZvXBnp4H2T6*L5Wg)(EDAs5 zjDo1L?(_S~+By`%fevRrjyrkmNK7U=V<=g`ci&g%gvAiHk3;XM+i{q5T*BaJC*a#dD%zFPVjNmR6L{ z_HC~varr#&lpkeO4%uyfL+2FFJXs+WX)?Kvy5j4|y!i8>f)`cZ-n*Hw9|Ud6M|*mNT}w2}*AIQW)ZhlcnhxrsgwJJhNBu64p+D%u z`Di>)qz*&c5U8{OKPnCpp`97Ap_241Q-ymsBGk&*=~_a25w>#0U<=|ol4k!MObPm) zD*Pi7OikrUbL7`!VyVtKRd!Kl6}N}wD``o+?fHaU!% z;b3-7kh3boio?e;=n$YHb;kHss8^2nQgI$OXFbSY_7vxcj7!d};=UoXzE%rLiYhRc zrsUR-!JQ&%`?MPfp&n|=k7YPh@Z1{r^6W#b$A!`b8-KqM{kiQIYDzr(!Ciu0twU)< zSbR-nUgZM1XXi!D?97fIb=cE;9%4ItmixaJWzac_4OYsPrlUO-jxVj_SR_KPdPI(C z%fGuS)XH;(CfoX#1WjaF&LLY^nS#T^tGa5HxASv`Hke6;E;=xaUA`R)9AICwNe&gf zoKT1A$XPLt$gg#a&8f+aR-$06`%m&!dcO$mHgooH^C@w_6GXTcLI||p-pIp*)+;3~ zt+j&N(*%8Z-DUd;x&kl@GOn82Ga$`S%2`Nt728ylNKBBFWr zF?TxG!GllUba5@9UHw`8>T)y*EB_Uy;%m8vT(s=$dz;BEy^&@o=g6NA4r-&= z*!kB=clVq{(m$5rFT9=Z!G0Hf|nux`r*q<)C>%Z$f5@#$%CkiKmvga*f5FGDLOM# z&jYhCz}~Sa9OO20@_r)}y)HwuC)##NB{`MRYBI>Ew z>_wg2atB(WHaX=@!**zZmE-1a#=sN?mQP{m1EX?67r5-a;wXCnexZ>)tN59RGU9MP zLpV{RK%rVM*SKilk-u1!0=c43*~@zzBp2nrV;(#ei-LYhf>MC+JQ@oTWy^+b@a)Yf z{#KHE!`eL*e%3GFz9pS_QkH$=V%R--Uj0IId|mgu8y`llXVl!Oa}YE!)BIouWj<66 zR9-c&%=SsQ%AwMub zI5X)YYSvUMY)%c(EvGQbWl;{v;rN)*U+M6i@n4+|4@k*A zP2kookU8c!bNHu;;q+jh7yE$fMEFCp+kEXwM(*X{Tif1bynp%C$Z{WUE*0Oonl90O zEBNGc+1`QZ-M=aCG;<314NeiPtcAZ1y;`YHGz6%zM9E?Zj z5k>nN%%7R6d#A6E-3YjiD0`gB#5d5N=r{R!CEX=!gS8vPVHs*Nnd4!Z`G)CZ9<$@+ zc|>&%c7XWN?Q6JZE8F6T6Lhp>eOSx>n3+2m%z!Y>zg7@V6L1O*ODSVmd!de5sfVZ- z!uV;o@^&Ve%S?ZFe{*xemO@cZyFzUVt_;m~khPBw_4F=)YS5+8b;Qcu3?=!cSd{e_f~GyWb%d08xMdocr^A!) z8|dT%#i5QGX9(%ipiaUdCXLM_Ab?|SgDWc+ zK1&{vgQuvBJs&A^SSd3L`QewusTcGA)&9sv>A9L1MDD@N1Z@Gg|fM{~6}07C)(5jSOON(w;T z(wni-d{R=cb2w5^U9fkr4cY~o$U-E$%=T63d;+O+X_%@yJH3;00{l!Q#2f>NgIfc8EOwcjP;#8oh|=DD}#8r%am zTS^7PKS9$8HM+7f%W#^)M>r0ksQyPcrZw+$kGfa)IPOZE|5x=u$I(^6P1x2+CJUVo zvCI*l+1?MTk2}S#*j$FGuP{~WiC*8k+Opp#^&@ay#SHVbJ)UvuoEm8U)QL>c6m2|luPfkeyEk9P{Yp7%YemJk~;vMT0F^D z85nFqYfGab-WCtKE1sq;oj*;xrptmiy)j-?8q)h#$Y0Pv5-RYt9C;w;3i>SV1lF~G z_YD5`!r}C(bW>)}*ccrGzax8tBsg~eut5Y@NA_La=^jCJ*i5Qzd=7FN@gQdaHTl=k zmJ=^T;0PI83@1QA($ok7yL0!l4#*KboZYy_VdQQHt7JrN<9y0ENvI4KA9MbmG&D@yIR;p)+px)WST z*U@fU+YxCZnEze*=n$9xcy$tNnc_eb=LM{x(GCkK1LUd&0(7^v+ow;Dr(qd7db6gs ziRg)5$(N7|mjG|Ab{zE>o!oW%7W)E`Vn$^75yRLQGDqgpCmYd^#>`&~0&67X%&6D+ zdvk^F?Ap4wW}cki)U`z(UY^*%V(O&NUQm{ingtRkA z<>pV^y*XRywlF{1(U+-jGR^<|sH0Yqr>ojuWtaJSa`@+I4qIMCeP72-h-{}5K>&T~ zeo!OoaEIZgr?|<~-!K_SC2VYLATX0_S`Gmq9@qVFF(fT5(aZ&uuA9-I%Tov2d(<@V z5M63065wlKy&J9<1Y2aU^$Ai^ps~1no*-f=*3$fUcC`U*ikK-w7)QLBrT;!92EnZ0bcoh~ zG??wRQX!hQJ}~e=)=f{UUEhO}ku-RD35bY%g&wqadV?%VVkf0>bqlguhQCm!yOX<87;d?dy==WCrSgtS!Ifo&M5f?S3h)9xU zt{9s#x!~g|x}mC~z2dM;)SDgvMZK>1WR=LRps?VI);kX!PF z1PIIMGK+`}4M^yr{R80z0bfBCs;to!cUYi?00s({tFTcT0D{W@7H>g1e2$gZ7av&~ zhy7eD8=J7AB2Fac!2W+L-&~YLQ11;>cS74Y?iUfv($G{y5jm4-CmL5fd;HHNI0{d! zQGz#^5KJGC1j49XacoY4^9IUII*+An&k1K5K|#ATr8?u-k%9ly(GM-e7evjz2X`17 zl+E6dOh80!6PBKkNVjfn=X9Q`r9R%F^lKaVp?x{^xW%E!Rjn-&rTMnxirHRoN8x3{ zUk5y>w2&OxV#(Rrot~@ZV2}dwfBg{I&pkpDpCso-i_;AYfd+E0@|#a!!UKH_rY2&R z`b--i80P?{y4m4=&g}3&v<~d5?W)CDI132^mhWZ35d@h!#D5#KYsElpb9y)R&71ZC z3JCT98b5)s4=)I$vJl#s!k)9MKW+0m+=Mpd-5_lO;zZ;aW>+KXjdAR*aG7I6T1IN?nj?_!VVX^Jh+A8l@mhuYgpSq;7xZf^j^Kl{OT^7*Iva-rk zt6kBiO;MQH77RMPF-xi?a-7hUu2=cR{gpZO860!HuQ0l>mb%7B{OvLk5#l6{oG`>m z1GJ*C6-mg_m;_I$-laA^eE?mdgtzXATEvyvV*-eTgB<2T@N~e90XAh}UO4Db4JR37 zTy1G3pCUp1(^*`%AMPC+yr+H!Q-X*xz8x1bDnBy0Gyr|H#h|F!<| z;Th^J->@(ffiHs;ig<(_{muP&_~5a2DTR;Q$niU)U9s01(Gf+QY0k+mB!a`*cujb! znqy+Z&s@^%(&S0D_+D>{FpOfEr4I(91x#Gey>)ckRPGU5Z^UYiyo<}WFNC~3Gs7rH zf(+E4r-4(3sMIzdjFd0HJI)#Y{g8&M96r}LB=F7Ki6DHMcu8ibHeidH0dW;WI8cmu zXW-;R69a1p+M$cSfF8h)Y+hef=7W~#wVjy$9Z6o92e6qAN4NVEjKnr_5?Js7BU%x+Py2=5S-Y9ggP`@|$H#TR zwTh0eJZ(N4bP^d9A_A|<`!}Z_gCvnDec{Z(S$i5m0fCTgyW5dU%y@2Z&ZQMuP_wbp zlS;7)JE`@_S8|i978qV-@iw`5@g+xOi1pQWWhnf|qAnK^7@+viI1o6bSs%*FSB^uw z2vKx&1wtl*?x&?)aHsG1>}A4O^0+DJ*iRaiz5dCn!1mP}Ro;d-qHlb~3*LAT)Hn-D zOKTL_Rf6zcrq3^YIJQ7JMAYGoT#uPD7q4{ir=em|oX`Nl!Um#Mru)F;3mlE#p5o9A z)y@5zV|hTZb_XdFcaZkNqC}e_z=Et29w;2jF;FUJI2d?=Y{~B}K;MN_2Z$y}l z{naK2pEV9x3WMWU(|m*&v03Rao>w66n10rk#tv`}7fY<{1fGgYY zosC3_|2w-D1%OIJB?R)4)Hc|7SII-CKXusJstKa|&f$!B`Yq;fEH!*6m@OYI`AMTp zvZaSDeB45}9Ut(E3CWj?w0fB+T`c+76n^u@RhJ?t6~qNP5g9ko*Fj?G-k`G#s18PT z2^u<9(`YCB9Z(=fga&~a23bBEvj$sMg0DqjtzK6berHBCYI^$lP%@29hS`s^QL`X8 zzlcct!mb-Kz$n#oH%Ufn2O**MZ=TG=%RBxTs0c2Atiuyv${w46w95}D<|UiGrNYW) z#5ATD_|il5B62v;IWW4=M6 zAX@yHSr<@;tnYI?{Ox$4^tQD zwQ0zX+#4WMo6NC$;=t98dPZp!S|6Dshju1Al0RZQMP7Brg|6~hYgRtrU8m*m)QylOC z;`vnLEN&95QP390s+#iVjTItx2&{^w`mak%cBY~YG9St~2+R(Kl2cMskrZM93fsV5 z{X32hx@I!^4^8dXzC+)2v-U?T{PPPy_MHt=+Zq6JLg0q_5D_kPG&?keKp>8YXae^J zR3~C%Z$R05RmxG4XXG24Fg8w3gdmfbmX>4816{m1 zb$8hRMrx~`B51oc+i?vIHK14Tm9(7TnUr_oN^eO+aE5V^9oL#SSsz%eC?QJ!_T1W&BSS7xam~vL+jcl&v7dLYC)&u!l77TaYU< z;e|9VlgGGXp|*8WUCepOa~&^4atzZF4ab!$(W&es7&MfR7TxEf4*LwhcPnBzJ#L%T z2caC1!-jA0>$a+a+r42iX!dHv)!wL74@y`__;7ANK`{(#wTNO8{9+Ujj6cJWAB4$h zGZ)R%Y-*@4v1XBhT~m_|CyWj7l#^N1sNWF{+C8SGrayauK#?f_;ai$3_B3SqoCI9d z7eAEhRM1}+G@qRlJKy$f>0-O`-BO(#jHC2+B8SnRcQ<>kE0Y4dwQR)$luyCNmB*#kxd8Y)D+W5b%-lxal3=XtaLwtY*H$JgUm1OkF~f66IbbtBYi`1^JYUOg zEco;o+qKUT3H=B>*M6y8V+5Ok7s1Ai%%%h<8hf$vheyT5-DJ@+{R2yQ(4zkW3cr<; z6Vh~0u2x(E9c^Hp3P?(-)fuxz<~W%p#I1||52>}Vg+K;EQhbD!Z`bEorVpof#SX$B zyhl>wb_MrT_5|a~sMOOO-K)iVe-&Pj5X;=9Q~cJ=Rv&l4^>``OyBf1WQh{f@|#UR-_fMK}|W=3nA z5&3t}Bx*p)RZx||MPq$nHyPSoQ2zo48c@q>tMLTl^FMYDyiFvhgWT5!q&nF8Mj#F+ zC+_t?q_u4vgZ|Jy4NmpU%tO=H`ntLZgw!v-!tFWSX&HO$a1C~$d#EfpBju@W-M@+T zQ`-H0E*~4g{@rpyS2kZ#YxY_2p=gRMA&zXJ9GXdWLbr>uZrfqzR!pzWrUR2|@~V9P z9N)dHhXS5OdboH}!6m$_GUW}F9X#(r<_v*5AUTi2Z9gb7t#9I!@v z`W3_jA;-dhPEc6a7Ur%{7{ZlXi|RpST%cBh*)*c04r5J#zXlr{yFpL^mOV|^_w-WZmC?J?aEaKZqyP()1)>7f&VUj;N7pmP9hJ)98x znaR^6`8E6hfexVZfRGh6+bBN-nQr?ldAYd#)wIkC?_$cN@#Irf*fOER# z*@cvfxX@@_=`bO;0DuC!*jF$zb#R1Qso(N*nKJvRSAq!RJOZJ(e-#qkrX=WB(&IIy zQxTm*u@Ji5$bj0G_X&Ia6@tfM)0p)~p_fSUNB ztXrvvX)@@1O}Yq*iFHC=lbeDYwfUiCUm{9;lh1UgB6-lI7U^&y6(R7{Ke>OG6X|5L zpj%LIiA6nwtqe2MVW9}J&9@%Fm${*OK`sW@(qxoXx$>kn4dp%{hl?0G>@7cN>4viT z2Iv;6)EV0Z1iTRi9I)M8jjqEd=ys`I4~7Ev-C=gt`nVZ8jhGW68b|;5UA_Kv2p@=7 z1c)Y(N`du@AM!*<9U?QtHH(TAs{||SxA83IAl&xV%LFixcAG+#2fHxrt|NVNaw=4oGkvKc;C<1GCmb~#?7L+fS&b^W9W z%3h0yq7dzLdz3uP;aRWHGH{syE)Vi{gKUU2^8&7C>x(ye!3X|{$`^CMTz?*~2g|_C z<^z|ysm`%o1uZ6BVRDnj!4b#3!L?dz-fljSseXXq0YGNRT+HTr4=QkoP9mA+E5YCs zVY}okm13Pb6#um4O_NZZ5~I;JoWe|Epx#hsra_ z!Vi3U?{#i~FMLJ2%*|KNWmTMZ0{n@$P3ndgI!j#zFJODZ<0G z>KkFjgLYL~!j2`;D`G%Z$u4%d=Hnugjwn|J%<#(eLR5gYQ#h_*kA>c7S`Umy#9uM4 zEg2gT$_st;)~CliHZWC_)h36L7ofITrvVpa_J0#_-vgxF4Gt>yd+oJ;@b>h8K=W)? z4E#$L3_dHz@qrW;PxGDyf@&dPLC`^^+1oRqmnH$Z97Jm#fsfnFp)?{gzU_Cuqbu`J z4wt?iA`5&g`YIi`4Ap{V)cw?h2E`6Yl{2yk(A44Mqngo9E} z7!JS?Ni1pu*|~62Q3Sr?D`rVFbL4e!DywnM&3S8YkRQVlxl}CyAVeGs43;+A)~DYn zY2PNn0m$}@Uz6!n$4|IjLF`e(DK+M*&_coUB_*0_#1U`W>X3uP(1>+N1^Gi&Zdzg(dM`Xw+>nPD;sdG zMg*22tiX^yWw+_{S-`=);0}nC6^&|@&X|2H@Yi5>5YPiie1HfbpM4!l6^L;)&a+~d z$;il%bjXPJ@#J8o4*3hbt3VX(Y~~{LWt&965rWztM(t3_FwX3698x@?` znEgLEth9dZMXls|^u|kymfpjDN`ebua^Yg_fa+IG;<2%^qE-;J6P;kuRzYvOck2!i z>8N*jIN8{sI4S6_eO$kGvYKa|!2OJGD}v0rBpS0`l#Jp8f+$GP3<>pBTI%ZdRk|Hq z3W6O&s#s-Wq87i16!>ffE_@ZbohlPhnoK8`KHA!qA*=~u-w*Nl3;sBZe>i0d1#)oL% zhY!yvYC|HU4vUpR%V)=Ap?8c{z)!W_YX#=2P%)H`wzJ$Tlt(3l%E*IC2m`vVR zZGWVZQS0&YRd{b>>eZHj>CsS~e(W0qXhZ7(y zPCobZ7NbMH$4!i`r2;-gy7-?|bO75OPn*3j$1;l%QqjyFPYWdTcJPnFKS<4b4pH-x zR{1-Je6q|NvGUAQB7MwAqm)ncGs5~j*XviW_&{tIfK4D3ErK~Y8^^~D9IDeO zj1RF}%ABRi=+#wj!?-As?Zk;AW9YYVFkR>gZy-suzp*El=}FXDZFHE<_a{pPe`oYLUE#+Bnp z{aJue;gBLNg7_G)5clKlQB3Hkub0Nci<{RGmWIBj0aIv(>+Naqlmd8v_&14S>`i9% zdqYAQSUa6=rTkuO<6c@>Z^xCeYwkbH3-t;_3~yXhaqvQY{krk&Nng6C(T4-5hjK^W zVP532D0d6U)6P!#T=LKCfB*}8dBrOLg?cwQw|J+gq&x(P2gJwa2rF|c2AXY>|!Vya*fgFUv=#3#^-r9we2`3S7LM29wdtA&i`&5HZ z>-%EOK}6TGg*;iO!Wkn{!Lo1_?W1&MXB;^_{~e;BFL-SOO0z~lgfWViNQ>9F6>FT| zDao=v|1CsZ-p9%ygz{?WfT{#e?1M%#rYqggjDL1Lc{86OVPk6xWw1kacYAxg^euNl zp@6dQQoAN*ow*1`3F99WnQmVZzeV_a+wVJ>zN2$4H_g*;yMYsHH54)aO_^RF`M1Gf zpveTi8z|yBrB;inF4_jD57;9gZk>D0UQraCQ1SOV7qi4pEj!*hi9ZgKk*_=H6tBSf zSDD% z4S{dPLlF&M{0&im@w$G|mEs5_^!OclH<-Yy?9G(&ce-ZuDJuT^%C_%RITTcIdEotO z2rSH+%*Nza+xYm5MK-ZnBt%pdCggxF#|PutSjR@I*KWo|_nl}Yne#wC)#%P!StsKZvLn$jVx zRE}G%Pc_}v7D9jSM9zCu0j+&jO)82LfHaW~*L)pw)UeHQm^O;N035}BjokML>XYigP>AU@DO0d{mWoNzC!KN{6_;B~EDyU^HvM4L%>QwsD3*E9$i4eNT*HkAeo3o<_c|?^pAUdA#^h}ha z4np}jNp@WtH1;!A`+C0kH^x2z@k-}SNp?a7V9UiO+#h=NE!WJQtd?0d8B z4GTI)8Hjd&+v0}#CKFDE3l%5p%6C^#V}puJoBYaSOPKh)8;kf(C~TPjC|34v79Uq* zh{PmyOkV0amLQU!RI#c{UlcX)vRP@eRH$PYI87O2bjb8@GE8ZovJ@(|yN9TeSy2y0 zJ!;K-=+UT9I(R!KPE|Mb#rK%JTgqwA{t{@{n)sa2)YN3ow<;Wju~y7H4bw}$0pGM? zI|L4V79&j-Km44^wMi~+0q-{%`_*c{^G}o>eRN_FVfUa8vr8QOQ+1Vw=3L~!cfU`} zIV7!N_Gg`VtY$NQIEj>=acy;cz(o--UAr&ys-p_O+G6ukISXzWK12LJ{7$355)CZB zyKz>gg{dcg=Xt($|2)an@*_-(=BePe-2F2NLd9SFP!e=e)t`U7c>G!2i z=l8Fv$P`+)fk3QIe48j5zk7*P#W7A2my_B-2npvAtpt!ljVbKus=n_8{Xg$RlRXH# ziq)%bqI+-5m}HDP!@5})*B;{a*?Aw*(5;>-ulWP{ki}Fg#ZOu3u08!E z^0}4QbnZ%c>o+T2$Jwj!DgT!L=jMeyX)Al}U?RI$$=IX%?jd};57r?9@`*|34<7Vm zOmm&HxMcUAbUTaUPv23&H!xfe=kP;7@Xwe)Hs**hpq%8v?o z91=0AbdIC`B~3w>x3_QY9q8az%N#>Nv($pd-g;VFndHRx<02nFWw4g{*_bid`asup^CqJ_Sr$>qzfS5i`BMFsAD$rt&^da zXqdpK^`VG<){!2pSZ^Ag0cDzTt#3j5?=9tncNR58%;hS%nF$qcoX}kH>rxm<79E8qN=89{ci5~pF=1Uy&BbWGuCUq$-Yy+*ugdO03|>2L&mZjI0jAuRSX{@vpPBci_{l za~}DOH>P(Fo|}~Rjea73miy$-J+9~S$-^p~Hx3ShQilGV`9E9$ZKX`kp@5SazcMCG zrY)we^Ak-~bZ?TZ^A`@-N1s#3Gh1tg_Zq&vA2xK(lj$N_nl3C)}Y%Xlx9gN1_3}@fq`(Vb#UkW}GbYc$+$XeUF-=DW@O*BF`!3%O4ya z4K(3?I~{%fPoFSK=hBkbOS>3()heyKl2uyXe!iFFD^Yqkgl7(DxL>`qIraFoQ&Ku@ zC|DT$ed4o9Zc?;>*;)LSwM?Pd%>NKOGv}zENrE^hdO6 z-Oi*um%!B+80e}YIf%uQULumCrm*yqk4?O8SN3v4+WE(Q*7=mI>pdQuba90DlMKx! zu8SvfP2~5y?tWdZm(N~trJhyZ&rbXM?R(#FEXTPOhVMKUP`Uz#xA{G5^3Ip@a9bRyNQ`* zVNYB{Z=%m?FYmRY&aCdbnNC%pYCZ;uJ=|`+rg^!ye|t2$Xxb1XcWjy4T&jJ1arbmN zYW?jF(Zne)dii{nW8m?%Un`p3^XS}>H!Xp?LQQ}D_N~V^rK{#PD*|yFk0V!~$^>&) zfqt=xP9qTjp8~~%wvtc)mW)&ks}$+_9djMJ<;42PX-CuD)d_cyw%Pcks*=$Dv${W5JPo_{C*7j2pxWkqr2P#R%<8r8Z~&##SFzJMC(ZGr`Ke0n9;iW8D(D9#9aCtXG($KVv%RNfkx z9Sc1Zc56^3YWBLO$G-K$7ThX>+Ln{3f>wXc4V)EU)6`s}cL%vdFWTJq$T~jsop<_! zS=gQWe@=qS(Pvzla8iPz`JC@COy7xJYnjIYzvyaia(cbY&^g1_vK@H zzhH$Vlcu19cBtM}F4X};=0Trk#=il1R0FTc&dEUKNusCF$yA6_6=vwu{8p!EtjZ;G z@u%-K_+{B2%Y2Ua{~99~9z)70b;F@}h(ga%v79O%h2LbV_WzOfCg4=IZ`-#}DT*?N z3?XDpC9@ErP%@7p8A~YhkSUpmNQO)inTJdnmXLXtAwy=1%oY|F)_Yt%-}^l8^Z(Y? zeQ(>{oi^4wuk$?4`+8}*b@ z4T+c{xuAy0?^H=)pFYJ;185dqj$hA`c!l?rPiD_=i{+R295(VNYk@wkVk0?5Sl%e% z3)SpYgM#MG7C8b%mBoAVN1D^|yqWAIggDh&hyJ~L&dWJGnm~~U>}8cD-{!KFl}ngUM(eH*c(J~I z%}R1p_fI31?Tc8cMvmM^^0v`4zX)Bh?s)eLU+!9XER?Q)rk52z?T{THvwz}u|7*eL z?U?bmj%(QDTdt}q`p_kSh{NlkCAZoiFY>^}sIQDyz1Kz^3?6n(9-hN5Ngr{38`8KY zuliGF`exS~4^SbqG4GS$XT1-}omNM|TLWs6Vo>SutRx%GU< z{Dm^TE+b4b`Zq2O_p;@`*O|n`JKaBD75PgUJ4J%-TzP0}yv%pq_yY$??Z(lAPIpgz z{(Gr3(PV}$W6BiDpEbjK>D3PIYLdrVkWk4?O)G6=Hj%UYY~MM^W0<%j&<36^li39o z5YMCazT2zCM@J|tu$re^ZXin>otN4<~ZUSxSppHE#kbT>9~ z;rkBb`e}`v*WnXR61UgJm7uV;S7*N}ycZynxa*cJ)O15kPEmZa+l##*@PHzdkgy`n*Wt_Mu5nGHUOq9d)YPk-$d|Nq23R;Iw&- zQDx=H=s4Ej^XbA}x&sGFRo^idQ~R-{EBhR^gR91I4Z~?U_|)ZL5<9ngw?JF>Di0jy z#C)#LFv@6fok%!lyRO58zrci*MBrIm9sb&*xp?Cj`z+O?t11j1l)0{Fd!%W<&o`9D6zfKFxy~G$k3o7>f`bF12(XKw);q_QHhkDW+mMP-`)TiY-Z??y!qL3NL zKu7<(;dh}cHGVmV2e1lfymz$mmt`V)y#M-zmQe~1%Hdv?(OqR;gSk1PIq*Kn@@`kT zJ%LzakSz270S{KhE`|iStk4>O9qXy?+ab5qN-N?`xV7_qEFXIgRle5TCIhk0xqG#+ zltJ$b9a=4kWcS4+OzY840k0p>{FATS$+v^HhD@2>JQ6brYF#d9oIwM*#Ovt5b!H=) z9H#fkxVpKe1&MLYJ6*g_@uVkNva`E;?Qw*cnn}xags9VkjRNPM2%}mEkNfZaoI}fw z@x}}ElUTIp-28txfEd*{pH9UQHSxZ-|m7$eS5g?Vu`E}1%a3f0gv&P$Q2ldSO)j5fB zo7>oNcj=vHM6u6SK7C9bSV}G9_g9;K^i=~Mhcr;{555&SsALTnTia{U*E*ZQb@CcV z@0`}&&eJDofp1lBB(%9+E&a&7p!ZlYHz2EkR`YC6em@Z%UsMAT2L;zPlarZ3CG1)6 z*)2Ipa&D=*>?%pP3yFV@pDy zSliP_vmPh<*0?%{#ckEpkYKb#I`9FF?QbL+-*mrl^h{^NS?M7%N zjTFUq!DO>Q##)on!qC5CEyXB){!QNL+)<+|?PO6Q`q!VhXWmk_oI9bf=|)hJy_0E7 z!lB1+U8YxeZ1X&pzSnDxbpoX`zt8sTTEzOBUDw<^RBx^X9*YzEWcTx0;pE_uckeEl zgqP{>RX-NS#lGr1i@!o0GOQtYf0FP;nHq;&BuTr|@pCnG-fzVkf{Xjyu*2T_^KO0U z@YvCSF`VAA>z~>;JHFJiD{L!T*QjA}Kv()x7o}UO<%w0J2)#0&{vvm~W|fNL812Ia zQHgT*;9UH)cqsIt4BfBN{dq~{y&s$Fvb%f3Ww*3^^AEYl+a6ET(^dTZIr9KS>G3|s z7{1WJY%+Sx0REnLJGX;*&|cXoh$KZmV0&ao4l(C6iOLvC%%*aC_!*!1BrmFR(s zBfz-evp@Ah!2ctywVM&%QYGPwzlo*%__{Y9R|5;)+|<+;0>oEAZ3;S-ZkSw|*MTB$ zgB-s>UbCGkfc$?*d+@GXy#ZB4z`QC7^Aa5LyCs4FL~JLkXe z7T4P7XUp6fGFseRekqdN&YLnz8!WML^?LyNzWb#8%>Q&jT*RVdMGdI$>(=JA6voU4 zVmi(;-#^nLI)v2@ks{X(>nF^ol4Xdf`?+kKfzcFJvzt1tkqZY$Z1zRDAh)2e!WKg-5~9o!nNmd zY&T0O-@_iStiiF(vuFV2h*C0T%Nar?It8+bp$(o3k80am-#&ur$eCvrUp|gt*j)wq zqc^R4tFE-QI~%jM3Ef&Z9A(1x|25z{D9@fOZn58i#gxMjR!NjrHGXi&&g%=-lTS~;`{)BRmT_a>hu=%POoWA}X=+P* zK-%g{`?9BfNdM`Yno3cc%ev#VyJe<9`_0k0TV4*SAIv*wiP~waj5POoF&@Pit2g$W z)S!t_sZBZb`#ewXj7^px*(x46^<5!mwd)LLQc=#sV)|@thHasDvO3a#F;j98y`wLg z^~1%Z;%c|3x%e(TYHiEH(+}#kc5aK1uP3m4Zhk;GNRgp4>i&rP=Vj;dAK{n9U6$?} zx9^Xe&#PGG()9hfv}T zT^p5TG$`2U-olrG9~drYHIQ_j2}-uH=N0zgo*vy2fOs>bt>`#VX3_r31AH;@eaq){ zkp&uR0%-EiNVz73P369x=0ITQ(M<~#I!ZXkz|%*fUSX$GVdCL78|xa{dC$P>p}(sz z^LFLriT@f2K_hqbmE1NkT+Y~ZnEZL4ap{ebr95l5a%~~ssYywFazVnv+i}Zr9$ud4 zGxhWuzAT*E>|j9#-5Y3^eIh7)YiB7l>=6ZH=QcZt$AAFayIQU^z{o8d%?mk`y_UD4 z)Gx|w0`uzYxpQe$8LrcVIT^+xt%UugQ9kTyH@@+Xrngr{>5)iGQ=jiT8`B%Gp?j84 z(FctqIiaiPueeLWW$r-y*iB4!k$U-za?}?M%?x6`lgq+4!G-7~ps;KjDz@!$STFaP zLN=0}dqUy|sciV~T{2-i(cqv>dpI!nuncxjO+5q#-oKADrxGO$sqq!scx0vLCP0eo z`*wH4euj5dw@=$oGI^J5t0w(H{?daA8J8rdgTm`VCCO|Rw&r3%`R_xA=(!gzQWZ2= z8~V#;QcYrqtoggkyFx?_P@0r4AJAh`@4cMlFzU#uEw{NS6}mJX!QJF=FDHL z6W**fe2-Bx+74~U0#~M)_cpsQ)JevSrM0aSr9x?shEk4}2Wr;Vf z-{+AmUfGmi4bLu_L}L>N>O*CF$RisOjz2BRW_|C`Q?#0j$_X9TJutgWp$_Bl4d4XxRS&*hGkp$8 zo-S&zPevgO6Oz^#F1kP`g^BOkKx|sv9InZjB{lB^HP63~5daz7V~jw< zgn^*xB$x}X%v(G=bYxVb0xJ(aF`CD1=&mmk}yW?%31#0tR?(1a-hJt*Pp8)=5S*2=+h3_ zMEP?DFhL0*ZaG9EirB|Qa4V%g4GepTl*jvM*jt6MCF%8$E`q(BHWzS@Uqz{TZM{ES z2Tv~�JBuX%Jl_HjsHz<2_%`4Oe)a_ufnIQz8{x6j~JKy%LB-OLW?w5+;&d!CLG! z;-}0CBNlWP}AKzj(E#X)4 zC(YDY?SY}2*N(34!aOAv(THoZ-}Yw4C1bwyf-{do+a88@-6<|0V9*p$Gu!&6Qu@eZ zVuQqs;yT#rC$N)^@JTg;!{YtGz^`RFI8+C0!ybYN(z{6v!nnxfJbHL)BQm?Vv+oDS z-_*|hJ`?Mk!MnxeevwteA(Nt{weM`nO0JM|#)r%ey@i9=%ra4S(jU!nK9^hL<_W%0 z1#lW%`dLc%aj3bJ+U8O3YP01DFA5*7aCsxHgp+z~lFUo{0q;^znq;;wu!WmqF5D|R z(&g-1?i2zS56r$Iqz*~26VA+PQd?ZtI_`9zsc3c<$fEkz_J}IIC`Nvgs<3-B`OFoP zUi-5qtwBAa@kq2AbUM{@&tJ&8WVCd$Hs;=kiU-;Di5<~IJ)0sTRNr(o_lYWu&9g^+ z<{3-^I99GXK4o$c7yPx$TAsTiowoBgyfCt3&6uk;=lH^+=61xje4VSB^#l?3`LqVT ziE#IpH5c9th78HYFcZ79Qm06}Ucx-_?p~iCH9o9K^j2ndPSd>KIjrz;XC;fYVO)S_ z+=50gZKofnuj4i8Y2#h4pW}tWQz`1k7&FV z9gvdUVZHeRQu(l;38=vzt)ssUsQPWm{PaJwE75bdp(8zQETHI=UG;_>ncYa|;sRT% zW~W&-^L+N_+m3%Pp_)HOtj(0C9LA_HM9hhDerm?oPTw;)8cf*?6F8bK`3YV4f|@Pm zWSE7QzFyX1@D){gy!`X5;Efw{rMezxDqc*8fuNfJOe75GB**i}f?aoM5qFu3y0?e8 z#~aC|J8#!*o`dkSbMgBj#)rPhvyRxzkhIAf#QFr%-+4q~ru(57F>-*h2IjEh&TDfe z9sFis+9LOuB7y@Dr~(r&#_EW{&{smZ2>D{5#+bV8HG3P9ao$b~yLwdEO{#*D3Nfl9 zPqGZf#>Bc;9K;nM8MKH|9?svM09vC~#N^Q;wR=641Pg~|jsInFr_?eK>@>ZNKLrSf z+SSh>kqtzWR3U!*jfKSQB@Z~hXNKXCuG$&WM+~B^C83Bz8v@b&$-Va){Y_fQy*7vt zkLg$-0SY6IYFw?D?9P(f;g;x`{c)NZnlA3=<7emo=brR$UY_UgTIGgoq+%d9Xp%Bw z$24wsyYfELWBpmPG{10PmnJSzX>az#c165OXxM^OuuQE{=7UKp5r5EDR`d!Way zd`oLNUHv;5x!$XwZ|Q|JjBogGy<{2!reUY^L?uX{7vLDF+G`pdnM^Vz*cQUIE_e<4 zGkmaQ-Aq5LB9J;nXZrM&~Lf&>oSFeX8 z+a(*mkJGawWGVCQiec@Pr?_1kQx%DFGkbSa_1$~AOK(HGSf1oR*`Mzqp^9!`bFi9z za?+cqo!L@%e%Ei5Q|q@Bwju{5BYWwfmkF;Khss%QB-)xU>^bq_){DvD2xEK7k&5x7 z>H#E3g-w4PEjc@Ot)rFosJTgQNUWng({uZdIY$7!jJ6FkS@MoIVr zPuq`lfk=*rVJzX(*=*r+uhA(zwGpdVG)1eFMR&ff*6ek%9@}{lV~5sQ!_C4a97qMc zrZIa%n(o@$y|*PLySTHGd}I29gRU07uvf7JMXl}!a4qL^t>C1@omRla=m@dRqdTBa z)Zwq1yZ8ciV7U`-?UR#|5Tf$(4m1jE$I20{yaS{R>!_Jf zG97>^LDr^Ap4PBwAAYzj=_4yd>I<$tFdT!_w_6m==-xRaQr@ry;^8y(aGFti0X!Bn zc|7Jl3s2i^f_1myYLVl;Syw!6vIkfhpssqV+ic%**~0M@YT0mo23#sL0>?7~mC$D( z$WuHr|pyQo(Cl4nP`6}K{bBRNO za;GjiSpLDi_n);{B$;~z(#aRTUO7uBVH}C(Uft!Dp?KNUeD0UcEs3;`m)w25>lWz2 zYwwkif1#Ywk@udRe9&Cm{vT6}wd4BO14`~yrhXjqyi!E*osJeun9h>EM&4%|R%G9} z&_JorWwael8<)6zCDSB2IsyzK1Ijg4bIMoNzuL2FrSW59*#u_72?LD;-@Wzf+$$ zd@M7JW)WB16K`5IlMXNBm2(!j8d^}v6hiX#wA*oK^{srtz|}gY-;Nik9UinkEuM2L zukneZ`;gtz;Be}BMfCiW<=TkASH^e!4X|YqnUb}qFSZn)6DJG^v`YAbB;r^s*A)m(XNAc|05AxKBy4i4%|g!VP6kO6sGV zf!1L3QmZC+r!=1b;7>@Tfe7hfbCR{srY9ZwCQ@LKKv(B)!ro{A|h+ z&XF7bCo(CIY8M>_i}F)9OKW_1NaMNOh52}`@s9hus@`tTfg_rQnvmMMJ|!R7c3C_%S4?-WD>R3L8sbt*slGbs zbCxGDNSG0QG7q-@gLB{;x8VRT^th->p1Bozu15~!}2&- zq)SOio?qsGDVdq(XvV#jizQn#Tlg-nXsw}e=~W4ZfQ z6VwCu)i1`rw~>!F-)^URqiA*6^1*HXX8{zMQzfC)f!zr;9@98>yUflLipPh`sk^a6a;|0YmF{BfT(AG#c#uL!oJPr+?7 zZ~5sv+5a4_3tt};*%7sPiS1dpu-;N|TL04(k8(Pd{43JgWs_7DU15a5ljXU8?t21? zdgR*90 z@=MXK2-%!F#9US`9WbNBig ztv9Cpu%(V@)wMd@i*G|ouln2IAElcKd~Uj@gi`wq0%?qvT=nMAd=dd?3-e70j6Mfw z`{(j=JRTFC)y)he$Xh6TsY+<9GMSjvaKBJUQBT;&vSC3(BlGr0ZjG*0+dp-r6+*gh z#5VbDn$tRLnc7LTvedIhBpR2-HTIv#tiBk!Us8% zg5yxZ6A`N>8C5~FwHwkKHd)dslZRp2#pal+B`zPj5(D=)^Ka*6Z-L6Cv|B8M;YFnn zL~OrztCg|?GxreX2u5OghcqA(?1&(FcK=7&q>vq|MtaZ}F2&DVmte~KkY4_Ry0Sj!KsbJn8P8_V z_%HY!i02tGU`3#N3oELia^@_=%!^{j9l?JMMzeJsSkc)0i;{mrAo^`kG$z?MU)rtg z?(QZGxLt8(I0-FkLPtZMr4Fll!PQA_^HIHk*Cr`!@yN6ANEsQ76&P0A{%*eUo8%Wf z1u#>7*~Sr91VZC(X}kx53*&hz2b@{AA~eS*}_BgcpcA+NUKU z{)hV6u{(UOx?hH#)@BIp+Wwdn6m+AtjHSaNV_SKhJ1nc7lAbwCEj&w8SD=u}S@KRd zW}8}eq^J$odBZ!m{_cJAGx{s{d2MJh8SmeDjuwxk#K5hZheO@X>A_={i+qy)+kNVh zpOrLKlQNrhm7^`#tF8?AK9I}#cGSTweQJX}z8&#W$6Ens5p0>3`9bNe3Qr9Rj(AE; zt!%nm%1ZqHR_Ij^t>QE*0uT0>{2=S*@^lnVx#~w-AdbfIE`g3Dy;1m_`T)K~3M)QD0f~;QXPi_EbF?kY( z$a9Fb9pEYubVY5PHZKYzGZI!8*v6lu5(PWpi-+O*$_Pe(k3~7=85qb{xW0*1m)NK$ z@>nrrHUm3F&60{;$rTUA7Dx#0J6i@FUIVZFc`%!Q;L`^U_JFE*7}!0)u|og=A2t#~ zk4a9Yi=c$QAiI%HTMM>+ged^l?h{Wy=Z}~c5#3X{F+hU#Vs1T`U{wKWl|$YhM9FgBs;p-SYVYob<2*_HqS)13F1lum-9w&6`}A z*|&$IE=FHew>v*TXB7BB%IeEz;~R;tl@u-RwC<) zla!tF`jYQ=lvO~s2aC5XjW;hQD?o3nkm8f(QiRR%1Fp4zfdw^M@9&)v*{|d8m(uNN z)8F(pu!@$DJ798=Y9McyCZBenYLnfL%Y3kBD15PZ@9dBlrtvh=|R3eYkd4dBA{^c zXvwa0!snOW^ug)bJ@W6;E9;Y{=KM*{sW?fU`A(dlkY;0D4^7As-wtm-{VKh88{lw^fWog2R0=z8F3A=@)#?}84R?JW%m<)zPOs8Q9Zy$aj_)4_e+{3i zFmjffghjK#Y~*lC`j0CgZOwkgUbAK#rv8)kTp|8YEh>+fqz$p6Ap*v}=OsEX01G*?yBxi6o!ffpBTsi$;?toodhVH^3f z19nVqT% zL|0=kSZQAwW%|XYEBqi9ZJ;&kZ1jqI@PJ}RITnjrU;UOtL9n`XK40PaRO!1mo5U~N z_-!?Olkw4@vHisBVF0wi&I?AIPe|tw0S|(K1My)V1GefTAaLP=HO~W}h_Ks#TETuS z^^XIB$lH-+c-WS5cxHLH@br|0H0~0j7(%2L;M)PmLXjuVNoq4l?Pc>N3t0WYVDSL! z^E^CqLcrP*hr1?HEC70F6IvUzZ`hUgjwWF-LJ_uBgHeT>p-3u888|J-uL0(l7V$JA z{CHRJT8kow9oW+=0pcOD^Xu_*T?G%Q?o;j;4$lth+sy-?L)gw^mZ54c`o8T)n@Q|G z3>6HIH<|HKpfyLl;z%nIe2x~$u2+%27$JlBG&EuzQ*eyN$6IkqaC$%oJHq>L7MU=B zz!5IrcJ5d|<0ul4xo36`;3BxsS!OtHCcM&L!kUuz5Y<4>Fwp}@T zvc0DHvY#Mpqe|W}@?-#5crDI345ZV>3uZGlU%ijByk}1KNOm04e5BRS)Yy!4ez?o! zvd?2Q|NVcIbi5tdLR^+yT||VT)4W7gFJ(jPTg;ID$By0y?o>ooSING`%)g4Sd!VRN zKo!d+d*EwyTjo7HyXxk@Jlhn_-o2>kXg-%%h5vEd<>~OO0oJ>&<-I$$==Jh-n6xd~ zjyVxFU?1vr4$2>JEs!4u*ZHgk$Tc`IqNLHrDXq13xu?-DB_bJ9aHU=CSUchXKTck% zGyw?l<&ETGjiQfvs3?hV{5!aC$8c$vRNpS|ChLPZ9k0r0SGmXV zxp~rhd|#^ynrN<=;xF6Q4eI4tR`p)w+Z`rU7SKlx@-t^Btz!~v@AMkvw~AT1mmWU( zrWPB;bv^?{(|vnj;kc}Si=1s*JC@Vh-e;b8?v8r$_s0W81-g}7xT_}qtpwh>o5Lii zg{gSKU(F0<(9o_yHQyKR5bD2KCi^T?y}09vs^ao1F#;!sNo-pQ87ncYN+?dc&lWwy zgSu_}e*Efi%0V57{5vKsLS?O81IC&2&GF1U8{1%S^ z*IQl{HgFRV@Xc!G|?6uS6w3L5>UFYjvwZi3HFJ?NF@HSHV zvXGE8ntEJUF-t7xQ@VJ_l|g@UQNluGi_S_IrdZ(ijbWZ}x#4`Yg4S3*rz*DpRADI0 zVXjY~&N>vVFIGk*CoO}}q~HEXN7;J^wEFQK7VI38@9z2;#gOlaB#8W4)i)dZejMnI zUy}1UW_+;TRK|sm#Nu<73$-=tt{4yQ$`%%Qy1hZKr_mUle(uvL$14vRTYn<@ z?KHifh+3eH3F7K!{!Zi*g=^S~)*beLL2E75WG`FGls-Upfp?OaEqcKf;3it3{-zY; zB;j95L+PG1J!Gq)PrC{4R$~Qpgh1Eaq09}*DihydW9}L`vK+`8v#qGAs6fMXVO5RW zT;6aJ8>QZz%R@!@93^5+{Dh%_IB&{Ymd_^tE6B7W3$${zKHf@y)7GJ1I1Ki;n<}7i z4X%4b?I+nI$8G)`96_Gu#0y-(3jxXJed`zQgB*Wo(nHefVCt(^>3_@;4!3$ujqxM< zMx~Aqkshnc;}Tvuw|STJUYBIGWYFkZjb-deVQ3PK zg8eu=^5KKgs-@L6QNf~yO6DFL>NrW%_N2(=Q|FZ*g9tqbXBUR`792zUs$F|HwEkq( z#$Bmy^r~Ych z$@+i&$w!Fu>WPtIW{ehD#O%n~&LiKl3xVLHqMlX3D{_Moba(IL{Qs}8)*UT%w)&w? z8b;<3)7}~@>qc=PMG~M)wYp1IW=%a!E&BAcAbTWJPMjdjq6!Qn>^matW}q~CIvaJb z6pA@jkM1_bC05CZrFdbJGTDkauyBYNKMW7~Dxq(36laWnxIOkm2OFokFko2uiV0PT zF{|3m-#jLFHrahyh%%Zz)_sm4Z(hf;$ZSUrty8RINvp4=?(*eLHgHw@wHvo4zzRjN3vEF#7-eWX>d`e(_NwfClb_SpM9!*7p1I^q*y3T8%$p}jWkLQFlNn+wRx?6tQB z#eCy;^Um?{Nsv!sgYAoX<*=e2MT$qXiAL6c)Foa!95T@ldEf*0=Szo<@VVhG!OW9# zU5_Qj7E_Po++H^nJu73%4;-3x_8y>RJX<(vJan=$dXcf?OkGHRwKP*>QFBA#UvU$3 z4oAot$>HB}nyt7|^B3(T4>Zy0QLFuP| zf`(;LoAxaUyW|qP_S<8bR@Sv|GGhR%gmzWrM!Vt?80$zI#d?;g zSeyDL!sK=#@kKfaltyg*8;me{*1JaYH2 z5uaU??-dM|>=-}KM#~NM1cs!(szg&bHK3VM&A@tKY{fg zOw{l=JhW{WHZ8nRitAV82a>Vo{yP<*a(JL0rM{^Y{qOxv&zcT zx4~3;&iJ|i^s&cJ1s%8#f~ywhC-#gz7~gQjX}bFTXg~6wU;lqL^6>dZ=Z_cDDFBmv z34Jc~Y(TF90sk@a)cje+O&`Hvph6leze@Jm-kT=J$0j=cQOp`J8CX1}D!F=7)vdd9 z+10qY}bo|R{3Bc&ecu&Ul@=q)w#Bnj9i?tf466&;`;K{cIBUM~232q!&4 z_NUfp_8{oi3;eX<@mVicuS{>|3Fp&9-Ql;$HTlk49i0bFLG{`XiK~8&HOxt{<&4*L zl-Xte>E`L$sa}9}T}mI+OX?NE(PW=!{qS@=oB!RksJeR2zs_VvC7;6-t?QEYdB=sQ z2tiYH7X(0;V2<*Wp4^~*VLoj3BMS+PA#v}DkM;vF5-FS{oJywhlU{v}mX?+&-x>Ob ze+~F22(x~qrA$;g3f&kLcx9pc46~x}$Y0(1Pn-Hzjn!Z7MYW*Q?m?X#_ z`P^5JkpNFW+!7A=7W6Bji5Y*HVYbpjGNd#aFM$Y>8hR~ktWW=nZ;KD%Kgu-1_j>`?Ezs~8F8L-Wni+?i!@<21!h4tXxBn_t^E zGwvm15+_TqHwiUl$6M5B58Nyx*C1VSuuO0$<`?dTaS@vPRDuKU{zoH%F~e zPjLKI^s4F6(KzuiKz z;4UMuB94)tLx6WySx5MlTGwwJnx5FB-|oXNyQ?s(V-q)Tj1pdZ-+YhQwwHz2?*wDL z#r&EqU?X3wW;<}>HB$E2zyowz5Q;&wG z`#LtlP}8CkeSShkjt4iEt2N=Ms<~S1q`AI+?B(5(7IV!wnbfx?d$QK#%+&OMyo&9v zbO@oJa84vW{!*4Wn@*XNH{m23CZa(%yKs;ZGjg+$J%K3eOD_p16RUR0#}Inz{;soK zR-bjr(wigE9dcDPj4|(V1;zTZkhSH>E1#4#;d|#{#5ZutpZ(qVp&<)l2``Ze3ES;q z^H5fbi)__qH+NMRc6(O8?-vYm#>6$8uk7AJVa*WVm{p_lU?Uav zt0^N|{c3wZ$)5F)@bm1x*k=l(D~Pbbt=JHodV6W{OjutLEp3_C&-VoUX*KG-Ly=G! zMmJ_@TdKoJ`pA%**&%kTuvij@G4i6}iL)!))~fcxzaC=$8an%tT}j8lfY+=JXyc_G zqTHCPwK49rLa<}S&LgDsVAA&!m@8h5T! zylUwJQy6CiAR4U81e;@q+M)T6!sAc^LH!NitBNd6-1|jyb_x!yo0OdW6J4H z0KZ}HAe|{GGUIO@mDQAxkO;m079jRJNK^ltUOrRoOPRkkJGxN8xip?kgY!XGM`y8E zQMh@#sf};6;NkvNCBlbmvFgD6qI+w;4^)pnOM+UhUnhM?V?5J}V)(bTf4$CB=dNfF z(o@#G*!1)MK2&rBFg7r+3N{NV$+Bt(*1i|;81}a4xH&+OYVNs9xy|&SFBFb~=E2Yz zjMi6;?54|E60F37B2O!|ST#;u9ni^tBujCUHE~GIq(5~3^1!%T$L+nf=aUPNt6~9i zC1?Ofp@BbTD|N{It671<pDX3A8OPMs&TBeEb^u1kr;*yAMKH(6}5AucrxmO^!|xQhKP72}0>U4d~Y zm$aOnXzTQ2amc(8(IP?*VsZ+~erh$>_Qx*GHEXxiI2sjC&CwSZ7Fe~Amg*mG!>S)&t=AJNIg!f%(-1iQD>y~W(=!*)t;lQv_ z2ueW47RXND%6w&MncX=6-2N&^GXm|S4EIk2h>c9k5d;|&AC-q&9f;Hs=~22XPWj$p zx_p`M%yL7WXz-PCzy~2cKV)D7#H+|?IvQEf9}*}NR&wDF4<(>Sgf#JaJCt+(Ua3u2 zgYPh}44OPJAGj}DsfZFm1J7v&TKvpNvj)&nU_nOkhC!Ha@xnZu?>qk1gN9`Hql2A0 z_ar9_rJ&FGzg`iOo}pyJZg;N?S>G*4f8QP?*zY9!A>*!(>CbiT>dHN)omaxl_QZ0Z*?5H+fY5O9b6e<%%sYyq6vVPuUZpLq(0n1G z9aa6ve@6AXb9^<8diHB4ZwJ?2=jt10P`OrXYh}C5`|injNsZ7|tD_bBO{~Tywn=MT zYE2?(yn^pJv-i)uiH_Ckz~E)Wmt=HQjhY*K;ocEixHYTLu|d<}wX#h!fhJ0?n;jLS zJGcvZ^KbdzRk15&4)F&nZBh#IT=g;> zBF;ky%E*~!Zadi^=KAUt)yof^@*b12qK6=l3PI+9$j}Is8?Yz90+(?ZJ=8IAclnQ(gngvBt|&9a?eu>aZ%1d3){D`+2O7ITvA~F6T{F`XJ0nv;>y@ZYs&_NBDjoUS>+~vyOU7@6QsN zZa`v2k(Qp=TK0w|C8bkoB9n63(=nl1WM@(uE5^0*+xlsv!|*7>$Z-A>?Dhd_RqLnG z>*dYracQP?x{8jl9}&XS-vwe&c-@>lhM)1P<$hQod~tSd7@-6{G&NUPN- zKR$F{pf&~>c5$S|eX+X4`T5;s!WVv{W@URX(nO0BL`ueCCf9A$&&aB)AFnQW&z9o1 zM8mxof()STcp>dn-TBwF05yTJKKWLQ_hAd583F)iRTWC4|5XD~Y(!n_04$B9e#EX@S91nXV|J4L6yxucw+?tg_{iL#YfU5}lnNRd?QEa%j6!lHob z9zA5jaFE+-@y(`+RL?sP@gEi7O3VCumJeR6T9F@ol05K?pw4wy>^#eZT|AV`m-dg? z#NAc(Hg1`foUALX=+Vou$P5s1&)J)p-PLWxSd^9Qv?Q(`ODtBe)sPn?-YY(#g_~H> z4V|6YFB@*JXy3sVTZc}vE4j^dT+6J4UA79E;gHpH%7ARx_W@t{1=&2sgN3r7`d3?@ z&^-%HcBh(TV#WCCwk8A|8!e=}rqv{qhU*r}6rU8Ay(>OtHZGj~28OPX>_Pt~0wnd& ze8?-)$Q@MYrk~HnoX!0U^8f2^VVDK`3t~M$Y?C7JA&V@g`u$5Bq44GHfH^DA>=4*v zVvz_M;Ift`@9-9&jt_)h@YRb??yJJ_)B?m+BsP%N@YMy_qXOB_`x4~e3JD2;(?n2O z+W5mV02-eSd{Hsan<5Mlst_etjsyF9zsTOf;hBLi+p& zYgs~~6Ublse>M<`7npjkz;sXGe)VE{3gGJytrIekKu$+c8Gfay7((Q8fgtI@z?PN2 zVkeKHr>8ds@DGADLrzN6K`zSl#fyRm!;sIg@xNa#Gc06{>O~KYbzT)X%Czpaa?P5V zJy0oNBV(6Fp|b!ec1)yQGcRvafAyf6YPO<&e4G(3X^^u6 z%sGUh*=6Si=>hRO#fi0dzhbS)6i zl>e*#wxQa!e>LHlLA<<(-W;(WBAWtS|L-x{6We(% z!^U^bW8HmnwvqW*5Vww!wsY;!Z?7rWs9K&2F^ zzI8B+N=7K2aAYGtC=}*k{(*0_wN&$>PjYDXKZ|ZAHL}HDT`JdDqh#*nYXP5(*e9)6$HL1iT>J%I7|B5- zbu6_VwWGWzee@L(r#^Tw+Vm9^;pz&XJ>K^-JIKIg2Cz8}(|@ECL_)`X?m$ ziN9|4r}{gn$Gwn`E6VKG*5h;&tQL7)Ml;qb(~?hRx6#)$`#hi~Yl*Ze*hEWPb1t8T z&?R6pbVI8v;x-fZpwy|N@sNIc%%UfEQfk3`iTS;@H9mH$;=|@_afzD||J&7qx0iL6 zKDK=Jbmm}oulBGhCNqxR9vh9Ufm+IWHTZ#eLOZ!-iqM_>TO*tve*!0U|h`{hj~&IyAq;xshWPv zPzmFHFq)YEDFH@LqmaPKAXms_K~%hmy2f#}Y}ny=AB{nj+_2Ol%`X8j7tV7qPu3$a zS0>U0k?{R$6i%D~=#3*K=A$ z7r>aR*6VP4osf`qA9nO;0|BaEDMu?7|00tBiavhdg-Kw9u5ovDEIu)D7FO32xPS3> zwA202{cs&h0^qiu`X>hio1b#Dmx+l_T-|mi$jp$a1F$o99KIfV>Ylf!*Xv1n@b`aj zfg5}I0sRSSdT`OSTwN&j!Yt$V+akO>BfPfRU>G|IWd%HU3zeTEOh6V2MGJ+Z(DSdq zOcQi{2j4!sM&kd}>$*(P8EUqQl*%Qf1$$NXA{hT9&( ziaZ$4N2-s?+n#J!M67V*6GmU26kk3c)NAZ*Bd7NMRoU>CYvcr9&3&tL%9ICH&Q;(3 zoElV%N|~wP*w>$@cRJ^oV`Cc^d(fkdqsEMBGdG;?9<%;7GOH50zMOX1nUm&uh2)m? zs({vWyeH8`pC2EvsJpzbOf1B7)ianh)C;D>UHxNMaS;K(2;=*Iuo)hH-K*=~xff9Z z>EGUUh~2yiz+lUK5T+p#EX1RY2uQfjsIU^pDrd6uYyUl^l#rVK#@~N^5@%eqe6;?| z@yjU84Pl1 z@YuYM?+(&0r_jn_AEg+6OJbI#P@s{U1`n%W5Lz{@M42e_xC&dBA&A&)Z#I5w}u^Qi*zT@tZPX*WC1_cEPg>ORH z2dxj5a5G;PuKZ}yep<#&1D%@y>jr5%TrOD=f@1LKbVt#yxmD0 zsl;Cealu#hY?1UoI(K#MbHrrdiN5-sN|P(|A>G|4eP7NgQuO}fKV&eG3QH#*@-4pT ze}`nA#K@*?%Z8QgOVXmSsKByfVf|e?q7P(g?CJ~j)26=K*KFgysp85I@vI)1vgp%c@1);U?; zG?Occ%jP0GA**a2wRv$Yl@4nZU8vx@nqMpzWLf>&gC=jHw4zkKADFdcJ}jUdpI#>~ ze>!4j4)hBy(4+8Kh7Mf0sWdFNFzUaCzB6bU5dOUr0f@ z@ueKjaJsx46L19!aO*&X$XWS!cPLoCex*xO3Ea+HR^SpQ6Ydxh5p9FbSI)Om*3rH0+ro?tE~EsRf6L&9 z%dm@PpC>v1dnF?6L;{R}3=ZKmcWRAV^zKv118+?I2N|@Rs*n&#kUc@*Dp%0HFBiY* z84F!VH@qAFq3i=hT0+=QnO=V9Bt*7?%aI+S|C&Sj2E-T}q~X0^9NH3 zpC3h+L%(FsmVy|Gc81yw5ypc`v||!XMPzb$W#Au{1PLCXoDezaHF)!pdjlA`h4>x& zgq5OWXvUdV{zO`McKt^`;?T(i)uyCyjhboir{ws-PT^+0omUw1(G<#c@yBzCS<#-E z7_@W*2mwp!5_Rt7e!BQmb0&?x6yx|y!CJ@Wy548XbIlYaN*RPyM>)I$rB+M31caJ& zV(5&*rn3Q5GO9D}-FH2iqev(e<*EGr)!*1-!s1o?t~%OUd#%d8WX-&*9C=ap>pMbu z3Po9t$cuz0WKv1wG@101hN~2&6svp|ue9e;+Q%@AKHs;n5`W)yO<;^=^{J0hfR$a6 zEO%x|W+(xVvb!w@Bkk1gzJFC22^-@Nc?&`Voh&g&_i9_I??N%v%IE)J`&)^2kNmr= zQMAhUO@=y)++-ybTrA7f4E$z&86W-Hhg>CPs--jW$dpl$xjvv9RH7ITMCPwYQO3EcK zM0x)`Huw3_SoN=`Bnl)*qO&^CmbKG(Ns`{IA0OYu1cMF?=^C8!hx1Ezf~5dWl97Pcd`V`O%71| z54ZyeS{~=|TJJtcTG{!f&KMxV9PkZ+K-ifa0rDmSV*)=mAE0JW@Ztf) zz7!%$%un_$l%dwedQ7Q2ydtvHm@Yj>%N*Y)8r;7TBb!g8=uH?f3;zM6q7%p-N#*T1 zVR32+rw4&T3!PE}$Dw^^I5|4d<{(KWfJwXFa_|LU-IHih=2fErCc>6nRF;6G6De=~ zkJAN+!`K0`+c$wCkx&U<+u9n<8>L)=Dr_MME8@#@0gS^&)xh^i;0t!iDz(1<8E&$M zWVYQ7DYOFhB~qA<98D~AzZV_&2;t;{vJ9^PNN@abpm_!oz080y9}qD#TyT?Sz#|91$$sYv#uY_JMn=}ti0e_0>>J|E+|*s5*8bM`U)L$k z9a_!9UdX2DNgIs)@h0%kuX)#>p-=I49|Lwq{V$ByRI3HQbG8IU0P1z^3i-w?@5;2$ zflXYk{h9RHa%DsmrcTpJDk4WzMNrFYI>!@xLIJ!PTnTZ#heMJvny`FB$qeyD^m!=Z8mQBgBa+8O2>h8Ml zFU^Xj-J0>%16*IAjU>&x8Z6S=jgvUw9Z+YJn^maI}N zWl5w(4L=j=#BbSkCLaQu_$9^riVr?yv7;g|JDTZEZ2kWcm^xQn1TVhT zI$D-wUR2|$rqJVJ?O+@yA=Kpx;$dKx%UJkmY|;W(iD~bApJUIM^ja)|nE~`O6@f-AHcW)0x z`O3QI=+q;+H}r}qW$1o=nAxSUv@%XlA=BS3{dHalhJyObus~TfSy?o+ciVi@bhuI9 z7mY9@qGiSd4q~Uikhq3CyXqHI-mUuPR_CxK43HeCEpcZZnsi{;^vI?u|L;uMq!G~| zF93-E0NSJ_#Q(w13-?)JL3(>PsYN^^?h+sGm{-o59sy@h0CMUX1hnw|Mx#igp?z8I z!0Y^5RRF802~=s-dQ~71GE&kU4+BS_#vJx!Wdgc#>rclEbx%W)(o~j`+Bu|Y9soli zwbhe#IxoH@A?NzY;RX_CX#;G2wt#pt8gMjZCkSX20aQ11*rqKqLX*z7w0sDnPn?(6QD3-)^T_O+_lbM^l13cbbM@4B6Aa#V#<{XK7 z18ns&NTdzm>j}`)d<%^BR{#ePQbi6(eSv+CeHI}a3hkmC7}nz8 z;QR{_V+X%j&J{cx0Bwd5q|t!0-= zdyf1%V|I4(pLS@pOVAwEn^0Wi+T=4v-4stCbTrssHl$zZiL_8T!exOlb|BhZxn7;M z9~sC1{Cy3OBZpXm&Zr`1`d=%8^+BPWjilK+@|7UNr&M<8!AqnPzLR^chsPcMyU7#V zk!3m3vY~<$kb&~epC1kPbot&{>xHoV`C)eX!Q^VK=jVCL+poNXFGpkFUMf&uU0VL> z@49&x&*~grk_s4clK&%`1{Tg@kGKDYtt?Ja|Bp?ng!?_~GLZKIly^u`HPYGxsNvL! z5W}s<`HwMXlBX)iA*T}Ee{Q+Ykjsp=iT5uoae=5llnr3%C4eL>01CDhfMI9d1!VIj z06zXy$bbBB0ItKGJE+YAz#2BJ2j86m5o4i1I79^!LylxL{U=_s{8PfFy+$AXxv zKnl}O<7~wuZg2eogFjq_>nFe!-UamBPXK2-&}F^`rX)shfP4-l{|5=1M*5;iNlB9+ z^?;ZVn7d@S174AHWP6Jg$pbkUr>SLPk-)yK>$eUt$ul$5cw+YOOCKF5#R#_rY`{c6EOV`B0pi|g12M+!Da2TREQUtpVREsQG&W^&L2WJx@^U_4*#bz zqmJ96aB&0Rk76*9(;%^PIm*`2XWmo*TGeH1_wf%lvgq)AJbec2Zwq?k6lfNQ|5ot& zh}9E0^0DcD)hxk)cyYv~fg@3j9P!&SJu{XXb#62HThuTdBekatlLoHU7l1^m(8$Ot z{B#HMci!@%6)9HE#l&dtP%zvYA43-n^#|GV1i6qT*B_814y;pxc}$8Np(V0 z!=!HiAl)I7aEgH}l;e1d{=^3sRagf}`Dz)7?yKtI$oSIN_M998MzZ!*&MNu}5$@O7 z`_nXwk*40gbdf;%`N3R!9fdj^TE)qzy+W7-~V6*-&O+ydYxZ5z5hWX*?!S9H0rp* z@QgmE$t^Klj9avF-opD0)j~-j|LQr)&*SIjx_O4Yr^R`PhVw4+!c`90%MBetF!g-= zHq%xfYucmBi_Z7XkDD>NLpR5fSQhAzu6;aq-H^oImQLw_lc()R6&(o;#G~B!?EAq- zZ-q$K8V;*w2bepIa5u!q9+u8spRH&(#^Z_Y=QQmCAmAQpdz?DvdG5bui%0+J0>lyN zl1-|Ms%Ce%-T9IHD&zmPHTp~Zbd%yH!=7`VyO!+?P(Wwqv`gGCUG6&oI#MTxzRZuI>|)^;}!L+5r*Jhan0PeIU{b51dF@ z8IE&xrX&MZ2~}^Q{@zW75TCPt>c7QfosYk6E@FVBsKo=r>*dDe_-w&bV7mR$rz0K$ zLmmtN8T9~+^=*Kkwu{^|?`FI1o{w_xy*%-I1{@1pO`qR$B6oln9+ZNTx5EG{)o|su z>*VZ!N&?VO?WAg}|9ncjG6Lut09pO^yoUh^Iq_l#N*cXJD)?wj^g%$H!6~rINI?!ssewT#lDTQ(vuIsHa`Qpr zlAf#c6#Vw4eZCH<8V2y?;dC3wH;Rna@SE>g(`AF@U*zl|0rP-c99Tgi*Ja2As~zMi z0>C7H0$XcFBgeNu)FEK}3JOE+cabSOz)B66lp?u`BL?kA3rs!`f&$dKz~z1c1c77# z=LCftFH}KZ9@wJ+f-wMcf{6;GKfxFPF$gl!D<%IP1gtgg{+K-;h9D=f07&I_VNhbA z%Iv`bV2=3tk%t1xk9tWXM}NQ$Gm17Fkf2`zg!vB3| zV|DIs#sYI_r?qffB$RN!FCkoO9$uoNr%d6uCL2jNjz`DFNH1V%JSGG|GOeGXPfe zlyNK^pw&)>l5x!+>ZFr~**5Q!1Aqh#OnHR?tV)?a^UyCAwU`|3nm=JL3=fD0D6L?) z#C$^}gKYh92CL_B9&EdCr|I!G1SwTy^Fs_AF|%w0PsKJdG;CsN&UG=#3TJm=%Es!A z9m8%FQi}1ZsE%^>_RjI&e@s-@MEV>MACTPsqMyT%F|wuavPjmqB5mgk%J^20*;<4< zPTJwgy2YUoIQ^R;E^x%M{k%5)K6Ynn?U_Vp)ySDSph zp4nvu4$;n={0^hI^}IuzI){fEuLq_>bL2g7*GtxoZyBKPeHDTMtVXSXIYa?`p8Q*H zFDkIVllp-6woSk!aQrv$VSZytoS`+hvx7p3!+PJ9L+C*aQr9BU#FplmLx?^4#jft5 zUG^f7i#x=zZhYtzvotvrJ|w(fk;bp4^rJCOr2{Z^0k@$d90WXWK<)wo7+6REq?%Wp zy*zaGf-#l4^*-5j3DSyjbBZN)Ek<<2?$jA)jrvl#>2w~L_i4^cOw|$8wy{ImiO*;QnS-=fLs1ovjwE%Vb zd3iR#Is%|cr$G}|07bDmAd>>5mgG^2tfK*k3G>VE$6Sa9k*U={5C2@urR1W0bRqY# zs7GQ-Yet)w99i!o2SGINE(TLpqQUmfya!!9gY9*jYZiRO| z(pJx)m3436njQVOev^H(%Ix;0D-QrCca?Z0Q_)bBymj@M{Q7}UP;l6NP$FgV;Em65 z5cD8-`Ohb^+yPU`)_615yEni#CdIxPGN<-Zsi`^4$eX+v^dlXyQG$?SS-g7W(q1Bn zT_M!p1h=3|M-wEK6f}9uCjL&KTGH~$3hI`F!<%esOV!?+CmggH#tj4DY72)|`N}4( zrI>#FP)+s1EaUbiv6@=-*U<0LMX9Y0(H3O}E-eMCsUN+_zw=D%)X576+9q4bJ>?l+ zTjJ8_zEZV_b@49CP7&~O@(N5C8|B0a+ztACo@wm1ol+^0CYfW0X0z|jvid(%#1l@{wGgXJiC((lCu*g}C6!akkze|U z2jtb;G?sI9xbpV3@0X;Zd|j5x8dO6&%kG-lq-XC{uG%Oz@vuV%oZdUj*jul`^A!E4c7U<1jn^ z*fe)niBOZq93LA?D|V6IZZhKh((juF0X}&>xJnhgTW$a{+BX9lcm*hGi+K6HQ?e?z z3uk3eL8Z>gz2aXQPczpQ_Dv_N&)g( zI)p%25R!2WREj{$DXRtLEsg7OtY(U1s4WH2LM%-ZAH;T#^M|w3D6syfro6-2dDvnf8Rbcxd)^q02dih zi9%i)Cp|=(dSsRU$9T<}wl4P)kN^NPVBi5m0tP+;BEZq#;ZRP+Ukr~=4ATpNU?BK; zXZR)OuZn#Yx%W?)u-{gVE0eH>%n zwT}8-#18=2#e~fc82mr~8P*8yWi?hWt!qs_tFyhh2n_yG`cNwT?$Nx|HbjPwBtG)P zl#%5arnHV+f9H}jYP+7KkY<@OP7SLRlI`!K_9S*^K5Z7<>k~H$4 zEI*6{WDBNZpa{8!w?MXgRF#0xGrOn7Zt1yUsV=BGlu%SClO~)87Huhw&xAQUU=*Q4 zpVm6E;-%hc6r04>g4aCG+oo_JD*U24R$-+CpHr!^h$ErblV~NK32Ls7UJ0rBp%qj~ z*QeRXDTryF6ebl(N%8MJ%|ZOW zj5Q7Y(#pl;t+AFv*ik;w&F9@8O1ZVYn@wyGdh8u`e%JYjEkRp?A6+ zakBoeZLO=CJh<^; zCYa@r*)|kgaoM>@SiZ8h^R0B0FZ;XL##sK9$}a_~JyiYv{lS{1Dy*YEtRvd^C8JHw zzM`b_fcW)jSjKl%kyQn?MYsjj9Z^vBFBHzBr<^v=oxnb_{{F3&hTLuYVO0mm1ME`z z>ab3vvAJ9fGhCp5RK6umbzVjG3=9&{qc8a@uBN42J-oU4-=$~3>#eB)3(GK|HAKpZ ziax%CYrYcj3}m2l^k_ zK(EYLQt;MQs{+>&!8k3#EB^8;GXkA|4%BGmjE`O7AyAO)vi7>xfU)B@g{i8sV|8|^ z4rvUac1k~ZiASK2Zo_EKqQ{b5gpkKT!TbttP$&P;mqtz@g|7k}Cu8!l&lxT4vKq4* z_>Ep8dw1cu+DwoRWd)u68=QS%h#lilBNHx@kxCo^xn(k>DAnWZ6~Y^wgm|q0N&_ni z?Kw=5Z=ul=^2l4pX}gQ~ehFG*Jv7*CPik)?91&hN%OM9EYic9JikgP=&GiQ3Qr zbX4lX*GpHgWX^=cVD?-##fCTpEa7x?qb9d(?#~@L?b%W2FlG31Eh5ME7|=6)2HAFG zW!MYp&SJ5yd%LC{_7(N%(ZIX1Qo(Hu-3@c?+W)%!P2>AN;?h%7tWk0QptFviQX#Pc zw=Te+*f+#Oq}N&6Dy4R?(hn`YaR-ZoTZ5PweZaEh4!N6_o3sPq==)C6iw> z<;_J$WzBuwF@2AN6*{5qfP?gT-XXnoA zmb>34HQU|?XZ;_44>%k537vR0u`Csez3Qn+CA1ua-I^(1Hn4>)hkRGQQRXEjnjZ2i!VXQ8OQfG+}7LYk{(yw&S zXSnFf=;WM3kXQi<^7teznyR_*sd2CoCMb&Ee#$6^9`}oZfzX>MI+>*8MpArpdGh&a znWRGLY(P>`R9swr7^gmC$Be@vNK*=FFvzZZf9I-b9DX+S)S%}l4_q%Yvr(;U@s*mi za%>U?>r)<7iXlD?@DSfP0>2XXvD6z@m&HF8qnt@~X%vs2F2#!QNNL3wsz5**7bGvX)knEwE>f<#_eHxSB_VZ`k5f z0^v9T-x%Mt4^dLN6r_4)h593boik5qT2(u)bb*J^kW>FZ-S0SLo_$?&^K+2~;MT|| zZJYYh>c7pB2i-~D*JU7@6mjM4be@=RCyaT4)7!}hNTu=R{Y|z^3OTJ@P7b5LC<}~i zp^e^W$*Ee!AG>P_Je?`x;vm+eKNp@!xY2!sX9#6VwSE)FyC5d-NvyJ|$ryp_1p{kW z*`bn5rNcQI8nZa#(vl+IWFHb&guyfmi=7E=ja{T`XGnE-yWK(=#mQd-6 zd!a4N0D9_V*C~T+`f4fiqam*p3k1CiI*{AT^IgurV!WL-MNJI$u2H>XlDk=R zSmziGNLVdH^@81}4b$T#xpXXvxoy3bhq3CV5D;KXYtHz;J?USUNu#7_Rb$qHy6Lfm zfheE*c3fc611o^W6hzPg7OD_Swpfo6oN(}G7KQ{~;^0#VxQTG*CVq@e#Or=P)~^7J z9^G4C;E1ALSl>Jcx27;BCmcK@Y-;~+MH=$u;M%~Cga8pn%TJBVoJ&Wf5FilsorMP) zE1yv{#wSJ@ObZ_gi0vRF-s{&5@oH3q6tomfh`Axv0bnvTR;-5q{dG5&47v{||C@Ej>D?4U0_dFv4-LAp;=mwh7n+W(_2% zgt*V~fFQI{M5O9Tfe7C?ki#ntVA`G&)b&?}{&GWi2G{$@!>#O$pzdi7&Ol7LlBGL= zB~hs@EtppwpG96CTvQt_m%Py*4$xtrpifGqQ>zgSWt@22VxmZ0wSsx=qZKTvBU(; zFYC8{ij4IWf1*OOOZBeQs{k=1Syj-h@N+H~;JeF7M~_6}8I{rHoSJhI{a%H--k^1{ zEAUF^va6P47mRzGCxD3OSa}0#ut*~qN(dGD>QD>qTLgL?5GY{-zXTV`8=w28PqKoE zp-r-TI5gPS?MZ~vABh?@lP0_1bvYlof)BY})x+(o>*l;nUdr*(lJkfWe@Z#BIzlJ4 z*)ue;o1&()_Vc5bhSFI%d41Gdwtz%5Gw6RI`}IbPEiMr1WBMi)Gk|*dpl|$pm&An! z6*Lu1bKn;-B;^$+s(Dhy;V2*XXI_dUL7k{q1igglBdb_oIweDsg|8Oxqx$=E8;#U@ zc`UfFDQKUTMAd?|V!)89gA8sk(nXZZbE4G%xHrK)n*lq^+*K>I#!s(XE8KjplS zQJK2#XYARwLrZBoEU=snQ6ok&1!9~`r~C`2*OOu%XqYT4j>FkJj;S0ITo_$UH+y&e zr+ew)*6)Hlk+g1A1E0&5q_fKY1&nw3n=c8qZGKa$f#sObpzV6D*of|QU7*2Z1Zhe% z*E8t&;wxXVqk4^&W5W~DCE_KI8(c3-1BJ65quUI}b(fT9Uu#-i>EChYY29I*v5Slu zC#j1UyJmcomY0uxMHvD55^0TBPKR0Iwe7}R>Ohu7*YqwDq)8HYM;Xalou>~b;BJ=s zn!{d_^W+V7trXlF2DeuskA`1foi6CRZ;|!%EeruE`S5)XTFn*h?zG0$kSEZ)2^cYo zkum&x7v=|L0v4WE?3NOM{0s;#OM+bYSziAyvE;%s5=s>uOhZoxi&$A|RL6&6;>dg> zQJveJ?`h8uc#o3gWY9w^GaIVRWEEhO2b$GU7*I5FwsMXJ;x4Zx--Yv3PC8kaD9;#? z{m`b@oHi7gcOZ}^1>PxsDEvv3g~Jr3P^MEHqfQBK62!b(&X%>Q5ZkEi`|lh^+^5q% z5yi8mgz`G=LamWderEzS6lLsULW8Pve-O^ALP6r> zM#7~EAFDJSa?T_$J!+bT^KK%rN*MMU{zho>dWaVCd+}MUCvGo{`i1_W9~BA z=Qx)p*B&MymdLbHb^hAR(E6D)&7R)E8rDM&LYADPnrr#3EpJ?%-BU0-Mi4;}Ya+3hxN{Dv9{g~@Ovdm?8#`eTCTFjWT`nPu9J#DjrtF*mAE5Kcw?dnKm&UkE z6>q<5+x(iJSTml@Y6;H2XD6pyr1&n92>PZdy}SLGA?#BdP zHWdgw%m_;Iqa3`xHSPOj)@$$n)4T!lV{S)Dt>ush>GkTS7y680&q{hkuWD8N8+`!p z?fFiN_>BYJLALR)j=D(o)@RaYVlH*N=O^*kX+_Jhzh}(>$2YTY$FaIW@1IjpJ}2k5 z@2*$3oMf<+)zMm&9!+zkp=Z(UxxFK$hbtl^=&lB1z46>^SHm><`I1ngC*N$~m_&PJ zhfPtW2}^NZ@Ej43f7^0zec(W3lW(zR=R;FnN?@sQ*)l*z47Uaj=Qze2kI$Sgg=Gx5 z7N|@^aFHXu2;l^*@K7Y&$gUbliKzF?xbn!yG|`VYn213H>Mp zspR*&;}9ejoBmiw2wBHYpjr`(kr+;^=g_*QejN=O_R!5#TBK60-m0Ls1*pKuOkIUt@2eBZ|ojr zFlSjXw2e4LKM3s%nU*B8F;_aj73BPiftgHz9h=&&(`@AEL1h@+r-i(0J!X#MuHK7eS1AycOL>08{oImL`bhRr6g}c zph%T8v&=Crq-4bE*?Hsw12cWz!}(1|Mtdzv09JhcBKWM(n&t6*h)~^LW`}Ba)?ijT8CG$n1tM1 z3l-4_{KZ4*YoNt3^l9%@T^gNB7~Rxv#C%&eTSk{Owwu4|i7s2Eyb-du*9@bJqZ{QI zDCJsfnk>ifHTV=Br^&ulA>Tsi)uG0)YY&KL90_LapgPm3;WJ;^?n zq>Gm?R=8)JY=*T@t)}vI!VYIFJyfdPg>bMnK!7q#o>h$)XwMjG7c}wNVj$zFMip^B z9bYZFP((o3^r@6`$}9r220;|1&J_!wqmgg z4De%urKjIoxg66wVIMLN#Dp&x&Qv9dZ?fsp8(n`SYpP0o3?u^92*XWf^nKG45#7tP zozF$eIzQ+sh3GGZWQ+%_GUnz%CgPPw9h|0c<=!#45#QHV@b+n;g$mhvi%~U@Cj_`*0Hc`S z=KTNc{I+=e0n1tM!XK7*28apm&l9gDcwzlX#m->V#yVN|C-N7QuFaOtBZ{0>z}A2) zCxCMO?jPQtYoU|kWb$z_M`*3c$o>$BO>ru+%i&nA3L&SMJGlAX0HG1#^vOz5c6=#*a2 z^NMDSkG-rHU7$A&EHnHQN=C|KKuM>W=9vSy6ov=?)h{y$0mUh>*=&eW|995$8==!TU_(=^I&yo%|_ zgIF~Fdgo>gu^5T`Qjh8R>C*CA=MosB$>UN~H?@8!w=f=vl;I{@w5v&f4+9C)h&q48-o z(Ota#@V`EB7AWHwu{#5%4u2_FF*f0)U%U`y!q(?5;g}@!B`ox?9oq(y)#bd6X#RL5 zKDQ#eUd9|$RIY^%A|j|9cH-&taW4GsCxuCc;3+yQu*{b(qQR4=qz^WtK98W6ZDu%T zu{^gvyc1>fw@tz!>$R$W&s{f?b=PkGxm8ZSfnGh>Y01`uJ97ewt8y zqDi0Ap-1;~XLuoLcen2I80G5|)C9Q+;(lO_4!ADc>uxklzscnpEcy&!T4(q>#olLT z)O3SWt;KwH+-c&u&CiD3#mHhXV9<>hpqzK?(LB%5NeeXM{d1%qzQyfuBChshBZo1; z(u>&LWq7y9#?HYn=kc3kq?R-(99eK$yH-%G^oB4Zpz!mfufsI%z* z|6a^1o9eREMe#nT_p5BDgL1{&FVU!?m<8>sthD>5fTk}4pB5SLQF^s`+9pb$a7^1$ zAD!@$JJ$({eOub4fUWRkjve4(jDqxAyuPEhT7O4K$LM`Lliuh84>g-L)ZjwlEXRdb zs>LKfh1b&chGL2^SC4qbi9c5E{yqG>71xiRs1vR;=-gL>Evt3dO+2m1|E7jD^E>l) z1FEI?LvY617LB|N+-HY&nQmJH&!_nrl+Z=aKem6-LkWt)G%Yd+_n})BErT#sSM*0T z(3}|0J1ieAQ(74n&i(iZYv;=39`Li=-*B^m`eIm$dq15Mg~HOg4upJ$!GUHKs0pyY*6{DfPEHlV|= zt0a-%tiT?6g;6cADxKldQ_Tu&HcrNbS5E@}zA4dRPe2`CJ;F(ctnB4nj8a|rt~P^* zcDA3?5ufu*$j&s`_q*;ad-N%4W{`F|qEk|&yML)yJ5Na;n4{wdvlP#vt+yMaqp*^= z96WJ}9J-_K>6Nj&;EPOx?#Mo&&k!G1X0Vd7|4>UBq(-dZbypqR&7}g9Q|~I*e9QOy z^0ZewGp9X4dPdg$Ljt6)Vqhk`zLJL&AIlxSaaDgqmUtSru^eng8+1r)cFh;7Ejc)T zCMD&#I#B+>I?WVwl;!;T^~|A{d!gN@ekMP&A0IIel~d=?fLtJfHRF0&BGysie0Q%_ z1#OMRH7C&q#+QYR(uSOx0rKfDjBlK?7!uN=Qi9j@-pPl~!PS|i2NT-Q&|H-uG1I8a zilogbwBMA9D#T`)InUO(R%_3o(Z zfF)SFION0NNn*o;YyCJ;S(k$Hq){@6z@D^)2%7ViJO=9+G}3eAoKe<1B{|9YkY3}! zx^^yLHg>JTdM2^afxntYOlpOpOd*1>ZA=2re4 znxjK(59K2XO`FGy#9p+en)Qu3y?UP0s>feHg6?k~qdOfYA@p4vBW((PCxJA3pC2Z- z`lLkh5V_tM1+_0HtRWNCH+jTi_iT-mwI&VPyCS=Ny5{sa^ zzD9#f?4M)v&#V8d1z4-l9UV&5UAcg{k`9P!4*u9$D)5;7m;Y>u)d|QDm9dkgB^+Mq zE$jJ1+4G0JXUz3};Pb_gkdvNWARbUGlejR|=(-3oe)#_!20{r9qEv{)_Eg=1b=rc| zLL$fWP8)to_oLav&c7q0{AnnA6fZD-A0KPS&-v{p=51-`2fX+Zip8@Mx3DY@mVd7a zdu={qMCkrVeXf{~q*ep!r&|psb~z9$J>d+Nq=X8DE)Tm^`u9 zFsx~iYe&xj#(>U{wD;!6nZ(5b0afWSZE;^j!i7Qh<}L1A~3LnWC!|${tT^{ zxLTUoptGv3v`931@l8jJHp%DC;M~KG&l|Gii@DD$+s%!*{Eqf1e|(aB=lH-u=0juS z+@T`bu9~a=-4;E~J{tZ)iNpA*`zdhX*-7l3o+b^{)OrD`OEhTgbvoczbH zPMSC^Ob9d;lUNzY3#64SD~DRhAsCuO89uNirTxswd3nK>pozEFO?l(pn{+9uA~`AS zMftF;v$dZxKf22zHdgt@+etLMXM8LJPgtE~^7e>h!z&%4iDJmo`M9IEqBl4s_+{Od zb69?1#=RCMQ~VL_^7-3TqXRo}1jZggp*MG+*rpDD^QB6R0vcK#9S5NXNat?k37cQg zsiJH02qS@PasexLR{IgmC;k(MN@t4V>`rgm%az$|G&a&(a#s%@Ust|N>cSFRNi#Qo zij)%ZdY6bZ0*KF~XgG^n`EM#to6T0{RE#hM));ugh9i_mRz%u9%#kvy-p+It!YGHv zCqIIgUfRe4t5x4HSxs0sMl{Tn4*bL{l68nrut?fKIBy;2Dqw186H^}@P0hSP`=FP1 zYn8#4#n2?>JwXUyJvaCkY zRpR<|z&de4_ovp%(W8X_YIe>jJv7CgJ>g|NAy_o5c}rVa?B?dng-^oY9bb5p@Sa^3tkj-{<36vMdfri89N+XKUeJ-S~YJD;Bf^2~1Wf+76xe<2%An24TEy?;bRHUSXlZQtI^C`TVzv zuiwvs91XF+v>w2tAV)J%kfjm*m+{G~Em0=~-V-@PBd7GUU#e#}A^*$@gZd@!x&PTv z?fov~Ibs!d1qm*0PF@N3sJ0!U^rEG{nAE|q>Uh@oq1pR=Kg<<1>>3YI#F{+(gq6c0 zSSr=KfWIIR6D2-E6>ONG6u`Pg{cmsmFRsgj(wgtM$Ib}JlTG1Qu%eVh@N!_i$9>KJ zsAqt}rkmF*AaD3LDHyHBtYf%#{S%kXWy*^ktMSaM=aq}$Z+)M$Qw!Ccc>G(D19EsK zk^mp4asDSV9_kmy%#PY{8&g?e&@^0?W8R|z2dUaxMn${`^gX6)qMv@Lx;mNqMk$>y z?`84;>)8P1K^v|uwn;Hh%~yZ9vW_TX)(_7VR9`)dyU5}0{(}lw7ym<&v^M0U&iz@E z(H*V{|GI=FhVG)X0FJXDLk6E+; zA?-jsUuM~1A;Dzwf4Hi0iW@%%fTr;InzzrGZaYG5dd%}C?6Y96MQwSxHag2{sG_>) zr$x{Eb6lEZeBT%{+e{udSdY_bKkKFQCVR=sB_0q}S-#lOHE8Z1dqK5lxbmit__=Q8 zYom1=EwxE4vLM;A?2YuBosLy53f8qiL7};5Z8<|y%(Thjzcbb`uV2WqH+xUV6|vyg zlVrv@CK-j+lb>j^y#vb#r7zg1&hoQRFh1P|YI%n!-F}*q(ME4qC3}fDYbaSgPnC+$54@UlvdD>&6!x)jwY| zcm86yfAfJqz68MrFOEkzty-klb5J0zDmc+zVuEW0N8D_r;b_oHt0uG(-Z?inzYpzU zqVqLVXX%x!F+^h)BJ@W#AQ73OVKQ{Xog%qKTuHs0W?C^_K zFDW-tTO1wG@bt%FudoJKaf)<#tzcQptA)iy^Cai9zq3@-FV!Z&mQHHC;tcAj59*0* z`R=VD@wXP!>YHw;wj|1>Cas+>+O75=`Kpe)wgq?404@a@r*K zuEIKAgB=xSShKL7i1{`j(;PJ>$(c`j`6g)P+X`X23w@$UI!2w9CBG2dhF;D-<9w7_yw(^`3Yfn6d(BOF!{IKZw4tMaU9tAtvQBHI zf%bS{@{Z`|bUyj4G#3%471d)%xB^W^4tC<+KP65M%anfc&C~3oJ^XZ!D*Pj~FrnzK z(JitB+Qi8Htxw!2AMlT^YDwIm<~2tNP~#+w?)#!+7M^y0ZKI@@u0nH7@u7^f+rP4q zHNp2vP!#!I1^ZX7pc|eqeI)j^MF~56EA^Su;U8V*;TH^U(3Y8V3O> zuer=*EmUnB|L3BsCE0ul%kh_moXvhxK|?SSGuNm?MtJey0;L5f`Q@{B;^k;dSmr}$ z4n#u%Pk&9GveQ1iWSf;^>BkG+?oj%1jc0u#u3V8aaW5n)Vfp{JkpI<7o;`B!#=0NI zrNCU$i=gksa?N$dZZF7gM`AyF*m%a)^S2J1jj*@0dfwsVrCzPxk!Nrnoh~_kKAUOj z%-HKb_3z%B2%)_=fQD}UR3U2%e(-i#7unqGzgPhZt_IO%;#l4f&)(dMl~uA4=DOeZ z%9OKM2xe;uL@nM&^Q#?r1sX8&c*|KT=d=J!wedXh(LGc^!2Le+r(5n=JU|`%5Hdt2 z5fagJnIYNNkCTD5S?!rEn<;;o+8^{C$N*bhS}_-1_+p@t<(HaJH%G+8 ziYMt21v=!(<^K5H7B>)8A-kO=tzi9xH(z6U$SD)QvrjaP7|ZCED5IzjUCtXSm;{2U zzuLcIv?&}g82xwrTu@$=<)`0z;99(A0uaKJP$qfx*?;@&!-7PE9I;GVMsY6gmiXP4 z=w;E1Pw_5?lc{0De)(tHwcdh<(PVFf(?Gh_w^H`)j;wVKt4Y?uQ26t9M(Mudmth%% zm^!iWv!7gizv$DOg4J{hic!`Jbmid=lurl9i&HP7OreoQCYt&vtYUM55z@iuX9WT`iiE6R%&lPYifZxbg0gLKmV#^MJ%Pb$)#3hxpmJFgc_;Qc zx=6x3%gxU-KgeUqs0B}vn9x|%gw$w0z%=Euqc5h7@<8{|u;~HCsLW?VcEqr398e;}Cs7o-U!iG=~fMvBO!la6cq&CC9h(wrN z6DcTxQ*{(~qKOjKAvRak%pAJfljI+g2o68J;1b&YfCEBx`ZAl&5(SD`nkeKX*SID} zkX1*sZ(3h5Z5V$QRK)7dYYi|q@-4Re)~998$_FdC_kCo{0e}pbTG2vg$5nn%$%mVw z^$O`1N%J)pb3&+l7rrE>%xwDvk&S!?2$K8+!B1;*F;X zf;DE!F*1zEnsddLts&`PDKf_Ac)pQl6dx zPPhc_klWFFfU(7)Uty zSVBsZs1>0{L_g~7`ll9H~hhGgrn>a#mIH>JO-FH?fLynEPFP^UZBf7}+|~xoaxFW2*Lb`P89^1cW0-bH47sk#-`?B%kYjpsdOS$G=^C_cipz9qwH)h? za8+3n-cMup=ofl6{PQcZwy1~_6pf8G#X+rWNGX6oYgr>91`VCy^ReFjz)4WL&e7?g zotNDw-!xF(Rhy3EUNXODaS*68|9=kM=fx>aH_T^wd)k(!b$ z74x5*t?}gk_Vn`l5ELAtKpT+yx$}~5;{BQbTvQ9|F1jJA{^z$lr~A=O)%3%3ayH>v zgrM(-6aegdv$y2J$}pp=OZ;u{jsU5D!YCQ=)Wzy^omZbcKJnHfs3689*Z$eb7(?{; z;YG>;m$&ZZ30@52SgzyPlopw)3HHVt@Nmf=(kopZ}WG7uL@!sd3cA@6Te#GnE~Vw$LhwPGZ<_ zUs>uJ|7n$I_IJk&To&FwytqVpHu;V0z}e+zRn&C)pY~Vr5U{2Fubk+QQr{RPdky5~ zVxqkYILJ)iAFvlMCaHhcfXiOaVZ=qf7mF$y8LsD)f)F!NMmK?#KC}ol+l73dr-E5s zEh<=hAG&l|zC}qf3;PS^z)KOV3Gu+R+bJlEp4j!N3?}DrcKCo0B7YV1%X*)s7cCJd zT^N@1f>PTeNT!Ua&_W}H3@tm!C+tbuSVb1a-gvI%ByAlFPF5-XFu%mi_g(bTr9pB` z?+x>9q5a_Ry`e3SMm?-1^2z$A1;8(uXLa?d)^P4-zF+}Ry z)``38h_)o&t_B0H?YVUk3s@Og12SuU#uKBk_q_f; zWSs?598v$JgIjQScbCB6?!iNFhXBE0aCaZv-3h_n-CdHw-GjTs&bwRxs@;7*z|?eA zci+DEoac8=Xfgm=F7C*K>8HKRsLeLhBAVfL`9_Hvw#e1m#bte`yj#IU#xjx0XxXFK zEtG)ypp|*VYHoxEeIC>SiemC-g4pTY+p`};kk5FCWtS+$r<(OO%M0V62^syK9G6y( zujuF={}Nn;IDUZBE-`e)+?HX{J%4Iy|ktu{L}e%Fd=aPKU~%-z)=^BqZ7b zIgB;~t`dm)t&XYd>%PfYIHB~h`J2brv-_V(=?AT4G*SlDRi`b1FTOItl#~El&6^TS zkr}f%(a9>C#iyeh-xwwYl0PT}B8{Tg2?qgwu;(bqwhjZ#qJiNaZr}_36M2g~(_NccmJ)HfZt49nQ;l-MD@sspz z$5AV@UURNK?{HVz;qOQLv0#Q&Io#GJ@0^>onak~qcQn5TcM-{!hUwv>&(=g9S3~%m z)h3)-ebab?mMv-tA;#%nK@8EErDz0Z5!i4{v!u5kr;)OZC;Y)C;T0@P`s8)Ox@B3# ze>~-v0j4-;vb4eq2#x4CL(nHU72qZKgNDTVbd!JZmP9+Tu8j+)o85h}Sv4*;4sq^X zFM>-V-hqC6L(A|N#9juWE~x`!G4*To%FJM18UZy#)(Grcdu1gGWK@ds|ElAJ` zw@B6QYXt^Fm0CrYJDA5}6_$YoFmZo?S9Hg=I|e0zSW&Svc@I}_9?^uVOC*smY+o4b z#amkN(>dy=_$aZhU52a%{2ObcM=!;R`ZTMw0cT#E&gzo627e(j9w*)t-?eM6EyxBk~#Xr;;|@iVp#Raqjj)B`#qvCyjg(50gEhn-!lA3ODy zRi`AsI2N;y6$3t;G{2buv5Vycd~~M-;?h!p4;m!S>PFvdkLqyR=!Z+|SRsSQehNOn z|5caVHd6f=A6n!3rZ}Lp1$GyZt(=Y@F1J6|?#i2LAS0`&sld7!H& ze4)@@TZVsAba?*+1ZR$^{5E~<^vj;~VLr^vL_K?@=4adJReJw=ln!O;TW{Gk8zshs zg#H!XNVx&1IgPLO^yT}RXVji{EUtKVXWC6^m91(Z;3w^$&Pv7~*mxFwquyafloEX9 zqlMUkNyxatQW{#CS!NV)5-rMpC##0QWW#@n6A#$A0Rt1fSb~UwI{$u4AUDRteuG%Z zpcA)MkU8NBqE#w1Z==DXx&r8|c%vif4O2pFdkjn5K+}V7Wc9VLzs3cv%9S{ZU@$oH=p@@)Z_$WCVidE)Jwzc9NP~-Qxaax) zw72-QH&xd5m!w{>d#VIQFk&KTIk4BT$>-vT{nCBo#;AUPwjCIMP~EY_ZdM=nBA;Z7 zy6b$&8PD zK7SF7B&Dj`u>Uor(Qxx=3BgH24k~NlIe+F4-1{@Sf5?Rw)j^BMv$fw#1N)_S&jjA)Pq8)k)Rd$>|h`D9io|hzCq%? zg9AEs2?JaLo3TS~x(5EFu@Dx`^7nwVJ4_8iPLk>(i$QZPaqHNtu=eUUmqRq~1_NF< zaKu9TS%co>1e|s1<-gxGTq2oUA%|=GH;_O$$JXh5K3fN$#a!hTX(Y(`FkXCqN+1GI z!T`IlobJpy(k8Z`T~TN+1$+=+0~P=Fn4-LvqGJi;JJ`3o^+mo4uDsP&Z-_h134`Q)c``MHWGuyVX}pewvNejU)w zi|Cq)9*k8&J#HHK1vQ6-dSadz`VUbf9s|_0PN$7o5mKt0bd}^cSomP5g$&AhBt1Pn z$XOi><^>3ht|Ho_>IhKCV`aBY;+qi(4z&_aA1syTS2OXDURz7jGs_iz>9pRJ;%jcX zOfcQ}im7gD9;-~Hpr`tUe@?8{;h?km13CN&DlV3-wy9f&3EH|+hd7s79m-6P@*6!g zJ5gx^jQv{o_*s_$Bm{d(>G_Rqz$A}Ci0Zqx2_)AjLm4T-)YmtMNB&n7mYGfGPtq#o z0}9w26B*GYE0PLevB8jI^43t0P6GD?{+>(p4dZn2BSryL;CD_D?MglmA%V!NJ`;Uu zcMh@SK)_#E%Jj(tl2etjiOifPZgU;@4RtNJI=let8GK+zBDWrCJ&lFh-k!x!-v%qB z!%ojq<}}+oV&3Yy5O==wvTBxCs2sd}+Ep-lxThI8&)Mbo+3Q$8hKeKc?M>LnTKtFA zI(6)7Bxau;Fwr;|%0x^cedM)Wuf-gthVO+3*=? zQOS0GYNiH!A@F3P@4&@TQO~&`ytT$ZchbN8<=+!-A#|%wBC?@R`RCUi1N8a1P1>%I z-`Q9P9EN!JG2OZ=N&}8h+DUxbOs|FQb$!1!V&EmH_LL5)X3`T!i4$2i4$UQNk$zu9rnh$;>L?`u%bHYrvUBMbt7ym`)@u zn8@<|K!K8lV@F5F-kI0QnadkUSi7yAT@D~Pt|M^seoYb!8#7zXA}TwR{R->jHq>Zq z@!l_~%PQ{t053tV&G#_iZr1Ym@=o~XOWIT1%)1>Gk1#kwzL!-6yzhDH=)n{DGdkA- zqw{tj|LNu9OtEz*UZ|fcs<1w&s?6W!__}SX@lm zaF;zUa(#tZn2_|P~2O+Y+7=RDOr|~LnQvi zc+fsqKbGzg+Er_4!iVndry1=Yz8|x5<0pRH74^(O(mo_<7^L**r$4UPMOF4YaKgFY zt3I|IX4CQm879u3ps^(KQ!RG=S9%<^{$IE#3io4koBYlF0|p}E6f7L8vfydMDA0Y2 zwLCn9_jbQepTQ^Cd72k`U6iP~maneM`Ou)9T!N>-1uA8(?2&#}aV z@{{g9BQ2a6ps_GtznhO&0)d}ObWd|4(6j2bUERaRT{FuKS$~>Mcyn)F)4C_yPy}sl z?drR_l;+QzA?T2y*Y?CGA+LR|g+^fVNy&#+^T zzBvpFJYeUul`lUvxY?Z{H=dZ7I5|3K*>*UdGPsG25|J04nkMnde0=+z#Do$=TfoWV zId*@~d;EkFP+a|4X&2Ejp)`kgd5S$pV;Xa$3dvF+$J9>p04vd6!46+4a&Pn9-7n(G zWayFNFvC(rF_n=`pJY3Gf7$XQqUg$wO&FN_(ET7RB_HCH4@?{Os;qe$GJ1t8lyW}4 z_WZWCVPi<_b~Rn6&7vwEPm!Ti_PBy6vDNgurkQkHC#|C1Tn(L(>v`P{e%+N0ft{+W zEL(-)his?Y8}9k(hIzukLDhU95?3i^Xf1eh>CZdUU0!!*o zI|nl@!94<^SsjpB}Pox!*qE0HyHIjTGzW~t< zq=Y!N-Tv`1yeB%mMri2Z0P&*mp6m;%z;&go7l1wEFl^aYS!WNp5M$y%Dy|?h!(X9r z5V~u{Wj1#zQJV3aKc$kN;hs@q+QVs-YVy~9HbZKy!Y(0+S0LGw_M2^KLJA~0y z#DbJL!o(si3DJYpgKS3Ull^Mqa5$%}Ix{Fr_J*5mw6!=kM5VAGMqfc%35~*nyn1#W z@I_bxgXAk+=kq_U)-Lbp2mi~}rKRo&thxHU1x#}>`G|P}QfpPr=*}JRIVotkqq6E@ zNnpVc1q>FHqXw+ysP4HWN+tY&4jBk1`o*JeT@UDo3r|CnmBc{9|J=}-UyEYswNG2R zz^|5F*X0T_amdkT?&S73%$P3gydKx8)f{Wf;TC$|E7EWGh@{bsunHJpCw)T|Z#)L6 zAKky7b5Ut^D#g?q({}o~jF5M?Uu{x9_Y0GDORO>9Z!}D~ySQDnN2>fDDqHLHfW6Lj zC3pXe?DWj<&(*wJeN+g&L z<)k(GdR0vqNdlgUOjO$WEVY*DVfVL@O_yg~IcOHT3a2iql}@aIBv`NAQyQ@B_e+Qi zS&9eH&ArY+esXyDcZz71@8_pqyT<;Ot!p12L6-MTwj&mKQ=Bws49{82NpaoUMX0DJ*- zN(~|xlre9{yb_l>DR51dgu)W@U$Gc5>Inl1dn;SRcA z7A0{paUuPy^b2P#U58E?;~`8A>IpWH4T!CcGK=F9ayqwX7k819YPZ^#`yNxJeT6#w0#8YzMsjsdpI6AYL^T@m@mBPaDf-eyZaN#O*895y;tBd> z-u0mo3)=WxwB$jds0VAy2yBvHbYl7a*Gjx8caW5=^07hgcrZyfupM7Cz#krt0$x1e zX)+VZ2vU8dkW&u?XZjhL<(Sl!7g)EpSuHIa7P0+&exqcFwEK+3;W|*}cd_u)iow`LPxn?dS0;V4abYE}t`%+hT~A1RFdB!V=R<+Y9c)ibUf zWu0XH^J%4u3S$oKU2xN)4mpSb=pDoREVn2SK5jbg!%4khaNs&Ub<(oDDrnX5+1J>` zEUPTni!YJULPK4X)|y^|X@rM7$pXo8+Riw|%+3y#5T#nkCz2*Jp55N@{xxE?B`yMw z8?TMJ2Il59pgyC%?Th)zB%Q!{d@1H%7E3PDo1L2ups zu;}PAH!({^rfGs%3Qa5Y1&UO81dsy4C1q~stCX#p2^rP8*N&XJ!gZWGxCLG@$up%n7ioo6lwr+D(kb9MIXHIO7~_5Vmx z%dxL}e);NA?bUS)nfZF#8_40~ilr9HhFWVItF(zxv2ziI>;qo1W~h_|g$%S(M8uzm z39iR?ZwMuDrR0O7zKo)Y%jsW^meAp5OTxX*u4Ku_vU<1>oUC-(92a}NdkU@|BRK5E{ zqZuE|re1`%O|bM<^_KUm{!0hG`+8f|rH{M#6Wt8y!+kDEQpwTD(E1xiT+uII?RFm+ zh32^vO#_ZBvbuEA#xay%#dUb((^Q%vAUG$!5?OSMFA8Nip0QZ)jJgIY3ep%+Td*Rq z$;on}VvqKIA%^-G5&w+*DSlJr@MUQAJ$JLmC z^99F}HaxrO;k<*rX|W~G<$Cw`IU(D@AW;G~)ZHiimVa)VzKS`z&z*<9Mw?}eCni-T z49H$xWDq6v82Fg8`9$jG=H^He&heQsst{CLd*2b=jSe3O^=%BP<2V54ND_p9$fyPZT0!s;mHlYY)0Lq z4*usOR?@Tfk`xrs${HTq#C-g0LSS~$3HG;j^6fd&N2B)#@6PveBURntgjq5GAU0k; zlQX+7<;;s?ntK!l0~Edc*r;AgatOY+yn*MX01cWt?;kLQ^W)Q>lZ4`{SYOCyh1p(%z1-}m1=4|;O>CV84^B1pa9P4)6SY<6lyQ`BiS6hcG0|A?|yvsg;GNk+EEQ<&F$4h8;` zy3ZILl=t*2Z+HdEj=Z36{p?w!#GX!nQvx+taY$%z(XAqR`t6h zuy|Rted>5wWJcuS^Nh%ilRkZaDxA^tPTqpm!18j;-PxD(vvq`$$V^PoA_YiNH-~Lp zt`cjl$2U(9vZy!tl5ILIYp3%?Vn2wefz4au3|q<@XgCrax&K5W>5;j=zJX8}M1wwW55xYZ}~XZIPCDv$|K z0O(36&d@=uHpOF__?59AB&7{C(am=fGyXbYx>-DV+MfrlfK`^JG zp-H}kwYvs!H=P4y-Q+yaQ>Lp;_i*U*cH*8fbIx@%z^!6v?tMt&N1Z?FtS`F*Kr5ME zUSGEmA~UPn|Cb`W)aID`gMQcv2B^bj#DeGz^K4_IExf(=h(W8tW7e3x1wd11RCOcO z0_XH;2ZP~Fc*YZqkq;Uuz1=UIU#3@ih%tv#C+W@X*IN640yQ0BO|(%|xlfO>Pj%!k zJjB7Q8zQ7m4+o^c)VZI$8L_fJLDEKE4|}=xQMsg;IY{cq-fjDAlus1akLVySy+2Op zkzy6PzgvAT=wbnT4sVYtvp;1g4_zv8zs}HoYY4e353J(RO`|#f+$9I;f0JpDw_r+a z>}`kNCRh{01h58$^h_HiS81h>BCh?xu!kdZ;#E(DYvl z{6u_bcVA96KOPWm`q_%wH*s%m_R8U_;MnPkGx)&sx!K(CCL=qF-}K4-+p;cW%+cPP&u?vd)Ct5b(7J(JlU$6(D56DCX;zfL2h_=5-3HAQB?FZ zF1Af#)ak71Xy|bSaU&P(ug~2xrge}yn-C0ivs^x2-pBRLHv@?0)pLA*!F=D15643~ zJs9DO_VmX0fg37h(h>3W_niH*ZFh zo(MuOP-=BU>wK`?C@I7h*pqPbH=J$nly^r^4&<`U@Bbtf`git1Ooyesc;sdiP`tV% zg|1Ppk0#IE8>y2_L`^xj)w0^^loouIJ$^HXg`;dI>TcXV3p8uudaZtp7qR;sZH|aD zfs2TyBD{0eB67zl^0C4Pu`+y8@*r}Ov)|U`i2pTyB_DMrYMzSd2^AC}pp~H!j4tR) z4h#})eO(vm{;#b)^Sgkx6y*&KoXr(XsDXgRb^SRzOH^X(udBC!g>3?p6VI3mrc3>D zg-hDCc1=NhgkabHUb8xFRqJT%(8{}Kng;%ano(y16?uVK`w-h(1jutNkb?$4$}|BK zqGU$_x3pNbc=^1md}Pz-`6NzNu|m%{dU;Jwxt}{99$>_Iy*mM_>E~eB^S?6BQ(0EE z$Ox#kd3(g^dGn{`T|TZ5*IbPz#a%;;i>(onHpYyvKb91*rBM$S2&+#_fzmC1cc%CZ z4>QU{B|2lOrfwQR%bE}vo4;Lj_u$ST%n}6%CqFEybhxoj9aBdD$Kl5Eg@>^ejy@DA0Co}rdbf#6>-dB zAz;9fLvw^o*0Dkh)RXcHFB+h%`jPhJ(`TA6Z~LX(c05PW-Rici)Aa<^?@r4vvYw$Y z`Extu+GRt;(HnPOpQWXaYkMFB;`@dXpJN5Caxu-+4)5^d z>SR#jnCnClw+r1r7JV(#xOZ6FzkC+XZGVQ1l|g_g{t(FFc&nYQn|K=*s%7(ui?4dq z!fvW;b79gF7gC;Pz-G`EcS{o|{068yq%0}Mbw?ytdbT;i(V5;JV@xCOiYhWqRX)=*tO)#I-74eO(v~u)-HgMDY!gv(eY3##mzM<#|i6t*r zm`yPj%5@eXsrPn>8enehlpAM&3Be{o~W9!QTu z$vWgDf@a@3JxX5?ba!%cWL7NO6dV7fv5%;RAq%CGTO=f{Te2swT%w`dg*bE5>hpvN zG_mFpjFF)pUf^H(MnZDYu)LW+PuSIjwp+vv=7legE;f`)v>1%VoBDzMn>mJ|4xr79 z+0W(=n^JXIETw>86XmsmA6WELs|-v;NiOx`XSt#B_}UB7efi-0_gFKE(Df1gbaU}{ z*Wdf1`ZaYVZF67fZ+}e_o*AolXzksN5k384PLpohT|dks95aKWlEr6Gy!P$<81ui0 ziQSa?^V+|arXf7Sl&V>6SY%q- zexiyByvdSe2)23A5s=TIUW~)D6VRJh938Yi7qZxW4?nPt$T;+Z(lbl|neLFs(qEKj z98!7vqjCk&74KK2HvNrwRFOs$bNBI^{lZXrFMrp9oZY%DUPXW? z?Ee3b9R7Vl_>qBVh_$nu8S>NbYd&>${YI_hKX!|LoX7d?E5#EbPm9==?sw_;)sJ&K zAwE-&Mp;E%?Idil+WqUF5%NRyT>lhE#pFk{)_ZZkQt4~j$5u~)tB6E;wr%Pb<0bB7 znTAk-^$?VdSaqLylbxP)BH%kZIt0(V;QOu(20wpYpsaGlwx)F4O7lPGeqD}ccd_4v z{#X@#@qc{eR^iT>c8W&w{}6qfIUawg90&+kHVR;wAoGi;GR^(3<$Y5ns<2n{j)w8O zam+B0BPqhnjrJt=JP-8@3SP8lSFJ%1*qA3<&n6!u#7`>s5H?UY@lRc(8YCD=7{-jB zpI?GNZwBfaEypl!);(cAAQ2WL0gAGIoQcxa;Fd+CH-f0_)f)U(7>|F{WVy(f>lm9& zK6gzurc49F!vgdO;gH=qFTBm9C3iEtVu77M`DT@%P*rvLco6Wr8eZz0<1p|irWk?X zH&5x*e$yY;?hbH8qEuvq>f4(3~q~SjVzp#|jT9_=Y#k6{Cb7j4eg3w0Ry1Pa;HlX<29n1p1i^?2^ zwGv+4%92^0^z*Z2Z<-4bx}>tVdhWtYXF582^h3&_oxV~6mV|dVswB_#MUA~atM~nl zR@qii%#3*w^}jHhKOKC%_P=e(uw*pyJeDTwdWJ;||Nc8z9ZeU~%$m=lI6Xbx>V84S zchNa^N6gm>w9ZmYV{>x$iG%b)N87gy#J!Hv*MT8*B}*$SrnTUbg;?=#a*Pa0VL%As zDenAF-dc-3K?eg%A+EjQT1b71E$(A= zI8dL>pfkvs6zx9l@-4nT=!EZ_D~rwQi`h=OJYOnoZZQ)oXjem%AM628#-4HF^y&w4 zm61+aS3lIzl`Y5AeRuM5i(unU=K1Vp5LF50tqkK@%+}j1C2Z!f7@E6+(hXo^d9XkG zs~HO}AiP^zVp!JSq(Jjkj*C;9w-n0RLd0(zOjX^dooan8F)9qqZL^)(hcn~P zP=^+5S{Etx8&^p(N6ocM>5c(K28uJM-r;5WE+|U+>hKu*?r_F`S(-#s(IWbWAn3N! zG;m6%P~tTaYYC9WaulxWm96L0cDSqd(0}J&7z!C1!&uZ9M9rg78J&mAJ=_MMITZzR z;-+FnhQ}ACLdEt$0tpq%+%mSyy=1ftPjIY0_v6pd!LQIZA_&R&Wr&JnqSPcCqcF_RdEx>qN{DyX$%n|81@Dm1%NmOifM7lD$R0 zv&E&2jdvTu#FVhM`cv}a!D%|Cs>i{57anU)dZ>{t0cS>#0L6OvE;!0vX-5K#KY3kM z2J)=tAkt5wxWTmZ&kBP9X>9g@T#yh0RI<@I^7v=c1|;p*-k3^%)^{~b=XVX2Ot}^Z zs^Y&6&j=|GMcGvZOxaSVOX$_%D>=kSCw0Lr(_WdD|f?4XiLqK|#S}ncWwWH$QR>3zkw#5^|C) zI4BvW18Zf0F>wiur&owAyLB}}ZYecMv5YefK5Ejoz3``B&xk zudwKfRhzbY1z!}-XSj^KcuPlODV&|4IFpJ#dK&MmgYUQLR zKX(70Az(QF!Zyg;)2&vfAfs+U{J1(NWy13QHaacC$3Ja`5 z#mbB-+rV)D^0;yQssM6Qy!?DbqR^}00}Xw`Axzq^d|dCk&9x00@v1S37F1CCmYHVw zhz$9{iSI$qFa8NCAG7poRK~oyb9T*6H2fdbY5&6lRJsbDUR*dkdTG0BD2$aTYB6vO zI$`ev^xJV7y1FDatutfEIyzp=K`pRxrPix&QI5RoPB+Z87z(YVZy`N~)_ z9-9XJMRHm*<|Ga($7rTN#?{GndfM@P?jqBcCgDADdmc1FBmnBD9Ya&n_M@xiMuTak zQ;nmdt}a6WF}>f6ZANz2UmoK7O#p;RG)Ry~8zRLQj#}2%O&>3(|6U}cWM(=)UAJ(t z5wlPL^R3=KvmV?)r2BwCAGKQli}+un2MeOlgkhGJr)Ol2K%b~&Gp{#S-WgBWsdNP! z9ypmln%aqEv`hsp@MDI##_o$e)|!^ z+3eev+W6+%ySg98$c?*bH$uV)`k#7-O;VfBh&Q=sor@;cnDcCcZhb_x*L`N+#ojhb zNuu!s4g;H0$Afs_^%VB%Ef;lT<0(Q6?Q0ChW^H*Hqk`)H5E#e;P;kK7m7I4$ST-k% zroO`)r1;-WKS=wVF%Q-QewvUo4Wh62e20OjWUY=b{;u(z--%@2+KBEJM@H9?#?sQV z^*HE!k6O8x03SwQD!C$6I23{dLXD414A{HvCMJ= z(pGioso&|5@Zj^M=)KyK%GiW7b27rC0V zWV{daaXX`rKypg3a)zx3$u&C@?tcz@NR?Mi_HgiRm7qu?q zy)JxQwUn1j8#OR^*mg|yywiWc?LxD88ILC-jJ3?mL0gtUu$D`V@9~yIku<**ND%b( zMjl@+dtL$luk?8%=)TJ6_e<8EKId8=l0qmEBnEq1o{#;Kt*+l-E|un{(cAyqLuKwZ zYE@Sw?6NI1Kjx@7#4ykb46U#D_%g*x#hg&@2FtJZHL*l)pCg05vI;4=fTQoX0_65wwKd_7XhI{by5am zkijZbA>w(fju>TywNJ0Sw~GQitEeI$^!@>V;X_qgx|Hij(`U-840hUsC~hA|xyel+ zpj&jByO=zDmL3Zpis9S%VtNcdpio3)6WxiFd{>(&7JfdBp@*0Bh)PxyUWMPh0j_&@ zmoe^1X#4RodC~9*o?aFOT5H~}ssKe&lP;#rrL#BmTWxcf%o>u%?z9b}hWgZ2be?~- zyM6bNnHD)MB2~qBz9avVV4o)0;^wjir@=TTuHu~Jg3-wwXeApp?h2+Z=I$F$7N?5n z8&5RVHZyy7z$Hm`ue4{>_ce+dg&#MVD|@$IcFBvSbLCT7Z+>~oWs*g66iOP6jLYjC z1I8S^cLIB!5~;L^lo7k|en;33dX2iQ^VZ|5HAaV47X*=1pM6PmoVOztM^m?Bh2uOq zB|PCpFGpRGiG21kq9aPNDY;|WaiEahm$g_)$AAKK6B?OQy!h<;y`{LzGzF0CQ-UZe zGvIesb4KaZ`JcndrLr0L#W&LHqNL%)4apK(9^wIqo{gCX!wvj4Ha2_KVa!513^M#d zLMqFfDpq`19`>CvoH+{@06D?F2j7^n%U8PHW9UWPL8Wkt%k(u-ne-Jxd|6T=CzO#Z z42FNlU*$Xg!ZD`P@i$mYB$VQKM)hLAQns@|j)SJWq|_yQkZCN2sM(3?%cdsOVxHFA zt?9QchGTWzKysN=eW4k1uEJ$|E~Nuld10-Ui+c`So+31X&|{CuyOWj#tjses!F3U} zKfNdtg#crbEUcEyJss&pT9R{e3Sn^*WQCl9rhSCG7n-E2AjokhDb2_?a@%8c`1#Y@ ztp>1&F4j$s{hULD3`<7DGZiu}Er#5$?fh_$y3)nE7Z!XN$}lu=WE5B(rzRgVYrY@E zr04_*7>T=(-n$RReS25B*m|qQ-033i^0{%LoK(l~y)^r0xM`8>?%VaA-6%t~2lLj5 z$NGh~+D0vR_)4q|mp~OH&J>PpEj+f>#s@R8;Y-UHmVPZW8?UE8^v$eOJmR-fb8b&} z1_GsMS)x0QQ_HfIh9~R!PY%ItUUy6l%Q(MrotC7SAW;H+=83%zR&G8a^-`#LJb6Kl zG-KI6sC%7AJ9`K2Nc&}^QfD&0%6zkyr=U(gEYgKij}j1;0(hj9#N(OK%&W<5W5EA$ zn(fbb4LwBJkqP#5@7+87k7j~8Jsp;8@$~*5M3Lh&zp$_c2f-hssCh`Y(8t@ePY(=M zaDh~UQ;Hp#CAMICy>cEF12C{gh=k@Fn>POTr^0^Kw6BOh#%+V+f2NHhgCzZlU@2HuE6$u(YSR6@y;Wz%% zThZn-2?UyXFT z!qZuo{MA%VuT)Yze{qi{afZnCsZ<#c2t!Wq`pZ_@Fz8yJ$dL5G#{(#(`PV5EvbP>_ zhZOyGvLF`0d#Y_AO&E7cCgQQoXFKaC9d@u;t3k(?@=NOoCi`8F_@y_A$F&&xlP;#% z+S{xDivlJ%del=~b`9BytZctL~1Q1qsX`dG`B=@HV8wNz}swNGmjtsH4~z zhC{{^^vrbG*|^5r_#a6s3sz4dRq=Wq4o;T%)5`Rx8#=1{mxE1F6&xhwWC=7bjf|dG z`}jI~Csf%{M(-&-l9~G?T~~B9ozDX7U9Ut*FLzHrZ?}v;(n06WPjx8zp08Zur}e(u zLea~JF?1Qz1f)5aHGUUH93oRzk8F!<1_Q1>r3-M?C=lQg)(^We_%E5K#j+qk#v{o8 zE!te;gLMm~pIhM0t$w8zky zmAX4Uf<_=n%?p2c#PgDl z42l~b6epI2`&LrC=@sIZZ7Mg{ZY)H)^PI@x%y3N@Eo3G@?(E?)nWOjcc$73VXI;&T zYKE-EDkv^J}A# z8Tv%754?=dLa4BJ3@!4m;j?vL5J)9bkTnED>Nuocq0R4x6?${`70iEsL0%XVPA}9+ zvDg2^8pBy^9i_@9UE-AHQVrVWAd8!89wd@%*X9r)aRE9HIttJzqP&lN+#(FZAew4# z>YG7!08=hDJS(WWPDukD5B$rkyO-x8?L33x!R44(Bb+8Al(>jY#j_p?g+d79?GJy| zqULoma4izJva-3z;~b0gSFPu4QB|45K2Y&gM9VK<{rayS+IJsT-Hd#0?n%l(x(6oc z)dm7CP%Q0Czo--8?xy~wAL{l(NS8>UIKL}?RUJ`?7=xI6`9CzPUo^wtzmgdOCm7y@ zKqFgIDmMN{nIg%Tt7HjJynXl(lL!oCX4A$h2B3Ju8JG5N4Y}Gx?*|8`2goV+&#cuW z#OlP87AFX6Ts>=V)MM=DpqaTrKfMoa-)xo-s0$No-D;#{zw(Kshv|iCz>%SK-FP2p z^pGb#wI$bG+;=t!?uTNM*ev3?bNk0>U}figHiMiQ%aYpnd8BK=VAIDoq6*q0)z(1H1< z(f=Ji`F}(cKa9sH7G`pxnIwDQjy8qO=}J|1TUN=?=N)cd zx_>11jll^6lOb;wJ>o@VT_!wfftmreOF6IUJs_!JVTE*0uD?|Fk8M7QWC6-`r-*?d zKG<{Tmks1S1u4fp{ad_P_}Kxggung$c9Ce3-bIL=LIs}zs`{h=1L7Wi5}Gmj!00rd zWYKYS_6oz7S?g|4R3p-7hsN50mogc&0*EUPfJ2ph_O%%#c<)V{ z&l57=M%!4=E56a*Yx78r@A;w}9-IYKF2+}U7id1y*)vYU>4JGV4J-s#@`hT+i*u-0 zFrSBnaM0$rZ!23UY3KRkMRTSiiVVL)JOyOZa6LIk+=YdVAXgs(CX)3eFq>PM|M`U> zDrWmKrWKPTBPM<35VFfL>=_8nnfMHUQmixlK86XI_@~k{zs)jecS_=#NY6nfu;6VBOgAkr z4h%{MxOKUPrFY=SyvKryc46k1lbe*$wU~5c>CS$joCwC?aZmrYE7b|Z^=6rm2@d9D z?|J1a$#uEfk#0XrA9YD+1rlMZZN<-E3E^&ckd{k`%~~la2$}%82Y`O#Lb%_OVY%i1 zI5O75-T25@E5tN)Ud}5Hs-?*+4gQ?95ZAGYp)Z5*PCGK;U2neA%4J7bK%^65$L%%v zyr)U}Hs2Gx=%JWn;P~+sC+Lu>L@Eo~4rO{;W=j_&OK*E-yTxawJSQRuqu>zFfIY&1)1(FfS5=IdA=ofI(K2iQ0C1fyr+H4)p>Nag8 zMZ$0`R1<1SBJw`=r4qy3V*KD0Hejj1^XPG^;mq3d zMGSnB1^+6sNTK`|p^Y4Z7rTpG3&A-kbiQg&h65C^JnIPI+nWtQPo#0gc`;83(qT3(1w47?iZHNO0VOxgbXF%*`RtYvm2aP;dQJXK0ofe z3$Z&h-hyW&S@9RwYZc2HI2b6)E4;+DF<`~kA5h`h5eY3^2K&XIDD8Sw2tp7y;j}QM z*fOJjtOYC75?J7r(c_&Ey4hz4xDeAv5S*MyBmYhmViY+j3pK+)@XKXXM zAb-vaW9YjtU8p)|3;S(l2cB)U3x%cuj?aFru;R1Yk?H|%N#K+?%7})!g+#|(f1Hp^ z66G*~3_bRAON(3?lC`?Avr@-q|2Nu2hpx~=egJsjQQYe`;$x_YEx^VMLCV5Tp!A6dAi4Cf+pmwTosr zRmJ1T#Y2SC6Fd=miL|`bBa3zp!e;sr%}B}Fjo;9{?{YV1W5wL&?VtDdA`6gk_H#km zyd$`M*48kIp+v@=|3MRtSyqH4n(6~Ni+jEu*!ewNaGu zvKbH)Dog=H&OY@Mrgg?5Djv59Hrb;7xd3~PyqP&&?%dDv8@W54XgSK^%vx-7R=|iN zJQ>9UffAN4Y8cox(v?jDj}i%VE+K4=RkXJxcoyOdPC5=v*4bXgo?$0UB#ansGPsZt znC;VP%om4Ex@5Ac9}RBBvWJ(xaWw3h>eN+38dxfb_Wz5lw+xHwi~mKXI~~c9PH6-r zhVJf8X#}K8kPhh@x?4fIyQE_XY005GBqh%NJ@@>dd(XMAX20Ce-m}+Q-%oZt;Q~0A zO+WQL%?}I1u>7Bx;bk_*r)ShOlw|~)0_1z;Vs&g~vD#`a%|J+(K0S{6c)XHZ1)x6}U50@22zaTp+reVF)VwMMi-994k9#l3$Sj zzn}%MxVkn|2|nEAWHi>|;Yl-zXXnoi!@NOxdEvr|`E)}&TWAsxLw|D<5vm@-`PupO zk57jj!2{-k*R<`H_3NR;pH4ryMBXN{VHW=+=CLfHhP^X#lF>(p5>K7T)EI@DDaP($ zMU~UR-j~xL8B!+#1HjUDOpS*>Gbn)n@kRLEL+{?y?aSSG|35?fKul^jpyccKSeP1- ztbAyK2k1KxV4@)(TGXS?&n~B%UvPTz2C-Ot)Sx9rVs3@gW1$|d0L2=dCm7QR=ED4m zCy@`879jlDyNC%()WaSPo-Q=uX^g=OxSd*$_2paNbjPwkw9q?+Uq&KOr^9TnVdhZ{ zq`_cgdj3%wh&TvEt4)d+ks8^+zO)~ste$#8CFD7O!knvMn1`V`R6;!iTF$vWhxo=m z)PA~@?)Vp-pmbOiRTRd`MBBq$y!zYTr+@!Q?7jgJe*Hr(Z`;IkYK|2`>c$L|d2}Qb z$(M6bOSrVG!no)S$m{$jZQc8(rzz&O+zs%sfDc~yyCYC=K zAzwN2C|rpFYdO|a_}r51fhaIqoQ4AQM5DDTf3bFVxjb-+MCiyP!_1nb5W@IowAwiO zYAMuu5xJd}sm!F?{MAmF85K}Is;;{sq}bk4nGi=eOIWg&;#5&i0m?mlEyMO{L@DX& zR6!CU-;YNzHZx-6@GSQh?d@Rd7mwhtusDcT8zuJN6z`6$>Tt>yAdl{uv?U)RnG}~` z`=FkD&pLqRo6XLhy%s2)I}?d`Y^hK^W5ye)0m1|i^%_K<{qwku*_&et`M)yT|I0X4 zwan=C+9-ngL%$PTr4XB1=YoE*^PeOv(S79?*aLKYQg^u_M{NyT-%j&&88g&jVWoDX z4t!R*!L;_xPR6%7YKL6XADMUorN&H09|C*MdLh$IIx)sP3F1%@PioyLa~ZSvenKf0 z_ytVNZfeFO2vDW(b0?OBGiuwtlxp3V70hyV&^P+R5YpI9>8dqyU&cNxzQEIJ5e2`t zxbJ{Vr~Key)o%VL5VR3?j(`L0M^zuAwz~d{O)k5x{9#Rs)-Pc?6$7?{1!TD!5ePXd zXdEo(7K#Sr{BJ2;PW_VYMemWL^(Eea;?9bfuNM#ppTE@ITGyspMfj{W&o5tPlnLps zmLHZ^ow6q>dumqd6&41PSzvs;BpmWVrxB%xsZhkyiRA`UaRt-K9HR+v5=z%1NPn}F zP3B#KGL*EiC-E_F#cWMZr(Awy-GUiUKr=UBxRFCk8yUJ;CFd;CPKHoyZTqLrKqqrzt* zIFEncbkeW~{OOrALixJ*fD%W-=0kq-bm3AJwIf2IS);-E?epFX%6d~R56>S#-e&2H zo&!s%%+l=aydrQ~^V*jX?>AR-)z4fmk5JaH3LssJa*sC%!ep`hPv^+(4AX_h3#aER z-B-Al=UAdI@MF`q@w~4mM}BboX7T=f%>l)Ma z?t%C7YRgE|nng=`0(ez6g(62L`opbgzs-%)#&%RnCLr`~7xLvH!{Oum2hx`)TM@&M z&m?!(C#*E@o68n`d=ldM0!06NRGpZXvSKbz5Sghp4I~#yau+PEtugSDv7DdhL9Dp5 zHc@yT&@Le;JSM9HxAdCA78EKj3=|BvOmMI)vs5Bnkhj>8U=Z-Cs;5Tqai!gQxq#&> zPr1Rl8Wjt*#gZ+V7s;Yeul=6vooJo+J=%=AJ!4I($87x+x>o?_azYuiEShQthc$BU z*lzyN>`**_$?K(>3$0qT8eNtJe91Zhd2+}D;_?w1+@+4?l9dy;m+7xWE52l{lDlrKVsAPUeYV-ukM@UGIlI5Ec zh*x)L`;_Zf-2x8~ZirQ-Y;^G7xOys{Ag6r}j(cfuE_!85+92ga{W%4l8DGQXTT==} z2|^K1J|{^ix11r(@jIyQyAWvU;mn-&hZ+z)p}NP@E=t?5nrDy(qLm_Ma`GUCl|JbJ zh(hB|uPM3`gjlv5C(jAp*D(3TYe)h(J6xvk4Yj$^d1N3k#OKLczCyv5Py%9?>68^+ zvdAMHm4`VA{3?k$2k~6S#Zj{|qDc9DM<;WZJSKxp-mK%}i2E zSqqz~OPGf}AG@+^GL?I`{ch$xlrTUN4c#_vVTxuDPqDCk55bgm(zEQ=Ljm5+M3sh>Y~Op!8K(w{|>u=OzIS)%Zw z^$hYyeM840HfAvUlwjXbUpVcY|I>BCBbCNDj0H0$b-WHW$OcYgydwzUGkhgK)>=YQ z(y?{DwFlfYw7m?7w)%F`%SfA8B9lM|+J&v!yG$iaVRU0X&5AKP-)q-6|3?e3T`s8Z zrimj>#k1e?MRu4CpMvb&#WI2vE(2QaDZ0rOtv^X*a45a_n6+T`?Crnpcj8%4BN8aB znw82>HCH@Vv1?=$qN3f5bCk_eaadtzXTLN5uPZQksDO!^b*zmEy7036^;@-mz4b&U zul@Yb|9$b?9ZCDqw?el4w8&wkq*EkfXlPqH)GCBhYcP%*NjInj%Tk;u}rL(VD z_8*QQZS6Gk7(tg9?&JcXztVZ~g61Awmiw{ZR}&vdIR?RRMR#_3`W(L`l!ji>_ZPVh z!nw$^R^*0Cdp6JzKA5zM3x9Vz8O2d5i0ns>9C&%g^N$UoRT~|so|79*uYNiZ0-+qA z`6pl8W3!3ts{ttzywNUiXvz559wsREiroBfU+(uvR`S!ddSeL{P#PU=9ew{i{85Bj z1+lwr?O=X{nB&~PqyFx(2tFqC<^>W|VIUU+S7-j+!#Uid&G&T;+x2;?jB%LO(a-}r zsU?j1l1K5OTNyPekG9-u_B<# zjl6dqIBkr#OAd_=XRUi?JW)s@s%xUAkH-y$i`l(g8mn3x5#{?o4h$(iz+Sn?Y3H6(Q^|0V38gn< z8SHoCt3Ix)6%cF1oeAG;2uch-a966FE|^OC1H$I}p#Mv8GJc4uT_$4yWT(`?U$%Q= z%h$G_f~v0Of3Ocaz&~#|9NXYl8_Id zT{+nDC904PeM7Q4WV0%y{MM?Rp38tmN1N5xKM!&i{0IJ_e9x z`TC{OrNgP8bMn>%`afMtWSbkM3B-TLEv>E;5&ceARkh_k`io}RBB8Ef4ixYa(T&k> z`o*zZObIlh#O?+{3=15{6GEer?f#$JQ=yT-2^I{VA<$Bv@WWzElEjm{=qsGqMa; z=rq)zfH|=#wuV0SjL=Hc2u&%sPLCabxm5oMJ_q`UV3oeH$lg~sRSXhjguRdXNmH6) zY-cTDONV0hgZT>C(8@bkIaR3^+E+)GKEn`4Z&ymd&tD~}ziay=h>(_@XH+4hqKT!V zmK{qnLsz>d)ry*V+A8MkZZQ=(5&i{O#qkH!ib*x}_l-C+$G>)!dSn$OO5sAUPOvWyECU!oG1xcer1_ zi#x0N>Ju$X31N_TTMp`fhvg!iCDR;UVnnowxo&4>7)8Uv{C?uz+<*F(jaip#A9^v3 zQGfA`M#1*C@S%U8W4pFh4`U98mHq(tT~~lQyJ>4++3Z1?=M(04hcWs<#OhItNkzFz zXiUsvR5>x4q=HfwAMYUvEkOoyL^+FY5GXS#`qUVyH1zj0i328b?rdNN0!&trUM*>t zxr#gx{!uAtirz}y+}A^+M;y^=4$CNYn?a1F28wDY(&p!mph4A0$05E~FK1_5QJk8!%BVFMKYS>jvZ#?^ z>@`&5J2CO_6)!)r7m1lMLdXBPWz7G)$FiKV=gd(N5bz%~^G*I-CY>3^v?8;V1T0c& zW2`0#~Kpu#Ac24lPhkAoXDAP1_h{(+(a#7LJsx8Clb?imhrJ+vR=SqZ%A$ewv9yFRhL4|3$RkBhc5uxUaat9@DUG zE?%{j5GWdVr4SaTn&3974qvx57ozYwT`Swbr`~+;WVCgunDyu3nC;Lbe#B2Ab2mF1 zJF+kopl96$dp+Mete~>tD@=d#m|{Ad;JcPdruwdXF(jb|LV>BM@(T&kD$XbvaucpJ z0XG#`I#)G)jEvpXEO&{lNrIU%{pqi>Ll)~~I_sWZoMbLkPItQegOB4G14FnK;nq*& zq9sxginIp4H*b>{U+c{buaRMGHVZC=u(g4TORRJQx_}5|_X3WDxBzd2b&am=vdbr( z|2?3N)yeU!jxMznp>XAc0IG7$RQj$nTHy45-g`<7l`ufGT3U<)TE+ktv<6gRJL1r~ zF}j8mH9qK~k>ow_Zlcza7%OscqZOelEAf}&H@ZfdoL;kJrYO1kV43#bkbm*%Y(tGy;zVr%1z7*j2hjgXvLg9Mj#F~&X+E`5r$X(!2JT4cLgX*+H3WzKY z76E!^^KX>5kF$8;tfskhV9D~Aej*_~^O@h#*VHk3eVvU3<8Vf17x&SdwO5ABYd$aJ ze$S1%&c-2UOzw%vzgUu3X^kAseWUo5mKIl0#&*e_x+g~JHQOrLJ*tD~9X)TG5}O!s zB)2#VyK6^A4yXgpVb9-8x+jkEd~rUYGhxZqA<{b}wQOug#FOGi{N>B~i{^OP$X7Iy zojhCi`v_seI*n-@BaK;I&%W1D;S2sf|B--;j#c-c8Ib+`)KV7cpxvvE=H{6|~V zUFQ5`9wS}CSb&9(qVWbD6PbP)1T6&`d>no5a^pjk%im-$%h#prG13iS3vtLL)60`= z8t}R!bj_7g{ACK0%mi&q$Ls`C-jUFw&xSI^k-7`f$x9?zA;Em?7Z3?j1ISc zgIv<{d9qa_j&Hm$`oD2=ME2t^c%DN5QH5M|x^pWH25lW313Cm>KtDH;ZiEr5TUs6P z=IQJ39*dkEV+U`{29VE+6_{lENn?ywZXu;wg5Ad7tK1!KiZax&cGW#a%VA>D2$~}a zoii&kDaKkLkRS`hIZEnx-VhO?XnR$^Dkfa4Ti)c3{_blC>d^=(V*S)&sUKQMnE$$G zKn5Kr^_M2GATMIb*J%vwRD%5XbY$zUk%3nz{35>{YLZD-=r+7J_|XyM5pq#d9W6}# z43+8#!QxePGN?>+qeIR~ubvTBO&&BY z^JFQzvkM4OaI+Divk_z}3@6hMF`^;kMEEppFYobrA60jVn=k;lOulj1s{PEFC%PZG zI?>NkHzkXZwsQE9pq0kfk3iN@(!4m5oIH(Pl-PW6eK`Qs2-`z}_8Hf7mlEowvO_{u`S2w3N3qr~8>;LKkq$-LFf4QqX7r;@hnT4$F;sSvgIVwJv+Zd)V4+}moPqI=3#|}$=_hY8JGdqeLyN56s z3{b)`V5d2pIb7~$IVGf`07;ob&7zhf8J9CDx4myNtLN(kdR>u^gui6!!=R@wOSQ-``V zlrxH%_jjg<1buNUwF>R-*f$|B;>T^(ZfP|y0YL$Co~)2M66La(aJMb~(z#DA_Zktp zpS|Ufo9HuCOXZff59(#J!J;MF6>xr{u08cnvHymp6~(>mBfQoFvY5s)#v|@ja?n)I z-h*=!iJ7ZApD}&^`2rYAQc1_t&B~wFe~!5EadypFkT2dn&Fca2EJD7PAH(IbDZ2vV zpE}dL4@xThPA9S)&OX!B42$^va^~4S?ub2lkYfhg%nT~iVQJgaO5hz|IBD@n;KK+Of9SWX$v$%-HnO`i0Th?%Kvw zCB?t!XM+(#8hDvvkJ@Z8ljy|lW8wU^m66Hlvb-4m;G#D(sB8*4>Qd>G!(;RkDIggj z5?$IP$(+_h|0|yqvrAnc-YZuSk%C~lMj}x#4U8-J@PVk1uwI%sb;}32A&~?}L9SSf zxJn_m*Gws{KuiIUO&qxQojZ{<5oQaWDjRW4g z8^6e}I#$H7qHmf>R_M|}NeR0cqSqw>$(xp=`SsEn{q7KWKc47z)>+rYY*7U8x;v%Y zXZvuB5WC}|@mllsNF5e7|5{3^jQ1u>>dYoAIrr)MU$ESzMzHfVIVPqF&=7-UUJr2r zCIh9t_r+{erR7P^#>CwWqWX7@j^u&&ev@XLuK+DiH_7I$#a@wm!eVA9Q~)bZU>ENm z$^Yr5dbUN2F_**V-(=qTS@*-)xmA}E^BZ_!==J&)HUp^xd&AC`D=kFN&HNHA<0TVk&Cx%owglbDOAd80}k{bszmTPPF73-Pgh<1N~ ztG;YI`d^fp?Cqw+5_1v2G!b4kOs80U{XYP&|2Cmrjv#}|LF*4aIDSU!CE8A#C=^yY zmm9rE>}MxId@ZTU8N_Ozw!@gL7r@Y+gg0(=9a4;>`iZX@=8R;s2S5*i_4l1kM)1$! zX#l4 z=(zpK2(p5@p7qi`AH%vw(z^cA7h3hzGs=P?J__6@9@G?AKhWVIW%)$VBCmYK+QxkB zLL$X@5oy)s$V_&csZUBi!TE<59i+f}*YF%b9I*d)`S&N@QKie%b|AYf1g#;n#z-e_ zy)G1JH13Nf=Xei}=NHYYsc#H95}>PqmYfj^;rf_p0D>aim48`svNg4HC8WL%r;g_B zgjf;5NkwI<=)`Pt8i?y9vkv)c-np4xKIz?Kx_j zo1@w2pTx5&bgSzO*v^q|&DDc?Y8^_8xXwDS*x{S$kg@#+U%gc60E-@Hh&eY|kwdh2 zy{z*pt&;gqBh7S>qI?tD*E-hCr4cT?v(>$eWZA#}zBchS$rpu63k+FC$&8iF?Q1Zg zBwxfVc}uhyxwv|c9vnn5RT5#a5}`PCe@%mRx+EL4tJJT`_z-mw4b@?P^%HwR!bg= ztL=>hytDQHA|*Q6rPU)pDKG8c}F4ryj8O^hTIC9BAfMFd>wRiA9^*?!9D-m_(LKAdAB(x#D$XI+aa;=<~Ll<(!H zwh5Q*e}2q8*50Kb-N?dc(Yw$43dUr$%V75(jk>plvOCxJ7DG2pN9&11|6IImSa^%% z?zVpp;Q3I^8pM^d$dZCsFukm`=ciMmC1>}sxG#~fsg5gE>N_EH!css|k4kFC+o>TF z-SIU$W}kQ14o|Nfl!YLb8it)oIOK+oh-Sz9_ytEHk`={DN5dK=YYT0S`0lTfn8!0YkI+q>D`GE2wk0UK(P)|DdnUe8+`gqd3o=aF-{Cn;#`y3jIK}o5mdlL&HLuk!Tvj^@qF?W1C14Vu6x0AKQ*T}JGjU7g;+m`$Qugau30uSotj-R0pv zi*)Y=}l-pl@m|Xnf>M&2MQ@$=L(qR`a#aRlEIx@aGV( z`<#Hw_&cYU=$Du$mNaMMEY`8|H=^2c_y1o$<^P#+Ov%Qq>G?v-t? zH&>q}y~*n&>^@Skh|u5_CgZ?|=*rlyNnxkYNugQ;jy4#RCE^=% z8LwyDYw^HpK6Uly{%GM8(lR{U`0;F1JGciP|8jn-Um17dnD@DP%&%?xuk*0e;{#<~ zX7EYyky!J}=DF>tuTwxzXM6n8A7Fxd#!2Ed7sw%yWww>9n4?lvFi#AW_x`&Ig0;-EZ%Fcb-1LL#=NON~G3j$j)OQ zt}7RWU2dG`Q?Z=Z*4Iz$4pIPaU^0^puAJBmAle$387;5EH=ode*_Hz0Cs)Bs zjgCkm?4y)K2bHO>owlj?kiY2-mK_=gkj|zsBF^>mzNbhZ$QsyolI)$y!we+x}xN}T}VT@-Y1LReqTH;qL#*2&8O=2ya3_; z(SDCmMvP?eaW>#m2LtO9W&vmPpG=SzSQ0ffuy~{aiwbS%t1^5k z^qKFmOQ(Ey;Z6m-{-*W8V?(Mzg8Ko*mPwlWXUe4_`NSl=zf#&F0b%1RtSQ(>bPXWkg)@^)m`lQML|yTObvuf~Y|!Z;!}R-~&U zK|%8tT;~@JQFejgl^~B2GSTB>Hq3L-K*R2amkbNaSAydO{6*j9(H;9IdH=i6+uK`t zI9Nf?N zb~YcBJH!e@sgzxHF0wf@G@`zFE|lq16nN~cc|b$pOXxWM6Bdn8-{AN=WMI?jN)Jv; zxsquE+OSvDK%P+U(P*R{hzZNl6&W$)r=VZhpj@OoNWlOkeeqVs^rCiQh$KiOrB>sp zT+;wEsE&O+Tc*BsZgamyjCp{ix+C0z1$oXZgoe^>FQk2(Sh0_PfTZ_k(u#FxXQWqi z&G!X~&#TELY-^;SK=fvp_{V~uLC#IsqQQAP5R~ob{0~<_(P72H-Xa-LB*MKhi+IF^ z&A77)q2~1~Wz&x88XD!;^mMQ|n9skQTT(n(R%^E?>^N0bbfb8g&NxS~!val=E*MM! zL}`sE1|7{aVMYsiO_Jos3y6v`#@$9T)cL{^Ml z;}Bi^GioHIMGuLFiYp(br7DD*NFCJxVYJtc95h2qh~J`&iC~9N)#kjc7}P7S_u1nQ z;5`Iw=z&05r4IVioxViU>KSn;YWwKAs5L|Z3y=C>=&n4=iEE>W5EfSFif_6>SDr`<GJXQU1p zto01wqXUAeHHQA8vGK9r@{{He?qQV4viu?9uY%n#Wlz_mXKAhhJ?BnI+Pr7 zYd62*fXA+B9lqo~@(ESWc8;z-W7nB?0F+X|2-7hOC#n1~M?d|pbePwpJ974Kqz>1< zfCPFH(;$g6SdWzmKMmsJ@P6@lrsmUlvOtw<%^}Xi1X0i#Elvw}zP^*2|6dTSN|T&N zPk^BQB8qjE34?cCybb@34f>a<(di$!O#s=6=MqE1fDYX)ro4{dM%@?hZYkDiIo|Vx(~U7(1s&;jPG@ED>1V+078e~5 z0FLA1oBNLGeiF%Qp;sk(l@b7r+5e|qwqmZ2M6!LglvUB)t_5hj=`y8_vrzi+WA5wL zf4YK-yDDXH1VD;KZ2OE>!a7DvR*n1S5Jk^hftCcD>aJ0D!TxIphxUiEMh0|5Iz-sb zlzceto0UrTtO?w)xnO=+LRjhS+w++nmR}WCa}jzH8>n{j)@Rj9j>xf->O%@-l0-YzP-*0t5sj?z%T;VRYxH`0d!|XM$jADKwo67GT z{N^ak3(x{WQSzwQPcEMdkk{iWF8o;5JLlq`egYdVPu?YlR>T*AGly-j6W#nqaX?^; zETN#_XmYHnAm2InOM^Ymu>aa9v<^Rvnhn|W$9`iwPdhKf6lj~!n~>oCf$>O`>ijK< zo*tD}5!0ATA;>DIVSB(QGl(c1TgfE2skS(5I#|R0@yk4o6$E&v>sA7JKsY1sCx0N)pE_2f*p(^j zP4p6wmr(1NWm#LOL+o&iy081W4%^~WRfL3@d>C9GRJw7zojqbX-n;o8s?o6Q_~nGX zQzdQUgzcvK%)(MUX^4qFA+?Yv^WIgaNkI-M({f;d3wV7N1=5WL9pm#+uXchr9exd3 z=h4NUAMt9L*P;{86;`e)E>;b>61cvcS}?##H!&UlMd15a%t=QvMLB1`JKWL@xYoVD z&wKIdx*Oo|Ka3uEMJhn6^SCPd^bg!bao*sWM zu}(O7mxJA3qY=^C8^jE#a8ezI5jfPaDOH#&15;eQxpS}fyf$sR)V{hX2Cd&O|BKPh z?9CtJZbnBaYnVE`zYy0l0yzlH(OX>Ab{XT8l+zRlQ_E+6a*l=!Gzt^qyhpmfvR4*~ zpJbD-k>e;lF@b zi-5I!E_)j_RG9|sf92($maIQKzr*r4!|?)orLU8)$84o<@^d38k3GZU|Brx~CNfR@ zC;OMjm!K}`xq^hlxy13+EJ^z}(|clTp@j>ln|iqVCKI&p=+!l-)SyO6eB{bMa7w}< z9L$(c5c#AACX-{sSGo3FnG+ci1Rt~W6`jHInRcmTZ&E?PtYt5!AqkRhAR}iD+C0w& zPE;k|MtJp>3zl#fPfj^i*Y*zQzIrw{`PhnDmbLe0<$cXz^rEQ8Olt^X!0DD*dZR?7 z$c+S3DfRwL50b9}HO zn+v95TU}GEeioT{V4l4Q?e8zM1*oT)st*ZW(#L}Wy@z2T&n0>G~gi63!<;usWYhbzT6IE zQW%cPHmQ!_s+nGw>L}!t1LAsj{DPoUC%2LC^l4iquPGbA3rH4=9-M!Odh->?<+-|t z0xWmq(ZW)b_T0E|J$r>5#GF|s>BHT0IvTkm)iG&2nve;fU@Nf05qM7AS zYdK(}Hmo?ly5#P^f&jY&V_8{)0nVohRO!_G=ootrXzfW)Z%K4HAtRb?C*0_YTriRn-5yLPFnI& ze{bgx8kkF~;#?##0|UBJF&${f(=%lO?{*ji3-78)yr*xnXW59W2s~uv%+>W0+PwBa zqsxBAm7%nMjb>>V=_>rGlIUp-HTR4&heOVzH-|C4<$0L}psAAI2qX^_6Mn*)aOWDV zqmFlNm_kup* zoy5qd3P;uMc>F+(k5B$Dk%q7Cx~kSGaVKOMI^)mO{PVh>7T0zdkN40hBJL*Ppa&tg zJ_*{;)^7sy&^7=`+@hl!qiOgtxaNu3pbj;#C@!3$M+`X=;E$Vdfb?FlDHzwF>w4#w zt{rRjWpMr`7wM~$zxuZIVs)l$L9d8+)v+h^PoQzFyv<|bbfvjDBR3v?fTP_?I?a#I|$O zX~x0Qmv-OPWmwl&Q~&H0;eKg{OhROYAA71E>*bndlRxS~UAMmL%`u7P#p5iifg0vn zM5&I6Kgy3jaJceld)ywDN@vOz%ZJ(pS_mwLOY7T0O9I<(@h^6(fHe7XP|8uW20ch( zK@9Xue)z&H?ZP(CChs0|CKx4fN?hl6pyR({b( ztk^PBZ=~57{>IiQN+nwZWhestK4#iMp>s}Z!6T|e?7fH5iqtIf7>n@Z@Q@aRRYp-3 zL&m#|a5wiKJzBp${yIGsanaJ)Hrr?LAuAw7l^v3G_kBy&C|E0M&6h{(jx*#TpOnqY zmY`AR#ZLw6t?a#Yee#X|@;tAyt{U(#Yt;D#IBukv7Azb+WvC2mSff|IqRV^SE<0Z< zun={a^&rPq$a8vE%O<8tXh@3u5&7ffUhV_!79NW2Uokh8Nn(`D;$nlx#)WD)ADI%N zIP;r;$CT&zUPjRuvg)-(`0j}zcHE6XeQTdko;L@ch$kg_uPvmSMg-Y!tKRoiJabwe-+g@Y#zsI!Pw*MQfK*G55Y-b59{>JiRGo#V;LW3XAtYRJ^Mj z+QC}sIE#!%$4Ip@(|0mase>5)66VmWG3yOR!6IV)-xtpkq$<|grh=0AgMXHntWL{* zR`QLE2FnzQcQ%GHxC@@pKkADS+0adABi7)A8F2YeYfq%ynD zbALIji$QajCHggpa{U?q%;(m(^`Q@oM1qz-_cAj6g<5&F#JVj#cW~J?FC5W=UyL#~ zeZnFxUUs}+;rnkXE3FYseALIks*f$hz7oS@DIBbk^-L4QqGg|lhZJ# zKd2}wcp{gk{>bj~WHyf#>kp28-G`$7Tb;M{ogSz|4c-^`y50{zbkiwFFDnEPbA_Yo7MVd3u6f{nxBIZ@T&S zU=}F0i37OK-e(FceT|B_efJgqIBERx4492xs(8QKS=*Op*yqGz0YI$kGHA=Q*|=a* zG;3o1V~*jyg%*Q+Fn;q=;p#D<(UI*(h!{eOD$MVmA8KM%adhA$i^bPql-HQyEE%S+ zU&@B}6ZBu8k2UT$2&*_&)pm6FHCN1DI85;-v6gBHd*XUxNK*E52?#>W_#rYRf`&HD zE(Xe}3vKRJ0J9_Dw#(xJayc1D8-719eg3U&R*DH{rAa;-j2-)>UAjU?_D%4n^EWs@ zKryBMt8mC(ma+@(HS3w2WLFirr;{g{J_Aq`Mv`#x+`YdKW9e}NmxtV|p796HGGuh< zKc;N~on96;DiZcAHJ&7HJm%zYdxsnWn8leNhsmrYzo2e)XXxhxhipM(fqSLc*a>AF z9UV2Tb>&=ZxfC})=ixn(Tac5nBZc8~#*f6T~+0Ocu-^-{-O{C7kVT;&X~< zmvaD7G!k>5#@0N<-56llB1B<}s{&i|6SR|`*N2{;5t^&k>Cz|k&N!|bIRYYODf|Ls zp9MvqUsHqe}UiGN)TGN=-@0gk}9E&2Q%xl+VKgp-eQtn<1$6pY3=v5wX25V zGck7^+%cbdKE30?DIUiN;R@+D_Vira=!)KJ_1JtY+S_mmAVRtciy-$n~ zpa83t2QN5vO-@#>#K^vv5Eb7EwqK}v9i~Ho~_;~>iw0`1SkM!?Wt<*uH!j@zm>*Ja5rSK9=YSX#5PCIWgGu|LKy%RiO5y5-> zZKY*1Tr2#lQ);Lf+jTyNw*e`(KOo>0ijj#Aqagi{@pGu}ZSkmUm^GQ4m z_vmylvjH9iICpTM(C4I|8K+$;ouOG)#HqPl&ZfX{ze$C4^IrIFf$|@OZDKQo^0C4Q zXbYo0hrQ%+xL)5t8;nYvA0X{%t~<@51MAO6qCFAo&4Zl50k^U+wePqJhu&*sAMi>^ z8Yz-K{Uh1}wk={~TPnrknJM=K)Vo&#tQq;qAsV)&ir9~b-Or%4OTNn+0@0^r(eS~n z`jR!WfLi>o#Q(EV{m+gSFpX};4^Ap&ZqpX{d4s#RFZi=s5lZMTD4c*M`dcbU(UMden>7g@{xWs*C0ca9JW@eVM4@)A=v6@$R%L{ph-!w0I7!=JR zL#62N=@`_(RDVb3_FH(tLW7LfL^3>|aKJ-_TJ#Zc<_RmLijS_|psVdO5i}F}p67GC z?ue9KvgCVc+w8{Q2LY3SYt(RBc_iB=52e}Cg`>?j_DozCFx->eGEx;ZU`v9W+_0=l zR&3P>V{La;UH{SKZl9ny{MsAdNKO(ySyA2HcS25jg3FUt(^jWay|6cb4H&+Cq7Oiv z)G%r}nmE(1Z#Cc7IA-1R{1Wt0Nd-790k<2TQp3HQNo5|KwztlXZZ?3Jp;BWC<-yvnI>b zhg-C^c;;NsX@V&!KV~w>4n+(r)pj+>S1J7YGB@xpbfa;>RD70a($T5DscEo8@z%}V zJ+z9v<9th-AsOSzznc)(9>A71=D?Q_D?2-k5{%J0I+f(ty+}q2^zv7SMpHO(@$nfk zg9$9)eyLs3vdP?`-yZHIw3zY}u4>YeRaDs%E-Frip*_C=#UX8+Yw0ZMkSy(*_cbc; zW63_E8D@XvE~seq<@~w)S(zBP&DY4xE~(sCWxwqDmJcxr2Y9kK)7cI8VCE})AqVO9 z&8D&kQ=dNQed5zMG48uEYU0Rd#C`v0*W*C8W#Ex{Lcc{v8{-Ea>T9I?=j-d(bXypkXndsJ5#goZ^VYhNlyN+hyhLw+xkKgT67M&ak4g)X{ z6RAU|Y#W^ap!QFPPIE#2%EePY+P|P&myT^Xho6)!o}i)=7w}yEq?4!NdpI)c2#Ds7 z!!JJ^Zeoj=o6{y!30WGKO%3k&&7^=+y+o5e*?QL#^4pPk!6R}uv}ih^F1yG*$if$R z5REdg$EIAs5p6bbwAWvrtY#eKI@hG$ko^}g83#`oz_10rStsR@Y41tJi;gPK6wc@U>+xJDa*d>ook)LJ|##z{n>-arz;jkRb7c!lYX6m0&sP*&jyfbzzgd;Nf z6;GIbd(0q`$(IBA8$3__gTK>ZK?T~=S9ZDTAQYCeRDjd(oT@o_gNut>LE>Vp0c8%y zCuu`~GW{s}@h(MjwlUe*ltyui&Q>C!l(dan{ar!#j1_lP!BLi8>Ez}nfUQ7na+k`w zvEzjwn7Gqen}tADVrA{2_`wI3->S&dQSY7;1~sw_CN^e}0Psmhy;x~iQf8LgmL3?A zCi6Ob6r3_*=XisiRVwxSot3A0)ljYUUDuKDoNL;LHaB0*WH;%S?X(s*5{`wAi2QEm zsrz4Ky;W44UDT`_2<`!byL<2eL4wm*g44LWyF+kyC%6S^+zIX$+}+*X&-;xt_Bng+ z|As4WfM%^VYgX06l)q@@;N=x*f&j3*yUaK#L5>#&>M+W zt{WNGdfRT^%Xgf+@fS@W0*yLAjW7TxcH-ML^}REF+|_+Emd_R(^Aa?5cYi#q(Z^f+ z9Qb~NB~76mMvFpnqPwx1nPUIva;j4Im!$q{$iHn|4g(>*Rq*Ch_KN@hABQ*HtSPWP zTdexh*Lze({dIxWm;uTo)QCctsM^=h6#}o=Upl-Ze0(EJvzmvOt_aX|TLw?R>Imcc zf2i^sV@~kBiFs#ZwA?^^=-qdDIGESjE>p9`cwZ1d;_e;JuljuMweS8m?71dvj!3Y2 zG$2z7Bi}Ys`=y&U>jkClj^Q3sewk0|@y!SAM+e{jaV2pap1|AY`ZE+s3%cMd;t;Oj zvqJmDZ5jV%J69lb;U7aYG@;8lbo+Ij8O{X_?Uz*D3)6uq)M2I`Cs`ZP=a;Vi?ERzq z`N#eD5ns{LP8{f17+xaUi$YUf{dl@Hmv#Isx9?0e#Q*p8g#0%36Ivl&xw=u2tZw*% z%J0xg{%l8Opu_|y(VkBGk!8%&Ak#WalPNnvr7~)pwY`+I5obbQv8{-$Qecpt8JZzd zM&#u#pPq!h9eB2PW5|Hhc*du ztdP%T)zp>;3dVqUodc@q>&j-l{hVBVpZT|jyJ0l+v zKoC{e1REH;C-F$zuM(L4`@Ok$YiU+fx->HEFW(3&%|p>h6ll1-)! zhpSRJtN4#d^^7irXysV$MMG+bHZmA7pvTW<+VtKIez|($wiH(bss)2KGmbBF4O7Wi zIytdGf2ei+9`D>|O8{G3`YnlQx(ckJK{4*gw3@SgR?}YdPtR@;s6e-8N*P2yv@Ore zAP6p`4C<|N8pg86*R!;YfG72er2;*^>W0&rm7=`Ry-3Wf~FT zfa%7l^R(tW1<*SQyY+%?dP%EYg0+W%ZG)zUzEQKYvq#qq;^e~fa-4FsW7MG34R|*F zM2rx8;z|(R$1Q;Ilo7Xw|J7zaZ~gpZQhV<4tZBq{Dm(KfKYFF=_UJHo(`_f<8X-(W%$XF3_a=Flu@sE6M~RJdbPy4#>pC_S0KtqB=RD zXvZ3TYHf_ci!6P+pM67$K8)Sxy?!K0Qh{Ty+{2_LchAD2My%M^BjEFgrgoGSH8_YZ z5Ere_w`Y?CC(%b=&(KxS9vHbbRfL{o2l_&)+mA zF>P?(PY5%Ko{RVs964yP=1js;p^{ezHAo@(b+oVY33eSQC$AUQ~+rnR-l_ho^U zJ>B@_?p$D8=z%Z>qX=_gsw>#{nY6uEk0@W0#`oR!6_4v-jfL$0m+bz(NeD`cYzR3K zn*MWizFON~OcxjULCoYOl2aFWX~c91`p?4HSiPXxYfB9(b7()~!~$^mha(+`gDeOX zPo*+r4*`nK$c7Yyd&sFVSIbvA#TA-8lb{nj8<>d7!jr_4u*Ls-P(*qiIipva#EWtG z+*H0J?0?bODJkyguY6tVpbjs!<{+YDw{zmDS2WGc2D^c495ukUJEH zn(mae@VD{BFG*_hKoxCVILR!UJ>3X#M2f3*b?oe$mWkZMveD@fKl%v$;x3l2TFgY1 z0G3k4!3Im$f@!~C##7}ru9)y6;h_WPBpicU{;?T$PA-uUjqeJszML+-)n9k*MeR_nsrdw8sIl)3S5Z~`-$E@L@M5}ETId@dk(R1Vc zUQ#-uF;A{G>*`=<=VuP);eszwlQ$S)ExrEJ8koW|seKw3NWMLUf!gJDG<~6g7cAbY zpQnX7Zn>es0*3TCG{zVc@&pUx8?Ut3N95;I23AzJwT&6+G<%_=p(A!kb z-AUVde<}10n)Dm1)%Kq;HLf36f2w?k+y9p(5%-Jk!qkyz+JuwH@p_M?51Mvl|7NCg<+so;;3kMCU&9STN>;W2?(2XD1kej{p7L zG$7Q#TD*+0m}f!AfaiBrqpKfX6qaQ12vdZ*wk8cq(ZgG$hW7r=65PnKx4-*f)T$<) zBu<59{;b(_`8?Rd8DU=#m;{N=epE37M*7A2q1o-t0L!D;w10Bb@MrCkoK&}>fI^#dac{WJ!b!$n#K42zOp5{AN^wZvK@h1f|| z74lo1ecEcZe;pGF_c9TR*bTYS@K9WNNY3o9_r?;i(F1s-6^w_Dj`)fyHa*aQmyF43 zE}fx<+&NXAP#)dqhHX8>4Auy@ajf%x8+W2{8rc^%pJXzt1PDYav2cqc`<=)*ojj51 ziy|KcCu@K5^q!441v0%XyC=y01rIg)Vjl{Oad9Q{&Yfpv{v1>VW!Y7gge8HZY64wTTO?fAYTO@9_L|&mXgB zCDFLNyYKt955*%W*na#_&xB0BEARthzEmmx6K1WuO~7r{K$jl6HeaG7Vx8Vg^Cv^z z(jq6WuBD4mbP9r^9*g{#Upn54(8CEsm@TTANYr}iEN=%i%<~(Y%nJwH_%R_sw$Ile z)b)*}-i%pztd^cRrTkCw^TByXCvBET(j|Xk(QfLg;B~>TC^)_X{D%?|B={cIv$N6o zqY&+QDxNh4;}UfX&QNdCTrw#r!YxIhpL!r*o(--MV>47rIuG>S7Ly2zs{s#PSE2IDS{?WzU8CuAxKsG92MMWleNK~W(Q6tF~f2svL zxmsz@3#;)3`O799T#a?zGL2yPS+=UT0N(!*h*nb%l|Eml;xLgmM>W$&`c4Ncz$MF5 z{f?yI4Be=~oUDNgJecGt0A!*()>gSg&tu%brxFsKHaSe0U`Y;&?AFOPafDzvE?g%R zf3hN**57>I!A-c;jlN<$sfvl1A`j8J^Ew}43&(CeV+Ats^7C&1wmV=8G+b7RmU<%Uh%awjx3Hj||C72fE2j?A z7=dNgHLS-Z!liZSYnFFd+F?Df(0=JIL2uF_v-K>;gp5?xl9*phJV}D{v2Z^XmDSe$6-&k`a38&-BabGm zBeW(OFmiTIYT2K<(25R`)be~R98O}O&MZ`kZz_l-0Qz;36Lw>1>C?CKwbirA%fhqerz2}*5&btR{>|Gomdt8NgUOOgQ8H_CMwJqa$fbYL$XGWWsbvZ#IzW;k!>197Mqq!89CA=ChIq7bnp5j4 z!;>JO7!djLQPOj;=dvkYuXY>{W2Kmam1DOGt!9%B53~_2=F0A%?3(Orx97 z&M2xCE1RW=RzjiFV<%$c7o-To^2p>f9nUf@Yacs=)FvwCpUn-5MO(TX>37;W^>(e1 zck%4Z1phkbtR_b8;r{cLQ3+CHev|C+du_qU)irzbGLo*;r`4)rIq()cSCjuaDg_@^ z>58BBrUSkwOJDg*oZ=ebcZv_>A8$Tye|~7re&%gxYy?dw?(P~Fl=qHmKwQqj7-kD* zFxZJaW@RL5f^X2v=r_&I{C}c{Q0juCbyUxj&i9QZU>IrMeEJt}k$IZF-);l$jDyl_ zuXk~l*ZpU@D;IJM4PHye;?{z;i_<^ZZW2jn09=V6D{VXGjc_3M`)E;n&^msHxfb5Edx`a$`ZciS*@ z^{NdaWYl@cYMZ+igykCD=c)Jsh#~3bD|2@|e#_p;eoG)Fhk9FIcaP`%@&})u^s(z+ zkM2)e1f}i&VL||Il#7&*)^rF4U2ZJ2Q|%F!Y|Z29e3I=XLLep`Y!CzEIXEsiySKOq zBs+G=<7$HJtHW$dK#=y+^_!3BHHN4VxR{1jrZzlH^#gQ}NPaj9nm>XzF19f!zR1Y^ zm%j4l%(WDI=JSi~`$>va{BJ6#HW(TB5lD-rGjR>Z-3xs%cj0U)@b-z{=j}O+EKf|D zR-+G20CBB+>5ReBao^_R9=D!Sc77oPB%x1m0Qwob5If7z02DQ=6B1$C*zEI4W3D)L zUdc)zkI)l~DZYcNE&~T2U^vCu#mbpi;BZ2ZsI%J5%IU8spZ>=pRtJWTUB}xv@R(03 z>DQon6Iw7P%rw4a>+_DFSOSL9Vfnr4;@Sd?9uFRCcF@b_K>M#_5p3n{nlYNc&#N)D zEj5v*^N*|R5BGGUKt=tb3l~-Rkd*{R=h%*4R~O#6i=Avlk!H`K#f(QDvfR z*1RHnZ#0P6hIGxq(K8__%6QNIyG}3Aows^qXJ^+rmhlzQ-*3nWP`v60NKvtBUMyXKjh;Pt~NcV!Y4aT6fH6NqLdI zfJ8dNuL|U%TExQm#2P(8M1*a>LLFRkn2>;vUP4CfX%l8Mhc2ykf4R-mfw{5LVTv9| zxaOqo7=!RX%hCu6qg23)$k?}0CerW_5h>EyX+_j9frjII5S^akMn+_QFR5?8JUZ@x z|5>W(?(5lhTG&RZ=JyOs%a*P2@RBkXo8kp8G(?&6E<_JFwfCIWt9_pj%?ow?d#(Lj zz%v<0_ZYF0hZ(A>JbBGJ?B$SGa8VhoWY;1s2>#3pJ_!dKq%}-t#e3gBh{LqeBUR_nKliFK3CGi^=ZAGuc+L?X`Ta}7NMjxWoFJ(wgmEX(b|}Bh1lM4# z--H@Aq;PmFgAs{5PP+2$P@C3?+A1UYSD_{F5#%Q2AR@ANs~Z?Q{t9q{Cs_-ax@K}G zStrFnj$4?t+D37;9gVJ2mM0r?`~@_Fd46@HVaEN7HB=19>1`}yHW{j>h)z+PR^4t+ z8Kzn8a57&Hn7G_-h-0dj0Fv*{a1tX>o$MRk*mk<=rbCFZVF-)4>5+qCCr(|!;1VT{eQrEPzP5vI$!zzBq_H zgcswLtSP`m&FV+$Hjb42QXa6+;B)gaX0ldqM-=a=ml_)s79@`y&6fOyqHVZOQ#(M~ z3VEw8T|u=LX25)uX;_MChHIigr1IpP-e)*VgNs*{^ts~=j zkW)VbrkXCA}XcgdT3usKC|I*Yg(;JE42;>y6~bVOq}~Zm_D(j` zB?wN!B?gdeUI4rUjkAELdR23Dmqdpho`cd%Dg0N(Oe!7#Eb;ATkXnAvYkW;G>0ZLoc)PkObH9M@TgG&F%3eOr~yI1uDij3sEEGtX_xGh2}&1 zYAhNs|1bdS;caks);PygQH*?U_!w=Ne>jWh$oiu?6Gdpy?Roj1!4U!1G7Ty;KhO^x z3V0ISQ5)udUQdX}S31$f+%AwCCYXjXx(Z+Tzmc%3MRdOLM`xrR%rF12;n(EPV zag2F-(WB&7N+#RbYVf8?lrogzRAh)E!|bMfnV)2;#)hfljB^gbx5S_A_D0!j^@7cN z9wSUAWCPl|j(_^=3zPUmM9WkLCSbcpO$E~w$~>ErWooDO3<1_Ky15&dGX12pa6I;o zasS#Inth@wg(rB*tggxJk|Nqz&G1^p;qfX!%%>B#{Q*DA`wq;PNqyGg6gNA@rPKb( zhbeAqj6d!amKREPjZZ}UY0N9I+^D|3p6jWM@kaGYwn&Mo(V^kaL!du_+y`%}CM9$_ zG3k~hdOx1(lQ4$sl6rD94K+NxBf zv;_b2i%ORJ8C=G(b37}VOa=mEV=G9~tij639!&@Zv4%c{C42Y5trzg}?Y}*fZqSmn z$(oy(HT3KG_D)X5GQk#rIOpky@J>)CP=)gq@@wlPe4ED{e8aBy$H}7nZ;`d{(C!Dj z6E`vVKYIxO^!KQgJG;BH8_=n1Rcmbmb<9A?QfrNj_z@1 zzugoA891_N8^_DH=d{s&lxPX9zvtu)jbHTBNPu%qlf_OpBPVoi%Ol7Z*X*7DMEoAZ zwf*&dE!LrPiYD(E|}i=-qH6S%^vfPHd!(z6Lr8*9hEY$3rtL z+A^XYPe&nxWdv3%z{iePE&ipiNd=ZA>T_C>QIWMz)JvynG0w^0i#BB={3o@~2ExFU zbVQMqOola%Bcm%DQZcTlZ!S7Jqa{BJU5=-ai{;x9?=)hk0F^C4^|1bwp0sK~31Q>g zaOY~tgwv55sBteXW{sGlinozbsf-&}dLPS1)^3@`s6x9|c0G=ldV;>`aA+-vXLNT=inKy@+c@%@VW z3?Jn`^nkF+9w+kMd^?1#vf~XdS>OJ({&=)lkgKw*f0&`IkeW%Z$MN_Cy)t%JP~mq% z(R#r4R}dyZL)FJqoy1VQigx`QfbRRy1LRKEUt7nGWSfDxU4Ow0v5wg7{h7390*R!pE(~_YQm>iYT04J_;i_(96Mp=9 zhy3Np)+hR1ujqilsM?@#H`WNh**G^3(IbuG1g=!tuc#tv0rp^%&3eGN5b?ZCcY7AM zp~+!v|EuqPzE;cm`BlEJaYV5W&)8<&#=YP(fTtfC-v~{VSK99(eJgvpc>b4f6_amg8t z1VMV3`GFDG;T|HZRD7lqR}X9qeYt5tN>GYv=F;StT9)$Htm_dMS(Y?ttbKm8iGBeNf5mqXN+&3sJ~3`PU>k(!U%R* zzxV#v3?v(lPtR`!S2?C@!*=YjT!(865V@IorKqMAsCr#6@L4fBT_}+AsA#2`2p#-k z;Gk)v4Vi`YsM)N=@(OaL!ins$OwZHK4i8V;e4ah))mC4BCkWZJ%?pTXjv9o$<+p!# zR_SQDUwL)4%{+hf>2Oy#%P?8pN~6v0L?@!zCfCexU0e-E3{XVaH`taT{Prg=io(T; zTUFI`Ny_llnbag~Y@HsNG8*a!i#t zJ>|%AUKmu|M!TjHt&P1ov}9^LIVGx%XYQY|1yz7LS&L=&HbpseT*E%)QEGGBsR*cfg1M0;)k$Feyqt+~s?<(3tN%`GV@>C~z{ zH_!av|KCsge7qnUIi-e%2D~T<{<{T3fNBjj?#jb2D1sk!Lj*XG#p50St_PJn?aRi) zAj9hq6In(vLA1SbH`P({5mm?bc$j`wCM$E;q7h&8o`&4qEg6oFlsE1CuO;%YAgUc8VEi zS8u$$Gh$tLgLSf{41!^TL?M=WGL6_ILK0PEKU@A`AmRNPM^pm1!YPfOk09#LJT=e{ z0T{LLg~~CWpa9vZ9Kr(F1AAq@{2lyv2UUNBX<3H+TcEZd$Tb1;Ca+*cRgL=oNi$c0 zvD9o}Um=4!cV-Z>*TXick+pSzve8V6m(4n$=<|on`Dc!?Ocs!lbh#Cn1zMh*ow6>>}~oi)aYqmA+Dq9b=7e7iC)RHz=ep8}RBH8hIMldb~I~ z7-WS^vnS?a=>zIhxvG`1yetWCi9@VgV_$7+{{EGYGqWlSuM&xlrlk3zwckH>tmX3p z067Dal0J7!XKbG(@{hA=0Jqc<_HUCV!Ga&3YhN@jiQS^lWmnSQb=Q51?>Z7%t<8DK z*Dm?2iOJ>MZL7rSS+a~fkFT<)o}O}@-BNE}qmOCnPM7=2Cj`pxU@_nd!@+Pi@>!;0 zmw|aw2>yN%kO(maF+4bJGSD2SbPgc+ak5>AHe*J?(Rpr2+Xc&JZQ38`MG z2Ij0qqrdKnQpo=31xn!eoSm@%O-fh40nkvq7?0wF)$F8s*V?N06&?8)MPdWJvf^IP zH|lCelXwgA-T+}0j#evj@;`0`=7FlP8oR)#Z43_7M~xK6!4=z9bgw`H(A9d*5V_xI zW^+fqSbdk1p_!|%>~~#_VBXfQ{%-Kf1ZDZxPZi?7>23Z#;%I(b25uZf-a-ct?^6_8 z|4PvR@&Z_vjW}tj{0Eg(^e5A^w~zCH^r&?_Q4CBQG8tDldWMEb(2L?JH$DB4qyFg=3Bpi=&EyIrlG=k2NC-95?niz?@`eNWs)Ahbw& zhwrUCPpN5VMFGXL*FAD%KcWDD(Mm>& zwek12i1**w@4CLf);%wgcfca~bL3gQoNat}GrL&lZwT*wKYW5=`IL=6*9p`Aav>q< zBa8DJB(GyfYdo*o@Qn}FmA~BYIA_2#8z&jY@v52<1+*m;*Gske#~(gdwD|84U){ES zV#s3f(9zsqM&188mojl`@#hGqjH*1y4k1tMG;wokfr0|51p32%q4;b`u8;WM-d9j= zvFSdXIKC{zcnkSH7YlaTzU&d}cs-(8DHOWa^*lWhKr}uhBQVE41}b#8YA|ROkK$G| zp^D>KagY5JxpkPL7} zo5QL&Y+T_#+{E~Vzn{$uj@%6Ht*tIIjYM7(%6MJ8;{NbWRHrRC@3_K~ZufRd_)U7x zyO(MR^zi*}U$$e=p9;Q+V8M_lT&6BDMayUS57G4_d@Q1J`B5X4PsdB`O+1h{_*owh z6YjIbE7U+6C5?HwsV26xg4ic_g;FPLN3ZH# zOOd~kBmOuk(MDFztFpYK7fxdgQVo6^wQ#p|B@F74pkM-(hXXM-(d7N!%S6>$3GtR2 zT0{SEqwN&}myL<@`$KfNnKINs|A73|&J+a0xIW(5iOqiyYaATyqJ%&b$6u@npag$p zz-O$<@}=X6M#OJe-yPDmwM9|cVUH}y*9-37w27?hy3ScF|F5rwlYA&wHH8VnQveFz z_dj0zFZ0$H#69UIR%;)%pVb^2IO zatNflrl#AzQl@OR|JI6V+0fJ$ce%lw3pvZ<3JkcNbf2bh0n$celglYkWVq2vB8;)M z2-S^nq@N_w2HI#w@fdJIM_*i9@2e;7{yA|<0-$(DMj{YoE^^VmL&?fFo&`0Rzgev{ zk3cjVn>w1sE9bY*PCaj)*|G>XJ$Lnjf`VZGWozcHqVe(z8o1g5K6?oWPEC8Ybmg}k z)^w&!pb2)qq`vHi)?eN;(4{H2aJ9KnQ$^B56Y3@tC_!C#9|DBa8N5k+QYC>9e1I zexKz;DDc|!QC=`e87GwCnGgKs7njr4_wD(-J7g8OoNEVny zuOc&IYK}qxo9D(#5b6*+6)?KqXnXz5yD*48g_?A!vRIRQxnE@WJN|xYebM^))VV7n zgCH`pwW^vLVvnB_0W0x0<8tBncnR+*rhF+!EAmtnN##Edo5SLP$gLsIvQMH{KJsO2 zFysfsMAHIiY-5;t{9W0I62}l4Na2-F39>lRfU*~^wL{=f^#);+V4ifKh9F72`7?p+3MzH*$*W|Ky+c>*8B`x`azpcOS7iFKI|CJf-76c z6+RR9w{}}^l~AtG$tP;W*{Xj>X{Z%~*Vs0*`(_jQt)7EtZzNxB+CdmFb(#@@^&X%p zLgeMEi&X~wLXgNPr?mU_?J~gX1rhA`vN1J&j6X~~i|bAaW*S*g*Y3Y(ENI?p@*Ukv zCLh`eSN$#EnB|f`<~Z)1CNEP}ZJ+Gv+W61|c*|E9Ekmn5RPON3t9g_7Zn3@T4&BO! zt|XMNvocu+AK&tQ$lCW_uJfg$q8i@t+!el3fn8TrR^LtWx#9Txvi9Rr_r0fM8;9_+19&t&t6)Gy|J4=DCRSn^0(0!;%1{{Y|EaijLB_U<%cw~4lI|NZ0TbM%yk zpp^y8k+5fN61QSXkZHsI4hRx!oZFe`xpxW+9#=J2b)q+aNQk`)Sr*FFixzT6kjquV zKw4*h9ktH4vx@lf+R6L2d){nC>RPfCpXb@>d(-%C$c}i(32l+~UW?p>viOb5 z=o~0JXB+sxzK~LOvy#avg==vT|F9#*RlzP07tUfNqW_6k_lrVJb`~4LrL%#xAY4Mn zjzo|0sz5q^tuD~o<;LGnjGETJSR$=H9B*pF37zG3#6T9djb~0mHv$9nS#0aaXh0;2 z@!1LF?6r|)64T<$Eq*3?$0cbbX|&06lIZ(&IsJxdgbA_OQ;Zd z{M&T#zA`K~?gZiPSI_%qw?~S4q+UcR+zPEF;Hh0i$lTEQOxAf%HB~JmqfLH*8cYUT z4=20jFQKGp3s(Rdr3(Kud-R|al$3=nxdtS#oA;#y#a6xr2;*0KncRzUTw!Q42`{G6I&5vsAk80@*BT1XS z2&G-K+Zn&O0xQsPa5o?;p%lFmTK{vE7}IdvHq3K^zJ2ytw|b5=Danla(3X-LTi_e>U(m=l*nP#x@)I9>)f>8Crev3;UybL^T;|aX=YqVq7AcEa!Go9ii3y zf~SCqCH^1SdS`Ep5C}+N{SX)$239C0z%SD?jVHRx<>2nwN{eS?p#7Z^CU=CDw7Ru% zWOI|eXDt@D-5qE{{POBf6F@JM35(|90_$EI^U zo;HZ)nmf%~qfeMwhSzgrnk(xo)Z?EadzcMe{WVNp^E4>L7PEe4d?G*hOK3ZQ;!|y4 zW(Ql~p&KaMEUc~$q9SEJ!Q>#$y$d_P z{I`jE=H_9$Ns2=YW=sJ0l-FX6&z)piXC-GE+>-;W3#rDX z!to?E@XX_ic){Gp@dYqCutYzjX{PCCErK-gCcYgcP}2jIMP;+8VutJxv)NKA^Wj^< zO2^yFVz#C31_3QkiIp_=dkwsh5a!Syp&(C_)XF%zuF>LlBb;Fm4F*FtO!ChJa>8ic zi46Y==$3JDL_+bqG|_4l`V%YA_=MB(yUfh%RLzvgs#v=R%m{O-=#cAvziJ0?B4}dl z(o5s212h(SUI@!dOwE(&!SCYwjeb5|0#E;uFx-oYmL#E5uk+Hjmt%y>MATkMjhJ z7Ha}_Bm%jqLN1P)h~#ui)mn@GkE*3Ct)WCdq6Bi@5ca?whJ-?yveZ^+rsq8n$PXWW0C@Odh(u16f?d6}-z z?d2%J40X!o5M5F%f&RPG6F>djO-cQrnZ;vA>Uwkv1UNYa`xBZ~%D5ZCsq0C`0!ziicKGjU9 zZ(xx=Q8iYs_sGKf9#_7azVzO|!Uzg3Qsr;XLcxk;E%DKU0*{;UtT&g?2Nfk{tJx4v z8sq-_JE;|qmJF5&4-&>BH1FiVz`OYH1G~xWWO1ZhFTbj;Ysz?&uS6|AJ|?+#cfk+Y z%_Dj8o1vC9CkY(sFUDc>-yw73g<1{hP1x$jhZFUg!L{F{{_m<6OS~%ImwyZ^m02z#3T#J2_pVk1H9 zt>6RctgVO%$%S$8!9~)9X8KiD@Z>Vi*3{+f1n56K_5w`;*kj9}DLKD+dZIi{Pdmru zDPL+NfB%Vza%+K_?-PoU-0s#BK3Sy`{r5`V;Wf~r8BW$kqpsQXu< z%-qtJND&jZo%q@&YV)^Qu2p+?FG@QZhw%oEH-*$ZfeNcXA2H*;1sk7r_0HhQKZ7SS&8nvApE7t%QwCp#t~Cwx2ch;) zv)!MqQllJuox=-;Qd52L+Jj<5kDVp6O^ z#AsU{KE6FdUEiRts)5r+8+$jm-lZb~K&PDfhH7yeE3(^^HMTo~+k7)9URoc^DK{bE zXlK`J$0KHm7ehlt?D7dAIVHs$(041C4K@Ag(&A|lrFS`xQRn8r0;Rcb{Q7)hP+`Xp zPD{k9Df1Tr1e%&5e{ZIav0*tiRp0{18!W4<77RGkVtetEIh(lMxM9!&edwh{MG3m* z+Pr<<@7slIKRI~KY&ZJuGw$F!Euj)EZ}&%O{=Mn8Txs&jIE9eA+N|y^m3?);-Bmjz zA-UX&m~Xa!H7=;bz*!V1fD1LP=u_JpTUi++9prKasp2>Qqa0E}8TtLQI9Mhv zuEsxPtt-964i=8mq*RxjwH8rYa3KBDAQGK4>>uk+Xlv|f>S`(u6-Z|um2VWA@m;I@ zNH^_piYlTsErNnxt1)V4;*qvKOtL+O#J`zl0%nK0(NBu{yf_X;*$G8;Ph5FBR)MKu zxAMBwi43d~0IiOlUfP&0DOWC7VpAG^qy|HTLd^Wx1_Td5bypx`R{Hk?E$_QJExSn6 z9Gs+wnYIZcqmmD8VeU^}1tM~0;f{4aiT(Q1jKoDi;oub+* zho^c0?K_w8C$848`1-dQCruP30G_kL;(bY}`McGk- z6+Q(29i+bkDv9x9;Heg22I6FkJ}Sp;cow2MVGbOKC|yD;E094#_e4VU*^BCD^vw;^ z?D>t~4}hvtTf+&hwkH^U^;`fK4+6%{znA^a(Psm@uYAFiP2*97jR$v<4_OiW4-f6g z8u|)35rGqq7utaE+-Gl{N2i}&K*oeZnVg)iK1CCuR5ulv2k`psb+yse#bF#vP z>?>7}$P#n}dw)Kr@&{3(!oZ|7=tVOOq+ea!Bse)R2uS6NeXa(GiX!9Kkhx{**M7lz zeO}(aiK|~$cf>gTS2sU)Vd)fVkG03&3Pv8Gs(?~RYN}9&R}z~FCc-Nxrbzcek;lx; z`(XHr41%0Hs6oUG%@(?f52FJPD4nbA}40QUS4oD{N<}>ix zXJzs&RNqb050vX;7;ilHG|Buo{>BAVge3X9+!_HsISg_XlRLs>=h8bh>CA>#$vw~U z|1ljBIld4|WEp=?D?=VlG%6$*#S_gPj=oTo(Pu3^`Jg17Ti;c09iFE=4+YfOrx(o} zI|KV1czB?1`&0ku6;2fSxW41HAjkm08>o{@Qm@$G;AH{ulXA^}*K&Tu?-ZCvC;o)Y zna>?rSv{yH_fbVJ2%JC}>!urn!YNGMtD_R*U-J!z~>G-rlrXEyHHm_IFw_``Pa_DPMFYq*8JSrjF`B)2SI> zZFB1TYdWi`-HV14<&wMS_PBN5m%ajz0t)%Zqpvyz3YCgv^fi$yorN;Ek2kt6_Yb`T zjer&?7l(hg+AjHfg<57qM)wKx73%N4z_C?1gcTpXy0B+J@JS&!AF*OPj&ba2iEq+r z*bON7rI6>SV|ivH9_V)AFR0^f^}#8`3SK1vechx~6YM@JRIxx-(HJ47xeUB?8#Qz7 z)bNgS`h6Xd{U{!NhCQPZdpEqTS_v0P%U0x9HyGC$#393feOAots2?Rwn=@H5k?qp# zYZ|fax(=Ot$jQg_g(>bcfJ)1cG{F?7gP4D50I#YWzmCF%z_-q1aIt7DZCo7qrRcb) zovuE+CHVpDmNX7ibse38Nwe5Ow)`$XPHC`?4oe^5lrTaVHn-vuk7@}OxX6C7Yoc%~1USe;dS11;8_z$f3V6Iy z68%uLR<$F_n7xG!ly$qU&p0_Hu5RNfT0~*v8>oa?Y4c9$IU^UI-K=UH;LMt^ngh_H zlBz72ZYmm4XhIjoUVLLX_qOZC`~+JeEFlA)8#1cn|RT;Y_dQmXJYl;A&9 zJxMs&;pRk!&rl`OhxgB3XJ35@M}nhfxql)xWjzB*T?7gy)iNU@Qgq?|RC0q6F!S{#3-Y|#bo2XS815nm1o}Ve z3SgGw2EkRWQ%L04BI>oqDYLDALsH{&GVRIQ)haS_>ymIZ{A1~?bL%Ba6jN!%hd@d5 z`?8JYGVOhM91-WtpzC-k7F;sw0&s95=AnjLLr5KL^FMp5h@Nf3qG#c&~>Y}ylK=9yB;{gJV6C^-zcXxMpCs^>{?(P!Y-Gf6T!QFzp`@i46>bp4ST+mg0 zv8$Svz1EuZnPVIq5Dg)V`2^7+_I+qp9BQ=|CvcL<@nwJ=IeZ=#LH3VxtxW`3g#m=VRJF>H z9uG`aFcRyf?Oxj%n-o&68IR-0zz*-7@y-h4|_8 z%UlnDFbkL2lK51F4Je#X&Pf!?64lNlA|ilHZV07ptLHT?(x3K?TWp|D`@Q-665_ja z-D2li{MZ$UjY|47fW?_C-n>w-@SReQRZTq^A>e~_&$dvg#otgK!&N{G5Uiq;0sMdh z$V}K|0A^%S5e~=vf`e|%mV*JTL@@!^p;n6_$vG%Q`}?438rO$6zfb8H(A#_`IS@)>w^M~%~~HXunlS}|QT zEs>6rcs@uUH*~_kotl}Y*pOKG)=vFe>iFj}8mgUGf4*m_R?V4}PcKfDraOL@Ks#cm zj5%c_#&S$>`_{v!*WIbnJu(0I-9YZ)O*`=R7Uhb5sBBT@8hWT!PW33-AC0dm=*K~9 z8Z4 zL4uN0qEgB1LO*Ec>u#Eml)n;}W-g<_f0maw7*9YZ~e#%nkkRnzhYP@dC^@?)8cT!SMI`MZ-P!(ip33{`~jn zZv^Wdt{=hQJZ~6ze4;&_PMzyrJie}>uNRFbtUz7mO)y_cS z21Yr3&+Gyup!KElTeUa=W7bkAPB`9VwZ##L?1mL9+jY6-2%=d5<7Y`!XZGip^OYGd zy$fAZom&0BgGxW=)pv|L@Q{anZaSCOwCLXxXPn{XBg=?vb=ks<;c<%Nlv`R~2Ampo zs|G6^?tsUtfh-4nV57bL{C3i!WipE&l&@7;yQr6|YpqmEi;N0KbV7W!I45q&)V!#< zYW)7jC#qJns$;Z!o=?Gy#Pgd+&?XntqoqnXQ>IK!=&ZvvqT`oG{vBr?DUhw;Ub`fh zjW_pLcstE*$=`=p^Qiq`FM72Gkr>m zHE&H{Ne{T^?wdGTeV!T8C%#0SqBdILKpY7oLl7t&O%%%!gQL)KEz{%0z>3(@$D%59 z&`H8X`ww06MEk3r$6cp=j{h$UKw^mh6%_4x-=4Dl`-sz1+oL($#u_p6JmL636%Y<>o^Z9-z~v>z>0IzvcUELapXzZIVieEYq;Kd# z%-Ldptr?)ZM-7-ihba*a8QR(=sr?Q%CFIUh1Dj1Bi}bUI;puqY0@$H8nNTdT0t_*2 zjTz&wk!f;Da+O%Uj_k6E8sGd6|A3`a+@bxMq${xX!B*̞|l_BuElyMb{J12`nia{KwY%VNerLfODy>K zN_Y6{zAA!LyjOCPjf|v;cJd#fBvM7^Xyea8Fcj(~atQ;*cI2VTHv0=AZ#2Wv)*6@v zI=HbV1fKCmGF-n#9f{~+EYrUd%Sy(>lo-`EG>CwxDK*0drtCPTnnVysfJ`@VSYK>n zU-^cH;O8aQ;+l+0a4Q};3)N+e#a$H8%1@NPn`+e_Oij;*dnCeTwam3*zf>j2)rC11-IjP$YaC>YiTxYRQj;V z36;I?-5jPLl_x-kp6ohGCDk6#zy=$xQ`C|iA^lUpXeaSsAFH69A9LP(MFKYZc+-~& zC7x<-Vi!IOz#JF-ON% zz*`Bo4nK{|)^vCpax$0pZOn=;q6M6JSE{i)Y(GV&Mj3gQY}|Y&?c2EI8_MB{9Kb;B ze&5?qi{DbQGJw9449}nr>LO=oqZE}}SP6tAr_v@#)j2 z#XI`@rPN2h?EkxLy$ztNcn6_Nz(|3^b@D#>&?eW=jOYcXqiEo1s68sd0uCQ^I7`7e zyhS%jbYQd?X!TSbC+iv^L^j1jH-Mk_h{R*@_Bxt$+6#6Y&X;F%gLg zIZ5g#2D&T-klzm-g10dKwSzzAYBBd+2hh$EoDr^mD1=VxpAiZreT?HD3LYc$K1Ayp z80tPxcsX;{AHd|0=exyDsn#(xEShk1kNK1WVNHu%TALFDI3JhMZzCo5f|4b(ynWofm$-=lnDFnlZ@+A_j&I+ z=N;M+Ia+xzT2d+m-$!;@imk zmGx?ub3||v&Nip`aote!2{(Hxr67SYTb5Eiu}WO7D}XQA1l-95wSUQ234({YIHg)V zJj3=TX^(%KAE3aWtONB^f5K$cx@_~E@2Frz(PaO5V2~}_=bx?zPJ|)bt~IbEkL-&# zsHF$F=1}Lfj#BeqIYwfW(a%FNi}b89MG+m-r@o(E0#4+Pm!q)`ms6_s_jPv+m5=D* zQU}g^mvlO9FT>!nruKH}`-@VQa`)xZ1_NeL-HfKF5eq@|63{U5yZ^cFm}8Qj+h}Nf zO9ViYJiz^N zqS=-_%__bN)?SfcSnRuMhX||Bf#}MBkaeI?3D47_C}<*%XrhGUs3 zor&nE2~WP#Wvllia(^$d^`Q`Z#Ym0?4!sH{pl>dZ!?UEt^QBnxVdPF;>kTVP)@AYszqE}ItcLWilg#N2*PpivG;5O_*JzQ0L_40g={nv6Nd*Wd{#@fZ>ZEKr z$fTbzkAE&qRMEk+>=E47D6(>TUg!I+4IGER7N{AQhA;}P5D^oxf{-1F2_eo0Y~Se_ z=@U%AzmMq*dgotd|APYBb-QM`Ee@)oZan9qG4rHP@tQ8MWuF-h3E zh6+46t|&IR0u&9kR-QejD+X#4d;i$BhC(vN6^f>;@Km3I$Ov4REw^UwGiY zwgJ%>$;b|5{~FH5}-7}=-(;A?9- zoScqf2ifQb%0XJG63t4Cy4|tDSdGu(rXdzz4L~R(v#H_x+fC`5Rb*i$E<+T6oX73g zHe%JOV)X(6%htsMzIQ~H7d&!AYU8!F_qM!W{MsvUzHbi8M{JzhQTDropofqLPt#Ot zYJVTA$#L3wV(18$O%?}ab~6~$G<|hWKg3rMR25w5Slxs9zR;Db|F*F`V?OEUgx(;; z3W1U`f9M+9iQ$u~#8s*cSp`z2vyOdxbf5l~GgvjkSt`|Z`;8ZV6GVs*{AS8_5)5}j@J*AXC0&<_N}LR6Xi80SmLVDl*K1P4%juXBkHL*We*_MxcyN2Lp{&}Q zh_f{2xKo)P)H(67NF_Gj9H0Bg>67;mx1PwFaD%}cbw^T`Ei(0%2wDPGxPyXMcqhI{+bwdNE3z5y(pZXIe z*K|A@UALcv?9P*P*jiS|aA0JmK9l$zPSb__Qwg1gURT?2os_gtNhAsSF){0p!^&6c z)`5Ehoo9-b^DIbT6279T?3vD}VVjFM#*A=&mUYG^6J2^U0nL)40CmKC8mJyeo~w@W zYhEw6D5*-o<}_Fb)1+&L_D$Orz*r5^=y~sf21A7WNd*!GvZ0as5N^ES0{2vS3wQ1l(lZwPI}L4p>TlpN z>)$YQAo~vAz#&q49KY2mNE$3e7KS;|7tpWd1+{Unsjt7s^mfn1G~hnYh`)H)^2+u&69|78&&)mq}xf0hl{W zU!4V013>klr{_qMqc**-j`h%!G{QI5(AG0EH1xN?#E7C0Vxmv#loV6607c>Abcal# zd*IAi%6*j`VU?`}&6H}JHdz`1>)+4a`kYt#1VtJA9|(v;Yae+QN-z;Z9zQI69IKm> znm%-~_=~sH(G7_@{=Uc+{@B2XbMi#m~quSlwIGx?nV*GB5 zcWL+kovuU<3G?s^;7is|_u*o$ICFBY0&R}IHpucIEik!kb9yp!8s%V<0w~3&4N1xA zLAS7liP*G5_<{;?e~IDAkylopjaKz&j{ATQZ<4=H$Sceu z6F^Q+EPqzSW&uSL$cn$LLSCWm*IP%X-zU~HhBT6i|M_$~pS2#Zq%60U-!J`8W9*m3 z1}7xaTi0R|)?q9eMN-C^P&4P_V_^0Q{DeVF>ZzK!`80B6m9yP7GD~SsqTou zwTsL(%R1}j?s|HA*Pi1g_tsMF6%uK5loR{7<0FuF)cIq~=e&w@U^zRcCR@Z1H^BN{me?$EJQa7}7oN4N~4qFF1sn!Fk9V z+UI|UJv&?PMf;eDx5>#kK_dW88O0BBxcE*SFB!m&x!1xe7t-ij;%b_=f_8YLmD%o) z9g#AL>A{%1d=s(ns(w8`kDDb&NVHh{{pP!_&Ja~1xzHy!{cd?4E#~i<1~RH87%L2Y zVm-w>4*Pc~E@=rxEF1T){1S^+jvh_{Wk?{!te&QAf8OiOm?FVv6u5wzpKNGR8Z|+A z@J$tmwTuW5s0D*UQEp6QsmLakBF*h*Pplc8`9yW{I7}Y>X$uixskqS1H!I*{q7Rf| z=UbdNFw-;)7Nh+%YEV=b7!WO><=% z6c`qjwMA6YPC`UM82I!}e=SPP*8hnm5JcIt>(P-RuQYJWs%+-VN+y@605ZI`mN8>v zy=2a+z7O?(hzyO0hVstAPp5F4n-7?K^H{$s%3@QWo`-VjBCtVw2rwXBvqaGVMx}-- zKx!b$Rl8P zNE#dI<*VLkk@Ke7znkzmTWxI@$&JCUxFtZ<3YrE1_OTSbhp$yG67d8xY{PZPnuyTd z{=Y#q_WlxNVSuD;*HbEf0720`_Wbmeq52aM0G>N=dqyCVlM{2{W^kKlWXYmj?e@$0 zs{iud`|uiqyJ&^z_>HWRY{Ixt4CW^u3@5&gCb>@Y9Wf3OadurJOOINvY?#w=%-+*_ z2KwaLw~qR9Hpp*I=r zaec-6lY0Ta^T`XnrKROpsD#b>jakR^$Cs!)dBd))=p?R()4wi!JGKyh`NQ7Nl9#F? z{f-uzvK-%q%2H*aie~#!;3?Dk;x@wxJV~63mc(1hrNBVJd!b5~0^&?GqNkK>fD^s0vf?=Awt%LiJW61$yG-pX~(pgrla2?iM*Kvq=IwL zP8#R8y~sTkGisD*!<{TAY2gb{R8>p7D@&CPC5}jjznOA=-YB4_3m;W5!r&y!Dq14b zB)s7ymLGPCz-G=GN*r4iEtt#89GAot&ZhRr76zr9oX+c(YNpNDz_GPq6iud08jW)0 zl3DmylUcQon-MGpfZQy4UB1pI z>woM8Sj5IE?6bEH9#a1}IsD+rU_KC&STN<`Gv$l9)CD|YI(G_#L53gYN7|fZ2r3i` z)4m`RdLOi}PxNk)+~1u$-w%>>-lCejxus4h+pY8DPx~h*jwHxeOj~^`E03Sup=g5G zTtx5Zm>IYDpSSZk?qTrg&yczR0xa(XVbaZo_iDcgB?B82hl+M?-5@3Qv-YovZGD2V zdsGnx$~r^h<{@?E3!Wvj#)6S^6ye+x!r20>E(dPVb@ayBxEkMkuX)^>nlE@_GQR2W zQ;vQ`&?Aj!)FVP@Alk-R-|ZFfH9x9a8{f8hf*?R9<*_P z$o35M)c9S6jJeZ*AZw?{Z;WY#kAURz->rJ9<0%DyXykv^sbFi+5>ZAw z)ebVw-u*L#XX^WGV*4=vue!=hLsqm5E8ayed!MG{%>SOJ`pgz$?K~3)6|I8CkoV-8 zvew_1I~LEG#+oDVxc21C6+P%okyt^kCjtM`LpA0+;~|$_f~`3^{RXu&!t&}1e^`ML z@^R9}&M1hS$=X;2_2Psz4(N;Q!vY+|JG5(r`E#RX3x>K9Q-WDfc zzh>n39&1)F+PzXD!P+$MhA!lAd!&jQ9aB@Z>zwllUFk+zMD!xC_2}a^X*YfBijVq( zEdZS=dk{CI;CYB>jlT~Rwl6kbOi*c-^Vm0IF@Oy_ZuaTr0}rH#1_>ynEd5s=)hHln zJa7vECaaF001zhkDLIq(9j&DjOUB&DhW&5WYqCRY3C|$^qD@49&qspP5*p z7tC3RFXi8-Az!)DVw2K^S`pMQ>jC5z1yPOIPn^^`p&w^~^UL3ynztuf)q^RHG`-QP zdXjsLDKRAr)>~8Vxqimyo)F&SNK@SVXNKlTGun59FX>MD)mGsl)o9XaYJu%1C%TNa z8tGkQFlYVuwf1js4}Jy-47WCo{3s32#oP&@tDeCns4&*Pyoza=I6`ShQE zWA&L>Al_7enjZ@Xy-uCFYXJB>>1q3W$zrV1-1>SHQRJ%paR$5gz^oMPBmpsVOQgWQ z*e{cireY*Af2P>4i=_(s$r2gkavkcmk`xxeEosJUB2EH8(z`6Q>rmMQh za#M2@VJ7~fJA!$|if0k(u1s{t;Sb4K^>8z271-|bk^y7N2n(C8rJPmyKs=Rerz z6s(7@pg&k2O>;(2(M5n}K`n{JLSVF#aYrISMJ*n61=Zy5?r0ahlB#oIb9N$q<&VWlCRuWNyl z0jq5SBwrSkyA3N1DLM_I*V*+waZuDT@z4 z`U1DMosb~K;rq8>w9Bsh&KT0?%N!B)TvFtzQOt@wnq!2E5tqKSM%m>xa<8F#$AVw| z{S;S7KLQaptp6I~a|w-o1AR;={7n7@f#{`2kS27R-t23;T>G9!8wUA#eYHW$X8mAx{(Gqxx?$tA@%db+s{zi=5D1B^m=@Mat3!QE;`` z$@XS2d7vSD5%!v0O7HTA4fn_Gl&&82?jMAd4O#(*16T9S{1cP&1b5MH1Ub6D%WUj3iFPzMBtrQHS z0Hpo?!2c4AS<}0T&*JUK&GU;uvA_h|`SOaxkYdxsC0r@~6CR|tvsJj7-Qa7w)AK)u zDqXLr&NbcQg4F)+Tvb7rBSesodkZ_|5WZ_%RC&}m)9Bdve44O&B4y2VLy=u^6H7tN z6p1}_j?XHEv7<)8dEZVhoAx(^N*2D@zz_eOI%>A$$Z%<6plrOfbQ-%n#Gs}Y7peS} zl|?+6#U-7+n>uhYyc451?tFJnvgvutQSWH>aY6lncIY6!{=4v(1cIFR)uA*7rMDyf zN9%^=z#^71D^i3o46=$I#;gf=_B0~`y9E45(=?-532nz8KZZ?Qg66pbqe%LWKO^r- zhZY@j^dMy-(Ha|uUAZUe#FO=;nwGRzq8L|xy6X5mLB}0sxOQqSyC!UnqNY*tS3~h< zorb27h(8O6+-jA7=FczF4;N77Y8L1?LPw!+4yJ5vQd6qX7JXACE2mfwin5Uc=%Tg( zQ`*^Mv`3Q$%*7R6KEb`qNV+&CnnFa7%MMJ)wFSp&5xLfU;in_#ISZbD>z!VaV${eB zKX?FKHW}m8absypA`QNBvXlM z-5+oe>aESv!>S2o?;kAT6SV#kz!bsI+r)$+QF5D7Rdk0C3Ty3hYRzSxTZXfQl&+O0 zRJZK{9OsE1VRZr|JZo!swAu=rSlm4X+=xs-r8>RtgL{b$QEo`b=(2JY`O|2<(BfyW zX3sRu+c#y-tYK_xERn~$ez|Tt-^}58^w@0l5pU0Hwap8SoGPpI3z#wjF<~T#`Cz*o z1}vm?>iT7tCA-?9Iiq1&JCnaVio!OE@19r7aM&oBnK!N0%U)&|Y=Zrt4`%R*L$u0~ zsMp0TZDOlWH1sqJg-70TXAotufJ?n9Q&=Muuj@ut&tnUHBa{bTS6~)id2T^a>T)7# zBcBG?;U2n3mCQnwN{14M(*I_P4j}V*c=*QX`)2bs>5r?`^@Tg2On#``cmYD0pCQVi z(=XR1K|6CNca)MA-_j5A`qYO+Mda)F-7(#MBqeR`>9yWRT)H7c^SRl?@sAFQ1qWWnUI`HKSGN zaP*9UFSF)ZL6oSIT)^aa6jUc{ii*Ec`v0;3bUfrW#X`e-%_^#!4;Bm#iRIwcpVOcX z)!dX-SMfO2TY3US6HPh%zk@lG(uwD9me#Mw7E^RS&$|z(qppW#@Y-II_?!~msu22X zuT77Zav^hq3AY4nPN_}5SM%<^P``s$p4Wq=&}x94N=m}2HhBKO)=%K+O{EID#7u+S zFL3Dcsy18=Nf0s75c!yM;&HxltX$OXiOcftQs!vSjY&8Q`U6Ts)pWS2CYl1gpg?*N z+6Jq3`cSc)#HJ{t);?!+s7fwRsD~n21>#X*88&L$44VB%SEKr=UC}U(Tv^^9YKgcD zNfyR5Qb0r=Tl9~Kl6%e%24ZHjmx);u&Oihuun+s>jQAoA;*Bv>CVR6kFl8ay;DvIw)-GI+C<$%Y zzjeb2pN0j8Nz5rB4yc9ZK|eZC^}Q}}4W;KLt;IK=8M}@FQe|8pW(c{M_571Hjbcoo z+p=x8$BUvI|2yntHdntzGSFyN*@SnvZB&2kdEV$xJC*I)_j>2aqvmY)38}2K4W~E9 zg;>+yeXhhZme8t%Y| zF3~ z{&Q@OcmN}pX6DDpz%<+7)qlPUq{q zfCDX5-0Qz<>7`p-cSxv9#6=W?j%oA7exln=^s%K!O~hVuQbit}w#-mj2EWxVfKW4mrmc8ZFv8oHnXs^vw{uEwwB`SM9Df%hf1cdM5rL37-sj!e&+XyZOCfy-1aUuTi8 zesF$}8*egO*aH=mI)lrXZc^GUK&22LOy|aj3UgB(8 zd{pUy{fN;YyQn$a{6q?HFgOS`tnrEEA2;+L_`|TGC~{YBxp*fZ-_GCVv;;HcU(Tr0 zt4fWOS4= zC;f5M4RSb=#8=zq4v^X(`t`0yl1w(m78L{G z?V4sK4@#An4p4;-c4M{l6$woGz)JaDj9YReR0ZvUPQN-bro9b~T zZeS@C4aW%=+uia)EiQj$rL_3%2psLc#?ueRc*CuuqkH6qD#Xtu9w<=|!Bb&tCM)2= zW~pV|ZvE_#0RPS;Q(^m#k{_aOT<{y2A31fx?4c_39L_{kkZ7n>3WEa#qd0u17*$&Q z)q|FN3@Khzs(V3b6lpJ5WFl5dsGK$5F5`AWHocRhN?+b(aagAOC-LD5K%(uiK>La zvxoTvg~!wee7U>%$;Q6U@NAu(>9$!jFzWEg`}q*>EIuuIa_6rd8q)d;%pEvbwt78- zERz#<3A#w@d<>(e4`m(L)T?+#?0MM$0;;J6tc>1_1(8vFO{V4@{iQ~ z_w|`1a;cGWi>phyQ!Eo|!y^wtH5i6;fl4IJ_G^21zFR4ruK@h6**T<6!ckXsCz0+* zzSt`8PXBGW#N%|5<+@?_VD~2g)!2(jITRuByJhM|DKgv?GNPpq?__z|vhNz0Ugteq z?Ub9k()2Tl5NE2oUg+NERp~jt$9>6&@s1~SkB-#~9I@zo%pxXfbx7XNZX5WX6IL2F zi?m@)U;ULz=iEW|C`&-V|9 zR{kP#7D(v`H7|~YW{cvOov%X*w(|P6z*XgB;lXFXNkBXmE(998Rm0{QwcbXQEMkw| z`8j!Pn)H)FLGD+j04T74vISR0hoUv>7v^x8=QZP|2T-2IKpFM>ndggz1iE%T_A9c_ zsbE%78UKgHJ>kpCJ1{MwAD2W`weaEh@D3*bjY5^M952Rp&igUb1$Fh=<RXDkwn;2(Pbv)=k&`L!$Q$4i(vkT2wDqfrzhx5-MD+Kx133^M5=o1;>+ zIB4KW&-zkzT&FR9*|7|R(T6FDlBgWBlVln!U{EGekL?dszc51hB(?61pW+OXO>AuL z5L5=dlYt8y06-E9o)En2>np6ynOEcPbJhS+N zdC`5Zu3B-2Gn{SW!Y60vH4+H8+@~_p`fl65(P*kM=g2<>ZUD-Gi7&to(YN`}=638# z^SM$Yj^kI;+Fy@X>Q(tX7V<*}GYZMK3W_BZlCvAppMdYT5dJs?DfnZg=-B zfae=_@E0Ur)H`_sWI#zc=+%9!Iha6j?KysJ@AbV>?USeR=lUI!X7y7n+e|a-2f9?Ku{2pgFmdD1NQQ}cP*;81&`R`0O{Ijrf zKmI9ZQmHd1Us_FT>&R2vkV{<;nPub3fTUPD9@*x}BZ{1yoJ0cB@7!tJ7Nr{JGorUc z4EP~<=kg2qP`W6Jh2WA7rWCoTb=^Bg4_jX>?7y8JHCa z@)c>GGtHE3@qFbl{|4E-=jpm=g@FU9ME_}j%l*{V_}Ghmc^GJLwj?j+t-ShkR%f# z>(IyS)MR(X8`5P*D>fr?-Z9uyJjU!gLh^zBG`Jh#$MNW!=)C=^cE_k zRFpp#QO@E#dW&g3x;)8(vQXl^N8jFj?qbd`&E;#GIC{`@^tyecsykm)|6OyHl#~=k zWG1heaN=LAIzt=}r=?-0XRu}2W|tDHJ8!;PS3;RLxlNgdH71wWQA!GB4tQi2k29#k zj^b2Qx*y!nTeyGLf&Vg#Re0fGBB1+$7JUYa-b_-p)Di+MJ_AV8LT(I^$ZwT?IJ9VB1WN~_2hbpe z;ek8XKWyAf#wYU7p$pAe{C)kSnH)=rIQy8WG^Bwjn5&_EUfaZ8SWfGtYxKKqA!BqK zDU9%e6Yjs%U3i57OEznc4C#~qsG>)xUe*iB0JqtyJXj?CK^SzP$j0=+=K|z9ue0V3Q zeB417{_y8GgJ=5O@vP&43-^Bpj?&rTEV&f1`Y>SX1JUdeyP5#qRU5`oBA>nUEtYV> z{#v^G=2$~_q2~wEUL1|zZp!w;jlx!yr$W}NRVhn8SQWcHaUzSI{E`kf@5UQkQ$egR2y+?rgxqs zmIDr_H1qj4SF>$S-xkLfyR7vao@z#+Dq5Xpu}naNweN{0yTyz=t>veDO)c%*S0jke z;W5;{G0F7$!gM{$|2k`9hx};&w$eRD5u=ma&5>IdGQAEJr4~x&Lhy%x|FZcV_5FhM z<)c=fy0LOau@qfqO;{Cu5{1N1M>R)hKPe@x7mJ=Pq5AtG^+R_dH~I7H1pYU?5hwsc zbEP^4d7tU-l}8GHj1>DlV!>hje#CCK<{8|5kxf^@-o87y_eb5n!1U)Ns{?e`k5|;{ zwYG^N{#U>S=J!H+k==}}2wjL}5H*N&i+=uc30dF8()Uj4*Nn2Yyqm`_!s5H`Q%58u zNvX2I@?Z~X+ZLRy7T?sedafKOg#Bs*Ww+K|u0sSqju3?Hx;nQTWt z!xX#-*?k||p!4}onN+xBWqe&%tnh#&9qdA(gq{82wB-T1f+7tU_8yO<`*wsW4uT@D z(>6XiiQ3a27z?mTP0c51FWdijp;?N~=eLTxd$Ixnts;3v<#d8Hft6MsHhXVPT{;iM z`frgkzZyb>6V<#LyOr}um>UtiagRpe{^Nf$8wo!)yZ=&hxpGH_i_Mn&9RA zI@Oqz0y9@djw>*;Z23+5YB^%j9&jGLA}M>Fr#zLhsg5KO=z2K@6nxC z9Ni;Q&YT7+Eu_~#pp2DPmwpHX))0T@@Ij-%qWOnO1g3neib>H}${|hAbAhp!QDUg0XqCN4kPiIqxj)p0bEa?oP?fACU5fu zt9-WM{TrX8+3_+TV)kzZIf*=!qF^Zj)r*=XIap@=iY-n?(X@DA&QMXw3oF2iqm6B1dO`W*l`GXZ>dwHS^!Tf;{u>`%~I)XLvx^izRM$DMwlS#`;bV9NP z&j?h28{fD`=#9_ceBkgFz+>SB1v|?JBhsj-(ZCFVjZK9j<3tT*L~FZOXn()(RbB3! zB`YWkh+$_CTHDxFF->fl*~-z3xVVj)umB~EP&H?P1NRZ7h#q5aCmh{Wkm7ITrmrf* zvh^4Ho1FdCJFcMe-xNEZLh<9A zyu|gX=J-TBOrIh9*ui2(4nCv{u1kxH2FwSFW?c1$_@nV(#~!!w-hyT?f7Ps+?5}dc z1+vc+=F+p(k7OQ7%BTudV@*YZT)DZCex;AO0NS|9v?y}`DX>G6xWCOEQa)T7j%1v> zf`nKAr>e*zX-1SYjtI>;9y2BS=k|DENkdy4{0B>(Pp)Kxd_>7^wWW9ZpdlN3yG7zt z{b2wZl4WzdMJ0jk7km`of-_ZJdNY}S#ufBj?v|lrF?yS$$}z@e67jIAs_~{Zzp!u} zp>aA+b?uF9ISZ%50a)OuRR>wn3?M&AVbm4E#k>N$qn%A1FEsi!pRXI;zsY8M{=+=Z z;GGZAW>Xc=)QEQpVZE)H2NE+|UKr3Z9Ss`BvH4Z4e?`MeOx8%ixpg=Qfh;&;DJrJX zj7~(Bjzt>V(bfrd<+MOCB(6BoGi)A24uj)rrJNkEw0{F{eLz2Sja{W*5=2MKv(X=i zi547>Dx}fCIO6K>g5AY*5gb~DNvoJA>yHk-*Vd99%0%J4Y_em;MPgT*s8T$jU@(Pk zDr+V&oBHT22aI}L6D`~V;Lh*mY*79kRbErk}aHtEE(@$fiEX*RfOg_;L%@}=%9*7IzjK1{FDP000 zGTu0wTzvERPDnr}1^ka|W;yiV`B^9LJja4Z;Zl#Xo$XIJC{x8Pso-;N&Urz6X)8AI zA^7oPtVE?mQCWOolUYYuG-tKd&gYpnYrzJz-PPt3k$?C62#MI|u)O0As>EHQ|5p!W z=z*Ot(l8a-0#s!lzXM`ETvB6ZrrdNQ5oy-d-};zs+Qt*TJDLb+|4>G%VkeemDp?oZ zX6BE3!X?CYjh@M#+^~k1J~_9pveoB|&D01lzw{uO5R~lji`BO01y|h}7k~CCD`EV< z3FAQx8>PK^HQ z9)!QS|84k+uKR5zQ%;G|Z3Uo*tPdqoyDerA)#b?k+V>KP!o_tU}j^XJ$k$C&9?+7aZt-wxn^8Xxn1OtQ}G^oU05x*q+nM9-`_UQ+ zWV{#~uv_FhPo%oaSQZ(jLsLfd{a;vb5vp(AD{FC-Xhk$}4Vfipu)l^!uf`wf|c&*KEp6QpcO9mf83}Q6#NH?XtjrpX~wkmcJI0 zFDPHrgl%Dh;^YfId+W2LF-R0At1aZsl?&4+fu}(;l;p@-G^!VD zutf!{Hz<*X2NR4lKj^6c6}8V6ZpYe`AU(-^9Cxt4k2OxgN8vBC#x|Bf z4Rppo;~N@hz2@eRi$nf59($i-ZB71q+2$2fcY8eGz{D+>f}{BNUl}ziMYOS=&!aW{ zKd4u`gpr#>yOKYhue_0sHa0e!w0@R0#S)03aa*3`k39eQp9uL!A;5l9>4eyr!NwMq zWoFMLGuE7I9)rhWtsvRR%PT^xy?0igFW7-H!gJi@t08w3*CKyDCm%VJbJJvHz2AMQ zZ+@w4fH-NZNXhK>t#x%k(CGxjWcJ!1Esd;X{aoKK(Cq6XMU0XOLDOHIHjg+!{p@;- z+b2Y4g&_hZuj3o(>n^YvG#;PHX0ij zz?J|qLmW5Yul|jwriS=;+7&3;GSpz-+|)^@=$MjWWqf2^Mx9kdA7g=ntprm7^X8Dm zqAw6uTE#djE+F2!#LsPZ{|1$H_tQnu;r@=%GmSz-G;@4PRSchlIjLQw-C74{%Bs;S zp|o6L7RH*ci39Ft9&Y#aOP3SSCvE|-q}Lw)u9N_BG>h!luYg$ES${NPMRX1zi-Kx5w*C%-}|XAG^@x|?>?mo#NfRlZY^7Yp#*q;BT93(1UF$3$PcQU zEuP4QdU&!~bjPh{*Y)AS3isZ?sWpP~kEjvtFrXCU%AH~V$~$Qc{Oc%82HF2$Moo?P zkpb6iyT@Ind>~s(HV~z00g6rwdhL@D0CCJ4^_4LaNJxGs1`g7+6%#x8Q;Dr&gr&3* zfkjJa3d!l6&+wVi(FF41$O~;958JXY3%Lun0Qdk^JH!0Y4c^34$Wdv=?zUH|AzE^q zXb;APn>W!ZZ${#9E~{<+XJxwwENIu zW<}D06sCtRGVY;9WaS6llH`=JkI9EFlQvB~>D&TyR(B4%&4XDnm^us8NZ&>BVs>b0 zQRYGAqnIIlp0#9>c!{QB_>U4JGumTeAjPP`Vm@jW)jt+|TX&W1|23M(5H1M$`fnTe zx=56dBHh}9%jl^SuxPb0o}ik(O3)2EI@pM%nb_PcAQm8GSw{ZcnZ+8P`9$M7Vv$~7 z+t@o;6N5L0r3*SuC&}ESiZXLvx;-&)5&aF^w<1LaH(@-u4Vach@r6rf4X2J1N(i=` z-hthAIekr=kP-S|endQ_UThIqEoI!S{>K`jaEAmzl)S^*=~E{05TGs}EeCY=ScLOIOv z)r-lI-zNSI;@J7i&OK1Psdp*lp68Y3TlIzk_W9*G z^4wVY2u;dZ-Xw2hJ_qM9~z}J&w@tyLf(q{f?t=hl##^!^$x_+dk*s zbPydie5mH=%>q&{U|!(dY5$CoGaewzL<4`x3;KRh+TW@SWqa=iLGL3Q4~%fOfAkb{ zGzOD)@!n&qFZO;f0WKJ`t8WxDG@tSYZifM{r#-@viIC0-WMyevOSh~yl(NuAJKxu&h5AFhJAHVupGtb z5zPEtVYRssZ~GQq`(}YnhW-s`xqY10{fp_1cgh);*8h*Jw~UJFfxCYN>6UH*>5>>> z=#nmJhOQx`rIAiS7`mIGQ|V6WW&{KTq)S@5{^xh^eb!y~K5tm_mNRS4xAy*QKl88h z+|C-Q@6@(>yG&EJ`(KX#?{jj)Y_n3o`D->7utHsfB$-ECVWWp{IfbmgVFELzj!vBM z0sGMPqpzd^ru8PF*4!pTO{t5qLekx(@zg*%^doO&xi>Up)=A#IO?;R85>q;|P~rPv zP!th?YZ0ntQDV8A(^Yt-0tg(rtOJT8Smm z6rcFhS?RA;iUJPu?P${n!Dl3tDrfR+@M39qQ=d{ZkdEk3RqOin5WeKjXy#>;1RqI; zuj5RBZnjFrCtCS!_Bpu_c1_>hX$nvxYWVYH84)qX+azka!u_+O?8_qe59-f%YZi;l zBKI4{H# z7TN(F%~Ze@;=f(yZ`XBE^iZU?;?GQVobYjC2xsg0Xxc48!W(NjVs4HblEF(ZmyD&B z>vVC|+)cA^(c)nbpsj&vjQSYgwuRQ-z7nwNob&a1QddYbR78W-cxcGv_rvNbbc)HT zRl(FT87guy^7PU{n;2H8REN7Q-V0(sG=A9EcJ`SDoTD0%2^&WuO4Vl$xZS3x<}n|D z%ScSMVWi)B`P(_y>4?JNPqcn}YTPCrUpduV9+m)l9a7UK!tSm4KAw&NZ;YI__Dz@a zpC-1-HXAoSMGeiN22Pc+H?{&iIH8(KJL}1Y3(hW^gYVo6zPGha-hMvb{x`zU>2b#h z85PA{TwbH=3YO%=yHa;~g9fN5mk9N(5pG!pYn^|H?lx?S?{x3by<7qZXkBvQM6+F zDwg5A3dqXy?SxXsGEXRe)m?^nFVWk!02thgik8O4fyTpTeTadj|09Zgs94x^6g&p3 zW+$)&#{1<-G*&gBS&X7I=gEs3UV=T1nyG7=H&#bC_U2OxJ$2~hC$j!#9-ObB*jIJB z)F9RThP!K4`h*HATD4ccozG(xk`-75c11p;W-ebQvQ0jdtl9rD;Fhi&=wigDkbhHh zOFs%^coHpp@OWS=X{?#L^MJ~Vq-nfND=m?9F`^PfRyzIVHt7|OvRK2Xzrd*%a9>ID zWT?Az205X-uMD_}xoe3C=qa)5Fq9t@MKj1UqqcDqNK2^wsalyVaVj_zc1@noIVl-g ztlxE^j?}GHY+vs41f8=py(O$;U>dW?j1^E)5M3B>GXfPC(0>SLlqRrY^D^!r!Wx;J z7kDdv%|IC<%EfbZ=j{^m0=38|LgyE`EUbhA4C}WA{ouj*FAY5e`fG1*Semc}shC5^ zbpu5X_T-m>d80~ZK~aUzXHwyO#5)iw@a#H_6NNOdmnd=PVL2^q{Vrzx*BlHk5w_d{vjYMSgu-EzxtHngKU-;C9rkxe4M`DMf<&Tht0#Wq!}2$sDJ$a9RTa71AAPV zfN)K^kOI$c$)YxrW0P2-`ogBVKjn-qTjHVL({XUpL|hmLTsG%zng;Bt?vXmg{xN-S zUo#U)(3T6Tynh&B$=x}x<`RD1$ojR{gS~()epOz|hJETEJHuL3Kl>gDcu8HD_3_kv zGfwOE9)C#61MraNGOxW^q$M@2y(8pk@J{ELQ|@FCj-&@CYgEWQ;SrXLjCD0bYQeYE zzOe?m3rO_&9|%D10lU|E7JRT_&`r;MAjTT9@j>%Sr&9TH;mN}MMW@;S$|Cauf?tGn zbY4wuTC#9@Y*`v;jxJ>+TPq$JA<8WcplX$KJ@^isK-HE_kLbD1au?xvZ>~hhl3voo z^RAC4ywGGXjnMi63qe`mF5Tpw4$u*aw>=~ zf+)Q?-K)KFUBY|Y`6(2fVIe}}E<>ow5M8Hc#i0~sj)ijhqU&%;r4$G|W6mj3Km{)y z{S;H}jY^_f;>ug}i-|B3&!J~B0=vP;Ol}Az&fiFk%S+s89JgIK$ssT?qBNte;jrx0 zwYOlOSvm|+JUnZ1xn6*fCrM#d{=;qAsIx;cbFc*#2WBRY z)Ex2^=*<|GH5_G)>^*OW21jf6Zf*fMUVwAQ8twHcV&EEs1? zd`2G;-8z#9$TnFj)2p;=&uRu6ffVBNg()m1y5@q=Re6tM=z zCft6je6sfmZ&NYMsptF?k%Y@$EjRp7IO!~=qQbVh9mtbNh`oH(E`sjhyjryERM-6( z=plPAjHrj!|Blovs1(f-jK0@G)5(3~PP6Q?U(3l)O;gwI)iXPbnF#cs${UPUq7?B^ zOdp+j*jfd{6#qHM#>Opj>S;S^Ts}YJn`@nHV#!{c$w^v;iJ*sLoT#D@rHU)(uT}9r zu(+<+Yf*JeVVe5(cGb$(FoMge&t0K4hbXxCGNC?{z*4H(nuv`_k$k(9Sc%AQxjB%f(KEq+sRm?3r)O7#nQoLxhlKpF3YEYyD=+DH4QMGxgS0`v|Mk1i$%k{+>tOuJPr0 z6-c#izUB3Hm5#-PJgc4xGp zZ7f!nEIqObMwQC>P;O5ifz~ED)FVkwtb4BJdtTg1S@@#V4wEL0gq6>Imv(9*qhiLy4x?*CGM2FftcClKdo6ltrjiP| zTq&BbwCWQ`W5^0yqm-1chvxuqxo$i`v%l#bpnz4bwA8Em!E@k!QM`(E=no*bqYx;| zO&@$^HHyh2!tD-iTjgl2>4;NAYb44Tg@sei3j=jl5(rsNHA;S9`}HxF?4$3M0MtO0 z9e&V4UjkmW8g};#BL~)1Q}dVE^!&yAnN$0T4{XfvSCGWI)>hflMe}bW@AZ&1bhb1? zK459pHWw^9XtG6d9#~2>8^s@Z>bd0ZsxT8>U0n^=z|z^v`hG8 zf6p8X3!i=``pj9|c?B?FzNyA_j0^qBND8mz%j<*Vn=*b?nk|z4MaLnPo0iOE^{T3> zkzx!JiUfF)C?Zu#lZ0oN64TMZx=HY|8U@xdY8_IHf`ell+_3mzORuLj_J;tSf2xRN zAg$a_ygO&xaao`n*n)?g-2W$(_prV@8(6EW>V{F?PB8#6x{&Q;=qO@Jbf7t4sQDas z?ZE_i1*Fw>OwLb=M~1RRydoH&Y{rZH6-zR!s78(F8j2_A9D~R%rU8 z08ay^Z0`K`K{mg2e)+I^p)vbIuoF5>iyxG#>K)L9OS(E}>M-uLh(4!?QP+=zj)|*L zMN@BRCnx|U)K-8rP@(Rmyj@kDyVKrvf9RTH8EBuwC&flLN;itO6_MY$wQxq%_XE4_ z@}?k+b@Ur@63)%3`UAP|%fDzH0VDyJX#ufs1J1NMu5+$GJ%Kp6LY?|Q)%Qz0&kUuj ztv3f=Pf^5p`HYFIj(Y_h=J*|t(1@Rv29A%_!ZM1T3paa+)H`|{I>roF@5tl)FS7JM z_MJTLkeGNM*WQfh0lSXCH8{EK7nV=iJ-aO84`S}0;|EAGL)^wru_Yeq-{Th|=LY)z zV0r$FfAhdUb@37?%p^Z~ahv-qx}#ffIJRCBgs#ZAPe>xYL47{S^GjVY35d;mK8>4o z4&k)mL=+J)-@m!J8OqDwZ*KK=3iayht&F6PE<9E(t5_z2oG#@2!6xO@|MveW&(H5L z`Y99>KMxF9gDNn(|?HT~iL3 zbYXPS8_QErajQ9D&<#16wJcWF*fi#Zf)wm`(l~xJX%ovAAw%2F&tsYJmq!;M7qvk_|pDvi))4u2nU{>sh>NpJ*kRb|91QB zcH(2w{=i;R4$r_EbDwt4Q7e@tO#$*Nd73qu;cTgFE%&SUEt?NHlCrt#K6}0B`$|e+%;zc##f{PM^*mP=Pz8c%CH%U}**{ zOl>tuP)zBb`_*gm=e41yM4qZL!xY>y##D353}(CR52O@zAzG#L6mgN-J`rR$9<_U% z?{x@=!Wn{7$#`C?+ukC{_ykqulLR@YQyM$g~_rmG0mMlfkyW9NLy{D%BYe~Ue z1KkAUK}|GvNFr*qwo%{u??b5<26(AAz)YF49)ZllGabivm(@Yuneip4PG**$@oG%F zbE_u+7m$d2Zrb?nt5owOW}&2y(#^|qF-zZyq@^R`L#i1 zvFm&P#9@}-Q~A{Q-zOU=c&0u_9u-)^VsVkL1Jb{eoyZ|T=N*g~qFtZ%$MkE0_aVg4 zC?1rtF@F^m>UDD+Qba$+vS9P6L!2%=%G}mA!pz=2sd@!tDm0eJG4lwzRLu?B1f+F) z?glroSbDl^oH`Ym(R4uBSkVmn^f*zL;&=- z8|?B6Dh5*cGSu>7_E=0PnI<9uDZ-v-hmF6Yb-h~Et@#VV3>c!Kol*8}7^(nrO$k#4 zC#-CtohlYhb85Kmj+bge(MBjZ9izmK^~aGH3S>nlfc~HY$ks z3l3p~01SN7TU$p;cT1aHexI-c3o^H6|Ct$50LKJQ^uawKRUC7=Bf_bxbam?=7hihK zf|8jc3cmk5nmK5&w=61tRm{uq(~it|`tayq7ShD#roIjq;#-Ew5MUt4ecY%AJus*8 zd=CpQ-@k!X}*j@ig3G3i#<}PE}@#VmB!5J%S6UrkR#qTdV`3n-x>>s z==py_?>f=i$V6?~#9~&BL&^#3pdB#IMe@+8F^;`&jJ|`{} zoS$J=H2Lu>MV7@AVjva?{rtP5QN6Y~rrhwa(}{TockC5)QG}hsxpsloW9}A2Hi2ZT zym0X!>(}%Vu=D~a4nI0H(I&bMWn~)3>MkyeGd2^*V_+g?5`FIDZ!qLO@m+=|A9%aS zme+C}w8E-SonC(!8yjmLScAjgh@U6Koem0iy)s@HxoG=+XHVkK4zbu1mg?Wl3pnw* z_;)cy&xC^>napI=|I z&*~~|&8~}!OHbVMjXVz!_6hxVCsm%6;hqI}_+UX~5VQTj5zxy`- zr&c%9;n)G;)C_U%F{EAnlVPJy5YFG^$sxS!p6h#zntjFB-X7_@>?E5kRb=>wI1t5bnRbbF%tz(SN~o=T@hg}Wf4+ux+(hvfwwzF zi^;5+L=pUeWn~55qrAX%;~yI{B7LOF^Qh*ZV2K4t}p(oDRip2l)ew`pBt zoWQQ>4CraC2aZ*-XAVmBa}@*UtjtQ%tN(`kf7k&I%7=%y4}><81}IXUJg?=2kg=0x zGuY2nT%RBDHAt9z5@+{4eC`%^<8@RLhJe#@?*6B18nRaJb=q0bK!fqDsHH!A3j1y6 z@cc0|*00r73xS-|A2#Buxz-Prd3O|(x#BW>Up15xNQIfI{3!8LPn``#)htPPvT+h;T11Vn|@Xiiv3s;wn8h{sDXOV!+4pS$jT z))#jPu38oJh?C)>QK+h zufb;i&`=_d(qD_KgN-W3;J^qu#1O#PGao)Rd#|Gnz<8;dFbcF%nR3a1AkZ;o|IF$a z3w5q5zQ!&BS+6E{jJo_t#`tU-jexHT*kS8v$cK>0a#@!|S@6;FQ%(X)WndB!^!HUJ zQ%Jf!>Y6|EjwTT9WXkcZl&@W8QsU!d8%YY$R)C+K3aXBmd-s2vsxIF&(Kmcm&dwo$td%`=&yx^%=hCP4*<`gSl& zk@p`XN`QD&vDMp2uTSS&inC>AHlOpru3M}A z!{e@hjE>@%r(22}R72r#88)NTrc%5&Q#(wNfeZlQr%T=z>L@g%F^SB?s7T36PW`RDIlQFz zU`grG4Vo(!ZzCkOi?A25&6Lw14y#WGk4%S!*Enc1 z5GcjJe^uf%86w_^}RZG$%zUpEE8Ad{lu9*{AK<4PwBa(B#o)q94RV+mmb~lB*pZzHKLBER2 zG~ZA1TX+4~^X*UhvU3AmH%{Bn;`L`SjHB^P#CCF&X~dYnlxd~t(x)r{%~G_vjZHLJ z&`JNnAZ5uuUzU*^g0Zt0O;+Pi8#6S8CnIH;ecdZ?mp|QLh3oB)h3PXx)1RHbeLXy1 z3imwYO6@XHqEmI65!mam@_ z!#)6}_MxDWn;_Ua!v%^C79Jk@-VfpdYMrgiA3-H6SLp$lGxlDsb)8>-ayhJ9kdw|f zxQeC)UMHOtsIGJ#HcQ5t0gN2)7eUlXJ-n^&cnCc63XT)7PmQPH#tw`UxBL==`y?0~ z-s?U$k85`?J)2oXFT-DU?N|GMq%nzS-xFBhbAdH~3ZW9jXIoul;Oyo9C)_4ke}JFU zqnze+KGyxDsMM~=Ak$|%`OzMAHkwtH=i6{J^^_xD-jM!J=Q0~Akl`UtSdADhpP8Fd!yj8I+ErjDu9OyCEWuF8`99m=d{v`n%&V@b~wL z?^UcV*-`7yvX$7_36oXQ2e2kkAkq-beA0Fl3Lm6HmaP29pcLh z!V+vk5oyoTXEy3g-t>NxnwA-ZM^xy8%y^SK09?U%V%lD6+9pyp*Ju&HI=SB&^1cZc z{9sL3tM}GD4Fa=oO@;)ITZn4?`N*Uk9Odl679DLUSlV%Tgnt2R?tIyQK8zjwx}h8Z z1La!k3;Vnx0y%_DC+NKA;JN8Kxm6Rt%y?T!k)J#%T6HQK%J-JnV;Y6E{1pqPTq=K# zvI@4YE@he0tX(^X%=bn&Z1-5uINL@1ZNuux1w^`rZ_v$qD}ks%SR8ku_or%f2LmS2 zD61?K750td2zLaqv-b;4iCuC!2i_abBwG-w+1}FD*ztnN0iLB##i>#3YGULES|~ja zZmEi7H8z5j#Td*u4?6q zuM$K*RWY;VCV1+S>ONZxQA#e?kj0%@vf0ADJGClBEc@I4S`0^?D3Q?ulu7q0S!ZCs z-bOMK7z#=dLT$|Di7|!4@v<;S%KU}zy#jc-J48dgOeC2+n7`3#w1ysOX{pVWb4vE} zafpl;Tph6c@mcFaKqDEEK-wfeJ#pm(UI{A9o*zs}Kdm9u5pe4PEHy+a3z98FX_JbC zWHC2KV%BX#G^2If$6P?`8!I+oQPHBgkKdZwG)rqgBClNwd2BF#{`}cWcI0Z_i3Z#7 zC+xn*o+mFt^lX3X`;uwD>yhxCUNBS4QaTZd!k>o`#P5rU&-%x?Kk6ph&~@Ehx$=r( zYR*1Ub5E2NpD?n;7axKuO_!|i=efOBT+sn|f`!osVYU&`UN48R53H)|%`Y>L-i;I~;JgEvO{EnmEPMaFL@Bn6cc+KIz z`!Vm>7gKHonQEy}49u=gt<-47k@#XYCsGBra#*`NiO28y6SS(PwBZWk;)=E`<2{UG zRvl?0g}Oq|&+4UaII6WtP8Zoqy2L3AV;{+!HLQTy9hkKKi!%ZIX!oEHQaS*VH1h9@ zQ*D&>+%gf%D-B}85;x8TDTRUcUUDr#mm@SPd)i{oJO6 zECjDc8)Fh%_~@6>FVb7Tx==HJOdndx%e*X3*rKS5S3rd%PUBFHBfhX^Z#E*&GW7G> zCm3P$y7-0dQ)b)e6|xdV!0E#|$zwc$*OCvh=E$9}H94tIhTDk@zRTrYC2+kd;hO;t zhQhx)0#ZOqt-xKHSIMO@sBvDnZIXu=%-cQ(58;jz#MxUd|W_Kz6>Vc5G+3v9n z^*p_wC7$r=2R&iO{yN3JAC6bUyVyc$&4JWx+K!E{l>|K+R^_#u%O)5ivQ#DT)uVHjMZ%# z>!hOu2q)|s4U(Zzjtk%MBrdfi24wKXP$YAAFI5dN9G1HrZJysIkf5fPCzS|w-)41B zG3f4xu{pem#5x(t~9(%i^Uo|7m&6f&ksYhG-*fm$_@fW z_JvrVpriyLhh~I;(HGpNWuq$)9JYrp&nu^kCUL!!(8O=BxDj?2_iyi4P#^ZFUhfQW z$QyO~##S$)`qHw3l+1%GnuXA5pMR8Qq@i7l-w>=_zw{z}@%$L~EdS4F9b_=BbZU$* zqn%#Z3>Wdx@L1(^%8e8S$s#k1rn=TUOcW{h_61r_>1=^@ZK~ar=num%@z`PA&GcG zn5>~b(|wSJYkHVAS}VLyIa_<&i@doFyclED+)NWchXkCntj6L!44z0t?%#lnvH;2d zS{y63yH-fWfeIY;f9I)$nvC_f$$o#rJTC2I&WDx@1@t4zPNPNtD*r=A(c6DPK*>-U}H}g!jXd z%(bVTAYmg_q${EdTBpd6z2?i`{948fKeWRu>9N00H(lBJq z(}80Bp#pg#zluGq#_jwkMO!D-$*8?ImP%d)#!yH=85_iJGdXSNp)mw&6P=oV2c~?T zFbF^%=@k1!eR8{}l8Zv1!=kqni(`tUdzy&~GscCy&f~@r+ ziXeF%0CVv&v4TCmLV5v51yM5h&sDVd?NeXe#mV!+GaS}sd`^yIamRs6DfN|ej67D( z3PNN4SO0Q>QSoDcvfUd{xH%Pw64#+xl9V7SUYf10@cplEzat;}#dPO=$E~%x9)6F3 zLh*4sFdvB(_9-j!UzN;(6IA)}GP6N?Qj`o=y@W{Xd`3vd6k z3%wNuEZe-~IIW&XXgWGseW2=j+||21xb0{WVjl>iX${y!TX%pR`O=|=!s%B$vjCh6 z;ec&~i99$954YQj2aK%Y+Vc85LNI#=SQzhU1>Wl21cYV@HiO;ns1FYh|2jFtmq}B? z(oFBM!mDhXm-A6RXMOfyC@|O5SYH%iVp7iGUQvr1v63c_xN!=aC5D`@w)9f7(Kn;%}1p!%|RU0-GLrU9|*-|{*n7#gl81MRKeCt{#1TyA6E zSOE6K07;#3^diTJP+(Hn$X1eq1Z@j*UZ%2+QV%u0@G(p}bBOF z1-u1BPg&W;aDxCa!HN^rl&ik6F|@V$$K4?1;iFC;kCiC(D?mB5EOac>JQ7XF5)Tdt z+9ltT9bccMZ5D9WOc`2uSNujL${HiNpkSX8K9aug03&2RWDz)UYaAYllwpjXoAZ#Q z9h%0DE-XwYEIz214G2t0c^7PRN3ajbl-$J!hH`mP zk33u)(IHBrm9jbtg+<5dQ%TtXeZP!u>JYrM{tZ^;X`JTSu3EbwV+Vv$jh~u@QQdgw z>fy@~WAd@Nh?0%Xf7!t5pLGq7Eur`@ukjR7l90xf3BmqFOkcBY4#9&M&?#etFuSG} z9)>7!lqFlGh5;hbj8Zr1wZiV7Qc6+uAkl>(ua}ZqXmKM{Ek{VPn302n1GH=$Hl3j+y#e0Ny*Drt z4HT>uzkqUg`$dVIv|t1B#JitDiHw_bX>Vr^x!s0Zu^m=_^?pB)3W-?ApZoYKf?m+s zsZQ|M&ey4cT+S%{gGPwKfu=5-UFOCet!rY!Hm2wPEOzQhC3Srr`4kHV;=P~>dq$m) z<=2Q4jbajCCVj{1Z!^5$Uu!HmyL*n2y3<3ms<{vUc5lC`KM38oGj%Zy6Ul1K!wi?p zph*>+tmh%^Cv6IZ%-XVwVC<+}!hJ^V6zQ>EclS}^M8;Bths#Q|Xy}L)nr)cI4|ht9 z9eFEAj^FR2ci`_k=H$$9IGfVPpop3bQ^TJZdO*#VbnKkG$dGZ4ZY(}jKKJ&{R(UE0wRhr4m_=qIX|@v=IFr zAL3o8{kwsRw04TiA~bHCyw+zbE+fT7nPyECJThbCdLEWP`i43sNF!ehyO~S*PgIPk zsFlF+Yy)ajbh_-Dw%}mQ-yUu1i8>Gaub=RgSFc^qvL(mNPVNLwd@nGm(S=pfJ5|6- zVtw_inkQOJXAZbiDCHc{Ws>HFI%XOc_9PWACMr6!pPBYezwu=+^G1?-*AK*$ct0X-b>J2|q%`*dM<>yBjmGPAKGN_#1P1jE3i!KK(&Q7UYRj43 z^}nmQz3!c{=+vf*bDph<*%v^OAXBUegUMl(!)e|s??vQ)`SWj|S(@X!5juooOUPXq z52gk1r^k2sDOJBn6JX7xL^-roBpK%9h>YTOi8Iv#`PFn#noRuHb z#&?xmMxO_tx(X3Qw!R}u-DC4txN6zr10x6)plmrfpCCTo>o)~6;|S+)SLcsB9h2%5 z>zmpq*)Xjf6G9R#_fTVd0B6;-gZIT7WpZ6vV)gQh=yi?03@v3~@~EhgL;(II)FIwi z((7PSj%x16$a`(R^@nhx-`9VH@FKFT7QfV0iNuDYd3W_XWadX9t76Q87*ri`R#;%x z#5KTXN?J*gcy8v~L+7aIPUK5ZPe2>ndvL(62+U)Jti(XD5^C<}9f)r= z+S*mz>d@o$ntZ0sdyOyK`U)?Lk^zrp$px>HWcx~Aom(BJd0-&^(CKut?$Fgo+RP6M z5ahb!a9J6QU?*~L#K=qh)hYa^p6iR(0k_X`89p=!JIXD)@yXS_t64p2#jqEuk)m8@ zqM_SP`2Eu};f3S;fEZYT1FQHzTL~4hWZ7?Ja)ws0*(MOdR8|qPor0I5v3^Gj5Fr4% zYck=`cgQid$>z2waX~?9pt|yRb{^pT2SFEFgV9XuZg2327?CkEw zyL~iX-)9Xs!pThj>>TPv!3oBuKk&)3k33JUW}z;oGHv;+E!j_f&J$9fyxyU)uQ{kV zh>{|}!HrIhc_lEcfcKInEQCyq+@bRqp1l5Byj<$_Z~ujDVSVk9V?ahiw#+Qq4|dXt z(=qn2Z?Rm>p6b}O~cy`6~I_sN)(ptAyvD)ZsDue5xtZQ89TEN|<*_5zdX*)1yuUA$P4Uq3rFBZ4Mf|^2qyK?%i^~Z;7 zf0`W3kE18abuMTK*Cm1E#*+z@IKJ}q!$Fj=Etfg3T`v!>8YPjvyFL~xD(S&C67XuG zfPGGPdSQ^yL*cdjS!3{<*k{&0&lKZ z+xJe4F_H7_Fg%RR#5+pjVPz_zs%sGYZAVWm$ASVPJ4t>BpqFKF-0K09T}K?QJ&$`^ z)FFA6ABsN){)Q;MBae{sn%=!asDE#rQM*#8*8=oxHa2m0Tj_HQ7G7&+(?_l@o0Q?~ z5JqM0o!ua_PiN^)LxqXaXMbKOf&IK=pu*WX0}4XhlUdhx4I8G- z{-=J5TJOl~{PD}9DP`C>4ga)Q8@|#Al`GIutjOv)FdWR>V^6X+t}D7%W?!8 zkjBW-Z=QXz$?a54v$e!OXxou_eMca1?Iv;k z{@=s}HQRQQ$y$lsv;hJ%k%WCX1+U4kp^7%LRLYaM`)T8I+}c!2Z&2fXFpt}H-nej^ zVtSX?jhvC6{bFh-v5x*rH-nZ9whuUz?#Xf@|<-UdBY_UiUcdfUy^ znm&G8y>^e&ef=5JBjFAESNnz9iyR5>@HoGl_S@LCfLMu#(B~|PoBs5k?=HBie-^jK zgz#j3mq_X=Blq_piJEO;Q0tcci&^QdS0Peh@mi#E+R#}4bK3m8gWl@4i^oU&a3}H1 zWK{0@KHMP3&3;#6`_@qG+$yRXa2U{i%V$$6V$0|C-npZ7&iV1s>->n_b*h-e4q-UN zfwS>sUf~vT_BOS;-v=mn)ap|OJ+tQ{ISzYnNWbjDgyIF>%RdV{uZip&--ZPKlX&K< z^*d!6;xtJXE$oS!L8A@~6X+4qo&VIfMQvd&axE<@|!D(<; z7%ntb|DmMEm2(zcs!R8(N*B`yHI<3i5knY>QV~wPyuAF=Llr@c@lrqlxi4R80cj}i z&1?$|_Dq|Hzc5UOzXc|& z0@SzIQ3?5ObeA5FM);sn#u%E$8i&2j7%Au>J~;#_-F- z@4CZLq&5G{W_M&EG}MwC-j`oaqQvsAjmB@yru9o%Wd!HgFmRu`$Oaj@1_VS@keL74 z-f{`A=#58Sa4Q={uC^y2v}=NgkFhe0(J8q38ontyI=yQ5^7(he``Y&sn#{egZ#>$; zFv4HQz%s!<%fK>bFCZXSl}K{ZbuYlW=W)mSjxNdqZH2akm|Tv-3WNSb#k(U=o0R>? zki=8}!&u<$A!i!LAQiJlhgs`Sj3ve&2Ej~Hrg*N3NKI@r6}`#KmD?fSjYU*f-$Q8u zsUfSZ28fy(Cw<6GV31x1j)5GhXW|oH8@PSw;AB!jjH)!JQc7mEXqj18P(k^^Xh=#a z*l}@Ml9&ktw@^2|CRiIy)?ikfWJc7cQAJ;MmsJC%pBu3HdLC9V2iIQmIg zfhf(>Np(yTZBSRF$hc4xwRy?)^*yQ7t94=>4gQ`Sn=e}*^2nKqaF5-FFn-L5IAbq? zBjF&g4b^XNKf?1l-?E@8C>qPm{2VXDtg$DGkTDu!hNa&8QlJRZRFDTG`;nXA>^##3 zw8j#1OUux8Kqs;TRAmP~mQ(4lc%zkexdx-zGnrMt3sv7o?j}czOy&~kpH=~#MFMYb zX?ur-A%cy%XMy5!tgspv$0WoyG6G~rsj8D46kPnSga_j>-@{hfHZxjujMY9I)a#+j zIc5Q0F6C4%3h_xsP`Q`YhxE#&^<3QkseB7?M(Y=2Dr%(O;oQH>S7q|&S5BC1?>O-g zYVl10xOhfG462r?l|m(UW|?TYC)3*R3>LI?7O`qnWgxrBkmZx5RlS#W?!6Y@E!;$z zIT+%rza89*OO>ia<`^Ne#%ak=L%om70)RB$*H?)E1&~;NNOc4Ze@*v#MpvEo)ewM0 zbAbs-L>zgM>jOBXLQ-bg#6&1XF?&=Yla7vACaq6`tGBm;adNWH$lMVXN^a;T*a{Ny z5hRVFTS)@+oiXy3VFV6NPIc|=U)!i(tN%xNku&BPt&lcAGuaC+;8l&%tnlDX+lH=u zgXjyV^8jWHd=_A zCfWd4aQft;wS7xN@mTocvPcgx+Sf&D8DZkvX!$r=UQ;=JnzXDbc4`SajF%4EaM{p9 zR8V2bOyYK(7;_hy%hBjN;T$~MC=Kk@yMru;BOHZIoMKSYV)pHAOle*~DwUv9KGnqF zAX*JnLdZ#p4Uqa&VV7KB8?6;A99gu}LNtKq5n)~!RR0xQ1yOYPPXV6H8U>N#1s;f+0RwAv$^fAz!rwA<=sB((4O#EpU^g7c!H|o%r)%Xt>x9h~*kQ=J8 z>BC%sq^0EP^iix7P zG-GwS7##-9EdTBqPEEtumcJwicn!Y}JgEQs7chV>pJ?i!Dv|=aR`s5wa&%x}4O9 zC+8b#w6iAyN0c$b-Qj+P#FO^l;}2>sh*Jd9u%=7LvSHZ9bu zlH8H9OnCj^i97FRME#WJtrOwsd@x6`WSKxf+ne5mQ=-?;tW)A1IqCsVstvdfEM0Z7v6D+cIx?19Kj@b67*hRw ze#4;zCvHSrv#ULWVGGtO1e|`B=vy&;=1NuUBQv=ttoiA8vuOYDC$e_^h0wPOGb;)V z%2kQk2;J(JH;NAzc^+2*m3!UufeZg{8UDZP@pBDpG*15q?_AYpdtTZYUYsP>iL$Kh znKE_ip?_$`J70lFU*xdCOJJavvI~8pdygIq9s5WHt`EybQ%F50AO2PtL5qc!V z)~wjP@Q81y6UQgcQcy)7NVU)^coT(=otWZ&p=s~Z*<9I0>}wJNt067b`x)}899nr_%9+W7r?@qanfBVNZuldlZjsP}D zeXp~}ct)5@icDq=Io=&Ljo1z%@If)6(^#}!2GYd6JCQ>l!RdXndT2ZIE%2KBPH&K*x^UX_tC=!RfV1%s{eH2wz6tmSt1Lt2r~ zZ${Z!xIO`6LIfK@goU$nq~^Q5P!0g~6ko;XfS`}n^jj!qRnpec(ji%755@{BAW#B; z7c&;Yn+89_rJ8r?8}iF3GfU(aGPnJrY6@nV>fZ3+MjhU;8fy(X!kVY!Z77V}y%u$F zp&B2ENuUOaI}|{OV>_uvs}&EW8Qsmfz3GNt;C31XK03}ly+?-D&O1F%!4`lrqgO*s zAj=DMBYM3IuLCdPj) zzGeD&)osmdSl3;zJiQ-8Pwt6^LH|WhV>yy?07FZ&h(eP*U5?8CK!{dHgTFJ~*z-oX z1tz0quMKG=de8awbT(o2 zecpIy4@e#n9XC5`KjZ#K3$TIC6W+Vhe(k*(D|j=T*7ZIir8-M^1d04I(rB@>PfzVF zSR`tsF1_uJSfgQUPR|r7N^Q2x%)(*=*nTa((~a%wUC8*zw?E zuU*<^UWv+5DZt-(yc>j8)thhlqNT22*?MTyja$2i5H#!z*yL?oRRcL_FKcF zwN`x(xpoi~!6%6PMe-QHqrCcU3UD-<3+Dv2*}Z|uOj!m7z8(XmPcQ?}zcf(nNc~ug z=W=fy6EsC@oTIOo)P$#}$+4osTsXrez*i1JTz$2^)Y7G>Yt2cDeO}10hdZON0kY|6 zT%^@okW-SPWXaCUH8(Ax1j7)6I)(zNh$~`|G&yku2%MMO&{%36E9}%WP3$qk4ojb8 z@iy-n9E`UY#9LaBHdC0Pq{Ehl{3M4&u;ElxFl4?3%!i9sA%|_+6@4DY(QSYB{(ZT> zKH<-rAeaTZu%_l_SFtRow+`*z9{-1|w~mVP4ZB9ALs}Z7yOD0`2I+3;?(S{`1f)A< z=o&hQkQ{00W~2nA;XJ>0o%gKotnWWyu@*2qbKlqA*A8h7JwY`QMO(+fA5LKN_MF`{ zV5er4U#G{-``I8R4eNO7ue}$Uv}?G%K2ybb0=@+TpL#@kfqRokQ0zuceDdyL;n?K44HJk>A2pOUxvuV#=-E`6-!4^ z-{}2Kl8EmXJtvRo?BH#%ag~?=Hg;-tt*$YJ*MsQek8Ayvr?rL`acJW59Vj&UTt&?g!L6xm-em=PcdgPAXz|tXq zr9GaP2#_DJI+{5f^uV(c4rzle3w63<211W$axY_Fmnr8nKb6y$@+*|3AHXMI#31CI z^pvZu-E!AquQ+>$pD8^IbCZ<;LE&2r7?D2B8V$pCTy%*%FITUZ>iX;hpBno` zAoSV7q3fUnvFNW_bfm`boIdK{7+#t^JyXhFm)T)@z_mx%XI}o$9jJdj9{!<)8pOnU zY*e3f!tx2da3kvVpTw&>=^ECCDeM;`Xu#iW8%YII-=;2j3A2*6hIHjj^60B-A8c{@ zpEOOqjE(!r2x8FNkSCOwr#nc<<-}~kzo4P{G#ft74e~42*L_MFJ0#b)cMY$Dj0)kr zNJdQL@|UwOkD+1k$Y8N9O>@^b5|8g1F5`>*Doj8zAUiV@q^N;iE-SdCl&!OM+vt&@iVXILV zaR)ggbvdO!u0*qUsuL?q*WV6|cltP{^5(sZ5wEm1SBT|R<&;&-5S>L6p~#J?1;yzx z17-m`jHnV^(g+-<*+XmDiqGQ}o!FWXgt!YADPH?>by{bkvQ*hBE!a)irc(gelr> zHTDUtHRfT+DwVdVbhY+KjkUGwR(pZY^7f{*t)(@}7^Lu9mFp*sd=zuX{7N@>cR8>Q z?6er9EGb~|dH|Tzpk4vg-X>{!NSY2R(qRifttUhQ&JepAcO^%2R|$od*WMvnJB`gM zrp)KDm5Vr)f0YzlVG31;(Yc78=X9)e!dWho8eCJOqo#vTr=hX|;MV5vmV)@k-9E{J zDK(CxtE)mgc44qpfUx}7@mx{*{xSGwTl{&>CeRVMbQDT6SN&B^+NAWiyQ^z$_`fxG zx5X2tF>*^X%IMG|N5tMzmN;;!CUX706x+J)1)@kZ8C?7B8TO`~!II+!o;Xsy)QZTQJGlV_QEbXrL9vPUF!Ye~E?Wg?=EUbApr-)^ z1?8vpumb^4(GMYEVH*!|S@aCGmA#Xy22BC9viY3m@BYBGEGQ&oAxMrliW|eFm>#vr zVkvCauBHZo{9Qjjpi?~d5zbabs#i8v3bz+VrRI!YC!W1Z(=^ugKRgC6`eI-NtykL5jDhHhD zY(RQ8S-QQwjUG7|$Ay6lgrTVX_gZxsf7o2x2XZX{ip*L|vnByt-6;BYk*So9T6I0} zC5VqPktc%6oOi{18~gHoc2Dj6q`5~^v6DxHXi6UMVVANJs4 z?A?6COK`bN^2^#vB~VYign?JwJde;mSL;BQjIu!HlYsVhdMq}jr9orc>cL4>;laPN zsu~z_#lW>FMj62(49qa~VVBLi&5)ZIi{v6%pZ+ZtC9o3B+gai7TP|59!-2T3lcWL| zzL}f6r6n}F;8{%WS#_rB-R>&$l{WY9)SQ`=kCI=cj+FyShAqFemvV+-OG3=Kb?iQX zpK-~^g2(d6oC6x2+h?3g#(}euxhv$F6q2g`DcUB`H<6_wM>Tt22$fczh~7~83+v3R zZSmmsy4L~Q)cORLzoJgKHHo&4v_XVb+tqCUZTH147zgnzs?~Ms$`No;tQwXDZvky* zABtv4Fp&RSWfNx;Ro`{UY=J?qQb(@Dxy3t&(_${058YdAAq4+r{GY#I72BPX+AH*JL7IJDY_oM-snCEW!nC?I@C-SCq2mq7Szo$GQI7u0@wY z$eLdQnO3T7FHxQSbN{-iubRB4X!jw=D8eHBnw`dBUK|j8in=S49D}_{vRla*=(WF< z!bs>aJO6mB%XDw58kla{(G%9Ms7MF4+ac8={$f0Ln6>Mmy;+B-B7s$?kAqrXy*ExC z^swe*uBpOx@XUlCk>FQ;530Y^r(R*dc888M9$o(4m)H>P=pge`}MZ$I{%eS(ofd<8{?ORHISb<_-bwdrNJZ-ye~sRq1*Fouic zw2YSri>c%Fc-y2tc|Jc-guBjb6Ok9GkzknHE|)?9t6o;Qtek-zhSmpC*GA()_n<$- zvp#+&(M0#*7mtG8912;?fUU(TuOWD^g^C4vSX|bWx|~XtWm3t?h@p)|Ap>;_H`9OY zYA@=lT3RQw8a&9)-Yja><^ZATHW>_BNWl>j&jFQBDvulpR(id$pi+uH5G0O~`DTvF z^tE&x9kc-s-yO_ZHHa1+dJhjzIr z#fWA55m=C670lW2VlYo~*L|LtKOu)GOWFg5S_~(kq0u8`toWU#E=iWFC48OinokCL zqA16Scehirz{zcQ5_ix`um2g~ernTzoHL$b=yq>_yQ)8JR z1qqqYg1EFc>Zm9X3)+~IuR0Ee-{QtuE1qO!v*)2mNsAdgndk1^2_r*U_WKuo#C(mv z$P^QaTPHi>IV(ClKabl-cF9=u2=BWIEZg)zX>=q&?AI{1@p;cR7Vx8}F&8>}3uo1j zoSbfe*ffjK|2#5hp1Q;eF}*lCe84Fkh4)idwJ;k1lt3=SPt_C))KiA4TJ)%SupO+q zlttO8C7H3EEzz`rI)N;!1*y(J1={NJ%oHyq8ZvS+iffc7lGFjwHmlKRxBBPvZ{BcQ zL|jKl>+tNhf(y5_P4~U=|AdPwXyB8JiPNWO=}zTPp`u0LFssfXKP=R5oZMWB7V#=F zO_iQ~m;Ho)2B`BNSF#e9a%*(`3Q?pq4uy0~Y3Wz`;;jNZv!-_~XBG=sgLWnE5%DCq z@7W9%HZJ}ndK(1H109P3u_+?cfAzia4qqV?K|MjHT`A6a_|`M$F2m6lUu?Jyn#)1T zyG)RF)u7p7UQBK1C$n>P2pZFM#1PBJwg}Kg^j*kDgAqFSq%*W;Hfb|(mMT;R6`=xO zs$edM203Gh8qj>#6S@Kw%+)nIC6%}hRK8{2kmzz!u9l}@XqMvtpLSUfuG_iX=1UOF4-{b#J{)UyVa`# z)dA8mcOR*<7EevB4ctOP5-do)0^X}=rQ0%F>$qKAM$jpyDFDj(HpAk~Az!fpb8#c? zJa*JxoLTP^WE11r?%#%H8kO|^S~%9M4jMZ?PQvd~OR?e>2vV$f!Tjy^l4Uh8JZ21x zjY``8f`I)g`WF9Tvyvj0iT7H>mb2KAPS1SpR?+FvPt=8RhL^8w9#v(O zEf>d{8#Chhx$dSLL39>~ElNpItJWU%6O}vRKiS#n*xI|=Apz<|PVVw47|VI$)sz-0 z!Y};q+NmxPC?v#blg%FuMI`q>YktX2fXxON3$0iY$chREjrYdh-e+)z;Ob=4X-Jw# zZc8zuGPNXJx8NCt;Q%4wE9-AbZqUh>k7h)$Pf~+Ug>Cs<2{MzLVqsw5si)W!8RBKn ztt=q7GN`A*YBZGU54;y*ifuhy_k23^Pl186`5zN%Yl$(CnHCA9Ur#8uZf(B?8M)7H z(cBQ)$M3Cw*TrpjZt3nv0fyjUp0AbVERInwT<_n;19gWWNzw?Xt|2l+1@{wo{*MAA zq_MU9s3tht`obu5nyvRwy(#Ki?YUX(>n_N1KUL9`_6+&qBR{w{MvXMCfi_7SF`2wr z{d7r1OVW5h1JB1?*~EwPgSK_Mw#Nx~I(m9!bAJBAgMU_V-e_wdtC1To*&=CN-HhY+ z;0?n#4FBFYi*(GevH@vKp!$Dp9%~+UTx-}yKCHV-I^p#10}3T2VJaX_qKh|R4sO|G zi*LM`Ue=F1Mnk7JN#~u|wL=0M{4?K_oAko%2RsP5DSR$b-k*vNd*%N%dmn18u~Iqo z38`#=apnWtEF&v^meu7m<(lo?))PElG9zE*8|$!-d&-f5@$LvfXWwIQ-JJB>5~q(ZW7K>#N~nlVeO8ID&4L1@T7z14Jd=#Hvn zG~|eH0M?0%-0gN#OmvnSLt4u0@@_uZiMd8eHrIX^k%NPy(JI{W*6(gR^U9_O@X*Yt z&E(7$FQZf_0iB~PjEs!=6qN4IV{pLf8+gkhC@yZx^?R?2dKr|eP?`gvG^$y1YX&c2 zU{-eL{>EK23#__K1x9Xz7uY0q_%3=L87_K6cD4=2%|AD{L9HEa6Zgt^&U>CYYQNCc z;X%0d>+u_Unj@VR`yT!_T++U7hJLJc976%lRICMn<#X8-reY^Eeca6>u2k1y{X-+^ zm?u}Izfj(St9gi5|BhFc%-*mHP#oYic3I;g)^mNKQ=Y_2z{^zA(1C5$I5IgL|D{I{ zw>Q$ZmNsGSQTy0Ww1DZn8E}iW47#xJXBbYVu(f4$PGupTz0UbT^QV-c|IdfAt&3~G z&agZA26Dp{oj4$)^p=`V_KQZAP|VLx&=kO#38vhCEBXMmH_}a={0#ueTA=g_;EXDR zwhWHn$)crFh?UklHhV?u3hCsg(+hP->TKI>p^J`5lS>M0Ev6`aiC9y0YvhXD3Sx(7N!k!%eW=9)s2xxy63?#Ab@1bxW5TP)&Q)j zU|$Y|@{ABNSx&HnCVc^AT&cw6%CBGht4DCE$OuYoFoIBk#W}myoMsB z>~WF1mjD5a2+{~8VTH0a!=UU?RI_N~%Y!~}=TT9zI z{sOtP9b(rgSysO z!2%5DW4FQ0G<(0FqMA8yDkX6O$creN@*5P&^1&`Zn$7eTKd?N_fW8|7P1#C3B4tfQ zQQn1L>~;6S8n}&S{BBNW8x3WDpPQ6yk>Mc+XHCWNaux{&)z!+tVhT36jmV7l4HOM@ zvpFVwie&1LymeYln&5pp1kgm_3>|^!iaF%H`JB|}0m#ZmR|LDNT1qMj79_v0aN!J# zDIuM1MpF4ysl|9q&{To=rsgz4FmZnJbLd4_!4*fwi4ZjL?H?LzA*1F5LKRLR91C;? zaM7T;8lZjm`wDS4Mu0RqbXWAa*gj`=<`cLS>aJhmnE)Pu#bCsct%RVi6>}(4NQC@w z;veRs2mUF+G!J0Vl%FW_052wxIipBZd}f)wusgYg3`eK$Eu1aU(GNXk zU^A;hPFq3u+sDl$dyxgegMh8-ZXl79`?%F)oN+g5;+{lR$J5)D(ks$={a1fzwqOc? z>PL8;g)PQkUc@(Cit+>+w3d)Coo$_SJ3yPa-4O^9Bi^D5ypT2ytMT_l)QGaW&Bk*1 zCix|qW8TiXR~U1MlG8yS_F!9nk+Y#Y*LUx;XNrdx^Yr`=N2^xXHU~VA4pkZre^fid z)rMDoZ5Evx`yhF$i<+#~2SsAwD{EjUD0xq$+(0T9 zbo>`#l8q4qp;eR3)-x9@m76|q_wm?k?%SaH^N(4#5Dz&{Vqny=O;w-!3haladdzCJ zHM8iI7X1pRo@0IQ&$gbe+)5k(8_O&GQKa0%focjCUqj2k-k=c3HxbIoNm}-X12z$zEpo#_eM|q zBiYeT0RJbN_eZmFmgorX_v({Vn8BghtJ#k~-PV#^K7yMGY@_3;*9`0x6pfPL!eO6G z5_&E!1gW*_`s4rIKP>n-1)M!77?yOrWXUSqS!uVv!O!9?wDXI|JwMcC6(%b^Q$IAK zspT~3-?OL^BQ~s;-Rj>(#Sf=v+7nW<{Rr`lPb8h?Hu3~71l`tOWjHp$kxFawVHSQr z_O}r+l0sN0)!>uem{a4ov;ETd`s@FvUHYG!wBN~4;4nf|c^1G24#LRy93Jg#9|6EGQq5(0Rj8ZK(zY-#8h_N; z$9Qlyv?@F@?(!H25*qG^#n(|Z_#E{2?`%iY_pIn8n2Uiu&wpLT(}wdHp% zTP`Sj*K`%jZPinF!#LWqlYaZ2Uip^92|(NU7@5(4fS_nn^_0(#FmDgl33|h_{O@HhS78MT~sJC^Q8&9xK zU*ILsXdUrgL$z!jz)7cR@V`#(h}R?00~t%!FiR0DSj=6t!tdYATlKi74!n)mL$hF{ zQe-H%Pr^qAoi%olc>pr3viY>;wBKh=UkKlpSGbXn^2{1b$3+mC^-Ke;uv@qOm)mfA zS2^I6m9^7(-m`l|H}{b7t}MFibeiRnI@IO2`d^iUmaTf)rg!#eQ?OENa?^{UNC~p`%g(PZczus7;?cB;z4nHLP2}=0>{{oncfrkUPCamXLN;?O&E?W?yyC+Dd+b7 zepIPSO)YvoUqSJd6F-9eC&y7`PBGwD5*-GJd$XrqA~>L;Z(lKdV7u3M^I-os{xE*N zx=mCsmb65<{aQIRq<=Q3ue_G5wz3iils8bW!nH|P^$#1Pn;1Xj zQNc+~EmfbL$BA+O^ecM;&G4(u+Utlg zbXhkNDs5foPp}MItPpz5$BW-xUk-A6*H&xELf+5uV#X|;<9zAOGmOXtv=&k?E>+ojY zlVLjjVQ{~v+7I`=8P~}mPM$gzM-asdLbtU>1f5+Nq3OzNxYOX$5I%-q%~y*7E{v78 zfjh}W$Z*5RpK)91uuJV*qZslwKId)Jf=cR|Ydu1)3#?M!9r@u3v@|EEN=L}@6WyZF znfCc!B%h2V``=Q%rMj(kDgg3a@?Cyu6nuYFyN+LF+bfui*BCX!&jfJs@N~n4_^{LxfLg zW|f-J1VVVYv}Z@pDvw80cf6k~V?a#ntDsNwVb$R_-GA{unf>as&2_ld$UGvM+f9Uj z;3@fja2<7QD?zj_i07sO5B7IMzE`;+C<<*FKZK>WPCOH`}aF22)Dij-JPp<^%(Aq1Ru7ID#c$&?MAR@ zebk(Yn^KkJD#T-!Oq+F&8oWsEH1#Ri@`k!Kh9WAIBiQHS-3Em2KKSnSTR~FZi}?Ir zY5IRZxD$xyMvfZwHW}(umpCsgFP|ivY_6<*%Z4-B*e`LgJtn>*H@}u(ntu5b2w*&% zySdYd`RYXEf5DVBh}K_s1&dh)1-)`qP&x|_FWs;|Px%F9Gza|{MoGQD$w2vR;H#(p z1_FV!Iw#_}0pdi1L%Lo#<=(@)JAVK9%Z#F)DF#+Fu~c5zIc;G(QQ0UBWaOn^8i#aQ+@ zkwbd!5A#OO!@#X0o2ZV)T6s4N_Z#p z?d<-h9>KxWPVL1^{4ym}Ui1Q~*vF65c76}`V^`&~`whXdRYZC}mRTvb9y8ZDDLr9# zanYdvs*wa-$(vcS1^Xg797Lp&v>LQo{13Fj_rL!V4;rKotYQf~eIRsYj4N5E=i zojpBc?w~jENB({mA94JS+od`P>TB#tr=5I~xw(jwz=)9{siL#1pUEPaw%50w8GuR@ zU;TRBr)}TRqKnWA-_>%VBC*cYCzI?_CgAIcrbK5(e0-|V?N~VLjsLFkm+RNvenhI% z(H~hYNADQ_h>qHAC<<0qfRtZ$eP7`p0|o9+Ma(R?6plx^74duvCYI*(Blo)QQc`uY zkd>`@-N`*+huoAwPaKB6kT%L#nP=RL9aPBMYHy`=pLm3Zz6TbdXS>oqZZAia)BmE^ zcj7vI$8G#`vwXh<;GfdM$1MDllVbT)EYC^)m|tKU|qi>K@X8EwvvI17?AVN5YVQJ{UC!NgrzQ8xedox5a;a9Xt^^qxByI>xw%?@mUOdNX#&JYjF zV;e*loK)A_{raF?6C1(*uwKz8?8YmZ?X8KrdKH)1vONi>ND@ck>&aX;L>bV7;g|PL zcavCP3nW;TfyeDOUpP=Va@{{vZe8r45v^11vS3@&W!q-w=jY?l<4O&V9xzje+`y^N z7P=kHP@~9e@%xXBjwZpb`6MJHs>WI6hH>TPIkGq`*N7uwQBbgG?MS2y|9Q`E2bK6H69!Y{#KEe+O?(_)jAK3R{23^??239)5}Y%Oa~ZF;Sl< z2wz*fQ}kT)ntx?C={7ffTVU3H>G;u3IFY4?NlN^2%`PszxGv`}-4J~JS$+&wkGUe! z<2?)?K8=dtO!tkBQn(HkzVKAddrAVImI1GgbV0n<;tOR`(jU4b_{5_7o~qDx(mJq{ zXA<1{oWJclk@g(X=X&SN>%_+~-CBa#w_!zR-J>o<3w>_n+o>Xq-Orhg8=Ch+w0NsR zys|_l&rU6CXa7X6Em?TkJ-Ydd659!FyPwYPio;xNtdQQ;nV{l?RVB$y@PBRSD|DYf*o?>!qHmrB`}5W~utl7dgi`t@NiErm z_2Ty9IVXOwukGOf{}xWylD03xulw_wndCKxDp>S|WPVhN=u<2!9EN-L~CSk|X##72*$RkjQ1q|JWUIrdZ z{b?zB%5PqAyIw+NY|JDgkz5)5BJOv|(~4|w-dp2;U9X24lzreKo#mRwLN%plJWHC1 z0FLI0x?-|vTm7_*Syh$&U4Wo)>zk`-@UzbOX0Ngae$VU6W4@WGSZV?6_Ax3%!9?$e zEuS?)ucT@{Yv!JXJt}Q>;4N>jsqY2!iWCFrX;n-Id@jYAr{sx>akNt9s5ocsMB1cD z-)l}YKPbDGtK-N3Id6WV3~|jIEc^-chS1hZ7{REll42G?ft{Gqn{7Y17*Zs13KgM3 z6_ST^C`A2^XzMkYgCmOIvDNhqqFH-QU8zY{3^F& z$HJo;6xa8BQuh4zGcU=s99cXn>o^cJNj8$Txb6mQxc`LGJC z65)w}Ip zed?YZK$}7H^75)oB+7ggav=uA#%#^LihdawAZt#?wIyM;EKQ9fr*xb(UlleZ?h& z0;OgX0p4=jW;lq?w#l?{^SgnyBS?=Yq1IBzrPFkF(C|A#y_LOlay#-tpaP_%jgS>l zc2PBR{M5s-7zQ%&uAkRQrtG{ajgkx<_vo^4ZIBe0YmaE2Lv^UFMYhK+EU#xFhm~fQ zE)v#H^ZQ#&{=v?QYMONu91#A*$3AtCPIXHAiJY9=-NOUeT^gIs0s&3U#%}&T;UHe< zJR&t>B21|6KE0Ny2|j3fSYH;b(6m+oay$jgE%UXfBYv<6^%@aeEgSu_Kk?2^ptEne zpb8OVh}y8~r!`U~{fX?Ig@O)?;l?KsAtGCK?lCXRUb5{+xaava!P62|<=i8-Y{yo9 zDly~bDk6G}3^dbi9+G5$9yOk|Ss`@U081ZtMTJE1V}|V0Mp<{|@|YQW`uUA_^j))$ z1xkk;Dwq^j{nusp^IDqDHLa*Xh&3W%Y)} zkSZpYgdR&*!4ci&L@?;BZZ>Oqcu0=9QI3inuuWXBoQ{NGcZR-F00SS;F0QxvKmg2S zIPfC6D@w(61no$5h=z`18E_WIxPL9-B^Z>+CUd|Y1rt{aC`3GfJpqT=|l7_9l^re zqk*eOBw_zQ2H(FUHN)p4f;c=GBI5?ug+r3BA>A^gZ--8oWb4{a#t^F6$HAi-=v4wz zXtF6|L|9|!nY6;gAb1NSQuNGE1xyZzg0(Pmkm1vK$-y_H`)@Q)rEd-1%v_({H79nx z3#Q*dFM39#L%xpC(kt%hJ_%A33>nLQ-##1l`TnVU=4uM~MjFESlIL`~+n}2E>-R=G z5oxHujvgPojvZg_xYp|T)+S$5zieJj*@zci|I2fA_juw*L?fG5ZRGk3-!Vz7DEVc% z`U;nEX>E2p;*2~8XH)5?TtDT9U>*F=X-vM zYc|~Rhl`8peP&iKG^Qo^)ffDZdS_7myzDHYyP;1d*QK+s51A?E$QZxOA z#|Woum;jdQqOe8+t`#FL6TR<*^v-2nouUxK$fM!uJ+Xw-%vxl5pAO8T!cEAVKFSY; zH(fpXp8oSfxd0jo29lgO`=34lThpiEttWZZ5<7J1!lRWXnhKf}Bm)}~47{On`ty5y zStSzzKXGjx-+uev`6QDfuDG~eVp?H$UD6`DgvQEu$Fi(xO6F|(Ryb0C_^|AA!jaec zSY>_9ByT^qR-}6SxdUVfL(ks@%uTTOxGDLc z^Vr+F2^0zWWlRCcJNV_DOSjaHz6Zj@Y5H%bG+(I`#IXKV_FRoQ2AvgLY{$KU5{p9U zRkdns2fR%HZDY#OA81kEl(5nD#IyR!`ueat`DF9H5kR5j{Z23Hm8i;=@pBnj?*HdZ z$dk;MzV-ZqO`HTz-cZU%(04&&5`Do60?m#uz|UTsUr!V1(JB7$;IryAU2w7*AuB*A zUe9Xg({@h&(;bf&&A$>f{lTb(=nNP8-7Z_D)7xfYq~(R$EZsI#vovQ-!^Kb9e5S|E z0%!T7(P|UdnW~1km_b-6Rph_bfh}x%O^xapOFsiE5vn?#9Il!ju1h5CpfAF%;Ql;R zy?T8{#~=@bmbIMKJt)<5w*($1WdNIQO_$d&60fsldwVQO9=ni+Tva)~o&F2i9uoY9 zAvprrx%xC>?$+LGx!*`z$Z~zfE^24L!sw^$^z$Qj^%Op%n_HPnPyVN!2fTx~yCGpP zfcG%l?Ti=|X5{2=)z!+zl+{Q(qJPuZfGU-JJtgE&f<_z5m2`p)UpqI5iKyEySXk`f z;H70%UinkVzRTt-JJWjp68D{A9ML`TB29&i5J$3o%~S#vYISbzUx#7Kw&JfbS%j?Y zmCklX{G7rs}jqmrdx!8;JYe^wyJV$Ws~R^XjKwKYW(mcrsX0wX)>HK-~i!_ecCs%tb~C_B$K|v)0+fX$dJq7d&^3kdwTQH znh-@v4i$)S@{n8rIev+Y>0aNy90_SES@z45%Lq0nek6p?T179RLkWCrt)vFpMzC-F z9$7CMC-{GYE%@`A6tV$8yd6N%nebe8u3w);mX3&@0K8(q10=s5tgOw+@Kr9A+fV-e z%Lnrs{_HyG<~riX8>8*!A2JA)$Npw!lHsh0g^eAbK_TE;$VHCT;s3HfZorp z0V6x6D%*bt#7pcQKC=pncS;)6&$AQ5_BtcDfN)vhb+${|*)6rXz!~EDs03F!=%V_i zkJ2NgeZadr072dhZfq&Ssf3;GC$f=GKW#lCGhNCauAlg%(tHjpNN?DIhpdj*GS}?2oof8RZWo@Ox9RG{OPX)r!@nYw zo!f8FpW*dWH?k1de6P|oFNuH`6=rbGnw;ZE%Z$Z*eCn)>Rg-sSHG%u$OQ&V|D!m z*OF|iTa+4o+}A$a?#=oqx87=1(tEbWjAB^A-f5LNIJEGUY9VXq24_dT#zA>~UnZCc zf-VCcCJ^_~D*igfgrOL1BTDfh4qmOuW~7Pc#stuCE2dxGJVls!(-rOo4@SR?Y7IQG z=8ODaH`@Ex0AmwtKs-+?>FSCMcJaL}S-f1^=mx+S$mT6T=?{!nOnI~vFJB9ZiL&|lwcsm+2=rIlBs zW@ zIUXafFm6tUn7GU6xDu=5wbr0UsL2$W6f_xUfA;q^YLW>5i_!P`ytQ{5a)AO=e2*x1 zsEs$Li$b5Ch97@cRDzUaBE#f}fIbm}LnglBTAnrVfl>d5-A%|_T{1z5$df*K;#>Xt zrB?9azhol}WCZw*SY9!pr1#=*gjat6TWo9x$0+b;GW8S>VIqkt6o-L&@_ODoa&yd0 zR|o3Nn#GsrEthp5XgUl_d{+fD(GcA#s09 z8^b7Y*ByGaHH=37a{CISyq?%gRg?=3+NyF<0?^mc)x1d%_B@ZzskQp`V zkPPRt;r}i4_2LEPNj~&-Sx7?S=Bijn2B7mH?`TG}_2H1^@h+ZozQZgvVY!(=$ zDr+2!m#syK-^ExQ)yiAcTW8p?=>lUB$b(#+>-d&9CH7_)k(CbIZ0r;$pIAH8j=8q9 zZ>_4VYUIelF$1uRbQ@kAruE%SdOII~zFpZ@&IQwx%Fs=`p+=M=PAQe%r7E{~5WhP% z*?hgLYE@NT%p`xWes?NhRyFQ{k;N4EO@)D+f@0U70$7Fo4H(qxd$=%nQpO)sIB^SZ z+n+cgIkF`({xO4FX#Rop9R!Vti0J9^^&TPQiSsqCvIeYhY+tm5PO9VCBn&ZpG#0RH zlhZ+WM11aq6m&CU5Q$APRMY^9$vCe9?}&Pkh7wK`MG7sqoK;c@UqSrLZSdG0cVzjN z_bF-Qr--pk1wE;C9n@Sys4~qE*N8j$rvK6VR(1`Lj6a7)L+T&+#&lH;_tzJMT{=nT zYyc}mmw-C82Z8%Fk^UjeCi6D^tL>K9??fm64NrppzixBBb?t*VKaqEeg# z?}b~v6ZgDmeCqjDS){wL=EG+NfnGxrRSiu+zHfFlwGovZICc;280{4*difG!)*s&E z`itw!=7JQV7*^)J6Mg~i6H~rsJ7*pJ5ik_dV2?4&E{2qMyL8m(2sHij#4+Y*@P2tEx=(EV+agv zb)Gu-OHgN>0^-dZOGYu}GH?=x)H*VEQvZ2$L&YeC#(=sey+pkvMCp#VjK=UOwbALTW{Yskb~N6$4Z zlR}YauB|NPFq$hSPnIz!O$K2!6SUTk8m|8hQie+jTf&Q>&J!MWFOhJw_m)n-=>+S~ zAJZq^<1r6>aUqi2>Qq=vm*G}2_=E9)MovM_MWGh5I@ItRQR@xH zi8u`@s9_=uVh*1__y+QGTQP|vzLWy{@Us62dU18}a%N`5i?Je+Lj^aBU42Tpr3IYI zZU@<$1^vgr*5mvCuiNwWRRIkI!$lG2=Ra;Pw#Tr6x#djT0MIUP{;~7T;DR0X( zfX@Me+BC0}lxevNgBZWPl0k)Nupt+zI@6!5kkB6v1y%$jGTIe#%;7NRe2XF&Ola++ zM%M2Q!SZoUaX(jCD~}Wxrj$q=gK`zi!ydhf4n?W#1u04nN5ap^;giRi8s3bJTP>BDV6ok|A08P4I)J zyPu$}|3>iifyeZsJQAei-~2Sa4yFOi zhJMnfFCp7QQzU0B(C;;N^A@5_QBGR)>r?OFs zw3$K2xna2*C{sJC5ksmN%DcX=HE=-rvLvy)yNfsLNlYg;7qa}t zNGD1I5u7OTJ{kNnzxW4!$18>JKvJ4c=L?LZ$T`eh6A`<%9u)-@D8tqfYX`^ zl_?>KPH|2Smo9k5#`Aj{6Ftc}=9MTmxqdkh5IoztRpso+Ql>b@&4T|KmL7uV8RQ|u zdER0??JkyDs)m+4H8`I+*ciJ+y8OjX!%8N(jd1yjSS`RD$zXAjnje#R122Zco!49t zv(-d1?SHiZB&JB2)`}8}ab<|h?rB4k#F9|EQ(Y+O#OkURN5hO8xggkm;AKZVoRTJL z=vMl0iqCuFlMaDYn2Rz8huTC!{vyK}h;m`)_wS@dk72-Lq_jACYZxoaiMB^f;CBa- zH(0un6RRxamMx4}M6HP5OB193q+5{|L*{7!ld5izWg=e#^SHJvnzw6yPdo8>O>E0M z*qC#B%za`rIavJV?%fYY92xQJgY4;(CQEaE?e5t)^B2K~eqBr@| zTvd%DU^i5f)^#3eV?tAP?94Tz`aYtO@B##%3P}OnAN+x!jD`X^WW-&iVVM@Fq9pxR zndu!*rXWK*_tl0wkCqLwB=+KQ#67j$9$bB^yQ>73lGsM*h~d1RUdeoYkXvaFD2TS) z4H|3#SL#J9zU-)94`d?Q2v7ifbkR+DJUrt@Zl>|FU%toY{4*}Vth4AvQ&$Gm86^g= z2{=xALEm?b#<3{RTTicMF!o$6z0XW*HEc0xXaWy;(ktmV^Hz8gkR@^JuLI#x^=BC2 z)~0w!++coV6XP8e+`>PC!kytu?8`(vzy!Z!81oFLC?ThZ2_NlDuVZ?3b3$@`5CKW0 z#6uJZ9!e^VHWv+$x&aY}oYvDEBdT;jq<9;^BAL=enTK8=+g4R&T8F!^$#^4 z?m&>mgM`}F->E>P2{u}pcuFhAE~*|KdB{fgQFww<+vwp{#^mxiV2XO}bwylKMvJ zODPj+Yh~UF!LT_F4I5iFlKqmK+cxw9(g_;DMpTLsM9&0-Eqq16f9|r`p8A-=T)s-t z`pu&#o7%@@Ftcx9h#~zn+@s;v-%f>0hzGKVd2IK;CU5ONO56kPDU_#3vsaNMt9ayv z<`PPMboiGmY)UQsgqQi;j@RbYLxbqXRCg0iB8nX9*L8KG%!7pfBRK_wd8#i=KU@0N zj~>T7HK0y=nG)E|{3hCbVV9CY=Z$T5Mjd~2uY)Up_T>;ftLOx`cj$%`a`c*{-$k4{ zymX$eg!CoP5gIlQ(|!MF&!sTeRn+#LLuEAJ)dGWRHH=!E$SBKPhQA zDnogT+1wY7=7$+`+7o~9jCq9gF_3tvx{Q%hh>Kcr#c7N?FPp02uoy4Xv+@h7{qSM| zav<|e@M6RUfMZipqNG-NS3jKVv;VNdM|>pn;Gss@|A(!&42rT1|Aqx=Y3c56K~lQA z8zcp!yL$<#ML~tjM(Qd+O;0bZ+mP6iF(bo(f z1$+JZ6)OAfDd#seO@hjdu3v$T(6yEeP+I|ILj85;m0EU>O; z?*0IhRYF+%P?Lf#=fEvx{BR{!IEBcz>cY?LjhunwaBXB~m z-?3S;j;6G6cZ@~G;}3r2NO#m9P09Q3-uzEK#YOqOf0A|z%N{Ldlr~^HV~KNV|1e?M zF~8=Ir^UUqv7b`vtcddAbFO9GQm9{k1?x}mKmD`Fu~}6^LciR9GlRuxxZl*&)RJN= z@GlfL?_9xFws!u!1x8v%M#k=(wmzY>vazFKjR6a{O=nL1*p8q1Y8tgbF7MG-z}Ko3wVs830Va?k}#k zya5%roo`K&xVsd$HQ$I42hl_M}PCX?js! zZP_gY|HhYB=J*qT-^i@oEtvcoS>HGWqWuQepT(I4!K`s98WPWGPPuPy$1l*#H2l$M zlhKOPf{q+NuCJ}dK0SR%)8>apPiyNVH`nk;hoj7RWrfcP*rrFW_RA5=Nm;XrtrsRp zeQ`OLpWu`pj-=5@RIrdl+t%C}FYxyKe)C=Z+VAMtk%QPV{lZ^Rt5-Pz;*`#6 ztG`|m_WNr0jutZa*Y*oOV!;ns{1ntO?b7dPI|FE{7+yhW>=%GtFoHFx&o6Mqx5iZj z(O=_OIuSp(k|nuPoJ}8z+RUS@-gF!8R}>C;RFulEX$p`@>}q|(GRSyStgJOctB!(J zP(F&1K!YhQ&0VbchDsu+54f%2hrj(5bh-Af&>WM*RO9T(H8i`oH`ti-bSaia9c?45 zbXKwKKocTwg-1a_bw2+T<1|NVTk38z)PIMlBRE!D(<&r7cq3C-HxZEQ>F)h!eO+8( zPyvmxrDG^Je7f73Z+{&suG9ri!yZsXc>+@8Q(d)p8nM)>-OGPLgFpnFwM*i3m@XTN z@!Ap3u+s);SF3)6|9YmL{i?*wDBqv3@eAo>~4Q3BoI2t$Zjt9FCHgX4Z_rYI6xw3qnyB9q+;owT*{#9ag zCO}AZVQ+UA_01{DZcR?u@TuqQA*ky4YGC>Bne2|yI=mDahU4I5N7Yg)#g>>tg@TMf zLMB#A&SxfARdHAGj+3_ec_0<@`z|ffQS~){uAA9IK2=j#{I7tIf;1^TFPdkuI@q$VqE+$*hb=hFWNQe zT>&h{GOd6(DN~Bs`-(X7c~xEj_5$t60B0M4$5!G$=#@xchoz zEkUgMT7VW7_qYA3u0o-AnG#%c5YhYedOUC3eL1=`S`1ZiFF-K6lvb&c?NF?COtNgBBCREWK2ZZe? zU63Al%S?mqz54t6k(K!Op;8CO(f4>=MJ!VCr%)Tjce3$=qswF36GETeFuV?*}IR$m!*Q=bCxz%_DGG5U8t7V z1|=S7fite#OVZ5L(;c$0zaIzu(LJ=0;S-;mj{_*3DR7YxI;rUx0j!olZp%MW zJB~q#6_l;phU#t!vN0Sa!9UJvEr_~nEUw%l~>rOM5D5zlvQZ%QrYM5Cn3J?A{VI|Rjg~WTis2QMtuTgGt z==Pav4=J0TgkYgWdPqX80w+w@?v{BSvZLojfL^x0)YB@a3DsXmv5TH80f)d!uP&unG!ToCDG zh7am4)bzm_;E-q5Xvdv+LSsReiT)cz3^Sm$nx2C*HxS}%Qml){dMXC)u2V4DA%Mh_ zbv!Jv2f?#fH|DBMniAI!D>d#;pTL^Z0A2+^AeIf@LF6inkR_pC-8OtcPe6XDgMIVB zO`EziJEoe6HK@Cv9$TehI|W+fupiOD0WhDm(aKd;A7djLJsUSiuT9U8xV5KHJ8m07D$W~A3(%d*Ht{vPg1kOi-rEtcc^h6_Xm zHcU=sMN`<(Jvho%jLOr?tIuY^jwgww600%ZlOuhzh}=w}%0c+U2S)5*P_v);sp)Uu zkp|Cf8k^G!c@BB@I#NC1cf!rZ{{*9WMml7_B}9 zr$3%uUM3hOR7lI+Z3b09$B!DXgyCk;lZ&U|uGNrG$p!LB@`OET(kzr=LM1_mK&~4| zR}bTj7CMztmFq?vUY6^zBoVdRZJnVM)a~%Y9O%Yprmxqnj{_Vjd}PBwSJ#{ zwl*abau7wVg@Mw`n>v-L724Ol%-#vT%ob?J_v=o#e4zoYT^MPghq zWK%H2y{FbQ1j>xradf-b^|W|*eDds)7kJ$I=Ahl6vgA_qIU8I*NBsV!6V1(V{PP#3 zHHnAk(4lpY;g{!@&cs)@<6VzklX0BSVDOWXJa$4v?VW2#QZv!x#>XdP`R5a^&u>Jf zBe>ixaeA|Rs$a?%*F@l4HlHB%lJ+#oVKaTi^&_j-YArv1{UPBF`}wAOZr!Yx5|;({ zlRTYW>;jJ>qA_Mxm^UiO^~;7uc(-c>Ww*T?WsQ zP!5!5N^GNbSHID9@{cPF{@G6KPutr?Q9&liwL#hC2h@b-E8Ia3m44Zcx4zCJ+0PRG#2@Lr+;;p|MSiI3v!|3*Kzmv9}C%gj|TIl zMS4H`E9*(koEQ?lQPT>Gt;@6Ro5Dtahw`=?0ID2i04PXnbXZ)~S9@Rk?aw5h ze~e1VYHdv9tU&&r3;U~khwkZM}hCF7csH1hEv|fz*dZ4K=A>9NNn5GCVkt>hH zPh9Ebk`%UFLVl@ z!)#|Ko6?urfscz7!6wRykS|ViEP=rXU-_fL-62g8-DIXlq`)9uC-m{`woO8k0u;2b z>IP2o757Q~d0d}+#ZvK(Z;wTtil@ZVtOo5MVv)7H!||~8lWNNYU=vHhw)_RiDRCB+ zr=_IL$CU6R>zj$SMCB-wrZ^R8(Gd-+sri=oHlaC1n{9v1x{G=Z{9v9M+HEoARmHnR zLWB)$A}EUp^W_T5_h=`QjE3~+a=)#?%T}%pGWLvx$R&)>>0);r)i6Sy@21RHs2oZ9 z?HBuvEC@;z8v&F>N~?p&b_iPBw6O&Gh80#oRyk6C+?kj3!rw4onaVku%A|kjh)Chs zyd|_QGARtSx_G7Mm8WNN#VyVP4FU{wKOD%6tu>8Qagl@^(ZBVOVmT{%osqzV5NXle zc6+QMUPaQ=T;cVr)1{r7b*LzisRlRIxg#a~K+%z*W46GYes5FoW6!t-eDhDeC8!C= z0HLc#TnRjINCK-nfYXuqECPT1sdj7$GAMtWX6t{~Y|f20FTnSKwkn!sGgYIynZYcK zKO!XEUANYaq1=mn+1S|8eZ2M$L{F~uRYhzb*<=@=O%4ZOVK3wW5L6516(;UE%m?%V zG7+q4Ns8#p1}aOEO}2QTU&n1LUf8Hg(o4u#ck7o=aJHcM3x-i9Zd_Q$6jAChsH5Y< zKD5NyB!%Tua>;HD0vrv|e~SAsDxeBj)Q#tH+2ruqE1(4qCJW>BIWQIh*)K^=8368M zr|=GF{%IYW58cG1m6oQos%AXC(o~bqV8`bzmDsO0u9igCKR~XW9bv|ojbM*tj}_|E zi&GeVhXS$0mn_8JaL;E$H++xmtfd*PIiId-1gQ75YWFlA3{9r?$nfMzD1X?-rSOjG zjaMa$35~aU*p4-*)zvVfp?Gl>zr)(I$5hH+Kt5az{?ERDptp@2#QvXZ6^T`*iHO8{ z^1U3Il&zH&`Nip#PV{GK2I>6@S<>)oe(yz(?fv&_%}vW^nSnUR7bf}7SjQ_LqIuMXXt2sFa8vP7&Ylm?3hwyE-fshee?x5?7 zDg)%N$Mx2hP7q$9aXXcqw@wPQcMeI-S!Z(~j)dU>(!gF$mvUboPS;7Cdr-l~>2A(U z)htsoR3QKJdvAw&Qrf6(VJlZq5r~jIt`#Y;?EB1`lwD^(Otn_?jEoH^f9Q3gkib2ZS@7Ytt`I|Ey zYs@I|qOh&{=iQ|=u)ZuOmmhqMBK2=9dl9)mk0m*y)yT4yupwSh6&GU{*JM*7s2%~dC?RkYyk=`jE%|` zqxIZ+0N(Kt9}rTp#4??q@BiaDNA|o3e#Rmry=ZxfalHt!=hrj91F<5QiugvB$HWGf z(=Z_+&WAfby-DV+oIaO$>d4=)_ zry+8d8}~EpdBRr^Ue?OQyL;a$$SJ<M@D;ghew=aywz@4HfKZ-b5aC#8@mM(l;ilCD)KSWV9n9_ zWvan^+^UbPsAubPt|!`A;1M!;z3>0b$Nw3Wr!f;AKS?iNr!f5ZDSCZ#1BBUzAxSx7C{Ar?fS~lMksEoG|#CSTIAVEj)L? zI4(uP;G|Z=_x)D=_Z7ycMp8?XhUVt}Ij=AbOgpg32snUr4>9c>RyoL-!u z0;u0fQv1-)illkc-@F|Nm#DNIPO%P%S)~@CSIO&cV*wqdGg!9hPv*bf2sF1i{qu?t z-3r&QV8`crAD_+Byi{8h9+#Ly(j5hTeuX@dJxL8rt)q`#WkDONJpY`nW0*>tdCO|a z;>rSTEPkX1#&1y&v@&_9N(}|q#&bmpY!mS(PXuMzuFq<7Wk$k;qUmC0KS$|e7yRH* znHFMDiO$I1PGLGiD&HronWZ1s(jcYq;y-tLqOF!oyYn#EZzcUf)0da(`E-if6?NWOLei zicA$+bDyg+y#@B=i~JWcjir0OX&Y6@tTprl5Z4`=%W%adxg4%UmzLl@ZGpMfA9rzw zfJ4;|_@t#t{BKU49(+j?<$*x3qCO<+AYzXc2Gg#PTm@8|*p%edBI^Z+9LX==6Doj7 zdc2r;ZSM8gc*ZCamvez6Cz%9G&~;@i`?*&_A&lV*BB(J5{Bf z@A=hYnzOV*B^^I^p|Eji;l7Q2z7n!Fs>vwV#2ZBCJN?AUN~=k$jZrZYKO?OOdPU2i ztdxeKDWzzQsjO^6=4NZMUgi6QUa$+r{>s7-SN-Lat1k{KBVe18s*S;`P_AuvzC z4`WroHhxfhw!0n<&TCGGR601vUX*9xdo(3oD`ENaS2>P-t{`p4V3A9m!=qNj|;> zKd>4B52{&9Rl2aAUV*OPdKE7f+a=6PElUPmzOcr&U zssW`w39_tILjRA&WPRTdYG20G`V&7YY*aDNDdbcTJ^Wc1z7qLBynJfyQ|sjE zBVyfQ$opMYQ`!CD+8I(7Xvl2Dg>l^eEYddP{Am=3 zb?q@sm}^wfcFf8|{@o1qnT$pvkZDw)i#9Ozms0z7vu%}}hst^81nWy7p)$%}z238_ zVPFc5yg6|vi6*fIjHeWolxKi*xi{#th+2-dAJ8#9{)Nf0ws;<|(mb}y;j-upsN&x~ zgg$Vezq*|RKVxbUoOV6kgyv;SQgd&Jym^87wi7d2qD_wPg1~WgP}%57nTXW?}$!uUGTXJLGit&!i_2g*L0>12w}d&TsoBF9L)U|93+NZdl1c@V|V9C2=8 zH{))6w(JX^Z0G)3Ne8Z1Eu$5acj{us$TaW+oqajgxvX$!S)I=iRPlZ3@|OF2a#V@? znS7f9`h{)u&~=k%dK6dEG2Vfo?z3l9%7_1b_4{wMg=Qj+)G7$seF2)Y?E&AiuHLZI zC&hO{5)xgpm5B~nadfWsWQm?hG$5fftv}Tqq?qqOV_)$>{QR6%`fsN57)Gt8IT+9$ z7aS7w( z+hO)7LFY8}{zUz<*b`CEYqt3g&Nt_HGjh&lBvIn*SYz6zym+6q1~H;zkp0RqN~f;z z*=2PFNc|0YXyn#T$1O1z<2sL?NsS0uZKLdESv&MPPNiCmE)5rp$rfa?*~<*PIra>g zD?~)2H>_p@tWwH}ydRR1Bo}q^LUxo!Dhl6aT~++}$$8Lj-P#1IKsoJ6xymq_mQhyH zX|7s|6Vk^-eU0mOagVhV|8APU^k6KiprC*ah9o6jo6(SIKoCWrK%;)v<0c{V320pW z3Y0S;dFxnIGsNL@^Uq$DB(s2MFl9Dad=Y{h2varmne4AwkEm(A@qr*3rWCkrkjc!=)%CO<#^*n>U|3xns!npbG3l zX$NO+-&A@D$Z5>U%LQU;ea!=Nal~H`0_MZ4miee|@WQtaAHyDQJ`PT4|3zluzGY|B z>=FH$$ZO~bV9$!IKx|a;d(Wn$X`Nvch%X1#JxDvrD& zWj3lnjlwNdff1k0CUqIV67bvhmP^p?Gv-W8)aAn7Z2VB*SNv_C76rBcvO#4S?uC$o z3m3psh5rVKjcI*>0mBU;rV(jSRE^c_06b3va zZu&k^P<)|<5EY&rf+fl8xf5%(_*UGoR2pft7+i73zrx`&C<*=cDkQRo&YE;I>Q9o< z)D-3A6-2MfIF(2mMVA@T5UG_Ynb1g+Wm&6_0qir1*K+4Z&Q4O0tbj{ao7As2*VEoQ znT3uJPbdmELf)6(Hj#+Zp;m#63FPqm+-cZ?pW%&8jf)v=Qyj$k=RuaYQF4Z(&5vX> z=(t6boP&S;3rpc|Q3svxDY2l;%*kjAf$?a52$LFJ)gH?^;l343zmb|w1}3U?D2Lv5 z$<*W<=ea?c3H$&t7aUzvK~{}r=E!bJ_ zYcke(PpD^NCVwqo-?txqW-rN2t_kBLQd)jbk(*a%SUWEvLWh<{tytmFR3l~B^lqu+ zB{`%EjEiqafiGp22B>q3r6E2{W9kz;klt9LGKy&_5|$Jmx;RAjB<%St^~{8rL-Tog z!H|Gj}e@vrY+eVD66 z&OP$`^%B-l#X85n54EjVpI>&)Oh8F!0lMSm?ccgc_{2ZktNy^BcKU7q?`$Mj6kr95 z&tD@+;f6&*oE;YM9Wepjb^<-sG4;FUygJ_}vZ89%4C{$UaPc`)@|`S@(HynKF2ASmLP%o?I%w)t(xHm5IK0+1_(VTN&Hz!^pgNpA!aP& zO-0Yf?#KP_i;Ex9D2+=h^ho>_eXR^#! zapEYCTG}siVZf{n=C*Aea)^5!lvsBaVF%N0OV2%`g(WN~y>X2}BcR(xpyAU?_2L&{K7NAUbG7WDc_FaeapD^c&y| zN9%O%N!;D|Z@AwQce#yA+-BUkX(eDtn*6#WdCXY7$xl`P@n-E~2-)+U#xuXf-ItGB z8c)N_uY@u=-TAh`!AGzQENW#-?32zA+I`nCFnK3v?33M^g|A%?FwR~M4S+77kfV2x zlQ+Srsd*l zNeVPY8Q-5(aXwB7r!d+%SQ=^QGae1dEfTdCm4V&mb?|`r-#Cz;^nED|W4S&kc;$ey z;N?Y$WT{LNt^4icZs?Mi2U7Rh4yZOknKj;2*YG7^!EBXMSQ z;M?4CQldcZ3~X@#ZpW;QfN){PXAI6hf(U5|R79WqT+u)qhcDu&$yPiBBZvYg9NrWh zaTvo?AqegyuQ=O|qaSYC=w#|h#QjSA>nd)T;gC=9dWjT2P zyzENS+_#1*Bp4OYHM0}4lnnMBo~`Fd)UaaM0bW#!x&c~!yBpK}mFodTWOp*Z+N7~H zXPTT`p0Af0LgD6IbtQumP}6H2`Vv;UYgj9~j}g$3R6YD&ZHCvxKH=;{Bm24`#jS&@ z-dPRSq-d8+2Q|IXN28_(3cVd;b=~Ikv#$e(lz%kKp>+pzbb2{{w&oI#1P!ExUcMv4 z4#S@zG)h(hkqOY6@3||s!Z+A({zOf{-dN1#sDHQbp{4<3Jgp~-O&D=yys~%X@_NO+ zGXa0Mpl;n{6{ymX$w_J(Jc(i^=#^OFKn5NE+Ao8-5c+8v4=GMDE`CX>d?9JFABm2R zh<7>4?Q=8ors0I=NQ11$z0>C9CsO%gvLF?MYn{24P7&%1(oC=2B&F{ha^JrKFJc3D^9Zqh-ZS% zO&T>_KedMIUjCOHaGUx0s18C)q1M4tOX<8E?yV?YjKA{az@ZHiiXynBImzl>rArHGkMc0;p&D_%2J)g8My=@}07 zX0U>0c@MlwXXCiSUw<>9HAT(>Wo5uZ6ggEVu*|4z^{En(^mFuH7>|;>w}P|CNDVC! z{!ap>tirSnfJd%yvTrVRaIAm=li@}DTd{))kj~92XV$`Rwi&e+?F4vL{B`c1n@biv zUX>Fh`?7Huge`sAI`P8fYaWoue}vbEU|0FpMa(A`D7--oeU2}To%I-I4m~6GJ3m__ zhAEKPedo3_tlYbK=yOn(pg3FdJdrXnto8t1K&2?;o7B+tXCRyw?mhX$6>~T2f^sr5 zq;m%mz;>F#aFOJS3ap#XShXG3C?`+!C-Bj(4ffml{3j#88`Wo3|66zvm_Rm9RHCAb zPHKaHz5jR!lsN~l`cn)78z#v>f&y>XWvd1+>4}@qd+U=CfsqAVBy07g38QKvrxT~t zVp`*tsyRmQMw&10;sC_lzt@yNX@i9pGuTQl6}4C?f<$!XY%CRt7N``5qen4}23$VK zoXdqfblWSwMORYP6Zo-yXg}^HS}^1&eySio6ktAi(r;lYmYEFtkP}%^{^XWK5OOMy z)aQ=l?3spv9)VWfrMPb3sD_I~+|@3#A@u2ew)^G)7U0Yc?1Ts2ex<&{V@e&~M)(fD zBWAoerooVGVo&pNvZW7stPOtsdMyYcp7ybo`u3wyV?WOGWd1s8$S$L-d*9&8K5P;- z8sp<{cE-Qhq{4+f=TX0VZZL&-f5)ZBs~RDES9JH&5+-0|#cdI&BH{^@wPMQYd}dp8 z==;V_-??wbgEF44dS@q*pX!ZQWyurv?b>!U|9(3ddxsI#^N)RwR&IO9{7w9rQV*2@ z1PKhLrRr9cv=`WjUqm8*|5!j@=j58WS0P}Tb*|F&$o{yi@rX#bca|#g!v6TP_664g zDHoaGaYiEq$l>CX5QU?5Zf1X}J{i&PHhDPBc6pJgTMhhwOe0cO#0B{oZ!%U!Edsnj zUTuuHhSCg0;Fg;}AZPy77F}L+r!hyY#R~-h=1)e5w9+)caq4w+;szif*v?Nn>|O<{ z!m|qLasl&;DvzLte&jILF0SV^7*bY1J zJO4UXjJzpQLegg2km`YQ@C>|RbI+Obo@@fD_$(>J0{j$H7<36u+p_AqKE55S8(Duk z=~7?ZHr$jm4GY3D3mjOPWWXeeAAb(7SZYpNDxIx_!Lr>-;0u4|zbV9rA< zyE1H&hV&I|9(;I~JqCXVwA-+Z;#YGDx{67ekye@GjWF8o*?&gklOteM{Ao{~IGZJe zHYML+zMaB$(H|T7dXEMT6OfMxsq-9%T^K1W-gzGh!YWH=DD@jr z>}V3DqkF}ba`5HQJ65ufmE-q<9=+0Sk)+n%a($~6;26!yFb|I6!6XF_0);q$qxPp) zBBAC%I&)q~+=9J}X@{~cX2-7y=Fq!$VnQYs#^~zxIq-I$28|^gyaLPF&q)(W=+mck z>0aaWQ(3-Z{$ulJc!7&B)(b+tjvhQaaYcpb2Z8Jyr%I*J9|hF#o6To+5rziBc{vEc<@Pxv33t&D9YSo*r+ zEJF^dsZM+1x&O<#IyuBfTQ_boLAg8rYo+6N()kB@9on2QpB@bP>$# z%J-8X)!n!M))ZL~OGwlQKzxk2=wC;Y)r%%GOMB2q>$;-cXw~#|GB}-`xufR!;~cWE zzeS-j*Dp+wNMu?xfy1e;2GYI}*Jm^$AIzuhdBsoJt4bW-5@=DkLu>$45*cH!xZW9W)7~n6FtWboA@p_sa`px6gD$y)3WJ- z_#~qdATw!+FF7{2xbhgx$a>~=<~6*|3a&z@Q}y4N@`+{Hev`@kAasV?8=q9P=r@X< zeWJc4aN7?00uW7#J%xaF@lG2K(lgwn7E?A@N* zDP?)JQmmRT$kKI54wCgPy#_^U@f4vD+a+?IJsd4I3*Za~EE0dNueqL9lBewZEO;y& z9Y_2QXE?U{&)Yncpq~Ls3{q*tHSseW-;N*BJf<<>zddWwEx+vTLf5j00cT{x3Vj1)?<%yU&_xvWDGwa*HWZ+ zw6;Tm^m4!t+i3@{5XOKyCn*4x~Al*%^+(IAAEU2z*;XomTHnro8R8BG$3DzvzysXO%MDpI8h||O|!fMU?NpIue62C7d zBqm%#uRU$fnElrqYjq6B;^kizoLe>}~Yc6vzIW|0iUdX>K7EX$QlI+r}f z38^6l!D+E@BY8x!NK^#VScvTL%=T1$T~nR}l{X@Uq)t?Im_WA@+3fqf5h`mmkfek? z?ratVIli$g+4GmsNA{p|L5Yc}L(thQGs`kjW|kIyy^{rn3=ym0?Cvb)W=(;Y427~= z)+qKW7I`PqRy?U?R#O6{It@9Jzg+(Rbsqm8j}@eZE3KK1HQwz7?Vs&90Daw9Tcfpu1L@FU z+(cQ)MS+zlpkpktul{s65?bVZ^VR&l;eOK~(67pk8Jm8FTErTf^rn)5z9)2)$xw@XEj{T zx($$gvV)sj@I?3a%G^JRD{)I9nJ=l%061UHg%#}DXCOD@V^11mqb_w(QVj!4B;5b z;{fs|PkO?^Pn5=xMystXUxa6rix-0~r)7#6(+AM_1pTVaI$5O!9HXPhCXSo~{(%{8 zh>Qf`m}q)vVX{_HjJUY?UzNjWqoFn2`7+VwLh3~XcxWOpS|_F0lchXWCK9{)u#`BK zSUlxvAK-V+iRAd?jHx?7)3<~A_wLXQyY2b5wsvzux-?pyVk0I+VZF(Uj9$5+SmBrB zYeLxW^(AS@z$ir${&_XH^zOuOLG-kQ;mce6?T6q^ngK@fIAI2wFIJ$`-I^jU^5RCc zz1ZI5kU4rmWapzl;U=2^p<|iQO7M4a?oFC2wk^xH*}!%{6fSlNk`jJFvn*@4L$Kh3 zLFko%PIl7A`)v((H#b>F{z`ADe-2GLW7L#Zx!@ZgfR9Ia$g)b1G34HIG|ut)H?H7u z(-x}c*Ni7`}(TS7o(kJKI2`~Cuc zuKy96s?R+ZcjauJA4}eG;0XcX#1xSiXIPb;J^g})JcI`w{LZg+9!p*>O_GTphS+L< z1#iB8*`_-$SyyaC_A9chX4e!MANS`C-zc{ zKcX;7Ns$KVYii84xKUp6 zji%#M12_KE6qHlml)&Ve(TTz3A?Z0{b_I&lywNxSr+8$f0`Ro&&GW+HD#f6}@>pw$ zFy8!XKt{MK)mfvMO6A(_j&op9Uyg?#-HYHr1WOLD0tiVa_jv#y?R$Wb$j%@2Yy;C=9R^63L|vGUfKoM`O*IJq#>X&=tRwI$kh zBzkv_bA9{GVEyFrPbeZAoqovT)h2?J0iPzi4ni-_C4T2O^NVGM4VPQ(N4p`T4VG7M zp}gv$QtOb@qSeulcimkBTF19064#*@tHCgZ-LU+}zWBp@ZqiSjtLN0A?9;c;MAg9w zP+Y|7D_h;c|5JNt+4}+$LInyUFj?ZW3_b?W*5WbY!D?~Jvzx(j-;xT$LNrntlFTI- z69@+0k9`uxIW|x&^Gr)HtbJ1zRS4=H8k8EuGi1-4&=-dapc!(iBqR;Nm@fl((Nt!_ zFem_PusL_Zk#bhRz}_(F09yJ5w&M>+#swq!RJ?fLic7{?a1kvx(oo_cU?`O}fH{aI zwQ(SptISejZ!dMr z#9xP86qq^yIUMgVmtu5HP5BUOZM%y@$X16$D@0#s7S_x|roMagHif@L++i076-e_q zKBhYG9tPOcITqE7LxSniSC|N&}@z=Y5l)G!FaiTL` z<9UPG-hj-SqN5J%lOkuHaz!5yN!6RnIr1qy1*@0Ey59VBf7DgefQL%xcqKU3{e&&@ z8I%ok)!bq4gtxuCd7hwt3T)r}Zs)f>o8b==%~wEt2b`|Ouc@OdoCj_GHkbmlS*r!>VjCa5-Tj2hVMj-@dCrid?GLt^ z30^#jGbX(8t$Gp;k9WUlzJL0e+wbz#8|+I6Z7ul%w7{9H>I$#Uk^qmD+iGvR&U^=` zrJYUUk3-);vqV;AYnr>%c?pufHMCgOTAb#`0^u@>LxmFX86sG|Xi3u%g0y5a`!G@H z6ZTg2y--A|zigz@Bz#FdtR`8Ge=zltP~g>$GK9mVSC6sPQxaIzG|`mxwCg&(;9Yll zX&7i5$)-f+xQ862jh*K2lHAa8uJLAiFc>iGIOl|uaFT?xCk)5a`JuGhD^Me`clD-&25nh(&En=AsEg83$8WG>D)r2NsHn(S3sWV zpyIV@y}1abLqmi@N{E?lo@jwfR9Rj?L~br+KqMx;al{bLvY7V)06d%JP#3CnRI&tZ z^kgGmc?HHZC;?B{-|F>QQD6VN3vPEG@iI>`Qc%dl=TSeQ!gpkdEa}KbIXt^qXvG`g z;9JMrAy`o6o_!c@9JEG@54!u-z;FhS1$}(-J>eWbF`OkHpC&Rnb<-MvBzA9t2ahZ! zt@%hA-py|eFKX0}z*q_lIp6q{1yY<$w0gp^<7XHr#LoDilm@z=Ua$PRc&WSjR1Ycj z_g_89?R5C#2(}Y1s|cu|iYp~u7(h{-;nlKQr;$_Uvg-d@!t(k|u8?5}u|QUffc2}@ z-2ic`qMH=~AYUb7A#r-`f|(fZl0{WfQCXp(mum@jR8@@r_CHzx^VM7IRzKK0mY{=8 z+Hv-kq6z%4@y0wb*fDt3*SurmPX`QE^YL!Uq{ zT8W^nEC#?<(zGw*5Q?TiV!4*p*5YjzM1XVteXQAR@258>?VjD)A72Cj710lgSjYG_ z-y}m$?s+E~6%`<)(LZm~tm#Hw1AI3IenjiKRC!6>>yB+4#j?wQiv{^*G+x*R?SY@e z_$U0fWpI9Z!!xe}M*C+IYD1r#_dg9kl9i%<5WoHkyN%?2qLTK@ab<~%*!KA1nIyOp z5DCPLyRZTG)$F6Vaqp#If-kt)F2m&DF0vDo)z963y(t~Cj_IbehYr1g!v>l1Q`ktGOT9A zFUY8Dc+VaLUq-unD?Z;zyj+JWzam48Ld><{m-U39Xw1xU=&P)lNw$5KVoBR2Da|V? zqD!|RmnuW%bbELHGC;^MX!S2;o!?UR_$ zs|@hIni6~n=ud_?yF<_(&QLP{sp_e|{2T%bckFS&?2EU5dbp zG>*K0eO~or$Qp6R2z+Fm6Tb@cChP#x1b=|FqwgLgAc-g?jp2WwTPq!JJI}v)CWHf> zj@U7#=6R{5Zazd0A+qN+AayCGk1|1>0=Ja0K}^%EP_)MzRn^++ahjN(bVyKBA6 z`|bDnl-7qNa53dOLS)E@mq-ZCGbdx}k5#X2wK8q_B8QvY0^oIy| zn!ZrE2Y=`lz>9LMM*dgun^8}%-+UUE4x@!b3vs8B(bi~Cb^{V8kNTr|XLlD!mI4|o zt6JWGFfjv=HS#-E^z>NPai=|et`Z`<@#3!#bIGyQllE}5v+6#Xq*v_|5-Bu0OtM)v zMsvgyjL$no&jGmI7{s(tZA~!bg8E_#92|R-FSg13_#0;$La3%gYcuHKtz=G;lvHMF zmV0))>^e!!xYQAteYX)YWj}K8F;KNINpXh1)UOfP;q9w^pN2Jr#l*IDPeIQ#OxmM- zOtK}~XeXA$w<+3I315EtFIt!lXFTsxO2bZfkAs62&v(1&(-LaG1n|PZcZeS7>w;x7_uT( z0!O@u_lBLBVy4OfTtO9w2~U7itk7ZT90Y_J%%*`vEX)*Kd45R5l^U|BIMr=MCbWN) z<+y@;iT*Te6|69;&krfMpp+*AB^er#5@>e=MW~KZ&F&PXYBUa8~-?ZD;HfB1`*M?MnKmO&Y=-D$*-{ zqQ5Wgh`dlFR!pNiA-s&w>D`oR(gw|G6{i%PWgVQ+)?77tD@fAeqtDkkE{JNEOtJ70 zI-=z?Q)nd7Ed;hLGyWy~88=(m9bl7%Tg8a>We$;%fenq!Zg2k|SOq>blQ3mL@!%_} zkxtxXmWUIsEB|=aeH&XFdc{cuBt#sMTnzv=vnP?57ABjHoHk~h*3fg@5&~e&`}0Yr zvA+H4n=eq90aTyxqHt~`C*UIHqj`l%JZ@xUavPB3PM?tDJC~2zr$pl>$Nqa-^buO* zCBqUH7MBOb3WxZ;Z~-sHgj0wTFAJJiQ|?xq#1;CdM)siH(;mM3j~9=3I>n&7$7JBq z6B+er?aAELG5-i7X)Ia&sC8sdTE^Tmd=b&o`Aotppl6f{kAP3Sjuk?hC6{cA;$Ox} zRr=?$es`fV=jevr6alTNpTk3BV6$^JFdgSIa!FSOD`e`v6Be@)qjV2)RGy4znD2Q% z>BD(Pvu*xDP{2v|yZe^ro|V*;dk0e?So+kIvvwo+f3fveQEj$iw=V8p+ykMwwRmyY z;$GYxic4{K0tJeDi+d#fj}iJfHtoQxAkMo4vObhu3+U>K}XZEW&!P zB4Qp7>!~ifhSwh+UdTp^N?nmee#_0wD(xq2KBJ2d}5-*wHR(jN4k3=u#h4l-|M0V2G0D^L!Q>3J%VqYPCeUQ?+c%wUncb7 z&$K|h&-`h^?BSfw0>PO*)nByNOftW-uG5g?lP9cs(KPU+^?yHHpQJ710C^%N%eibF z%a8E{;Pe9wI!6KHwzqQVd4*;`kO=t|bDmgl(IH!1J!sUt)nTM5&)7HMgPEDdr^nlf zQW=3&67P2@G=ciKrJBkZnEK63+XonX)W9+A-44QlId)nE`B8y5=SpRI{>|HQknvFV z6-n$KxtU&Wz(8=BUWr&Gp;H3oxz@}LtAD;!lt_>hsI-%x51==&5IQb}L^7*S&QQ9p zi}xrAw7ID0N-aue{jewI?Pg{ctE+D#r@0N8n&iR+@$BQbcl2x>Iu7{(n|Nv)!_thB zS{kh%yEaN|1K?klX#Q9+3PAlql7E>87qJjG_I!9h=|`Ppw(7r9vAtCy&pv3m>29Jl z=l6lxUEH;+vksZNA)k31CvNuFDkYt1>Ylj}H7K&k#Td|q_3iHRHyaN6?R#+fJc$Pa z|M?$YlquXd?+Qv4HP{wDb7rXstnwQ|(ksv+zt)W}NhExAbe!bo25z4;=Sq_Pne3C- z6=}^JIc~YTShd79#=PSDAP@VK_KtvXJ=%0XfnEOoozRc1nz5wOB z%#{IdL^0^oy$Opz2jtCE99cjJ-k`l`QJquE7%-HY3V9H`^DO)q{Jbpjpc~x%@loNw zIelhWg$twBiuX<&gC=Iyp53q4VFcOl@jMt_hnPi9Rm?f4I`{wsqwpCo>3KbtuRdbM zSZ6{XI0Ez_F8ZJhOLv|hp12ZAfVsrd|vb5TlKO1vpdLN+q~0_RLlqsT3w(=RqB-_qktPbu3P3O zfO>=R^X)S7&npk8+atz3{P)q#xofDt&O|P+j zV_(068RX;?eAf6pKBeh6gjX8!VKG&el@9w~#WGUqQ4^M_zmRMoS57A;h^NC5R(-&V zAE?N|sC54K5r7rm>2cfaiP>vmyGG6-!aG?ir0+36o(p$H$LaRq-GLmop1|B(2~Ai5St#T-9MB6W zaN+Mn*w3yf`zAZvLCMbPqCG1Z z)}`oR62}w2kOfwf56J+?frCCY$a8!D{)Ioc&`;o&;O=ZELaQ5dA@BxCCZw;()jsm# zKhvZ&1aajm>{mtVBK|!|d>ZC%*oHGdUa7zEDJUoi3f4>HqQsh9@GIi{_B!;DP4wi+ zVP)of54m}3JMLsuM1UD`>-IuC#Z|h@F2X~b7%2;bMpQ*9p|wRrpdBS_`s9`Sb`(8X z#XKnHfbGY`GYDH#zK%0rkI;Jt4*;P~Fb z_Jx)t@hg)*T%j7rPHYnBpkxk2TyG{Vw+{CGC=cuoA$3tzjzIm07BoQG#>;Aa<)xaC z3CMZ=JU-@$B72fg7=TcodWvc&7v`g@>JUd}iBk=*VZ&FNnmfO|#~s^?k1Q=04O!aw zCym9=<5JH4cBVM2W}f&Yd2_l@34RSkCQmBS1V;h^pD0$OqMtBPW`+*_-0(kp9^RCHG4{9p1_yz6DVL<9dj9f=O%%+ z=|DAZso88QlOvS#dLh*T+23g3wm*}leE);0=Ad;EI^ndk#~xIwDw{Zwri$}&FnrKb z%A`N2kx2>nNs7B9!6b@+x5hm0R0G9VERBB%kf+c;l~ne-Jg}Q6)7eF|n$A zCnuhP(+pZcISf$Iq;~KA;1MKZElLhyLd8Gr8Ti_}_b{43?DkGCmp@^UBqjzO;G@9( zZ(Vx+wQ_sDJby|g#6c7L&u-_-hf7VZN}e3>bI;SUbI?17S-tLVhuPG^$HW8BYEa(h z%?MeDi0vF7nhZ#cb-NyNj%zzT?Ai;60B)OI@ixU;qmjXX9DaaZB;94r~<)ZKDsuPrq8`Qeu zJzcd_dPuzh75XatYdB*!y26DJF}_Oy!o-(v)m-p)|JJ@%?q8@ff4?YW{aYXz){*@` zmN`JeZ*_7fQcVljvwp2`#OJfNBDv@dRvKW`_nx@E&QsI9j8hK^uW(RI&zrYZo2%K{ zp68EIuu`?<8T(zdU^OL}&Bs)U+iy|0e2nEn9CF`WxI5V$__#^;DXz)^VA{xJ2wo*1 zD$FqgzfyX``bFnVs*XA<5enp)qr+X+A(k>^eP0yp*ZTJ5N~-b|TFzT>n>S0>&aWM_ zE?PX!`ogP?x;!zk`I4nptWs})L_w}kb9Q``X%)+A_-E!k-<8DJnf#w00ZZ8VY=5V7 zmQ&prNwYHy*utfcB6=^M!3VX0sYN}I16VqPL5r2B`N3pT17OA`jWj3DJN7RxQyiT{ zmzFXD3P9O&fvMdH>r)fTm~bg6lkYYv>%bX`UhGVbS@Y+84go0)<96!GfoN86(6 z#qr821CI^r8a)z+9Cr_o!DCCQwO%)jL(F@CtXAOn9Iwsl^8Qajo!)z410I6D2`vF5^rv z_>oC(LghQL7UmPeSon{o7TkL3+wYgJQWX6o8E(*#b!=4GC8%Lj&vp`0=sSI>Xe$(8 zv8JA7nnrm2&)a`cb_6ghMwC14De4alzO(wLDD^Y+kUP1afCB*2w9#6*x&9Q_tI80D zVpPO|yuFpXaGDU;MMgvJvZ_Tq_#6fQ{|xoIdpI3evz-BxDV-O2K9RlqBoL|@r&9oq zd&qTJZ8G}IQaSQgCKDE9N`&Nf5apsNg)T-DS%6|Wz0W_0CPLok>8kztTm@*(r%1O!) z>V=oVYwyB9xr~P7!9CP2xoXtJ0VButgRXi%=J@*ID?zj}aSQ+bVgzK%Ae0Nyy@lG0 z|5CN!T8qYAZU@du#5ubi2`0Ty;T?pL8&U&~61Bu8oeU}us;>*~uRS3;8lQ2yVdVM5 z2HYBB)2As0^;x2UKCpuWa;7ZuWtlr%lTrsl`|?z+^kaesQnK_BBSz_gcD!hcm|>aB zYIZ>2tt_?b(-_kfA3I3^7>%O=Htrk15WADG$jaa@2WH zx8qUe1v`&ZM2(KB(uL7aBVt*haC!awqyND~mzoC7P?*fC1)u2#vc7FN@>TqSC- z_W$v8?gIC_qkFFr~g% zip}&DusyKe&-nOL_ETk2!Cr`5WrZ zp#J%5Vc%r8QjV?{_&XFg|Dz+fp-&;@l34K!d*_{}sZ6YDCLeF%jIWuQcb*~{#wpa% zH>{=_v2?&soVu%TMsgev72#6x(M)zG% z2r-blE+W_3H$7M?HROxSVY;Ls1VW4-5kwfQsao`d36tx1OtO5Op9k)fCx`dmj$GO^ zu(`h>kfj$lj>J_n_@+NrLkmKD8hRbX^S>w*Ie?2ZQWU>o7r0ZDCPqxQ;G zZ!yA0?SGzc66((XF3L?8jT>%d45YM5)q)%`i1&E z?8?*!r9Sxn1^l~!AMM>$!22rPq!arwEKdIP84Okh6g-D2ti5;PXBeB`1V~)wn@s8r zYqtnuU1&;YLL){&@W85y-Q{LG9h(F_>$zR{CcwD3;#%$*T>3Vh~iY(GLFa&^C#W$Gx|62;cy5qeF`W$-Mb z$RY!=BC(P!IgaP+ZR9*R#S7y0QZV+`{rpODQ(daj^eI(1j=hWD#SX=+z4%3AN=fSg z>iCZNh-3H0#YJM>(SFK5oFU}+U^)=;wh}i({i-7PE;G4wA*YGM4JVK6kJ}vI)x(p- zW%y6VQpDEFl&imt#l;LZon5b$9Ir(4z3!&y@;e}St_``4 zx#xbK(eph^I`76Dgn~b zwZOsz69tl-Zv8peUyx5eGdG_@jutVhF5s0U+Uo;ju@W2FY8=Xu@v?xFwAC|#IsMH< zg_86cCw%x<%|cE|tbE-nMc+_a;xHow?DLH)^KV5i&$#(Co#qbN2h$H$wMnn#ZxcDj zdE)xO8hWI~Mu)aCb6z!z=6qKlpls^!R!*1P22V@DbV>|+PR+4nwn57Pz}SQUI<9*Q z@b_}Fe>0imu%O1oe995&(eq#E&jxUbnj!^ML-u)DUbVyR$rY8~jv#eT7$^l|fzbrv zKq+=q-#fW^P6+TS=N;uVuYfg+tq}QJ>Z|>ZOw*j1Bub!0T|FU9zh2VAmPIn6YC@V- z-7->HdBt~vmKG{mQjS#FP*>_r;*Fepoq0a+R)fOCc-v+0;sSEHH|78D*aVE|QWD2n z&Y%WBr4h>PnhiI*ZQ4Ho|LLz^hk-MS)?|@4@5VKp68QT?7Uv@;2k=S~qbKDDZoEWL zg+b$WRu@`M1>(J1f7f0`67YE|a8Dsl9E+61M_gW^%K*01l)r1+7t6wQ!S~3Io4t2P zh0njfvNnMkY>r5&L>J!KUb0u6L~j`XE%?0!2xhH_w`n z?TCZ}I6)FCv#6S#$Bcudau|dXB!!9io}R=*x^I}T;TL@dD@T6$ZKk2JkTy#W7PXU^`&B;3YT z{c_4~gTaRs)fqMr%@sXLfkbEGUTQ++C3C`CK%Y4`%Cq&^_tv|32XAq07zkwZ7L!8B zvCYa{PYX4B%+rd${z#KDh^jZvuM{w7&LgRm1Uc_eo%2#?-B%d!XWExNp8DIt^;&x_ z5UY3 zRJDVKssx9pB4E@*y~1X&;)Y zLJ7O>-}Iu+i%kA{P1gmxjwBCb`KuILGUo`#+J<6C+Q<5Es9KNhJwMP5BDNuIsD%H-u&?-nzISjP z`TKT|$VMgv=>93W_AnD_dR2wgBYt?ZAEDqO&NB zfygR44eA1=or^x}_ne9^PdzgGq0o^_N$AIJA*>6q?9wYTsO+j2^ewF9_MT3x|6jrY z;OWt7c@=!t$3uOJJdT&uWD&um*RtCoRI+|i1|yERp;juMh?U8qfIt=((@%ubcu=-Z zCtGJjrVl(#H-smj4pu~6Ko!Ux#O--IK{8@5bx*&K`_EczqVsfuz|rm(fsnXZi3`#m znMzBtZKD8^iF7Rse;NurtrZsKL%~nD zk2b9z9z6(UR$mYex_Sd-z7L%~-cX45l`5o=CqH~BkSMKdm-_z4P+8Nu<@2yNr!pl9 zq@tEFnk+1nw|o`K`RQZ4s9jG-pOK1*jG<9Wbcu$wp?UN5jQdh?QK{70h2>E|XRSdk z5}T}y$w9VdT`uS9Ne(n3ea^}?pVsr!r-}X;{QD@gI|-oZz;q~Ru4NCt6bwmE3BFElWr|ugTB_NWMyxXQb`D^f^v*&de*67`6@v{Oab@{pjPXDZQ}3 z)8M30>mT#ip75YcH36G(^QG<4hbbY^AQBM2LxG0}6r`qIz)>$OBxJ5#4~)$=t>WEV z4Lv_~Z(J?#%FQUmI#s={7^$nTr?~ou6ZlD*08k?ux8cNC0oR(GfBetY zz1MTp$#}rbF5&)TQfkg%z+lCP%YV6UJk&dUYJ>TmZ9*dAk~_lV0W$71Cf^8=y5J{o z(P9J$`<-Rz4HEFf2t*ad>?W^1d*~V zQA9|DC6!Ly$Q0VGV;CQ-Q@6K&A;J`XHp>*X{5T~le{UR)vd1YdyX`z*v)zgXmLnQX zFcFQ(yBg84ppHc$!f`37T#W{+jl^d_|GF15(p#O@KRBTlL1DRm087ICx4ug%L_(T6&$ze7e^L0(4ucnOEYx;zD6?c^4t*_L>{g46k3Yb^UGP-0xRZg zEz%H$5#XJk;Ay*f&?23Ssp$~$?g^xVG5rhX_;7*q`{U{{S5%*EC+b$;Pi*Hl{IIGz zK$B>NGd>>=Xf8|^0aL6`~>vTtr|Tchb0p zxTRH2Ic0X5zkr@Ej*Xo7Rq!z|?>o3;?z*3^FZ~rL2#$$}pp82|Kl_X5`}cP-%fHU# z6G>fNU|qbiwH4lUC3+xcB_c-8Pce)>Oy0he4ot}O&7ODwP%cJogPIEWsa17yLbFQU zWc~L%6K%J58KG`n*SK|DWMC0J3%E#++`QiJcij`t!u{VOIaDwlNMo{Pr6uULKg48W zN(Z)RdclZLa4vWi(v4LWJ^>=PZs)$uJBre0%>Lt4X!U+hw1-D5<$InuAaauuTF$ye zC_Bpt39{#Eo-3Q@(gO!2lg+%ciBi;t$o@@q!Gwp-WLxx@ zrJY{W%-i$z-Q&?9^;CNpK)_#DoJSr$1)m{fx`gUTE)T@%oq{xJmhg1w_N)r!=LRr` zyO%rv_d5T7ItS*R4+@!sxFKObvLo-iY{ku{TZ+8+5XcfxC;e-ppwR;;(dkHgPO1#T zLaBdCfId*)vFVP#|-# z3y8DmZYf%%(y}gq@kmwLXFt%Nb?R(zzg%zwA_e5Cs*dH$oSTZE8{q4I=03Le4p7*T znRjNB;^Bdam3NCo)#2ScnH27)*5P~_S8rPY4fz9~Q;ZAf)CPsMp+uHNNw04g*jB-y zRm-kbca*+2P`6c% zQqIr~QNfA54C8z1j8P0@YFWVT!%_AYiG_lP552F+1e~!f!C7+;L#s%Rud(J9V>6AR zf zsWXK#9c%TXn8%c$x%Yt7F71_3haFqjHdAQmm6SACT9m(4Wq)&{8b5YS){0JYGpJXA zl=TS|OmvhvPzoI7KpnniF;ylj25?)(o1G#>N>gR#axT29!OsRu9Yh|?@RlA3cS{u> zEn~q1`=jG{TXegrZemCF>yF&t7wIN=A~L?x$_JVKW_PKft2v^KmG4o~&fu+SGtQV9 z5gi2QY#^Mv_w;W|4bd8N?s9n)3|O7d?6;Z{L`q_)5zwZTT_T=}3WWMv+&-3kS%s#F zH>|k=AU&8l@vDi>N%K>&A@cZ=qWx=wI^g!=iz?SZL4m1s5!mO;LZUoddSnzw0zc&? zL?FAY4gG4=>V%=h_<~AcG6Od3uMTiQ1Mi*I?{jk&f$GY!xqSb2L{;93%Grw0s7PbU zTuC)vnV6NLI~b-?-}UqQIKHZe0tZdh?+n9945-pm`pIB#sqvH`BO{#gmI|S91?_cn?Hr)km6ycIN4b2`5|_ z<9q9jE7EVjyr1&Fp4U&41}>xfy71y75x{giI6A6yJiB&{h9CGTz%T`7J^;H5Rj3^d z61kz#*OjX$W5oh2LqN}-)%$3ZjITbe3|uP6c=%th9#D;(B8iB*6MQeJc^DiR2Mw@@mLz^Q2v-EHvuJwmNk(9t(`bsmU_m$iKAw1q5v z>U4lq$z|?)OLlr}UA|Ip1V#`!0p*Merj`~V8A5w<(Lt+c=vNJ*Rw4d26CFM(g4n9&UNJ~=g>|~CNPXd zbJ`4mnhU84b$kE(XxO;yWq{pZ9Pc;XG?Yy<#E%k=e!5-pwUrcv``hD) z54N1#>3gcJOXAl1X~3hmEN(u?&#ukDRK$L9F_at=xKo9k z9(W%@tE(ZazABNC_pMgbf=hS{)tPnPi9?KsAN$jpJ)g~P;NS)5G5y@5Uh~5o{HB$V z+vrx_Rq>s2#uyGyL>1PtMTJrk`L7}ZE!}ty5?hTjF&1IMkC=|;yiyp|1X_k8mf_ge zamo!yS=vkH)IPF89c1;LYX?(*^|T|rZ~SkCD{+&jDlMHs)C5I`MS>+b$7 zcS8-@*jL`a$rCI#yVx+7<)+cz;cavrc|#_W&??QQRuD6K&#qq&qzlskn>{?h-o2ZD z8tj{0benu1Gzp&Kt+4&YuAz)-P{u%6$}6x18_oE3%6bFt_82e^`MG5YyES_ezaHCE z8`#_g^>-(l_Nvn|Q*)`je@{yw=k6hH6C9kZhh;2mdJoT~rlTfuQ2Z!0Gj3Q@@w@wh zG+j=OTViXhl?vFq1CHy!)mPnn5&wP|NTI78ekHUDvB6BZPuzCWkF$&_24!LqhQ)*7hSaZR@gGP* zAC~rJ83nB*F;Z^KR|1gper$!+{n2Mn>0^w-f8U}e+H&>r67&&66oX*1KOvQfNm992 ztQSMzQ@e3`L&z1jMn{Ap+Ftl8Gqx~KJQ7sFZ_6Ck1X_^>TIhaZ@A-y=GBWnT-#wh{ zQfW0(Z7Gtx2b38zN-B*qcXLLa!zaNJ5yY~wpZ`LQzMm~&XHUFNjAV{uSb^G#=ev?& zmMNuNroUzQQsO-j)KgX|0}$PAZUbxdoK)8!-!ksKMwdr{p?~Bj3mPLu%K5GQC7;0x zfBAyFeIXkm@@BS0Rc6>Gdt`||j^FVgPTF4Y^n)%GV02=-UCRiU)W_7(MdX#C_LoK^z3d77|hNNUZ z|6ju40E?6~x@HVeT7C8777`I*U?&19K)@On+)MXwOW!H-3{c>8rT(h5Fwwi33m2Ub zU?sGrI_Iz45nku`a6y$?-?%WthnVbpKBLUq<(WN3I8JOu<(@2r zg=e2(8$z7CW*sb5(=U8$A0l~f&=|Il7Kun$^bYBwr6>!ZrAb^}>>Ni+`J!exNPO?? z%+JX&e`@b{r)L%zS8NC#jd8}J{QaZX=j!1_9+z0a>gyu%N9Od-YLQOHX`*xe+!f6* zMQWjx?3NtoK{idAbudV{-)MZ32Q*>Xg~4@b@VVv@YxmE0<&shR@yy-(JV#dz=vJ-1 zy8CMmMW+cOt3|&>*Y62P^>JSBAz<>kEr-Shbl>yUH6HJ?3XXBk{S)WIm!)relm<~4 zpKhv2y)a2*acWKp_pB(})v*l>i)Irm@O*ChkXOUqNf?kKZA}FB8HPt<@^@$5^mhD` zDwRugq!|EHhwN9368B3mQ>{Z9oAk9-3#JEXxguiGD9k&VWtQc>VUcg`cVC*dP!_%1 zl36XL$Gm1soEr~qZNI$#>4AddD>tG#Nt3#F4JL9B@F?TM68U9pZqvBbsh)#Zuf8sz zKyW>|l=ueZ2tjrv5Iom-@x)j*W!4R^J5M?u^Tt<$`~!nELe{5}cvq=Pdrwv+k5v&;o2D?+mKWD)#a+sTd*f#O`HexIfo9TqTq@VdM=q5nc@v z)TvB_rBW&9^qV_y;eLxyE@r#7(Ix=#It=^F!T-x?q#3aPix~x`R8$I!i`(Acp=^?J zkZF9u+Sgv>*90p;GCqniCR+%NupaSimXYHy1o#ilSLw&jQvxPle{L%tdwVLS)w?7ryp>TlapJ@Yl!tj#uzkhn+8ftmGHhT#SkV}Db`5*sF|D~m|2&xds zVs#(}KA`Gd$Zo&{98MdD&GQ~RW-tunGG$V#EFxhpFhvr@uJ%@u@qD2~H{6?a)9MW7 zF)}m*pwu*RsC;WAoe>;EJNg7jbuhvR#D(58uAWXx)o7Oy=u`|rEqdUXt!kRr?-`=j zud?NH?LB3{ju0V*cnnTH%?uO*YyMf4Sw3c9sadBvGGSZYfY7g)r)!SXlA*O_vm}r4 z(C9KQ70*SqJK}rzf7POTi zM%{4VXco1zButML1}_j`fN*TJZ2vIZvBBYMYF^76$5?~;@PRc6!dp3+YC5NvSyAWE zB1M?2t(}YT`xhk*`YVVQmK_JJLK&0t5$89TRnl4#rJU$r(aO_&B-Og+0&leT6v zBVbPvI%?Z4N%%mU7)?!0-C$Y|NX1%CIK1rf{|U{ZjW}zK1x#2rF6nXoO}aIlBCDy9 zsf=dPD)Vnd42O-b99?rwtj7GkEn)dq72iCH`X=+I?b|=D@fjb-UCSaFCJYuWoc-uF zsxsc>jekb^5h(P@eJFs24WWdkOb$T1>1HVsCfh&;g!Z7=uSI;lGD&xo@Ym6-D3mR7 zdBo@VnANnmfV-L2BRF_62-^3KMV|>T29nG&0~YCLi)kxxZ00Fmr?O1k1WK&ls@SLM%~ z|EN}PR%9dHV7Xkk$@RT{Cw{&~cuO`F8?4-Gwa8N};86 z6sJ8s4`(Y!T6?YXMMY zU0tyY-|`F{-B#3YIZbDalij5gb1VF_wgu={9z|IJ3{r{$BQapvT|b|yc=cx^j5-|av2XD#F~7Y0G71YLQ^aRk^y ze#C#i4tRnN_X)Rko9pNTt>tJrRT0hAn#0$8pOydh5bWj1E|oW=3Y>&;Fo3|6NKD8! zCW(<)9s8MHiCFVkqYAf9(#bukIE}O7+~9z)Hk7pDm5`{8xw%`*6jcI=CNXtm!g9E* zTp5xzNuK{U`PiFCqzb&2C_zBmo~uqB=7HmBpl;4hr!_&v7oNK~+|p{{-%(*ILmlQO zEn;aagL0BCm@M3Wi_luxkPv1HHsqoSWW+sU`aw)hcl@^d+o(2A>n7{~Q>o4{^HtvM z2#?&Tmwaf#=Rxw}Z-qpa7;ZE%4}p2V%``H3sCR|z_Hm`%wjv((u3`ui{Kq2#ozNJw z)%96e4^loZRAWL2<_+uhzeDNONt9|>*i+NKz5%G;!W|Gx+<}iNwl0K5<~U_ah0sRp zxDsB^8+ptIhUAD&KBWyyEOiO*#92x!8S1~whOcmh2iZUDtub=4=S#4^PzQ*=IWN}oKp+1D?E9d`%zvra6(4VVv?7X%S)-s2IfL3#ne4;^CGO~h*eyfWa0z#)6ua7U;Rsv+S*CS3`GQpXY^#e{f{aYojR)17NS3v_!NRat`iw@!da3P6H)H zMqI+89WWqr;5Z2By_ND{z+ZAvZ$;HY4i%ZN4O%S~6?MQpGw7EPYjrg=P4;I8HSPV3 zvbm#zHg;LcnNWuEx1@4jeoY9-MtUvWJEv=D{b~mb?TJ<>f)|(Jy?t$eN3>$qhKS25 zPp>nsAvJF<=MvSGVGWx*k^{-CtbJBdqNRUh**Gn&L8 z1UnkIa0>)O6i!*9m~Jhc#LMS`EnTt==3zMsMcZWB75Sdn2YmSf%d1WM*5ejVUWD;; zd+Xi$^SfDwy?(l9p7GthEYpCv;NGbj*yfGr-LF?|*%PFXYwJ%mFM|r=|9PZ9ENH0n zj%o|+skDxBfVkx7nzEK3pwsjYp9q@m*-2ba0eI9^mKTQ8Z4BVF>P_Az@TZjn)XP@2 zYg|J1tC{b7|GNA5L~CuXt55zthvA3B0{71XsGx^KChuQ$eb1Q0!}%@B9lP}KgY}!u z@+?yeK5~HKqf6U+O>UTZ{)ejVzVAVz@3!}aQeEsC1)%%_tp4dEvfo|jcLHzTm2vu& zVLUeQ<4Q+fekRyDfz|WA_R@9U_d`GLz}OE-ByKRRr63cob&8D)H9)`=r}0>nESK4W znUaP%@z%*}GCqm!#K~G6&RP(H9g?Mr%jjn%HXyBloksD37XIK;*k^-r_-VxAG%ta` z+`a8%$vak`hra9vHY_C3llLq6Z=nu923xgtb%E$Y@d2uD6|HdbiFwWWgK-d@yNkgdGv7X4q-P7aj|QM>jJKnHYFop4rLbx2sW z8rBOSbAzNbo!gEs1iVjon>^bicGsRy;SV-|>tGWECWyy8{SWeRs7K0gs|0He81{1A9nJ zMpXyIkv2=*LZZR(EF^h_bq*)-gO+jVH9Vo)|5|wy2ICKEELzzJiO~9a3Po0^G$%RW zf*^=~bh0K>#6yiERnK*;Tbd23esVo1vdo1B;F>y`q{;G1-1OYe>F`HLxviovLyN7N z>zoo@?8mV%E;|e%7Aq8XcFk(_*3k(8)(+giP+UcdyVG^9u{LP{yMqA`u=q!{LInTFz?y5=(%4mkjR&Uj3|wo8PpgFqG#+=t~;a;vrAYs&Out?U;oVO zpYqW7b*ZtwNzfvM59OKWZMDjjLs*nG*vNxB?#%&I^(Y}r&Jcl6yM>9q{gJ&(l4Mg3 zH~ENoH9S7cG$=~H_la^viZZH^J)@`**P&oD%DS6Pxbq#Zm9m2BpSMj0=h0q@4zX6< z%TuJX1Fc6X=f|DvGH!g+h~H=Qp4!Y}XG*muqBZTYru5zl~)MwrquoGjm%e`pTyLFp`<8 z>+iYAOuuaAVdh5Ob~kl4KwBDO)S&Wh=wBf{?Z2BA!F(#_dJHyaf;6$lvBllGn7`JF z7TT|X%VI79;FGG4Kv?lRx9%tf*OC~RtGG;Y%F^5JY!G5ClLvskUK%)}6fN-W+NLo$ z6_o6(aB(tPorQ9`IN2{wkpA|0EN!%P(l~?{UgNJ-z{;sU)Ob+4eM!iG@Tn<5vJKc< zGC?PZeg4M)V4jtbSCJ+WvVcxj4=($%;El`0!)$lFFulmhu#e*h@*UqIcfz6OZ|>ej_&$jec#isV3iJ185(4rxad7@&NDzU?$~H;qW3tD&3%@Z5)^shrF^>L9bZDP=9$O~q*+}K zq_;tb2KR*+xV5%~@;oJgl<14o=QXp7nUvrR^smf`H$zv4IS~;N2#V#_T_Jtx>LR8= z=W?{a-z|3q$L70@VJ%Wt;a&wl{dF1I=A9CMIQHqBnw&KFsW01T8FHGM^6A(LXv6+v zua#vSpQf}ujcQd;z0Zn{Qt=+Q=PPpf;lH0G=xXIcb@-tfh1G5LX!oZr_WSpLFB?-n z;ZP|3sb;G0eP%0t#$dG&qW1Lj8;L;2A8AS~VF8r!O&kZe*cXq0B*dyr!(f{{W%xs< zPZEGrh3vr&g4`S0#8SMizUt%9ap{~}6e}~IKCMQqPYwzLYzI+M6!UJ=mseqC!=D*Y zacrF8GEgYO5)3iy`5%wDUka&js9zTCLP(>e1vLu5^1AtJ-~6A|q1zMy`nhdb-8PS>4P;3z;IHg(50m&wqWE-^Zb92rkH6HPh|T`ZX8Aqe@3lRErY<@6(e9>W#0LW5m$d)6 zT%&W3=N$tmG%UETZ%>{)lxpwEpX!-=pKqEd-LD2G3%Z`THp=W7 ztpBeL=l^YZ{%NwE?hZJ}8h!>ukdsr)LimOv;8QXK{bI(rjNsKpvf;?zR-1hidED3) zaR`6H5gEKD^d>0hpkO0yYvH&=C7Yl0>Gzm z9~nFb!r;Z@7&tjQIe=oOyKc8 z6@|z6-w35N)E4tbm#j0Yc{Z3+j(5~FNTah9qA27$IqHCc8L@~`!L@MVd%yGY(=dn* zp!~n>il`Ye;LuBaK#h&L+{!;!tc=l(^EN@(Z_>gb{L|k#)&Yco-XC&ubn&%4-Ii1N zXb6cur%;*KT<0zxZn*8gtF78#`E;4||Iqc7QBj6(pNa@5-8FOw($cLU-6<_dcXxL; zf^>t@-Ccv!&^7eX-5vY*-}CM{`|i76IPitT4A0!xef<(zrp{2I*FJ{bm_-?b4M;Lh zyiYtw@Y(gekBnE&#!MUjWN_Oo>9<$7o$;@3T_16qEyYdnj2zuWzNQPdVU!My7+$AC zhkhh0vU^Wa#Y|1mRMe$i)lg_XQ-p>UWL7l>%S6x&{7o1ojuJvB^^tx!WFUz{{L}X_ zMUj6+4Rpo{q~ahSCUCFjmY?It4=R`jeEhUWAakF9%D6dh9fR0 zMw*!OaY$93%{n%IE*ghQYBSqcU+vaC{FAZDae2smR$8o2JfR3^RE1r?(3njJQHkS~ zCl7EhA9BeWDlCC^S7S|^#$moUvpHXH+a#1~f|ueEke280VjIzjKiO9Ew4F{Dp~dlI z<$lxS$y1#q!{60VnFA_eBY?YT<(vBp^R*BZd0CD9%Pweye%4T~Q z0^kd0{N`B0xSnd7_2Wg~b~y2PbbHC$UbwRgorbs6KW=@0rUBwZIijm)9bH^{ z5*37^T?6RkF_mkXWk|hlJaOCsM62t}KK98AogPQ2j8~A?kSlwV;l6BE#%85$><2HH zC^XK0j|3E>$uy_a>=8DJX}VL);XM4*>gwkHESS-VWBw)MEA%Kf34ojdum}hjV6Oz0*Z)caS1FgTW6EB0CGNjL;MkBAr?c|MFZB8^s|KTKWRs$+?p4%#IZs)JIH z$yZfDNsK#=LJtd&b41@$#HG#`zYkeW{jDocdO}Zo3KzhkPZ2afAmGI9a#p0+T5)i+ zA327(q**`3;oaxo>a9(TziAw|(CooKm|C=l2Xe(|YISpZXrmKBd-%6v*#eP0r=^|u zr2^OUhJe6{{3|y)!kgpeR>Ue@io~5eJRDcHvE{eFwUsCfH_=~C(eI{)Ph`O?q9wQS=)kn=OhYezDC=xzo2jL@G>^s2u zMNm#M=ASd+`D0^Ia4Od$?NrZBCDR19llmB&K|?g?Cpl;n**b7Xwy~*0sH4N2@HQmt z$^U)|!cyguE!epOMn1*O@fZdWChlKEJrg0ojG>&TYPTiGBS;Zrc&_K~81o^^Euisu zWx)N*GErHr+w16RpvPePm6^8e)DPLU1*~985@YD(tbuPGlYY0h0#u!`tq`4#qIxAq zbyxQ1r$?Jt9}=8#KgZpWS_-JUmy{R?aWl?YQOUO66}D7pmTl*N?9A!EMC!VVS8Kev_hT4$~m8W zgq^lF{y_0yf)`r>dsYYzqy2|){CG(5N@|vr(i@cGZa{j#=K;?4FD+8bmmF&0v$@iz z*GEvv`mg(GJn_&L&Z$`xL{C*Uxn&NHS;bl0F=W8mop!^+n_8t+`6sH_Mx7Bagz;_j zU-Fd>^;!|>;8QH9hLs_=jf?`Tg4C>WG+WGoKdyn5#vhGY)LHd{@a@OV038Mous3yp zMZJjz3VlM7l(V#&W{?BVNkC$oxyDGc8A))~9NoH?Q1E09m4947jkR65=)o@_ON41; z)h%+t!oNGeHYlF~xV?G2QSmGohyGSs!~9@_=)?kUhJ&Voj~_(W7)VpoJ08=PVQ7yb zyJ{B=JHN@`hn82P^TL4p-o-}b>UQhu6B=+(ZKf8N$cV!z<|@c8h8QZx84&8Cfl_TW z^w=}`b6|%6vc6Ho2J^U)If`2{uGTiOUP270=nyguNeQ zfLm8wC0NhwfcV@;HUo(^(y@l;GU0<}1Qy(Zpt5CMM7&5ol~|gTKm?C;)rxg_m&N%Komw1vl(iMFnjLpOo^fLlZ<)bCW>q+Uo>g`;1?n`k*)2ezBjufZUm3k(R z1H5lM_>`Bq-49i)eW|ZD+pu|TyAi>SPAM5Mw6-^KNVyn6EV0OJ8$J0(x2`8|XK#-P zbW#|CP$GHSUg_{OjA?)js;36{!^>sboZVjIiCStWeM^5oWmG%9c3;-3Sj* za;zkMHp#$(-Jj6;bj{t3oG~-96WLY575TB_Zq!y8hfs>BwzE^Aa*k^FQw<}`?j)`@ z(sAWs<;Ky$W$acz`_3!eoMg6set7*F#6nctE)T#+QCs?D))*T)mLjU z+W8kUgKFTQjf$N~9eX^-?tg zsM5$?KfP%&re@aoK{2#C)tJy86dH`BDV{(L4O*|jKI{bJp`^cF9&>POze zFe+pMx~t`e6XpCFe_rdMmJ!-BGn`ZNCT-awXBcgd%<0($0#I7eH*?mp^~onbH?3al z$lurSfo3D1BSl+s`Q!$OW$Nhh5?Zy9am7yBxtnEL(*4?UvJAWOXpc6jIPlwJwADJEx|^V<@& zs#{QO*Odthyb9L|c($BWqD5 zBtijfs_OS_hWv4@M%lQ%%+be)AChUf0$0-%Q<0tisx>+(NDFIE8S_LHq|2KtnXSOC z@`KRv#;gC*OFX%7e%4Ni%?PkG1OVapZ9!fc69?3lZq zLrfBpDb0tQ@7us|Pxs~DT7A4PUJxcw#CfMlO0K0lH*MT+#YMG$HEu650cp7CMC*3Y z{FK_(PfiAt6`y{iAZq!MgQ-Y|-CVSO<@wp~3d>|_jqY*GwFBIpyYYt1Dsf3hj^t6_*|GiqHWnBpz&gU;!~n4EbOy2sH1i z(c+UbXqC|RHdu#+C+Fm`zUa;{m8ViU2gPvk!4-V&$E>d{o5Qu*-UGK|enX2T1o~=r z{_!LWT}2$xQZ)o07{%h(Gb9+ku#k|$lK2zp5o8WNm;U0RAJ?+^>=fjRwZOBDkDbs4 zMqGW+BlW$1cS^JluO$}SWW)c>bZ0j>)NwNfRaMt^XA6GlG(+ERPhXn*WUt*5e#Pbf z0o0u`^Lk^rb8fVpSUbn)UqKy^Jtp~%FG2Mxp>z(7{#*zV5fRAJ#HWA!IJx_k@~tFI+@~JTXf`%$7~6pT zQ#FIv%g;Hty@%Bz;fQ%*W*#A-&wH;pGBFFJx}W%O2+_cGYQ3)CJ>rWjUN<|(eq`FS z)sXrWI8#z!Wdb_>PLuHNV}iyahNTtByLTTaRpp|u3`kqc(&H@ry0n7rfj_oFg&Ws- zCMatI_4Wwp$uQQ=ISO7%gKf~Enj^Y7Qz za#Q14GG&HI5pcW9ep;bj%}6^UP92H~jPkt)FaR(_2~PMb6@Z^G8+3CV{B<9ryArog z&kB#tJ;T^hD0$uO9e!6;-0R2taewQ=ZXRUPbIK3l90Qs`q0};er%?X91+wqCeCIIl z6Z5IX_TUv_>eszJ)-lq972LBvWy|ch&@gx~rdSq561r!F94RZ-J+9mU%WJ;* z;w#!Zc)RCeT*cfech6_OnAe615csx`De>Cc4)en1`2leR1Z1XNMs6y1}~{ zaFZ<5&>Nz3UhsGJ77Ja`KR-fVGP3Vdvkmw%0p@*eO@CN{k2x<%gbv_*w!Ho&z$ggc z!2?L|ncK+f^U-Qv(B|zB1#s2Sc)%&Wvmj<;4*JntK@fW*l@Qeb!=C;}>x%lAOVLb8 z3F#im*hNMIGg&ygul7fn&fvufs8j^W=f>4H+mqD(&wu5QQ>9(`&oMDT{^He`yB7Q@VDUVVr(Q)EcLzC23rA>gU_^;E(|R| zFQ&HqAe07@N!;|tTv-}$EW^$S+&GGw1AmYlovhh4E&^qaHp6L%fv=?!#!qe|Tp!UY@b&H{)0o7h}OQsB*?HKR$7ufKW7a+pax#cg!t+S+f<9p~qSH|wuWSSR`|^d% zkfH%{60>*Q^gqlNVGH`gIIVT&CFyPIR(p$3B! z4W&yJEz3V9$l`%QHrU+S-%!ob#uzeU+@FrUNtar4%E_ZeA$HUT9?Ea=E8z|Fowxst z@~T-j|6<{7n}k(=z>4qzV5L6&Uy7NtjQD6DMByrA0|H$Qmwxb~qODM#EVXyvB^d*y zG@|lH8T~_!_OA!J^o_b1PT?#AFQ$;=DBHw;g&~eLe>1FdC%KIanklSQRr#JlE?k zFhXz0f$f9bdz0FCO{^zgPEL}#a;cR?bcN=!GKM|RNyE4z!FR^6mKN>?`t4CE5%WU24CAAwfUMKXjF_w@1&i+zwf60FlMS z(>fiRd|GM2DIVt4D%_>p8n^=A4oYOfPKPKiwla9exQ>rQm5NhfQT&o*KkScahjgt- z8oLYkxD-cimZMKG=7pTzwMt~PqIW*S{)R8F28GH4F^PP?M*f*G0oZ$mKkCn)15PQ2 zk^apn>alSxM;{@BX1ZpNtNVdMP(~3D)j}b$(7?2+QwR z1#xvVL@2kkeQ$=NJ-=JXmEpjJ78}%Ot(l*4@O-DhbPHhbFeg!KUpsvG06HYG-GDJo z?PWwpBIi-lN>fWpsFnX2B@&hL^$N?+b-{yv{E-@O#P&y8Di4RGU*ja;pv@fU;yXht z?N$W>p@MiYTKs@UYsVuqs` zX2w{~tH>)KY#LM%_{K72@+6ebb=;Yj0yez$qlVCVUiA4R`@@XP%=|j8^$a49zck8H zK`Cn_vvnGlaU%Jb1AiD$u!7GJY;)?-ra~$VgUPR7e{CGg3;w#h_Nubv{fUvrh{~L{ z9yOI*THl~#ASdHDfD2QY&;sxxO(5^*=`s-@JP)Sj{<;YuLAY}-K*;)<-)P*E?RHkQ z1$-{>Y?piziRWw-FCFC}fL$bNPvG--iI(HTwKWjaW@^d?=-iF#H88|5f#I%U37B5z z`F=z)eqeB@q29V5wKS3%f+;NZK-ZpU(|;cVBA}{H->{pH)YjyCH=zVDR+AWY%=nly zwC&orFXyJdXoWa0qd+)r0DghgKv|m7&nqs3blEDMvH)KBE`8P>ILSRLXz>0oEkOPD#s=jy5ScmaaeedV(HiOkMJ!X@ zjk{h6T?|^c8{TUvSRR%_>=I_&zeD8regP61lWct-ppUb*PqTP*&pU%}#3jn+gT%iQ znf_o@d^7yhn0)P(WRHlT$<23(s7htJ+rpQ-Mgpa?&L`k63KW4)Z@EIU{VW-TOxAbz zLo5x~jePYo`6G?ptPNFOX~_nA_8m(0%i|6($FiUIvbX>JeBv?J`U=Rl>m0%FIDOmk zd{xPwDer#2SA5s^L8u$(75d`y(CC|P>wTbYR(=P-dB#98n2$Ab&+~2U%dhWuKfkX7 zFCHkr`B&+-BmCkHR5*sietpw(4_5HKpL+aPnmTyMEF<)M7JG5f`FtR7v*h^sRX(7< zA$zDMqlysm1(Q8Zke&Stk5lkDPh9HoPX9-MK#>QvZQJ|*{o1+CXJP4+MkzI|GK z@ou{TT2Ay?=K~HEt;mGos#^`8dH@0p0NT#BSbS4=vVBSY0CQtB#QWIM>n!p+HN;Wq zaUC5H*nO+e$+gx_pk7ya-c-0P{C;0JD)spSTlfsy>)0_HrhDRnFHQfiqWeE^-jS_u zI`^tqVsW-l8jJUyOxw%T$tqkgF!x_W_@C^Y7G|L3Zqiei20{JMuGO)v=iO0=DEQ(3 z)gsqT#Y&^ge<*kgqLUg|5)sfoPbZv?F5{7B#$N#QJ>n%Vx@ z1OH4rj#3@oAU6eX$%IZS@R`A1Q&XAnUK1ucLDUV)bTsti5311sw-Z))eeASo; z4>S@e;q2cQ6|)D8?iRYg(zV_l*D1%Rmg@0by|Dp;L|?;!SIh>@SPLpFW3JI9C&9Pd z+?@b!?|$Q%g&JR3p7;H-2@?3qLUy=?Idu#l1iAr4pR=Msaz;sQ6?%F|i{1pw`$=lb zh_^}Pak8{3W5tR_?^SncNMb`lpb)o7;M!nk*LRg3YwvSLc@g}j3j1+Ag@8S)I)*l}`eY z5*0{+@=yGr&*T`Cl=!)rMBzHxZ@qFj(5#6sOZtFaE2O6>0ErLeq2__&VMZln1CQW< z`4b^D{GC5wDC@(K`gkP-dD1%J+&L89UTG~cTeN$KeVBV5_^nht_NVrG#S+3fM|zRI zdXhh)GE~!b#uW6{SWlUg(;upD{v}IY!2X^w-93C&N@KaR+drB!g3GQkNIs3d)rbIvEMooaKpXp@PHhKa@BscemlGdJKo@*9^GS4; zGdr>F!T~>(=lk4B$>Xu-iUZ$PxDyA%?aAuCHswis4^_3U{r!(SW7*ve!S4+3z`IUb zIAZ-X-@c3L3J&~HDc*BQ(bUy7etCW>E5Ff%&e5`jSe@9g6UhTg_UV$m&S}~x?|oW{ z5+WLuFFyJJBNqv)m><7n#a!7IKB#m6C8+xxOx_5Z{`diYw zMeHQwz-YPBDT6<)L0cZvVq)qXw|Zf-+X8bxzlITJL0@y23yDy%P-HOOC=U^BYZ&GB zwc*c~SwrU=g159Bml|gmqq2svdg%mxJ6RO`hdpL(ZPpji7O^gfL#@-P?aQgv^b{Gw z6-}Z>x0^IS&02kCWrXr3XrMAEzM&f5`0Vs;#TPfzc?xIw&^D!^X|ByjmA=^{PrY^b;iPhst*?wYPh2eSm?I zwQ<#j_~E9qww@h${kB;|DWq9DztR+C*yUByN_x;mfu<6L^E{~SR_V*R8c0|_BRX6Q zlV4lAth`)F4R?V$JrwUIq?M;ZZXpTC-*Rzr;c-0!>6^97X|799h-u{ncfm!JA5jw0`dgG%*K2>8 zKBSid;`>}aSYmR}Bi7K+zymN>fTtM%ih;NeSJxEz;$EN!g4by`F4dD*iYrS|4fjai z;qA~PVJ6{}Am-?Yf|8P5C%(hua_jLbo zL|%_eI$+WXzwYYrerSTl@HcIzS#ImLn?ka-RI=}JvUb=AP;LRHiDBikh}-_*sIj)b zzW?79K<}ny?re}M7T6MZ`2B=#yU~e)B4-^{+*~lnI(*jr5#4|(J5t`bGF17zUkT{B zd)MuJuv2L)P!CqUh8%QVJJQWfUhM#BieWb%?ag;Dy~2;Zz_=D{yU0B0bJjg>-XV2y zbzN9kNF`&5p!B(v@J-s7b%@zSCD2 zs0x^wnYly7kcD%eIC~IQXHUA3U6tRsN%v$nF|;?hXRaF;L1y~DzP#k)($X%Gt92VC zuoJu@TCA495i`?G=a?az+eBpp?eP=Q)|t1^9%Qc}k3qAHjTX{;CHV|DfP{g~I<jI^PRi79#G62|Xx)M9m_p!{?WlHZK>7c^x(}j8hZ8(Udoct;t8z6z-@wEL!|B z;?;atud6cm9*UcjGeUvXRS!z~xRZWgm^4)({RIS_ujsSacePE+HJ9y?L?VXZ!hiXi z;3nYgA=0{xaYwo=pRLDYz_Ie<)7S!(A^sdrjLPKsopd*llIbL>^C64K7B$&;!XmgY zS8892!>M)o?jkZTi2PMKV~An!4k4rKPvS&9q$+D9(N%KR12#alIAJETrqS2I=9k3L z{VQ*9Tx;WjS;Wi>0_*C2!g24%@4OY8Jd4{A*wNH!b0dW+>9{@tEj7gl#m7sGPP+IK zvu;`X&ep-dkK*vD61SIvO?5lR^jUL1ehMgLj%SgadYz~g0du?bAfdgB)2j?kK;ut; z6TnIpgPwqkTdp3;ic*2>5E=1~wnlE7z2R)LG?D-ZOr78f)l)J!n!&F0Bwg7i{ziP8Q42 z);5$i%3e1GsGaWcCT3)*RQU(e=yw!ZYLj;0Pe~K$%oW*u1WIF_3*$faURfulx%@&# z9YJvrJTYodO5hUyR`P`*I_bR({Cq=Kf&Z7GkQVxC>r=1vNGN`sT5rc21_9@NYPA`= z%Uz{?<#l(V#-(!|tGS*tCIpyuL5YUmk=SrVPS|24m$jIl#xI`iWcMDyTksw#^8Q$H|}1-UB8D#~8Ay;iFD8ad}IDDjIwhAn-RfXlnTgp1CX z0zU1}T~ya(PLRm3NrVLYsZRQGxo%R31liNK7#-(d#M#aymIvNIg1UR|h(Hld#lh53 zJ%$J?Y3yCcNoOEWO!NA{0gv}K=!1e#cR2Qk+a1qiL)Im>l|0kxc1KLGJyL)l2Qe|D z>)J2RAlSMFR|5k9%7BrxeDN~ua81Z_$X|@(f3a1xw>=x8fu$OJaBMufa5NjwbQ4B=pSiCEw&O@h${`H zmWrHUh554x^mTgPxyBn4f@8l!_NIz8G&R>Z#(2?4`1-=J@t{yBXlXta#&g?|dpe*L zY10S-i#khl=bDsnYw%5?CyO_Y4S{ z_X&geT-Pr7JRAY~&Y_x3Q{QXTGw*C*QM}6FbqwK9lh<485Q;^4f(wLMb4STwE3vEU3HDB?N=ME5{MX!G;^fqO6UN|*36 zO!yq2+Y)>_(Ys{y&arGd?zZo2k^~@?zl=cO^lo&%d#^n@I3PRJ_`Vk#szwE%BnuTmRW8v-hcnH z3ss8$h9f41)1;A=H}#2LjS2Utz*x45u4wMvJAqibs6U@Z_pE{j`t1eM7T3aF2aM;^ z6DJe|PtpvP{3%Uq`82<|BXmQQ<+A}?2Qa}*q`r^T>FF3Bs<`2xp%a5;mD1%HpQq?1 zX^k_sG%EC0{R0KAZ($%E)OV2qy)wFt5D8jrqx@eI&TU*~yrSa z56$fMBli}?zB{jJfU9oUMhE!@1C!vza zbu@9xScs&?=CcY+kPkA*sw!(O%=nOWzo95q4I`S4lZ|-_J@N(O!YMS(;hb^?Y@Sb& z+Z11NfQP+sW`8{b32d)a=q{MGGdjl^y}rguaQFiXHv8}nny!85IeUd;%%%H{2}6ql zzR$h~(BA7OnD&1@7XLOoOK&}%l~YDt|7kU)UWA)y&JiTCzyVSy8i>|`%F0+t_WeL0g*{eYkdbE-_@dIA^!$);EQ)Cuc-lwa1t@a`&&24QN&x7)%dN zH&Kg{-Z#fLWjnfzwgZ`VF#G=TyqVPbfwC$iUxo35)M-MCDCpeSa;|no4d&)$xzND> z(pd{umNwKxGaz7}XCM5gGC>fBPcN35fNuzs!+Br$);ZsfgpA*zn&eAXao-t&86u5! za?1k&iYuMN-#bU>*P}QWeoAwir~%xVlYF&6b=qnT)wgPz8_f-D1Wd>Vd(DB&LBUL* zp}a2&XUFwcvNue4J$Td3UnXM+57GW!pnz+e+|C$dv%G?Su6)!&-e~GKGVR;<2z99p zPKd~p(p>KR+DcY?T(6;dWPgMT2JDdn_k*w{*HwIiL%G44w63e_OurW8!^0TO@7f)DJVgL=iF)&u5ShEjI0jyt<(vQk@H=2N}xaoP3 zL=!heo_kUAD)&?%mSgm@$eO!JVj$PW0?+W?b@DuPp)eVBSw8ZwThz(h!x(XsKzUGJ zfxfXh?y&M9Di`2T2isSX1S_N39Kjxh-bZhVB;8usWSW|r2UC3`(>E`a01bGZ+;kB6 z0adZUXtT78WH%iLVo`i4bv*`|LInC7 zafj1WJM>-17+F|=pd(x5HRSKoem!|r&pnlL`@{1%5(Mn)#7>vON| z%fJmL1Cl?}n)S&Gdm1Awv-1wm=lltss^)dJ_sx-$Kc=0{tI*bz7>2?=7sk&@o4AcD z_g)>(gZW+nCc7?p@{H=UU;NDd40(aY0!)Tb&xB>n#X7n#!Rk#ju(xe*4X(aCtwM-b zZ^e(>Z}jx8O1_P1F4P`R0i&#VYP}ngEaL=CLr-rTxDaFrxF?V!0pUu8(-u=4ZKuI3 z@M}O8*j5A7COtbpmG|I5sM3AZ5|Au_$$T^B+K-(J%=vt+opm9ufbJ4SPgl3F!t&oH zrlKI&uf2M&uKw-Y4p|5@OVu~&(b2~RIVQ-(9b)FfMaJ@=iCbWix!Z1TXcc25|8bMy zGryQpoH3!A8XE|0&xy}1OCoD0$UsteZpq`I{1vbz!~^4eA4q+fx^qvxB7-PS*MfEb zr?F<1Yx_+J2OG=;DlMY_2#?{0Cr2YGfjwy-QO2nyC#e!EUrZrqX{2W8&RlV{<^iXz zF)f`dEvJ%h7g;32GkyRr105^>qY=7BRTU&zFWocv9F?^2yGb~G*fL{xJdq^r4;*8A|T4MUrUrzcNCPn<3~d99T+ z*?Lx})=ETuQ__4ynZy!dB~Ijhgn)$f6!D*+&+~BHlSbxZKN-fi3EU}^v?zayTW*_F zV`S|)TchaJmmv!%taB4V9sXE{VZdo)*`0sVU9o-9fv~ z;3$T}%cDyMaXj_1Omkp2k*RPzB-*@y0N?PiOj#M@ zIwD&B1oJ=J!LAc@$*s3mG67z3(>W~QhqtvA`}#U0hs{v(7usrhIm!Jn zL(*2zlqq5cFSow6pow$&@a#64m{I_$KQV=+X~fkiP^oozbhLi6SdgEaOW9yZ#z>&&Gu=xXj4Tj-fYt4JF|nyl=m3- z5l%(Q7FlCur6G*$yBc77S^QgWB@`BJpH9N{$5E*j+W~>^($CLOiXz)5{)_Al&(|_f zoQs(la(`F!(;au@r)(OFmZvBxU~BHAF-H>|wDzs7t-$BU9VF}n0>7(fN_l!fV<$M8 zn2v}{-&t7Z4aMM!p1kxTTfgO~`K-Urht>g}ZVJ(CtX3Y%Fty%}l0j&0qHHcp5~qg| zOIh=Uw94p?W$=MlpO$^|OK{w0F+!PT7#IW|n&%8!*BXBuT1QIpA!z57r4?*B-VO>S zG>wjOulBiiZWz1SgmrECKXeXC2;Zkz*~aoZxkWE$>Lz{KyW)^jk_$X}2=bT6lGD)B zqKJVT$K&U31swaWiL8Xhs%l?4SB(YaflDZ;T`#sx5>sT{q8>%$_7jLZImg1{k|P`{ z`-BH=7!}7rL8YkD4Lb0{XiEMJ#WU7r`^z5D9wE=q_HMt0B0R5IVbX%8=o_>~HqpV* zBec*a4lAOC(vGA~eY&J5USE5gP2l_5TT(6Vq(Z4(3p`b0 zsN8z|A4ZSSuA8>^4G#~GJ`tfvEi#cdy&wymB<}!M`5TpEw0N!YBUiVLX>4k#0J8hT zL#x#HY722+&)V|mZmkfSGr!RUP8dZran*%QP{R)IA~U=;=;ejZaJ03x9U%t}tCba& zTIF~R)>9Vsk_kcMu7E8Q02t*T!UW+UAXoQ7h04~TNmQ+XEi=V|-!b`NZxGS*eo~s( z$H@gERCL^1oaX@rDAP$m?^{TS{V3-gFy3q$c_vzt--M!jd;Z=@-P4|3$H5kD6(I$6Ij zCw@B#U^F9Lg|HJQnx8;ai~GRrriM`<7bxF|cx{7#Ll*o4ya1 z0>*riQW8pElT*=2HIw6u=mDHDvp6#)Ir&x7dI<6D(vFa+5WF1b-y*-o!x7+)1(1HL zYooS4?Ee7EE+>4cPrhZT{(Qi)iBSFzE*~}HNLwuf-YEe5unF6Ck2z=opwo-ZM1@J& z)y-~wRt3md7PgMaiC&BqeZ-IF=aH3C!Z%AbW$xjZR?5P_@>H&V5MhY;#V-k%hybEH z?L7K)vkLiVsCovH$br6U9;e;$#}GcK{gyka0fD^c?h0=B?!rata?bx}-AYx(=QLJN z7>?o~R@uhz2q>~5P!+Y(9#>7HOq^Gj!r`F%i(_kUxIoLs-)lCO03=+cs^*%`4hE3- zVFgG)EPtTqsf*}J9gb5-Et**?r)yazP#dtag|D^IRa^HPefkm>*G5O60MAgW>$Pf< zp@vi6aIoEcjw-#9n{&LGt(El<2DVE$rZ zndw)&XkijilfC0!hlLCsj<%<=WL#$h+F7HO1L#uovjr7W4He|FOG*^!7!B^()5WXn zn@5jVe*LBHcYH&ei23BxvqG0|j-$7Rg}~+!@v5E?8Fkb6OYsaXgqCi`&##EfvO?+y zX(`=%!w|{D8Wk)Mlq!a^xGxq+ZBrY*@@Q)baU@P1yxUq6~9 z^&#stG+OFZ7A)^8s`7fI?OHad| zc-Va|PK}jn3d`J-I(Bt~p{Ere$3Hcbz5#PZC#E>G@8|8j}Qx$us ztW+9O$7oiPCh>g5#_(`k_+MIp*}1uiWI3AdD-r==at3K5DgyLRiR3z(u(bgp0SJHt zC~i$s`_$j%W2%5%P1G%>oiaZDkz+B@G<@e7V|m@Czf#I~AkEonEBB(4ddfL}Dr0hl zGGnEgG6Eq)SS)bsYeG9I(53q4pI6d#+)axVOB#7WYM zCoKcu)_XiOC_jes@@#LE>g8JN`|d8%qa@z;`b%x(c?V6aiiIcS)Ca?UD0j$Wj=#US zxm+?g9zPcOl_odrfYBphT0WxXlV(cC(OyVu>otY0h?l@#Ja#^vsNlFiZ9XR8{hH?E z;_|P&zwZhR`9gp8T>qw!mH|F(7{0d;FTusxLJ;Lu zf*1v%=H6;UOO52wDTVA_ku#Z-TR`F0=xZADxBY&XB1^~-ZMf#_4RIm)=s*)dAk6`} z6asUcbMC2$MTVf&^y`+TXIYe#lx^qFfu_vB96V$M!6kF>%TeLKj7HVA$g_La1fl=Fvr!H*s>V&fNEM=#*X#% z`9_Q9js4}+aEDf1+`(f{n zo0z$p`sUunMWO$QQ|3C3>z6!F+Cf4NVJZqj#!;qoJ?MgfX+lj&o*V0Kx}@7)@NwMg z_b(&E8cG_7V?n|Iwzaf{rc(5#1R7E3xWHm=ZuO2t)c*f z)eh&`+1YAqWXRd>C0|+j_21zDpGFA+3AY#-^(3=DT{ZKID>TwSK*PBf)CRi_r>B@+ z!ba}y?nLsqNY87$!iW?2~y{}~7LnT~or&aH&8!ec(~3F|7nk+q0p-t-gBOxr3< zB?KYoj-uw2Q1{$OVa4VpwE>NOn}sai^#6FHm;;C1aS8w}bj*HO^7^Eqt({+C2?SQ! zgB;hoUhgkbCz_hiPMC2h@Ic0tFyOys6a!oa??0Rl26;Y&{Ciq~wpR&vAd$n8HfR9H zS37y3pNl^x$zhQ{Zzp`Ir2^P-aKsE;DrBQ!K+g*V5i&Bp41h|EGG42upHhLCbpQtr z%H8w*wVs{W=Vf=`#CLIHVZsNA<6?)u9BCp!3kCdLEz8UR*;2#t#yc5rWo2a>khJgu zY8Iw{@)uxeJpv3M>WMGVw0a<;cpT;rzyQvzZN|PUih;t*AD@L0PvAxat)8#VCr^y7g7Z51S zBMlcgU*u7ivbRldpMg8WcEmE8);+GtG-1;!#k}6@=0P8-7(+|`E-bW4GU(-1Sc>PT zT_+4LIPwpYuOBFUXBCXAFZgI-L?8b6N>eH@Ld_upX7&5PLz=cs%Bai5{j~@_QwzZG zQzs^=y~#q5z^Es${XCcRGv_yPn>1B@C>6YzUY^peUeEEEUnYr0&HMAV?i;4hvZWg% z&E^)tRdPjOXWgV}6a*?-Y(p&PR+)@WRuTQ$=0Cqnku_Gv$=%c8{MpC^S80)Yd0jO1 zqtGefC1OZ724{4yNhIlp6UykMz$Q-%4I_MI*6-lC+Ou*PqxU`-M<3CNm``y$du7_2 zkn{T>Ly%9~?IOxtM(@k0>~svj_O;_7O-ZC16Kc&|rYuS>j7$|8YbwsX_1{sn2tPms z3EL+T+X#qHsd{a#SK41+a>48)m>LM8uTKSnYiB7gb%%%Y4_6K!14~;| z)*C~Wp{FS^r<+7spWhYF!);35lR0wrC}U=FoVw!P(B!I7$4QK;iT^D=sY=U920wu# zT9#@=n7+eJKZHVqlV~;g-21RFtXvX_zuN$v&w}V@#LH3F0|<%c!aUd+TnQWO?!^(4 zpHgj#iG|ioL>u$;rtB#@sH>>YaM*1rs?7-4;ey%P_0U&uDnD~Td|Yj8^pblxzn3yh zcBF{d{CGZ*8L0eqz43fwc}?J-O|B-T7A^M*;tB{mq6XfyWa6d`5zN*onJuq1;l&tE zaNv4+@@EKnr}^0aEU@OwCV>`1uX!DA34oBs~mMnHUUyY>B!rsI+2`#Qin(7Ee5T$V6HwecsgD)`!B z|Ec~iQ&O7liqd%;w^58W&xSkC$uza0;A1;KtC0sSoVOkkWpg5lJM=Mz>pW=2DnBgc zmXmPmKkp+TlC5jf4d;DHyKGLFt}hsr#$xf)GHgZr0-~}Sj>9$zJZe3RLQsVz`~^5q zSqbZz=_KR7JWP^WLJbEwZ*ermcIP+c{FNgmpI$*EZaO&JY4SmK!WNs7Y}HD%*5 zT!U6>%3Qcj<4IW1`ib|9t0H*sA+EpoCv}*VCvwbG11mTatwc0aj1rS-ILuy(<+CZ% z^jJi`w9XkAt`dpqj-OoaRbK86x z4A;CnuZfc0*xuD6&hz^sRJNpkeZyDGC~#^GdR=WPpC($ zQwN(vSt?^R3l$<#;W#!+EXpJ-ocr!8CXxAWrGD7af2W{&mp2)jNy$1|Vyd9y6tGs}Cy@1R*>zqNOuws~iB+bmT%z zUr4W?m3I73=JIQx$&`L6b)v;~RfyDmGk))_h2xYQxBbns>jmHq!uA7V(GSx8sVFqF zQ->1&_GM%5>rV}V&ewmG)#C)&6XrkiP$7XDSao;Y0f?p=kcjk0 z;{Pd$0MLll%$vvKqocE|o3>DwR%;=0h3bWNJ&4X_)`Aq9Cn~$m^MBW3{O=*<-TJ;A zLr@pqRX3%pv^rRHx1}hwa;*E)9{mj6eqQcJ%b}X?n%qCsJ(#~OEFR&K-#S}A7S&jp z-E90>r#}^;lO~8#zOJmO>1gZw)^X1I-Sbx9<+0G#4(bXrRX(2ht}DVDQKIgapYXRJ z?~f~;C7?^IgA3t}Ld5Q{e`YJuF+lz;V`gD?2bU`+@w+f}!y-EOTM}mlvOOfXu_B!R zb#fuEFI)b^+O0mruL63cDv%-GZ>=wH)M(;|L|}?)@69k;is*oDh>+Tf?u$MrZ`IVG zy8MayZc%8A=9FbpA39}8iN3WnS>j*X<>OCK{v9bSf~XHgiP&~ll30@ENy)Y&yyeti zcJql+T9R+GAotJ49x_}~5*PD-B?y7uGZ&eV-ZVOR2tI(1&<&^<)fL%rh;ZEchgyp! z3Xx8JjIE9Dj6jOB{F$*taT#berK!2OuXd6!KsK(!}KzS zjPEG`HMJ5KZG&h}mw~G*@o>o2Ggd2(9Jnl29V)@&Z9<0<%X7ixcBEz zpc)V)$jRPo(aRB}9>gWvDy)4Yd+HmKW6EV1rf)XI+Dt zBcY}26ok(b!Bg!JFnZ?4zQYn1ot?u>Y?L3Ch$L(`(IJ+LBT*qV0LTQ}SFm!4l?pi- zj&Pq-a)Obt#;k1uN~FMqPd@nLMGES08=rbzl9Mv;6N#d`((_2j{ zJCvKR?Mv6*IMhygeTO^+F5Jk9%sqOFmvI!GO)Jj6yv)^EL)nN?i9~6S;9n!6S)BrE zs-FiH-dyEwxN~fCofvRXOi9feKyyO(KE%^71~dln#>D0&X>{R#4if6?z3ZUXq>tx; zIL1RO`axCH9Vb;S4N)*ClFScJlPq>~lMBkXQ%Rh7(MgiaIl(;+@X1sd2%8ZA<+II` zg{Vx$ILbq!^f#k$OK5p3sP`LLUrkP#@&UevOyls#vDGx$USG3nqs4xnH}d%wD&+8-Zr zJ|^;OE~~9;JaF{B`+ocQlp*XLGJ3>hL9b*+$!}n27-$HNu|K%@?iaj<{<4P7^Kwbp z0c*gA@iS)`*LHNo9JK)K70h!}?e9P?Dh`nq-2oODkOzr^JZ`gsO$}M6wBQm-N{R$G zv7qM*%Y+xf4`dsi|BJ1&j*2>rx;5S1okKT*gmkC0(jXu((mkX!(l8($($bA|N=r*g zGo(nzP{RHB#k${(wOITCi&-$tyze>t?6aSz`Qhk7G7-rKUqB!KJ@zYr`G@04!&;U@ zesf=lJeU6afxFlhiNG7Al~>lrs^lfybPxB|64&2}i(#0#q6LeG?)J|?cyzzCm}9}m z_9~ru)2DnX;XEzy7S*{_z;dqo@+DrKuNyjta2`FeGVNsEGE=m_XbWJmu)~zkFVm9N z?D=D5ga;Tb^qWC7T;4utsSU*|haMZq7RBYHvOAZ+6Ir%$swuGWFLO9P@Zs*jA_%Ag zTSMCU6;>p80K16wTeAV5uE+PFcN%H$f$dhkfMW-XqHhg9Lgdj6fAcUle) z7R#3B7wQPzy3G(9cK&KJ#_mKBhXzuWkc5-!vcI4gBYG##@*>7Kv$*B`OMXi*l|c$A zhvFOP8xEj#Fn;rO4-;tSY*<a$>S>`L zZvNCC{^nJXE$kaRmT~pMDu#jDIUvlXpWfx2ZUIf%d%FiD_~Qb6>#g?dp`ZOMoA&$j~7pejrm*M4<|4l>2nxDC$NC9k4%4yPzxF4 zx;>|Vb^{C-wm{ETKTHSn3EKC;2<-p(nzg9|fuB}{L{cpc#RF1C4z}?-{M=3y+iWKP#`PTFI7`QMy*7lTxc9i#C zJ@i_pZ#+N2FM&mf9BP-&!cgW4?VDen$V9g=?&t$=->AU24Gn@DwAcUa zCcq8#nMMMV6h$9I5qu7b(~S{LC>z{5Y(fv?8j5yW@p!ypy6*UYT#Ns1%5TiWZt(>M zToS{I_8}E4?E*G3CZg<4j1F^7*(PF&>kJNcj@BU51Z6XW*1UMT%=bfX;_7{w*7&gk za$pJau`y3;R@Hw4TAeiE%1Qw{zEYKPV5uAwn7CyhTvrwukLwH8(BqiMTL0b7klm_* z#*)by9Y9{<(1g%2{}Q`Ymm&F9R)uD`)j+lRo3hU0fo{Wg^GrVzA5{YmH+kohHqqSU ztgm|+n56_{h?nMCM>_$Uz(hs|g9GSk&@0p?lE1yM_yG@;c$-v`*%z&T?aaA6*L%jvU>Ugk*Nd_tlhzu1d3Hd=6WN#7~? zz9u}>?<#5|R52o`;c2wQUcjy%&net&^r56?qTPzZ50V$VfHZX-9f~n^IWil%WtqLU zhUnE5xsM8rG`_9u)+_hOLYn}bjiZaptQr!xiQXFyIhB_;)l)OMEyqNWjB*&;3^qbb zgZK`P>cnV_-Q+2yp`*8$N<~I?^@TdZ@y?c6_tdX-IkS8zN-H>VnF%!`4^o6;yp2~c& z>xXLbFxkzeQr-G;(gcU3S)dmirk4hY>#TU`yf5-6SaC{NWH*Tw8IN1FD(9JELdBef zG(8GI-{JBJ^gU@a_T)~gV}iq%JmSYJtG!Al!YNkNj8x(LL)Dhv-6;0hj6WQj9X*`H z(hH&^oKoz>qK~%x*GaZ2&jaxno4;0Iy;Cg|we`1)GIxn?;GL1P6vN9S|C0Je=hxLd zR`eSr4q-)eq)>JZ_LvWTlKQO8F*Y0b;*!}F03_y$F!y?E&3*Fie6UMP28&^9J zq=D*aLW>nwV*o{?p-Q!oECHtDqu$Fju5PS@Jsi8VzFu1O!B~}gBX)UpRY{oYFm(TZ z#|VHYdEEan0>o+D7ITaW-G-*7AEKJ0F*w7Q6p5PnZdnQSv~wJfB~jffm9%abJFu#& z^pQ)XDYr}wCHrN|72dTsE1rW~sss;zq+7@CLkz@KW4CPLoIyHVOkmpL#@Rwzwx4Rc zyQr_iB)z}2P`(~AY++K>;Bn5|ztl9AqxjRk8(L8;5bhN3NHr^`qe{==&}6SY_TELb z_gsS8$=iN8L2ijG?O0o%RF0JehtI?FrBnU%U`Z z03enO|LL3?SbVLg=PsdHG08e_GSxb6}{ABp9KT5DT6wx4v3%yxduOB;`eXy=cj~ISW5mAj?c#5w>Bw+ zQyqs!oq!my>m&{L(0{K=5dL_)@x*f)u>a~m_U59bt{8!5we7fNWlzgXFq5Gqhb`ak zZ)0QkMybH3L_lOzmh=&){f~So^`0yBP9SxZ1xFr`{zTS1iI2S>um&W?8`|zN_r-vj z6&CZ|KYzZ9|H?}1<>V_Pz}QjKae|~_48Pd^v?tmv}YF-`OmI61P{D9-H;Xu z=vX^hZOW5eN0&N7q#4dEb4CP$2cJTL(rm)TN|r!7jpd)D`0o+#{&`IDA4l`2kG+im zH!0vkMYjZepFO~)`u^g_zl(SA8@KVka`(VD_IpE+g*2^sgU8kW*jc|%`+6hcl6?FB zb!{B)vvRaJ|xh!#YE9Pl8Ya|9Imx^_r7R&^!efZIjRdD)6Cm7 z^$_G@oP8;nbnr}(dv4S$h5*?OD+$3f7!*zzf*3NwADGJ^ z5@JJnrnt%QJDEKjs$u+DlLne~GvU*%=WX)WsSN@bdm*n=NMg7>@q|0+^Gm9u>K|Ko zeg9bk|8SRu%_s40)umf0OV&sZnlKt0w|h^NsH}p~#}F=G_N6I`VT5SVK6M75m@kIn z+ZaO+h^mRQ-Vh!T3VxST%hV-dNdd>*H<5M5oqsXHQga{@C|WjtIgnM_Xv)0^BE=y~ zNaPL=X`s>DAss*fKcx|{qLBE8Krz=T(X8vpve4Yu^bGO_29W=y=bUUv?;Kft{QgIV zK|iutM}sb22^ji#iWgL(cVcs=tN-jns#f&0R3DvgmU#Td)mmpGfxYU#&C7_=v|vx0 zJ2JqZw1a8HIx-$QGcx0iJc$ZqI81K`lAsJP3k`YSMB3^#t_`V}InZj(F_i3_biMNY zYp0{;dUL>-Z7>d$Nqw+kI|ek?IVijbzGmawe|P8W`A%K6g0xm5;4@#(Bb85nc-S1_ zUxe%lf(hy4-helPd92|C^tEZBhXHtoSqqys8tF7>!_6~S;%*JcCXt8@MF-rkq;7Jg zYi2N0ivYNwbyjzQv&rvvW>pd+qlVQgx9;fXh)SNJ;PfY3C(&_T))ZvcQR19bX5DRL zr#T_hs)}sk{kuLUrJdKiueGc0ayK6KG*6Gwr5+h=zr7Y~^GF}H9~&HGu>eAJ?Ay^` zxEP~rYM>t>z+*~kz_xMgt@MLKll;_&uDvsWdD|O%8i;@DcP_>n z%dz~`=8Wt}Qe2ZAW9d8tRz{BF6vh0-Gp^P-$}q(!jm21{WtEp*}w>SJ_ zg@<)CTFXtsipg#d>t^flK73a{PqnNv!;Lw7TqN}~$#riC46~0w&NGR~s_DWWM3Jc0 zzEE#S0*WrHsJV@w`b*_xouL6#y5MXIc()-pWJ?l$=KypF6k4QU)@dWPG%Z=1&Zo1S zkLMqsJ$UKN2qikt{&+|{{CE*?>0n_kI6*ioAKa*%=*#3E$~}t7ESr`3(`nGVZ zRe!NCPn8T=hdfgC`PZbWXSLf(WV#+*r5-vCjazJdNeS06n!T1pXL~`$_98FfH}CN9 za83@*pc(>o;zrM5A?M&YVlr9LZ9Z7flO4z2p(D^7nTRj}!DaS+RV@bCKMB9hvYw zlvyV?Am?w|L~@d%B;ApOzKh?9dg`k!O5OhUw1t1>xqW;6ygQ81yM)m9LS7Jwj(m@X)!re|oDXrW?FX`#%E;6SABBuZ|*JqKo80i66p(O>3(4M{7%{pJK(B_z66}*^H{~LUQ<)E zey()(Z`n*_a{1e(2XI-R-UbO~o*_%0A^(fjx+QkGyuW+69hROPmVP>yzNYkh$X>d> zd^ptlnDuXeedFdrS54}sKJgsLEB>R^IjI$}O$>bG-&#M6t@sD_cwK;}EN~cGmwX#m zPR<{PHgE(3_It=rMRhP4|A_p~lk~s&1FTpmyqL}TZ!f^qe|>Skqko#ZL1>7{A3K^v zLrE_#4k=OqEf=F{l2H7M0b;?>uU3^6%8`b=?kELcC`g=Rnes03rKN;M8P*XEB!p<@ zu^_dO+7HUTKXXS~n=iR{vX_buKXngq`7wA;!vVXdKn^P(jiKQ{oea_EV7#(vQ&Lq) zqCk3|CrHI|^_Q$^P|Q_Td4$_o?$;f=4CriVnG}7P7!PkxW1o4!V4?->bH5{FTk9D~ zo1&dm4Wepq7-b>X)dkI%DNzpFjF|CTeV$^DTQfUBI;euS4To8!YoBFcT**nATUWD_ zL&DyRIJY0H9OQP$%U_u_`|jE6Y8R+un3$8HOzMXM5Tqe-Q-U}p>tc8PS|85=8Dlb% zyPWfpWP3%UpZda{xyq~^Sg%~zl~8x>foNdQK=qAKC~}{Q{s~3}^SO>^mX_U*QjbVF zbN^idU-9jQbK2Bt8r}rR<82N%v1j0vpGk7*Ot>|&shKlG$n+19ppSvCc@n3g2L6cW zkR{rzzTO_C6S~=Aov5fSz?p`~yWpsSXZ3aG(aLo@8~;=YBokG|o259xGWgU&6KNZP zc%aI0D#q=g9w*}@27RLZ6$18I6uUm5$Z7cw%;^C~0oF{C92(k?Z#$W`so;Lg!$@|0 ze{%MV9EnkioRV@A&#V~(+?CQ&uu0mAed@(}qtmNj<06z*@1Pn7ro;0$Sk@Yy(&p|D zw`3Gr7*PG)R>o;zo)Wr(Vy0v&J2dhA+u!Nk-``q1aei~oKTGbpK;H2k_usLn)MA zW+|WF$88?3h;CZac7JP~CF=ZyEY`2H$fNt=k7dS$tpL(n#dA?r5`+0V;Md!&4Tu0@ zXD>cXSmGM90aZ`M9^>2~&8zPt8xt2;nZGp*bX7bbVDQYEoj4_7Dh_fJEzKa$;7k@TjRsgaj?>+T3hXpKpih%d*+WOJ0tvBpl5jZ$l3}VxCHeLeop0h=x6g36@un5&CHTH zqA~Jbu??sC$`z`)R|7zAAQCO=5a(ZYL;%S-u78tk8`FJAz_i)JSXt=h=BabVXv#1BNm*Z(c7xW0YHpX98g&fVe7=E}C9I z+~+7&!j9F6jU&G*9a&@7SbpF?;3pENZ{Q%rA%_}DEo1CSltCW{?x1=hN`^ku)n#lU zn?zECD>1!RbRkU z#*`l9W5=_&5$hA+NA0hCm?yayI63s4>F(&jX@50e^_Em_8tx{3Ailk~_pznh`sc%c zpVI$*GTTk{NGg?tZt~N{3C8PUQTDbYR-**2gsO;2R}vVz1{gD`jH=6EG~r|Ljl{}G zU$OHL4C$poTdtc-M5SIIa02YV;6uomt(n{7PfTM>{j?&%SZcH?Vw@m`aV#JKXIbB* z`^HOtG4wUE<{V*XX-$!bG7CrP(MU>aV-zkrv;8+*Eh#s2J~hW#9UsKfgh%}_;S9|% ztuHxpZ5giK%_VRbXj<0%0DCYxzOzaO30?_N#q~?^EL5A4;-kPg?3ZU}Uc-=|$si8n z_bMB6jlq^bE(c0)0qk^ zq3tzaf43@?5G9pbcAd0ct}-^dE9H@?pzN~S`PT1IBVI`K;l6cTa0ohkc;+-R(gq@1 z6B8lFTVh&LzOjWrbkzP$S5h7TJd6mBon7K#R@w)%^SuFJQR;9f306d$w!+2Bn|>uv z+o6eDRhf0?tzh&a0Z$8ZbwH?Tz!=)^NvEn-QG}3U&mNnqocL1WZpW?4@Q-Bqto}UJ z3kCSC-=Sz%(Lr3nF`6y9b(T{UPMStp6>kg8q@6^4hR0ToiqmG1^zC2IwchMRzJu)W z3(LOJ!*>+?=3n$u;o8S$yZlwr}ihF?LsKU!$=rG|_6r1xCUg9Y0(nGz4FFlO~q zttFCd#KOEpSnIl-baWXF#*XJ6;${gG`RE%vjb}a8Unh`h?2B>EQ_SfluvNWzTMUlz zK|4ZA{RHgjpkjnzyWtv%Iz}g<)>0SqY`AY$W7IS>F6{&{SJ~l|y@f z`O7`)$ak&fy&B$uQxR{za+fAzQOARyC-H;AC%ngFPkocMo{OG8*OY@>s4FJYR^TTM zt8XYyGw8X$wv#!~s&VDGx0;DGpm*YL;$mp4@#iHPSvVybCzqktc0Fp66=C*=e$Ly? zwxglRud8~~d2=9e2#J}AVWg1Dl0o7%)c=&QBolfnj)Iul8w*?rWO~0B+=7xIg(MAY+kOcFUc;EtxIQ2>=?p)GNSPE(p_#oIjuvkg^R-n1IDJ|KeKuIAVVpHUR}F4Ta0}-rlxsre*8mllT;T< zJ29BP2mHn1mjxokF^ibZs;M1ykG{?;1^NYk+Vra- zOaE9RA`#I}yrp%fRLeD|4BkDV>@+967t~Xt@VAh67=1I>tau^i8FkqshUhXF6v)vF zsS!$Qqn@dP*+aigKd)NVMIJ?0ReTVYmbUJwJ~zKO+hX?otsVX4cnZiLY+KShMG>bg zfQqKtcKtoU>XEh2S%4H;zeVqTt5fpXT5ywG`c5{B4)294iRbr}3af8(2rk5d@IT9! z`|lc;5nM2P7frRg%(QC%s(vS?^MaxEoY6rTRyNBchC=NfN&+H^7z2lYH-$5Vl> zzAM@x6hGqJu94vP(e-KVNCj3l<<~NfuHSvN7?k|XYmg-ew|{ajP)?G{`CcNA=`yDW4u3W&y~HFZ=enS&3K<0z zn8S;~ktCSWSUUC#Zbk+UDot_#;Hck7^NjA5=pO_rnca6Uu|aBIQiR0s96y~56MS2- zO14^)F>?V|9E|D8&B7xquTjjIR6q zQ+o~g8+EF#1ib%};uNFz`BJ^7?;Jc7)%`pG$Pj9CZ#0IPW4L3$yX?xem_T8tB>^YO zb!vtGOdWLVYXL&ANXM^==iVi^2+k}C(k+NW^%fZTRTmO zBSR+UiQf(VXnxAr%t&KafEHdd#RT*v zkz_4SncKB>Zw~rM4+CMYs&aC9I}&aWQl$bp(h~b;x2Z*g0>JtIp;;C@;ece05I89vOUD`n&-V&nWi+I%wuAk z-k-a4x*#3uqCvC{RMyYOlZad_{k{qqqIO`X;m<~bZs|1c*#tGH_R2Cct`HCk0ahq} z)8Ah2IqkQ|f(CJdiejPpf9<3P{Cp>m=lmZJEFMg_@tpN`C>i+8WYjd1bTUX?I`S8p zzUeL|TIkvmHGiTlhFPi2O=fE0AN=AeI6R2V(@#iZ9K4$O%OS@Aku4-ai6%j!-(CzS zKzAxuU^-(&z$2o8nA%)9eo~{N;j_pM&erc0^gF|E~q@w>*{eX{BJ`G+J#B z`~fj_4?1TBA|ZjC&4$kJ{?U}&D;2w3A8!R4m$_N794A|i4LZ85DIyaZXpp%g`+&?{ zMFA@zPHk~n)DV0;iMZID&L6GtO)2rer?;y;Pm2L3z~29;UEVH08RnKiqI`+oR|suHD~ zC{&{0D2oDU4@A}Xkd2I!Dwmq8nr-SLFNe8`)!bfg?bi0Fr6rXArgM;#QUQ{wDoE!Ix`eR1)DJ7JL0*$veKhnEnkH_pqWeI# z4aBCQ+ri9DNr2^OXX+|i!x~=jN(^u!kLSMnCMuevM?$Y~Cp~|-f`nY=m40YzZMX4iE~fTNn~&iOx>L8L)sp&4qG)_^KOkbrCz3-)>v4Wd zME}JFy`|DggNzX%$L5hpNc1SEkf&hEG3anC;IWfvnuHLu^RPESfn*ms;!x&!$~n~# z4dOUG5N8R+E{JommF@f`L-QxXU;Sa^6e9edk)@S~S$TaZLHm~$sL47`EvD6J8)jRJ zh{q>K0y1BHq*d#fZf@3*Rd|L(@4qk_U?9HX+WxqRz5z%gkG^7(l7kfT(C^*o`>Q4? zP8}(^($~U&)??lrwkIq*MmE2EO&gf)9QR-H$^S0Q^LqF}2SO}UAhX5fJpuD3?Zek2 z(e;grycqq~Xo+k|`<6(zh;dyfM^_YVeS`M4pC}`|u$g)dZ6S=-xri-NLR;SUT)_KQuZZdRXo z6A6Sye2&CA`Z(Yx4_cC@dMSugW*Vx%QB^*Ir3wT!CA|5R;ZtR`<5(A3L+#D`I)n&m z&Oax%t49_MWiu{%gr?nlnob1xV>7@EF*iF6t?72D*6+HZZIH}N3?WO*F?g9wLeDtv|lZSI8VX8Sk% z5Il4T%d-Nh#HN;(x0;&IWV1(BFYsK#FzpouB8B4R-kX!9mNGLKRlm_F)BEvyde!lZ z1I=X{0^f+DoSu^aD}gb)EvD9L_xSl^hOM3s{?S2|vp=s0>A+@&7V9lTU1`}VS`IY0 zuXPF5QO=dsGC&cgMhpeXmQfbXV3Z3xQCs^}R#>_FVKdUi-Vx3PyzZ*0W97Hd@IC&# z*miqou@e<^P$U640}W9GBp)gmJTg6N{jNeE@DDxDispWYEJ`VE zB(~8G8AC<^XT@MOKxC9sZS()zy?fC0wCtl0z1Du<72xKHF+8#_ZSF;`xV?15^@(SD)2cM--1c;F!&7_BZ(SIs^XYUs`gGoV!&;fskvnTRpeon40CJ1Bd3|a ztXL4!kZ!EY;)?*MXtJ3d=0cTMRPlfn55S#u5Jf0pM5Ja7+qrC;S_VO6Fz`Oxx7WyG zXr`rM6zB-b6Iv89*;mB}R>{BB^WhOhxzJI~EJI;bv56sPkdq-|PSG=9_$*h6#G@OI zz=B$&6Dk~9@a?LrpyI=?miNu;tKYrn;Ow8bOaU(1DNP;^AfA}>fmi5Gd140v*2-F6 zn~Z_5zJYQY%MV-cZx;4fuRpzpqA-#=ndvxDpR9IIbmRr5S=`NA6jf5wNd}}G2FR}Y z;4BDa#f_44aMls`qxMB*!?A(T9Yg6aP?8YldCVf!v5ouso@fVgqRd%1vNT-1=SOz> zeku^SllHD7Pe=!+YuGbQgN?wZ6PKF#v{7MT^Xm~>2}4 z1Q>dB`v5h2DGal5GpT2(G(a^j` zR6=U|X$}3WLZf-j?H<<#0$-ADK{#uxSwuywOI@FwE8;0lxoc7=Hr**LjQhQSv;s?3 zd*%5M%&FI33xgp{0Yx@%=c|75A>gRAM{m)5oqu!1diGZ8g7CsUW&`(6z+zF}z{xao zT`(dyMnqS4@Cp)bv^GdBEQ$d;4TOV8hSU(~c$p{p+(RID1{kN(CTs_QSkcC1Aj85a zt$uANBUc)?dM=wd7x2-Gi??Uyt-$}D07~}%IEp3xp9IgPV%X{v#-OaIQr}T8-%%7E z6o9~`n2g#!!VD@z@jhhgmUUkg|D1RRvGJou&tmaNE+~+1Zpv~*s|c}T`0Wc!xJa-0Ky&DV~6zFk&NXApG-a@phm#0GEdd@YFqt zqbswS@&LHG{Av;>Xt^!dP8Tdp>F$(>j3M zgwWkhFQ8`J$wGCyIFlMf~k5kGb@P013z6Wa7uq%f7|^7$mLJB%MYNJ zQi1*mwUGTP7-D?Z9Q_E3wLXH z_sfh0SXh^Dobk?8sa?l!;O=9J*xbYr1R}YqR!k%iffiOJG*Pm-PrNh2X{Fw1A)F!O z^XRT#>V$uA)IK4nC9mtSy+L)@AGsMbXk2z(?34rw|X6sA!r)B$ksStaQ6%7 z@9UG*cz5t{V7%@O6nOsd6E{!Ka5$m^E$}q01GB|2I4|947Yjy|SAx()h8DSv5zUXR zDY7g1VZgm2`%f};=9JMjz*UZ70|KI>3fT>-(*S=!N{R`I;!w58H>+WfE?Ep!Cejg< zYGEU2K{1-cxh!KC8wx5O8Y~3DO}Wc_amQ$sR#&kIP(bqa!MtzP!^v~<^0woL(WXYX zF_ga;zf}QX)7GIRG*kE#iRyGxez^*)_S@Z3hGFoRHy_X`&|=dVy3pviEtSaz?RY#r zXV9Ys(z;KC5XwQOl(27TV%#z)`& zG3}_IrV&HRJl-1%?vvrHpGW&_i}6_yMHb5T)y&5qvT}XA+_*n=PPM9;&!YMxYs2}Q zhyeQ{-llZ?^}V05@W0V!j?D2|_kWHR|Hon6qY?h|D@d{I?u2>37*UO>Ne;!U(fnQ9 zI|>Q4ke^sQLV^4!#QcKao%Q%!%{O)IKO^CNRw^^5M~Wucnd4v@rwEX-9}EyEVHXU? zfVc<@ZRQL_vX`n+t~Iic2u5Jzol1J4I;}7^Gpb5@^%SnXp`qhtZ z7o34A1WyW;(9D?J{?vLRe;jx|e4#OnnMm)I$|6MCv?7zmX?j}J!DFafEzqZ+)7Rf; zg`@Jv(!N9L=HOSW#8GX81*$koC%HW(`AT*3RhKe3rJQ|Lm@_{OordZf!U~HfHWO+| z^rRzg%1%4Mw45F&RAPKu*HS}kPAPq-C8n!EjpI#a8g~kbB8d_)rtI+bZcUh5=C%e& zp^|T(?NU;4mc&G>$396pO$c4ABBoZab=bhe0gai*WYBHZB(iYi};c?Sc&i74Bbv%ayjR(_fy(0@Kkao4GW)sgg^Lh#GWcq zgkdGU8q}WeJimTRNSA=0s1gR6!+f6xymL5|t;P2ZonD$&FQ_0zf0D;=S`oxS)>Ug@ zVw+Oeht`?a=%|tmTKRoJE8l)H5&4&NzB@pFN8q#;qQ|`#6>#Gd^m%?a=Ja9x6edr9 zD@7*(arIaOXALe!I?NcSux1sd5HB1F15jUXi`#zk+tK_-RWt|fXx4GT$ai0k{o{n$ zOMui2km}j`hUbrVQn8f?|)kWZv^!e zx7XapCdwX>RI?;b`K6|^Gfp$HXko=T(wNm@WtGYnX2#imO=1cRg(Gngr|M$}_4|iw zX_K&n1a~?TQ5Yq74Lhj`I8keROCT`*cuS9Nn?TYC3kQ&q@isSmW+4g5-KS+oS)({Y zjH>IawP3j0t5-*2l5G)|})A?nqROO%NgMjgtJ@Zo1(>4z86y7b_qBll!fMC({fVaE{5xgtxd@35KVC5i0$6L1mQ|q+(79T66di$>OBCy*rw-LVWBDH^u>IaJteD@0dhAh-5Lg=0ol&76!xd{{L01)ZH_ z^uiBTV!G8Xtv5FIpQrI@oz}Lyn8)2?gi3C3ebb-^BoUUW>AuTlJ-(wf579F~8nrjE6IZC>%U55T|(HWR0YBq3pxYcu(oUJn{ z^rA-TPJ5v-3Ym#$FTN6~L_3|BFlLkuJ%alXN+}8n5#rESVm_lnAh-d z!4;}R5si_cc^Z0ppncE4vo`mI#r5HVh)Rj031(!;xox6Zlz@Wj6K0`$eT{xS&g|K>S{>M&)WVmLPdpW8fwN})90@(r$?qY zRMOu;@m_3+E|;@ZZ>ePlp;)L`H3o;sjz-DP&!N6l?kHiM>b`rpO=hJ<#K0QN>AV`T zm?(c#cf@-F7C{yd34>7rC+derSvAp~uXo2Acbc9TaDrdK?hquD*h{n{o^_L<*c`9M zVk%Ay=nCM!8~}I~mL~1pa$g11u)|YE6rja1LW=}6dXh@}34JX;28t4zJ0L?^8Gz&v$Vi-1&i-0-luwYJ3*7+A_} z=1LR0ta*Dvdv+DNz1P+sdCvW-=giRSWYi-TIKrIVm>44VniuKZ-6eLrPJQW}F$4-b zYi3k84;$ACD-1>+3`3pOy#C!;*4W#@1F#g2Rq zoutL8vU+gOcxwu@@H89nki9-X4svbh1(hmvGr;ng>j!}=uj}bLGFdF@H|Mo2fb9nK z=zw^toK@;+rVRc5_2OuMfMUQ_Zw8JQA)}g+pd=yT54?-p>>!<_H|au0CQvutmppW znZ?U&4*qW$*n0pAP`dVM0DklQ2UIBq_%m-z2en`4MhVRU4Q!29w*Pcp86^sRSV&Vo z?fs78n7w{z6gM9r$9B@Z^Y0*bRu(cF-`Yli4PBXq!IQomWJ!rTL@*eR5=ivjWqkRf z3l%Ck6_-nWQiYQ65PN0?lV2SNm;1GsvS{hff)ryZ+~O}m;260f-VfF~YS4YkmymFL z6%zXU-YAs|lr7YiWI7}FVxyb}@ojHn7 zT*G(uzo0CX(P~L5B)?hv&Djxk`J3Lol_X$m?(P`VI3w_8p=25;r1b8Y4MwFS?CLGE zC*emBM5sXrGeG*CsrH9h9&??&KhkyDO-)cgc}>;A^I$ORR9%2LV=r`{@RwK>IwOS3 zh+^AFnVvp_h_kA2{?BjsKMLc2a`SsjQ{_3|NGWlJc&CwAk{mnJy^Ld-Ja8zXjhId5 z`gMw5RaAq9z=E}@j9(NM-M(2<7g~H8(@-rdR-B^Rw760eCyO@IX4vwz+9c#~jn5S# zzU%9ic(tMOv%#_b&Ff-m$a#BKI*&)MrcAZzN9>ukR*B-n z43&h2 zNvib+7*7lFjE}QqUlSodDnD-}UgiOFbaHbD9-qJ8{y~+z6=omv63Ye)5xHNS>yEYN z%9UsV1op=u&P{{NTB#AK+9yG6Yun=#?S7p>ux|!3W~p1@9sY5?-jo+it+i-e!%M6B z+mI%%=!>9GC$KEb{&_mPcRFmE&QWW_Zx*ErE)n#X@n}42kb4+E((Y7p@X{xL`y|&t zZX60Mbp_TJPIItFxbUn^3;v{?Xpuuv4bpYJf3An0)VDaH`);^M?0IzE_~*mh;HyXe zflik~6x&N^)EGKn*qv2T1f~&6y!D$SDo{h2h`w@;tMD)hp)tKh!$L7&lruzW1~Z}{ zlX~@1^qh>t*Ds|W{&X$+1Gb2dal(u1!$aN9pLc4nM@{@Uj=dI)J$?x6{mSY&58T*N z1Z?V{$X%4y zJ{hmyme%e?1LpHnOL8t+V7LQp-tvu?r;&C+g8h{EDR44!5~3>z>N($@EgP#tODR^M z`(p6Z4aK7jbC=#1wI7kw`7DOSqI6^KtfD;`=rLSC$F*fkoQRpfiH>}FI>KLTK4ywInyHtsa0KuUJJh4qMK+E8e_<3=M2$90r6kIJVa-0gR1FS*QX# z>R>>$het6Eyr3F8TO11N6C0k$_Mu1|{*i!fMe7%&S>@UyGgdb$FQ&*r^`o;Cj9uDD z+zG$Bm(K|+^#&M4TU(5w{J`=uUUcE7UH8%Rfd_;*rK0P*=7m|S@=5{@mz69lF*_Ik zs0aK+ZNWkT#MdT#?6#=zlT~H4(S=Fg`3jh~n|PmpqG!U;%cfFX0eGlonwk|8C4p&d zpGj1`@MI+3m4s$S8miC9`Zho!k?`IX{5zB6>-I@6bZ!}C?k7p3SPS@kJyHs6H)H-K zLZN!H@iQJR@GQXFJTCEKmx)LRRZxJpIaNg=XjGS}L?>B+iTyW{9XF8{H|bQ+g^~I5 z{o;$viPpbkPJn(5Iom`8XAxCqfYjK>i8xpWs%hiGfZp=m3K`G*huxfs2lkjxbDnD} z&hd7Fd8q8XNUrf-p(LT8nEGl|wz^-_0JqyOMp2ezSi|Y|>{GMcAe39Re!V95TjQt% zf5JipFL?i4H|aM@F3KXm8gtGt=Cm9vxTVI31T~)L5Z6yZe&YNOg^OgD>?a@~J(7Dg zdYfX-u%h$}ry5Ox^wV}9W6B-C0xhlI0VjgSbT~y*Dk~VMSlKZbAXP~ali6#0Y6FCQ6UDJ~M%A>aNB!+`Uw1$plgR#a<@?^Q`B(aR|c`CLd@a^8!amD*M=MQVZw+{O@Q|SBU{oZ;2 z4SI8P+_M=@2;}NqujsJ)CV0iO4LqG|Hr4l==xb4 z#aF2;#hLP0%C-5-;dXX*D23*5a=#;rcqRSum~0Uj-JiIV9Il8+TrN86OkJ{mQFT0B zLZ!`Uim{}4JUnW~HYfwKldenFc_pA^IWfhwVu&>*&V$Mn=U8h&OIpjd!mpxcIj#tS zygm#+uu@*cLmDC(YSeC*zmMuAN{N0jnN#eW81CbUJk@=Qo5iLF9H*3p4%?{yh`?s_Yu&(K>ot#f0RFk$mVvRK7_^9fHz;Am#`W6< z7k=$UrC3+D!zjtj;T;jw`j}A=0VGiUQcD66*|F$;@SL625+tFc8aQFt<#D+;z7Vqh z=nzGo|1tS)fcT1RsnF`iHIynr#b3;8jX$4vX>9|bf**197D5g`rvn=MN62@`%Q6uv ztDFI>q;o877RC#54ghI6C)Bi1W%}NZurNl0}S zxl%O9m1_NT3)MD-aslG)1LvrWDFu(-OLh_pX%bI1YpZaKT+&$g`)+J(l+`!@RGc=S zQ@T$Cfs!=95r<*T9Xp6rV9+WJHX4|B{##|{R_T9Zp;GX4(r67Ol|y5$lc{;<99+6Z zxc(q)b&SxMWLLY!!rYw&Tl__4*T4ExeAT1+L;N)r3riV3Id>Yd6^qdiZdJ#TM!JQ% zgvMipE8mf|`Yh3ex7lJp+M^6HLN5DeKHj@(WR(JOR6fvM_h^wAl`_W3F7TNW(P5n7 zo;@L~dMJ|&Ca(dhuj=);vDo_jrRqZ!c-k%eOzKA)S`J3H;ydQz_+F*BmKJcBCBU_fELFq$?*0jO34P@*^c zMb<(F20EmuCIg60)RwL^*kcVKO+65F&~a$Nve)Kik$D=%DS?bY=DX_mb}r<*w3hWw zv0h|$l5`=9@2bXkq1DwqV*o%~0+V*xD;}PA4$;VCz1>Ozq-1>-)jZ3rEOyPhQZugz zd5}SH6>oqPJ1KD)VRN}EEN5;G6EbSwG;wU=1LP8~_V_0Pj|BqEarS9m2=T^D&EGRO zSG)Y~uz-#Q%ZpZui!B9neEy;Pqjd1;T|k0v%$DmXcu?-sat7I!yq6s0gnuZg`KH~g z(UccJ9`#WS05nq|Dxjhw38Oa|L|Lz9-(=SDm_q6jYxCVoXETTKwUDMBK<3pUnNj!P zXZc*&iyf}7!sm+TXzeD)_@+5cSIvey+8|COPi6k<-o((Q{0MEucvh$+AO0q?jb96Z zWybmfYn7G&``s&-uhk#U3(nh8fbdvTK|##%Rv#As7h7i)R9Dn&YY6Tx!QCOaOM(P< zcMtCF8r&g3(BSUw?yzz95ZFj?_q%dWom=(ab6!^QKowQ&y?XW>J^CASoIs&>0{t?F zXxTz4ukU-trT-GeD!g*>(K5D#E3CM&*0E5UM7ZOX;ay7`eb;Go8(MkZ#BRvB&DZT> z{Yy3wO=D8`Yx}&W@7!zWB+FDdwBb_m6YAcueJmNMNuA@E-nwtXK9pmzk#@G6RsDy4Br7~>##OiM zxf{VDpKAX1{QSEAx~4WOZO|IYqIWTDS7ZFfH8M4B$ZXuvCVtf{t}(co^#+dKvX2$? zP`})Ry1YQN*%fXrIPfLxXBu)rRy`AaiELIKauSJFcnZM@OotDgR23h;u!Kyk8U~%j z>_Q{SZ~xpm9oLi@?^?_`e>7q%x%nNvK;I>uPz}!EdLeu^5=F1y!#18kHsT~<_g`5c zUUrbuQl}v}AN>SfadYAs9_@Pd13l-kK!*9{XqQVMFM?1H#1dZu;-_DwGEW1L09VqP zf0$n}BdpXQk1__1_VZV7yEV+LJ`G-%x11h__wR)%pJkfdd)@t7w|vUWbuv4CgZ#oi zkHHuAB8bX0r_kZ}pQVd|@6=^rR?4yA<1rCC`)f@0s~o=YLkGvLGZfV}6|yi*NJP3s z?X89uvo%i9yS)ZJb`G^d_{MV4l`X^a&{G31!Nqru1_iiL$dm=M*Q_B5vjOmGLc8_Y z9Le=6X5m*vC45IrX48Xt>Nyx%_b&s!&B#rGGOAHwT9Q&9VZ?v|c$wum^%kO8^(D92 zsZAn9XTIHl;EWEXhW^knexs_m4weMM2%4gm&VXg3ERls&+2K8V5*2ysWfVBnyMKpw z@#cB=A#DQFMmGk*ezW?ib|Rr^X&!MJpvM6@*ZZBwiS5JM6xp>cU3f;t$gK1DVwIG( zoB2iGI&$+~i3)$wA%3+|(B?_!ZuMKw&(~o|@N{o(Zu5KQUN6AVPK8;b@paU)8FJoI zX+e?3#zOkO?8IvUGL8{@!1;q`q#KSIWnxf$jLNj{Jbng3bs~aWqUsZn%%C!}I-IaS zVU<+FUYfFP{+xdZhWeJwHw+D7sLAX(_P|*P;SySD}hFIxNfqdu#Ikw$;^}KY)U^r-YYXSB|P)33?mRtijq2llb zLUaHYE<6Qyp8rbFkdUnlDw;BGAgr8D)%f~*h-(5&x_;GMRJM_@cIdP|bg@-k6?vqo z?Fk?}AjqqRE7-@2J>gPQ=~%kA+$V&lK!638GSo{v9kK9+l1vPC>UOAQkQ$?uMUC}W zUKXBG4MZqs5w@!06umDn&zb5_m(Po>N++%s`_7%)^q|J+qWWR@;xvVjQt6^JE}YJ`_ug9UbFs|q@G@9ZI|;mzqeab-*gA>5di?C_+-9yTYZkaKgM_{@Ka8s zLsyjT1#lviGyWn2W=sRS8TlR^1no!x+F^7*QLo$~UIYg>x3*x7gmbY*E(xC8P2Kz_ zdDbioV!8k4Lvy+5-G^F!l}H&p!s z`F9geqJ$xYiJ=%RD|c_7QT57$fxUT%Qi`cxHGKU1`SgVTe|ny4(iIr|UvpoPSPa*8 z52{qDjPzxdznjVgODB2sfPEh4N({sGnzICXjoA$yJv|cvJFM#O%4tcFHy|Xe4D5Nt zAqgQ)kOf)u*~{}_tYl?vb^jon^6Cp|najPI6q}Zt ze@QC2sYlLxWmw{FrLAa21lPiVnE`I8>=ToMg_>PR)i1l<*7AoZk51GwWPqjR`#X7B z8HAKk6oRX_cyWWpN>U-kgqe_iri%L)Z*l!Xr2@%C7T;FURekS#?tJhG>pZ zKN7Y2cDuAb^G)(xMu_3PJate7){in$5Sy+;pBM$)6UZRkxif?+;qPg&AOhLgib+Kw z>Ng#F0{+t-*&Up7pQuckq?4+%GeY`s;o$H}%Tq5OQv3t3H&zskV?U3D?%v`02!unj zxU+4kgr)B-UWX3goV1zQIa+T6e&S_s)VoiY3#y9Fp2i}qX~XlJrwoXO1*YHQpcMtZ zvg`F!mT~0gS+l44{5{7n|6p4Pb>U1O9fYF?bIJp59Hxm@$K8JZ#YLUyCH}#`HLbB1 zyB=HZI7Wg{sS?T;FG#uM(wI-L!Xce4?oNzF5&03bmZ2_j&k;M~Eje1i6wUn*BsW;p+VCQeU zR7B?4Mw$6XZboR2PV(vN#RsY5_HX>e96wVg53njPZ{|n@o+*Lsf+gFSMK8vv;I1wq zrMwI>1GjY^c`?&|twnQ*HZ7IZ{WVsrsv@_$4I+*c=((y{Zh*)pI6bSwk*k0{hb2i5 z(0ZuGH1sFG`DG(y@`9GS(MibFw8C)(Q_uF>-DdO|+poLzSboaUq?kAP6M4p@yZ2_#k0C>Ftjy)AwP7ra-bvm&^mN2+dMhAp|+J-FjFoL(LtWYR&TA z%?*$*Cq0jSF7%J7IpwqcY*1~`)!tkPWu`rBQb#5~e@plfjEQQC#BZ!Tu>I=rW^s6a z!Eyd9AhmP;iuWEGWO!wB{%)*-qzZZdc)49{OZ@)){6>kKggfd|7pGdP8}DG_?bZIF zET^6ckZ1nE-Vmsddh4ydfCz@sj_qrb?mdCGI|6GS`GKV+4bSQyP%Z1k3E)Qp+ZH?7 z3_v#-Fk%HVCt}#*TeH@i{h$LqE@$l4F(oj7XolAn7Hd3E)Iks3^3DHHL;kDJ9<)qB zmq_X(gE1r*pL+HAP!6%|ZV@Qp{J%jAnB|l91rl0R$gisA8Xv7>OYeKr&3h zm&q_6>pLT{dk!>UxzJ!0wx5AgT<5>y6t#(Gk2~@NF@D-IW6v?xi*{qSvs*d7KcxQH zkj$o?1ed02!`CgcTSuEiHqD`G$p!J(P?4)?jrdv9CX3B;{LszFfg{|GqWsZ}Hu0QPK?CeqAO# zP!xW`Gb_lNt(Ba|hPM(8FLEVk5zvsrk(0y?y4kTq>d!M(Ol7=7+mYSAz~-qI8Rk&z zj@!2dIlSIEINv{zD{i$a6y{YUvFL3byv+*L`+rRmCy!d>qbO2h^f2m4tJlIVRZp?b z$6RYScIQ9X4KdB}f3hlX?Im)+z`vUBG#-fjHU~oR2)Vyz#abIrLqYD`xSrn&J7P>@6IbGe-jz*>zzl9HY5_XA9 z`y@h81jspE+VPD*#?uLMsN>e#PKk=h554q6{5+3;+@4oXkTIM9=2FH6;$ch6t@YnC z{$*67cgZN6m78~5&v8!iOOwT!7Dqo)9zk!01)pUt7we1NoMp@vA!ykw`_AHv*=$sV z7y>DG*|)zBD}QeTV4<<|7tlE{rUCr>{|t=)7`vWHceVKzZ&|Sd2YwW5Ws{Jt2}2dF zEwEL@$k1!8D10(Wdg=w_GI|;v6LkLiX?sK}?d3)Bof4W=ztQ%dl4y4Ix`yW7kylS& zi%3+ap7VER&tvA}_xtx`H`i;2*CmI`0+FWzz`%%iF67{MqU-hkygiMjC|GB}`7fE^ zF^}|#{0&$@$@1@+&fL180gV5w_?1DYiZ6qT7eQ#gfn#RqnO46ll6D5qT% zXid+ydnUSk?k#Nx{{7Wz5&zhUw7Z9!22u-NBK8#mwrmBfjHt^2(-+71W)`cH;4}l@ zpuPF<#%l3F6rXj0KV6XWjM^+*Tf&kVXz7zQf6s0r8wb>ZD&%!GKTU}(ZY39xuy>s5 zMKl|)D*R><@I^n25Tw3&vGXUT=Z>fQ`|GQp@MBs03W*O?+CKvRo|81di=E`iv@SX^Hf#v z_GVu2I&67If5^7^S2|uyyuvE+DVdO&vRqSoGDFZ^s$ldO#nhf=jqw!Z2wHq=t4AOs zN{gZAcN1-jj4;}21C!bgc}}@6r|4t2Ma-{#5wjp}piikxE69g7MNUNCQ9_D!MVFqM z-SjDR3a((@ONL9C2#yZ-={zMioJjLqOsnk@`lI@3OMI&i`}RW#@=`cRWfw+xOo>y? zPHc672^Wbyn=(g)?i(io zWR*Ez=3WNBc&Cn}ekxH*7?2AIw2CB=x4{K_;V~mv`MfkTSjExQb~dH*j(!qOL=<-6 zn8dWe=FMVbikn2L?vqX;6$0FIxFtDndq5hMwCCSpl&#m?uFQ$$YIb~NU}iG;%_XME zroMUE^f= z!c(||^Ky}>JGTk~sDOV&C%sOV6V5TOEpvCA=-IS z2{HLK?bOw6MjWsu{=t}=nk1C5|AkaN-#dYJDhG8GRpF`&DCCK36h>g<^&N06b!7Eh z;4yZzazdpZP;*#tjrV$Oxpir4a?amQiITev9H!#<$=3LS3+Va@Wmgx7h=@X&k(TP{ zkZk9xNs*M6`^eI%#t8gBS-1@EU9NpZ2CA7Os4BZq6rLm}M`>Bz(ThL+(q71-5p_p! z`kJfN4OC@ZEE@XP?}ecDgPMAm0pqS7&dDRwLOgz3Fuxr zF^ov~knm?Pa(Dr<(47#Tzr_a*+|lN}1+$fXJq&xe5wwI_><-c`!UnAKSKe3yk9&uo zyVaf&b+oDmZYQfA{ur^s>#tV00smfLCDqrL=wRIWa+IrXofn9&NE6=B4{zT)87^E$ zpBZZJVR$&zEAL&~=l>}Oq{32c-|BA^yQC(N-FjHjo}4b-WJDDztW=9%XFY z!?Ce3?|ccXNwfMt0MU)pt&60SQM3Bu9}d`Nx%x6v(Kp!e@rU6qU_^a>m%jq zYT=taw11GfD^-zORRG9y_97%g-oWHz223yicP(Z5lLY|Od?6Sx&P@*YXnmYR^4%u{ zK*;fi;8ly<{R7!g1>gS+fpbPQP$I`Iqml$cGw^Y7XD)(5dCMml5*W{L>*8gn z-4d;fV&3*HrY||wwu~H&VKl5}b>?2jZr^B>x9>dSpwv%fV!S#2O-#4cTSKs~^DaLE`?9%GhZ!Ra=n%2Tbn1f$SA zIZ|@d!j2owwZkgcXaE01M8Ph zm2P!KH6##jr=w?cNc*uv7h!LY?UVl#hY~%YV|W5$`}55e{yer`YwPsVRs!6}>FSh| zMWO*&Ri3p`8`H}AHbtz7w-u^JEfeCn#Mn^?!hQX-UXOov_&urf)kVrlyrIPc>Fi3_ zs`I!j|L_8eR}!!pI>+cP`HXBTuRF-;f>vdog2LPGmPVz?$^7^3YfOHqrm$afba;57 z(_vmtPTa?XkIDpR9{1itUkB`d^L|s-z&4k*AqHY58itZMrxVpBR#SKh<;s+^FiQ}e zQZT7Mmn?j{H_)5l?LAXFew!areF{ZVIXTD9{4Id2xR4rYswJVa5y*INCpGIgsZBm+?GoW zgP1$TWxgw2O>&*Q^1pS?zb}_sh(pv6t0C5w4f)hPWj_VKcS6m8jqkmb8r@-QrLpWKVCN zwF}YbvwyWFN){YIu>3o2Tuue* z;G+ARpI4O9XY^45-zHIp)et288$15<2u8IXMn8r`P>q{g#b(xVZ?{@r$V$z@r_g(> z_5h*bDzcWALtfG2nLN8Jq4mz7kyhN$Upj5E1-vxUsya57C$L~4YZ&Q{m0b|mW}9jz zjbpR@X_m*TJNOIy7orgxu>X4V$>=dlDoL4!;RkYR&me3H*FY#yYjKZPbi|W9E|x5~ zkC+g?cs&Y%hgA)`FT9ebD4bjh4?8o$J>;TN=$Pa~t8P=e8SNAbAqCA=>kTY>bUH&D zKDO)C2hN>2F2uc4NulP-mEhuQy@Jh z47A*W?_+ogepAjWtX{ld_@xW6bS!={TTG^M6e7MR3^x%GZ%U2?&yN9X7e_EG2AxvM zOzG3$JY5gg9mn^C%_*wEKrU1Hgk^)L~CjMycHS!b=DLODq$s5faaSjy*Y z+Xul$$SaG3s93MPRk57?t_8KWYJV%lXAq-QoE5)#u*`(*<9xI#Mc!qsn5@L6PSk1& zJTLEx*dL4z0m|;<3PZGUXMn_H=|S6i_8Y#;6lnbt!=y$$3s~I-Sf_hYBU4Ph7r+m9 zDZ69^Jnf_VNa0k{F$pp}x@XVY#L-424Nh$S}b+LK4DBVHD*1f^5 zA7&97=d-p*ug9ZXfVyl^%R#n1K3Z?!sNEbUZhf3zSVg22c|#x}o^O)V>Xa>r$>|o9 zoNADCwX;Or++3r=f_R5^A97Nqr^1W`s|~T`rq6+oyt2A&%AI++^8jG#lISK_G0h0D z%n_33*<_^Du#FNHAoUh#AR_WhBa%Zoqr`km!>#KEKTf=Dk*LU28}@)=X>)gWb|6N6 z+B8(#q)wOzqDM&b(|t#0JaEO`efdsyVj-X?0B7h?X}3Oia*K})TR}3b#8I|qiQ@kQ z(WunLAt&BlsOFRK@y88BZ+9|T_;{BO=h`Dk0p!y30OUys{`?ZW5lmc~s1l6qC`|!1 zh>IzH$au>T$nwe85wgbHGPBqi2(!Cyn2}_r=1=upOuC`kd&HRTxv*+(@c=xCHnb)@ z&DjDSgcUuuf*Ie;?XN21*BKSZZ_Cr9!@0J?t5XAk>v9jU16=7o83oa@?ENiMw~Ip3|lk zwsORun9Yynpv?u?1r_^by;%vi2#ngjKedia?bd^ux)s#!(=(l1`>{&w0+-P-MFY;R zwp&-h9vc5qvz*wqxi@v}=N_m=-{ejiPI6USoJ+lSe{pFX7}np_QI}Q&7032psMGHF8EyLO;6XeH5Qm( zvQWYz?wfTUBj&NXF5PEt9c*(tfJ=nbDZ*o!iCFSbN?8L&>wWYYZt1+l2Mz3#xoiqe zSF~(zNWYJVcdLgDwr!9lHDm|X2FOeu%w7Bo4>?(`Vb7gz^S(s{02&)T zUg1@x(=VQ5V6dL0$vNjHT0+@CvwLCjlsw+{OS z0dMcWD8}x#xCI0R1X}|#H(!OS^}2eyo;{@GL+zM!=wZFkD5eXE_I!u16b<&umPI1( zbB6NG_~;)NMua5*$ld(|%cq4;N_f;ej&rphPVqGlWsWxgRUR~s64XJL+DED@wmP?yh+O0nm}^zp;K3Kw)L zio{1WmC%)BWo?07UjoZrsrbKX<1pcJJU#Obf3D^zgbdQVuaK#_P%svx!MA5`?Dj@av22#OeU=O}kXy}kGoJ1(4g>1bD`;y zi+llO&o8d9OOv2vL~`TRW+KIs!HM81LCPfzi~DQnZ;RPSMZfHjol=Z+#p<-e&JL@X z-^Mk2B0YTf*4tcf5v6zqTR&^3LUMZc`L^{U%_w)m0x&RIjoBh*P~%{tsCSR^+V|yf z2u_3s%Fo0Llo&l6{Fvqd4eD)1^gI~$_6xQ#D&DidFb45Hd)?kz@1*@uRrMq!Yrm(Xj-Zgp7{&(uqWpf1 z;?~f+5*$9#QkIGEsp~3msPN#aiIz`LP*30!WL68=O}T)U;D_4jcMoidJUskI_y}xK zGOEACe@*lz#>No#F4H;XrRQDMVfcUP$wh{WGDODp*BzHeL-8~g7uyF@vdgO`@lxf0 zzxqI{CQTTM^Y@m7vmy}1% z_{jx=^2GRPqBysZGMf7;`PB;OL=jL#O|tt|IKpk<&fA4|Yx(l>m>6Q53ayBeEcepO ztCz{JNr{T9P}u%f!z(XDDnj`-!wlRa zZajJ1N@s;t32$p*LUQ#v_;B9-vkT2_QB=~130HQJz}l4bXe8E5%O$DyZeZF(`S%SO#1PfcaZM%!&WQA^HTsfmKo z<<;Z0#{Z??WG@+mf!vSK2O zMi9HB6eyrzS6jPVWdi?`mVjs~;;W$d{j>**_mi4SAnI>V3c-rVl+p7p`P0>Xz=Pz2 zNWi;CVlN0pGCo4p9`0b|T)$Js)17L4w6e9<&qJmo5!$Z->q~a>e)HPX`@H>r?fW-5 zmrNG+#z$;?JS1E&+R8ezSLvqG ziyxA@Q+BwahxSBqp36`I%GQ<1<+O|*;y|s0RQGic)PF!M@xMyo)!}n&~ zJQx*k8l=PX;Te27Lg&O^CW^{wDJ3vPR(Vc09zKn3AT)O2L zUC!|MAo&(E;-CjE2za4Yvy;!VWY2pXw6Ir>MUqj!m=$^BsMhZo{t=y~HEde$JXX)Z zw)HEECi$blQAA;y5pk)Ek$#9R`HzfK!4b(|nz%OCqYsiJ_od}w(H+l3@$pC0LZgBP zd?v)ZodtSKeEyE&HQVtD^W`(h!dm6l)3ZjWGJz6{hkVfKIuW|c>`X7`l7|oyHCJFm zag_Mgn3cYoOr$<~_G@q(wP`uu@9P3`H@6%g{+Sa$UlEC>nY2uY#)F4-(SanwG>ayE_oEXmQ8wMdcx~+`PR+48qY-r@hBUtR|cUPM)5l$%?|?(@4sI z!=m#1RhIteCp=&@ymmJ!bk8@V&RALY80=AzEh&Z34Z1yW2hCgppUW1>`g#X&R;5nN zj728J-{`{f00U>d85NA9YoiC`JDG=0)a7Xn$I%?V|DieYvaS z^waSs#t(m*4R$&aXU8>QX<7U951}E|kRr7mW6s zzQ&&gWy2&x(20E6=SG;-y3}l@-Ta}=Wb>Mc7L$4J$G~DZo%6}1@J0wKsUp}Fd?9kfJlamB5e?Zgz zj_}!re~w~f)FxkTc^3w!^Cu6;y;>2$si>$t{PHA*qmJtmK~I1*C5k68nA}_C z4IfY{qR@^!Z8cE6mdcQNfWq)^C3%hHtjohT?jbGqK`Vln#~N!hz|&g!+~lPZa(?f_ z^^^m8S90C0OzQ6QVqadGt!e45hS#`xJ0U82c ztm{jallK}QSz@ar{OVobCi&l907TJpb7AnR-RGU-V{4jhG(D?Cemr<0>>ddDg4bfA z2#1e}D&R^3QzCLpk_ODNe%^1?p0Sx{+Cx(P5kmw6>5{{oO3{IdEj0cP+&e=!#be(??2LLH|Y{KUo7b1S( zZu$_U?C|?w^)M_{KQKaDp5C9J12}fo$_!U(E+;I1CKf&h9wbE^ZC)pYf4= z`|$h`0^ZNx4SnZ%UX6vH&;nAUC3R)!eHS%f?f((i{0}He0oQx{`$POS_&r)gas8`Y z;C}rcp70Y=<7SE&dhw1K;kUAv?N=Z_@%>MH0Mhmq>ATb0aCkuAruz;6ZW{mwns3+; z>vraTbGv%Gmjy^5kV1{FD1@$kb(kKODNlgN?}%xttx|HH`GD;!JI6|4-ro_FasT;v z3kc$t^nb+*_<>JhXTQ3=-ms09L9P8=@utS{{mqZRcNb<)x!Qm(;`n^g@~jb5BO# znA_dc74~{`!j+eF@QJ~{>UPEi@g`y!Jnk=BX2628bl$c)em9Fy8~%;>YA3TUG4kj= zRPO_c2UX+$*F4O4=jSakiFrI{yS7MbB7g(iT=%Hm!pICmr$BqlT~2tW?05~MV8=q} zuosI-bRt?kb^q%waBNm_T(vd}%G_V9C2kgUxwks&dLeipd}BYkO|oCD*J7?)a`tlS zxC=mD97`C z&6W5_r^-S5p@9ivki;CXD4P_d!%n9zeWET*rD?}zLoSm+tP?i!umH3r9x+}A3hamr zaLYM==>PQV+y`{FH8jl1=wfdD4mI0uP@SM+0pRSf{eMYG$P~+o##c*uWN5#aG&7M}= zW1+EZ8q_ z9sKFq@tNbLEB8qm*CMCpZM-HwMJRRj=qYAmGZ4WY^ckj4qc*9rOPuqX2MHD)G>t;1 z`sEA3*L*bF7R`;eYivFXU^YMP?(>~Zbe;3>69yR3!lFg1N@GC>_|&o4T4xRmTpEmO z?e@&d^v9%o#Tg>~L_X{-z}>!0J#I)}TV*Tn7pS2leq~ySDMQ!)r9k9IkAtoiNpO;t!f2UM9W){9=VPo0r7|tb9mE0u@cW#)ZLAPl zaG{@#N@a#hDYY?1rz*J-2^2Me^+qlWq}N-h{fgYx)C4aroxpOs5L64O#Q5uz7sRT z=co|5SglRI$|jR%=E!YQ>f#gqIfj3`gcG0_J`1zOc+qsANqpefWA39@R=|1M{48;k zqZN%oy?#;%&of-sPCT$sMC)VSb-W|kClMTtMQ>XtY$R(w$`4LM97xAtlJEFjSX$nR z4L!m7ZCI_i%{1xAv{yR=y|gHSHlNtWwHtFFfqmF3BhoRIsj!l&R^6V|hEl!vqhxJ1 zE^2I;4$2aAr_DumpGhKxmg$j6G*6rg`;b;}L!pk8*!x{&4jONEWq7!;5z)U?Q~yu_ zk2AqKGNRF~kiv)gzP#9;Q=fdS)RM%WTRYM}kQbzW;1REvwULj?!FWbcR0Zd{U#p}a z2Li4FjNnUrA9`MRcsXiyJc-ahlH>e7CW->z9kbN-n}Wt(BfKQw7(;a{`cYCDLvO7Z>XfN zBku`#hQ5i(w;%ELV8(E)DQ%w^{m)2WiJ}|g9Nyy`_Fi7Hb_n05-=Ap#kH(9G5#t0` zit|`S&5J6?o;inVI_8@kYX!|_Yzf+Xi)zu_<-`j{E`2)B<0C!&rTIvgk3T(%ODs4;H{R#qNo4+Z;zt$}JM-}ED%7P7);=RUIt z&|divq2y-{Xia1J>PRQKm81)5rSS2)-MGe|+?yz_(O9;&bf$UR-~6vNMZV5hU%Au0N>CSKNL9m{mFSo5jVjXOMM)GTZ;x>3OrrZrCy@8| z^Pq}tQ3BgDq*V&56BnjRF?Q1kYBjm1y8EgT{&wC?MSOD8Z}x>q}so72c{QZjz z{;))1`>Te-3T?!{zyIgSsq{~OROfONRI{_2j27ctz1U&ia#5x0u;kKwWkfaT^I&Hg zIGD@bS%Mh+&RZ=_jHGg*?4fp8hvGViKJ5@Eqe>V-wU8fCKdXo37z|G_mp_iXskoaE zb0H`&b)4p~Bj++Xs2>Pow_ANlmQXShT9KKJRO+arL*V`+NEojGN)T(_3-NB)}0 z)EE~mBP=D3%}&Nz0Hs+y{oR&}xA(a0r>;SOOXIl@EFu64p=cz6zcfUe8n(8@zBy(y zP2xqT4w>{Ft!A)r1CT{l_$}QSG}~~Da~aP*Pz&F>eLO*yCq(E|u2{ow(GO|J zX|_9RrzYprLQ2a-ish`r*(0v7XRA2!pvUTD@NqbhC#`oz+oSRB8kw*Ua?GBue4JeN z%Ucp`dEV91UzXo%ob(&=5t?p}ZeZ73?Dx{Z3u#CHqf-k1ZT#kzWioY&Ley66C(7h? zgu9+tqKt~J@#G)q&+3{GE~X@r$?1z)vem~1L~CJKHrh4IgQckp1HWKQ2UwNlh6P5f zSErU1ic)B+Hwo1@*Tzh=i}^N>f92YhH04#`sx6d*br$)I@G*z=1=v@Ph!(BLolcgR zGm4F8-9t;iEBN)8uH470&Xr);2yGEMA5=wd1A*|Tsr$|dbk}eH+;$>&BX28mPb7jv zXmjr&pWgdUUQ~fZ#-Qft`9}6ygee;1jc%7r#2CKo+n)QAhneL76p;rWkxA0Wf_L)V_wIY= z`=1Fn#{#)7y`pNz&I;k#U~)=Xc00e*Y&6|E%#Gl{;PwCvIbX z@*-m4tgTTY-o}Yc3}8)%)4_6xGVbAYXC9*#j(xfNGIL?7?=H0&Sw1299r#!9Qp_`hO_*(4Gc1a$XaX|j4=i(`xNL4J#ndr) zon@Ycj$1~t%P9JF3&R|DkurVlrJ+uo5oO+jj1Nob1o2LZw%=QIjxM2?)&sG75&I;3 zT|Eiu%0@mauETbsa9}X!bN`f|S86aC=_((Squ#qU_NZ^Kz_t8T<9TUj?kJ5`lQu?-RFKO?&QMb-O3 zKGX^{DmD4#t?si<{{9Np?8#z0cE7gcDlGTIlw@)|m3+RTnw{+OPwp<-cy6^$ErteG&Oa4J5VBBvrC<7V%Rn zVqg=JVH?EaAY(PYb_*c)!+}GMConvoM5$a!CEk{?>?<`y0fSkW!;b}PD3Cy>r>Heu z*Otrq57sGdy99}G-*;ygPo904G%+-e1r;#z?jiB8Mpwnx$R?d@IcQU2m5HoHCN&k3 zkHh6&jUR*?JsnEi1|6AaD$4ECqVBCXD;}4GivG~oEFNz-e2B<1qb`nRvmO$V!(8~N z5v?baw^W!|IzPt8soAzP$$NKfE1;KLM9%B$s3Y~;?3fnTI`1HqEe!uf&P0ZJo)umE z?~7?=c9Y%`eiK&Bp4@1;xpSWm$EsEuEh2j*m+F@kbGZ&atQDP#xV}1aZW5kY%Bh0v zGdOk}L9dtwJ^SW)-e&&vsxQTDV(3u|tB7k-i;w-Kdi6>NZ_ddN>H-&IMG$mcvuOFN zo#y=05|Vg?{K&C~o-QVIWeImsEYx)0_x}jag89ovrYb#$%g5I|i7W8M##G<4t6x9k z3LrOOzm};>nc?&Y-S>in`be0|=wd&V8MqWj2w_poYj_b!QD-;M#j3;f&-hIwLyR6!Ns`4H2c%y#mwgBjAecRXOo!3KnQrPy}-4mZ)uS9m&yHD32F3{f5 zJ6?NNPc0tuYhDnA0XN9N%ILE1;r&(G`?$wdh{%O;_vN`CmVS(&-#xeCC63|ODoPNH z3PH(uxYXA%I}Wsa#UFv*st7Mn5_eK>B$w+Uoq5Y$ii%-}_EwM? zFw?i;<>R9SCpt~C-Yt}84%>B*eO3I3RCfuz?I>zY#BO?A2E+QpBG(I5uE>l$4WkSe zi~=i(GesoFRd!U#BgK`H0pFc>O7Xn;S@)|9ZWhnr48yD-Mh}+-;KX?KH`{i&WTC*W zyv)kZRjNnNr;Poc0%u~`r#7e6tLE;fXbZLEEh8N`t`UDRW?r3y!VP#YbzzcT)vrsgKvpx3+u%G?4OMhS;fs#iw2gB_4SI zHESQ6`!|qrSo`kzHOuK4^h9D^1u){^m-*^JZC)HbDZv=ewXa+xejX*i?Jo5?m_b`xv|P2q`exkC#{N)5tnzn|mvPx4L}Np3%sZ=D$E|%^d@+?f)$%VPzY0NYi>&4R!v*@_Q?zOKrEJ&k43*=3MdLJNp#dJ7yzG3=D& zVg17%646;?M}LQZE)J85*PS@Tu1t01Wfy=SQ{DW|LkgO|lV@D_HN3h^#uUS5 zra2F$6lM|t^nT8%{ZWb$xoNKz;xL@(F|r%x0TJB$VP%^;C+kO!@7tnJ+uYl!WbX>Q zLyLpKFGj)8XjwUX`#es0!ozi1V(Me~Xk%ebznQVgmq#96f0~^52mfh+($BzT@VN?D zfeaa6E=Mt|Xv?y^8th)eJ$m==q0OJDxpN^)f~<2udq)-`FHhb#yKi*^O0D^Uvw+=Z z0$6ROu+LsSD8bJvuX_D=Dgi{cTU46e6D_2SfdePOuLZ&B<+d34ni9Lwq2tPiIlda1 ze`)zo5_iv&9+Cfe(!jZuG)&y~ZoT$g8)&^uHl-x}&sg`rls7o0QG`;8-n>#bz~L;@ zzLxBCd|Ghl=}Vioc=T;x5=uxtsM9kjchYiu4H|d{IhxGrIBf<%dbOF%-89|>{Usw| zT;XdRZ#f4)V8Q8#y+vxC8|urA&JD4D(N!HC%~}PKz)u|^o_N4BZCq9Hi(8GdNU+K%w6?1Cq{8ueMOM9?kB%M|6QcHqQ*b&=ynaxZd!ZmZj}h%W&VnmbhS zv~1qpoUG=Y%;|(m>awhqa!-$3u~Un?F#oWxg|WYTcGGSy*QTeTz-n5Ij68*+j5J%L zGN+~K=x@NLagxVSCq(CH5${$1S%m^Nr}Pkqhp;Cc6wpeCL*fCtUurhwUDVHVevOMh zac&mTmE{{^y{OUiR8=>BLrs+sWKhi*VZVKoCA{lK9b&ZRiCXOZ=_LByHC;a)pEaW0 z5kaYtG8}#VA6$H!&`qNEWynJ?hsm{-$>d4E>wHDlO(A;83q6Exr=+EzRjaYXpuzhEV*qUc zW2ZI~uNdBQ`l!uQST?IS6-90pr@9XIia(H*kAXzqkZmNNi?&sl<3wZk0!Tg#x(m&L zRmMf(M*y|(ROz-e9E`Zbi}A461hpmXiHY@QYk7-W$<&Ox@STW_N1DLt3+ z@(37fOkh{(f-fl+J+~dGOzZ~9(}s3IPpj38N)z}{V`u(*rX46WHH@o@wY{Fty~m@7 zth!o6QQvP!Ig)E;gVh-mTJRSrv8y1l&x#;0g4eJ6+gH|zR4xYVHqEg=b;G(d3S)@o z=aN4OYdf+g@_S{=V~qPZN;&qOkX9VR0Rt@_i4Ld%-+d4G?k*q6~AvQ7e0 z1nR=lIJYeWuo^XZo3cQ@Y?3NAJojH~lkL^++*uFx(QBUeCFBno-LU>(}R zO-~SuxN$d5qrD<9R9Z=?&=V>UfxIXZ4QV%WJvp$|Whhg&sRRU(A){_`n;x1WK?PR} z7QkmmvdlcX=pFmjP{>pDk1yGbOSFBgt0VQjS5tFoRQDbC{LXHrCCYFAceeScxL@`V zI7lq2BcGkFi_)eIsWEH?3TL(Fy$b@PzJ2(q$j2Zu&nZV2mDxh^SDk|tnY|1AGndlb zwN?_lulfY~B0T4Lk?Pxj+%jNo{(Q=-@SK~2byH$inY&t;S((7CkZjS7wJfc?vsz`z zuKT7G@kNhwLCVkrnh4(UC(&Fo+;#Fqsw-dw5t6c0`GBq#BqBJH00;0&rdGrmvDg%= zigFS1qso)5`b@0Ql!-RCLR-b7ni7Ba14vz&Z>u1b?xH{HQnmAII7JBf93!pY5sMHc z$uOvZTiwFJPW1!~)!~bCaO`Wu2(0ANHj&{-iBdhEkc^hpN)->^?@F@0CT{xw1dbp+ zdd2W%uC+mfeyJB}B8n?zQ_v~m#CunVx5!`bg;ZOnj?Q~Pg8T__E&ur(p14#-bR?9> zKP3IsrHQ@w=fb3-L5g^kMjfT!+QyAoGVxtoGI+3xtVYZkA<*5)45w*LjBDyoS`iOF zy;d#4tnpzv#XIyVDTTVbp_w=LFjPd}xY_z{G07f(!ukBSrr9zl5(f`)0{xMOtw`;J zzPl-9J_zF?wlp6sx^^U)T+sG+P=1D3dESB`ak55)%F0*|0=fY zSyXCW;#SuIsyg+XC?6Rg^%2zNLPh8lV|V4HsUA>YV{s(18`dGJ+VTjvGRoyf-Fn~q zb?-)FX7+NIms^JCZJbR_-@CMeKYJzqB-Z*5`Br*@9FeX?zU*7 zsGjP-|8~>Ru{czj>lRc+1XT~n5nzpJ zZ2gqtHxiho8Q?%UhB%r=g9Ku1e-I=GS>@1Pj9x@uca* zsnG`2sq@gzr-?B7v|}T zqgsNCOh`4yXO&k$2c_bC>BXzkIFZ0|Azc3B4qHtFBml)t%ceDra zF@9YGQ&y7~qGB5^u_mY1ZC9wN?;?*F*WZdSNM!Ji755V>8VRZi6erwAc%ZI?12K6k zuWHlDt7VPG-;|ox^ioncQkJZL`CGq^%QR5^pILysSON2Rl>pH$uK;>k#@~cLNs0;5 zHD=UZwc{3QuUr~o*~I1af2%4i+!ZTJHfqLmIjdaxH<|!s*EHmT1qCK>4g;*?59pe& zUUIwopLf6eG%`iTjdRD*Ap48F>U;o_s=qz?At`;vWE>zRt_6P~fUu-ZIYkKbT4}4C z4hR`zXqiJ4w;dWC;VjS`CFK5)FmJFc{W!-_IEN&n{r1Kk+q#$g4+2`7t`!)vzY8 z?U(wFc~OT-KlsiBSwyL#w&CTiQU}t+|KB}(5sOArdt_EaENPrDd zj5coVh>SdJ&HO)5xH9!ILbz@i)$~u)U6k$S)zu%hpRGyobPU9=p^4-?OXD-_5VeWT zJquO@;@st1wbek=l&WJXfA)bgjAMVqM^w|3aR&iYUb_dEoi2f8Q!$#bi8cky%I5=~%(v0%-(Phz z@SZu+l&qMurIu1-O-IOAlo>6f_;L_7vSBrlQc>FQ9gs)Re*!oWqA(@L_`}6##2Klq zC?j!|6ecsa>sRB?HRUwbIl8L~m>jY0`t`$-LTYN57$fm^@AO_FO=R>r(GMZ;``?F4 z2w0|y601_(w#P}EfylyUGc#=or{)eKH~W|3oZQbxwu@T7oTkz*Q=RI60N_ldTJcj> zR)%oxvAUpK8jrPle&8jkgXD4(>Iw;b}P8+XeW6-3p zrN)|EHxfZtJWty8NAGVhx{OV>om)<8&JO{DFa60Jj;`e{kO{_}Fdd&`67Wdm^iT(~ zuNXYM9hCD-dY&EhaMAW|ucOuE$NjrLi+x?*hu3Tqe2P<>rR$<=8~^yz(8L7h^smOv zr3w;O){IYF)oy(7L6pe5Z}}$#k!F;LNP)X8yWr2!YITETqTPq@Z&41sg7V4$HK_qW zwp()_V&3%EOUs{?cAmsC_?%^^cG+?I=sIxAA$Q*=4&8qJSPAku9Z*LL+zy2>^K08z z-vG&0g*nLe>eLcS*x4Hjc?HXehLRb%U&_8AX4`R&t;HC!;-}HoxaOl9#p0{y7=AAA zHM;N@koorjg`GzhuZ>|^3#CKgPLUA`pC0p3ErnB|j$+QK8`t*DiSHzju|fkDR7u0s zr3Y=nM5|N1R7?ndYmGefGey?;tk6$u43aEOdP3NI{X@JXfKJaq)m16JdERYUF63Z= zJo`OYvmZCi8-obBr*-*DLQL-u#4h*}2COH)X#DxD2YvDi`8Jp)J13*qjeqv-Zr||l z-KmF*4HQd^aE8ik3KUkzDd?5d8IRZp@C9)?*!6s(s!YWvJZh__v}lai|K8(Mg{#JB z8PUYTuftbi8xhsvX8%UC(#&r!twkj?e#w5oJ-9Hy8YsMegK|pkic)^?>&=IM_i*{i zE*AeeUR$MWnIIhnVzfv%RnmYHVfa3yDqLo?i05J)*95G=hqYU`fY59)RQ;3Wf6EgR znJ%1h^eR6(b;rLsm4YY-?Z@ZzE@u_5U(Ukm?(>Ju%@`}_Fk+8$yy`*_l|Y5xuW+k_ zx?Fho4HUjoMKhVIC!uJ`nKUJHbyg0LiHr+%1=ym5=df?JMv3f4?=qUl8#>kl^lTHo z31!4rZ61`N#`v61!}xIm;M2fA4@Lh#u4ts;r#5|^p4gJnoB!1=f&6;)f%06$o{7PP zyX!-^t4g2V#C~Y@9!v0MkFzmBg z%Dms$4TQ)a)m5y90i4s9 zWkP>^Sja%t?JW?(BsXu$`YStyRqB)%y}Rm;TA*wdfc0&%GS58-4II3LH(OMGKG&BXA4dpZ>KT*7qi}E@7D~Y zVPMz>z+BcGn&^sMh{x=A{-)HYpC^VBbigM%*14%1IB|Kqq~ad*j@{wh_fyyZ{s6Kg z4o9}f1X~WG0t6i0z@Io(JtkL>jU4k#Jm+Yw9e0GP4o~b zS{GsKG(OBfdx1fPpB+)W6VbIMxq17%#!w}7H%QxS`^9tmuvq)J3;SGB7F)B*F#)sv zT`XM1f~GV2F4A#>3o^8iamRy449kbnNC9m)?>=Tr+Kp-Q_h#%QS((}eH zvrSrW*8V=eSKXI6r6(vzNW8PeJ@eW>ycOW1EP0wEn^Jp$7j_S-VlhI#-F$!U46W`N zmn6l~!|bf~-PZ_-{Lp!_n*PGWgjT~9cQDw#U$<9lE5=!lE0kzn#PxkU4BLh2`HPm3 z0zMaW@2Cbxd*Rt&W@;<2SpTQehCWh{p$(8mIgU-NW4<~MC@miE^Ae61o?pVZ$|%J^ z{^r5q%6PybJDYVn2%qY&*a)yd=fqKATs7WSiWWn&$jSNx-!7&k%b4YL6{+p-wje-w z4C!CUz=tFS-IfS-J`ipfn{EADUK|9C7>|kP^=k_EcbW(KB_^Q^XSw2P$0f=nk-50J z4P{}f>;~dC>Na$dOf8=;C4T(xqVB)MZVtQu;iVq}`WlYji|c=kdmP%mig=xDct;#~ zuNjzK4ccCHYZll$33@*13 zoQM*Z!LymlWlGu-PaAxJ&(nc}HxwuhXW&&OC}P=f!X4~GH*jx1Ft&Uoy^BXkD&+UG z*`Qg(=;m~gYD~y2$Zs|ow$jDTOPrJoPX~{?h@vb7ozihr@xEA&i#g#Rl^+;?oV$uD zf@~yaS#r`P0jnv{0fl|A4TCWd|MqAF#*N33t$)kc?Tx5J*Bdlb%_iXhDXYd!Zf_B zVNsm-(j84hPCA6}dQh~{@HclUhx$>Ig2~AzvERnlTE4}V>!Z?ytrk%=+QbQ;Zzic}bNS zD3kj#li6<%-;d->H%%`8_7ohyAM=RZZ%hST;RT~R3yh?c-BM&5KHHJ8AEL?uYv6^FNS_8)j(IrbxlUkRH+T&M@5H$b4&O;n9*PJnjW| zxAtR5fmr(ksl5j&Agft5%rs#CUrWcDQ%5w(8jAmlH40lFcpE6(c4!@ZfARze!C^yY ztoZr)D@uQQaY3Hi$BvF@+7K&1T%;mCkhkA_V7KOH({DP5xDszd>vJgct$+)-=DTD* ze{vVJw*~&BheUP8;YKQM&-?~S$(HP+Zs*8(MS_#G^R%JAL$<^;67ce zA5=Zuc=jWfQP!z=?&fIf>fX;5^j=35#(T@WJ7dt%(UAnFsK;amJ{Y=LZvvSl>E&5#EY&mS zI(Vr;>b`UQk|FzfLiIs^nI`*>FrER0w8Y7viY42Ak$xj7p2zpQ67A1`BMV!jFun}t zx4%)_+$cM~;uhZ}gCB>uJ^#|-5Y$wy=HVa@&j)fmxx3=2L*yZSQ-B@PeqULs-a zjpB*K;pGRXw4a?uh0MKdJ*Z3J7+NR`J#4u{ymsdC_#hwfNgucKC9e{fV80E-Miov}Or+Y#u2KvT0gmGFd?tL~h11SG?c%qLFA*S)-n zWhBGf9a9YP6=(&LbW0>7yrDrH#&r>+gvB@2m@^T9@#(222^QNRR{-(OBo=O6S$g&( z)Gy99nhaVV-sb`gBCgj9KWm5~YMRqw($@uIfQb_m!j)9L8z!koXa4cJVn{ zH*7e0bg!&1m5c^IlJk>%JwekNBRs62UW%W!D}Xs?)Q(t_h@QV@V~M2s!^!f~EP;-@$YzuDM^#PZSOJm!<#HS z>7}9J*0{mcg@N_Ra;!dPU_*NwpO$|c=X#oWhGaBL%^gGT)sCcO6=v_8ZL?#W(8udd zz-1WOVc5V8lkZ*xUZeK13G7R`UZ>Y{LG|D8^qYW>sZwLEw2jB_xdXe?8^S`~jYcBq zgK+A{0tRi3n-{VSP5N!jKc?tr&t_z|cB`u&@3Q2wVz{f}ZqA5iii&LqWs82t^GvF( zX6n&hnY|%@OOk-d4-S^s<_*eU|?;+5d={U?0 z9N<(b7=rmo3jQ)yNhKy#7xUvHb<|HvUhbwmZw#LG2gwT2n818zr0bTML*XR+*pe5j z88x0(skg$MzsQO2zb)Z|yt&=IilFm~r_tbBChn{Bi*J&(m#2GFDXa;Sg}e>060i?k+EUh+wOoT7n@zRa8`)A=m$PCl*i{he-kLqr&WtqpW8yp% z$kqNUeSpc(v0c{XkkQb{ksy-P8Hg(tpW&*A94HPHkkX7D6I3J^Q{_qO`$mlv!P%DE zZo-oxWSPK-exyi@+Qcb}Y76bb^4Vof9T~Dko|Nvvd&)nlZx1RERj&8^l`QA$*uf)417P9nlc z@bc08aNN{x^bojfjp8pfEbJY`Wvxyv6oBR<2Ay9FIjM<6DkbWdHnRp4k4h8=a7XNlmxGxELZo*&#V zGpX(fb4_-FL=5!57k+?J2Q2qqp2xrP-4xA`jL<2VBvw@vJ_z~ zpE1;>eAvQH1~QAfC$)Yh;(O`-EQ!W@AVeDJ6G55(O$sb4IAj0(8%H4VYd6Td%%ZEG zZ}gqDX~YEa<>h6|dpB^)?H<{+xTsCCsk|K{9L1%cp;jAfrlleUjR z+DMTAO#(NhVc=oCxsY6bW&h88-T8;Ec??bF|9JVp$FGf#UWzwvfGEEp+~ZVcYk&W= z2}|+(6Jk=*;#Na?m*e$zy-e4}VA+9P2zIu*8qu;5zFM&EE|k2TS2qY1HVnpWbIw0q zD#YdMXFR69#&wT6y*0L3Ew>PQl(<_6h^ZVwevVuDayM&T>g z7ZNF13UOYp!V>tUcI3$6>Pwer|e__lv-oW zUx+dl1512k3aWRoG}B`$8}W_1LB(NU&aAG&3xqOOdM2f_Ok&zjwCrXb3g{0&>Kwu?cWo% zs&9dgNO^LMToU>rxEPb;^aL<)pKR6CO~8D7CIuD^C*cS7R;+Uwd4n0`MR%)6Fvzj( z{Nlbd%iBf}I8%9j!<F(h=+mW!EK8SHBh;7jqi{JjcEb4RRQ#nZqQ7$%IK((W_Yw7ZU4LP)hKDcc(@+WJ za+O%vQmDAcxoTKyC_t`>SGU(s6ujE~Lcg2J{8R^IkX&c<*G6{WhW=| z+t$1$iW+uN33QnRg@QdXyj0FzmLlz*kbqUcs(>zr42N3kVml9fOu=}D0Q(Ay=H8G$ zunnH3(m*1gj$0`#QG!AvIsv&iw}awgCrd2R|ML_5FhN{2x0Kop%%-Me93DFh6HwCz zN8<^xjHQiUCP;d(+t2QibnBQhyXc&W4B`hnj!Hceb{P{z6s~UY>6>o?clm zz@EbVn}IqGM-}2V_b_>~jSxo90hM2vNYiADV2w?fOe{RqZ|XRNH6$07QVbhv_2br{ z(BZ=F#R!3W`V+i!%f?-H?GqcJRuSC`W~?d2bnoHZ*y8*51lNoIpq)tsLRUvbww9o-r#NZ$Yz;9ovJ) z$9|1g7o71Xe*Zs4Op?&HH5stv;(LOV%1xV^TC$(qos&|*q5exu=uzykeZ`{N-HTMR zqEUGGZFYymSg>A{P6KkI-i0F*Xv*SUFQ(= zt!=79spVtRzpb?X;*JmTmF9R~mh5>bZjt`+z0fg?Pzy8SY9Q0)`Btv~!?`aEZpV#{ z1tkhjqZCWA9PZXU0hj;lXEu%NWr(>$<{38FfH_@VOb|Kb|+E7B2-X_HX5j?bJ z!tV`n;nodvJgiD@3sbG>|FDYT$SiL|@;_$hi%a~83jNKf?bId+oP`$xsO`(AOT3iD z$@j!IQ&dWo)HU#Cv{SLNGpz7%uC-R9!yFmrmO{Yv$X_(Lh#EphOK3`#T z^Q37`kz_2VFUOV&!DF4?4gXSfxnU6@gBTJ^Rr(`qEOKiHAPxv=@yufD@f{V2IxWV6 z#w>!#cu2MhC`Iq0O{6s3PPO8Pd$9Y{qP7AxV@v%Yaj83eG3X!>w~b*t763z0+x!G z3Z1}caIMCXa^(?0s6QT%KaQcu_C?eMEYXSe%jR5Hn;#0 zTbnvsB|zZYrRd0!5|$Oui}ElqW-{gViPF@z@`R(*wv&@CzZMo2D8o1)o{=;Parl*$ z75rs;Y^kpet4N4i7Ea_r{(Z)c1Cq?OIVX%3yBON;*AB|suT8z0U7X<8r$PBYVKd zyaJg<_P+i%pRv((lX1CLe5y>WOC0s*=^@R{U!mjUtUIy6=(LS;#_P z*T#mC4;N8;%B-%HE9S05=|g$R=Azve2dWkc$2&IdL`Cz#C<7+DQI&tZvyqyNH(Z2{ zoReB@tMaml+wL>dT^vc;hT0naVqWG`!$9)1dN};BJJ=1@*je))cSg^{X>h@1KuO7@ zM;Icag_GfyN=U_YX2CqQV(=d&6%^F*{nusPbu%ldYh+Z0r4GmW+n_aeeP?IP!o?}p zJ+i%tTOhuz+}7t`*9kr?)c#CXfFn#DmIt;h;EIrU(|m{4I24VyNgZ}MIF*{)ljPU0 zdbGOQTJxEB$RkY7sDl+qv%b*D{=R{@sl`9WfLCYUmYo2FbvSW_*XJZ!3;BI{W#`7i zZB|WdxfpHwBm;Dirfj<-SKB9^R+v6^o)t8=m=nu=w)8u)nR$@^{@!cBk0@C)qlkGU zQA|s->?_EP!+O~>3_ZDAZWT>RXCA}#LHOhpjjR9m_JX_3N5z79#Y#&k2M#WSp;#%~gxC%BY|rlv(b?pkSJ%s)Vd%MS#i`j(S*CYcIy0pI}Sa z0~n`9(3=y7x1_ED@mjVb5pXW`jee5%Q$?ji7WXgxf)Nr;Y~!*R{v|=yJmT*L^QDD2 zgC;g5>c-e&CXL4CcTWHofJ=w)nMpXZgmetQmalcCDcA#EjF5+W4Bd8FiHDR1Mx8O) z&FsxkFD&iL9(0?BtWbH6_wOMM9Sx_(eVp%+x(Kz}0G993enL>67fgS7=u<`w;_xU_ z=5${?OVE>ELqiHOffzxV&_9}{MlQ-WIbzSnVm6^=K6q#s!agw3xF8f#g4u~pFy|GB zCK{VKU1O?pVDjTS_^6WI4b&R?E$yLEckoBqan^&^~vVpkyG3TuxDI)6oXzp`d64MRTiNzzjaXW*uX z><<;$8<)tjU`U{RKQkfM4fGzP!~hZVb+Uj|6A`?_&19+IH6!VlV?AE|w`c zI5?=TLhOtwRs^oZwW@VoKtXR*u<+7ZdPWAsDGjMi&#d^5YRw%zJyY_Sgpus`e9J*q z8WpPW;o88BjWM4nTuuj_*sx)VMQXE`5rkR}N!NJnQ2N9xR_5Px9UV#%_Q<}OYS^RV z3}<~N=pExRyHD->Mf@E#?JJAzD0-sSR-WOP>`YJ`_!S8H#vPW@h(Lsu1$o)n>Je@V z_a%LA=9WdaU#m~;?T&Iwt^UsBxh3@Gt^H#zo>nQ2^umRQl$$!UzT}YEsS3CQBi&v+ z^a+q&&MZH$?W>wpNBW`gtbZy%`iy)HL%q1Pw3czB{HqK`0uTA9eQLirw0fUyXx>?u zdq;Ce$2bI=L!J-A?TGVx8D150vsG~ldo{;p3$xtn7rY~69fo^MVeo8;j^F(lyRNE| zN$IxO(m5E;nsHHbX)-6QTg-E$1{;&ENQ<;Wz_S@WYlTDKfM(XOwzlEsSBc8y3Iq*L zFUJu3g+ij=KBxRsRyoRe4NXd7m_=rKGXQT*AXcy^fMy zKd#k{#Ce@{chl=kXu-~EX;k4m2JwB+2ZFj`*_?l6BzH)Lxk-&EF9eZkTbBbUAHp80`*n{tP{<^_WKUTZ=t$%NaZl_BNY{WF%CoJs_`^ zA>aD&hnr|HWg-RZHpX|ykXyt^JN&$B(s3xu_=DD+1KMjWd95h5Nx7Z7nWT1Q! zxjP*9JuKq;N?4mH^9DTg8S>EIm;54^Xsch|qvP{lro*0ZYO%-CNo&X;=0$*k+9~8^ z$ml0ovq@cVW*sn+QBhFR0AuoasL}f%EIRZclyy1Aw;Bat-b~Ub#-LE~4YJ&x@s`v6xcknPNv({F zmEXuyc{zt9PMJ|!ZQy|kgA)jq2K)YqW%Bcsf(gXn?DJ;yNii39bA=v8%kdXh;2YiN`d+_)>~n9^NY$`iuQq6E-GTgpIqmH6Nr~d^OpX2*g!1yzH8t>sPK3?eWvgH= zdq&i88Au9|9J+2v7<&;RIZmXHF#*`WszxhH@&j^el?QUQ*L7nz&LK3_UY;V>c_oeDl6q- zDaIKbS%8hxI|!}(FD-#k`%R6`U-x?>5ZgOZ2i91_{$V zBW`SN4ppz75^JkWY|O`s9M@@dCdVHb&Draq4$>m`3yZK{o1>Ihn_jLg5@j&MYp?Q= z*jyQLm2_nG++@#Hib+4dyi9HgKJaBV_Jb+IK4CL9wVJnv#7Ui*!}c=&DHYCYhq|MC z@wiSEoCXeXRS`TjTD%+QW=EN*_2l(d{}TV@5ZaIgVR#x@R5MWL_y`APNIkp~`hYpU zl15_=>X9cNu(m*M$+#xk+~4H)6#PN4(7Tf9^WM@JWXvu@@q& zqtUYe^pVpw>pp5{w92aXli8YCobJqc<#1#;sjATC~xDo)*l|Oqi93?fuPO)D7yX! zg!*2$1eM_H8^eGnOxIdHqJ&d4_1S!ZnPD{1t%Rv)`dQof(I?Yj=CYABM0=D!Ya&gv zE^BmC68UuxxFj&VjZX3&ho3evu861X`ggR8$mZT!x9^m}IBjP(>U(^44jNiA!adaHAFisa(_6!zMfsobL&R{DWaH@bd}s^^9091|GJU}O+Sh4 zDD?PzUSG%WaS3i@k;6jDt7m&^RmXG9D#WnkeEJczWl$i{(bvkiOZRsR!4 z^YprPLl4n|wC20u$k7~*+&aK*_BD-a_e#2YdTaiWrF^()HdyKRAhTCpW`%D4*B`Vj8TqYKX4z+bl zQ*KT@ciOZ0!g040A`q%G^j$+ZU?C(f&hi(|EGERz3@RH;-Dm?~9e@AxXli?&(_Y8X zKWK*Mim;1&CD_23>z(t^|IpV9*?Ir37=>&q7t_5kR{33xO3}1&VNd(zNeEg~=k_2(4}mkx)!VS!pL*LJv9nuz^jvy>wT9;DWfguUG8ZCQ zz15JT4wd5voG5MrP=4OI zjrcca!t9v;|L6~bk!jPYQmM`V(={ZXJ-qa~ol%m#{(3TEgj^8O^yC+35_=+$EObjV zxq41>{k(e0otq2k0drI07Y;jSak*YkKJ*HCX!EIdiUaS5a~x%$z(nC{MH?&&j<}oy zQFPan{oYr*h|E}9j*_ZSHx7ks7&CuhRvuPoxh-Bp64peIj<*kF?8J9JX55)PF6l&J z*4^}E6M_)H%bZ`_HN9e%bn)`YlnOdD)FO^fh;-vEaTN6Qc7~xitkJBx85a`mvL*EL z@;ZHZL0UG)woOdbk9WRWDWX&=O$hNqnbLjFPw zKfb}m*ySY8+x_44Ss{I`LbFg2hvzSb<-y$rubmOb*ab@32PU5y`kc(YNyh);bcI7J zndTR%0hIP0iUK{Rm=%l_|8SSe187#S6r4Egl!a=+j63<@pBt0W)QKs1UzEbff-|nY z>;C~wR4k@Z+PCcO?IrVIz*j+^_%;IOuIjLV?w-H#4N<^9b^0XXabkZCPy0%)s((-m zwdbk~$5S2Om{8~_)}cCw_|0l!&r&g`9MXPZy)d-WSJpGovpAWwLVd89?QR)l?4zfT z4P7rStSZWpD?h-^Krl?DivZzcP*N~5m!FpB%a(J_~_e_PB=++CPnFeesh zk%#7emz6O!YMi`7{b32QcWwIBh6M$O=kaJBrQ7Yxm073X>dnE~z#UA8j1g&8U)KFx zBv1Isi?dTL_MP4}Y@!mb6ur|4NG>F=;Nj6LTMA;L#P*^8Jv7UE+c#fOtrwz<mVG$Y-6-MpEA%YvSHx86ITx6|nI4&uwp7jWHqN49hJabsZEr2*!F^4e#M%cat>;_p|N8D@d&{8@+y2}zuOz&p6N)P z^_tag>&&uEn`3@lr8=kQXv>n0%ACp7@;xPL$8r!>>&h>#>KwCb?HAL!9po zKSHn}I%5Z3Dg|}ODPL_+ZuMDy(SR(aE~%1pbegE~s})P%hz}NL6^;*9`rD!c^L?cC zrz0LMwd9F#%?gJC0XfJ&STJz;#eNuLN8q`S)Os%e`0k;f)o^MyrnsKzCq@N=77-^1 ztvt$dm{hHpARZPVq@-b{7`GTIYa4!}s@OQ1^))AKAfM{Z5o5s9D6QP~6kTp;aPafM zW8A>6x%aaYF;I$L8y{r>;hdaJ0o+9*me5S-xd?ht~z1a~L6LvVMO zKyY_=x1fbP6z(pCQxJl?PyId9y=J=S?bcfNK2)vx&OK+JEeOOI7_lou&~iJTA3Ibj z9YCkmeeg#o*^xPFWSBy5;D%6P@u$vYf{)j2|ET(&w!!{kl2&P|^Uep-fCG|vm+eRl zoH&u^TV%gi*BRHt@eD{=R>~uFo)PkFXziFnp6MOU7rDXlsob%T7wSWM>)XFAb`o|@ zyB;n#+S~SfG}9Nh;?3|T^?5W2cnsejWnsD;$B|KcToQR>hLBGLAI4@1><4QBj@LIL zA4WHeS`Uv~B9B;gN`s%)h|9Y6Bc-2$=^UWYl8a0-%5%H?PzlU03|f|)OD{3ENmiFt z(pb6$2XrH53ri9c3>JJ;5)CyFNpXM2`~6#3z5St-3)-s_P;N?Nb}%vcjlko_;K!9_ z{{J@|-Xd>weDZ_)diO>x<1me#cvR$ljtaq*?wE<7!eWE~k`Q{s)vu!yudXo3}&h zN*9vff~^ifDYO1X;}9rnrVAN~n3YZuDseC|YP|G*-F;1POAJU=Th_yi_=<BaI9Q`+Y8(c~yCw5-wdd^Sqj|L>)rM@FNhOnWnt4>u4Tq6YQ z?eWr1J@X!*92`uI*YL)v%0bp7Jt`154i?ESOpdTKvgcL+3InWl%IALF zo1OKHsVT+QWo4JWMeb>M@9B}h4Cih8sE}y%j+&h^z0G<@UR>~S1F=P)2nSv#T!svSrz+QSha~-`LafH+BVr)NDU2mfXMeCbI z>l$JVmwBh+Hd!*R(tCWV^_iKR9^7v>iWU$$pUh4B+sr6@>E0EKp4)YZT41x zZE|0BZG8Jvy#)Z(Kc*eK=Vlgrr$(|WqSd`b6^&Q}j=a2v$tTr><}|U4;Z*Om%k2u< zw@Lhdf{jvDn>qQ4qCv&){xH2#Pd=&im~&7do}PF>F2>R8sJ+}fEM(US_GLV!3$r=Z z;vcX^!~Zw`(eb#qM#|+8kMMx%#(a^$Qg7cxUpg;?3i~%=P0cxZ4ux{=sT<;b-TV9d zZ!(R|(m6Hz*|=;1l=B$u*EQ9ojsb6{Pp@>nBc)r&T`q2scd6=+%gF^NG;F%IF2ufWR|RNyN6u6^QnkI?rBxHKj3Y(SITSR zRFq5%KGzOrGb}5tZLI+jfzKnjwUsA#;ndbWe>(H0eo{wLt9`%984~LH(mt=anu@jr^X^|Cw{8jwGqfq^>TT zfM2yFvn1cvr+w&|K=q3=u6z4#p_2qcICRcmB)v9aGzviw0N-(SQ{PODcrT~lG@|8T zFHB2Y(GmDaNXP8Wy4ndyrAb26`f4bNsF(*1zO=U;?;xL`DqBFboXMq53fV1CHb{}s zy(ulv|9LvZ-PCw6p&S@SuejRY8od}2yGuCTx?1(~VlSrnG3ZTaknAm7xuJneR3fXo z6aJtZ+g9jTK)!^Hg4qd>?erJalv_w8QbOL?Bf0t2bLg6R3>(Fu4#LcuYq{)x=+Yd5 zwNS0~TBlzsBowoup+|0klO89rEDmcBD%O#gS${_e&)rCVOCW^9s71!t0J3l zYg%QzxJ5!bDL~lV-y*bLkNO*ETUvsUL>dyq;E`u~5wwo)hwW^|=mW?pN|^OQQ=R_)=G4*jA7=v?oyX@YqDRiRF)L5>{emYku0+<(X=?C=JZA5wtMd|MKg5eg`8) zPt#a^*@3r`!Agq#R7s_iE;|>OY)8}>riX&~KC_f|7b?L`50^<}JXMKd|1;sRyYT%6 zWdNA{mOkpwGCOH}yUQU`@2!0A(9GNBOkv92WF`j!#psP6#^1N8$o$hkw2yv7W=^7u zV^7`cDI+^!l#0(@XtFtT7nW9#_n5l-`%`~C83v{^n0pX|1@rrFQ+k{0p9&y)IML~t z7*ez?I7{x8Hm5^EW&cB+fCJz;xE9Ugb@zftU&UYeI*h67suc@i$83i9j~)`c&dpmq zEaHpR4UEN&CN1iFxzXe2fPdk=`9KhQ1Ib`dc%h7p6^0i(m`%<&$TI)k_24hdru)lQ z&a}xV>Rd~g1(?PuriqaPpry#$7qjf9d6B^(oA=AH`UcO%OJ&eYw-w9N-+*!HUS|pQ zmRlb^{T}_RNW9*mNG!Sx#gUqOTCY+MKMT>317~;O*VCQBG4U|BSI2U zQO3Kg?NC5d`)GL*ht7|t49A#dhbYVQai>qiHcx?Lo+yL634+n9Yg=aauDRW`WnaG# z{Zdh6Sac8RxxcIzek>=>$~dwL|9I_v^!<`#X0`_5>%9P`xBfpQ%>Rdz`8W+>RAVWW zFHC2mKfiTRZG6ej&W-^>!hW<(TJ1+$P`nfSLzOj;2y@Z4LK`dORgX`oj;7=FKexY>{V1{O#PH$fJCU(vlPj;_ov}GX#4>wgtkBu z0jZY(IBtQ8t3RZP_A89yj5y_AAHpmj1mo|QoknCC2|h{Ei;9^$5r5(Jg+*t!uH7h}_z zt8AJ$a~}xs6Q$HcOJY}xl6Khe-N6lnZ||0Hbhb7G_;is zKjAvUws0NumRTBthNTk@>_ zd?~1_QI!0LtxCL~GtBp^7{xwls2$fl=FR{r0n+rqXuCn>sv!}_F)K$jQKZ)!Qj(Pw z2+jzg1WaIlo+tQvy< zLHf7bW!#0Uj56!C2axYmZQ$ER1^sSnF4L%tdJBsE279LBNxA=TS*f%`nbg^2#9smQ za8=n+Wnrxq=%n+DiROgXL|w3YJk6T1SalFfMhRKCuk`-8$YIiQ@GEdEG-VDlz66JE zQhW>%rA2u^co&TQ2UWld4-X7yG4#u;61z1(rpSKrbjwrNU3brq+6e-Cbqa(ym^$}n zi!dua#*H1Sus9q!xhkZrqM|AyJ7QG?aV9|tOeQhorc)$mv7W9k_28;|vyFHW0Vt`} z1eBOQZ+Sf}2=ZLZ6@7tj;;X1LolrMn#myLTqECPO&0YMICe^y4Rvby1ir+!iy313W zdcb{KQE=2Dg3%FI?(M^9s6M5zO4@d6WCYIWXX5qL`}MqEcj3LB_b66S;~|CkjYasekThP{i$~J@Pclb^v!tdd&M*kWFpofyhxh`rknY}l&BvDQXAa?q z7GyzR0tW$P0giZ8AyU5s)PPHa2d8(z*Jz_BAx5$*p6$D@q}`5v;UAAof=^H2r*5>s zsNSbzy}3Te_jhS;>+P#^GJmvq5pHAM!H+xTkBIX8z(~tH*BC?AhLa$w?ecV#N5}VS zGEnDzZTMYkzsqxO)B*bMIyR2Ss&v0@;?A3{00->FzJGH)cko!}lqi zo(n~BZ07fVRXLV_9zD55@&6k=|9^bEpuT^2@V*|SgWzw1*P~R(0~~Q?Uky4!m$Nt( zt+Rd?(aS7gmxj2Ps70N)MJ;DlRegf6X;8THG{e-QI_mIxvp>#qRB*&XyQZh#xy>C7 zwd%Nm>Dy~M@?yC&BWKEzY~A0CTEcINIQ@+4 zoeN~i0PEz|OY)P_+3xX%0JeLPLYT|K@#&@zXiTO|g`iQn;?KT@-_I(AD0C62pLQ)c=8J zzSu05-N2z1a0@4N9ndq%r_`9xue}7j3`euFX~?hW5{jN;v4&AcQu+I%%-+XuA!+t=lm=gd4Tl z%inXTyDz9aD^KmBMCg_ftbf8D(2Z8&ORhTj^7D|>JPK)5=mRM{y`Fuedql-%p1R1n zKMu0@_g1LFOdxEg{65&zzsv$!KHgl2H~Zl$bnq#(L8Ik6{g^rT;Wg-Mi~X$ibYX2o z6SnK5?#2sIwBT_~TKq`?~j8QkkVqZe*3*3 zs1*B!#pvZ4`8Aj9xf60a1+*UO_nfsYFJ(eka+jLQtJM*PHWY{HFwxaa6-Nhh>tAPB zwRo3L)3%pA!q9}#yP|KB*`{Sn7Kfa7Qr24~r7`4?Q?6tfR2b363jdUx4uUAmov6@Z z^!$#a_?wYoe9UBmzXb7u9)Ss3{Hm~j+*>h$ zk^j5=;&M>js1KieF8pmC&wWzr!*dy)ne zbY|pjN?uUT*vt>HY%(<86n|M0L&|z0Ed=_40FUr1_p@>dCmBrX_1}nZM;l2O#zF}~ z=(Wrfe{OQpS4JdbZ@b}6vd8F{7(_@|p$vOPRocMxlN8q3Lck$8Q46A+G?`kN{ZOf; zw#HI6h}cTSmSD)y^&za+_-l`Mp78s>&UQ_P7V^HMVFOUd@Y@C_OY#^D3vAZ3g#?5! zOR4OVgPo!%X$F&OEB;!CW+pM}G?QW35N)PkA+b;GMTX=>yiI#$8}t2i)=3pRks1-A z`T37aUPS+xng2u(@RS~yxwNzddm@ml)Jt>HX~hhM8-E9RArocOH53iWPfRa;zOPek zdzps+vwY1ea?eKUeSksgy}$>dM}$TWcTS5vt}3EMX4}ek|Fa_z%MGI(jxshPq9v7H z^H}mm1wEI&cpYu`4jjHA&KSAm@G(4%9QqT2y@7h9Qdl{Nrmz<;V>~w-WS~P=Bi~Gs zz$?MjlN&POE3U8IZh0SP{ucvtm3^AbbK2$;y46 z@v|5|yjfY@$p7YGIT|ntBi35aAUm1Tymr`M>)Ymt9Pq(I)3XJh@gj$I-J%5bJO^eyIJ+v{A=jgj4xI0)ClG_7XmSnE!Db< zSc(NC)l>PZKH%ZQ>|)EzZsPoTddBAr=)Kr^UhN3jvgh#tbe=f?$X1QX5x&7-LKCoO zei{E}&i-xe(?`s!G&Rgk0zT)rtT`E($ONed_Qao@)FGF@`$LC**^>+YYuy;}=*)ir zbv!KBR^6=o)~~!a+=JY!&b!a@cy|KtwHR~x-KW>;Tkdtsm;cj|1){0OJPmI@;cvh7 zKdApSPLAg9eeTRJU?bXWch4sK2oFpb3`%Qmr@sB5?mG9ofcgyg1^=6IU(o-$_y~GD zmKGWJ69y0C86Bi*8UBymi=}0Fx=}zTI6pA&KXt;I-3TPF2)@r3bVK^ztLDEw$la2b z_hmmk!$i`PpAtfFG#+bFicPJgy2pu2J9TIRLSx!2j+hEIZ1gbnh5vYw-HKYOoKDrU z?#Mn{(^?IkX6G416L1-+>=$zJI(;FS9Q&+0Q7OBw2!7jg$r&q0|!HI>_WBc-i+^mZq9UCvE+q z9V|QpiM)_NK$YMJL2_*V=+=527lyY%7Bik{o<5ymn6>$bW@+j0l1c?1H)idqZ-vcXy11bt_aLz$$EEs z|F*JkOAJv<)1UOLsK!AKj9$x)A~KV9f8*Y}LB17hZ1IIk+4FLjIAl8DHM_X}%t=X0 zQ_0B^=|*_#+rw*WU>(>RODqT9jGb|XyS4OA{Nak155J2{PigUpvAts7uMN<9hCrB%q!m$mfw6{r=A zhfZ0fTk7qS*~07STu8wm?3uV!HL{*{MP3zjisQpv0RcJ4YF zrcE?qE+L0Nk!u!X2^1mNh{iMabq#mXM=#o+9;1*t^t)HjKcwn?VF(meWzCX5SGUhIrR5buDwTVD*{xO=5S*Jb{V1(>cSD@h4 zquIZ6BwUX;GMtobUu_DV>7!$p$u?pRz3Ew141ZDSV1%&|q4hqS)}f7{IV3z|O}#j! zBN=E#`By2HQFp0I4t8oNSu7zGQe|rG=+RqS%-#n=%L^Vj&oGVUb-%dlFet@K`f5QNPAIZh=pGobykk zJ+FG-lefV;2MI*suEKX>!QV5sU}yotfqdSX|ujmuX5S40BAxY??Tq{eZ4@syCKs~CEN@kM5N z?$)vcceVB(Q%Gc=$7Napm>AEH>;dPSBgN+N)$PuRl%zSU(3bKaZI*V;dV30afKj1v z-^7!x_N@z!)BL4cuVN~+<;cPFi|-}($BVnVwmE3pU|-1xbF<{BGm@wxnXA|{-5ssJ z?+=IAgY|D6qOFEqO5|`U0g1L!k4lok+30tH%b)2$@zFjj5>0vC;AkyF(gI zl<@FyW_tx#=zej8Hcb@agt4r_WFiTI!U}p%YIU?u8oSum)l7$ms1Q}Y-TOvUXE4I9 z^Z^<{l#9aF$-3d`moOQ=;j^1_(r+W=IK)#9iMHYlJfoA`W#8z}BL0R-fe!9twRm;) z_pO|B&${LPo|Q#rZt^<^f1wFZCp-G$^=mc<_lP$3p+cviGk}|?UU3<5BxGQOB`8rt z3-nOqoO5%8?VF})^_zc8j$q5ABA8wnj0@C*(K))peN-`u%s6GwU=o=*=;wYa3*;}h z6xzy%rBrFYz@tM)iWNpsw4N?uoDwA@oo%69vx`fNg;_rEdL42{562L}uY9w=ikpYN zAf)VR=`<7ot_ru_ubh&ep33=Qs2e_;wjMx4V?~qS#+~j4h`eS5wr9#e{<-?S76*>j z62)m5^1~z1D1xDKG=k&?w@xVnI;-mMf?Mir>kPZc-`|DFo@c|o zo=?hORyq`7?q+&$uLsaKW}ZIrID(FN0&f6(S=&;7BTy>Y5AJKR#Qx~_@b5+&Ju>G% zE#l#)!(oxowmCe?yucD?!D&O^B$!Om%6Ct(7{h4v(e)y*8gzcAAlbe>2P6XY=&}8_ z%(Nc6MP3BS0`Fmk->%toYM$1C+XH1miL&j@?gru}^kL>q@()vJZ*LD*3nF)diuUaR zXP-#D6WrZx;RN50Jg?~hRQVs9T!w-@677iX%G@(bC6BQYJAi;Q&ovfquNjVu-3z~q z4Gh%x@QZDIo|0e zq#dtqdv95_w|o#67``X7@V7b=t!)VTb}%1N>_0$!0zP|}QAjxu=Y3n>+M|1)3x9MB z*eh=nj(^=0dBJ(_BzsX}zKs5uY3g!$$%s`Q47>t-2+#i->*Jecy#MfXGvfWlG zwsaNCH}z*|g&jLeSKKG9NhRJq9ig79^%dle22w2~J zF7qfk%-iLDjP)0^jKC>6op`S4cF$)S(8^nEix4IQ{t7zPK~d|{+3JuPjNd52BhJ=4 z`x+(JV&6Qmsd-DFj`OzDnGKsZ??A;Zg5n3B9$>NjH@|Z2>c4J*UKeW{8)m+qtZQlfD*#`E zm2RPnx64$FP9stSI6C`t8lgli(PnBK44Tina9s#66c}@~*GVb81o7aM)O|5Fi;F@b z(sj`Akj&DeMk{}d(*uSP&(KKW*f$@sKGVC9WWTYSy$scM$wCq$mtV9@3E4EP`Sgal zTSpbGGDK?2*2y(qzLKx)FF)UiJ6|SYqcxI>=tmo41YNOzPRiH^&s?H#E{oF^%*Fs| z=!DsgKz-^Q>x^DUw)w{3Yuad9o&Bh<8$9DBM_(|RKJP@7284bM;HK9qtIPHuT zeD->p2d3Mc$6xlG!h5;>71}>sx#T;ZWGQ`5~^yq5FMA6uUw)P_1h>0Vw#ZMuQ zPs@%L;5Eyu_I}yOQP-5|%jG8huaOi9w!g3oQphRS*0!mnDsbh~=s4ali^=w%ky(Qi z9uYLn8iXsW!jwYoa5;WZ)BI^ASmvRpnbny#?-;9Uh~eSJPp7%5IvP0>Z+&>kuyb&B z@tYi(<_-*Siv62)7@Uhj3mG%3igaqeQ6}b>yDIOcn0~S~$jVQZB6pr{(q9@vznr5G z>zfEt&EwbL)eK6TtdWdD9MyO=E&g}__&C5`vq^RqneSHwQ;d|e|c*OncXy@W~gUaJT;`%g?YxDsU z!VMV8U5gqXZ!%FMz238uDnuSR%s_~tqfu-b+CWT_aO3g#o~T?|g)~JgCGYX|+~sWt z4!W&5+nF=JcpRhmDx0h@#Ry2{*!JlziuLuX{HYF2_*W8j@BLv?>`97Pa5dP9ZzK#> zm6QG?A<@lluDHn3(KcKx#CEA5r0MtcR_U?Nh$u!tOJY@is|Ua;2nb5JalZ)2GWr;D zecde=o{@e(=AIGkp6Gqm>K!W~z8WIBha5te@%#7GYr8TD%k+g1D4A2tN@r74`Rjub+kWdD&*3s5s3^PEO`HumMM8 zSP=9P;8>UcJk{vQy{=H7_m~l2S44og8T?f4a|f=z)v!M20n`iu&gXH(FDD2`H|90y zMSyapzd9Qq-2&&35W|$dK7x(oIKgv-{c|7p`r3=mjo#%BItu~!+h@MKbMYX|V|~gJ z>d^>vsNArWDKN2QW}-#nPJdX0TH?-UZ562!_dO+VIu${` zY*o5am{j4cXL-u9CQPY?nEfY;rqp3o=d*Q`za2;G{Szt4F&hB1wm+U>S61UZ0fR;+ z?3v$kl_0}H|I4VKuu+rGIiXUsPMs%K@2UNUi9wEgUWWF}dw2fzeRE*mI*;e@r(EbR zERP|4ojS&~QX=qv>ZjFg($ zH^hW6ge1_VSWfz?-CoFd11uHLx;SlP#1Sz(z!>(}arP2+hHX{c0%Bgo6xk&joBO3u zLG_d;I5Fn2+@tBLGF`3%#o>yE%{;Qkt^lm=3i_0OpnK|vPK$_bujfN0GH$7c(U6N9 z7>97bfp#zg(JM9qiHdXl;PnYCGT}NCNUWm^dQIcm|Eln~(tE=^k-GPG@%-bfgOMnV zq8bWqn4{V}96AP=s)vSCfbR2!8m8hP*@fDOII$h|?!pFHEYo+gVT zB9PV4)INB3x>A{rQtUV0l8)-NvnT!vF?3RYJ(qqb`S7?3XO7ci=}(uLTxt}njyYDU z$gb+f6ZFn3j5Thlsyxlwks4K?LhvHPkCmGIf#c{sp-1o8suMXX==B#rQjLZtF!zXr z3Wu?*s8mvuEl)|C#kNduL%8yH)&JxIL?GuugcTezuD_0gM#Afg%CQ>p31WFxSJy_ysNqVd zOY+6jZ(ys3DM@_w=&{zXmVDzKJJrBx=;DNysptjR-y;{G>vr@^3HWobo_8hZ_%G^& z0(ACP@WmH6A;;M&1^RURc^Pm`C2~#m@BI889{v`~`{CtOyrY4Kho>@&bMC*$u^i^O zioXyk3VPHI42Jv^X*G0_?o4K2C;&z-f4A(0BUicLf{R+=ZY$PEYC&j2@g z8o=yY#9QT_bl}d*8s|4|6@a9QV`r83zhH(yH)=j%!QDu@ub0QL!$0%BW{v+R#r-UN zCpP66@Vp;!%@M=n(eBDg#|-w{c*)<5)skWW>p?fru0X}^es;Xyd`~lYA9j3$VtS(g zcuW@w7Rgip`^Bw)iK(;e?X$1G|KIG#{p}a5fQ$IvKD-{UWHka*#;LH>a7L6GlRJ8Jn9zcstElJ01F&0!yoH*bjW*~?_0=%*VU&@VkN)TUPMLs0+ z-Ud1$(5!xr)%&?;Acwkf1GJ9ES@tZa;s=`O1ML4BzW%@K_6{pDgu4so0|J4Ng9l;U zU4l5Wr&ib3_YMw9KKyNMt7lHnWOQup^M_A!%o?_K1=E#6noPSf3Nh%lY0aP&pTt6)ry7GX&d9PvS@>`X0|3PF3=QRZaA@zE_ z&eN(ZTtq}fmJu!mbnXK3YjOW#+3r{5<<=Zuy53x+-#w65w~D-^zj?eQtbZd_oJB}M zwEE1*6GI#M1-0L-8)%-m1Iq|Wb};|Ggv>=C> zz1C>AueE0}hb?aC4-Y9elZ{bH`8~J#jTEoz3bI50cO~t;pACwjkdBJs={`}^?{JHR z0Ql{(5}U_M`&;h8)DgOY0lh8F=RS2<*QeTa{zk}_I1%OCgx4vPj?cRR7m+ZYLa(gJ0T7F03eV~%F1}f2|So4bvL@AmQsk3GLs*nq&XC3^9_YC6?*#OcHxjfS1e61=kC_ z&tZw1eDPFrU|R!GG27C1svkvkGJ{?`Z1X)I0%I`j{&HlFk6!0cl0iYA zlBoG!Gt-$`>&FW5ncA8qpO_DTQW^G($PZv|mQYaR^1&rN(-tk!DYQEAbWtg@l}EDs zA;^Vv70QXv?pBC<9RB(x!(jL7X9tB?w#X+5rv2#eMG{hpu@M8*nmsNNf1%s0o00~y3LNt(V0!N=A&70Eb%)Q}jG#M#Qgv%N%U44_Yc^oNI4+ctw zx?)$g=`2r{F+>U0I(g|?5Wa`Vto5AGK{Tcw_s>`Q+^#D^u$oKXavj(ObpEseqGNvh zXg2YIjxsGlQ*r7H9$EUODBRN#TUtoX_LMkktxL(H^Yc@ioZzX=ZMtnNXQbizf{9& zkp^U_@g7mK=d&j2{AP>lXtZLuV%tOD>`%51L&sE>Ac{qR-jx&p!sN8bUe)W5U!g$7 ziXKohEdLUBn}cUVmjELMK4`m&NQd36bUwIAoY}Pe?KLwO+p~-1fZNvAFWV?eDQP@E zax2xS(wfgIP`aSHP=CMhe?U3&Uq=h97ug47`!zD}10gv1+V=KEYR^Z{@mGsXa1Ac9 zROX)T_Kicp3n1Wgp&>Sd%H{m z$7^z?e%`>HH*|Fvh=z-Vw-an`@WFVrWD zky(p<%*gj)P|(de9_`~k-xZ>)PG*=2o6z!ly^^L6>V5C$`6G5!X(e?9WKn-` z1rQuML{{hglf7bor+8qRjZuK2aKHw+s9ScaV^xRaF1*L#&sDCEO;gg4BLJm zrPG;AgQ;z61Po?>HL$2wFbd;Lr2Jv0%oR=O;fjXI%?t?nSYTnZU_F6q1&X%y@GwQ))2|H5-K6L{#^=G?rK z92?}1aKgOXW}w^M`P7u|N>1l&TErGMs75SI2a%|x&CM0`sF z=KE0*ZJ5O=qh>fLWX#}2eky}5#Sp`ELMUYuBQKTCpSU%kD_mi5F+&)w(Ue(W$fsC< zrC2vttWIh~DcDp=S+FPdJC>uYDk2{NP=xLYy#IxtV-!CnHbEIG8SimF#kJs*LYP}8 zw=Dm$zWYvn#J}rVf9lnvxGVyA2fb8=H!)Mqs2gz|EmHbIY~TC@#Wy>q-1yJzyQGUT z4!s6Snb2;-(4b_Oc%PBsH8ht51oE`{w~!zHlGVF|M2$4&TCUbs#3@6lWfGq&RWK>O zBgi+(wPZ{hhfwf2t(Rk$d$9C)z- zwc_T@+bqIbF}LX1sS@|I_R}4m+h+B<$RWaUsf`fth?sjGudDUwQDigo2#shOU74aA znA9k~tPTnyobD!@%i0u17;`;h=p5A@M>{)b@UnYJg6s(+$@e<)Is|9f{;Pj<{Ep{%aSy1Z?z`NmOw9i36)fM>| zg?$UcQ%n8McgA8_**r&xAm|Pk0`~|t<_&W>j@29yavUm6onia^iX1yPX z4x4TLr4ugC(7VzwcFu3tE~JOrK)Nq%_Z|EzM2ntE9ZgR z7#U*@iJHkX{X;xt`KY}pc| zJx|_ZYGc~>^pA^V+w&vDiWV&A&%4`Z4N+vYDCTUJZT)B;Q&a8NEmTdTgQ_FNDZtjH z6Kk_3Y@XvaG@A}8$pbeJow!@P4p<9^wWPhhz4dgQGSPU~G|}f)?Z#Ph1nkiTW}L1B zW<;m&nxi(7TyP|_yVW8yrvdS46=;7a59h#>1#ncSQZ4WwF7AEj{XzgYj27@<_G-C( zqfLm;cSvZP9iavry6oCDTV?U^dHWFr^m_3n8-(5{c^E^;RA9g35p+xJeRxZ+6W$H-qm5Q!aZZ10Y{zMTuwBft!-z`*cl#eFMMOrdeEXSK12f* zxpr*mgKg#t#%sD6G^)>0Y*|?Krkzy60$R|a67j5gFG*>z#Y#P1^Be=BM4k@vuTHWd zNfW4Ez_?xbo`+xNn4>aJYZIf($9AR0>52=Q{vZnzj{l=GzQhZK@HdJ)sW(BOa~3-R zK)*ZtGT#dL`N&&ofpgJ4Hzk_oNe3HNQ?sGHU3P)9n-ZwI5m*=9d%CQ&Yj4kvONuT0K83iv^Uil(!sApZaV~mWe;u$dQLaaN7rwv=6x;D zJx@nZwLd01#1Ec`O*9TlvIZ#|Ym^b@RrSKL(#F3!H#!)67E%pOdrXx{M9?LmfD0#Y z{@HX@!$RF`+jATJa=KU%lSFTaBu!0wSR|uUE;gDrdo9B-Pe_OSwHo3dZYX3V*b}BP%i$~|JxnZ+(rnG;zIRcdUV!)axp0Fc_0iK;#Y%_jAuD& z?kqwx)BctZ^cMKr>8hgqa`qN+>T57_zm#^M7*DTzXZ=D2ttJ_I`-o2-1jLfH&8Yq< z>F_01w;?I6-D%S!ZMaLUhEYttsR8h-Iz0wCO#F{anuP&}+V8gsJYKI8THsO$KGR>6 zcqSyjx=d;0RA4;aB0D9d;}cB?8RuS{#4`HEr@`+*}foS?n@j_-=F9of(qh5<`W@wwGq!paSOJum5ho=K?}WRMZ-YzTJ;_#J@D?Pko4>UXn^+ z21wqzMY(q9yW&}OQ6Wj%ft4@(>wolmZojdcb?mq~JTw5ZX-nES3ofg1=Ddq8{!K{+ z8X-_zvQe%ebxuDt{P-R4!4?!`S1v?g1bc24f+JyF@4&$3MX_LT|W0VN~jSpKF#cQM2EnLk>wcI>KI zn0e9*fb%&u{2#kcfB&HR6gTRK{_R@OdUo zT}(Mt!etEmfM|bxplxSTcm_RYQ;|Cgp`TwO#gzQRWISaewbC z?|9I?@?4a_V!1a%4D613YMI_Otgkf+zq32L8LCHT0PrNb8Z?MekFOeel&*_Kp{t0M z`Wlr&)Ziu*1wYb=)?J!nU|7aVi|}zWw68bk>=o+P7-1C8oTg0^nEz%yA0Y6sF`vTa zOQwyu+F9l>qw0j==n90;?wy(5yLWRKa=@lg}ptGcokkornoRd z-~lX}&?|X8$SX|C$Uk#rqsiP)o}RX52DWj=@;u7F<7E>NHJ>q`99c3t83c*Wy*fqNtG!~cZxl@62Z8oA#n@lK|GvSzY^dH$mB*PQlqB~%vk13#yPu79^Y?Q z>4z9T^o6w^k5-$Pl6+?8NwBsdz-aH! zF8P~^5UOT93D;%y%NBMAS{0EHqtb%X(>k65;c`gg9w~xyr?~hEg@V6C!Q3qotRQVB zSGwU1D^`ZUC>DWDOJx&3hQc<3UaEAzC5CQx++OXAQ)o?P$$f?WbTK1J9WbLzv5G7HyH(g}w z01F4WLSl<4e4;4dLtrg9sd5RIiX+u1VYNk(;~lW&eocI8G&dk7?+9{7S#XiF=trN^ z{e;?8nzaH`O3zcaioi`f^Du-7?;>d{U;7C*8ZIhi_$=y5DVUMF-&-OkBTrP(T(63I zB69hc8-49Y>}RWH&dAw1mUh{dN;{hEp-+$vpB-)%oD)on9=hEx;tS|36?nf4j<0l~ zWl$#tNC~pE?IE9%DH%i-V&Or*R4X4v-E-AK@7P;8)+VffCcN$N?y!tmYL!^AL=Ym>ym3vZ9q4nCgmZ2 z@Atb!Zron>76>t+N7 zNi`%n|E&GLrk%h2(DweQ`wn*^9=ipdnW1};VVo{6;)iNfRLF7z_~dL-#^=Puv8@f5 zX_xe4%B7upzI~d7ljve6-T-n`+c@ zU5i1s1EOyzr3AVfWy$wKr|-rF)DzU)Uby`n>XqnbN%3s7W+~}i-q$~BS|)#TICS~s zp26RH@0}?(06L>_v&vArd@d;gN`^zuAt2}`e~h&hJIl^RX^tN(ChmeprrpL|0(;MM z_DJMJj(6atL}^u|5*e}VQCmym_;I$WszL|G7!3Sm3Udkm;D{vYI>7+}&^0F$kN6^? z`0uDF!Dtw;3VRYp!aPs#W%t;S~2M4V=5CZrq=vZCd zJKAw$9?Cf3B|Q{i*n&(Q3+1(xe~v zpW96PYhS4w+VS+5D9vG&%A+<1A^4!IKv$>B5pwS(=%FVY&uHDUhgWK}CC0@u@@jFU z*As51nf_R#eJlJGQ<8c}qaf(`xiW;l&HXeXIT;HfGJa$8|6=PcW8!?HuHWK=6$Yoc zySux)6_?^(3Z=M1ad&qp4uce@6nA%bcQ1DC|4E*cJnwnGOdw1=@OU) zK~~DZ8Y)CA1IR={ztRd~#}{7MEqoazeAVl{=;+_Qlfk7JmMKtpI3F59tgfRA{LtOZ zxRj>2w7zUQi_s;eX5t);fw4fz107FbP)+)SP(de><*-`kYwhI3m(raY$==Jo@Qs+$ zGkg7oE>cdV8*Kd++p4lmY>2-Lj#9zN+xNTHgcD0qY?*JyP!U+#n1$T zkx!`$mG?()5=!Wkn5w^j3H+I8DWb0AAL~3aZZ2UK5IN0pHMd+r-7g&pm{!$F!Ns^l z8`ToZnIW74O@HLc#o6?zB383F2PtusV9=+fdo>CBpuIvgx~^u~C(=T>1Jo+e4ZfwF z0GBCDXM_$Ds|UHVS(K~=#>_E6K^$)lB3rnNt0SnJ4E@lNcTV)OcX>OwD230gP!xBF zA=^JP&dQ7u>X(@2QP5M8H5QaALn!Nz9btC=X=P*CJijjQK+GXFglO`DEgg-o%UDaX zbjMr<)8B+lN0U&E2?uM3ZR65f8j}pSwvucDQ#Xq)vuNE@9#k;F0PKSC2iO0M(G5PhIio4l8crLge z1mcI-qif$>R}5(|7s7XA%+H%<9NN4#{;528x{Zxj1TSy|ctT1e$;l4SgPih6LXmQFj{~2);O_c)O+`|aq(o3g)u;< z&u93~eB#NSS*OQTI}d4W>{$yu2gw>@b#KwlkaK%cV z+vr7&*0&!~y_&DE+R7KZYDY$X=N@SMHri7q#vI7h=@=P0{>ZY%FNUp=QkOrK(qipI z+hEtsA!162x>6Xu?wd)PIBn=Z1x?kPYA8;UO0n-L{fm5F+LU>!fN~Q&&oSQQej%_v zk!tkBNR4G5&0bBiX1=qHlLkG*tJy%CP9fPF2~wlZ|7LZFZ`@X;{M?%X{hou+IiISh z=GhBf%6+4UD_f=N-Y{IpjbR#nqfpsMyQQ8VIW0*zu3h=5@4H<@Ij2^KDJLD9M?W%4 z$KYFE#}991?|6{Iw-{23a!c^R=U<9jC!#y_%m(YFgcjcSF1fk{B4qGW0vA6&bk3dU z5Y@CH&%}tZVJt%@C4s&9aX@51_Pa9ucW7XH1x%SgS74J%Lli0IY^v*{kP=I`ixJ~l zgx+;cGNoo%%Ly9T@e+3od$y+7Sh}2}ZBVdmGb*sz|%Q7?>RP#^SHVxc>_SZr=2`SeiOcC%z z{}kmsPI}yXi`ckZSlBqolAvFk;27D1Y{gP6%v;0|bQE9Su=>c7$xc*uT}vMTEqN%_qD(cBLXEe|8a2vqlQE*Qb;dYvZxwb z%25;+!X6suJ^uTe4gAY?QkUn*KMtO?nKto8hMRg=RD!giu847&Fm#Yh{jn$k&H(m^ zLDPV$>v0YVNg}_0mcA^YBSe*DaFiC#pCB1RTu!gG{l`-`<$tsQ)>2kmj+r{$q%708!5`#%h>%14;}gQ6hDn(7!SU%)yV5j5l{roObIx+X9?%ZpLP7}ou22RNS+rjf^InHBBsr0vt1yyAZP;k&&*DY zO|{c`wWnAC-&~2nL>z4S)F(Z|ZGHyhD@dsS+ZY8@xEHCNRNtdiU=Q)LesB}ZDRClN~;nHql7(stQ-z~Z>*)?@oO#Ub#lH04sD zhH$`sEtNi>Z4=GaUX8~Wy*OWVPyv0T{@q-C!qMyK#&|+`)e*Ka-q|YfbKJRA0G>?U z*DNPBYBczDjKN^lH;&XUDNu^5kUwJAl;fL6RjUFS=r0w!Xp#NoMM4;Xw?KQ6h?l6B~K|GIBseU92#Wt z4<{6n`Us4|H+0-?ZY{O-BdLx=*TsdI?WVY^@yHqSTl=9|S%d{D(7K&P{RIlO4o0We z?C_#C9`|~`agO`(lI$<09+xAG9k47i6^IRcb;YXLqi7SO9qPBQ*I{5c&V)* zP^oSKmOiB*2Zf89>J5SF#{2L0_~(lc_YP~0uD@HWblJHf@u+p-ra_3*!BgI1l-wk& zP?)UjT6CKd<+KKISW;@r#ly`=VHROQ;bsCUjJi!!BTeLuvrLUtciy2Kx%H)7?Jy+k zjrU6jw`Y#{nok9|=z&kdcPmJ9~QZ62#R4KVyJR)h)gB#C0$Vq=yKproHWy0!+G{czf}r z!g7XolXN@&?Ehrs(3}e_k@NB5C7ix^nDJg6|7y6Uw6H&(3}_`HOhu;{c!e|A(zBT5 zmWtb;o%!6d%UC@``#m7|xJ8c&Brpog>YxJavs{Tk0)w7X8GeX>@btPV4~WZ%*Ns#! z6QzS)e#@_I**e@!qseKHp2SZ)f~I5O=H@73pCyC*vW4`UiPJA$(xnKdE7$1Ex#>28 zW0SaBTIJKP&7>shIq50c%pLPm!9K}Ig|JnvElOWvF;o<9 znkTKHlF@qceucZ^Pl*?xhqp!e+RP}U%VnODcb0d1L~(0^D(6rlvV6NpB|~Y@lO<)t z)gpdT%~N*{AK+wL(2>09tG)>TqP1#?5j1hM8*VVtD~_YgJQAEZI*>Z9C(pVQS>8@+ zdTpHll}0F;Vz;25U|nE{J(K36u&pf*49D@zX#X?CBw9WEMpgqbxP$%8u^0)y@%%oz z$-C)A<)yn#p~FmUydYHZM#_dDSy5}b&fQ{*@)R-5IFOXpu_#eKIQ%x*q4Vo6u4!5F z0Eis>g`)pF-%pT|`ph=AIJ^O3$p^a+hNAWz(IGJS=pi;0&8_7j%nRIf-d8#1sHWZ4 zIA>TqtVj6exnX<#$Wh~im$KzW{ZXIjt|e6wV!`ZM32>p9F^lmd9~+{q$(*1w;;us_ zIz+Ld^Etn$k=JL5W=@?5nn$37AS6LGPz8UY1do+qEt+6?iP9F4Ww{!y+;tf&^3M>cN+6HPMuA)K++0q zdVMmSV<;y_T+T0uYU^B4)soHUz=<<-uO};6(o$IQg-cNQ#Kx(?rolJy5d*EIR(2hMi zDcK?lfY{vg^$rC!EbFTDF-wJ&L*R#ibRNjs1SDMrNd*fhOnq$fWiGpyw$+ZMpU%U6 zDxcNM7rE}1snfZA=jw4wPC7GfN6Vg}q)%7g7R|EYbo<;~@p-I*dxdB`X%KC^=4|;T+9@8-h)TvRsuIcN zq_u<*SK+E3aDT8#R~vT$t4!@MHAZBTRu@O_BHcQwu3xu4^)8+iEBiccB|I9OU22ZC zqF{*#Y%EH3I1HOG^xnnIY#G^*Sa66E2K|}@osu7G|JXg*46mJz4wRnSt&Dkp;LR>S z1%V?g{ZIei5ZM-MUf(OO`-hnPAG1>&t-i_pmW-b9@^ZViCTZBW@MimaQOhb~qDQvQ z#UP95%WvsaRY~Id3UNr;x~Ax5xm`AqGN!k?9?~^Dc?P`4NbGj3>VbiMSHVMDWaLOO z4>2~%NGc`D*%%G&;6W_ej!s!K2i zEC$`vVc}OZ7njT@@A2KsxFvgOH7q=fAr}cr(kjzD=csYjX?9`;oSUC`6xub$WWoPN zf21WHFjzoH+4L=Z}z}pB# zl;P3*UUDA4?lR6e}gLYdI(qYd{;MJya|wQ*p?|4 z19{6ziODy7tnQxqCxmG*{Kzezh?@cQxy%k1ak>&%0n1$G{Rs-0^N0s=9Z@>Fs<~B| z#Bxz`-szePn?W=`LG*OB6kw9n#!n4b7r~@)7)7zLO5}DyJv>~^@Mg~Nuja+=9gThN zlLOB``+0aN;?r$imSGC*{b4>;l&wS=BR0Dm9Xyi;K8X2sJ-YucVZ@2F5Q`@Va>bUG zmu<7<$d#-o=S`xdC7oRL1kCjx>-0X%$4`H?zhhJnfVDbZ(#Pn^jvgq#la={UW2DJ5 zsV&0TPNk=7J8?^9>%BKwV#r+FJy2357+3XT2>prVljaCvzZ3(^18W6g5Nb51gdi7m zD5X|h3py)1MZ@<>n0;b)8xXS;{DYE$bkh_16mFPmw@DUdXJmv}N+Z-CCVU2jGK8Oq zv|^M4iQrEGYzZZDl(sN<(DIE3V;G96m$rS2QD1UQkWiWzs*4K{xz` zlae&my#9OfvR(n{#S77doc%!;4?@BQNnpW=`Bx;m{7x$JDpqfT5#RhI69#Q@V*wWB zVP@QDSv8Zq{yXCKbQ${2=j{Rwo5i!5!nbU-*jjX<65kP}ec)o?2iqY$cLYvN)1VzQ zxK00@Gu0ngu6NnT;=5Hj`Q=HBQE+o@Z;7y$+Hc|iEVX9QUts`+j>qA?>oH`@+*z>; zj};HK#rugKc*_T&<2y!OMJqV^j8im{|CW;zz>BJ#F9_LncOG`9(#|;Ive~#2Fv5Png>+t@HXZ6RXP`e%*hx*eX6olj}FOWh-p(=VX33T2#~@`Wr~9 z;$T@4H)R^;e?gnddSsJJ>M@)3nLf44-&dYZ{5z#jM>liNe!bPF^U|)Pq|{@Wqk1A3 z4?FnJt2O&JbClKQcEN#%f)_iWlgT3Yq-F7F8^f7(mR;j(+?N|N=~HoFWZyMsC-i_9 zKs(x^BR01*+$7IyhSZ=w+er-{a1*de4~rUUDdx!8{V7c~I zH_kn|&3XdI1<9 zjLq8D3ZpdkZTrz)LeMn+@rlVRXJ`ZlZlZicv^kWQb|EzQU{w3Nh5!H;H^+Z3wWq`1YuH zvC_b73JZFJ*RmcTm`UbU$?LXtK*tWiO}rfiv-rGbhINC?AiLl5k-z7F75g9mp?>%K zz~2KG?m|qLfRqACR*7&}x@Q8z28V?~8P7d>grI;c7+>2>%y_9;5|~_dwROsd%;;GY z%EgwVOi(q9DcXDBRFYEgG_FG8&R#H}$@njkm{5h0%oTW9kQ2htg~;j6!)S4*B#R=` z`pG(E&b8s+?aC?9t zmhe4nSxS6{wBnO?3g`mNUJx*4J!s8q&a23VX`xZVrE~nlA!2Z`)kHP~2ja6PdmCVa zk&B@h!xSdzpDPfXHZJYUfZwHO_wnOLV4PyKEb_hR0*9LO0-wV08BL6+;4knQzSqL3M|x!pG}?0kxU^b$y9!|U3u!j@%W+-ai1cm?zs5WCq zmd)6lO1LTddSHX8t>>fkSY6lu$*%H$J#0uDbUJg<^@;bI^NG{{>jB^9ITEJVJ)+}( zbqv5FBq1hCmd=zEjtK>@?|a_ez&=)%{KmO^ZbVxQsX;U99|iN-sS|%X>uKyE8hjQZ z38bTCsK6FbX)65Hvg`P+jwSB2hoo4lVH%~A$$kQ1jE@`Adr~w=Jn%Sa7)Zc7zw@-N zn$pW%@jDyb86R#L;W29T{z%5yCzKs>Q@+=L4xMQ=ieuCD;Ov`xbQIh#03C1CwXv^K z(%vU(fZ-Q%PBpTOo@(w|x^K9~T65xA<|)L-2heGTAqEM1+%r*4&Oa_T@~>Tr6wKZ1 z^># z7qduV3dVMmekJEDfWNX?j2V$KrBaq3+Kc%NkF@8J*8dxox)7u6p|{x(vT{Weo=D(o ziOO4fnMj(-%;Cu%P4O7k(lS-*M_7Ls>(|f3lIo)ROr^A=Mt`@|`oji|3s&4tidnL^ z5lOT7yK~s>TLAI=*Wws`DgR>Vb_N_BrZ`?)1{&A{*so^{MSnk}Di>2}h&zR6MPVEW zN$*KsIMqqpip|Vg&yb4mCg#3S)~tD;?vbCH|6Ie_6<)I|)@b@3mGEW_qZa~1MJ0YJ zqpjeZzyDQ~2Pu6lG3RaWoxHy+hho6DzxTMWm?+Tfci+J%e4`%w%hB9E*6vF2AzTew zn+KgDeJU&sG>wgUX>LJG27;P4sibyG(D0DovErQCN$wjNtSa3Y87tk8AQDs_pX$NL z9kc!mMkpPyUvKX|w;OO`-`iZOxeRdgB}q>P7Gg!+b2;d+1zMDLRpIWH%JYY=vhmqu z@Z$Pu0kRMBNIvVtdan1YXFB0)LeUO5)i8j+|Hk=6)*EwabrBjm{YYbhN=s`y-NgbS zjPK#${PI-0t9ymSkKpwx%#?EzfTJ9l{zQ%`7+l0#H}z^)GUO&)6Zv8$NIHQqt0i?A zIAtxXH3wY8or4-N=sbu1^2hyC*UF7{$yXI;Mn?UPB{{X1TKaPCY?Kh&uZfz+RC7ke z!6amn>~goPM4XEsV)0faqGtp70a;dEUj7ekW_aI!W+Dn2 zD7@*ZfS5U09)GH75UgIlWT&R4E4dJd z9ipo!+$A%ZN3S?)ixj$A$q5%pT$i2ExnzLG9_6ROCkKvp-yo}MLknm3C@nsHeY5KI zX6YPVz&L760l$C4$M1i1mp-bT*j77!_~3QxU~Be;tKojFLJg_Re~9Vew*|F;)y?mZ zCJeECE*`x5$!iqE>r0l0Fk?lOjP#WW_9*{O4VM3UOj3t@5^BUSAisx)IDA1FqR4aSsR<9=-~@ zUkC7p|KR34VZ2YNywmJHk;cbEJuxY ze`_GBZef%ty_49s1w@s3l$#8`L6&-;1H}Jf3BA~)(gZ54M482$CE&MeDJHIN`JX|p z@-R_%@7gTQ!1t|-H;MZaY`?vYx5#!keKyX3vd~q)B>qhlld)0Jy!r!*Dtex+NwdTr zhpEUbKU4Spbb%dg(nn8qaeGpC_A={~UJqH6Ci+$ta>jj3_#P!eRRnZB3Io}cHR&mm zuTYzlS=@2>c#e)c0n)b6tPJ_Na_lRGwtscGVBqGw1KFw^q8q~vu)z6n`PK3LMQ9II zV@|*9*zG3TyV|~85+R9^&cx?HeN~qhmjogujPy)ur+$10jmfd=K~)wy9p~!0zS`KF z@Hq@>e>hsXz2;2*?ji<)qM8dDczIGW|36NN|M%MsoFvyiR+6{}Bvbq;elVF*_H4a{ zE<54J^l_`9a^4Y}45XsJ&!X`bK)L6Z&J0e|{45SqF6DrXlIjoBr*f^l352wn1DUvm>5sWlcNXZHhzNyM^JfFNmh$Qk0$c2gE}<|ElocJwU$)L7wOZy>js74jI=Nl=Eq zOrv0bfOy@$*VLE-q?~={hcf{t0axzGcJ)nuoqSr8bbbLzuR}}o$GLK#d+LRaGEaf= zd_cjzoYU1kRV82BSl&kkEYwmEWOvO_h6->|63TCD zkP_)cWK*p;`nZEr(|K|cG%5+45)(+TxTP3xJ1Fm40=1{PC3>gmfl%ex5n4Z9qQ>(d z-ixg&IsCFUuHW-DYpYlNsVu3(`pervq~yZ$&2d=AOD4fRq9EB8(K}_ZZV)PTvWM~- zow4thUHjvyg7w1A*;lWK3(srrz^qiGj;{6r^(@`q(nqaWWGI_i_Ac%*hU-=Do4nQI zy`xA@KLc;YVXb6$1GN*H0xlmq#U%97W@-$AFtM%dyfPvqk6~wJ&_@f6`0$4^UMto? zUOhsWi*@E!T>P)mv=PF3cE_zHhtyT!8Lgdli-8>54ffkzF%)vjvjv%NjJS_ zEwvYX{D~)cBQky^8{4Z$bJ4Y106Vwcz3pP~FyS@Fl-Xy(MGWF}!}2Jx>v zb1VYNwURfiCtsb&pL>^mva-M-1jb8RIz;g;!m!U;NW=w_80c!-h>A2E5Tlt*Qr{nu1s_JWovQm=K9wap|4`F{B~eu)m4bj+6qVy`yeBX$hApH^ z`Fi_glZNQXbgzEMzhMhpapsq#a~(Y&0=VV_{AK79s-DWt{L+o+mjzoRk1Hx8?<=V& zw$bAR`$-9gA#ZkzI@&AYyb$UU{g5g+b1e=+g7v4z9Rq?W-sP2p;sfK&bA}qzD(OM3gWcP?$N8%s+5$zS=U<#; zO)f~#`4jy^eOls8^NZ}v+QOUqwVp zM}J(EizmJu+X#x?gXFg(uj z6J+m@KBK_&H%if#UeDM^T}oabrTe=Y`y^5!s=DaMU3_!U>UR>M!<`Y3B}|!UBqvw^ zN-KMPfQ2wUIb7_{gbG9?h9e3OE`cs_d3?E{87)D0sUYc$P9PRZ&;NLe4%aAF2D3eQwXjCbo27PCp-sD0}ael9HgnTnq! z1%{u8HJz$}uc>_11GVFY@ijFK=e%0x&a*>vdNYxE=?VUVTsMcJepZI2RHJfeC`v3n z<+h5vo6mg0TSgxh8G4!powEw6Ro>N>%|Ff%#L);tz%}jBpyYBj@P2jhl&tas_Pb11 zx!HI-^&1@{KvToQzj-30!gip1`ac`||4O$A*UQ#{aAadf>kkmP#q*AzfI#9ST5OBk z1@Z5%8~cq5MmtMZxqC+dDZ$PqvqtD$i@4Jx^1sl=wP&}bwY9yi%vjYqWI*K|#^!V| zZYW(ymdb4S_Zi?-FRd>X8O)CEV*(L{yu$nzysM=BfZM;c`h+UHJgIG+>Qt8I|$tsQ{m@f|s=&6F7E=Gjt$yb){pXdrG)R z4Nbi02UnfruM9r<^kO|-+1Mm#Yzk(2dF{psgSjT9;X|bhrf^O=7Owt=bP^0c!WUiT zQgyT@p7ZlLDFgdZ9*X@o)OVg`4nGctsksHe$%kq*bWA#My9zklLBwgi*nZ-3bj|@^ zPc*ngEEkUgAQ@Kqu06GD^*b&wZw$9|VSnDC)UG*;{IV51dJQnYlj)Ec|`F0C4|-Vgs8jar~STFxKcn6jv!-=1of7b1GVCk(Hd(+rzz z@r#j$8)I#M>NB!R98yE~{j+2-01@WMgmpOUI9>iR7xNlj^VTlp<`(5*BRs`_XT|W{ zu3n#}dKHEl!*KJ`DVIg$8O5#3BbVe~XDsXD;mvS1Zk=b)Shmtj{n+(gxDE5S@cIsYY>V0+Os}jDcikk@a2vU^!eGrP?!R<3lL_w??AK5%Ct}Y{e zM1ct_UTs?Ph$$8eVQA`1we7N0%DuF#OCm8L*-!&AG_WXAQ)a@MCax*tLk$tOu;kK`Snl9> zF?4ftK}OJceOgXIl7*TVNWucM$M6oxq{dzOikGKk|G37?8&mP13t_h3`fKB)p z6&KV35P@v1%UZ)=?ik(;1ExcXMwY{4#?G&zj|eW#zJjnwb#GnK3DLCxlr>MM(fAzp zcEQalnw-A~LnaMUy4s33Ttc{Y!>X;aN8~L`zbZaqV*{eO3~I?wG_0s;_M%58#eIH~ z7-kTHShg!Nam2v5-g#y2ALZwyVQP~M|4!GuLUa(S4O>TnY=#y{hXga1klo@kUgE=z zW)^wgp~ddh_VVA_=(i6llJp_R7MkSFtBls-YyT9A{subohACe?!@K+i2Io?0KmrFq zW#Clmu}`7jZbhmZPbtbw(`L$Ld3(!49Kyj-G5MUVc$~ljpf_?n7rbhP0*2J@R?g26 zr*NyPM3q3bZZ+E@#$Exb4{mHyKdC9HY&A)pgE^D_U_E+uxx|V*Zr`*+2$~!2epr@1 zwA@7d81b*}u)Ge2s(yn`s*Qu?=(nu}XGrzbTIq}HpaUFv@!e_{#^8JNoyNnm03M zR4%`_p5Jx;$7olmf{o55yM^C|zyCl#2~&ekl9epA`;&38_>PakMrwvyXH!K_IYl#$yH%zp ziFlLN+of)$7;`Xc9vk~UPeR5`vK4<4zY^OX-9F}YXz`@3lp7%pxgTp)H1_a?)~WCL zzx3z75vAgphQ=iIs2~0^Du_sIUhff!yJrF0&)N>3a3hhz1p-#%(KtQ!^(9GLv0K(p zu^>t58~oQVXb#w}xmt@(z1knQBikRR zm8wM=dYlCFBCr#O5ZB?7*oV$rv}BRN@$`*Sj*O5oGA;SSWT_KEIxKO#hGDt+I6AT9 z#dscQvT>|p!%Vk_JiB@x=MDoZDs7h#?X!}$gKFZ3yoJ`VNXnDUy;tt_FGb`LH^KHY zO)4e-#nY#<7%S^e>UOsG$INy;wgQ2`ED3HE5&K_5x80IyPnSENpEK!=v|fMW zh1C&BU{E^iYJ$Zpa$-o^DTB=i?4EsoR2!E@#M2jXuP!fl^9`7)ku?Z+{ceHO(UFf@ zxl|6(WoA%I?~k*&agn>5##xhEhYUMcueJ|4HFrNwV;8W=nvFMJ*yeZZ8$QrOf9o3- zqSLp#h*Jj#NyyE_EXZ0z4~ja0x4rrH>H5a^ z=h-KGJ~J>_;R0mOIzNz8SM9b-a;;(S@Rtq|8f`?Fe@}P+B-Trx2DzUFvk7O zV?{xr@a%xH&|ptzvHouUeUH7+ZpFZN7bnOb2A32mR&=Hrj-7hs7LP*B-PGL1hWG;* z^QjduFM602?k)a70+bNAhn< zio&L{&q-w75KMFu2Lq_)%n|^K%jn`8&Gs@n@q!|9g(=c4u<dVMyIO`72sT(42xsgBl)3DwYN0wK}(L3_DtE8IU*-C1X6#HBZ)H8nQN zK-w?sAXR)8HDz7hSf0@*Er}|2<^8z3=?>nqyxii@14<3YDls}SjaGAoO6Yw06~UMb z)h;VA8~I))sb+?3u{}cqv>5C#EuE*s0IYN&@%s&nZ^Dc;nbc;F$YoIQp>7hC8I~|7 zXLYyj96wC^5JDo?QQQA-E^p^eaJBB%MdNT;&Jj4{HL>sByYtmAskJ(s?Yeg-mI`A~ zihBSJ(;E`b{7(p;fC6U*uA^jN-#TbnfZ2E*Dmkn#@d#0x9%3YRiz+P5ZnoI+J)Ha` zK0WKnyK}TT8xXhz&U>lome}_c(2j%2<;c8C{uokm@%Nnrvc!bhGp7`>G);+$-6^R) zL${AkDaEa}u7q$3nTJ402bR2mh>39|rHCtw#+*5!i|ER(%7^G`WyxRw4-l;YO(El1 zCBem@bI<%ZUIRdG#o0MSWi}+5X--(O{~0USQemDFhAU>*n4Wd!-ALNc{ewmJlNEZh zSRPmhK8USgtVywH6r;e==Y(9`-4sP(+M$u?o$)ZnCyxJqEar&P(eJasq00rsI0({O zjd`SBd=V#Uv{U6!spRp8PQP^oBKS^>2B|Qjy3!`m*OGbn>$4R(`*&-bFTUVL5*0)0 z$a8-+w50ldAt|ind(5|xcAKjB=;CsQYM~d_*Q>Ox`Tsua-7TWn6zn55?OnCGbmOnq zJkmps?bUG$JPRA8Phj>{MiuxH^D^6Dk6~2uqIy+U}=~ z?-QPpuzf=LRUT1Ze%aYABXgE`<}^Qo=V0H&-48YAeq1hAo|IVCD6H*H7A#txj2Q#X zlz_*yl%BIBJaexgSM(KyHXI9859u03StZ8fDsv(}Ij8fy&d)oyT(9V^AVYP5Zo`!o zk2RfmM;SU5z?`XV+H4p>qx*7hl8r{U4sc0 z99wNPa9h95?nW{FhKRBVD(J6^_~BV>aMv|KqMGJ@cHG2 z@Qk>&h0W5_c^DAQl-BcEx_!kjH3`Y5rDn8r$#R)x26tKVO5VBrYYScd<>*}DM^J`> z)Y$Mn_AG-!s^U#3GE4YD2)>rPv`nb2?Kz8((D^;N&0uBei%nmBaz0s3BYD>L zjidQWeGMTYtPk0BG3MLcc(UvITkPJ8$%F7R_kOvt`77Z4*6N*^ng6Y#>rIXOYm`oJ zgdy1zLf0Lm-}TXi`Z!SIUbs*GB@L|;@i}3Wi`@&N|BT!Z z_up*kbm%==doEi0J1|Bk@`0cjb#7b|bUo7uzDH{>b-Bn!Mabm3BltaSJRAK`0g`Z@ z9(Z|$w-4Q8tHy{go~j2P7yM3N4W{#u#~Oq!?NQ591FO3dgM5QzN&HP|WR07CQlhgu zd{)rqzc#4%gMQy!5E(jLp1FOFAbEMCIcgkmCmDhiT`J90+F82&Z{g#AI>^UT1ha%~ zo}XcEU^`T5g{NXN*dI+S9NF0gMfr~M28#0Kqd0<3yNRbnrz~>8UxX#)qoV?~N&&8f?cQr-b1t_nPA?`@*tU^F&>q z_Nk%EbWv?59lvHzXaBCbXjkQgpmVN&sWL223GMk}hgmTJ?jmBw==z*VrM3X>s*se^ z(o%RB>?1E*;NSlJ1C^U6YBufc%pt;8`3x|`LWjY#%-o=7&?ba+55zS87(}OIpX=`% zlJw8VV56dhcHK8weA7QiltyIQO2N{!I(sEuIfx8i%>)-`o4RUEJzBbRFdY0|wp$ox zjtyr6Qt5A=vd|On?&s%mg1SGLEXjOM9>Q(ui|lPww_U1XUS{=c3)|2VznHKmV~-$Skoe5eX}DxCyqpXBC`&LBPjwt&3x!cLJd7%49`1Q(PhPWeqE@6}KSJBUf&s!Z5o9J~6^I^Ts?4`Z3 z_Jm4d!1e!|r+4sqthFU_$-qF=vxN6jL&|;3vevKRyySv#8{(uQS-99g2II%8f?JW7`;y?P~#O_r^RZoEbiH(Rggh1KvfEZEH6Y3T%QP;aH(-Zp!#k zJ;*3Ca(A%2?wqvkFoY7s%XEN3lR5Y$V1kouVX(R_oFnsq#}IAZwzIN4V#}$SP*z=j z7!dRIsJ!i}{KvJvk)_jEr*9vh-)1`40c8d$aeGo2_$ylBm6hR86)W7Md?pAEyG4$~ zCDSrgMK|baRFX5kR|9*)@y61#S1QAtPswof!*s7{cMjLQ9^1{%bqzkRKft0zV?eFa zxpiHBdb#j>pAmd0_Ci5O4U@iJvNGOmX`8s3@jDaQ++yH!Lo4-uds?_up1D!=95~4J zh-dM2ArZ+fj6iK~@P1hk>E6l?eLV5I3x(oMlQ-f^n_eV#HM-e;3l#A^iXAFG=z5%@ zv9?4tewk@|xw?6%U5Yc?_>aNMdpp-VXeQkZ=9g6{VK%Y)Z2*3|w_7T^d%-yeT87Ho zItkk#>ic|bdn938Q|w=G(6jQsHW&V`~?OluAAx=p zu!?^=G=8!s52?s7vb0%7qmgF#gJ~)n@!NWni>Lkna#zUwkAZ|?r=%Y0InjeAG72D9 zfIfUP1lMSDzDj?!{R#cy{7gN?h1lozOcs%5;CZ&OP=pZZNQ}4p8wu>~9WL)`e28ML z7D;OT+(jKZs)fEMcf9%(fTG|fY!_6``PihDV`5r>FsgMg>coFp$ycWFkN^n~mQ(;6 zumlKa!=84NoGqXJO|i=#xeVM4`uE*$T3UcP3c@HbLh>;OQpqRG_k~|bicW5R z2DBGGop{GT%|;q51_}o!pu+<6NVLHZ^ps3VSV(kC@|Ln+;>Z<{q;}!@YV0|PCI&~e z)Moll&Z_ssL~70>MZze3DX1>4FScITa5tW-R=JZCG_{fk(NdFQEOgoMP=NLz{}3(Z zmCDcx@*!4yQ$iNPwZ3@lF^A-pY;Yd7@ihe5U84bivZ4=u&91X}tqw%H1*%dhGNN;I zVn!!W$s-$XraU)|3Qp@~&`oI+$5BGP9mquC`AzHTvp<91c%$Pm9%gJ_fhn@Gu32=2 zU9>q%=wfz2?PkF0V3navWcmk z-?mi%MHcJv_nW&CWs0H@+rY|O-p=~Z3`Je_$EokV>|eZd#|lF>|0T;b|8|S@Y6~63 z#mt~ynmtZ=Nv2GlnT*K=f}+otf=;_x?w>8Xj%S}4f*+1`T6N;S#gmfU%gmm=eFuCh z40LwkBcW0M%%ULHRPomhTE5)oQa{HW>`GS|&$2Jp+6H*Ko|HPD+eH4D3YXGeH(dtb zkN;*ygd+b^))YnF&~7pOP3c|E4|BRS%jUO1<*2QoBc0_Nh_Jtt!E1^87Qa#Bc zdWz1J^Ctopc1T!QPV^M|2JC*K8Ips?LtBpJ4|h?n^sSK$YE2Mo4m`?YXE6rqU(p?f z?<#>Vz0}wU=JW+g16y&8R_}AT=y%V9-<5Z8We-@V;t|F66p|FrXaJbblo|#qydaXML7irIL^J*`xwd+vAs1k=5mIUds~%n zzFx{s>q$g`=tv_pnZZ2?pnJBa@`q;4E)rs5jg*g7&JhNf&aszev~=}2g~&-bySmCb zD?c2|!Jr0i^ksJtd3AYujxsAdxs(_y^zs{xx&AI#?B_el=ZWkn!~YyaBeqpQ(!(E> z*IA(7ec#{M9iquK7tUp=_}N+9(*An=Q8URLqg+>N!m_vjs!YW@2GAOQ{HQYc-JFy7 zz3a5YEzV-WXXA-)tK`AxfR!T+$`YOw6h;b_@IjVUCojF1F#-!)ek37fTaVe}toU@< z&~79%(z)ult(%2z3hmJJa2o?d1~r`;B}hY&T!|Hg0%-DE;cmNQ9ZMmtPFOKVP{|ehlQEeAQUZ-Ka&;EWabrc-)+IYoS zM!r1hn%X*TnYhaLdW(AKc+PI%53Ezy#C}nEUjxula9y{VBvO3tLt`iHH%v9VGr4WK zUKg*_spEK_64t-B`ZWUIuShx*L*SgSUzTWycPF}T@p9j87u+{0zKRWeqA}$!+xd5w z@bJ=GQ42F6^1f%>m&SGeJe=03Z7w;*9!2t{j%!o^|0#VwTP{0{$b*0VMup?65UMCFp6li9SF*CQATU{UI9mx{sBFJ z=}#xE0o8I5?H z*m6Zjs9#jOL(gBK3xo#B=91d{NNK0)DK#;vN+}NxY-F}2vL!*kkox3Jz2WOB7Md2!c#KBH)RH18;v=F zK3PsduWR-W4lZjB%`OjTe8M-0@mE<(9Y2d@;$5eQMdC0*o}Yan$`!B22~J|ve=PYT z!5OKkxRAQFj7fHaib+Wfk_Oa zPhca|GQn3$E8<-{w(NN&76Wu9KrF}E+1Y&N&?|87r(|9ebM6#U9)=GU=n@h~-|n*o zWkR}b^eXYj$0@B`vnB+8KizF&GYV1q5huM+0BvImw=UhDZ}vr{Ep;o~m@(vUmNT8) z4&M6L{ZCO@K-E~Kd3`$OG>k)hMhqoa+=YL{5OQh|%$2Twk}MWDXl&z(5BwMs02UYt z;ulRJIN}(IaeFUQy)+n}FK9&8l~@% z%zGBxj6?{-u0P(K;=l=S$3K5$J4Vx0ukb~vF)fn>!DCP@pWsPx04D7!>C>iFR9FN` zT*Zz;C76_O>`Lyu1sC~2j4sOCsRMi=V>5mwII^sam8EmGn1rD*W)LHpZ*1(M>thcr zf3rQa8&tf>7?lA0?l?Ooq63JboWsA6D9sdUt()}-jw#}Li8RtE?Za`Qg8O{xs|mpD z=?i~ygPc(i@>BJSiwIKs+Oy88ai^h-@d+79G_CU!Mv@u_zp2<86m$!jxIJ?6luh@m zv5$DQS~>v#T8ru)m>5#{WA-Ygu4Z*ji3;(;{kqLUe|QZDM}0Z5-8s0ofe#N2;9Ovw z@-4w?NJ5jp#2i#W{)6IYhL?6YLsiJo1esUySumBchWq#|mtxxOi_!WvkbcVbFxN|M z57$B$a~Km9h#X6`v7IygQZRtJI9^CnFiHU*obUsK2C%(MMHoteX zR_e(*3NU9AxqI zX;Y!SKOoIP5Ljg#lE8znGtm9Fp*ueQUFMH$6LayQsUYK{ncm*ut@e-YA`LIbsir|| z?EQ}7DE=OgJsi(Y^6tkNM29t%IA3UkW9+(4< zz|qi>oupo{d+3^$_Z#}~q84A!GuAoF?mQr&+LzL}>+;s#>D=|0O7M}7a{RF`{L7>N zZs5Thq1BYpcdN4T@&zf`o>S+EjdzRH;icANh5>{)a>MQHLrVLUPS_d@G z7s({X9iez}EQu%x4`;b3o=S0#3Hsi9z4a;3-uujf2}|pZ@=yfib5-YlsXvNXW@@E( zGVBHgeXiv?xOugCOw^@K3=Lf{B5z_VInYI1fMV6-rMZ;n%F*wsw=BcBtTgFT1g=PP`2ORGa9&ClZwPk)>Qf20zY-oEYR`@^!* ztaS>v#m7?T3ID>ex9{Rk!QFG8TEpO zHtmA8fL(d4-djSB)F*B7d}&C>BJ(*DB!6D+G+1BR>nHyZybL@Ym&4SM5}S>C!Y6M@ zH~*fwA(sExc^jc4=nlmP3Q@QTV5`jgAMTDr**QG6z-vq!dgDOqVVg$1lwaFzV0s3J5lrF0x2Lct4JHO=9!OCnDnyHU+3lP8NJHHtd-l?C zKHTKx+<>e^TB(hE)-P=I-#zfoA4N5*^>ZE*xm~-3vNM=QPIfM(V_Axx-`wa$^aO#hj;j(8 zuWJ_DUehp<Z!_UY9CddX%7)${c5h1agKp^|d2iMgyU^Fm@hhP|Qrk(|8=dDG8D` zEDC2V_!GGJFHhfXsr38BFZxn-FhxO?;z0J9XS)&r2Xgh{;o~3Q!{7M|Dd+I^zP#`+ zN*HO$GD3jVJ&Pmcb5G)u0WD3{6p?yqnh0e|yI%74TmZ*3Lb7tI7ku zy|xiuAKTr?BShff9aacg{886AWnV1v_^Afa!5Lh{8~maZL9J?|C^C)dq6mA$((eO| z!G#kSz34LA%y-MlhLlB1n~%5(T@7R0Bz5KaP^$MeVfl;d$S{ZZhKhD!PJhcuJja~7 zH+njpwKXn^9dG2xDDF4Xavv zyt=)?&VI5ah6hXgwKtBJUr92dmEfYfZBa%)(W%wZ28Q1f+{`TddL z)MWUrm!Itse)k@v&s0mc!`jq8^u8&bHKCF9J-DkR%ZK<%9tP|2j(eMROwKXr?=*F; z<~p+7Q~|iE(i4&UJr@w^k~RJZxVsv!Kl*mIdJ5Bc=-G}lwv~+l$gkF z!SNN*`0HJ-d7@9E&R(-Ig-spzsMSSB=!s-i_V%t1wZq3=ezN2coB61dS8^OMiMkFK z-esSM9JS1`d>sv){7!H6hD;ld%Uq?%kCYH*?Qir_8a}#k+3#6*9^5ux%8)H{OuOca zHl_&faK@t*P+p-;%LyLZ7%1iH@x0^X%#vQ-4KjbpmQl!Y=6ua45|t*3C_dt&I>xLB zSJW`vxG)PE1%jj3y{7Sfz-vZh zrP2DljUxvw<4Qo5k$?#jXaDcOR)&65nFe`T(~Ni%YWeay+P0owVTM~p z$;YaEFp$iCW7=5w4xt^)0c1C?w9w0?_3iwk?VAUpW?-;kV->~Xpn5a3Dwk-}PxKVW z?X9Iw+F(X^Gk3_WjZl=WAuEMJMx2o0D>h1}#so1CI2ja`F11*mj|?0dXGHO;(QK-w z;N>?Qe?G1&a*m=ocfP*CQ=S6wMOp`ksL^QjjP%fVdH+QJw=a<+5Clv+u50lPLteuJ zXr39Yh~@|aAM*xNEu_Jm?y}H{$N{E;WD&Qz!7kkj++;m1G_;ntyM(TKcZoRqRx2Bu zg`K`RiqmF8hEboN{-Oary%&Cc0_pdRm`MD~4ssTG4EXnbNLgJYPJJnNd;ND2HR>9t z^Rf*bp(+4NVGwd(Xoo23=;&GK^dcL(=Zxv<jkN}%Ani$K6mqd7<;8%R(XiaXDSFZ3yXvHL*U5k$j!{p74AU;pND5F%j z$beeXamL@@G&YUB%sHtDG9wNiR1E9^F==krb)9FX_$iu0h&iyop~`0%oM2@s6Y2o! zaIns9>+oxjHTGMf`2sN|`ArLf{MpvM3%FfM#;5KfhHkoPENpDp!yG<&Ux{LMbaWt{ z49T~L)AcnqJ-fT6BjAZ>AQ6uoR!Q7rqVrtIx>wX6(%0_}-dC;OX=}pvEEJNeCvp&r z!BWY}CU;6FO>bM;&Qs^XDlUmU*q49F|yQTNBILzVO`d>c_- zq+&iHjVj=P!3b{bIC&P?Ao)~)vCT>ma$`6qs)a0NgDS5{aHyJczok$yW`?Xv_1(`5 zze9%7d*jr290*>z`5V6(iXX+IaOK947@rU+H^s)Aq9vPa3KD4GEp2s-{nP9I<@qj$ zhm}F_EGL#j``qkxDAW1-1~KpsQ%^$&v)F-SaEz{HdrPee&J7?P4gNAJECf&Q%;_FLkO#gmywixK$1bISNwMr zGU@uS-3u=sww8xnY=m8gzhoZUR0YAgPf2SN_NU~tYKt0n_dWeJLdP2MDe5!xX@?s^ zesiA+PH)kLO7B=Z-LlY#bv($63L|!k4+PIj?F?ljI7Y`npWq#aPe3C5V-AWMR?8Q3 z%WFkXZCrFxyBs5@iw(N}XI3axg5y~@+4u*U0Uk+Cm~8HHGfsS7J}~+oVt=CvNJ4iT z>nLb%l&D?;-we@Zuj#wrl29{il!zjd1?^?Ce6a#mSI@=KCc-(n{zgiPe0;GA*vjaF zmsXn@<8mp&==)24whNNNE^HX^jiy~bCRR_>P8yIwz;P-0E6;xRD4s8R)~cqcnnL{6S!qLlVZU)dM)I2K{7r*&hq8U4RZGt^1A1m!>451oKgI| z3g4mZpYtYvW`O#v;T%6j-up%RfH{l)k`@X>QlrIN!u@Zvf=h<&l8|fmINF#3DyM;0 z6Lz=xq5>-dbW1c=K@o)|$WGMrBKS5SP<05bH~b>>P7ykZgE-NsP57L`v-uAx@Pri^ zCk$mfrCAL}j4vl1$EM>4JKX;F`A{w9QV|07DnU4FHi<2Ul({FECYh^PnLHD_J)hI~ zcO0h0@J5UWr%JD4-qhwsaDQCboF)30&LJy6&%~oeL4<@^P)l3{aI9T1wc~d#GP|%0PQgbN9Ii%?~b% z5z34nq3GPHcWnOue(Iup^>^B?IlF7Jv0@#Pf>4R!r9NXFCcI5eEjv=ReP-p5?t8}Qq~~zFDZYvdQM*_U+MyKQovS`9`d|j@`AR?u z9ZbY5kr}PHZwzaB1rtk=y4B8NT5UwRcyJj;KWf$?s>^4;=dQT{x4a0Cf}w}j+88*x zs5Tp@w$XcsIzRLZ0d%s%hFRY%n7k>1JV+n7S*S@l9}mxPICGvq?+`2P2m_@Ozc*C^ z5hczOgU&Z<40+5^1gW1Ds|fj2{<+;uw&Gjx$V&w%_wXr^U7m<{VVd`4STXRU>(b@R z+Y~F@l~)c^)s)5gO&>=4FW(?8G}qpWS-&85awhB<3_+j2@$f+8Cx%iT0|Od6FS>!4 z6fCglunmT*;vqY8tQL{epE98?D?7e`jNQk~x}=?z>c3>ZB+25);TlM#zg$g)eoLe@ zT=ZC$%mf#7BKhZn+nPTZkxda;VsLobuHa>}5%~;7+FmlQp(sO(t}_>vs?+E<8uAjz zb_O<=v4~1UrLtyW;$V=q_!^?1tkiHbuy#R{iO=5x)~sslM{4i6nbfID`8%O zzp!hDH#Qb^($zPh*~fUPu*$A11xDa#C_X0kPu*v-Ow+GnzeX#i%wwGIN8|U0*jEi6 zpE^?5NM(!_nv3J4#z^bi*DICHi5+)_;4t>LutbH_TjlRfWY)7xvenhFt0d95d%e1^ z-Uj2KC|awUEC$q4I#nWi9tE0Kt_vzwmc6d#b#1yV#~_8nBIF?J?uo4&JFDBO?31=3 z`rii&-WPe^c~X&Nxp~)?-K2VG6yKSY_JdvO;^0iier1b7Y5%HtbvkP6Yc&Z1i56oN ziBhP_7nD$oQ-{lV0|$2+hh!sgp}?#|u=~#Eb%u8QWtYM5aA8R)7QtG1;e$A|v{Sq~ zF?>FzusOru@Wvud#2i_Ev1im#X(EFEMjACwn{b)iGc%Et-s1EeSdUzTnM-shtj(RL zRB>PvnIk)Cl@{JZ7#{-hwQiok=rfmw;-`=qVRB#;T*Ndz)>+=cXHN4`KX&Diax?ss z5vUWvozRt=SlVU|IB@UCHW|w)V_7S%595OcuL$)ub14dZ)-Mz|X#QL@NNCFt<^A!x zH9eY4zp}i%J(5VxP)e8YF{M;NP$jJY87T!zL$jBc=j_bBw!sxgV`6B?!rzC z@~e_&OrrSLCENOdebay>D#@-+xqEVBg1%^ zpxqzsMxH$6F9TN3PgY$$;)kdtBB(A<_<0Piw^AI?@YLOsUL;}w3M^TyD?msjw~OJQ zM5xM=@HyP{p>2hhdA8p%-wR9S5Q41SCA$?@8WI>WehsQM40PB@U~0_N8qnp%1ER~0 zKG(UWypLeVvl{=SBgu?#1UQ3Z5x)Rs_3S1lZS*)|ka=DHVG7^3*84wHlkW`hEVf?5 zL>8JU9SVL}BbSQ9kN)WE*WbD#>Uyyw-~Aii{x%-;ifZJugv{H7F!+0Sx73Yg%A(`K zV%S+zjydGCijT84Ce1|=68QN@eJ;QTq2r1`!;>O%PG#gL(UQmbt19Q9usq* zqiFJ3NB>8ur}!?jIjr6iuE8%!rdFQJ!2G_YEoacZH{(<9TH4bta^84^h%clP{|vbJ zC*M0dhe-bMrVY^TyLIYF>%LDa)`7p)>_*`GZz}r#{`j6h)I#9$d{ZjAD*b)Z%8rLx zNxhvGZ0*WW;+riijfVx=Y&yf1YjtE-1Y-;4;pN}`Pm+9wc6&i zI+V~3B>$ZVoqPI;e}lhiTa_78vO;7ol}&;vou?UZeD)6w9cU1gb+64Abhy!rE-I)9 zxpz*p7;sT7s9^X7lGgB%YHJ#(Enebe^3^d*H0OmDmy}JU3Ku^`pykqI;zG12m-v;J z-pE`HN2IWv<(&!A=iamTMmNVWefgvBz_WD0&h6&*KDTseqE9lQ9;xEP+q)pBGM54| z0DveykX=Hb?~g?ZW0U3j{^rxv+{_p7!nI@^B$TUcW&EwG5sycTiA(NNV0_ zF)f36w!dX?5BE~1k5ZWbjLmNIC=itv>E7-7E^6yo*oy#>h1jF)kpUN6`l%e46m!jh zUgEA4C+(tW%MY0%0IF@!7}#gV_cjHi=%zTo9dR&Gwt%Pb-L{MaV><}2We_d*dKYa~ z8EY4}Yh)?y!vF9ZBu?fzJodhA9#a8B-NwKF+uQEoTU`36y0YFClg6=@Er4*$=XOA1$81)2Mx$pHBMn`WGBNE{le%-WKMpB#T+1*Y7?NqdF$%y=tn$?b?TDa{9E4%&$){pZGG7`W683LO@o zDCHsYMUN1oW`*1D`Nl~zt70+t2t+jC*`cPw7e83CA}$a0?27&!tXF%Blct{KDxEu? zIlXTI#|b=T=06iE=LyPnZyiDoW^QlAg zj;37DGOZj{+lFxN1J(6$rcT2|m{XsAAI@B|LJ7;*)ofnt2zNnE1 zbvoPj;a&-c+tT=>is@3ibqFZZy-~bTFvxDsrkIYc$1ui0PblPXog%x`-2zmO(}_Sd zaeP^1U`QH+++>Di!_h#nBKKgz#(4S>4VxqsTNf>Ob^jZ2y5HMP_Zw;2Ayx^|^}Dez zo14RtmxBL789{nO+|atm(xm_OSmZ0YU&zPpN6QZuUzU+1a^IC(pDBUBgeEjIfkX^s z?}bWa|9|(@dtZ(HV%UP7#|3XH;ejcXza(En4)gfO^o<|-JGOt#2|kp+K0oCLL{9s! z&t)0+#j*VRF89X+9!oZbeh$qb4o?hV5CgxrLF&$3QY<>%FAinFCqCvp9&pS`@AK5F zNyg`vX#8=H&MqP{ZIEX2Q((RAVa~v-Q`$}`=#+}}AX8fm(Ey4*ZF@>z*=37|d>>*i zW_<1Up*LsSc;sY6|4U7qcBibuprnT-n=8~a^DJ# z$vE_S-#Fy;dEtlqBAve0aeU84|A3)zrK}u4nLWW?|6wup|7jE`AJyCW|JXiK+An+& zr2sBFeaWE8%IoHjhYf=KTjK72r;uL!$&L$;>K*m`*GK>BXya|eOJ95|Ho-A?kteau z_on9BF5fVbcd*F85V6zVuWZL%bdfjR*^ZCr2NMey{eI{0go(xn4vVX zhykO#u@AK31(Cg>nkWsj9hgh$9_C^@J(|~Y8PbXW?AVZ`UHh>w-PYu62~IPPV=>bH z=X$8nKP60uhSX%QW+9w_;{0NZ{I*mGH=4O(31>r0q7iJxfE-NLZzFWPM#G|YdcEJ8 z&FT*LWasm@LhbvZ=O~J+ZbdizVIv(xavnNEm%YPu;5%FEvz+WLVuecxS_&y1>*(q2 zEZ2fbx*t}7YQ&O7-eHiy4oi<=^j?J>wj&VaNiyu-osn$(N$4^4E>8nPDh`vIhoUl{H%nkk zr`)gO3V{&R*ZGJ5ySj8@ZLI&@4`5Zfl-Z9Uh-ZaF#fmAu+u4txkn=MGh7H9<0X72K zzw!Y6c>}A*HwQJ!Tmi@^g!@IO+D<9OI))UG`MFO|PcQLE^|$6K(sv{+evj{I-Y4r{ zNE*O+8r1Ooc)I167!IE?r~S0)NHJ7lDT9BL;Cx@;K+L4_w! zaJU92sz~&9W=I^z53(zJ|1QYCPLE6wnbDa$CR1N^J$A7uij?i^aNrh~==I0aR~ws%>b8=<35PjG2a%`)7G?aQ$0DK@%J3FE z6l1p}4zY6W@ouQ6vfJG+0wNRSfp_YHp5H?&E2Gx~H;{B;`$-lLmwr!V6p<81`t-V` zd0(n@g{b_CfaiVPF1F7ncQy|ME<8~2?*XvKG3cto=rIX{4kwq~Y#aM|$c~*K-jY## zg%0=;>8tsA-Bid5p*#M0uobG^`rqoS%xrZH@NONX*{LMk=os4;2fH3Z*|dhr)M;RM zGxF)S4kld|$+J_--lB3+nsg|P@mKTG9(RCK{f`q-g+H{nAc^Hy&{U<{c_U(35+x&Y zgT>$^1efiM{!Jwli76)-fq{AH{m&3oId!`fpLaNsOe|Tk8%N#}d>M=i+_ANjg>hvk6!mS1qv8DXN~OZ zWbT&c_{)`7LU`IBcsCBq5Bl8yp>V07BT_eT&y%w^0K|s8JLkXBmRd;C_hLdVk#_{`HZK9m7ma0~6nX+%XE zKXDk@{Q2aNk~e3&K_jPQXt6Joh^3poyab<*N-XAc-OnW>t;4=KT)Xm{0jw{rz7oz_sy)v}aoY`uJ7u z`u& z>H?fF@{PKq*-l)t6rZ#EZI*%I2euNd1NmRKL@TAe4{M|;!cYdPt8a}0U?jQiI5*-A zG3uUr@*;)ET(*3zibrx2942eM$?XG#usL~oqu{fYeIqg&{Jk&G5Xn=7b#iZ6*7nNJ ziOz~beQ{K=tWdng+BYoO6&Yg1qBF+Qbg~OdU?>^oWps6Xi@z*^NcVRSU|%-Ktk{G` zhxQd9|M&HBbN66k>uI5_5~&0QUM0^mR@j{E$2?VnH06t8+GI;VYf=8iI{g|J8SX;R z=>W|iza*Jcl3L}AOO~0_bF9*+^K-++wD>yKFK)X}9uPGbnw<=t9&dWXFjeiA*=j7p^FPUP0+li?dKTg3omzR^BNTqrWqm3uLS&RUQ7q-b`o3Ho6kKg*qHnA9&yCRb&2m_rO^z`mpYNqU;}6cpdcB zHwl0*w5h0W?QunNVu^8Feef2IJ*KwdjSWzYBrE<{NSuNMR=wUiFqm>0B#~B(wDPt& z&3oXGv2+GjRXvjmK^%hl0k@W6osL`H%Vi?_Bnv`2nKbW(KbMl7FSzzjmsfk4$T2Sv zH@7QxUa8ddm?)%uE}Nu8+9(?3mE(tNsy!+@@+eo05`asXyeSi9pT;*KC9YH&vW8{y zY6{_(zws|TUDvV6(ZlnoCj8dzwLY6Xc&CqT8y8`B4se?dcdsYT8jBREdqJ;aW?YJCqTnNyiwVLQcbB71?N5 z5aS5HH%|{butlnD!&Fq-D2T3VdQCGyYA27bruQR&_lJ9MVmblo!`fYLlnMN~VND$# z*2{e@BRUYlHOMe%N~5=870XEF(|3rO5h4M)n<-nnmridj0+u#&uGBx@PKVDE0wXkg z;e(PHo85KSE68*!ZNL&HfFR_1KJ7LXXa}lV}$9yHZ#c5m+T0W`>GT(ym7gyz^ ziZDWk$%As{%2dF)JIRm!IZJOdr;L9%TynN!dyl`Z;l2%j3|_hovDB=rSun2dl7Fo0 z`yA%d%as%0%qSPV*d=BA|80HT^z%MHHR5?zWa&Z%;+UK0ua#HyJk*Nh)-*-1fKJqTX;Kz645*zvEHQFd#n=DfY z3cYAkMab^vBAc;o#OO;tloct2ekRhe7?(eb4c?xsm>BDTxs1?e7n4s z9v-P?!*LuuJk8UtZKF@D<4MfgRnCwY&9{>bLaZz-X!>?;sy_r}^m)DLluZ`{rj@V@ z=LWo)l^7KvEJXfxbKv0;22tR{WmkG~S#{Z59yB?%l%!M zY1{ZR98Z48>g0o5S_>JMua>qiIf=R*zPfaP#-U4XJ@Va-^@T8U>yific)XdvCoD4V z5|}Y-fCclt*Qk|ljmUA4u_KvcSC5cS>J2FZA1%1o54-6$=Jhcm-&n~&kC9OiHXGvL zbQLV)eg2mR3mqH8%%H8c0dG)gKSS0`?eEroxTW(MNZ$a})m=>% zLSwTDgNV9BXCZ6`Ej?3HXpp%3ZUo8gJcdO<6cOZwaC|+xgtXW*!-qy0*h%Y2Sw_fq zJ!TdTqigjNB_y_BeqkE)v;C@y&Ng&+Ngz16@VA&OITc&DgwE&9#l;>^s_&_4!3bf+ z`C0X`UX2wVV`=TJONvQRLQSLJs@)n(QyRwz>~j?$C86e9Uc1D_Vvvk45P$NG3ChQ> zCsj=PUPvj-4(I02<1S`LwOg!|s<%G=-QO{Vl1Ghx4n0QGQcQkxdVNIcuqLdb;!?>! z1gA_lvjr&>O8T;hL)>Veu`XE`ePbBQPe8j525^0V7=^LE1RB=alKudnx)`&J_k@ z=f~^NS0%DZ)Ln{WfqzC4FUsiKR(6HNj7k;?%En$%#vhHwr6WQvNk89$Wx-6)vSD+{ za)J}FJ5-03Bd11wJikW%%EhRXg-Xdv01zA0SY(va5lbA7#9^OocQ+C+5yrI4swsLZ zI-#I8nw`3yCEvi}PHy?y3+?6WS3KJ2?C6XDKd%a~?#5I+UDWm$fhG9a~vug@d zY5>e)o~yjJ;Wbs74PBp{GSUgpC1>X=%O9{XWY4}S-M9omJFHTdOql^j7S)cL?)faw za{Xo-a?O(>*ZOAquz}WUIu!o@0+n8r%f2w9&YRm)xS?WM7u!e$bEVz?Y>1E|9QiKN z=oC#YH%|tvL|D*s{bE2ulO-A{@UZl|ye**gQz7gTsMU3=`C|ub6EhRDC5a)+%s{t} zL7X>%x?kiav;Da`=-D_~wig&4*1YMHghv6QlrD(8nhHZo<|h%>U>lXwQoP-FdC_aR zd`-*$A7WH|f_B4Q>o_}Qws3- zv;NsyG@rcsY-7q;^~EaPfz=$(G!ut#tT?XNawhads&UhaWvZCpOPrys&Sr(}=_~r* z{~)o^4*4-LkswKiVZv1tdCc#mP02^3wg#Aw22b-k)qMHg#>KQpVk<^NHP(T!Ql=Bb zkzxU44Q;GX4{>yo1sp*5wYCjX-%#Q3(Zo_Kt54#jBa#+bPnwOpAYJdx@!4FAS%8w{ zqIrc3b&bcD3M&m>Nb8A<3$S$xYlt}QK z3#32wsB$Ep{+#q$;BhI|c%qRgihcU5$SVtiS5w%{=@lTB^_SE6^ayom;UM{DKc%XC zAN?;rHufn{>g#`S1I$PPuNsT>&E@hXmC(k@jD*fzU8X>EJtLJ!047Ui=ci-TO>K%d z8i}a8BJ8zXcDRIJi?YPfqN*F?VMISTlp?%3^OmpqC&M8lvrZKlQ1 zbZ-9ev_m^ZwX?Icw|AT&M&Ve53~JXg)TfD7hx^ANh3Ps{=@oOs0l=!C+pzHP;MQ5x zrezp~Mi&}5KCLpdvqL^S#PH43vF=F!v8Dc`On@DafyQWOItKs8oDHQfG+9iE=q3EO zoIblIH)T+E?QWunW8?4CK|FdWj^omtJJxvQ3X`2HwRw5(p0ydRDR2&YIQpak?eCSR zo(Aub0RAcJ6mj|Ris)!(GBye6%H}UQT1p*!pErFpK+x*C5V?z7cL@hpbgoY$}JV-e%>B=L8_l3}S=b6bq4;>EToiJqd^RXz z4(B_2^ILybON^;FBu5hX&p($!ujnKvGTr%%jiRc;KYJ;qz|AiGRjtOumEG=uApDti zJ5J67`dF<@VW4OjNeXYF;AGs*`2}Ic3>9PMAGo+g!Q#dK0XE_ANI3i&^@@b>cMhXn7@>h=g@cvn)4{i4L0R-)cK2 z_}IJrAOP4UDk5=;rqIgD;L#JP7kLQfl}OG@R&&EqdU#(Zu>JTSSTK|=WKeF*4@_9< zjys%h<`~kqA>t`Vd{P%bpLj92jO5)(Mpnl7+~lXopwe5BzXsW6itCQs0oNQUGfeknRFEJ zefVl)^R%kqnC0>9B>)UG^42Ah09nr_-!uF3q*78xUJvTf_eh;#-a`U>T5Zo)5Q(9M zl~pwS`^)K>Cy$Mn>E_+9r8#bWUTrwjR=U;)OiryL+wvb81t~O9uz->oy}~=AG<#iw zAux%ZkUZQUn;mMkjb5$1F@nI|;jPKB6D($Cy9Pbh4t&}2P~XW{#9s588wR02dvcougnpYpY(}h)z2s~7HT~{& zY|r|=@k_2!+T%}(xJ(o$+sJLs;Gooyl=7d{zvrG1Yb4oHxw@42fHN})Qq{hB4|eA# z_4EtC!^0y?E!-kF?bS<(>whN}S42X>7A|fOXBMiJ^O%~qJJBAVW6U8fpc1kXDAln3 zYDXCRA0q|`%boA}I^y?B#&i3<_$@arIu{g8*hp0oAW#vH4 zKZH!m$yz=cCo7{a;7oZL?>asCjK!S>Mu^%Y=3QyB|#6IC=r)L65l}%k1t_G3(S4p{Oj5t?bOP|2t@x!UF&Fg*CgfXv@i6!+7 zF_Bz2hMr#>UAgqPM<&^Jnv$o>M2OUUMrM63I-2^ofxl9Occ0!xJC)0=ctUl!dcyxsT1O@o|cS44dD?8{1|iH*@Z(Fy!!-p?IGTJl4#&3lmg6<-X#Jly!c$QOclm2 z3Wgond?}fk#~~_Lz0WgN`nPWhYHnxCF0;JU)9?c>VIH)b+B(|1AViWVHETj%;%YON zz_GkGt)(JSqy}L@k&R_lYX~T4#2<#wtF6Qto*Fe%L1$s8{zP?Bi-}->GawG@g>Wd2 zQ=TGA8EGD%I9t58X&Z(rU2&K!3A_r6&Ei&z&LLx}~M6Fu%DUk#Q0pp6TU#y6r0ZU5Re7xwJ z8V;j8wc{>Id1j%s1e(>MyNc6-=6zawp4-hZ-(%OSk)}#BZ!vq&IvW5~u3dfM+VuM3 zAGCF;Z3EIM=y&7W`;3eu&JdL#zy`(W2z&kym50t;Do&K54XpK2L?3R-;`z2pA7Iqj zn0D+gFBp@FFC$4M_A6=aa%DfxPvtx7-Yvwn!C>cQA2#TH-wG3@&#kZeFVidoBfBP$ zW4qxBZ+k4Cn9^UFgW_~G=)(CMFRy<(z?{}53o3+a98)|24erd|F^qOT2ZL?K`&OSF zFWX||FPyx!y%q%=BJZdvfHQ9Zl3;CC;7}OM>QbM2iW!e-+b|;@4G4}rhzJp{VWeT{ zU3%A8n~%T|gv73yEj3CW;}oj*?2aK-(x~a$>VHp_j9UJhVK*x)7hCkO_X`<0gusL! zeHpGYxb{y!bY(W#7ffZi*$yat%CjEw=2k)*t@vezmC6sll#3MOmDIyrj6dkzTBRES zUz%Xrf|ajcU+PbPlG8ih<(yup|DYg)cvM=UB(XZhJBZEWfn8l;wjMhlRU?8@GMM~b zM-JKV1{_IU?LQsd!WRD>VSCe*N}?H_TAn)>^1VCy3+e46`>%&?CXFTo$mA{A9U=j~ z&sr@7o+oF|u%}8Y|8Od8F%iD|z6&Azwq52=k$%?)w&4nXU)(gbnh}I(5%EK7hI)@18!q2}>CRk+!&b=Yu98x-~}r zYuy4P(tS+><_Z~Rj?%t`K#`@kkdANW9#ZwSM_(hUx32UG8YD++5bfTE{tcN=IP+Ta zl5i5m%FfLv4_W}rp^eVWe7Au(M9&_!x+bLwOwLpL5*FAQ<{Q*YyHHErW~%jD_= zT&4G-Ws;pMvo!gRn@f6OdAr)t2Y^^g-5i3qmZs0^Wh;A_19JyFTA-X5&jm*0A9SW4WtDj7A`xDfbd^o|mNGE^m4$LCfVn^a7-~*I}>MnDRGeV(@TDa*Cx}`N%*fP^{yk9Pr zHC3t9O{a}#ImQU~^vTO2`W=^bZr^gcDHljeClh5G5*W&7fR;HWM>}NgYjNjKIPgoZ zUpo8~6<(JZqa;juEX`VmDU@ZC!cb&vP{ZqWz;0{dH&dUDV9!VWOXs~ZpFA++K5D9O zqjpSWHMN8NQWdQt6o({?8MoV_zm7+A$R~i!TL*wwK;=Gj5;nQ@DfKTn*bM=Dt1!@O zK3ID8zi$$A0S$F;{H+Z{Ct*j?3uFNhRzPq$9~(Sym_nUl;7qXdI^c2+G6yED=goZ}bX(Yr6) z7psJv`4{T45r8P2viTv5@(kWsRq^6tnC}y{7p`_&e*f(RA`>!FXz>q2dFWy`2T+74 zT6A>M*m;gFQW*rN1m>SfXC?)HUBd2ClTATjqJ>|C5g+DLw1OW1?g##A?!3=lm3_N3 zs6V!^^@#J}4k>uRf+FNZ1Z0T`_H5TfejBEi>RLkhav1S$s$n0Z$`!#eZjZEUO^~di z$mHEoWbv`bH);JJ=4}~?_^|wS6LD3Lnc$inW|wz#PTt_ov%FRDBcjp>uCSyd20fus z#3%$%PaA(i9-iH4)4#Dg$x|3wYEf#r8Gh-4UfBj&LOQb~8XGxHr)n0!n7-9FNx5`? z+PgBz97Pn58b_WrS|2+*M~58PIxvmq0We|HQ%g^e_KZK1F|0>d1#Zw~!nF2kH>#jO zh@XGA6d8Z?HU~Z6NMb$Ual@e9GZ)fx$4S!gZT<$=KB*L0(mDg0)4YO7QenAMk0ER; zzZortzRj!@DDl3h^uCObx=dTx)i8o*C%-Wj5PtbU7vMg3yH!x_R35MLl&$U8rSH>; z%&fI$M%v$-!7}bVl}IC(%|RxGxhM%K_{k*FNrZ9y-p$}8WUu82kIb~dP1Ph}W$Jn= z3zE($={Vg$FDMF=(xPk}qKr%IQW60%d#H@n{-hO)sjVdSF1%D8al%x0E-{IDet|ga?rmu=+OD^7;4TvjyRfz;hK-J0H-jKVnKjI*Z zq-xxThH(WQ=1>Q}<_#61dY+Tep@&>Fn^Vv!jU?%-BixGrD(6V$IZr#%cQx!FR9V2J8MH;Yv8|4RW9TR;jmN* zTQ}Z-gzku%DPjdp&E820DkXI_#udMDo46{rWq#6H7oVQ{=bS!1805N%A9A&N)E1Id zxXK7j@J$cX`tD%&ZDjJU(;8U;Q{1x>$o8$=Bws=Fwja&HICxqE@3Z;;U3v zRerDq(A7SMMVY?8Vf_1Q|H! z2!4OOKfMdIwM>+a2)fW5J~l3D)YR2d4=deDQrW1f#P1TNdfB83Qa4%e+Fw`;(mCc6 z>63Exx;hit1v<@-v!JV=?%)O+>W42og+35tH;k&g)0z${3^Dd8>(jmG;eW|>&p*mNzj z(*LYgpPz$jy-rv>kq77R)-ZbCT+~A^1e=;gA2BSVg}nj2 z;7FP=DIDEnl@)+ixWXs;nGq9wVtWe1nlK!!u<%e_*3wj0xTDj6C07L&#t3w3!b zf?tR-w*fJuwN>W4@-2^Vq>9pr(jy7F)&YUG5l;^1Af^3!@--5TSPXzdngD$QRUcn? zC9c}gz~4`mY9-0CTzW@oR}OW)U|v+)9qGxY^`Mi7@bVL4EK+(#*Y4aAljozO|3%hYM#b4hLAnXSEx5aDaCdhI?(Q@M zcMI#>?&4Ox1 z+Sz)?sN*T^QZCI!o)$FLHaDgP6!NhRM6%UVxuori=5UIK6EmE^|Y`Rsh$Ha5R?$VUvy` zx}?3m{Xxlr$w%S<9V7?t{9bz__;%aob>0DjP#ZTr&QbSu)U4v&&?s9ZW&a}<%feya zKRi5bl?#s_AH!aFU*_36#COB$%T_OJ->>RYRD5qJqQiwh5&eznnh5S6YCiK8Uw({> zoIBqXi6W{Y)NDm#T)W+Rw_852n!d<)9Qi!J#jq_(faJJjpkEhhoWGIZzU;B`k1#&Y z{Gs=>@z1Jc!QrPlAuHd6R@LYAr52g-`+)jyyv~u9tQD@4ESpg)E5ZeenO_ILV}-SG ze~m|(kT2ngZKF8f5*~GUC^)uh*j=B?eOrsQHF9AU7}P;w2hyJ*afaSz%^1s}LH)IiYDYdU4m@}A9ju02-y&TCDS~4eW6Pb~*-7mSkyESD6^=?T&#*?vK%;!{o32X&Da0>0u64 z3Bh#i9)+{=#+<}myI-uFKWxQFu%-?pOH+l!Svz$^YP z-2W>%WOE z`8tWT_I@$T#Htu4i&fjzxWismicw30pp?#aeN#AWGosO;l4Rx}c+nNLW(guUo)^MM z%&{cGJ*wn0s^rs>KJ)>aW`7o8{Wb*?u3;C~ytAu+*9I|yH@2AD8gt(B-pvmi&2YD_kK1yJa^A(o_b%q~}Z1A^?Xf4?z45wb>8p_h{DR z4RBI4kiO;R0bF@(IaTMYw30%oi?Or2rJyNNb`f9p9ibD($+`mr7qsS=Bq<;%Y4djRHtF@FILE*6InF=F2G1 z2oC-=ur+VP(n2bH24j}^M&##y3jX?RNVc_!@YbZ<&s8}W4sXAB8^_KOF9ShSt4{p} zOj0_&rG(`8-j`B`204SoRivbDgjo@Jdd^MY7Ru zzR~yI0$+fTj9=L=K6)R>N~8dPk_P#rY5=k7V>BE12V7A_xE`R~U zx`#e7i$_Idc)H|ui=qOQI$}`jWUHe(Dpj1&r!!2|=Z@20J+-k?q}q|tf1BT#u;Dc~ zoHgp*Vknt(B2p2hngTl0gY9;-H|{;phdU_WxLPEc-aB()$p4}ylos(-tIW)0UU9o> zGMv=Zoz1^@G*CJ+6-Z^;P&gSj5_)#__UazQ*i*nrI(!a?FL6jBe(ZkWHRW9#PC+l; z3RNG$@pkY&*~h+KZx~~2>@KTBVoKJL;?4Sw|B*GM1LFAAS5*LndeG(@Di?Xe@4Z^& z;mcLRj~hMoR@T&{8v4AY*`V7O7NTdj2t>^h$ay{7dHVX>Ac)e6H|rC%R!8CAH0CxN z@%(B;?(w*_NFFY3w`uZjq=1aVM)*or{vxs-<39}Fw+e4c8px1KfAVwNAVP<4$|rka zA{lhR3UqDn2$CrGTm7_~&D2h8Ms&d>AxFSo$NlG)-Ow?Z=4IHR@yPA7SF7Iy&0xHN z_s{ZE9hktx-0QOO!<1Nq?D?%U`+b1(#L7QQkjgsbQ0U6Yrct4{&_26th^_Izqu zbGUiJ!AngS!>6X37(TtVP&4b5j*X=`b3B8}JHA&$l~vO1M{WKax_BJAlOc%)@;G6pkcYT~w$_Vbhg`IT;jeDe;B%TZShckoiR z;hSAGK}c9bOS+y;sv$!<6<1O#ytX-i&ieEYw>&Rx#&ASxV@ny1xQmDHUu;|Pmp1`G zMUBcgcX1QOf?v^BC9cJi$)>K`i>^*I_7+I?4h_rtiu{aplhGX3Gl@zZ(M3f}fMibK zDuJop^;@itZ7eGlf6+Jj=%T^Y@O4cp)nJ5q43KE2sE1x~TBY9P5X#z!>Bk@4qop2- zFkbO!yc$es^j2=04vpl2WM2D4ySOFmg-q~aX8L4eZ;Fd|&Po^P?;ygD?5nPKy@#r` zu?NGp%1rQjj0eK0)xr*+j01#0BML8;O!e>L!WH6^Q!e0}4EZWN1_Vl132v{h_Tx!t zYC0^}wT~O=uVi=W_ty_sZP?dVMqfZjDQk8oni9iRKQH(4|VWJMRV=4UJ5=m5Zsmrt6&&9QJFGg$tT+KdPGx*DXO z$rn;cj_371CUVYpdb+m!69sacKhzPZX&dS^3kYjZb#drkP4iyO<6(3aLGz@wg!ddZ zEv|)L?^sCeQ$s*SJ%)s~JX$Hsn!c2H6cR@!gI7==UnPw9?*(SB%U1f5=;n0*<47?Y z@l`#%RJUfSP*C{WzULN;i40 zKH+Mj^+*RpKIl)W%=GxTvgqvw@I(|k9RsbY%)TC#~lxV}SGWPc|Lx zi0O^7iy8!(*o-(GbbFhMq%v{Dg>$WrnfG*C2a_w^pR%dnWlNLPio(h!V3Zkh|1f^G ziz}p#Gq0<4nXl@t9^wVpR2T-~K+(#pD1MP&KO!kgrNeC!LjUJTRIhUgpI3YUopB`l z3lCN1-`Sb!63pPPtUd3n)&+6?lDeRqd^#yiehH&!<`4kpq7 zvC_rqx6@6@vM=|y6eapOw6ql&#z-R<(abm5{vK^xKadH>2$x>l%YrSBe0>LM5@kuj z#UB^{@-wt%Y2(7M74|RwoIV}b*Ex9yAScLRRyLN=A(mXqzX{Iz2UKXlpK0D(>QdyA z$D5bT_tfAjji~f!rcM6R*H=uUXpu>K$ z`6(U7pyNPG9g^lkw`vo)Re0Gm_q-AxUptt3K-HZ(pOVkbdv15cmsOU>zt#fHzWSA! z^cFBAh^3Y{whG_TobuzjtmiAp$;$n;I%NUuA2`JqbP#$Wci`-=D8J@p`<`_gdl%nh zSmgpx)#EW5KKn4(rH6qs*QzV`-jWN91=e=cTd|8_JLHXI6Qs$9A_vQuv$bB&-gg3j z;nC2`1K~>>q*?Wm`S55A`o3i{Gt?5}$5zl?!)W%l^IdJM(oI=$01vK|0<~9K0?{G} zd2xKY8;PF3iZ%(-<{|4Wh8sUye|#~1I$d$HX)L0dM_AAWX7w}~^mflyY%NS#x!P;q zgpfXiUspbsMEVUnBu`yFesa+3L`73Dkioqts0act-u4a_*$2ny8^W7>J+FXWvo{xS zaW5UdgpJ)MxlnWyMdD@XeBn~9Ccdnw-Xs{Oi24MFCRoBhqC-U{*e-0 z-$@Lt^gVF~g5kDjel)KA4I77kg-|LE>_~3fRPv7Me@?qa%5!3q*+->ggh;MZG;2+X z529bi|0^6*nAgFeFP!=H zjXYjVS_8J|IOKQzp_FuX$u5<t786r5iDCRA6#rW}>!#DO=1qc*1`W{kN7 zX<)l+{whXcB~a&I6bY5$bvl3%wvSRoIS9H)MwEtRaO4^k|?zaj~eGTN=~=L>4#a(Ae( zU$Qa+I&Wf3{uZUt12d;FuWDH`=~H~^t|_HR#2c(~Ou_(A&&cQA8b^^pxmX_bR^{7s zSd}8%F(Cm}S8xDK@^nu8znz6TN=kMj;p8v?(StwLbq@OJD<{5VVK3_?Tl80`TeFr8 zE~0|%V6Q@Jra68}R7mF?D%D!nbKXlfi^+CTeKD}X1Z$3N-$S%ycNELL9)ub#$s}#K zS&(Zk2i?()A0Zc{Cxfvh-g328Zz$b+`MtY#<_sgT&SL9TUPpVHtK?j6t>5taS3|~< zT8%-7YkX&|{*h_ACB!=E;^fqSG?_s^5e-M;^%D|Vf+z)$b$Lyk8|2US1>*AK3M@Ut z5J-zs-Huyi)4BVzI6{yB`Ikp6^3T{(c-GpD{)C(I`aC!-4!(_40STCe;1ZU=3fCTt zA0>jlni%&>75)kODRr1eb&CPC4~jZrxs-Ak&G*C9{C0dqze;Aa;xR(i@U+Qu0ZlV8 zMZ23Ft`;}=a#+RCRL-F_jAapUC34~p+EJq^>(%;bb8kHbU#nb!VF8W^O77h%1V@0J z@rm&fLeYrt9u90#%LL|%3en05IDciGeq3<76?vbJSl6dXbVhRcg1nxtVRF@n`K3QC zoTNe&qUCcfC!xqJlA}c}mls1%7ypl+oJvs?Bg^-&xGd>J27U2pu0?b-QE&t93!mSg zFoPS>UGDJztWvgx(h`HMOe@5JPtWTs?#edDS`QujovmX)rls0JLOdQAw!7?NF@>?Z zJ5R7xL)mNH>HcbFqT08!Ep0QIgoJ`0GdDh_qjDqsv~T_k9^hJ}!5}Wp(E;-;|6Ugr z=%TJH*SysrnlDc!+?PKv%BJrb{&^k0KFu*R9;+3$_NczV7RNqmiFHjm%Sy%qx4hf$38DA#Nak@g@M6gCFY$)x z5#wA@Xx7~qM_%~oJq&3AXhgo-$}K4vO>~ZYc=hqPliyN+_wwNZOqWw+8P5w?GNBt%w^M&p+`b#SsVl62FHxITYSzr=to!IERWAtuQ z9<+Dgd~oG&=T?e1NItF&uyU#%YefG{Kpv;|2O~7dCp zZ=Q-=pNW@W&;sB~NDd7bA@h1n8xT|QTv1@gOGHsx(un$tGE|GKJLBjW$emWvkY)+6 z-e@cEKYAix(da2!%WV2);nK^`37sbijZK>0U!*#mmELW8T;LiHUa5nW;#!{fT=;z# z<=Klh&4&g!s=r(bZ*T6}`1IQ(s$m&XJD}r%()LjXFh`v?NZk$9SGa7mi&E`C%C15v z^!Zc>O>427ccaP+se-c*YN3Vhee}acE@iy=>HLGYZu+9TQZm(IOtwX`Q?pJYFuR)- zIXP5{+nO_q{y)zYeRMRWgpr@0LJlLa?|`jo?Oz!M;lb(B)miqG=DLthgt?<*0;nL6 zq@zoLXcU=N;2Bwy%2=rZz@=NueUcx zQ{l-9#VF_SZU)t>pWuiHWFTd(tKUJ6ikd&z79vm!w{oi_p>hJBi{j^OHW3-DoAA}> zFHY@{#brZr=+e#G$z33ezyi|c>l|KpMr_=e|--j9EEm_@X7wZ;t z@nKwpZN_7yTzR~3AfkqOVLP$56ly=Yx+$({9mL5potE1S<^Afm?+|H#3mF+1zklYW2gRgsbdYF>W7WM3tuY6uixf;2m>$KdO6!wU#E`KYQ3wIx0j(TtWSz<>6m3m|}Pgss<-`yMieP=&-OlL8OBBLG$j%TaNC7>4zKtufqKh-C0ck9<*LrSJnjgA?LhuooRL*ww=FwikSr#DW>Esgp1 zM!;$4Kh9x>*CF7H48rwxioZlg4^wFH+yhR#G zWdw$p@Sj82s9U&xkG($p( zlT2s(;v&U|-5A`Z+h+*X@Z{@12rx{mJ)wgXz4VF0YnYF3Hi(>U8$akwUl1m%%18aF z#Fplw(l+!JFet?;yQVTpw}hlCr>*jL*Vl^}6mVi-AdVE$x4$xwcj14NHI|eD)Hj@% zKP35uqS0w!kS2rSN9CNR%!>OK#$oYXBt)y*yuCQ!Eu(Wej-gi**TmMb9*cp(9+BM} zRpA(oW3$i=Po2l*M}}2MZfICI`;A99Vr1U7Wl*ISed6Y$a2`J0Ucan{1#@tP2VmCo zTG7CM#34HSIpB!z@wMXsq&Q0i&$+P_pK<-PLKby~EI$=~_G%X0YD zswEYb(IaMJ*<}IB0Ht)x65HqoqlV5OD~jI-05$rAdu4UYD|1%8++m+k=-YB{CPty) zRqPp{m38O6hRuYn&6`J@+_I|;oZRZa&L>%OaZzs^pchBss>str90^xmvCG+lv!7$q zot`GBYmIs));K_{K&O*=>K}avL_-6Kl{gxurL`!_qS?qvdM)OKs?wDI*dRp!R+eY{ zha6&)I&-r=C5sR{k~6iN78}nWqARC^d5J1Ou- z=Px;Z7s=CGc%P~T=FS2P2X+j)2DT1+a87Jz+a||w|r7i;H$ClKv)&a#D49F9#!cf9WPT-)n@1Yf(rI|^ci z^zjMt?EUcd2EFt~@SF`;u@6Q=W#kq$6aLo`f~@Ks=Iz}7@jCl~xsPRsrED8;w?ewF zo`AkX$V@vUaWT z$jnS;Tkpx)X27{e{_72G`{Q+6#cAx<*OrH?{D;liwI0@UGp~IL!Rw{+ry7-j@VFXu z(2UaK?t{o!*R~7nmu@c@;g3HZ=q;9QD34rOzVkWW)O9{{ImN zeW#A46uxmK<6)1r^Tx03>{zp2)^*i0pTehS%bP2rB3e-Sqt>a))o()8Yk3j#S#kbDLireyoSl}d#~?)+-UqX zxvp8C*QoKAo3Jzy)X?a+?)B3xsZ_<>K#(dDmqL%v?mE3hhIuX@5$|q%!W{&MDb>UNlNB_>feb8mcti^;O`1)+ZAPN4w=m z)C};tRbTLrJDg4A&aqw!l_`JTw&Wp=xKVlEXlHE}$Q6>GtN>^0l&!9_D`Mp8p1T2R zDr#u^m6+GTi+XJ%sBvl?7q7M5Cv05PLSB1wsJOCbFO4OYABrR;Ha)8(AWNSp`Rlg?tPEV7 z7F)5~@Z9UC64OLGR8-UszZ1j+;dkDhn^vCsmX;An$sNCd1^f0O-jGFZQA=4Ra)>F! z`81+8X~AwPNa8ESNA2C)zZh2>EE=6z#DpKG_L1uHDElcGadEyfCrQlGZX_ylMx&l?`R01|8Wu`s+0j;ZsR*LJuV#zq(4|GG8+Yui z)BAU_hN(AhUdF3NdHnUNtWhX@AL$~eZ$!l%)h0KEq5aGFNwIVD=+vjn)%gpYrA(9D zqiq%6o}UUnyaVp71Jf_wwl5qAsiG;a1!T1)f6ny?6C}wUz%t^RLfqSba7i+tJvI@#C=gLITB% z#P=O>RHe~NLGRPYvF#dsTZ@qTH1u&6txFnRYB3^h&9XB`4nnrHk4rG1^E z+0@4^&MW_FX|#^~n+}k${Biv2)__&D#9#MNMSrWSVijSy5H`oa1>$aJT;R`EGzAf? zi9aVuyC=BcTn@v3Z`~L$0|L$-NcX}3)FKZF!u@2yvwmmZ`Q3WXiJGx(txwB${@;XO zQOw?;M$9J60z&8GpKuFG2)1W-UU$)u47yQ2UizMq6NI0!K|F z)v>CzQ_@X`Akk9MY{l|f@K7T(G^KQxAxk|sqNL$3|0VpO*~#XA*F!+OG|?1}Csn81 zG4p&8^<2t!sY$7p-b2WuK@`fP1N>`G)r;#UxwP(aRrtU!6P<&L)HH{B{P6ef*t{`+ zcKxV!)uO_r;N@~{=EbH?Tzyl^E^*Qa9W@96Xb=aT*O)!`7r~C#VN8|F{x4shP8Tb< z)2ERd`Lz~IS@`QFOdcSMUT&(O9rOFFFsM-djt?51j)oFcvoiDHGZR+3rS;w|4FwFk z(%+}ju+7mwfYuM7yPXvPeml6b{hMmLvWf0zJc;Zw<|Nz7&K93#J#z*Xd&6G0s667j z62JR3>!`HjHS2<-A<}o&1C)!h6FJxwDi8}@aFuHVvJKLVxA?>6a*a<0@h zjj-P*q=Vv%rar~YW0)hshCu70R8%Z(hf=r(DE?uz+H=iO(5D#CZT8Xg0LJD1!= zyhjP|f5}O_Rzf0&zi&hr(XD1iE)#4Q3{|zW7Y9Xj$lAGc znmUd^f!V06_*h{Gx_8;@+|jBVRyDpps^R;^npMv!>mQjDEnV-rH_l+p7sS^i(nPJvkqa?MJip9^nd|@vQ4-TEhsFmfL#v0e^f^Z7*bR=i%|RULX{$6|F8HAo$u+=d$78Sx&@-#YgeFde!cbtF#gmCvGRYmLvH~`fxbEa^Pm%hcnD$<6!i1Z*vxceoJu5H` z zu7THdZ4N)Kdr1QsPfYqv%zvh4Lttg3dqKW$aK(596;+nvMa+TVoex%#tN6ZY+Q1uC z;inedr$q=?MC9s=rzp{{)DrGO7=unkZ|2A#-I*MpD! zzF~)-L_-CEUxeSUc6O6!jd!#By|z#_T*lIhGdjR1bqACpZ_@bzr-*$o7w@UXQqu{q zV+ohr57e(BAJ5JtK7ViiviQe+4Y+)>=r0hwrrPOc2N8b_i0pfLxF~PEbo`jceSAJJ zK1>O`wG22OC6z2894737w|<)aXi8}8L4s@IbKO0=@DuXfe)BPawnXf^igLVp%m^%i z*eFE~dK}--DCz&O7tOG{5e)`OJ+P5l$^Q2E%Qt+1tSqWLV5-X+59jwXAFC4hgz&!K z;dn#(QQSAAd@9nG!AX2$_D+u8;LFP>U|TkdQDSB&YQ3x7q{YA`7cT}<;d z(8PC3{s+tRp92Wew5g#v^1cKhA|`HVYnt>DM3uLz`wL;Uf;ui54R%fr@~Q*c}?Adubc{h%R$>)$wSPa}#b#)Dl~wQAO(&*@(f1mia^Px#KU6_V&%8 z7U`C4hxK*>j<&p*5jF^zAx--o^4VC6ta0oju^D%E`u( zY80FxEp*f{wMGe}8Vqyr2#+Cq>x+PTx}+*(AI2Rs5`5KPHw3Ao+B?=d^U$Z@KX!heKB5nCQMeoKNoX`;E*qPbrnJCj;+T9|`58eA5G!^LyHP;NhPg|%#i zIpi9C@p{@9?y`n0WFkC>Dgdi_K`D!-vpAKJMPWhkNR-xNO?*i>B~di<+j4`8(QDm> z+`*j0-!);u80=)Fv=hH1EfEY`9go34hQY(dCk3cgDZTgqwXNxLq<990NYD z^zkgA^WLw?V_#PY3X&9H=)(nOkyi-@*Ie5;-Uef~X~;i=sgy+>URTE%W%tPkb@xwy zrfx*0l#YlA;+ckOzmZ@S%3Q)3du7S1WLi?I3Q8_guY4QY(q~nq>Jnf(P#y3WsK2Wf z3IOe#W1gh;sAqGSdu`~SA2-zb2l;vYgbMEmeLOz!whJHMp7=hc8T-c9Y@tU;#gRB% z4URC9lk(A2QMo5M@ASMsxAMrmOH>9;zJxpa`%WOKk8t4DsgI{Bz%6iV<5Te~38|kS zHbi6~VAgBD27u}Z8{Mto_Csw^6NH}F`>yLmM$(>Qdv4mU=19F+xcG)t74ru!-j*dI z8H)5$Ul#*!i>bWa{V_;>*D`Ft{p=Bg$$nGt!~6GtKUQxaCr!Yyv>p&KzlJjn0#TLA zhm>Kz-asysx&6q>NgRX0KslBvd?|fG`&YRP&K{Dc8Azwl%)xFqR^tfUR zxz{qbF+@hC7d@&pm2ym|t=}2;-;Mb6uC)~q*eO_;wPfo~2h8Gz_%SuUyOXh{S5nhc zs|6*atLg6ZirdOm@5g7;>u?}RVR%;^W*BvjHO&f1W&04$a}pPskHoO_NE)sfZ1fGb z3}vistR39d1%7GUan7dmAhYY6yTFnUPDHH`u zp}q`?KAwI-@;f&7%Z&Vq7Rs@M24ggZghCkFs9f1S5l@4QaDY*RI37=H8JMb3yMLf! z!Iw&Io`IsRwG|R?Gfi%#GRGgQnVwb>ep#D^^oEf>jmfNTZ_^ORj!gz{Z5dX#Fb8$( zFhv%@gS9k0;+3@+F6~mTHmjO_dhyvH32S|(KNcWv2jQ=#7 z8&1fwX_#+8Z}ptiz*>-mgG8AQ9Nc)BwJ4=}bv=oz=U&g1{`RFnKuANv;I9P0pvvhV zM(tLIS2Cf5MC3GR+u_&AkfaRcjl6E)iCtr8NjKP5Lz|KSn&*D&>gZT|_mp@J);D7Wuh z+sGwD`%N4qQlSP%G2zRd@j~Gp{_+Ec5L`O|VSdS)_nlJja>FN`cC9&V-P>)Gf;&#R z9~nJ72`y)kN@-!h>H_|`-_8N$PQNY|wOupKJcg}zV(D;W7*%`<-jCe=sJS8(L^s(W z3Wo(8)bERIkVPHTVg>8#gtQfD2c;0S0dSa6>q&cq*oPK-EzMM z>V1(NaUuF>=o=p5d)RipufNv=IM)70x`j2P{h_34v4nA3TtLl2CES&f9~_4!v_)cx&HCK;A+nS9%n6JM<9fEN7ty}G0t>9;BxwPmo(1nC{0_hE0pwoj}(#_ zc5!iOtnBCI$eeYw6rufQ{e1;R2_HVqhonX`x zb*x01?~ioQt*Hq_kjQw)wIxt1_Ij@yNt z*zW3Te^U*#N{WsjXP7q+R#>r^PU%m8nf$pkbS$d`B}ALu$}oo^u`jJ^mDiCW8xaN_ zf#ofQ-*8zc5YH8r@c}9p!cWUWn=J72RF>=^S9lBuXSEJ64`*UYsj17C`;$DnmsGHF znm$z^&a1Uvs!LyE!QIi1f!PMxR$fDKe!QkkB3I{XIf;?Nfj&i@z}SEV@dv5!+ba^5zBV5xDjFNJbcwd`!kyNxu143L;TAAchqT703(5qXfK(31QM{zN0 zdH_^M(nbTHm?alo4wT^wGu4CGqut%eaa%b)<07}{#pM*fPS~Y-&yQMTBAk2+TMqg- z2M2lT=82ZyuS)~>&Z$McCczY~w)P6oHP`M3>s6F;RC?u$En@O2RBcF4V*ZTO ziq@l?N)lUBY#s>W>O5RObW@^Yfit24t)6hmqbsXBU1OLkg5qrRg#^m9ZAogBAtQJ4 z0P3U(kUHXtAH%N}ofQ+p0%f|;LMBS*oWd4q53Js0KBj5I<-7oA5kDFO+CU|opyrvC zvE15!yG#gw3|A9$)L)~0H$)4zmUXd<(FPxKI<2^~5XTO zzL&1P$*U_i(#L+dcE2a~G}}xTT#Yi*L@%Ukui6@d7EKPH7yBLU!RMEiU$Ae|QClL4 zxzxx0s>4E&#(Q;ubn2f+$J2y@*MG5NE5>e8D~%GVk|jY9vuGS4PrJw2dbSIf(!w%@ zU~;$~Sj*7YW#1v;t^1cZgjD|DOG#5R$#M;R46X$pM1N9F4z=u%1RENhjQ@hvUyCPN z^Re_ivg2NC&?r$`^1%t70BS6GiT)Ftov-#s(z{=M?l1T|q5@uHW@eq-+=iWWAU_du z0d97C=TXhkmEy;S;{o{cW_~M%;ShxFrh$1LhiQce7F0yeK%~%?T$U2D*HF3cvh;#n zkVM+vmgdnmBS-7TkEGB9?yWfz0V5H09#Fg#IkhBq1FuXe!99LWH|5?&9Q~r6db)f4 zcUWre`~FsLUh;Yz)UOGuQ5M!OP~p+u9f!;+Js}FXBqnNG@ZZ|8l@=~1wEN^KFpn41 z@9#avFoLwA%PO2_)Uf!}f-4kmy<#L$>RXThUZ&3a-FtfN1~DST^4ZkKiOI&K;{1|; zz&O@=gC5<1y~n&FfEyx&?MEJLjb@5Xp5d(f6x54v=q^@Lk9n@B0IdTF508tRW9`tI zodSE!>QLAEybeWa!1131y{fnG-Q~%5d7^^yA<7o#qd4d%;piTJ)(nTtH=(Tr0yZz*NBGEba_L&Z162h`K#u`!> zVR$jQl6uh9=S4>7ohV${JpLo`le=_hA~%2EI43vXXrO`842V2o^}LBwe~ej@$>zN zeN@?Mv3Pl`^nQE~Lru{@3cvrE=RgOeQ-h~e_Sf&H?vL+Ku3x^uc*EY^h8j@YfJx=z z8OG*e+j4g=rO=e04wymT?FYm@M+y98DBlx9@MBI<1&^J=9hH$wQyBWl zp;89<@$@$H;(eQRx2s@!>?(cz2&y&ukMM#%T|*%~imgrGub;*r+QvsmEWK0b@2G)K zBF_tge)#V@Duc6cw>vU%ZRlRftGq$YsHukITUTjJ;?=|NLhrkOa6H_?nXIYS5}jd1 zZbNoPK3*T*KSweLyaqmvzCL`6jDGL`cn1`Kl#9obllvZfNUzuCXS^7TL~ z9U5eb`u3ahzwmy-#j@53lU zVx6m(@{_@`7?_Q7rxEgpZS@uNC0MG?x@XyrsL8osi`|FTONBAZgZ(g z22y6x4PD*@*~yHG(<8N$Ej5#^@a@dM{MQ81sKYdtl3GM(!%)ZmF|Fbsz0u})6J*_+ z6+s%1`Q&%*;CU0gRbyCd+&AMTc+U-#5`(CERvgXq#2f0KxX$;Z{xzKI&Z7oPzdK_` z>lOiZczOW(NqUyPSN4RyJ+b2(1n*kDyj%(hDJgrXn6mfvh^48ouP=QAsk!9G0w*(Q zFZTcv63#I4iK5N-f-*;jTsMPAEdMRxAwCBPigv_o&WdRViOq32>>YxOu2O@Wt+0?9 zuvZI~{jWrQ_&vL4-s|zju?$ieSN#mc0QJ!z-N3}itD|lm@1(&Rvaa_ zt%H!+)+Vj7p+PJOS(gc?z0%Y(u)wqL!B#Z<2_}7#fR;*G*8V#Y1N8+4jC)v+T=J$A ze?D>Xwpri|5C}VYgi(qGv6SsOMPgik`(+BjR*Q7HPORmw$jXljuX4s|ALu*Y{L3XL zDD#b<>`FoeB?PMaY#cRK(}7`LUT{~}*N&fSaM$`8CmDH+2G=D-U2cw*8kPn|pu}Ji&P(+n=oT#>uOhtuWpHFy?uhszt2_O3+6pULXMx$sUI!9iCdTPUJSGx8{<2(WyzhJdBA`=I#sduLlWduy+G7W&SPssW>?yPr z3Wx2yE;_Oa1%y5LFEkm!G3WLj2{|4f>GQOEa~@p0-$D+Jr^vuL9eMfQWWmRZ!RE%{+iY)8 zPmFfQ-Tq3u-<_#4VItyrmzT)Wl~RekA2(w#lXknEToA22;TPCZR_78?aixw-b#N-D z;C9bN-i68iN6*CU+rJOsHt@mKyL>kYs`oxk+j~R*f|lL{;0afu-bgX<8IEI>bkM7P z$li$ZhP)W14r)fXUel)8O$RA0Oz{gpjP^?pqJkUELj{yjuPQtoa`ws#crABsc7VdUewo1)ti$N#@< z>3`m=2RktF8F8}@nglhR3=F&uUw9kEf?SPs&Do|5qnvSykq5uwAK^!ZuPZeSQl$0E zN#OiTPRnU3p#8@!T+Cth$gh525GKy1Y;LrN43Bgj#KP`;MRkmi2#SJHCC{Z2qX-?$ zf;9)EI@_GsM*fcED7*KIPcG3~&V8U8vuq<{($mBzP_WmjK&ZDkHf2|&o{8g{y zyN)V(nlugmGN08XjO7W3l1%aE8O|{@P#gbOq@sHYd}tv3b&xb&m@7)thdyUv8kI zX9F_+Oeyr@23D<>&Y%Smi3kf@c{=8lT{$%9%>41Oj5<}Ba1ThgNoz3B@~oIJr#Zcu z6`5@Tth77r4Q4yEEN6GJld(u$0~?0f_q-{2oyB_5xd_=)rk}P$+S>j=q&iZya3&AXO4!D)%)cC$JSW| z#T9kiI)UI4f&>c@+%34fySsZM!5xAJ2(H219U3Qi;}EQoMuNM$-xWbO|?!&&umUbBnt4uGX z;j*IA?(oE?hffl+4wfXaa_cmWBa)+z37uxNFU(Q>pQWecnr)z3(IM9dE!8nb0u92kWftE9%S&GQOf;;=Gc1B$X`}!HDKHxGQQFDs`he~jl4Lk8^ zJKarv6hT*7jHg0Tneo{-^bMp-`Lqrbyv^i${9|5i}#qsDg3)(n!9M3Im(&Eg`k^Ul;^rqfV&{3s9#`2)T zJqC>VQ=cp&6Zha(KP@iJ4+ReIjFTvecf!Jvy}=(0%+$zqO=Jh5fjxJ56%dsTtA0Gx`)++vQk%ntb|vTG=W?|0G>bMFPw(4BMYAV|9aHi$$@Zh=}To z<~B}VA#xh(o!`#bSN)RDYU?m9NFwE6%Ja&%ojUpMkKW^ zC+jas)UPLg-+cLfxzFIY|oH|qv6=6grrg<9Nk)d}8 z%y26=<4tEhbCe$@C?78;9{DV4jU)?G`@i@f3EugwoI-rl=r^_-#C}9j#G(UFR>O~V zzIVm~7wek0F#nzG*kruKucMEtk+7RMX$M`qN`EV;OcveI(NM1-{Vh^OYZVr&amkvZ z-$2t@xZ(>jCZ_#qq~J@8M=y?p#6m=rF$Cxej)@E2`PuIz9QXEt@_)(MkG0=Lyhi#V z#(F`9S{%k_b2->iSmR8IGJizK5`}ZS2rI%t3M-&-m^CUE_RgCq$7UfNZ5(&ZOsN zGGkgj$?o8b$c;D=JXA~TAgXd=Kq|mQi zhSo_%dub;0w6Dmd4-EG*g0#qzyIIo5Xh!0rqA)5D3bB(%BG|^hDX^xG0d`osXlq<% zpaYdXto0&;Hb1a6T^V($5I4HdN>lp7MJQDQ3SeUg#w+VDIgx14@DZ%(Zq!l$@L>Sa z_jASk&}~4Fgz^1@*$T=5oL$T<7m0 zOJ7CjvR45z)kwtkeWE!btAT8WGvD>RDeyDmi)bSIdko_gbhSaA|LQ|+IVdKa6%-X) zytae^dWATn-u%XRChvDKREOG(B5fsoA|g|+cGt)bw1+?BC46hZ_YP0&gEHfG;Ra?B zj)hxxAEZB&S6Ba7o}bStO=PHWTLyn{$W7i@54l^tNmf|jS5NhfT;rhKt>j0 z+}Z~p4Ugm5rfJpqzG-%RMm;O(t2>`(R~o;QB;Doln6>t{=*lCO0-F5xzn7PZWo1&+ zuIg^u$-A4!;`jDzV(RMdH0*P*NN{#rXNrhPMVGce0|Lr8dn)B<(ztT6Jb?qA&K+SV z(8cpESR55F?f~NfvQg^}LiSPDyj$i^zN)R{;snK3c?5{TK^ZqnR`5ZC|@AG8l9oJG#_wx0#+Fs5}A}C?IrLa*$SJ4VWJ8-Wd+5 z&e^d~EtHkk!|&*E4Whj~wM*4t@I9@#pPj|LWRu^0U&s?H3(lif!rs21*|Ht?;QG5J z`Ek8Nu`{zbfma}<7g}Oe9$;r>6EKyg)*X@=n2FJEYvAZ}aid(dT^sgso58_5ap(61 zwyDrBcn%~od&a*Lz7vdqi-qQSsQQ_eK(>lCl-lhEBK1a`RI0(qn`|R@1Rr=8CY*Z= zPdfllq5IQmK375o{Lk! zjXL#AW~S>ccLYj&mGb3ka;o{VX1aR!@nehAAey0P((3)uDultptZFlys`~7>iEq>Z z^^?~%Ywudq=|Q$n7Hl9)sE2pe<5wgx0zOBMc2@|7_)3P;>MrTwx*_)qUAeMKBC%###yp~N;9;e})=kq}i=-=-zgO~L_ zCn_=zopMa3G_5@dUK_g!-Z9;-<97}^@vQw`wma_h3K+p}Vp-vT?N5W#73^*Afb|%L z5q9afs}O4rpA4D&?D2RWd-5>ve&+6fZt1aymc2DTXCRUqx*VC_esF}ZovdW0v?;#& z<3BXj|0|sca{Q4XHF3)U`*o;!$PU%~+*fa$>ffYIj1?Xtv!)F?jK|h6dW|zgj3b4y zF&oiSsbY`NQ(Ye%qL&R%-P2QPTaU&7!6}A@Z0N=z(VDg1%a_CwTlMtRiT}unPry!u zXb1Ef1zpuOl~wfqN{j8Br+7`y_0rKyNgkW^Dg{*)B~ealI*^UfC`$8`hl*K#@T`HZ zZi2@<#c7;rJJOYIH0N;(dK42xTv6XVoSbplT-5%8@Ct=9kK1XWscJ zl1<9Q6|UTKWB+#5Pbi|%PF@z5aCwKn-A3NO@3WbvUrD7r7cNwY3q(<$o_rHk+JO)i zn|v?O$pOqwCZ9Dlz2rO8H=yf?pD4a0hMx z@+;S{vO<3j>sQk4M+aUQg)0~el;Jr~!=}AtmFtVLe%i5TPb{pgSny=lwX_UX>Nd^) zYXvxhZ)|esGyF@guCAPH&h^$Igny}h)JJ(eElsWH@Yqh3G3DP_?K1&G5w0HHlGFgY0x-LIMsj z{j}bY`f*)?eghK7&Idr1nVz0*Yn)pSbB>0jwn64R$xrUytsGWaTf5S< z_zpCfl(CX^R06w*HgKh(8AKW5TtI}IG<yaq1%)(0+$@yIN|Rx`b%Ez1@+T?PB^s`yl4LOu-l7lnJ}>nP(lgdjI*;U6=FbnsZ|) zTyu2|7r7hS$2(PrFAo1R$}=2D}wa`pr`JBn@BXchp$S5I0e1JvmYm4e)41(M#m`sW($2eHFXGx=|Di) zCBl9kUiM8&;2bLd`^n)2PtD4CpPNfI?dR>Ebi9d&(1PWa?th)uPb^(cElVMrb}Z+M02~9J zEqv{^H?ehG6uN~>B1W0E*0Nz@)B!Haclo*$%6e)ObxSW}UQRk(otOYMBM&R7fg=fu zu!0#C4@c28-wJkjCD}^R6blq04LOhCS<{pTDEPSmkxmAKI&oAc-wPTu)k0@_HK1v5cSOPs1Yp8Szi z!)IBf6|V-4wMVgZ{8lY`oj?xk#+|rX7H^LAcJv{s&*E39(AJ}`<1HHM9)NfW_=mKU z&q@K^Shwl;G}^sANb;j+@T8SkvUx^EhLK##8|5Y4xC3R}5KTkI1L!!)57{_JTrY7#X18U0{EA?;*P-+RmR68$jx z{pLkE%8=?|1oj?{Z_Voj%ZjWQFmXbQ&#oeRpPG@~Ty5-R7@m(Ja z%f}dQ;K&VxD;_?2FWsbUW!(9oey_yI=~T)bq-zmx`;)1&)!6 zKwvgx^19#l;Q#JYRpjqqS^1bS6s+hEELa{6>p^xUKmZ!uyjy1A+5^eh*w0y^%o%av zhnhM4Hv2CyTQ{jEN4l|`yeX}XuIWK&qUf^k+HHF z383eCyWd|-|10Dz9f2L%^Z!k{J9_MN@)nxER;O($B04e{u&?qN9gXU1%ocoleCJ$~ z4rvT-#S&1+k&URvg)|)D?L=1nU^9qG&Ukxv#)y?Mxh4X+i7QcOEivomSN{G7HPb4d z>;0G)OUyy+bgjP(jpI~2b--8XfS?PE%*T+zUA5FvAl?$vW>Sb6eFQ_b(w6Uty14N+ zWsoSFRS*Bwb;O_8woPUn1h?4gJn(#g-O19)xguq>6}Fl*GJtcm$lK0%hL+kYMtXbw z)(=haoa}`xXfjpT9a9=fRIfRlTsrX0u#GTSi!{TWd6W>BI3r_*&*kU~gqZkm7d>T` zxFUj#HXExz-sGz!?V4OR8jLn^iJ;3&2s^OQHZM`OG8)IOAulkqlIl|Y`dc*hE^+H9 zWx?fb{5vhzuNR8H^12y_T^hw{$qA?rD1!7R*_>U}WA`%tz7gG^7m<=MSdyJ4NUYyhmYx0k6drP;e4tXwNBE|GQj z*2+jxJRYW4p&MdhY*dhQHUY8P8#09lUg&(`K^746KWzeLtKQ^1QeT<$6W936!7>`-2o(4RFuypF?w2wSACYIL21x?acUY7 zd)v?cAqX^h*de&(8KTH&BOU>$!rjx1pW9OBh%b!tr#R_N2I&7Lo{E#w8Cu(l22w9;`(r@_< zhU!dtB^5H&@OlFh`Xocb^CQ~0VY(*0jJv3GhbJk1U2fl^7f{#%34q@+;Q9@5G<$ zNiWiVuvc>$fA3r^W=C|+XUY2O8=!h7%6QDRt;{ZpNQxhQ#{6?aad&i!we*PIJt8 zEXIJdsDeUtEwrw)bE3ODV1jsMnL=Jw5i;>~huJTF2Ppv_&L2P)xpvv-DQL zBWij>mpuHWd8P{%rF8%gR ze>iT7X{{Qn`?=?`c+Pec2zD=bY&+QiM~c-!Th*}*JN+_&b>de7^crYvk@Q0g&^r3h z(X}jo=*HmTyQ<+HmG4URs)Zw~^(8ogE%&no&#GmiRLwZ47`BYFi;`R`hr{fT zT0w(|++;`J8goi5KCJMFx4eesk5F^N0a-dU`gbd3^C&^il$U7mon{D#PV@mvpjtgR&3Ja8abp^Z)^Y>)r6U0m@#XilVTJ!j%+URbc$?X) z(xjcr!2HnF71{|-2_`JNoL&a5?R)H_1ye)^rEOv)jXWCo~M>_SUpuj+5m(RTMO`K4!Q9;D%2Q%g?xCC^TB8w84RZ?^5 zcyy)VxcE@ny&vqFV11L#@0kqUWBoJ_yfG>abW?0szErc!f+50zgHFtN%$3o;|A!~$IqEqw+XmEMbs)|U)M1f=*7e@-5|KGb~hEN$f_wx%`mgfWfqvFevzx0ujw|9E(`OAjOHjq!K&Bb?U`!9o!+Grr>$&UvR0FfA4Lh1qybmo(uG1&(4Jp=i9z zplGei{(=+-@hq+1T=;5@7L!#{p1|C>Jw@IN_Xl@kzMa~(`V(ho;sK9_h3#w(FvW;! zhPBSahSg3RU>B&fmEZGZaw@AjU?-(BxVWuOk0U}kEFq{Yi-s z>Hr3Z+5R)He%qzvS}{C*^11C1Li52-{M_8uM@|=fJG;BcJ0E)2n6>7T)ztA4`~U6z zGqMzvMK*}S)RXgrV8{zK^p;kd@dd0}PG}Wq5nko(i<*>iDW39TNp9-uKwbez-Ugk@ zu_%Or`W$YusXR0aZWcO4LAQQY=j;Yl*~;`nG6fgh>zq}qoB!5yL96HV<}GFd*%#ny zUyMp$Wl4II+aS`9y}*mY@TcQ^{-&+S8pwM69U52_iYJ$&qynH$(`%ns2CPN2^GoYB`33V~Wx z>WbTpUPkp3v6%9GRJ@sAU-AONeJ(t9Fag@$wu^xU&oASyK|XTY<3c@92;-}IrwA5y zagLtU_#(Y;KHo-1m^w%EV+2E?X~2OzzHs!ttVHjJ%-ajc@pycMBKvQy;m&9UbpUhh zT(|R%X@SV5&LvVd1t&R7bxOpu7ELWeX9cBmX?)w}y6eRf1H#L@5|2 zdWcZbrTnXXe@}>av}xfRdvu9bjkNT;SwI zRe8_pdtc?x2r?58D>MhN4Gpn6Ad!5c98SQgo5a*gWuiMb4t0M1qKK>njRmcyzFZkT zP>Z5i!?#>F!WETCsi5@6Ii!>c7tvq}2JHJtX*0H0hL(PrToXp=Qf9y}@C-nZ+4v^C zUR~YycAOsR!v?ATU1s@hMxkR=b@S(Wf2xoIlps@P)F#&hI+S;)!`Mj_sa_~+-SX<@ z9ztk+oooG)*UOgG zkz>rsn$w8GX~#F>5jOfB#;*BFULCB16rcUbO41QQ!aLHB2r{7U1d5=jjHdQAIFD|x za>xpy!>i~z+M#KIou>ae(ar|o$Jve^?444nf-5u&N~NIR(a>i6;z%0Q#Ke{Ka^frA zXQf-c5X^{*c;eYM^#6@XE#)n&#rZIt9W1T`)ooU+SlTlQJi4y;+rh2*Cz;)Ly--3~=zs=txLNOa6eoeHP_l=Kn$p?CuTfB@wItf}vG3xD#Oxos%V2v)zD~%4Ou*Cy%y? zn)PSt&;?&?J%)M9XB`6frY0V1l%DFNw}?T>r%#VN|FxQ5bc^hBp2Ot8HXG+=1j>JH zIW{gYgMp%G!KdQRQAvUGcNOYp*4@>Q!_}v^8!;DyWHB{>SZLdrLod7EDxx(s;D3yN zoBQd$9EjE?kfR7bI17%veJ(uN+4bl#V(v12*MpC)MdrxyI*wFrAC2L0Xvx_R&?f(t zlN{TZuPnh}Xgij_#;6$1V0Lp*U_O@LiC6R>>yjSG`5*adAa?^%f=RJRLs3#3#GpXX zTorJ^4I*)e7%~4n8~9}D;NVcnf~8lGkb2mLyZO5u_j23^V@Y1<0=gRfN=4z(AQhG%BtxK5e)hoR6Z&w?bTO>?w)y1woxFB{o0N5&%x5#cIjLK0NEz}|2FL16 z1;#az@?z}~VolZAoY0*K-P|q59~*x7w)CWrJ2CZ7^)Sgrk-(B*SA(a0d5&PF9BiXZ zjI-P|!3`0%pe`O+Qw#_Zva?!7xtgvKZuA$_;7VOy0~l?Xd9!~NPWe=21@j^iDc5(9s_kE=?O2fudfs-L7k$9Z_biaM za8X)7N5Eb1!a?-f&4E^=_y~h)BJ7pj_uG=eiC^t(GJUi}qHzI*7S6J-(fpyMV!Zwp z!@?gkl%_m{@m6lMg=iV13>}l~jsxVs5t+r;zDj&mDQ5H=7X@?dC&)<(gA2p_He-0I zMtgNgf7{*kb$l>UtoE8UBK zkrP3}OswL{V?Vc|XO7T}n1o!@-S%m%K2A64gd0M3+&Fr0 zugwzmee4vSXPm*C9|Rvlm)pT5Y3dY#heeZF8a;HLc9!+}{yE)xX$07v{Ia=4A8F<4e>z!8EoNPGC<=$~OO+>t0l zV($ZuQ}!C&SLEPtqikTx`44pA^(&Y&b)>vHV>KMjo(t{!V8<<4*A3e1Jelw{Zk+ykF9Qgf-C)J(L|V_H@ye$CDca zlqz!R#dcUpYZO=dlLyBJN0nVa!jqN!GKEOK7HWIaDM07|uCQ18>MIvn0HhIc_iA6FfDk|z3Zpa?sJ!5C;;czh8_^RI30DcgyvBL zhoH~W*a9~#6OMaRg&KB?%MMKpX+_2@dQ)1da+G|Re? zi}B~sDO#G5*7b+y(HlpPZ=;_lw3D5m53^tDKYU!yrFPo)5>B?RIMt|t(qJvdAh9V} zIUwB=0cR(`j9N!8O4I-R><4pm)klhh*|6U;*3D+_b(+i$@W0;Bp?F#F2MD9M4zF?Yr9Qqt*Z48FW&N< zzIs*t`%yj1Yo7)&hz~cx-BnJ^`znObe3Z1yJJ#Jt@KCtV6+5t7V)vT*0P zoB*LNeptIDnY6~4yW`F53}K6D)Ysf!u7che#9rP){(iSyc@gl>{P3HnCrt}N#8ci$ zX;HalSIk*KnYiV&prIDf^p+;V;N8;yTnF6d2Xr%kz${Inp#D>eX;#ytCA(o`HI9X; zyo~$x!3WN$0r^rkW!$Jz)2&EcA=#Y36hJ?&z-fY}uY^qZ) z7Xsh3nI2dxP_Q(TPQt}mO{pOz{mQQZr48>WLW@L5|AfP(d=~r6ULf(8V3W*ZngXWF zD@TP^Fk|I}ok?aM!Hx}sMgy`D_dH!QV2$6k1`yM zhAt?-lc@nWP}0`;z$9h20sQ907L$LRd;1a1`$+9U-^$5F%bxAK?{)NdMGjs_k^L28 zVm=4D0Fby^sJx7#v9y;0k3m`=7XiAMJi3>q$XCo*yF6ACGJ7Z4HV;@G0Qx$#QWwB5 zHk2)E8hC~%`rdPTUQSBhorVdH{_8}FFTj&>fz_1f)I(L0%|B<_$;JX%Cm^pnv@0dx zX>!d0AWseN3k}zUK0O-A+DLwp;5*Kv2L5-i0>ldJvKe)*NXo4wP0?4+NLF9}(UBau zIr2c;MDU=qrUJOSLAp)$!2g?kv`-?e=Mb@@l?oo*xxB?z33)-ulq}rOC6xL<6 zjhCJ|tQc`Il(=6DxN^Vca&_IvcQRCyUzZK1F56TBoy%dpy}ikwC+g5a41hdn&TZL` zytJ&L<88vKvm&wHMlai$38}a$zkQOTrzsV>_cQx4&u{>Z*P_{S{ti5Ou>!Z8fKMuZ zv-6GuNZrRk!BvgJ%`rLSC#b11kQ*x>s`Jk~Ii_i_RiFJtkI!_RpJ>LBjv(IZP~Jaf zNxreq0prs7KIa;xa7-E8){h5lWGmT=i;DrUutfg5Ci~^}-w(&8JelhS_WIZv=zY1) zY+zxwK){0@5xDkk)J4FYZSn8Mrxz{&An2a3Mbk4&u(5cCg~r;Yafi982(Wk+PYpI}=gqRrR;w}+*1>$zNb#=)y#+sk@e=c{Fo83|T z_Ig4CJp0wB5UOk=f$S-%!N@n?fRVqp2&Nm|`6{6*54B|GSA_vUlrG^ zj;H?Yv|RccC|;(-Eppl6c8pH?{k^RU!4eg1v;jr6bEIijriMhU@(V7y*4~mL`}rbvQPpLA*bUZlQZ z7E>>Qp7`VY>yk>VLAq^tu7xihhmTcHdYEHat9{{A4DfM#L$Z+&H=>~c*~e$QKrE%c zKmnP@g#1gwRt86lo@>0x;r{GtIK^Tbtl?FU5Pz{NWoYX%h1Abo17;L9JE?lNOgB&d zhKILy)Os{3Zb%+q~Np6m-e{uUt-X_z~#`%mqC##uamY+0o*ejaC6AcPBKsdZXKy?| zoLKt%XPZShX zcp{$MJ!xlPc_Zm$^r1}C9o(wB?DaKp>&u@K&8aTZ1~^;I@38?EHS9)V?9V@*T-|q& z-0a4*7T`?S%4@YvB?W~{8zDyUyrbWPW2JLAZP?Y9)qy6VW3ueHGnds*e0;2|2O6$u zXH!}kjWynM7Z$-lP)M>d`-Gc{{PaFm#L>+ux*#n6^)G{jBG9_W(8|i|4nLvfs%G~W z4&zILLhbm2#NK@0)}SB2kefUL@-FaiK4vj_KGsrcGbXd44;}ml_gN%$=tg9suOQiF z>94X^+Z_p_klJybjFzlLF9h;SURlKM zwLQl;t~{Ny8w9L+VPi)PZq%62F%71O1Qnh{ug}GS8Hc+&XqGM-E9fhjYSfVSTV}OY zIVWIIiX$)r^cSojtD#Ze3~!g8?goDi>$|jc2uAGpBFwNAk@*rQn)Le@%}SE29cX4N zGb(C$&nDGyV2>B*&TLxS$C$U5;VP-~&S=GR%s0%vs>f|NR$I4(V|{18CB9-XJR^RgTi2&??dC5ow@E)btGBZ>+efA5>`qiiP^d>O z7LR<-pwnPAnfISB)*XmNWck*}d{-AQNXuR6-zw9nMCs0m|5e{Nu%<W=9>TEidcGt5J_nH&(98JXt!te9bR+yeo{sBMD$L_lUKhv){TJtGZ0t+bJ!FVd z_e$fV8mSx0Ypy|?FViWAlYqm{=a)mtEQy5v2@fSdgHv>+Hn%^@459D|QPNG0bdw)A zjQ!GT|F#)jbh<{i^1h@F*LB}i^6^+ly%kJ)V^G&fSpEA%7X&k_6(6^+V2O;t4g37V zrp?q8012(%4VTr_AE8eyXUm%m(A)y2z-4t%>uRQn9Y^|X@IkTQll2ta)(}olYTsN2+Ab7nXBe@kCc_{Lvl7`T5=+#6r-q>R=CKOF)UVlCi_r>9<-<&xc- zuvg^L8kNiJb9-)^9MvpkN9(pwjCeK)ntmfAyGqOY5DGB>aO^Y$ASym$!8ofP3ithO zz`Qy}!9t)I)_PD9WKah9gO`@Mue|ur`N~mLR&M~)gE;^~ucOzl)VT7{t<(Vg$g0T{ z|8jCQhBSVkFjIUF9|VA-(!~X#AN!mZ#by43vW#^k6Z6{&XJXUcn+Geqfm1*u2OvYP z-j?+X$?C_3R3;~+;Dh6*O!LN$BRVad|KNu(9p9{Pfq) zuzC(i0EG9O7>9^wReZoPJ30aVEG0p>e-Z$G3Bdon&Sl}?)W!Mx3}bleecVsPj(d;s zEMLt9m{`JJyzx#=0$Fc@pwf6VrUtV2>FZyD#Zb!CZbYh&o9KsHTo2wqAbBHG5MDy0 zXt>k#jM)gLi9<_-Vz*HiTFFt_vo2dM&biAyhwg>~)%n1T7(~$Wc>5b{PiMT zNys!j7=f^C@Po4AJQe47Rq)>n_<4fDTBS}8;?kyHP^VuWReG3Rp5bOnyJj-I5WtY< zKb-;*Xxyhppc@}W(|>7`{(EfkbR6Bi?V+r7WkW+>x~R69j3MsmyWBv*=91*9JCwpX z;6&K1rrn8`O@);{kPV7#s4gvgl8C6h0mb8`Q_<5JXZ$IOFaeW0GCaE2%@RB5L>`el z%^{KaSMCwKwmIsJwd){1ss*Xfe5~ z`1&vRyPI)Q`PLJiD?cY=Yh9FJ#6Lt7bVOQof9mc_)El?I;}X%(qZI8ANd=xBX~5pM zN$06NLU%TUY9#G!VoS?jKA`B2F>yErEnAwhx2l<^=#{!Qefn!5`UpKa8RkrPsd=@= z{=?!Sy7QE$dvw{V@$vnstj;P$ zR8=$*lFFW`avhxs4&;q~cKz7)sKaBvMk{S%&(Ncog(oEV@5AHY6!9O4r4+LI^s{kT zV`A}(Ds4nv4t+m_NLj|E&}&M96hotBqj}iIF2C<{l$a^~ngyFq$`6&CvXFB<*au;z z^KT$0;)^9jIq)rg37%%20X=R~M{O8Y;uxv@JOhkxK8IA_>kxj76`AJ5pFH@aW2!6blGJ9ms9vG6XiTrkOibeYas*$^W&Z_vI*mX zngf+x3SO!Hq%`HtY8WGQYaFarC;k%r zIhw(X(ZPjh%Q^eu!|Db9swmc*e@+8~YRw&@oBJ3y zCiKAXz-{v1Ec|CBI0K-*7t?}I(;3;>&VYQS5xG!)ojn5YPOefft5J?8BGd%i>c=-M zfE{6rzw5m5?i}z2BrdcE-zKfK*=YYb+Bv&_i88~N`?=T6-ZzX6ei!M##>Y_tzi21h zsU7Of^yAA@9Ex*HjIFvm*Gc9pS6WR(q8o->dyPQ!@PLZV$i*d3?eGSbSFL zwWz>wV4lVgSq|f`8H29#K%^hmwi6S0?N%v1eBwi-*N|;hMq1S*mmYHZ<+RbC{zh1+ zdX+*N`>~|Ad-KPgO~eTekNzi4Qpu&yA2m3oq=+6ihWR6OR` z$R}Sf$VkMCuMZjtNJ4IB2&p0_#-}MwcN>isaz(XKPEPE3@7sJYuo>Q%#UHc02b4`#ktK7zY+uoV$T)RCQ70pN+_|QGU z=IqDmTTD${X1?&j&4hQt^Xm-zTM~kzv-+s}r{tWa<_gN<$`MMn%of{yIx?acQ8;sD zB_e$o58DyRe>-{n*Ae7dAr2uHVYluT4GPe@*Ol-wkuaC3GEY*CBQq&Y_A^Uj$#CGT z8eK_rAFh_G-LGV;T&$id-$YkvR!?z|^bt>5DV}7~aH)>}g_ttjddsrn<^%Y= zn3_#02 z?dfVCyB6Ubbh|X5<7F+UC+`ck;5CLZ)gjabd&BH;0+>>2Yu^-5j6?nz61O9{!BQ zQVdVqg%SY|W$AdMpT->qYY%1Pq8vIbyD>Jz`}89~lC)qU?aC{vX-j;GyfYoOqVw6L z{2-fIDM{WjjDF0DeNNI^kCN#^XZeq#MWAcp^%05}N@nf1U{t~mg%Yx!&hpl_+-A^>Lp{CqNvv-P;6 zuaIv}PCYlB7nyw{6rb+@gaLX9u=H}=87D#PaA3F|x1fX3pA~0$MF5FX0HUpb;)QQa z0M!P!-OPjfd!t} zR_ty+-2#k*)7H6;s$l_l8@Yv=?#8}qI=P{Qj48T3_d`9U)WEvYd00BLVTN7Q!FKKP z*(VN7{Q}IDv32|3esNo_1os*pys|X1y;jVdr>EFKD}O9z);DB7t)XEj#j4%Gu(PRm zbL8O=GM0I%#-K_zd0m!lKX%1PL|(3_6-oJorH5Gg#s5wpU`)0^F35+x`aQUEE)I$B zE{g>scM$j-pQJ;3-(~HtNn_O&Pz&eN)e)oGmFamea7~ommez@ISV&IN(G#ofW9K6* z5(Fy_?JdH&)XUnn><28!;VRZq%|)j_l& zb|_GvmO*6^94`TIqq?vLi7YkprbPjFWw|E5{iwKh{r0-#F4P;3uESLzR7Mz-rqG&% zs&#y*>+lg`F}Iy|G?%Fl24F;E9}~&6GtI%VyfHoxi$w_IJZ+Og`E=_Kc?WIQP4C}c zhnHSc63zJ^EG-M@yxv>g_bpM@2?T(qK!;dW~!rR)~N{F;gChYsl+v(Vw6iMszErL&1+6n z!u9MupJa?r=h>aG2v07Wr%o>G7ZwHQ=)U{7I8U!CGYGcG>;tSQO|Yf|U!q_o59)$* zr5@40lPAXsJE03M5!LquWCZA5xGn1Bnh>az_QD4=8D5b`ov+Dm3(}@Qrqw z^UX1TbaeD-$9K|^13=4}qvYOxcowb9THZ;^cC^`Klczx~FVU@@dtAtVBBY|C((CX_ zIsqu>JBwftOk)X8x%LaVAEaR>p&Y#9>C(n=Fux#+B;4iIkvF|J^Ppd?dHL|v>T8VU zmT3jfJ4JloB_vs_F7-;&_Np!E&Swxz*LJdC9x2^;|ti4xOjNHk`m^S zY04k+NFC(BlzV!pM>c#p2iuE!vIieMZ;tgv1aqeMJ_nb4O-(P`owYF^+GF0lK7z5A zdU|=u%%FT+5VK_Rb2>3FC+Ya-oj0fs&)a3c%I=tuPwH=ZdbR=gm_M#GI|cy?5pend zT-2oh2IMb=VwhX++ZK)(B16D6sf>FzqpAoX`8c_`=6f&r(hJjz0ZfJ$CJy+gg1xVw zyWHX8U90!_1s^nN>;Xu7w)j2qD9;P0W60J>S1p-Mx$*J?t39w>+0%T*(H3bV;aC~ZqiF3+rht>0Nqz~w$)i}nOcPqCb+XTyga9?dEJYFC(I^Y&XRi3GYWGHGBxa57z z%*U+XqKWj7KyeAgdc-rgo|~?h1LoH|VJcJR-MHdFKL@$^0s=ez*L6PPf8A}@WaCBB z@N1<-Oj>pA!0-6|n%>Nf3Nq=IDQbDhtc0$3wd2CFxqd1cU8JQxo?A_vHZ>`sg98Ps8$$=r;k2+zsAupc!=bwIm zt(tR)mA^qX&NNOtQk%uEmnSb%EsdxorMajwBplt`FEIM+uv>C>ym#)O?U)ETqrb@SIG|D~3@bN^O1CRnrnoWp4c2*SG` zz4tdQK@6$I+1IG5D-l^bm@MYV2V*xAS021rJGt?WbL3O_>i)kX$A8^ZQg$CiF(pz? zd$IOPhsOzfN@TTJP!z&ViO?F#bPPvaqFLIw11)slQL;&ZP%~Ax#e3h+V51e$s0Hu{ z$f9BNY}35wslLHbQW7dxBq5ZtQAuw+XK-yZX{FYqKZMax!|yJQTL?A z=sudLs&k=Anc28B6`Au2F{1vCjjzBEU@i>96=3STM3s~bL-rY;sIxV5u4iE~okgT`r3vXRT_aoZ-Z#gN8xRakppNT6cXb$871^i| z(9nXfIh5Btg~^bv*G~D~PF&pmg8`+lTv8^FY{9<=D;ynE1=No-LCPsL|>#(n)5BRzd}{ko~Zbz6OCRWdG81R0$|z|rM4dpoRHYUP)Ew+0!r_ssDQ%r)8WeLlG2 ze0Q4(mtGw_?w<9Z+?jM7)3E{#pJrcz44=0Qi(v17>&Wwo|Ans4U-(a57jU8ZjGpi2 zvfVcq#FL?I$#ZWHdY3yFaPRcwJU}v!fAWd1q@Xm`Y0!m@xKGA1qRE?56uWO;E6-EW zp~ag?V^{A*tG55y*iVveKObiCPGITL&EXrIil3zw{+ob@fc$^x`s%1C+pgb71*McO zL6DRZ0RaICX#oKNi5W_yySo$trKP1CB!-a~kWOhBxpSOs=ltVZ z56cH(?)%!;-oO2eAbPKp#t&&`aUFyA$+8v}PX=(&Q^M!o^6wj4*1Ku-@yse%Iu8FH zYcl0bW`g+gwZH0dLr&;IwJ{GU4n*~IvdIgfk=kR#!5ezZreGU2=rdQ613+-0zc zV?=ZBt>Bsp=0dPz@@p_ht)y1xi(0QLYi9<`3RlLF%FEebBhyerYxnth>|aCUhSg-6 zMxlZ@7+-$ zoL28+q!XQIt<$jsCAy))H+w$+{_y38hbV+`ELRGuai%aJIWd87yYs%O^^7S}sAQpJ zV8l0{fx$hWhFkj<>DamU2i>u{^^AKKEB(*va*vCne?M)k`BEP}&i9c+do93kE}XnZ ztdyfshrf}iTE_l=K%l#%vUYFzz@5bu__+6}XF+|aS>Zd8{8_Fz4w_%qlo>&-Y_{lg zj?1URnSu9)uj=?8eq#9NU3GbV$vZR8^c>3=Y*W*1of;JTU~LH(O|PPIWm)TCF5+(0 zIs3jS;kq|L9d)r$_>+rJ9||oP*Q^D7$P7Ev6SpHoD-3=#ap@&vm8A?LrFD?7av(2 zJkWi|5LgzOaJ#(Z)rWHlh2i9{cfV$T6pGyUl}(_|{sB1M%s2re-q8A?yL-uNWCCkHsfuh=(T`@GTycQL0) z8K+4ilye46p+CL9_PkSsb5xZPC)1kW3X-+gzUMHwGdYRNz7ju(y5Ic?TAP2)&~aa_Uv z1#$W=)9azUOg6Fd+*e`cq1c+5EwM$N3d)>#5#uu^wQ=c>?A5a)er^~E2L31+HBEnK zp*T1^Une(>vSK>O{DB9T5r_gkS1y-p+Dooa9Xv9Mnx?9oJ+(DPNAUhTR)(7UkJUr( zL(G};IcC{=%gbY`25w8~N=?B(++xnwI#rKu*r^M;9B?RmQOfQrwwhe4lgTSrEIc@$ zQQN4USIEc_C$)K7!%9)Z*WTi=f~~4z{rVPwnF_@c>;?Kz~`sv=6!64K#4_klt#naw<*A23E5?i7xcXkWE@c+rO zCH6tzx8GNmtiKCu$ZUACFrN^B# z+OVn9mRAe z;=HFiw9&GU&eIbSeXL3vmpMQ~E;V{wr_x^og_ZO`*elBtMg~Nl6G$iYvP2*5i$x{c z&1Sx!a`Y2t!MV*7b0htq^;#9Y$$;_P^|(40J8W${e|`FigeH zfKz{O+L)%;`u6X4S4#;tpS=2KqscTc19}4x<8z_)Y&d|CeqUX(-e9_Kb_@?Du-x+T z)F(2o$f&NC;SM(5(@YvyVF`)6kq|3JM+9^%u!$y73QB(HRKtoRJm&633eiUL?*%_m+JX~4W6OsK9K)lBo!jR?fk8yw_ zIuF6NSTXipeO~p4#(0C&a+Gl*@*a`j_g~nhxQ=FNE;2DgDP_|Bf#F{?$B3obS;V7T z=kG{q?S~D&n}svI5s)NWI%lXh@CyQr#Ne4~!>onfoLu`(PqOHI_RmIe*7bPxcFUgm z7UCxuq|OuUYQvgN57E2K2J6N>|17`{Iwq`dFI1yb4>=fn=Fw^<+tYb_YzG1S%2P8l zIitdtrJAPq47$9?wbN{f4U1z`-H&?=L2m9Rnd1ePPUj3g z>{u29awq^fANkC#A3Dgud0EuGW}EyIhb#hkgM}ik$vx6hfks`xQ22U3>gqeDVb^y> zHgq@WV&)nZd(p0XfwkYmaS#<5DfIGX-pCQLMMCj+KYyUec%m}?I`8X*^=1dr=^K<% zZlI*UOmg1G&gI1U_Z9I`lo!8I;+;eBxSiEIWp8$!PdA9?>~Ne~rY^8#6r%Bm@!B}|pGe#lF}(U^L~Df#zw#S>EeCFt7^#cviLTjOw4GhO3-IZG-E znHJ;YOe{YYkl|T|#g><6EzS2W3{MIc_qe2o{&1C5?9UFUZIGJ09S5tad^lguF|rru zdY3|z13tBahBoSqVSe&HjJ2*TpF&CD47-LC(@fwY6SXdNt?+W#T{Wh-n}RBj|F5;~ zzxTT*_X1Mjvw(7<7I&9H%p`tpjZD|naxi&19l^yfTiA_XOpq|PRNgU-w!$*KCHESD zp~Lcc^nv%}vLa+?6bg%*m@?VOA$9^SQgSARi}5oUkWGF~qI&!`J1qAz4{@tZ=F1~3 zGx0d$Mp`1TJEB8DjErGMV!e=l=g@acArBh2hH=ka+HT<~sVJ`7qWY3!)F~06-Dqa? zDcM5x)b|dY{1IWOuKKWPwg_UwgfDAm8>()CsJhhI;qrO0ciMDvyV|ZnDtQe7?cI-6 zft-R&E(bR^xfo{A{dUs&>&t6_PWK&6{Jn?LYO?23%I~I03S}<6AAS8*VF?2UrSa2K zBs)e_T5i4ba`7-%Tg>L`bOX3_dVXr!>`nSKvjK2}B9hv>5#UoAczoKu+SvsdN4lj> z7F57KIbT<1tLt^351u zp9R$6A=yW}>P|1)&NsAhu+d$Cbc5AwjVGGbk#=PB2xv!P9q*)tb=qP|hjDi1>X3O# z+9AsV3NdAR+*1a;no6lnC7EMVw;U&C@;yJIU%7yh%_z4?jw zK5kFB2@jP6a1cmQ)5Sca)KTe$I%3{8sUw+yfJ}4Vt-8vCLTYq^+~iS;O_W-YqMeUU zwVyq0p(Lv&hLZbvU5Vj>)%mz;gnA56fC4qV$Nq0h&&vwr0l=dH@X`mrp6=A)(xQE& z-vP}tXWj&OdDQi({~2Y~>))8u9__{+bBSxuos6`sxK5MuFXO?hPO|Bg0IE`4Lz6em z6TM|t2<8cBjK{)4X#*4} zT77sukV=CuEzOv1h!frPIUp z8t-nOJ7_Je9rMFXaqsd=rbc({G^vWvxV)x;d*<>mI&5HoiELt!>Qukyxlxzq{|m zzqWC!z1r+}_vIG7#l|_6zJBq0O%?3HFYE-gO?)MZG(SGWmd|NO;5}1+VqH2rk+i--;nISc7P5VNK*q=yg7F24?6q^;;59#KY(iKxD)D&^LwM~e>PB4py&6~* zNDk_MD$=o7pPMo;%c`l9t!fcyE88WSnl{*=4PZ?CeAg z4@ajSx$Bf!FItsV`*)e}wO}+G=&xeLNp~C3#YY(WP&Mh-N=c{?Q#lbEa1-+ zjnXy{UITU(1q<|hj{w!S{_P$A#&nwMOpX!S#aYc2cd@%n}U$+!J~cKEJ46ydRH8b})O~mdB~xRT2LA zvozS?bd`tuV|M*AUNo%tv#n~HgxQs-?$9CWtof;(0TfFni}fiAb()%yMk>o-YWdV` z?u0t(3G*hwr(8Dv*ls%S*gLuJ0Eu+|Y`pqgKCUDY7#};W5GC;rDb6GU48I^xhzYkV zKq{K^(V6ScqlG*+JV2psv=8Y4_L2u&o$oQRp6t(_87{rw{bt11(t9U-STnr5FzrtA zrA@fsUueIb*7j%TuM9{Sp0~YyMq3-xfGTnwbFX9q7b%M70&1fQY9kAL3Gg03()ZFa zjdfb@=xMi{PY+B(8Bz25yqA9TFr{p^CHD;fbg*kWm^7X^nYcb96+Ie_HGzOdupjDl zVXeC$J#z&2^rY!b2_-1-K|#6C-+-AdKN4+ytf`=OQGn2zsqZ#xGwY z(NM4}HA!V0E_{tb3-{)+q{`(CQK)T+>!M5^%Fj+$J)?MTR^dz$CM%n~rW>{fNf-;2 z)_~yD`3mD(U`A}`>=Kz3fGp?m+;@D_6$ZTo{&;iuKP8)jbJ@h2`su8mTb)f9R2zVG zAfTF;zslR4T?f<^^GBWs@(A!|Fk9yaq`a`t=5%$6wXiqHm^0ofip+}xC4(vOCT93w zYhArYpCrIk!-OzBo^uru7hk*Z2`(Do?d1b`egAxJ`M7&ly1Vq$-V5LDCKu)T&NiUOn$8a~5{dXo+hy;cTy6dJno>>*T6C;{sd? z?%+}ewBVsl*TIK35BEnY3OPKA4oX=7MGmanTuaeD;_^5xN1GEjc_!3Rofa_A-57~y zjBLBv-mO>Hh5W_rF2HA?2`ql^$4V8-^Cv1Y6o$WZslNKVkv>UApui6Pr*=m@3HRK% z8>zc_hHpZ*NdU@I(`-{t@@1NeB#puKsK!8^kY}FBGcO&Hq35xuHf^_3m>^c(u-Hg8`F3lp`UC%!a;TbdECe&Bwtg3#Yk3{awJ0NqI%di@~9~kg|xq}nezdXfW7=_|EGvf(^d5lUXHA<|2BmJKR$CfuUkEpa)@WA5NkUr1kKI@p8z^9dg@*qnFd4|ABFcNb;TxQ$7DBz`%RMq=sO`(06ApR8&ylg00U ztZZ)1_P#Ble54hunorV@b6)@$y&_SXk#^;>eF9^Zbq@H=jU;~=bGk@GaX%Y;u_JqH zf{QA^L|er19I=)K!hi7TPHd6`Cj=*9bMj}9C%lmK@s*EE((#8xuYI01V{V5NWBHx@ zV>Hbi`eb&~{Q8gBJl1*a4Q=xI3}(bN5`p$dUNd z&S<(C+0eSn#%v!~@5byL=pVgoZF63xJutQG&c3|7#2*`@oKlq7I>TiENjOmD2Uaj) zaClX(4^;sxay;L@=(jVA*lh`ByqAFeq;$gO4U<48A@@LNTiQ(|wkgj;rz76F1+Ly# zc;$@d4F)sE7F`wDjCLt0)+v`55MvV&7XwmZiL$Hk?bcMA9@33dQqatpx%b&}qO@n| zB0yvBA_5B`(|&9ez8F%FE`=90<3u2zLmi6WVB0+I(`N=V2n zD!|PvY;3=D!w43NBqJKh2)Cu##lSZM3|kN<3^b#lNHHr2iHh26S!1Z+`M>PGsg(K> zPK8qt`r6in<9?=#-4}=2;~9Z(8fjcv6~qHEi{A%@LRzuK>yfj^FI6&ZL31~+4iC{4 z@FtgwGW3#KcNYJsHfU-C9t|?1xZmH%y^;hIlb@era_Q6z%}i_JSSmAw6zgiuZ}3CG zpXPy~8!}uQNKXTll|)0o8rHEdZ47NKKcahg_$mZUleA3|&1$|zw=Vmi8(zD&W_~71 zV7`bqJS7Kvv+dc!ck!}%e>`L0en-7j8ZoB0hUe4TY`v*tR-fYDCJ0MWX%%DpWxh?% zWP6^?w$c;dTV)}OXV-YBjVM1_S;?*Xo~RCfwg)=JDjOp>0%AuC;NTOJ6oa3e$@4W<>}Tjo6wAT)(hMCulI)U{)pTyCruTo9E|Uo zjP8i2$`QA|Oez1w9Yp8HUxc?fYWt)&W+aK*%3w z+U-Vuc^!H8z7x==_Qq9W+{k-iRQ0>}h6&$%O?}4JthckSk;wHKgj^ECbgNs$hary~V3; zeZS=i|JWmu)lR>y&eKK^tY?O10a9vkM!g#HCpIZZi_@B$o4Y=+NJr%kPfrTk zRvB_~huXTFpUi|hyKs1z+tXq(fTbq@Aq*NFKP$;=3xWFvaNCVH0p+9QLrR?utmN73 z^Y7s0f2(L#T53qZH$gcqLh|8N0t0zNJ;-$>>@ zw=~m@Y`&YSc;JL`_ifpo`Slkn(CLS!n?;1}y58$UDLpRcLS0UuHqV)>x4fS;Zioz7 z{*{ao6-j%bSSaExf^&Oq1n5}8!S$XS2q@$J*W9WSmjqBsy&A8OI`>@%7l*Fyb!xR2 z*&`8v4MX$7U}YN7*I; zb$SzvtANCLg@h7q=aHYpL3Gr+4MUBZM=k)Q&1So)_#S8L1t41BVu=3o$^7{|hL0`^ zH{j!{QwT2rH7q+J5E86g`(EAqbK0PeKXl)jT|82i=;d^`BkoKHJoe21AA`>VM;@sB z;FsX4#=c$E#Z-y@NqAmLE|Zj zz2_$3Fnu5nHh`%xNz6)40Nl{*lKkWB_ElXRbEJRrmvA^RknqRw$d9WPH&M6hCJ=!)VbNUwGJ+&>W&k$ zt9d<%`(#1+Y&~Z+MUy&}pAnh!ThgP)1B#ME9;|GIR!Z*Yvx#h&`^`EFX71NHxd<1* zsB~wRY`1UoY4qWKgOLr5=Mnw1rQ${ky2e|Ll?cCQGF1pwCb#2-lSj&VJL485fmA=BG#)i_$_+q3Q5>+4@} z3WED@ywQ5r*DYa!vn;Wx0WJ*&+MWr*rb%}mvKNM!7hv z8BI#Ebt_dH+%4e{B9MNiP8C5}oBi<%r=|a9wO<%OxevV zLIO`*k?pbZ8*maZ=c8r_1Y3?6X5I#aFP}e)si^MWNgf$FKW-Q`Tft)h$Cc(W0nnBK zYDVqcSDphk1LK_>n?8-A0a?st|3bX!)K8CuaJd}iDog3^!Z<1RPwGG~95S8^0Fh=9 z0^nRQeoh}DH%5#2N!`E9VDHzP0v>v?M|a))k&0Kt1JfjDH@5(kLdP;gY&Q7D{L$D8FAh3N< zj*zVOr3z-CB3y|2<#LKM2p(ka9(Xid6jiU6L6Q}o;rT`w5DNEkR;zx`fPZ7mC5?E? z_bPFmK{E6oc2N^qzS`S(AA!JH1TzhBm`OdWY!syImquV$3gT!mM#w#k7-WgVHjR!h zV6SE4$vaA+kYnOyBS`!0>L;%1!^}D%df&?Y24lVd5SklWz)Yb()WM`pv|Vmp*ATXb2zUfZGfO zK&0$S&u$>apugUy_qPakh&}QBe)(J{&nW?dFebusr6D9F+^nkeb6vjm!^s5eDmF9~&oJ%_CaBgLkNoZ}B!00-=nPCQ^G7Vx zyf?Sf^=IgU?1SrlsnjlDCKnx!fa_=qR*-@{iQM|xAVBd*+aIyh3((Z%_A(X&{WY|; za8t&4O$JlsM7X^71={~g;$5!Vz}37_8o3XUZlrtf2xqfNDRzT<0zeYLq^+lXh0=eY z5;*^Y4yBMav*ds$Q(?=`dGg}Ygs(6}+I+%VANv4bd|4bb&GtQCeb1;#V#CX@(I=1f zm+wLW_!-s{{R-U}Z?3(YgitDit%g&jro#p2^J7~8%1Pmfq^XE$gUJD$V_^35UPP>z zuSJ_J?<-?Uu@5K{>F_Re$@G^+pdS8tS|e5m2hO`sBu=}%8m)@N(nchelO>gdMHqE( zB-2qQkTT^zW4Uk^*GFYDn@3irz6B$|Qw0nmR*X}SNE+j=3Xry&fS~ zOcgwpviC|=_48d5ST0sn{l2|)w>6*OKjzpFR zINg)_DR9Ud7h2G_a}PN%IM!KDW%GW-Yb{#i8`;SDBtVXede_{7=qbq$aTth(-)XI| zNF}f#|C|m(!<2~1OKcY-*m?7@_@%6JN!V0JlYZ5myIDjg-AgZ1Y%E$ux9!w@`Ax*X zyBTJapT+1;v+X@O9_}^icXt|>2k=)GqUAT5!@B18QsOe$oJmAjV(}qsU$z?*7}tV2Uj$M@7dQx&cVAZ z%#avHViScPr^feg;w%QGJbA2pK3TF|9VGynUw6R?$TZLyC=Ul*3Q@%Z3%5{xB)Y`bF?qaa;rE9Q`|D$S zT}DyFco)=K)R33B$(>rEd$+_ts>EJ zZLpC}@kdpFK)HD3T0*y zryNm`2ge^@i3`8rOH87FYaHicOBn8GRI zM4p8E1oGc+<;>)|KWCS*$_K)uH4=hV3gk6blTa*ei{C|`5w}h!(L8-S{DeT{FG=p+ z-n(X>s$9~e4X#PUa|!=DIkK1Tn?kVde)sMU{Uu;nF-B2pr+53J_1T4#>}cufX~y;L z*X%Cns`~hOFS>rd>;P|6*6OpfA3)I85#~IgsS5k&Ug~)WIrO7(ah7fB)MaCgtZ~wb!6RB&FqB zQL5QxM5UIH%+;&b!_@1P`;KdkQzUv@*PPsb+wV>#x57x^<2{hxGiDVON0+7&#j^#- zq6#siR-^x=j3YkywVnBId+8$V#sJguEdLp?#b(H_}$bZR5W6v_y6BTV$CI8r!X zmk%K6U^Clb5GAUbge-V%X*-yv?5;-Ua}b-cvNLy%$Q~VdmLIA*ri=YlHc5kwdd{G| z!P}jh;0)`N;Y`fS50m0ddqdsgq19%entU zl?*DtfIpLzz~k)fxd+z8Z}X<+?ljV+)ns(6^LUs*HkphX-sYFyUwkm6{$Qho1mxX-Dz&z3Pg_&GCk z!9K=}FX=5A80Ld^zf|oiMhs=<`mX&l&*lttg8Ug6YbIY5iWw$3r-n4X|BWHIE-eO)P>pDaI<2m7bvZ=Tx+<&U3*ot>@#iHdp^my!$Q zLuEfEZ}dLCmu08$-E~L|)LPl{Ivi*qQ65Gp+EwF~4%>F(HejIl-(A6fbm=!RfHx@M zfJ^86^wIkIpDqUZLy-?7F}F^coNZb-{L-Mk(Rj@Xd3j7}7!2ly(ZZ!<;Il7#brN;` zi}l$f_LZ&lxg~en&UmkP;O@5$TNjF~{wgdl^b%iR-s#2Ds0yw&Drqv=LoYEfh^C`J zWwD+a1@H`zA7FfsF&O&C8fj8J#81GwQ>)*15#R97wfSy;j%n|P2ogDe-pAYdXu%t! zEUe1R9Ao+Eal+eNsH`SCG$Nl(g&pQrr*)}zJt~2yo!Ed1lvMp7se8y%M#it8_zL=a z93ewYjJGWl%Kn6J!DS)MI8tbN{<2dXRqy@$RxiK(cql7deZHz|?HzGiWth3uZMj}&a~p2xo%B^Ne~K8WY2 zRkzbj**)h^(drkXeW1i>{8=uiWoL&Q45~l`Y8)k|l~EvyJe{QXP2KnCA-o<;0SJaS zPsdL-+-^lnO;Z6Sc41M`N{aGf7%q*xC)@gxCtbx<32S-|o0PTwjD>q0=u12;dy@hB z{x^!U(y~VC%7~gwWL5z=>E^1T^?Ae5Ll^j&I-- zcSAe8ht4B)CpAOzAqmcl^#))HX7N^S~008oj5WJU>f$Sf^kDOh<^L6J-@(HSNlUD!EjN4#9$Zo0}dD@8lQ1(jk-o!pN!Cm0H?F{&3Ug32v z>!I6i4*{a`9`_v#oxE2o`4jqKRLyR?8BpXMXn}8%GMG*z_;8Cf{v9SQ; zQ?K5Gm;nnwlf@8yeUOkoym}b}9|W0NCUQ-)Ql`io{18-fchO+MB8y z#X}Gc=5RF#KLb_77VpB;R3W;qSX?+wMc93Z7HXZ%2I#rVp6Qy08?!NW{WuJ^=i|_u z-Rn*2$lJV=jAw5eIzs7v=Pc*1Q zKB}JoJzj{mDNWCw+j4T@F)4cu*w5KRe;@A+2E8ZN&2uI@oLrzW0)|utTf6taBl*Cp zCnbf()y$m;iy88U>h$njEE)E-ZnrT7c)H*HELnJL$V07a3GAFA$V zDlc(I+Q1k=Cd{PU?Ad9ru*$55!8hys>f=ESV+cvtM+fndN_l@Z6&cbt&VR&qmZV;D zV7so4WSWPea z5K{^230mJ-aK~%}H%nym$UubZO^T4sgS`)B?{Caph5OB7?W&d1QF=8_d0Nbm3@61K z-x@-s<<;67F!Q}VJ$UBGbQs)RUpouIQie=C)i0W@n?hz#Cf5O)EPlD5U4 zT6)@8_OhcoL2j>zu%6)LZ|n=5zD#<<7J7T4qNbJH(G6r$-wgim!!>{VBHjI;sSEk+ zR2cqwWPdHYB(#`uHR9i+WO%0T)j(c8N+Kai#`wsTyaSqvjU!KtMQlU`{hjZ^u6XcF zS%bEdCG_DNR*f|@AdgQ}l}ddjg(QOZ#|i;Nr}6RRV5g|AIK3_CX$LEy_rKVOw#)+d zb@lb}0!eTJZP9Bq_?f}Q(mkAFR~tfqmPOAPY22~AkJ}3%+jqL_RnVty?(QMkKdPE9 zttRK@o;piDwImN_=r^m-dR_{HWw}Zg%rGLK+i3IknQ7#b-P9pq&7T}0So^WtBRI## z><8*Du&}YKU1x1P%zHLuh1mG;Pp9Lgh<9=}8^G{NU~rzK$P>`iVF>PiDJeZZeQ~{J zIAkMRQgTTB;2z>^&Z4F1gz_3cOg4Zh6woLql90xwh6}6F@^nU`bj~|l*mvcbSYxSE zQVP_1R_AuF#=Hm|9%TR?$xY4ysj6tVjbQPNTm0%qEjM_+TE%T1qN|C3`?&5_r$=x2 zB+?jsI)GzAAcdo)r3HrH?QL7}uHSu~sQv6FWt|7K)W zey%qGJ@v9{uBo7Geyulwx;RCbz~KPl0{AqGGGB848h+>pn-suB-w_(e&Qfoi5#6PT z?f%MhxG(xeR`dyu=*x7^2mNO42y1O1ku-pR<_!*`d{$mjA+PqmmT38Oye5I_bA>t5 zVR1=#{Ds!Ki!OgMLr;z5KaJbA*Y_levf_H1E)uUp%_@}P)d56!Nc>-`2{Tj=!1=+g zn7R!EGbX5u4y}>3YG;INW_G%0 zwcyB&G4Gt6ak!D~GFeTqiha=7QGfDxyFg;}dcZxy^T&!p^&8~ywXEH1hAQ~ZQuo*M zU2kEexNj2IbAm{@+(OpSWMJmUlYw;9&ycuilW28)1PZIL_pvB=sOxZ-=unY+Vpbcfh_LU5))KgFOx_>w`*B`IsjZGqM?#XP zt6hdOUfU8+`JonlWjy-IpEh5zsV)Z5vAs=ief>>w6x(o2q<2622WjM8mO{>48IB;Q zN3_TyGc^(>Y`N)ugRl+nDX#Ysg%zKoVp|_d8}YwZi|N8+!m1fxk@NSYv1G8bQT&iA z_4;0+UfgmPEn%S^?L;R&Q(z8JWb3}zY;))SqmoyX?|(Fgb>Q3|&ZP7Do8|Ag39B9_ z^$bEu7=n6u<(3VVDZM*fRBkcVnW(e0Sv4^sA$EB%ffjSrm~J4;W2<=W&N7Q{A;X z+IO5;IWySMxw3PeL!IC9OlJsUREUL&6~}!ByI*#%&xb#DZedGN#Tm!@pik=u7=XP{ zppi*P5CRcHP!(#tfB{+*&^hcSA$@{ju;)(>yrM{7l6$I~qO?M_ylH!_q4HyRR;yjp zRpf69cfxyis~`8OKa9BBNS_%eosjn{Qij7bfJdlQ$WMG7eZlpo=Zu`~Ig6}<1)i3+ zHg88!RlEzRN~_4LE#xosz{^trvA#?dcYP=w+44S|^{(Xuw`o;`;3TFQzV!ue!fwk#2ea z7i)j1ew|$L*wU&$id;sm{b=*0&xE`0ljZKOkN2!+{`5zT00zhY^u(1IZ6{ci?Kj^c z9CaH3mbCq3vI8EX`3t+TC|O%aAHWOyQ%k2nk{G&3*JwXh0#cGqy>kahCLWr_eiu>@ za4@=QY7VqqsX0=`;`~9w>wx&lk$=So>t016|mrk zqWi~Sqs#6KzApgAA{6O4R&1b&!f!f8z=1FVT$$>j&ng6SH#2A=?t;%$tG8-_S)uE> zGJNKVlJhV>&~#Q+!z=3Q+T^eI2y3>hW&rqKDY!el2wHR&0;c>5V8<?M z(SbnNHB)XI+ij5s#EeqN+%GP5*Z-2;)w^_OlRGnRNdWG7e`aO|&=VS0bsK{K)k($t z#Nf5T%A11c0nPH(lao5;LbM0ns(vx}l-wj(;s87Cr1wt+ZZjMnQGea)fWq7f7Ezv= zGCV(1wQD_5weOqJ?V=ZHNy4yo0czi1?PDA!EUl-8#PQ=4vrqPldJnkVC zGcXv`O4SYY?>1>K`&T)UjvJ$_k@%8-mQJ}pFA^uh_15~5p5~I^Fx+af5b98)s~tQk z6)79nIf}AM9j_HC>rf*tYo+yWKnTLuXpOO`c{DI=kBU7Js z2nCwi990TF+@hM?zCl^zkFArPMIlKWoiVwvE`x4#d0;Q^$ooM#W1jb~x@i0pr6%J? zjj_$f%vbJKvP&T2g2+hNY*UL}vlVakm0^g=Id*>Srzi@kjztUn*N37@f7MWMr$ztRh-gRrv&;`xWcfXqY_FBkF<=@Nzv?d1hY-v zROQCB5>kInBjb!ryHs!0y9skH~7s|#T;R=$pjn`qc^Mab@g3tz~2jo@>O zn(}J{U<|!(qLQ%sx0NWEST<{FT11KV3A3YO@ffQCb9)#T65ah=Y4Z4-li&+e_$RZ9 z-)CncpIiR8DD21_#icz?(x%<(Bf>wm+%T=; zcj@&+`v9Mz zZ1^i%IRjI_l@UWp&B>YYtF#0b#`vUHy^`DEQR3-`P*hF(eyUsD=VhVrU}GqZ0!ky7 zgS+kaC40~#9V{0C8-K{A>aF5&Q9*Ly>^yZwH~D?eXj&OqD}HD}=YUO8IU` zu}@ri5OKEAWF*|lZkucE)v()iUktU~ALv_k!vAmqKq=X~6XijixZyrSc~JlAu{Gy9 zSMQ{#Yv|l?fQKmEh+Q=hV}OZqV}oM?ZV32>fWQq&Ke*khZJ|_xE1j_FkuIMzWMXem zkG%g+2rWDuQ39<1^o+oG@wbiOifJXl1YY60=qEN$?gJjv;XpkV6XmnQRDTe^5V|S!y6^-zUTJ{0 zX%BcuYPu zdMdS<@WxA`KoIHR;PHw~;Me(%_je>EU}b<_+Oit3xgJ@+pp&Dz0~R?Qj(R|D*)du3 zuh!ieO(se7=ls*t!7iJYA<)r63=J!`r(AKQm1Zd(w(_(d>6MEXjMyy;Jy>4+>Q>Qz zeDp}`+_xj=mip_5YOfRWX?L~(=o5LMS87oACgIuFhYZ@>yFY7dg9WMUytRqSo1O2h zq2stR7QYCW7O*){MReF0HuY?~&niytt-COlGn!RVjo7`wZTly8@lSJAO1Fn%-IR3Z z3A$6Ft;X4$S7&CGMumEvz?qAEt~mQ>6tb~^q0N|vt(UL1yy z*ud<;BRxG|gXm4tq}m?Gr>D?J>-_nxzMP;e9#7?IC?2Lmg1vZQQrxsh_}9gKb>S6g ztQiD$1%~K2+e|5~`y zATPkJKw+@5UhT0fSBKL*@hirZ_+^-4_nYA}U>Q*{+)t$v=`M?Wr?(S-*V z7($UrNR&{dbkhWCYpTMvB@1R#v7~)a{f@BB)gUv$MnTVwiR6n<;h0 z?|_?R(Zu={7SJfU`=CC9c|S<2x2Oo2CJg>jIh>aM7Ylvh=mS!HX62_Kt>WLSy*KkB zj*9+$^o#wAvqz%*4s&L`cf-2S;c&T&dAH4N8(Z74pa-&9o8j6>=c$DS za9!~wg@PFbdlB#%a@q4Pp)S2#s zT=~Kowy#jg`mZWDe@aC1pLaa~2_p$sE>6(T1)=eJ$gDA|WluYWK8UG%-Q4PMo|253 zOjDCoOgmU6R#goE3W%^sdC&Ux_VxjlW1rkS(;j2xCoWZCJz74eNDGASNe*jqgl7Ie zEt7z3bZjnfY?&B5-fP-XFFb2NaK}XighhN5k)|oR^fon3F%>L60x4S)8aQesS;M0% z76{Wq#IFn$RC`$5bMt|69i6ewo*s^L)a~GP6ZJI`)vwuiEt3~d>CU}@&MP1;V9Mq0 zB!TsWqXTVX{U8E5pDtgZCoh3$G6fK+%J9k=JLldS$6=B=o4WIEoR1w>-yzwoU@7ZHL{6Fc;L! zKlDl~vzaM3aW*D3wowaEe=xEhXjTDuTCdp^dpGGKS5SzP)AwaU@GZ+^Fjl{2vf`tP{3@jsQ=kx_PNGqY&)eS#)A~I9}<*s4EF3fLHNny&!$bT^wl9{m!UaE5r;ie~N`&H~7<3 zD2?%QIo{d@e@o`?pPHLv>Qxt1wf%{34HZhta*bTZi!m|k^jgRnve*lH=0lu=y}3za zk_6iF7!W(5Mmi|JLB z@1u{q-cM*B^HfF8b`3raYl-xALlk8PX^v=BvUfm*HDVAk>f7EI*P7BM3d16$h|6a# zxAJ=QMDSe06N%L`SI~N#fz7WK1}z@v8fzjW$?r^B-?0``hJ*)*Y7w#Ak1XEvNz6{| zE%wzlyQypc0S(LA4M{_@A1iABv4QO!ou^isFOL5=Q1PNVt2SS8L^`c5b0fZAF2ezh40t<6@05c>`xQ-j_*Hjd; zBRY+NavVH<9WH=gf!g?SI(s_CWCQ!Sr*w0CW`A~W(c!ClXj)pDh`i8^lnXR>or&*) z!s8J;U?pLVZ~PIUat0Smlp_}WuSZT~40iXiw?ajQ{8TuPoDrJXak6SWbWxxHJPR?) z0Dl$CxqzN0aeDH^bFXFh&+lh`xFED^{m^4(X5I{DfevR@+MLx|z-(VpD??XGN=o+D zfK%+M2-U5OtHXkuz((fJEnn>lkRPH)$9vDczW~D1_&D%V2j+Fv^Ip~s&%iIntN`X8 zpiuy%voy^)8$nCK6q#tvzES{B)zvAf=`cQ3Ah|kfx|(nuKLnvoOTWX8PD`f;LD1BV zXCG+7Mha9XPFtbYpqY8*4?trPku&^rZ8BL`BWcrf+xXN_@Q^^qqfnkXvH6ya+B4m$ z_i1%pk@Xh^1-5DNoRH->tzzlqwNwfJ#>!jcPn;rw;rf&fNvCseph|&kdcnsIM>5Gj z&kcd~sa^FAB4ynV%mCANeVzaVal}#0?l~AUbE3on5Dzj<=T8UR0W2o1Ms{(5ycSJ! zBV4Es!UtTblG4&~!I7%h&7;%}n%*NFMNtd;$A<0bi|KSBq%*)uZ$uGbxCDz0Q6%T{ zgr^}CosMY|MffS~-fI`K;(MPK-t$lyg=a1pn(`$v0v?k?#Z>5y&^5M+>)9O(w>mhSErkS^(N0Ric55Xq6Qee>@9?SIID348t2pnd@)%zvJ;$>9d$kP7d+ z{e8>DG@G`RnU?K0j}n?US;r z3Go^fv}@uMY_i~UhV>#8;NC5N*4>QTNd@1Dh>>pNq;|AVgpV(q0S#!uVJan8y%(P3 z9>-#!KSJwb;jx<)+++J+G8D|t&Kex8ejW3=4?zbm3HwaCK$Z_;>5Jk)` z%;im)*G%Z<5!IUql1=cLatL+7ks21iV2#1S#bwLnq8(*sa`!REq>(=|39G-JLz?Ls zwbYf5I)}<@mTLY9oJ&<7{2({3q9yZnK{nou_P2?&9w!d^Jqc{3OHMj_YMa+c4(1v@ zPC^2!!&XgC81bG%ZRQy;lV%ki7zww^zZ&^ki3>G%ppo4uo5d<2YK%+$--%@?f;u@{C6Y0 z|MG5$k_{g{H21PPH1>bD)JMT@fs)y&Wc9fm6UNpAvpnPUG!I|1Q)a}OIw5Pa@-}WG z)n^`#!j9-?P4o(X3%|un$;EP}u?{$l*zy4!V(xY-P{WjdYu!WY{pT`(=O!d1;N+W1 zm23W)A94nb+$W&p?Qya(Vk(OYOMJK6qVrAvH_r&A>W~y8LH~)Zt_80EA;#B@A9`BK zlksb|=2LFv9|gNL0-U6@e1xt09f(Sm5+Wf9LsnHrn_k>-=8o!S5M&V5|2g5{ z_*%4jn%URfKK1WqGlyXvyJ5`Tt}mas5pNNU-|VF^Oqj7;b{| zWv69*2ccL+bJzIzQ;OS&3$Dz=i9HCYZuY|Jk0B*Lpian{*{4?QtPs8?cg&o&S|m)H zBMZWUX-01$!5f7?7!t;s@Y`HbPyoCF8!<7TR3%6j$;P#tBw7v3mmh;dLUQR12~TN6 zPrD^wfLPS7wKb83B`?9?VBo!BDA+tTvDmjjm;b)5g;r{L*U9_v1l}9qEO%X)$7oST zE_&?$YE2Rg8net7H59w>IGN%G!6AE-X+l?5W2eF^@F*BWoK%L3lziMg0MWN!^jfB3 zC-I~8`mt@+$cR(zDACKP%aCC2pCve@W#YrQ8lxH>d5$RS=yoPbA_&ejEITmTTs6ofk`?aS` zwtVS-xs`(c@ur2F&bVGT_MhYiWONs~p8qi;Qa(TSkSdz|WMt$IpnOb3&BjtIP&6qf z=Erj`xGO$^k`|CtH(1^mP8%@@KYb%$1|h~meCqDrY#s*>QSnL#be)0gz~fYZ=V+cM zzUr%)iHNIM;u7HkvqsZ&swR+|7?2@A+mvMlu7x`76;&RZ``^Xf`7k|-hTbl1IhzcT zk=BdFM z2hob7caXC^wc>lAmpJLzK6Q?w8E!JpXRZ9HzeaMEropxRw)n`Zu zPTF7zDaawH0N@u3l_rxT6UmAcX_8yDCT#nL9H=Bl0%SPSB6dPXZONEYPoatHKT1aT z$X*8jhz!Pz&HV*#N?bPa0xCa-*1k^%v2a>NeMr#wT$XQyma*aX(oHqm6bAEVQJ9$6 zenlYFX>-4A;{Z-DKm=*CaS(?K^{Z-*q|*^0$gU%Qz031!i!eVyi(t zVU2Y<39)mo;x%(!>TJ><)71MDHl<9bg1T1u&fN;yC$wkI8;{(^D(qJj4kb`Rj*u7K zD@NXH$j1`6rM$KrT2%OqumrbMRK!FC>t(E?7;d1V8BTt5t+rBZ&vuBkYLBb2LuA1_ z7JRuow{ntrCZz=tj}?4!aQ}&=rHcf|m6zb0Rl5NGMUU|;p2n?TaCvmeWuM^#F}X5E!H5PI zh>yPCZ=@0m1hU3}&<>2-)#+Z|f#c?~n2kRPxJf@$SI?Wd-!Mg(;%qTg3rWZZ?h8Ot zmGB31?^`1%@r>OK~KygZEv&f;j^oUsrZmy3jD{-B+pf--!F4 zIP+$X)OHuoWmZ^2hSP;qzg5jaa#hOy$1_tR6@RiG?7C~~K z&zo~RA9HBj85KMc4%Xye-%evU2=6=75n7>9!qF*^oj`)6{@Sa(tP#Bf(}kiX>zVT* z?FFwR0kFw**w~HfvImNvc3yaYbwB)q+D5^tf}MJRFZO!#1NjZz{cw?}w8hj~;ld28 z0_Cvj0@9cAOaH>$Sr{-ujG>E_6S}?ZH*YfuaObxxsk!Z2DF+K_PyDDg3`j|3Vhb3h z(c>LIn;~)Rwsfe*QnMd>63l2^X7;o4t_1AMzlGOG(`w5g_C(jHa0>Z!UBs5rR zxum}PvnWsV4v4?z{pEbq)Uk^|hg7~#IdCErxPj8Ngs*KTYr+tU+YgeS6w1pK-lo$V zOGWni;G&qo-2$=sGQ;fghBOlO*&Y}T2e+x&e+BlLTZOE~J{cXlTHu;Jcaq9n*b&e6 zkYnPq=L)axWz+s_`?j(E;IrX?l5!#U1hovwGkHp#kePp~<&pvjH1@TFV&(xo)?Lna z{i^kEb6O5n3trUIBpyC(rN?gvmc}R zQMK`TR0d_WMA#^jqK5moHfA0+W}dWBe6k+_?M-|FPYem-g=b_0LVG`nYva0N*UB+C zN*k(0qcOe^H=FKKl_!;9wF%JU zxg=HNK$H3ve8&xRd1-yrH{tn+8Kl{%RU90a%U7ruiN)YY`K=}ZCGNnBAnI5k^G**g8*}U0ISsJtpn_Mq34ZACdcO*HmtXVT92yhcwL5 z!g0e1a0HgfXD(dqgiHIn1EB&^+dQHW%OF}Q#ov*boI+=RCoMCUjD^T14(n&<=AII? z1j+ou0Ai{MsGJ=)$LO-Xy4DcLz)u+*95_Ls0EO?HSg(n^W(_zNa`2urIa=W)Dzk;B zb7Xlg0TKH{Vv_ycaoFwEj%X)y+nMQTrY;pDTHDsqazv+CF@O6*aQk3uLwh=M+g{o) z78DZl$+>hP7mh$N0o1REl0p0YeDl4kB5w8Bzoatu^zfSB^U_XxcG3)Ep9;~*eW&}P zifdBepmEk@Vy6@fXh{w1u`ATHyFcTREA?YHzQc|JCXm$Z{BAJqf^ixAH~mr|@fx3R9) z`Z-V-+kHoMvFOfDVs`CueKO{7q;RykY7hlN!r0ZCGMuEl`6=!OUTZZT89PXycLA=)U4Rzz0)5~V+sRhIqbb@AEc@^PJV zUi_%T7M=;zxFPo6_<@4h7Z3f>S6wVFPaAEmt=M*NB+0`E zWI`w#7m__;b+wyZy$Eskf5D} zn?E0Tfp)_Hc4tm~VmT^Gb^ZyTI0g3_mZv#(0TNZeE)k7K;tzJYx_7?{A+~;h4gK%O zS+Bqh_Qz5Yxue@2#F)X6)%az}3$DcGFCwJF#L>I5eF>0F@NGjWT%Av}%nH<|JIw>% zcsY&-QjNXo`PBA0yvhMv49`)jMMfz@!^gXZ$Gm_fW4N zZn^wfBR(Z&MzaHcl`d^u#=Qd1bb$k*HHEJp?I0q;2_#~GTRKQrF*0$kx(vNw0$W?! z2%q=8PDYK62`w)%mK!HK`)zMh>ll%WWxYKxxPkgt^&%c{`_$~@RT)rElK#;JKyYjF z>&_!^F4XT4Tt0cZeA(yS1uBeYybfkAJ9+QGrsDr_W#%0U_B(+Lo`+)!VcCkA5_Hut z53!o@RfC7G!QShvEZd2-S>a||{QI0~Y{#BiiUf*%)3HKwJB|V`UIwG;eItA+{i8hU z2wCwpr@U+WoKQD-R{=c6zt_Vj-r;%)f-HKHNI|E;NbPf9OrAF$4T6GJwlpekH39WEN2XUaXUR=UesZ}( zzSGOzm;|^AjUZ|xZ;tE*{Vj8z!aXLhyKair^#c*~4EWm01KINBl4uu)$m-0>4Y}S! z#w+`qvIfu?ju*c%dGO|{(ff+xvN-EYGVn7jtlTSmT^D&1`!w8ju^)E>*zk>8);7Ok zk?+xs$NAvcqoM=M{d)IpXC(O8rY2G8szcWUX z_u=q^jDWEeaNk8ljC=`y_BrfaM@XXle=Gn{?*X~3f4jZ|e6HK~)FE+*ANb8*sOBl9 zM%mtxvSO42WnsOt;Q=F}uviDUzBgZWBo}lNK2bRXY&vD(nB>H87LK~kXmdvqfE+&iaA!>M zRlb)%@SSl2{V||J0t6gI8kyF_b6|uh$RHQ@gyd%6TT*H|q3ZsLU$gpYj{JWQhn< z05GJk@u31J8$6smygVqO7>sL=1;R0-TB1v4`-=j0RYP%r$Gt9g%6CNZ9JJ&rnEZ2k zuyTJObibz(UBq9GX8wlkRFPAkmIYrX8=ZcVsymPDuyxgDD(SsLtKMtXY7K$$dmtI0HYyXdIW3mL@+=QZ1gd_}E`^v(uD z5zDz_>*$%~Z)|<(YQ1k7ycaxnT)fQ4()HLog^#YljO(PqQLOQ2&bN~2OwV&Dkl26x z-2k6;3L~MNIP$pcZn^cn*{{kjc@A>u18=81QdgZ;?sZ>#e^}mWi@r>FeXrN*&!w<_ z!5;k37YA#*-M{T%B_IQ0)_#xO&o~v&m<5~m2w);f_P#i}*L7l6Z;OJrjOk(n3FagM zP0&k$<7MD)+Q_o5^O`3nlv57*i2Xls(Iq4x{HKwGi%nxu z(ng8i^HsQwSjZ!w);BaX+O8qMuShH1+Qn8mQzBI-#AKT*o~W9`^#d{K_(>k;LJbRb z`LP55xePrHc+)uard9)pxypqiDj@;kY@f-Dzc#Vh?Lv+=Y{bE9;*6d*hm zGaI|R-|C->0tX7vZEL4Sv&;(UhAmh_IFEtxSOIKQ4}9V%%V*^>mmsb~m2_r#X!k~``oZ#vl#(f~N87d1;u_ zl99J}yXKH!q%nZLBO=~_plrDfHAcpeIMS^kLdFymnea(7bBN$TuiJWYcb~iu19tu( zAt|}t^*>lp9#Q$uLLIUClX^@eK2iiA5`ysvp%Jk5g3^mrjFS0(mZlEolR6+z8Lz&+ z9zbf3Sug=TgQPNiKZbG!&@`Kv`J_3?#>`!FG|=f$A7+BR!rE^RDhd}4Vhb4$q;bm7 zot>SJJ%Zr9btUM^mG7fir9VnSbmnfYwR(cLeEIQ7^R)8i>Z8fBVIu z^zsTm=IxheBPubA?dod?S?+(L76{4HsLx8Po|t?4S)of;$lJGd32T?W@R&i-Fib(i zH;>vFOLY@%i^M*o-G`wx@RZYraN| z@f+mC%|=29jJHlH&ZLsu%l{63wkgs*KIH>kJE8e%YL~!V7HfNp1m`!w(5~CQvA0UM z(`?w{l#Y8nsBHxbDcycP~dF&c1{w-ljM!SSQ)fU{!h76%r@yg9L0 zh_0>wrA?idc>EnAh#z7xF!&vdBXwpbRfiO0%?J0(P~Fe$EIwaX<-4nJ#rL?upM_&x0Kid?PSaqE4# z2y+|Rzh`qndaC8@mP<~sw7Q4v^25{hrqD#^5WWl8%D-q*IYe+qEb2WGDo)RtO&g4!+)xV;%15 zFFi1KO^sVOG!L1ib#^@`8bk=d>hgKw8`DFHifH~;-eh}3Fw-te_-IOWTI98j{96~? zz8{ z&ctG|Y>1MD%`EXZ#!&uf0e8{&@9}2q<#44O5>u=e>X2cIvnT`AiZ?5ocqfpYl8&lp zx#pq!*Wf)Oax?dT&;P*KQc|)Bjx8ITgK?z%_J}Z@)9+5Y4T;(#gJG7Vrm0V(iSw%f zMVxIa5@m6I`c6UJ3@Ji0Z6{0gKf+60MYxw_`S|%`|LD)BM*VhR014Fa!=`;U>-IZm z!1BP9vqVPVW1=dAe=Iheh~Fv1hU>YcbQ*l4bEvT#{V@VhZ*A3O8P1(Uv+xnP4;f=X zF!CxRm3g)bYQEN9J>a#&1s`an_@xG*hD+gR%sWyoz|R0YS2{DjuWH+mjJa~h%?%cK z!(Djh4!;JfR8D6d zuxFgb`{yfcRxjKMiD!a6zDeythZ9xp;$5)Dcp5bGxm^5FLGw>g&EzgjS) zzIauPtBM_G!XLD!mIEo(`vWII>}>J=`6Np^kCQ!h01n{b5#R)ti6mVEKz-rTc(!Mv zNfMq0F0^>6K;GA6_MbM{P`-E~LchIiA!FvjJ3KV2&N6VX)tr5zYPi4?L^Zdxyw7={HGdB6KxIDUClB8S^wvCI2`_aYs!z4#3eJ;Fswlo~ghb zJUlBXIsRibh1SWs^b6K5I`O3wX|ND`U5{HiIw$EuR+f5yRh3m*wY=PCM!duCbb1Q61BKKU305cP9|5hRFW)McS}gQiG?sl;U|Q7T(YOcnP{ z1#&of2&vr?dwSuuPBDP(&wD?#a5<4A+P|=Tubt_!jrzPhevNW%W$|3|Jop(%brQVH zy5I303k(~hj3A||6GlilH?0piXJV5I&CO;Scli9`cy#+`iLsZG+4mWu?Hr;CsBlth zlJ3JCXnyk?clEFpNksnsY}0r6qXyplq}h7-1vA@SE7jFnV~yh%E8+<07dixQC_jP? z-hPyC`bLq84G;VGMJwb?+u*s*n9uSYA;+_7GbvSvceBxiiDkkO%p=#jvcl}2u)?%@ zsPU`5W_=t8^f+h_-+%WyH8ghu17RkYg&CX^95v2Zej^y`f-gGRkg#=&QHkx{lZzccX0fi|4=E;C}*On zZC{Q3R_~cHF$&z%rEOV+FiD8o36eI_m}IGnt1U1AVI1}tJ%)Q`d3no{_6t4S!hvl; zQT^sxIhV71e>9~H9544AL*MH4IgdE7)&NWCPVBG9JfaFQOt2q_{d&uoQ9G^Im2~U& zipv2jRI@asV+|+klJ>}B$ELDnaijI<&gyX~v|K0z?x)n5TWYaYBWP+4y^hhL3ttAk zR$}rEvBeX*{`!MPMBtdO`|12xBtK{Q37Yu4c>>G(^tHEkP0gD3Rrf!H`Xk~S^ zc;ai|I6s&YMZ4Whw504!PToL`UMt#)pzg~5fq<%d6ncNg- zE*Yx~P^QAE&!EX@=WSzrEJz9{#iASf-D0jm9{y17{i6T41@zK_7(x&{<|?#3TV(`rV301_f6%Zp zN*noY0JWQbl244$pLP^vz9b|7Q8l1&rhp0eTe=WMG-x}=e+T`?o=JmJE-otu-Nty% zU&_1>zC}%y-PbkqfIWU=sJJ1ntjszh{-EQ~;V!jY%EX@2$vi9Dp&qT}<=;r>9m}^X z7jxu#zn{EITy-NKD(A@0pR=rP^~CDNr?u-kJ>?qbkbbIAs*n#GU0FO+eQeCelERAj z^Aa*}GeMpC_141s$JmC7P$1ElWZ%^kxQfH>C3fb*=3)B{U;A~F_wZ1TMv(hQ40;KV zl|o$phyr?)xVuiDj+&iN9e*uuuY#NlU}t`Q;xlM0UOLrf)tJ7(9~>X6D)8xS7wsc~ ziw%|%C?MUU^LGlaNarmd_h*?0&mkfpuy*nC($t8gRh zkILF!p9_QN_*yi)6Q5?0*BCxx8sd@}RCqh5^RhwN=%+`B)k1~>%UI}>$6PA@q~DoO zgKDZ=pLdP)H4kU{{<&GMW{IUOz4QE#toVb?BSigeyn;g`FpZi#WK#?#_aSz_rnBca~vI-A=vF@Uu zzT$xX4ux#58>Gecms1X7*EhJh9j5H?Id0;Cu5DaKp>mdy}ksk_+gBF-up z{s}u`uQtsXI^;?^jd)pMi``3s7`_7%3gr8x8t*U>ffA+_eqeip^Q%1lrF!~!dRMuDedz7_kE`s8 zDQUb2aJLd-fOlD#y9ZX7>)!Giydv|1d_FXn+o6dw43F8^dX;Op9t3p?Aq z)J?3F_f6}=p_vHp-5hAKHJse|6{B(ctLGIROoWQP2v;h9`l>p zr}a<7<g|<7tu|}l24{0~v*aYFxSvUyPYK>WVj)a50WWj^ z1oYTW9yoHoh!YyFvI;(N?K(UpR}sF#Ej0Wj`)tN;?;_aaZa<1LVDrNJ;R1jilqi*~ z$ivm(np##Mf>dZ&Ra>hVYyRAkv_H8}wdM!AoL`V(-0MtN5QUJyKl~=j?I~Az?jifwNh=&9N$Opk6HB$dxzWV{Diwebn<} zZ7qoIG!IK^U#CwUG1YB(5(G(6q}IC$YwvLt>a5aThl#7k19&FW?K)U1F~S6xg>;w# zRAZC)(fmzICG`B&O(?*!uZNzI3fjfrb&`)b z%gRL>ic5(V*vo5hMbgKcbo#&Y3VbA=kGwD3J+6G&PlnR;2k-T=nvZS;t$!RoFPsEb zV{+;vmMcQ-gA-~M=j~IWBJ=F6pZ3>zhKHGx3kS{l3g@i3QeVcHimj3;=84qn8j#TC zrv9=_b~PO}xAmnEx?+%ts;I7=r)75X{kDZNYL#i?zC+61d?rAw)O&vnD{rw6ksx6u zzd7&Tw2QP5a4iqa&S#)zDwxZYPkbLgFRH6^sziX?r!}%X9eV<9-)33D3PqDrC~~Q$ zh+?vN<306cCGt^6O(>F4s9QfJ>LwP@9l#8zM$^Q+vb7Z;hxfwF%*>7gy5Na2(sA3u zdt*V8IwGyxqqfRdpXe9)DVL!TSoh-tazwNAO&$C+i{B9jrH>(r{mNcApyJp)Yf5ig zN6X!dA9s~(p3Gm^uc~vxnyEJrcxs{tu3??MBV?ml3q1}9BA!P@d>+Qnx;bW-=Z&~h z>|HlF40q%5)!Xi78!opS$k%2=j2s1Z12|mQ-B-+DZVAdo!4UcK_7k+i6T(2biU!HV zo$w$DjLH0^&$0QaD4z$7d>IPLEmRRCQL&j4X8OPXu{&BNbqm=l-T6M(qT`=q&%>^7 zo%7_4MZ+OF_qsoBpUKhSAB3WmbVsNLu8Eu;?xs{utE9b*`HBA1Gtp z6EA|QuSr6Pwf}wKZRK)zTk6fWdf`uTTl(-tNclbb>|s%4)*;5|tyMs_^7*c@TB@m~ zwO+@?9l>oD(sA=wDHiemC?qdtiJBbCklGHoa4cVEHR(|0>R;D5eea8pm*=ff>-Zw# z)2OLZ&F23d(b@OT8;-InRwQvN zhw0hE>B%jAIobL=RV1DPA%5zS(I-OuLYNUDeW9Vn!@@i}ha7e+ADsesHH*Yog*Nw8 zUD|D~szTVO)NLWCpn~yOvXGkmVf%vv3oGlmIpoh+GvZKcVF*ks-h}hwL)p-u*o-Jl zTq)(uog_{NkgUcsN^7UdEY+Z_Gl{Ui58XC0b2b^O`q&)Jl|t;u8kZ zqIguZ^gGpUmKYLxJocyVj^{b7dU$(h35}sju$Hyd*Y^Qo_?7TKOwekmf0EXIrMG+) zxsp9+Ilfn`idL=o?1>Cz2sZiL*%@k?{1&@`SpUfiX zF@lZPCHsTigGC}&cIB)@ONCN!J9}^j7Wc9OA4iN-K()?8t(18BYA8 z4Iv$;*`kZNlU5r7BJr^$?_7fsT|s%ZL;SzgV|V0UR~thtF?EPC?J=(&^0capg*c7mjfa5X$Pz2mDf z?@Z7g0SR^6-Yc>dM()OEKpW!fy|7Bn8Gik6Xv1IK7H-BYeaFg@w+YN~Z(}yzShB2i zSh&8=rH;TEwXwF}{+VEDBRaM{tv>54QFl;GxVXwM*;I>ROB@7x29D$?ImYMpuFnk+|HRbN%_|?lM6@p8z z(5m5=J@~5a0vBYzEWfwf;pjy|G|f&Z7k9(qBnIY=i9c zFaA0r;6`e#P9-3iOB7~L#+D~=AIUE@V?wOCOQ9&mO{#J?+Yj`|SWT&g|GhNrrzr?{ zX6%^ry9?Lqf1-%gZG2_M<#^h;b!%-1MIGxvn`rm9dv8$88ojf(2rp!r5*oL^os}E; zr%~7N+eD#%&Wz~gbgND~WD%`E=Hr;nCl z2L-Kn4gq__itDImV76gi=BDBD(_GnDJY< zP}VcPnw|^GEKpr2L=M!45>Lhb3y<3kimYcHK+V;^?bT1`4trw`9i?MtRTyR*yLEcQ zw@YO#RiGv`CSIIgGK3U(3Ts{d1Mw&oRz>NYPh7ko@4?7F*ncot-6w_RcZ`1_P2i`2rp+R_Nf+Z?(Q zvkpxmB}VjK5bgP)Zmcp8^SM+`fp1vuY8l`=ggU)$4jQ;q6rTVDE@{yInQLY+E7ULSLZ6=54drfP~sy6exdPeRj zXA9Ue1#mB_$v;M@VM<}uTfsqxlk1`I&11&11OFkBtf2tUUFTbFNzY(&u3ip|WzQS; zHwzQ-Em!rthT3!yiE=S7I28j+F!F6Vi6Cjpp)n> z(4^371xckOq0ps-)7Pe1tuu%v7!dKeX&az;QUF^!O>LEu7>^QXyySbldPZBaFi2{y zJgaK@mbxNiC98k#03k?bZBt0>`&QC%K^iKAq@k9;U&3T-i8EGLr6>nAR_v4L>M-IW z2cK@WPCGI8G5Ot|6^>c*Rs*S!>R34GZb_J>yQj{QK97@CR1!@rL4$B2_1XQ=mzm}r zqZttIUhbv}E_&Tg!j=nQJG5>+O8{L-q*9QyobxIkMBtmMW_b)gl#Bm`y6_d-y6Idx zc08cM<34P5f-;hRHc^3)1%AujY?(=M638ynWvg{MVk0c2@ukN|j0;QXbn56G9X;0t z=X-x9m#V)nW1mQ9H*p{rH}GGHz0>$@e}iOUK_aR86VN!$Ad5&~YI)X>Z~~;#{VNiU z*#C2%pE4gek337Ge#8!<3Nle+ z^gU?Gmr~Z-dY_vcOIK*L&iB;+KAG}3T3QUUL}#9?<2iyF&*XNVvZER(A@YWiD~*Xa zC*Cy@Nkc9XAFM(J$ah%vTWSd)tC10X>DANFT-wk=c$IzMuMBRtSFW3*@$4^$q($#9 zH*lpmFUB(E7{>ZEx;eJn#xi$CcqgmD&IKc+L`+aivMPjBV&JF~%jRrl(Ghc;FRo(8 z&2U5q`C`9&Pv-`W#=Cm@_D5<>vzfuk-(*uH{u;juf1k?09{lI^9F@`NeMdkMiB)M~ zC2R*mb^CZ#}wCQBiu>V!w}fF6zYlK)NHpaWxB>gRMDC&wM6k#yMCsp9^&9w-0-N&xVzsx8jy9|56+Sc zL)7r3QdAR>E|%Tdfvubw=sPXGH8meHf_=1Igs>M?UeaLMa8)@I33I$g0*^K_%<80Rto;q65S==4%8(j6^OP$H4x^4Z8Sd z+O9RGr>A$F1+@};@9)VoOoLlnJ&E-?T(T}jNJ{s$>Lmn}#86mZpU<0llBAf#0@s=K zy`t4WkiV99=DWG&*74km_z zZ#I7KsRv}>55+SWR<`p>%ErYNm1i$l+1bJQ&o9n70teR;a2yw%roZ&>zDcURs5gsC zK#HVL8%(M5`GQ6BUfxJA9kZX464-QwZvKKYNHa`C_{~3X(c_EcPI7pKpwIoeCS0!~ z7)HG4G^6`CcU-gOyLg$owQ6Rm$a=uMGxV~?FWr>;drAvFNQTN~!0ZB#v0^tpiYFK_ zn%B)M7GXg%NBYqwAuyiQy8fnm=H!SYSmN)EybdR!_eju~HNjNRRDv(dRZ3|>6%6)L z70rsf4Rdn~5+QzR`p!6Rnef#Q?OkgU`yf0W6ED%~C(*s~!O?x|Yp;&I(sJ=9psh^Q z{(6WRjJW>=-+A!~3 zKaQl%t)k0VAo2>Tw^I_%k7Btnznsm2{$ikwvftHKB;B`BD(7xasXLWGkPOlDRkfu) zO8NaaKc1yAjCZ+-_B?EH$&cVP!sc#FZ%#IZLd|+VA}`E6B%%D&p4XYK z$K0m=SOv6)|2snTN>l}*??+>$c*p=S?w$!dglRtu3%i77K0tdvX=s3}MDyhDR}6*E z;^AoL(4S8XX3oZ^HbnJJE6ywA{{-i6w_t0s_YusvVufA0Nz*aqyJC@lFY8PY*TB;w ztZa0`8bggvG_Ghze>#v8sKK`F^Z#C1RCg1mh~H0ZC!L6AT%4~)r@_X+I^rrhi?WxU z?;p#fVKRN+;pa+R^t2S;E_Z~uCP93ZAHniWJ9X{5?1mo7=DHu2f{*K#J3NpZ>s zw9waJ<>G7HH`66KMRnluuHSN)(RG10&D>#wcf@1c==x(l$2<9{yF7rlA5S;5B}fFn ztg5Ti7-mqhF#Rw%KTo_fn$c|s8U9(X%Q8s?x(}j3UK7Z$l>nOu(1TSWbST8x7z||E z5%_>jZof*4I=;VX&*F+Qf0G8*$=y%Bu3upZ-@iLmF7BuF5CGbZj~wSx>6BFO;(8`_ z3&5CZBVjvsq{vcoslAq@+D2w(X<$?ds!gO~@+y;+jn*O3jQ)I~yH3qoLB2z{r7|Cg z4qsJS&I&wuCcf%4wh6DC$GE^bY~6`#xm#(=;;O@(_{2xJ(ZqJ)bckL>4S?YSC0wQG#!hXQgp>P#W>GJK_Ir|}{K=_1GjDH-e#qtKYtcc$l`G|HmR>$e z_U8Kfp^YffQLqNR)z~IfQ`q1|ND@jgo5MbMwu|A(vhj;H$n|NkqJjBE}`_R8*%aqR3($jRp5*dwwcJ9{5{uMo1y%7{22 zBr7{k_R3!0hxhyUdH?bI=XL4wy1dBic#g;Ye!JbSx3e;o<}-rl6)_8+fgUtOJrJ|} z!v^a7$S9Lkt-j|q=?1^Zup3u*uh64W#;%@GWvrM!Q>Z0h`hwS;zWbjDGdc^0k5+|> zSx#3>ydS+!@M!5jI+A;y$ERlW57>DU*{uYk6%Ue<>k-E1(-V9&>h~XthFMPG>{<4B z(%w)omPK!utCVZLv={H_3o`L~KheGl@OnxHc)Zqw(8&n7OxrxC>9jbJOYgwC@cG58;NBr zqjt!Ypegh7xW??4NIe0I?%>e)+fJ8Rkw|^4#@b`lLC*a=VwrQ5$GQ7q|!Z%@^e@8yJ&IwAlsclJKuc3@mRJ37`fV;)mq=CT^jC zpc7bsI@Y6Mburx_XCO(7U;28fzzT=m>VDqiL+S+drSDxyaj|2z~a1S`Y zf|U_q!~=*B;Oo21*WEncC1ZaiTuv`fNZps?IP^5v!?`2Pf|v9HBBjg0g?w6HYUeFgvfWH!&Hp2t%wI`Nx&OosG#z$Y*dDw zDk&(Bwy=gc`F`@zJXd6bd_lN_n7fRwdAdhMTme~i<;KXCt(3E9v~9T3)`qpgDq85=82)QTlC0Lm=$VcKWB0+C9QjbRAJkvnut7O}3CA9-H;vP$A< z3X^#1j#pmFV$|#l6wRa%0oH^&^@Fg3=gkP}!)lenp9CM$NteHHmKjLnbz+8HXWa2`z;>z?c-#{TNB4;KWqKVVJtReD*q8l(h zE%M;JBkDO|r`>MZSp_qz5DKveo~Hg+sunYJz-jx*PGJ6QdYEok$)GmY{KBnqW)ZCG!6w^MpwoT!?DxP~<`e-A)AZH@r35W<7CB>n zIt}mu7n3}40jeWhwY&GYUc)7u>SLAD&vU2vVv!h&g9!cBggwt-Z2$<%Pda)=pggVY!G&5--+?*IuVdI+^4vf@r#XUeb3ud$ zDX>%->z}kTCy+P4zokKsNdMeU)OtMO=r(rP@qJr8hVi*>sMSO< zb(QyFdH+CC8RyzRIE3dxiG!qB_DLUim=Q8audQy+i)1e5S4uEXODB0rDU!^| zZ})hlhF$3Z51mZUB;PGzSFXPRkw}POR@N$2f+;z3bx!x!4Ef-uIGJ zZkbb47IeO6Dbu+4It0G4o-f-+EnE5M0qwmXXJ#A^P?gUeC z4M_DXuuD^xe9#{G_fV5P-{m=^p=tl0Zc}^T_7xpi2F|~6aR>uE{Q!U)sHI4-o(}TH zi4Z^d{?yRFyI$~>u@<4eH-PdoLOqN9v<1?c3J%=`0=$6dx_~EiNq^%-PI(7GJ^nKL4F)* z;gM-hK$|F0FMev;bcZ`1WOpHm2+V;WscY90QtY!akYc|aK$jBD614^yfw=K;-Lp%- zEDLI2GHLSM1HE|50#e(iox{=#)m$n!qoQN;3MJ@i8~mZGh}8T;0mR8a1_8@()ez4Z)$MRLEV)Zn3nxDYN4NSBfPZCf-#;8)B@na`nntb(W0!=tir$od~v}GOfvj* zeVg`M2W^ip-gPTXun*AA@W*TauoqNJcrX9dR5V&sdGY-Ap!~z`PoA6AJD=+6o>$Fu z*V)_8Foc)9_Ib1q!^#6^zoH^tly~{Ra@Cvt-C*zIDzkl!?e-6Yf4WJ0Ajxi4l z(2k{F&#Kxsv*R(}d2q55ft8A8k<#OvoUNK#DL&evxP$)nrAnKk7}0LpVRg$r%ZMU{ z%3*NMC(h*}Kfh9>{1N+xy2*9qe-*@c^EVG%{DtF^JARV8ov{~+nwosCKH5|j)O>Tc z2h34bR57$GZZ^wEb;FvQ<)Z4=iEaYbL)LO{mvZX1Vit_Hi(LFLnPgddo4(uT-;msO{rbo#FW~phla)aMLs@0O_k-+XyvLm^{;EyKl-gc&FOUE z0(Ep1dO`HN_0JvSEz((&%ZO!uy~D~4&K4kf2P|b^H7!kC(^5M;u+M3LS{8=yyEpU- zsYL?6>~hn)Kc}^r`+>yWe5Wlw+W=7gbaT_*?PQn1vHjHQ=*RD-3rs8#-I2cBr( znQCx2yX-Vn_F~N_y*+ma`PaJl@`|p(;Wi$+&Q_>WCA}DSyy8RqQ{pnD$^)JTu?E@E@j15ix5aJ+kU;O| zQ$%fBeWr#-_8+m^bTq#sj#a21 z&hI%0Z1%O$vc%1s(tmvRBg_+U&qJ1*Edn0W!m7(Cr3#Birgyz`I3wK5WtIzx$tYu12;OI>%x%I>1s&m+kKdY7c#BpBlz-~ zI&+Il+_4Y2BpzPdQ{2-Pbf6tfcO_FK8*!5x5YE06!Rxz-Z}|3*8Zg+^$ZiFG!JKVW zm3-$USgUTS?HjO7+^B3J<>}~vw$p3`a3}Oyvl`}|Kp;orh z{O|z}_*1svxEv=#Wb-4<5nsL%-5KSoEE*7`uj`oabAMF$W5H7wSq1MVo@@v)i-1eK zq>}GZ>S}y^Nw=Y(Cml1@+SFeyJ0U<_tjdPvJF~p!1nZ|Lsg#L(n!af^9a#4*t(c{F zZ9h$8zE9A)vWSbE=w|h|~qXG(h6)L@k;mQFo8Lv#M2EI9FXJ(WQ1-k6_x|H0iMuX4e9>>MB{3Ei+Un zA^N|+_j+eQx0VI(j@hTIFcIQe1e!h3OVLx*Q9_Br&i+32RF8cUV-i~dkMrEj&f5Rm zJ#XgV^{Bgs9TC12mINpYfAcuQzceNFeQ;aUPRC`yTz($6y-7s@nWk|DiymDwZDB}N z4CY*-1uwX3`-lzDRHEe*v$Bi=zp$z4_)3}zg#Y#M@yxF3l<4{G<{|U|KQB((H2rhO zZ|Cl4xA9;=<_-cb+`Oa(;BAlLBLJlj(8!I}tn48BzK?xm_ zPX?9HRI76~*!7iZS2wsq#$GEPWELeO&d%RPv|1v((gyLVPJ5rVe@zAe%Mcy-rGt-8 z82v8DcMQ8>-d*BjT7oi=@BNiAf`3Y4q!@17 z@S1S&6C~CSOH^I@ifcTr2OAa^BuXGlou7NT2Bxn^PL2qd3F^@`_%3-Kk}!6!D4Ul8 zVn~P3Qh7cRKKcKDTVVU`oW$RnBRJtk%kXL+WYXilx7Z?jeR1N#WBj`;kvekkZ^sqm z&&a;VSQo2ap@@e78m_AwB`*uMXyBl)$g$o|-;_Cv#;@#`zV)(g!TZ`iU|u-pbh1yP zH|x!u5^62NXJR~?H>lHeTcZK2o0c$G7waz4f$y}}|AZPK!x-f5Yn#z)vZRI zvVaqbTDlh2v*QoCeE)N!_ssY|SU8rv>XVeg?H>Ss*BH7Y5+SLy)X`BTn?=Jrz99kR zhqYP`M!SCtVo5`9OB3h6P|{6SEDfNWa1-|R3@Tb-87Kn;3LuO}Xrop1l-ZJqSkudE z%F;wdN5mje;5`o;tBENXN%d&yzH#UU5pz%!?BVKi?8EvFWWYW`@?x>}V?~8oI;-`N z;UM@KR8+)6yGauJArs^6A;n0#-IUh4K^RYD{ttTf(o5`GE+#b{)v-c$sH`2%i36al z?`r+L?>YvxTT?dh(b03$%Th1X7roB|G|WJUsisPWgg@8;s9mU9WZ9@x6G8;saLXU7 z9?9c^1hU&>F#Nzy|0Kdr7J`7GqeRCZ zoi}B>;6-_UDXyN?9(Z*np&gMfxP5SavF5*Yw&9dJzPY6E3)4(A;?h5GrGk5OGPLHuyh%Ad*YM9SP>5wB47$N&XST27DeL}N6WWuF z9sYfN{DM4q5XY=GU`2FVtp0;yZKirl(8^?zT*%hcWP_aX3RwA=Jv_-)@&BoSE9`o~ z4jdNBoDGewUUu8I>d}~K~rIs-h z?DdjJI?dIj@x-Mx&Hro0sihX2sJ+23w#Hz|FiDf z$Fs)U@PE4pWMymp)^R1>?4f7!kngasQkp&FpX&ea@#I|vvA)3^7Lkpo^TX$>*~#@eWwpn1@VHvoQRwDQt9?Lc_ir)Q&!5gItFh zxC+jW=cJONZ{ipEEKA3#9EHQ)R=7G2C~;t#767j!_r(-C3nOBn$GF+e*Hgm<+I;Ha z(e;PAu;KF0^&!MJmNN?nhh)%wxDT`T@yP&AB4^=`IH3;`i^7HrXlXf12@O!X6Z2f? zCXmKkMf#_xm!Qwia4I+6X%GHnPO!AJ1S$(G$)C@8#A-`z_oyR+V z6OS?_TnOiV&b;DSmC4CPOZ3Wzcl09wap?8upSFUkV?A*=%2a?;EcwO7KA0F7`AGU) z+^Wlr|8aNrOAwbtW$-jL|ndyar?hD!nn#j2Pi;o!yYWC=}YCjVs1k&{- zjy2jFf2KjRj2^x38rQ>D{gLz@?@D>`7K6Z9Tu;0;vfkqyo_Or6cDyTkvD~|}cpfdY zw!gxA7vegy*YZOKpSuqHmf(_E7RD80 z0Y=L)WRvhWeC~hvqZ;T774CRAD*IEWf3&l?jIzj7s-cT;-Gzhg9xAQb?y zqB|fP7b5IIOEe?Ifj9VClzS)EEwS;rK)bEXtrKIZcsn4oN)yL1i|AL{9{^5FZCzdP zvS@NY1pBtOvi;2Jw|J(Lb`xrHQ0}6r6tXN>QR7psn!TSGo_l%#x+=l?4TUP>5(&6W=9exI1P?WMRugR$RC~Ub;V+bkpbhPd_6&O82b@KVX;@a;UYL!oshgjL! z0ZNQI$pZ#{m0-1hL+IkZ#t>LoZgMb>9VTp4t;D;HB z^-BULvKzuQ%gK#K2rl$N)J->lYH2?E@x-qqiu6HH{eUbiQPT5x!gd3c5&9Low-@W5 zIb|=e^=CYn>pkg;H{xD59|%mi*_W`QnMR>3G3cb%ZN`1o8#hw1ZT-m-RmV5r;RB`R zU?C7gCqD36FF!?J@9bd6C=uXKhB8G!?aE{W8svu(_mZH4f9o;;3k@fT1dbmev+N~k zIAJXe`w#_IuP1-ze}C<`Y`n%n|7-R&dpJQ@_R}o=kM9y$4*jrOZz97r#{Y~6s23o+ z5A^aYdINrr^U`{Gn!w1EA)WGZP37u_c5Qc~7#iaG~kAaiRIPlh1@pEo4t&+Ja?BZSQoY{k?m$AD&eBB+K6I$XU@iHs*!vk1Nu zPX9!ENj0DSTLM^3Q#4c>N>Acwq2gEX_o>r?g}U2MLn403F!EeY7LT_H@#UFde~qW> zfy8h=IpzgNh-%t9TUyTP2}Ro^3P#?kyqd9LX!b-z$`?FPT!Mb}z$!!} zQc~B;2W4}IkG?-h;UV+n>Da51e2UinV;g%%Efyhk{s)p0gFAkk$NYmd?eo%qoUg4V z2haU3w_pd+eV!}LDP9v|j*Dp}bSp8j7f%|h48OdAlOv_utaR{whfJEjRg-1-9)y>8 z?oHK_FUJ+H)w&@f`Ov=2lxts2_pupTBX!d&N>=M; zjbKEfP-XCsQ}%j?OE+CbAST>-MU1XV9qI+H%o>oR1FT{R0@)Xrzk$~F2)K>5JOGM= zrj_G*HecXv2r&h#IBsC`?JRIfugcQhEibnNIq-d$>^A}KttP#Y`kHM+Ie!K?Z2_CnomSb#fk23ZzGtb<+cuh@^(UY3uts6Mnx zJ(12&A+597^CqT?UFYh=$3cu(N*bf=to zv4AQRlk2UEig68<3(lV3B)_WC3eg9dN>r7H{7Mt*lVMCRm2?^N~@A3Mqvg)Wu>Txd*i4< zhMZ~d%^!cONn*#lABf|UWF{t5YjE0z6T~nN?g;Q;Peld%!b_&=alxhm$R?$wU}s8m zIAyyD;IbxhlBwrhUtpSnsq{Y$6p50HJ>g`aVS>JpRh@B^3;37#vxacHAzv0N51cVpevr^V22*#lSg1jUcRX1aXzSm!t*Oyav#Xsc zluq%d$S7w@7tmMeI^*EPpkxljdIsYYDenv?e+>#*Ao$!YiW~%G}qb6#Ky_mX=BOw_2(Cwh2kD733#PME}dX}^KVsm*&SS&67YK)V1hExKqNg$gg~wngkuPl6`i+0Ab^EyyJc|-#k=(WfFNh!*695kV zR`%n|8-xHT3JFh$vnmLXudQwCUSG%i;QEdU_f9)7RJr{7%b(9)IEH*0ZBDbYvlb{$z3deA?pwsfO-{?(_~;W`RFh<;pw{)EX0pNV6~JYH4R+ z${q8|tFIgx)U`bt8mI}aT6dT5xpH1w(W;&Nl9c$G;pk1KkTTJ9b|U!uUudIw1Pzh+ z1@3u}cuba|>}L^m{Pur;F-odm$Muc+bQPSwXg)X?c=7YMDf-}}Zy_T86@>`>$tFgk z?`##vap7sCOd(hN_eu<3mYR(qn!ITzMRC!)ZOBp}?ad%1E}_u(GmUK4lsVt&}Yp z;|}8;{oordc_yrH(W?esRW@uKWBu1n*6Bn=;ivyKq1Ix?4IG{BEiay zIA(^m3(V_Hnu5I~=4co3b3r8okz<+FzQ9ppaaz>|HT+;Hs=J}&wC4XF-(`WqKrCknG<>PT^+xwNi6(??kyoHsHLl8&B!qWFAa3{QTE z9BYuWN#dz8(WTBvdVebTlEX+`>Rpmzw-gOxJQzAKL0tpqFuXa;|Mx^cRoGL$Hb1e> zmsgr}ll@ozFaf(c>%xX#Z8rIDFAL;6ID`?6LGO2S=$pJv7mhI*J3ZvpZ{Go($^hX7 zjQura1c=i8%^0!Q0Dck$= zSSZQpBcHtcQbne~fvVdxqLQ@%?hq|ulyv55YJ*0S%?k!CyoM@!t*X18F(8qq+02?L zkIP-Hb}x^`C6!p6i5A^iZ={*)`qf^Di9nXNFRjGIA^1n|A~{;%R>;QmAGz;g5*L29 z0fSealv$3Co=cRl$g%4t_zZN;2IhYQR{mDS{u=C}{fJPk1a{?bZXssEf6|!41&bFg z(s^<&H>voe1O!*kZ$F#&ecEPB#DE=R5zkB#qhp?<)?F4Qfvy|Dlkesil$3hH{vyUq zxywfHh$13z(dIFOn^d(wUr(JwaUwATHj-w{<^-H_J3`4t3`CiRWrEfD5HSwOeW(l- z$7gnS0Xe7&e^JPQU{$LxYDfG)Ty<>eng2l}$P4_ZoeXSx1CS3VE5CB3n@=uG;uJG@ z?qt15=)K>r(@iWi<`O)>tUYt$m<1beY5NZ7wh7;f6(`A4rPo?l zaK=vriOk9$ns4uMb@RW4wP>;aWcCx=yUdu zu=v$9Ci#xO``DgKC6QI<2ZwNCjqS;buXlCxnV-(u^ zi4YHu{4U(KH8*rE3Bxf>pKc{=MTk$9%=*(e!zDdIDO`))vF%6{?wA3MZa#c8k$=hW zBE*180~uW;oai8#c-rs&e$B>eFBN=4)*%y#?twE>C$AZ9=2MWNKlVsc)M8vYdsx-! zdbhFlG&;)qUTVXiitBYXPxtqcw*!fX$#O|wptM0CK5l$E3WZaP>;gWx+uG+BTSmv` z+Iq4|Iti=yQ5H`#qvDGrcLWv5EvU#MZ;a}Bj?s>hC5v2WrX@8aHg1ZSz;Cm#XjVrg@@nUaqM_qXMD4+`XNyKk2YgO zeMr*p9F`(~R|jpz{I0m)(KFk`fBvxba#r7E(-L3d{=esAuhUbzxJFt-8T*;IUX9|y zRPpu=f`^_;{97bqwD0GmweX~D<{4@A${w{91T%wYwk$M*apXIzj`u9f5+B3vhH!BZ zVp8*+gJ@GFpwQ+5|As6PX~o^>Ts0IsE!z5%WbxQKBb3}A6f^yumC1LaGcNE;6+g8a zxP@A#7$WfrxM-v!*E~aczPu4%;$!^K{Kr6%oUrtiGFyM{jl}+|#|(pHHHHnzFPu;>mf76Ky?#|xIqKcBol3&K^a{m77 z2w^x;VC=*g5~)e5qv+9C`ROepEPZ1cE_72D5Z7w~;JPk9L@MpbLiwW|Gmrvi{ta>! z`nyMBP7D9~Db_urw`$3FE^L&A_6)W%8M9xe{(R4hY;Ko}L1r+QemNGKj0wu8b(Xo$ z%wncYl^dC$h)|A%_45}2ZHwF>hK1#`B7c#*cJAFmnK)P^4D-CWJjJ@3o8`h-;XnYqI>6UcQfamnE;x%f3O@Eg+3$}8&q z#H~8h^~qi;KWX(8Hr9lyXdH$SnS5ePxqv&aSzwTLq2!I4|NmYV@W0kN)PK48 zkrdmfg7{+5-jPu5cv~^C7R!)TQ{mOcunrlB{NJxU7u3;Iho3LS8-2>F?8`G>P8{@K z!}KozL6KiO-O@m!PxN~7_({s3-{xN8{5d9X(fQlinfH`YQZdEZ_NQ3;n@!VQas*UXZry3=Ryt2cfgriV4C4nDz#_Foej9c~j zBW2!4D867<%Pa(9fX0Xwvy%29A7_zLLK5J=n?hK%$WwNT0z6uxIi*ZNTI@-|7Vro@ zNbJY15JaQV;P*}2CxaWEL?2wtE&!~aiestF;Wrqnayi;Q;032G+5DBIUXog@R6w#I ztRBKf*j;l}xOpT<9a{{lZb8NoH>fktneqUfLO-Z_cngA+9kP^2)BUMOixEyxC#;m< z(3@<=BW*Ar53}KAoa`C14C!+L#tbf%)tQga??z@a6Q-%&^URhrW-c`7u@~y~VE(M= z>_Aq5&RgiWiEt2wbafunKp-dW8VQy_J2qMBXUpk!5)uNv$1rUa$49;>+*Z+Bm3Dw0YzhgSo!zp<{nFr2!))=! z2bBH7_P<$ZDyB<=tn&{i#-eCDpYK*=!NknSo`C^8CDLWDIbV~$;Ke8|4fYo@H<~@a zDj#=&w*&HpyKiCVg_jj<_lxX7=N&n6RR3XH+oeG1`_7$n5;8ApJK`=4}8)hwy7ci`pjs^ zSXAQ&sPTf#zbSV^rfIwG19v;`M{p()iJyFH-9QBR0xdXxC3% z!G$_;&cNT1DaG7$YdnBse`P5akRcJAY*I) zinQn{l-kQUeLe;`La_cabkJV3Xnw<$kCqtw_TBWsK{fc`1AkE4X)2lx)H@`c)li|} zcKc)C+y*`*fh~`e^!Yz|VeL_vU+=rH`}R^*tzg%`W8+2_dd5p|mpRfir(T2DYg4RW zRi`Y`oI=6c{y=jIL^bTEn8VeTP7cE`_OQeyQw;Z`ptJy_pjMZagZrZw(v2%_*Wx*h z5!QK45xw0pfiP zGXt(~rWc+>j72_-rQcl2EPVwo3kijUnu=zb8~pOs>|LyE*_OfFU9=nk;vkVsctjN6 zBMoqwf~_T3&Dtnw+BxravFM@nMJ69RFZJ9n47JRrS1$kqbZQh10nWK_W&bi5#GYCk z=a1Xwk%Oqp+%~X6-J36W+gmE~qH;@H;HlC;aKBp?KA1Dmdhk$5tumtK9R4IJ5T^gf zK+8Pg;EvHBT*4Z@zm30ayp2Xn88a<~t)v>KESej?JNv)KjQ@ZGhgKgbzliT*)^O#? z?&xVgur@GywfHSQ+V+;p3U!Q~>vHtOvbPX2osTw}pD^QUT|gSmG^7yRe_JkoxAIMU zVhT_${C$^{jvB&RT~`_F;aQAN!eZ>ZvALDTqM-fdq9I%=!rzbo8HM!2s^h|o3R%YSqWwNOmKTv}d{r2+qW zb?mMy*kT12^SNT<=?qehAOcW#0tz+px81 z2P80a)WhHXLPSjR5da9RG;!{WwC&5YiH;aE$cZ3Pcii``PwT7Ytuv>6g$Zeo4!HF%}}MZ)V-8fEVC6JpaAqd97qY$8XU80qAUC`lFcpJY@^? zD7n0W2Y;Xn^f%JLls(Go6B3kk5Y+%NM?2!C;qu1B(rGHyF<<5V&xpka6Zz5Q zVpzy^-*Cd@S{^oRA@szh*9I*2loB9lkZ%lIdp%HXp&$a;1^k+jMKef+&^^hqPS^ihA!1p#| ztgn)BQ1t?yGX=FSZG4_7uc&pTCpOBgY+l2~V)M(zH{+#TVPV~8!aB{Dm9nI4o|S!b z+kQx^vZX$W`3~dSsi+Z~o~t?VyJ_hv!jXPd0hQ?n4lb@XzmAV8%I2;`K&|Z23U8YG zEvyW~M+&|2tQ_`)ErxD5ec@BZtBA`sW&3R|lr?hv>m{-Ztle=Ba1orrag)tKxzLn< zW`Zb`XC)CH@MO#7d2TmbmriUTcq@;@k_l0kJgxDO3 z{kPw=ZcOYN4Jucu&!%L0cDuA6b(j3D$}V)|s{Q$U;pv^9bmw)M*8?;IZKz@@!Xk0GZ8MX**!$$dzMtSnD&y^HWMc|06aQd(i*=tX^Sv zV?vMOX??7hv4hYOjM#M9419e;6_BYU%sA|ZSM<`@U}fnPztwe{_TD`#W3N4e7BL@i zSVf&ZvZoS?bxbHp$4_ba7D+pXqIXT-5M{IWC-i`!UPN)FVrC+!Dhky3Q{ThKh5U|jVg;!@(tM&qTflbs|+x8T#^0G zftY0ZD&j!cFh=|viCi8KarZm}kx3sMyZHdvF}|2O6rpEEh!v2>qWwJ)U1o^Jw-w}? zk>`*@S=;0dU|0r3#br_c`a_Z>yrdof)yaWaKFofoF(&b(KgaV0$EOg#2MO1SeHxO* zl9$ytV*0&as63VYJhT6&40i_9`*CqKBFr6q zDcO^kz370%ttrjMf-ko7*c2hyqd0diLT@9Dw}~n z;uBZo?Cflr!c%n3Y4!Kg@paV_hO&3?ir$d|h0_DcYd7!?bfG-}vKiTg``T;KR*d+L z892Jlc(`+g5QB*%=CP!)R)|$Ckdsn`W6C8#_XZFLh7X#+0MhJxD&T*b;%~sRr8@SJ z;1s;HlC;5PT$lu0R|(9ZeHvV;;5PuA^$}Ku^~EFhq;e$S1EI%_)81dx@K3j^YC{2r zIrz8Ti|>V%`)l?m@fqT}Qg^7Z!1N?GHyMV zECM-}ir4sKcFwQ#Sl>TP073((4Zm#PFIqf4f0=CaBqESGdTLstulI};4&pP?v?buP z;d8B1b@p~|;LYqjypx`#dv)X_5kmFTb1fO8G|JySLN|Z0`V3R5lX5QMBMD}Wu3O?c z#*)IqrqHZ7%qeY!SpLjbG8UB#6SHJ|rkF1PsDTP^;9FJ`IpKdYJSblvD2bs3G;8sl z=R3c0*v)N<5iBV@?r?uTkExjmG|8b0_izW&DmywT9=+vami zWh*@NXcU1sx`A6g;6Gk_$^}aG#|L05qA#8*^;4w`Xc^}1|X`b$Sm7bCbb5GYRi7ckY9zCG@%Z!&6 z!>0LR-Ot$*_Nat5lszIapZ%qY31)u<4G^wc<>Qlcb5?F{ZtBfX#&W>RZvMD=dFah; z76YKLkc2YC!uD~uJRbHPfi`Y-PPIRGVCJ&Tgk^G9_8$i}mumqOVyx!cb~CdH-fqL*K03VTIG59*@y^*-5W1og+Y1sNr9 zNo&Pf^4CrUgXE~;gas@+zkcDQnyht^(CI_vm{P)mC#6rfo2mNgH>ZvqixMHvzv$!r zLnq%f=#!n=nDOWA_l*9e0@z3Z!=Kp0Cmpu89y``@m7mS1jmf}S8!$`4bj21y=uHKe7)xVq+La+P_SxJ4?yZ}Yy@e%!)7F5T!SDfY zplAw@5syx*+l$@2H9H8-4ctNb&&F>83FuHD{Q~G~u&L;;AplUS+1alEeO&$16m(t) z*c0g#YbygUjSkD3jYH9#)9={3tk7C56n1r#Ajj=ycw|c2np(>SS5+ifL{))UL^OWq?-tRXPR` ziiXU6c}@MDzQ_{!r9I`%`RZnu9Dn1~V3XLppQH_pZtw7#f3Lj;!v<-zd;vTvb{Y6d z2h*NbX;wW;RWAX*R!At=$Y8xhg=m)vToB6c&vabA!j_JX^}m>}ZE4ZD^qSz-8lQC} zGGhO{^+4;zQgT~*>~b^kO986$RZPV!pg2xjoVY)(z`rqoX=JOHJlE<`kUY}@_9QgA zJQ-;><1sZZ>OTwcK=Ds##{%xWF#ay~98EVY92FdB?9#J^6WpkFpc zCzr98w@0{Ehs1UYM{K~T#F^ObZuH>61I~gf-z|<{zOuz2*f4+5LXWOOljkC${c_7m zH|So@`NietmdWjSzFAR_lTvIPnj3m2Hh=ICqy>dy|Lv{gfOZ^k-tf>bLB@309z1;t+S2 z_mbobLUN%)%Lb|)ja|nb*H~O*#jE$2YauGBw3~Esz0@OI#q&n_WA?gM^$s)k4m)ue zgzJ0_*9|2Xyp|C|t)4igEH(jpIPk%HOBA^(wA{Bs%s({_*Un$xR!Zfgi&6s1n%AC3 zQ<(mmeC7PdtbPZuER!API~iG7Z@p&`uk~ntnn9S@#r*1jDUubI-e2Yzn|jAbNClIW)V<}H*YfLPoj^_(-UsidBg}Pb&64qK`0Nl_PJ%e8YLXI z|D$m?lg@g0%jFtFCl@I?e6c{G_e}kufQt8EH1ZYf-@>!_pHp6oc->j#&&m^t@K_T` zT564+)Ay?l;`16Wjoi!W(t5jYPN6d4xp+!-x>&36G;KS+*FseXfT?~DTwRHt@ysnM=aJ&|U#ZWHvpnVnVQ=Q#8yyHHJY$ z{K$imfcnRd1L@5hDiYk(9&Z|{V?1yRNTg>M{;W~JA4NJ2v&Dd29aFeY{s(~Al4kcpOM|WD{hqPFDdEM*_%UEC*(O#sy87+cxhslbKE6_Z2}KA|SgL%QF;RDoetQpeI4mYaN->;IDm~Dn zBnV1S_l{X5O^!j?t`Mocj&!ni>L_DPv7tNWe*0yGwGH>pw*YR}4(&6q-0bTm-m84o zBc;yiY0+nf{*Q{0^d!kzKB$A%e0Ik##kfkLLXRoJ9PAT6bLx6+ zPF7Et6~CRYBF*>8PU+{Fs5rBE)YsX-oeRB3L=}+8YzC!S6cz#nAvXxcu@a4fBu+85 zBH&&zOGn5+2M4b7yZIEyUS~@j4ZP)8fk|6g%m^*-VNVc9{%jdvo(e z{|C}YPB2gLLkMhyGMJSD9cDnDh>$`+Oid>uAC%1HKIeHwsg&@dbV7!LLfIEaHh}=+_mPmQ?fotl-XBKm`#%$hKed1Ebl!OfwyohS<3%DzXMMJrt7v9mPCS@UZ@vbZ zeh_7Za)`ZUTjsyK5&)^_#unL@vF6 zi8F0VQ4tTgxGfEO!G-_?4+_S&&6Pm!&D(50|FjWjsoD|x2pQM}E3beMYGQJ3s<+ng zMOmC;_SI1$IP*ONImQ4CQ{2IZA>7CZc;3zZfRu1=q86aL&E4IT>&FF$GQI8&9~l_K z8HNWY3{b0pxbe{GbJ}bW*7WSnt&}okv@lQ<*?Ne|AeNISRX14Y9$RzZi`KCulsNy< zW;p3{w}@r_`j-Lg%>90PD}TFKFr@X4fYJg%SJJafis^b5QOAtMD-gTjan!V+>=Sk* zv@~#`kVhu}t5?MuOJLVEeT9>y7YRf6kJ>wKhnHo%il~un9OF3ufxfbi1YyWX&^ZJI zdm6Qld91wZkFI>n`zuetFb12*(4kP~lr0~jkFjw4ye7XS4BB;S+Umm)Uf_@tbW{JJ z$l)wc zm{gVqVx>gD{sN3maiP-jnAGABjCX2i&@a9Wc_;v%X#Lps@Yc+Qm2y)cgPT~WFFSpml-iy7s!6FYx|%W z5nmoRHt{h)acWk?)RQ=oP2wm>Yc-}LxH;Y}KK3M#O zJyxeUW;u8Kq|ELx&+7~hs(}wC-b!+?P#790zKGZV83r4!{&?EF^cl>eh7&6z3UnB5 zr}pTI3M20}M1rsdEFJjMr70B@xruSVi%>}23Pn+THlP7M5|y5gUpBh$I5pY#p*drc ztNn)||8bN4hC{$U<=>Mxzw}MG|4;k9I;{sxy8l{+u1j*l_Ri<8W=xXqXUSC8)O0;` zYNDHIApUIlF-zUrGy9o>M2b?^6a9g&UNa5IXJQl)Bktl!oSX-IXn{hmL7|xjKvD*$ zEXH6kU6~oMHY}UY9MPt<_JD#QVE;u-wawT-L1hph!4pg8H0T4xG4k#>kUmAyxCK>( zI=ljHB3k9Ag-97x5xZ{E>{rx%8?aDSds?Tb%DT*1&0Hj92mV_Cu{T);xdCix%_DW8 z45@I2iiwBdIx2($oISB6a>$;NF%DbW;p$=_8x86SL1oOEM~de{z&#O{C1$T|mqT3u z$PJ?ZWU&3l1}YBR@m|?Usmlg{sY3Ge)#i50B+NA(pQ=H`XO%S8cct8SSN1x+vE$MK zcKQ9Oy`$s8DIM7HJp*wFL10@euWAp4bJNF=)o`&z0GJ|R|NG9f4GZ7|NrxP69eV5H zHNoU5wa9N45pFXMjb;XvU@@dT^#BJER;B%U(>_zRoH;p3KIGd`>*zNC*S{&B1m85B zkD&A(;SwLKid(kVIyD%+W?qSn(|7hKvY|V%I23Dvs}qsH-0NZwKBD2L1jrwb?uv;? zEm!A8t%nUJ-2x8VZ5TRWuT9}K>Tx%$)B9r(f%%M!9kZ3tvocSW)US=^jLu-xr`>!U z*K>cv&hEsIutG5Bd=n#F;}z_!$?KyGVx{T^#@q3Q{95FotN6NRIC;#1e z<a${gO+ zo|$O6&0VBzZ20E4)=5<0O8+29DD6x4HDrwu(5WnmPx~UryaTl;j*gBW?YMm!lN+68 z;kDY7z4QCniWJ>3lmPvqG!Z%uS&Z~W#qnfzz}L5wi?0~Z>*#BTB#6WNxl;T3zwrcZ z_(^g+EdN!BZvK6CTjGm3GqW~lMzYR*8D*lnZ!21h1AF8!b9;9@I8p86NN60KJWXby zgHv=f%cS_+%Ai!MdTj61Zk$#$hLU*U;d@>CPcI!MZ_i2DIm#khMsO&3T9qtI6`B0b zP2Mz+TT~LHTU&^*n=G$Q_Sa^aKEk8MK{#pKzU#v+WFq={KLk2DWuId6z{-rq#%V12 zLF)!;?}UgAM>j1R2-E763n2@w_h$Isrw-uH-mfTKx?rf|s;_HmA72%$fEGp51k<{$ z?(^5_eAn@8+F<~U_i$n>>fvWs+$e4BZzt>7bdq(0W+NQfM~-H%ULk?Li+iTq9qZd| zzi0xZu_BR0p8sK)#QtK7!(LTNG^ZY{=aV3rvDwb)L#M#N@N&gy#i8~QrfBWi))0%| zpROGl&d)dygBd=1?S4kh=NNtshTHZ(i5evveoaoz8h5-`{v_s@ewN?;tKUQTOYP${ zm7*BPBXrjY2;zMOjHtU886rdn{K|503`mmYnPD`nEaW#;tb=#!>+ISo+CYq2+uYo< zyv$P70_;_7Y-}jhQHRBC1t_NmBDP@ALV(O8Bc9s&`k@);mZ8Bx!4f2z)v?$dGmpMv zdc;gN%VOlS){~tpeS;R2^l-XoUvdaBlgu*N3z>+~aayVqEhk;BIGv=Jqjk|`fZ{xa zNmynD%0gfXfyZ&R7mh3h=}4SQ5A_3qOdp=YN+Y5X!$*M{cMppMN zhf2#_8CyBBL+`@6!UP;1MyIs3!%iA!g!gQqrVx-Lz-+SI91|257DkUKm z6#!di2)cHqprF`1y8`L}kIU&V#_!%JZKw?&eROP=)|=e&lo)<=d8LT6294PdUY<{ z8*~>qCb-rkb<2OY5F`a=3?KrdNNnSV_0~z}petw=GR^*Q+G>JPDJmDrw(Yt9DSC9h zcqL_STiI2PD!bqfx@sftVFtLcoJfLto75uh!nvaP`~wWJmqh5-<{XD0S1AUWZ4*Zmvo4SsbzgW+n#Cop1rY9Y{YW_Y&L+(Fh8(Ovt_SB#8q*;maLI5L6=cl|_+DyY7*PFT;dl z?yGuvKrg5u^>?*QTe~pu(6#WhB~+;A8xqK^#)3u_%952u6-raRMsJO*P}VO^V0qX) zZ%wYC3q#=>q{DU7@F;osgvI}HV0<9=!(JkY7**3YVmdfTLZ~YtT7KX$_44>%Lx+w7?7!i$DOWWQ0!s@ zBS`Ds@%j2{!lG~MZ)+Y2!fIbCx91+e=ge~Ok>%7V>O$Yf4M0n|#+I6%SBDC?=U z>`8{am1&DaFNUd!sqMH;4iArA>!%g-!$^{onQ>V{G6`S93Zqymd+W4x;Bn&Ma<>0a z+YMf78oTM+{&PM5@5{;7yU}I9GVy3OHk#xZKsR}Pt02M46hl&HP9mVL4c-gjU^qGb zI0^KgWQq>y>o_#;^wGVHDHZxCUq9@iYMlgzChDk|`~E0FAp84{9ke07z^P^kC&MEZ zR(B^=MIGiRvvM3+xn`Ay2aBuJR#f!w%rqoN$h(4IE`_NA1X`JC;XAu`z!({XN_Dx)vJ8yo;jJ-Bbh7WKF#X~z04>~t)XDT(S z5ZLrfS_|?cQ^;&e*zgI5i~aK)yw}ol{__9003a}&yHZ+5>SSEo2&fp{8V9{^&zt@C zhVOD9u*{qs2)>+`w|Du(D@b%;>fJ}jN7o{0=iF(i_D(fG(=eO{Pp)7fH zON2m%h-_WSu(;f<XNNTtep!D%J(VsBJ0&yPrk*MX_|%g2Xfnm(mLkkIDRMP9G{tEFYl5k#fR#AH)x0k8 z`CJH-%R;~zX%Bzf$;-CznX~iI1;12i)TnMKcp=Lb{E2-NHIfL7|7C`|gdWZY5^4`$ z6)9c0NDPzYi$s`NRf>FElH)k|J}y&De&c2)CJoxB?>E9UaLBO zndZ5lSmZe*23ah9EJ$u-$$cbU3URH!3-N$X<5_D8*oKFi=rsn|$5-YX$?4%=Gs)0P+=mnw5s()d@k{|QT0?BIIyS6=+P~|2&_4*9oNu=Uc5M% zAvUo4_+?u0h3ESE`XR#$kBSlnO!{0x-uXfU(_%wT*TYT$Bn>G$V51OWFwC`3ylfCs z4xu8suZ!$MqQgi=JkmrGV&^T5fwx;2_dramhXVY3XW`aSM|Uk*i2?X!0YNd|_8uPZ zH|eZWaJrfHrhnF6Ndi*AdvZSfcqs03UFwM34j|v&ELxBuf`E!13AKCg7RnKL%9SM` zQW+MR~f?#N0}W`g4q%6;fJ`9t?P|^y^kEkA$7ZoIGPM9}F`x!7f(Dx0=Ua zxxY41B=Q}nC7-U6tg|C|z4-g-x=pFbS*-iFtMwj#FY8=L>IfuPa1d(n)OY8;0r&Gd z6?qvos&1>d(sYW0LxTkB2gM?`u$aS=1f#D5E<<$|(oh(3`I;2iDfK<~=ZWtNyZ)Mo z9P`FPhev&YD#yf8o{!Ub3Vjhec)&PN3#&_I>c5JQrHO^^I#F?h@FXR^N z1_6QUU$|^YDWb!vYqk@Nf8ZZMI>w}@{{ld>IyB~iuL!_5daGVG^a_ahoziV>ZQWB- zQ+tP?S-AM=eJ>_(ebnr`-H)KK`wjFd&_QttzZM2S&U*Wn8n{;TsgrtV{`R1Y1lTxb z-##=3cZKmC>JMNCHBkgVU_qaJet3Jxdxuu{fkXkP?W%Wg z#gD(0kwOk1gitm$#h6oxB*@iFuFN*NgOzY8;@kOhtSE!{fXfGo9j6%}SU&{oga$qp ztk7?^r~imRquJarlB1&|5CnjPbhwkgnt+iA2=Et~)YLW4$dci=-tlS@^$6Wv4r{XD zV%nPeV+h<=7jpf;Wx#c08+7_iVpuNyC~#?K?lA;r=I2bSkTx}ISf=Ckwf0antJHkv zl#kfBbaJZ}{4kVYX_+m2V%8-m(+`jCYcC7P6Gqe%RTMfYQ-4K9Lhd?7h zcBPbV?bGic6(<#RD{kHPPZ1yMAF623S%(|I(b?LSt~k| zdS{hk&={EV{V4kSjizKPpaA{r{6*p-T7EKDZ`FOSg{52h`<~FSm8n%u{1^kAODjwF zhcfq!UmV;>HZiX>8;?Oc1$7IdOa!b}oC}emOv{U7GP|O#5qwdZnVD98-iZt6Lklc@ zhj(|CZI_Sy7dA$f7_BWV3YnBned&QW5hH#381(UTrKA0%^+?1d`J+AsMU$Q1x0@@QW5#pP8MUE1TwOqGjGC!U@ z^KEH=uZb)cQ3T(G2<`W>w&AVHDI`i>Lhm`ZoPdc8;1xbA@xq6eN}PLKlb-ZI2ZBlk zA)XF1-Dk!C!&uk@MDj>;D&Q0>mpWh#+K_}BAQT4D_Jn||)B6`fP4)FDMXl;7Ud;pZ zPO&X5LfR=$I%PtVVtU_q%EYn!9aQHPfM<6L_2XYk*0h}pef|r1f;##z|1F+{%c0tl zEMUZ(N;aK&z$dFo3o&A+#z*zKqX3;8ma^$Jqo1yBKinl?A63|UddeQLo7BnD$_Q|m zfuV`v=#(Vd{2JG_LoWLUZ_RH{fxd1&dkT?6^|%ub|t8s3?@p{QxPB2%W>2Fp&hX!{x5VP+WLIL)AaLf+Mr&dUfiUKqsno z{GB#JreUU=Pf&orCZ6hsQxG_f2%(zguQIlWx|MRjtmo969-f8l)5Qn9ERF2!>S|>CDxwh$jp@mr z`-eD10|rq9V@GN5(b=2H|ErDK_POpknClsIkLHAOgWcEWPJyZT8I zED4Fzm-$Bjfczc+%mCOJMiRoD2l~N#M&57CH>DNpMP=wVa=Q)ES+JK!TW6O#1HB(`rIQoTW-K2M~pTdt!T2A5{H zk%xs_#WiX-9@UYQMk}0| zlPOP<`mIN2;(XLH5%~JHq~?%(aU9+9f~BAvqyGIjnY@JXV(=BCG?^7X>fMCXlV{=` zL)pU6v>X;%$3CPrH7R+tDXi!3# zIav^00X|mAyKOP@f`}?HyNK@Xc5WvLv%BTM5RJ~(sQ|mu7|O3AU*a9JewQkAae@JI zO$9?BczqS}faJ3w`LJiX&ZA>rAdisNJ4EL&h=4?&x2jfY70kWTu2aS441*7T9+vD8 zdjgH2#f|X4kUTk(~LdA7$Y}TWTQr9~L4Omdqe+ul$$K;peUo2Q5mWc8L z{o@5ALSvOOjk9d;g4wYMG(uR2Qj*v?AH8UpGQeo4DvBbY&33#r=^ahM5`A5)I6U)i z{$sfw9dH!+M3;AY5qo|38PCXn12tiMnhcUxQ2wkTh?0Df#4ke~Fr4tgD$HY{u z_k2l9%jV|U=D;>?x^b-V%w^iH`zjdk)Y};i=60p1!X!rjyU6SLy_@?tdBZCJ5c5mO zmzm^JE{v|w-*#})=1k+9VjF{WeNmhJ@rFCz6)S)n#f0y#kuNrMIZbo3dk@7&eT=zT z8qKZR>DoR%j-N;Q(bt_Ep5)>XIV{zt(Wp~kwXyDAqSZa(34twdE)|8j#@YPIEbZEv z@I)7oC&mor(bj(G)!-c^_j}r|wq*+Nhe^&EUe4H4rAIN9^w#xPy`=qpDL=2vqbR}_ z>uzhhbZOggzKtU1Miszoih40$W(OGV5O7L1I8_x^3ax47$}A}83aWKTr<05A{Mwh` zNVY))+x!e5ULqitWbF}%B>{w*n6Zq@05;AVJms;>I6B&0KS^5Jtq*~8h$dxYE7DMts#uxoMM3FAC)8sZF+S z%zTqrnB>$DTJd*f$O(WVmo)zkQ(pz$VTCYBYag0)I0tRbfCB7*Vi}O0d>=EpP< z!JtzvMoOobynp2+ug9h9zrg!EU1kwwr}nX~4(O1I7WTk}t0{2+Ia~0P!a8F#x3olC zVEp(|M6=O|1^*chsVDGITFWq93MG{Me)gdCN-1b?>^2nK&8R)X5gjxGt&6gtYg>&R zk>nyor1H+yZX2VzHb8@ae;ER_MSMBIXF-pJ0Ea}7#tNYaaWf4#(FI8RbKNvRe+2Av zfWPsMwULsNZZ?@@&I5Q@Km8&0*ZF%hUtp+IaHO5)jedZHKtEn3ZF}E@j|qkQ)jKln z^ytS|JVWbNPGf|`6M1{&-9cmuy)mh0zWpRIEXfdlI8{Lbe1_7M8viQRq^BE)RQ}jw0kifFQ1ZHMlo(I2Jgbl0-R3JG_ z2G(!^eIE4*_%*LDUr{FOf^y^oC|y3MQ?_s4zFjKGFj;QBVt6;V>$d&-z~YT85eO$O z)~Uk@$?WQ~MhaScc~MNBJ-5P{^ag&^zzq{I?J-t-Q%e}QlpRgYP)qXnL$;Mv1agv#vT{QCtUI_{lK7ZO&gEJ$HqL7*fmILR> z*!<)NWFLdM-lg3}-(Dv-Hu{L=63A>G-C|L4W^nnR-}?Pd?`v;=0MynUm9s{S-_9f_ z+`{cAB}?FyN58T+-ex+uTpY4#faO1 z%$!{5G+lJcdHg}MQQv(@;!^4N$sNs*!3*2)iyo|R@HzZuQ+fx~UmK0T}+%PGZtfSYa zZ|!-){z9s8@aAk`;O|g2{v}VnySsFRwITQROJK$5fHJdmq*rE+SH8Y)PG&L9E-wC3 zze%BuwBAo#A#GsuOR!D<;Gm|gI8j5F5<`tOsi#)7{WJk=5;uGg1KdGo;uO2t;k@EM^vM6c-JSpIc4wnlSJ-`SW$MeV^o(}LD|TwiKu6ui-Y;cs zZH;+Xg~8eDUtd3||DP@8f8g&@)9{0<#Jlq#K<@=1au0FQN}b zW8}8A627Eaff?b*sZ(U_peLwXj_{d$&Ey*J%=d|0Cqm#eVH+GwbFrF#N}^LF&Z;1P z7Q;Hbi>)fIavexb9Kb;hftd;g?3oNx2dERFW0V@gQ!6V41saaD<3ZPNg_6WVFr2E^J#ufvex4<1MoQ<7{CJl$F0L} zpOnFM*_32c>grn*OA14YM)vkd*wEU074+EV{f{Ijs{Ip@1voVG%1t!HXn2+$DXa7`pCMpwCw$OKggo1sQ8~K zcX01`h&{vaV2QC%L#=|9XJ#ouac@kg+2Y|~{jl4eFoPK|8sJN)<<4fpeeQ`P)2lp| z3RQv504O@FV2V!it6JM62-FPqz;eV#N$XevF~)QBCX+;Y<@f3n)aYpJrR?{xualrr z&*jtboLhRfxAAN44n665mcj8UG%Wwvbcg{;HAMBvY;bHjt>9nJWxiso8LBMB&qfj4 zmUp)bg6igco0in<6)dD!#C1@9DPg4+y$+hvGg?wl4>{Yw!1UZ)bv2YU5i^^0WplVz zvVrN#A{HHkOhYi7ZC9xGI6e`6rX-;JHaF`B*BT6N(1-O{P$67U4%pR}b%M8TYRb{| z?<%#GL7`R^Nf+^&O8C@UYOj~#Q7pve71gu~zs-zGZX%Ypxp)jIi9q>D47c2`!gRQ}`O<~dR-2C}FTcxXT$CsN;30nmF z?UK*DGx+`vHP8_*!+2jwx+Fp)H0H&lWJkBFqFFQL+XRTjJ zxLk})uO=wL8r#3tEp~F@99t%N>hEkZ?Fa4rq^}#tlBMkGr>A0qTRrd7H(5L3Z^{SFenF}98alXxDoD`5phbxh>jagKwnK?VxY#LAELHq*o zIWtt$G&Bk;49(G}6LO1wTNC$U`O3q3NprIzs<-4_^BfY3GWp_&(34dfBOsje=It+? zP0gIVq9;uPQhclW=L zZ~CrZEHaT^R*PiTg%B12q4*e20)w!q3gmi43jP#vF_YrZU??*B@?OvWx5isSsmn~T zRe;rpE!^BJm?O-iD;b0O+ph!FI;?DLFc*fgOmq}hYkL@0evh(7g+xK3F5Fq8v6rzA zxRc1E7l`xTT0kGsmi|2&P8^(o2nU{AUo$BD$cShhJKp`=6*o6WFQ~rqr!3#X%PYOF zZ#}8_ej()DdzQe>4FtmAXQaP>KKBrjd@witFG(xeR>QYA*l(c9Q6X=bqAn(jsjcGv z)5&{I{-?38nKLn+rJ-#zRq$qC-~F&W8}I*SN@s?MFetW*{=9RU`) zN{I~Ar)V30av&FOEviDDe5D5d9JSdYAE2NOrm6>+PWdpgsGSwrZ0;C+0QYR#Iekk) zbMu}zL>(1@H>zdcxhkau9bCG;JIa&kaV1hnhQ>wArNItFVg3BS5LrpZIHl!;#2F6| zSxk=vU^%qaz=NiP%%FdH*tRL9BIZ#BwPTi~>kfua_o_-MdG z5BnWLCHR+-kvP-bp!$>f%KmQC%OJs*aI6|l#xX*s2N^5hAilL_-QZ~9cVW@8}Uucn)ma@Oi zaUf7HxON>1!$*xDNH}NW9@jq3eqj8Vi^n}K;#AMMnHRYWN+GqWcx;ttE`X$1BfGG>`!?BpzV3uUMHsEe; zhf1dl3O-d*nn?&RwDP!mjBi||muux$uhfU&+x#kVG>FO(4G5zgmK^GPQfB8lO_km^ z%y38Dqe;iX0wHE`a-3_g*8kw_II`odZ)j*Sa)Qv~$o!x=wsop6S*PY+7hMPinPlZU zz-7eTKyP%w|KzW3){srG$imc=xw$zbP?Y(D?KQX;jt(1NfX(yjj_`twn;Q}cShcv) zzPc3RBidt>5-iMg9amiK}WR*&23z2z$%dtE?) zu<*5^8Kz}Y9NxHcbXq9lA1#L0kaqJsEfV-yG{90aRm#;i z{Zi>;fBj^j3<3<-yl;s;f#-7Itr&esKRn>~6U!;zt;7glbC6y{+TM@WAU!rfMff2R zNp(husEMH>b8iyK^hByny3xqo+s`>FCLQ5D^P#E+UZvr(Jkl~KxIt7H7OEO6 z67f@8Q&N*X9qt&a=8f~`dF5Mf9u2L>f5J@EY97_j{Qc+wGy}XrgJq00EMd6l0&Pb- zN}0J?eJ>m!(kjYp5=+#!)YJkGaHCiZva)^5sX)MIe(H4b|8W6ypA+jSu;Bxlk5q)3 zx(0!3kEq`K7e}z%JFGrurjUwZk%tW??|YwgsUVeUY^frmA$`Bo<){?Lw>-H%)0k7a zZjK1x;l%mAstE?uqXNRW}v6l zzp{w;svO?lmK4-2)62E+^`(Hp%Jm)#s+)OxV-3eQ9v;~8NdP-nU&3OSyMTqoF{KQj zyB5ODPcO&qJs}42>5$!)GeLtarYNR|>ZU%a^BCxGh$;pIu1Ho)SCTV_6AG5j73zeZpAr?`+@^JV*B8wwx1;VE87Ao4ti{lCuQ){&c;=lCU*1=^D;Q7xpTd^-KSI#P_ zDZJ-*FK3O*7oai9D0Dd4+bpNCSD*i#ALrZk8XzGDk@4pLbLpF!{%213$9ZYZ3MB8| zle$6O-DARK0S%vU(8^0S&Ee;qY5!8fb+||sm~R3TvxQ&uzG2$0rKeS&zz)rX#<=E? z{9|Zwl_1?ITlwh=87;wje?F1Iq65kT)4Jzj+#?7AJ(t#p{t@CD`Bas*`0s3t*Q*JY zqWVUMhwDD*I|$)heudJ3;vf5&QCAn2`(yRi`wD^WS3~i5Gj)Kw*1-o}fE;yxzI45@BW$*Ff}_oTP)zss9k1rtvXr{afX`KOR*-W+SV^W zwrW};#Hsedd8Et{3m}1qh#VxZ;;U00blfjYEiCsDdy#Gp2-P!ymP(OT4b<_#z#hN8 zzCH~8eQfMO)hR;>62!VZ1jOVdc^usd7vqensoBkO!Fb@3#y!yWl58#aJHYtM%Q-Pa z?lCen)_k3~0?_k2dUUDyI9uU~tviAo_iu5hrD$EWblJ}AW>hZwHP_%V%w!6J6 z@boFjwr4EusAujL;khhA37T$FVkFXqpPp1U#&rG)egMQ_Cdq zg6`c z-}=UuSpct@4l9F@gpI$nP&hOC#;ka64F5 z_<)2pOj^6S#Xw-70wzi}g*m>|shlWG{N;HRARgyG#=UejEXA6@n!4m}RH^sJOS~7^ z`L`dJZNU6wU0rse1JD20FDLhlerrAFs2xtE?qgXH2w$G z372(uBMHb{9`}gXv!@(-J~cPTtijU1hRfS>E|z6+a8Od2y3Lin^>X~xL&;V*>JB0O z3ybhqRbi!-%7xO%F!bQadukKxoR!x7UTJ_knQmQJ4oGyNOyDDp{jsqz!MJW}USEl< z#3J8!xvy-h;q{wIQ@<2NFxla~b^7Uc5t_(3^KicHb$G|X+5Wj^{@VB-XP31VdpdEi zET^88Y1>CYiqooZU|u@47;7(VAnB4*^>XIh>(hrHF7dPH=%+{7YZv+9m6ltWb9(a_ zP8oE&qV92eLD|FA3-6krO2-MV)5Knn76rwXXGM`3PA^7Z@BU7 zI(Fy$Uo&aGj+IT=3%Xc)p|7uRHuBG>pSQ&$;o`zaVz@}J<{|&Cn`<5v^Vx1YdKn@n zD$G$FUFOXmMwodjDF%1AVv$<{bSIRNWX4ZM1xbe= z!mV?6`KI=+fc@MXk%TvKdX?dYPzbCY2mmdC2wg6HJybEKkVug@;;r|xfJD!+-!nml z60p_U@f;P5H)$Il8w*5&=wQD+{?Qy+A}i_dJX;P9)vP!qz&q|OW@$m4*A+Xmn5ppa z4~OvA#=5@NfLJ;Q$Wsp~z1|c^1i9)&3rC8%sRG3kTHB}cNd~DsRl)R-w3ZtOW*oF5(lrg{N z#WJ3s%N2$=*(uj`jvqs^s)^;9l`k445=aHm)#k#0HrbZa7!~_-=~|M*${^4YX~X$v zaKDc4Z$E5pLOaKz3 z_g_fRP0+=C1Fn&+fj{a`d@QFVG3@M#TT^(I>pmg|M`DpadF%bqJ zIv(BXt1FRVczK_JetFnC8B(r1+u1?pfLuj@^c(n>tZL>*0<9aAr4FABtBq_f!ps&I)FBr`&h zDy*0@HAes_Tx%BYB=2@-7TO6PfDJR^CEYVOL1BXmPcS_gWR31U%*^c*H@)8urJ~`* zF(-S6;L0jR+K8sRhc%{KQ+Mzk_0;XL+%qQvu(n;pOZ4QPC&Ln5f1aFyc|;in3=@L6 zV+V(a3lL(!sZ3$)xmB(prhIbi44Mp+iUlB2EZp4^ioD)uDn%q0Z{k1QN2jnMx*v4|Ga=xYKl`{t?KlPKFy#(K&(H%AeFMUamot62(UApw|2~;2o3Iu zPAS_*W0WCzu0xLgdiP>O#OqolQR+ZM8-*IDRWB4N)vD62n&5o#Xi!bPC>v8|(R@Z| zLIpz?e#nDRFPhmYpcO+xNzf%(s8fb;kRl)^*wn@B&vzo;th(kF)fO>@MFno2pW3e6 z>4cBR>>HBV9%_3lKfvknI{%}|XzS%0Vwxw_bGwF-7j(duPDpRF`0%~D;P3gFc1_uw zrjB3p6ip@YY&#+)oQe-inQS&?8`!f+Z>Km_*s$Ofe?Cp8_ODqyJpQ-1Nqb?kcDnPF z$GB;bBj0FctR(T``0rC5)5iWC-e3C0EnO#Dj~qTYADqtYjZAO3{W+H_!Ez}wf7`jSoCU4b@r=IXe{Nz zMhBtfyNRv+u70jP({H_Ugp$2KfAK^T(ia)=px#e%zTg5-CnQ>Ag5H zk7fRQ*{aU#t?QSmRRRM?k-tr5);~|0tgIgRffWN)R&>GN>;1??K-i?7sUwaoSMK2< z^QRFy^RW>Nv!L_1MNh z#+e+2p<$I*Xv|!RQ17Lhm5!&TZpJ`{!P|wio4^&pmCaF72j@N4p0Zs?0%>}BhW+GC zc-hxK$3xfK@ssD5d$X!FGhLkc;{6;TlIC|(WdAVu4PUx|pO`%U7fzX1H;?q8xN-)=1MTBrZ zjwwv&#Nty=8GVh9N%zc)4xz&Jz0MdwN5BMyjb+$PZ9ra`KN=rX^w001dOE(SA~K~W zG6kSZv4SORT+AV$jRo{4Df4avZa`GWX7lc zq?n?O0D6TAlGN(6dOIB5xr>+ih7;Hw-&5I3T}Ie4$GVX`m?yS*)_ss=18uH%Bvj)+ z%{i?eU+Q_{c5yu0k|BEY3z(LWDf~;nX>NY0xy|QT0n2FK5=D>41XST~r_+^mQa*G8 zNNmLTu4jRLuHmbs2ly~+Dk^Mz&NJ1WQnj}N*8QoR+JP%wu|XQ&Z&o{hc6VcfX4OLs zq&Gc7LVlc;g>-=j{_n}VdLjanb{W~l2JDU~n@8Wh(6i!r7p{E5jLn-ci(X5YEtm%c zZ+$Ni+`_)N$@nRLx z?&3^2BT!Ib_cU97OmU6PQ1^GKT>9$QFG?kzkK2`lzkf%v+r96Pv76=%O?! z;!=<6FXd7<5|^eCqMZ~*JT=s@4oCbJ3}vw9DOVv)qdj+`opjPld!Q|n*?-SY1Ctan2eYOxZ_P8K;6QtpE_4m zK!!-UdsfARt{um?Ek$USE*=75-T-;-F8+#ZTxaNPC;7vE<^9C~+uGuI^YP@2YWuzX z)HAwl3H9eb5qw-R5@lSEbWF6;%v3WX8U4wkgB@|{RFl|QTW|K-U{pJcPamnh;Me$K z=SA0U2O12XN3oTgv(juN(Q*cyhQ|4OH;c}rWOgd87g#}Wm>uejEOppNMGEG&k=@jY z9C+HthL%u!@pn%n%!zC{6Pynwg4}u2A5q15pWg(X`H_jOHw12|Vxy#|NgSow@Kd#N z{0?ynB|5jhLaalUs5-gU@XqGtO3B-C<1FLb z!{NJ-i}?q^E2IQH635>|MZU;qaLPiNN{BPVii~3*>x8YRdqj<$T=f1~beoS4JKCEO%#FM!4-|z|cWY3Nl zpG5ZCH6J(DGEo$STYx5)2eO*Z)JvJMfaP=)jN4?TtAkB|cs~JiHqJ z6ZCuUU)XI$dmUX&VX*+yBR9HXg-o|QTV1`cd68q}aOBc&1|L17Et@XqdzE<0nPOMj z^x|T82qIJ2;nb^JnU0HX^Rqa_RV_X4Vy9*nt#NhvNsYEV=Bkipo*zRR4uru#%L0Za zM+-5RtwEVP+hX+~Gt;HZbJVQ;*WJBQcAtH&`^tX*p6+t~G&Mz=Y(rj=8U~jcd1aYN zK|AwO87~YY|K=K)Kkd-nwNth!WBkq=5@7&dvst(^o}*OwJsjVCPLTt;Xg4rciQ3UKTKL-89?bKoa)6tcv2@a)^Gnt{ z$b+F-|Lkwy5+>uQ*u?b{Laje@rgkQUe2A*0OEKcmZ*6zhHS4CTlQ#^}<25_^&7FTS z>uA*Ek*m7*(C2z~%Wf`boXd``86zz+I@JEMw;$d5oj`cMn@7QW9h^p)G+5Z-M~~Ro zHOuXd87>NFZu{J%DY$sC-(M|FsecNQ(4|TXwww}4SJ&lo&_3p(?K9=AMtjM4Yb$^kBvrTTMW* zQuw)@k1Lf6u2P_SJ~bSum`*N8^Vq3vhoG2m)OyF|@xWy(h*!aTA=#=3C;Lp>2ow(Z zJ*RzI;XDsL43e!eG$noVxCej~D%HA?k=EGT@fY#CQUqxaXDLFPj7??)MBUf7w5XP$ zik6<9_XSA(hu(Dbt!c~6Hqx*4+L~@gzC7d+;JE%N8+P}+;nGrZYTgmjn179?!kPLj z3bwG;-rf#Lm}b{}Qq0WW(#Rt&E`H_o{-O)bszTac9Z3lYn>SK{Z?tq@n|w!;3c!9j z?Y}V-q#}|))Ly)>_XH54J{y9#ieJAdun6dwu(Jeds;2p0HAkuJckIn60b~VO_pmn& zPR$u8z2FR7d~W4KfAE%5r@(dlO`V{=fl1LAX4~tHe|}XrKu)YhBa$$*YZke8-PeHl zL<1bn-=$`G$Q$ZR1KT=)$xRha*^N4VI-rZxs8`4k6X5-O;ktc8Sl+SVyPN$6Hq zb-TSzA+v7HU(J9}1I@5-S^?|`9hHvXgJ!dS`8rrL2lBpd^|tMfvq~e*F%1l3v`~j{F;}c5`JxwM}o^b6{hwLD!SQgFs_83%C($amv8cG&YlC~?3+h%XMOhkwOYo{BxLn|TF3Xh-*iPNCCPC5H?70Ww4mE9ljg(Sk02Gb7^& zL&)Y(7FR&Dvpzwi>qGd4qEg}@kCjtmxWl0XIH)ivEV?L1a1??txXURnMkr>jLl81Z zYX?Hb6zkqyyIv?k^igUdS9!5amhCn^R;qP)usr9`XZx++rIC9+->!~?eXepR&%3U` z#919VhEu9dtjMa7E2e-V)PHFpr$@n&I3H!{mm1z(M;CZ|luz1i*?QKo$KUYj`&7Lx zXKc(~&{<@vfDR~uvrg~ZP2j255^LG`zIc_e?ci}%_3&ii*%`KfzF-yo z^_MjO+{$84@7U189r1W1jv%@Q`{$&I!0JEVE0%*-VrYJ%lDnn~B+N@%x%-8_bZU)$ zsli~oH%-x(U~%R<*nP^-aqtF82#ZC}rKRd$vUR==dBo`Kax;AjIWUt>kHqiU@@S%< z;v~N)P60Q<=PLv3cxJA+n44mWj`PT3HAiWfZja0i$TaXs2A{1Arv}3BmzV57!#nIf zY6#cGOiRb^D4fi-^+Ck9%<&Js`?2kiPnjQ-9@sDh$OOdX!0xbnC5)T%e7j7Fu*B@E z_g$M;FAz*o)PVWxNj$4>Au9iEjs2qFz55~B_!f^;cE$RH`*-KBI6 zjf8--(%qfX(k0zp()Him&-1MHetN&KSS$u%ysm5SeV)JbIGj$eE1kD?Qn-XFMd2K8 zU4Q=l?CR<$bSQ)ZQqiW0<_d+IXOpWmILKFM?!QgfpQ4Kc>YR;-do)XK85Cp)mB=qILTV*fmqZ6K$zPf#;yM zO)vFXy;JyO5aKau&D#yH5-1D1Zw{$1$Jtr;ONRSt!#~%w4zIa?>L%SDc+Gmg*fP)jI%bcas6R>S{KQ;bzsZhf=Jx64zz--{tUiL2 zH}<*IBKk1#vNKAD6ZtLI)8IUt{hV3j`K{frn_7VZ&-%_3?iH;>nb3Kzl?e0CgA$Z2_=G8-6cG%F>#|bLgDHkCoQr zj0ki9B*Dbj=tr$P^Dw-ib!dp#?>;cmgR2v8UBSiZ(WrH*ARTC4yDWyf4<>pSYU~Y{ zO9uqr)y`y%B(!HT{$vA0|B^lFoF!Q@z=)bfZ_R+-SX z%P+z(6pOMHX@?#X#bH|PW@-3EKe4y>-{gdP=Ockd7SZ?U@trgtaXf|=2Kvqz`7&Rs5rEcL7|zN2)dQYEeLJ}nBH&!_96PR1 zCH!O(ir+>5NT?f(=@|C^6$m_4VbLgjV4OU(cO2OAeR7glJRRUk!I0^lpM7{E+>jUR zBZ1BJls$@8P&j)=|9X?}VWV*EWHX5J?c znld$W&rSVXX;l3CS432I2uJ-pjn zC8|yqUdkE|Cu%)KwbmGx4wij4@2;oC1K)89(x3+Rs&xM)rk1SMON_#?7VWhp(*; z7V*H~A0F`1CXc?$1<{CEx2@+6jt)da8A=IhP;mBQBg;fA>kI$FJrqc1;kJoU{OOhU zGhKaHfKhIXOOq7o-dKV%Q4tePwK;s2$x^EJG?%nsiFhY;(D;51gOp-WPV&_UGF%PP z^}4q)yuS)C3^eZ7h;Ch+O0OAdAWX_>Pc?r+6eYp&REg4<*!par3RE4g7V90QBIB$` zBeE#J3DxvoU7@K_!#+Jvc3wqVR2^XYEfM9*s`@IS3( z7=DZjeo}#2y=Q zhU7163G+PEKs^!i(NXnT^0BZ@p4p+(i7Vz58nCL8(-i$K;2Z$Ma|Xucs+}4Dy3{-NV-{xsf7x!Y2}8YG7ap{0Ifi+>>wA@D4?E)W|DzpFIZ@Eny1( z3@JYyY=QC4GPA`Dl;rKd>^+8kLALyWC2Ykw$>F90+30?vG*nOjA=FYbd#K~Iwzsze zJN>zjl3qK7@tR~Vh^~nM)O{!+`B2%Grppt>KztqYIETO;HT%zA3(xTVEh;;&zB;Rq zGfI8#7^KJ~1HmD5(8kwJU{dmeql{lBVB@oFWi%({YeX_&C@-kJO5RDs^OeR6>24y8 zD+1-Lv{_RUv%U(2Vqj9>&?Ud5l^|w01Tf6fY zc#zw3?iJ7F8nXl@=VZm77YyIGc<*5w&({!S4&BBKY&M=8dA>2Y`PBKhv481({9$3A z(pl1fCALOLBkscK?Rn!(P>|Z0vVMQyQs>5ioiPjyO3~qW0!I0^?DGN~ogtIaXL;tI zRAbx0z_g!^6)+Nkk%(p|0g&ReyjuwXrz9Z@(2(~oqxEz@bQZx^E5f2mKC25W}w}@uNCz&X5U^g=ov(fZp9PQ0H`0+SmmkDSJQEkV`leM%nz~Pzc7-CRe|DgGqni+y6DLYcmRnJvgCyRwRLs16P7?@oMmPHNEsp2nDgd5g$V!Z*T86PSoMv#h zj8!Rc$>~G$$ryoHs_{#H2B{7JvNJAE*xoi9-f;*_t9e~EYC;Het9VuEba4J{<8&2% zI>9TS3~!DJD;yy~v+)hb1UKb9yQ!p$E6r>fLUc3B9qmt`5_3q%ET61xs*5MIAHQ+@ zs|+*5h1i=g!`N%f-6pYi$o-AHMdy{&=VV#-fGyWbaRSnWakTo$(&{`tY|G=5BHBJ^1_Jzyl$wO+n%Gwa zZ#(lhX@#F@14xYpaUF_5{YK}pwDH!I^JTHymq{!JR_X2^}S9B(7o$k zi!f4>2EpY%kgVw;N!OoAJTAB8QlP9xeE7;i=G(v3s5K^Ht1uF#a2oEV5>&rHkj1)j zJQc^}bMTY=Rt7*a>%hTo0`;zTw8dT!K(T%=(CZi&h##i;(vkE)Lgxxof`m49iA`jABeQF=5%h()F(0MhbjqonPn8wMbtnQJ7{uoN={ve5N#L3Czze^P&g>}h*(GPo$ zHlPoqSag0v3lt!GPI-Bdj1dfpu)KxyH!YkvUQA-(;)B48fGgo8Wcss?4hkMrEbAW= z^D+{yZ@z<_yte<%^WgFKhI8@$WcP3qW>k~`QSus4d7^ZQ#OOq@ubM!@CWAFDMN6BL zs;H>w?e{k9`+zkT8v3wo%qjVO<6JuQSdTWUs0Q?J4Y234s4df=FVVaarn0%@rE-cT z#l=#klO0VNIZgKJAgS}hW(bxEwRO2B@B@-u3Y|Fn1o31-KV6p@%^B}RJq9UpQYO$p zfhnq+-5=YaL~rg+nbzYnp8`w2^)26g@{d1?edYrvuaB!Wv?^;PdjLi6*@&WF#0e~}6mNtF^& zF#6G%3M=!eW`)91)848vN_R%LsiHD|ZzXFh)?gd!s-dxLnfv#1nFp>pV=GWU9)bx= z2SfWNW~NdpVJtm4v*M=S7LJ&X&rZmZUw`7`YtXTgu$mMG@$k{u8u6G zJa_l5Wkhd0&*LuN$Ky6CdML($k9U={m2XQQ>8@^QZ!d2H5xA{iN}zC;Wo#^hUhs_C z7kE5iYkFX3`DLpHTL&xyY9FISDZMody`#P4v*ifS!1G=_oeqKP!x@gyrg$p)1WD~z zo}2ULG!3T}JCihdji{3gG=W0=bipPLjh($`q5?$B;HXdpfG=?3|2~5B*f2%ZFo6K6 zU9DgSDOfa!#pphO#4xTU z2ep}nd8vnc6bR7?t-QZke$Q)nMkqqzqY%I!_@_VkqSlKQ3g{a+R~-x`lgx75$<7zX z1ke$S8j#H9Y$}5~I8*}ZEcE?WS4vGAH>2M@QQxJ>JWI2u8LhtADQhEg*+_Nujz5_G znv|Fx2|U!N%)Va4;5S7zw1a)yAx>fROknDT-c! zO&?~hF0tgJQrfu`mSm`J{E#k0O}h*4VkSN?__atbUw`Qb3`1I%aDcYt&~*C>o<1c| zx)b8z=>P%f({d5XTB$n=``XrNdwRyV~%H^qEcKPD(Wp)Hih3 z^>)Y>i_N@RmpHZE%C7|f94NYHvhJw($KOC=muxQnQ3B{x_2upWVJ2&~dP`%zJCMo~L&_?XEsMP&a^q1#zK{J={!CJAXM{sWgWskHEt9E| z)i#=gCC4i*$4Vp7$udBm2R~n`l=S%z7MZe~CmrIcEK2eS)h@gB{fDFtHHd#l#eQ_59l2K;f^(= zf8LZ=BuM=ZkTZU_-Yv{~*PVMd|Ms~YUO5{?`VKpL`+G}D%Ud(G>N>%Whb5+^0&>`^EfBzZ2%#hOUcf|| ze#r4LOmU9QY=7zDa-05LzyVJ|6+nSLu)R|Yf>GO!XA8B%A=XFniJQNTQk}Q|rn~Lh zrZ5JHOwAAow=P{AZvm}g_%WAC_Kc3LDan9iU}S(psV{;z-yw0(DMVk5K`KOd>R+wk zVVQQ8khkt6{)u1Nrzb&ZkZfO=KpG3M>rahlV& zJcRxyD;VPfWdz{bxAr%2$F68&hD`AZ37>gQ5-gk-N8S}b|Y7ruI z1Za351mJ2dn>Gh`bTKqIW<~ji&g4?-u-svaNZ`MIKUhHyw*m;!=$be;rS|R7ZHpTj zr2Gg!&(%}G1R8Fy_dwq8Zl(g@l)*zi%lMhkgyR_>${S%K#KDLE4p_wHo~Z znjF;{{Nl}fKw%g(+AlA34+ZTJp3)vk^DA5qzKX_z}HCO2SS+m ztc=Ra2fi=d?oU?$ZN|L}4xucoxHM z*2CcTOU9rqH9JfAK$zZ0VVN;8aT>gUV{7m9+Y2oNTirxX{D_ve66kKt76;%APESwk zNqOCM%=%;t!w9_$N~Mww@iAQ|lBE*bL4VI{DITWw(7GY)v{Jy=LVCodJBv22HF0ynnlyL$A_u#H7l;8c(_HH%t8285!TA^J#h|*KnL~xp4Ug zjJpFYBVDHN*S|u$&db~Mpn9ELzYk%1f#Xj{9H@^p(&+3iyy+$0LD%_mVvP%YFwggT zzVJK`hEct7oOQ;^VqLdW6CI>z{fXTQv}iPib%(@TTjNe=#r_eo+9yr;)U}DE`av6# zUQO>z+XYW&y>m#XrxVp1J(6Z-%sF8|i!*2>sj&R-QVI=Xx&0X)D8ohKu*Nl3t=^U!dJbu<tHS+QKjy>tm6+ zFhwYs2TJ?BnUI$@yO#v2o&a{7l9LnltfcJ6G=UOvCTT1T$1O!AJ+xcKY-8vjUsV+h+f#swLDk;1y8qY1POgRbk$|Q1Bd=W7Dvl8#0qE z==jN<_C16@f6Mm0GR9B^Ap)VqYD@)k^xy`8sU3R=^bGOMJizwSK71lJv`+-J-iO1X+7I}wR)qNg_>h+WR<=9f&Y8tSU9_$Zan{#5sj?_c5YzMp@%&foF>45 zPd*p7;dEy2Fn++z4`{#NoK_DIcXBx=(`B~VYqW6cd3Yp)F9XH^sQ694PdXQcfvFTN z!Um6PJ`k{I)-HTQ2W13+S10Xw&BFJofPIlRzUQT|<9Pjw>VCl%kk24vN99{Y6iMwz zj=+`?bY{S_C2?|+(udHl7LYj@@H@-dD+hn_-}=18j+&|0fQ-{geU?=O$v9Ah0Z)Zk z{X6&{7`;Z@KUiV^SL2RdvVm%*;Hd|Q;0#hg=6DwM{>Lw%xy#=% zfA#tm-2KAfX8zRlpwrrXD(O}FU|bL`C>ptnN_j;y73?flzbWOhz5HyIz*L3uW@MB~ z_+$2}$jm>q@8O+@FJVV$K(p~3a%{Kv$AaQd$UAI5S2|*n>56c~=L9C9n*(>Z&6DZL z*{LQNBRFk=7JOh7^SV9XouEQ4kd2f**I#vRB5Tx4&Lvpa2d4&s{UFUqwsB6s;Prdr z75g$HHU2g#VG@m%Iy>OhR2c)S=-d&n$2LXHNShQwBK$G0cfBA1w3n!Z2&Jowd^LAF z`{- z5cZU9l<`l*hJJ10HfPIpUQU&OJ6|yv#Ua(0C_(DJKc1)ZS>|%n(6g-Pz%_m!W=zh5 z>J)I;RR9)CeBhEzM!;Mz9Q)m3m@%damm8E{QGLFZZTPe~Px3_nD&aVET3k zE`}e6nkwnfRB!UVs?gVsw}0_3kXpW|rlK1#vnawO)ZNaXseNRS644x!cN~Th83<~! zrN4QTmxIe9brfBKI95oz_bx!{Z=v`{lc8HRI(*K|x3~{j-^%-NvC6QKuqpmAgLS1- zkXXq|iTUct5MmD9Q>0M!yI+zoG7Nw2UG zR06nudxC>Wotsxz$t(Zbn9eMH8ZGoRw~tB7OCO73V3HN_GI;Ch;Mc7EP1@AV_#H;J zg@CUyU|_Z0sW=NXR>r0+Q(@9xSrXsH;K_ZU8Vm$>bXsSdA15{E+CEqvZvw4Ob-YDo z@EU*J{-Uj@!f)_qK;GB{tZ6#Me%gh5>!?r+fsA6(tgQbh3*J_3*TmB~m$2IRbA7UZ zI&jPgIP3=xm|`L#^tdp|r~!0oC~exDYdj@gQl{b+mimoVBE7$SNlls0^QVD+e?7L0 z&8Ycym`ZuvGnC(#{j__or$Y6IQ4EPNmir|mt&wKGQ?HmNH^KfwxIl8rM?N>$ zkUu&TWO)9hn5Xxop$cBG%{qex-GH1mMwk%BRb~L6=s0GSkvUq=0WlUp{kXX(yz%?A zTSX>h1qQ=&$2Y4Et9^MfTLsNJG1C|SqykU`qZF|Z9q;MH66nO;$fm$U_uUd1P^>bb zT5+uROyRVx5SssI!_H}={hO*lk!U9DeM)1~-(CnZB7DVFRsO3!nNxvq?TQW(O_>z? z-F)ry_738^ zfxp3=AU|K5KeAaHE0eqI4|={@6Y7qQ?LCJ1=@b8%CdsrNp&x@B@vQTaTunW>OwUmn z6$d6Gl7`1qJ2pRm3;#sKphiNWTI##S(5{*!60|ROw21~b!n5cXjbvjfs(_`IBZ9=R zMCYv-3ii?uD*OdOru}(7a*a$xjYZ>!y?g=ji61{{P7`NHP0vS)^&GG6w-jj(2e=A_ zwMlPc%Q)rmG-7{%w%A&HQeu0V-jkgIneLo6!pNulTjl{UlL2q-lKiu_bOLLLf&zk6 zOylAIPqAvU1lq#645p!J?_9e_UEe(AAb|GrB77}}+qn;uKyCx;XKk$#KY+AyP zhO6ZZ&!{tgQ1rUW;<+n*-6h9fbQX$$sOjzI?Yk|$*(xX*druF9*Tx4xQ_$wJhscnz zhm*BJ{6wPEZPxe{lB^MkU4C7EAR|Uf2!Dz#-;2Cx!vM;5ojYMG@Z~PgH+zFB-qIA< zZG+0ujC@#qz2M<9FgqdtOrHn8^=GZ;lf-6i&OjenYL13=zDh7CVS>%9K|?^8}_X>T%E+ z0OBeTmhLkEn&HWbi61#^U_FIV=}aG+^2kMj>U65_T_8I$YG_f-2gu`=gleD)9^wJ(7+<4d%cZf96{2Ux%!40E&ecu9XO z-?D=YZIofR@}c-bL}=Xq5fKz{=p;mzj9xO3o%3`0zF6D5 zT<*1^`rUmW>K_J~+WQXf0O?l1ikgvsd~dqsmz`Mh%0B}Gz)F|kbv_g?^ULA>;ZrgK zT9fE>vQ1AZCBRHT`XECOH;vmF9SXt^=DRXrRkvShZMSv|f3me7EJ;v?NdWyR#q_KA zl$7kj{lG}<;Sx^$YxRfeBFek~0Pu$3$*1(+JXf*)oIhZs*%ozQ6=3sOirFlz0WIOu z(J(;&q~(!4EutcrVxbg$2bpWOV-RVX)%I7{zq;M7zbw_0aNjxa>b;&l=2Nzx%}z0~ zmoa%sjP?~B^J^X+#Zs}LV{d3+(bCO)(e1Y&H z`;04>kojHE)h~*)4Vm>h9(YN zFP;`d*3QXE^)<_BFC7$$xw5)%Uh-mxiYwv*uAd%UoRkVn${42h))+~pFJ}F~*M`h{TPqWP>@h9V_Rs!wRAGNYoa!bM=2#J16aLMm?f(bunOwK70`}px2 zCCX1VwX2(y{kaYV5zAPqUWJjgR)zB4a>|3gP*m&V0YHQ5#DT-rV^g!Fzl)&i8fTy@ zpClNl?AO_FN%1MW5^inco#d@yhy0V%*(U${QHm4Fja&aV^c!!LweNA19D(cWaA}>G z<r|YykT$CqHdzpA{XS1hEwLu$tqNL&s!#-UM zslR24V%lxR(7ij-@|$~=#>Rm1h7LnSa)^QPA3c?IeM#=zTYNhX{y;(QnDl$d&EwIXYCWl+TkED<$aeQ?QaV%JM17ndWh%?0*qw&1F!=fd z&;Mls$daJtQ&p(oJ*<&MzTDj0FY}YMH{p1dGa-A`(PF}pOp>hevRN6%s3j*^CLHQ5 zW=?X8>J=5g*86vZ)z%PTcR}TFw@EC~HEi)v$`z?ZFj3a{_8r>!CR^C26;idWqj5KqnQc;i(EGrS2j0L#OZzERfZl-eYvS>E8NiLAj#gZ#r z5LB+w1G4?rY)|1kBK0|kl#MFcB;0<;`oWyJ&87Kkk~5AlwDMZO3~WzmSxYLQ<3%`z^sk zFzF$k%?d#*1lUVohV*13xrT^c@ zD{fV7J6T1rOP~*)0=+!b_Q4T6XK?S46~wWiS3y3rr03{6aJ3G>l78vshTfJy*-d*V z=P>S4s;Iq7Fgy#OaYD>?*-_DhRwDId%lrG`0K5k2B-1f`D6Je@h*F%C>aYgd)}teQ zFKx{-t6dfKzMq!k*oi(94DNDBsfE)S_LD=&6H2>34u_?gUuG7Y%2N zf0KDFMnFaItYKih;pAo67)QvkO%vU_BS+7&bc08^(u@v6{Zl$f zU(&e#Ge#$%ZM;oiZpU89a$EI0hbL{{oz4b=M)k8TNCq~9EE z2t7?Ag)Nbz{z)>i>KmW+J2rT)Io}bgvFXm*nBRbt-W}DHMk*3S!9jRWE&r7w?3PEG zwQNk_;OrDW!Mp6Z=X&q`1?!eL%1Ik5;_|cyK=it@J#O#&48h-! z@-+uQ-pLy)woJ5lqp{;&Nq&V=GP`FO9&FJpnTh7`c)_2tBl3I(^?Kp)Uf72EXW^(rhaoxCtK}RSw~jM6!0rze#UKR&#nD?(9Dnh?K6TK6PY5CAxVqN9Wvs! zd^0E9^WD3dMsr(RUCsoNrqVW&F%nBvw>RrrWwk*(X|~;W7)?DstLFquTPj?%K0ijN=AR(&&DJ{-kL z`LSw#u>LwlIF3RrAlHo{r^b<&F(CTDE==W<_2m=hUoT}!4#U&Fb5aqU4<5Zx@|Dw+ zR3MeyAVjA_EiL{E=jH)*-r3vPS}A7UC}HW`2GQ(tk=W(Blg%y269OU;x(N7Cdo`sOQFu4#{&_DiV(U~yJBPr%jN_$%Q3uY zWc_fK|Ao%scmKviiY0m+{Uo<-q8g3pUkb8}1$kd1qN}rhcO&nM`@Lio|Hi`FWMUV; z#KKkiJ66dSzw_XaK4U*#E1_;qu?+U7H!Cfs>=+~L39F8bjz zhr=7Z4@rk&;K?~=!#!y4rPNu;+xF1#phZpp^WoOoT7dOUKSj?GB>!c>7N9YCtc>y; zj^8A(?(%OZ{ePbSPL=&nJe_x6C&^R(lK?G_HDwbe(;f90_RQ~-*)>kd5)^)_rfbw& z;D>A-v-H^9TrAy57LHD7NeU$-+{-EeYQk+UgE z;2~2Kj^m8|_*E@w8bXKw^TEld_e!0+#XjF=^Y1ch zkrDEwWMueQsL5zmf9}$J40&_jg#~vu0m0{RVko0`Gm(g@`uly~7ala@idW;eJ7H3# ztkO~*x2HmKV%s=FW+AjyF={+gPXDIobpE95|2s|2EG_GHr*;3LHZuP;%ro-o&+Y0@ zGB1N{x{XGdyLj#lLBQ(_%r9V}{Q_Dyq+(ZHDOX*2^-hxPQjsC@xvh_dPM;dBSE#H* z%d3~_9iRHlm)>3)g82%OkGNZRR?(-}XWsxy2E^DpC<-)cJ5p{oQfz=zdI=6RyAMXT zu)x9uPvCdN;esti(uCGlnn!MjiYzOKf$!bC)bg7R-yBg|{G9-X<5YDP`wlCc zHXX~b>uYoICCwNtesQr z(A8s>jAgOLHV|L3`;9cE^BQFIhhX}ANsBeR(95!Crp+H>d9?|LBC{3I29l!6r0eq; zUR6AsE@QnHC(DHI|E{c{zZ5~arrIlDdvXQ|6N>tPwxSZhips`b4Bx3YUv%*ak7Ycx62(PHL+mUcvm#i!Ay~10>Q37k?=F$W#$ZyZrY9x8jsar5>DTlX zW0h4~s8jk786@_}>8Ud?hWue#3e7E45@RX&%$e+m;TGf!ljcynD#k{c+Q@e zkMCKK7n0zF*f}DS0W7~i0bi)kgOIS({$`%XQ!u|dL#RN3X=@tswtCP95gU4Bm|?w&phtIp)YHe<5L|u(}p#f z|83^kjp58tE!}|CtCI4V8C_EnG7`=LdX1@%5&ef2TwWzb=$av<1l~6Re+s#1$hLQA zh&u1f^u;~nijMbZPguseT9$ZmxV-c}Twa>s6f+|oCto~ja4@__$TdmpYMG5jj!95h zaN_C7N6AjiPb_9S#Wim~Eb^hv9b;b?@wJ4z)N9Uo#A^IvY5J@_@HdwGf!e9uGzEZ`uS=GkmJ zAn3p54D47YFlIz&AVnf&6{Pz{{0uA}vm2a8Af$s9%_D*J0+RhqU1R*$wuYf;jV@w} z3QXU<6(g@L@ZNI;WY;Y|TVHDm%$O(U$UA@b-lZ*L>Q>FNvwrCG&zB$^8v+7*#QsEL z$wyB{gndn!Dxzg=Ti@ zMCy=E68Ype?MAR4P#YiO5I_1N(6Q89X{k=62)lsL(0s6L18@r=ZRhG%|J`c;4ZU6? zSlXabBqOU1VYqD8nNEP%yad;<0=XUP)zL`SEd zw~lV>^t5yXHk;*qk1guo7S1h=1y=%>52iOeng8Xbs;=|q<(whlWJ&O{q*kr8H-BX}4m_{?+Y&g;yzds4Px1+1WI&u|>z^?QGB~aJ4_Mu_U^E=Y z6xvLiKX%^yl?``3WMGz0SzO$yEOjiBNgoCEx|GGCC*LNf=XANBEMdJ7X*o@C2~x@a zO6|3lTb*NX{L6Q%7M_E+q*UxX-ZnF)M^~2L4MC4Ki46>P=U0=MKsFK`)fomitMc?@ zm0`2~=?!~E1zR)^4@rt$BdTV(+wNw>mB$gz3R#WqUtUjm9sWqOS9kG zUMx!ir$RfZiIkL=H~+FVgj)|Ityx5rrfzr))%@)ZG8%`bmAo7a97ww0Uvo!{0k zG)5Va)`d-E>NvGw6a$jta)8ZG$;FVbZLS|v_eXh9972drvvhE8{9~17=8gOL;}@l1 z(CA_cQzyS8hP{v{L3Z8lTcGL7%}`8X3NUO_u(jY4<1zwFP8z9%B8xbWKf#DK$Y!w?YSw#Ew@iMLNBs2ZFiG6Hbp00Q4;1 zEp~hP6gA!I>5O3$5uAplVWIWZQm@c*va3Jswi@U~Wh45L8TiBa&(WoMLHcwa%c`}wmV@mwhivC;+xg#vFoNc7>)&WA1%?gB67cWZ^3 ztl*%s%M~yCLHZDMyKRQ!6E~hb88j)gis|_wlrd_?og_;r@;PMTd@V)S)-8pu)^ z9c;dzzJNY(U_7E0f*EBJYK#x4^HkaIlhQ`bBIKA=@eoM27eB}yC?45r*4khwnvAKu z+E2o)op#rBJ!X@p$cm!pXteQV2Xi%@t`^y&MkPZt%eC(Xx)MLmeKub~Zy5g}iOyFk zD(o|=+>A>qsqi$f*+?crgzq^^Fq%eeTno^Yh$(n|IdEz@3Du~XVZ(e2W?M&kHMC;~ z+3|!pIi~z$qfn(Le}Rj}{LFN$#(4hND&h~2SAj5Nz>t}H}1i|-O#5@{a&I#CXs7f8C*wyOJ%in&KmAAosNm-?@JSooOk z5D72@$JsIOY>_E)9dj(B?9G1bXyTuJf= zbdaY*4$ibzS? zCnua08G|`o@hFz=NKS0Zuug%Sq)yQHRj;{rD0ybcojhb*881%)VPv(Jg0ze3gzTO9 z=!haoSr~D=zF1VgtJmzb7bG}&1gu&j*kTH#0yh&RfaM8>`lA?{?car1vvJEvc0U7i zg(lW-3E|QDLFqs0M>0k&iYpsI@GzSQ@%4kAareRk9jJR^(@92!NYJ`R&+KU24L7g* zf3MwGm3}VJ*EIwgI7aRi9D=3i)@r)_lR`tQ6L-e}smFY2T}5y6!hK-lD}jPM|H>{m z*dX5MgaJ_qVEIUKuPnAtQxN!rP-bLaFHY+h2FlWkitfiWS7@j1+v$49men!L0$GxNtLbOZ z6uNKMtuMs=BSS0W4mtMuORmaFh)_Y#BPBav NoWEi6$L}Szw<9Gt$Op^UIx(R_m ziW(aS05RV87ip_ygL4umN)?G@e9mTH8%>ONbmLZ+b*aCySLfM3X4i?aQ3C}wLMW&i zi7F_C(t2dhD;K<_2N=@FSf7kUb&5p1_Eadxo#k_9-%(`ZZ+Yo=_Vbk zX|q@FE_wRz9fxL}XlZ%d;UV|2_`^=$JjwMusDi1_7ah;NFEF{PjjY6gt(PaKCsu-w z%weArnE~UiAWlU(RozjXgFPq6=xfpZ{JgYp89|F`9>&*rqQ>4rcH6~|+UQ0K;W0Sf z_PJ(CINd~m9>5uoLTVxllv-3nSaa1?kSp71=!}@T=m=g2WG9VPb#i-Nj5rltSpD6n zcI~(?A4G-QIy$J1UEWq!i;g80)r{!5y9XYv$(Iy2^qM%vz<&-0eT&1-K9g1m)^HoA z3t+byKYnLJUxf0HW33LGew+LlcpOh09;s?*>I!_HXH5}!4tL#zy7FHF*PPYjvT?He zDrG`GQ?2VXi$r85<*=SK>6lUZRP>b1R{mqk_u{3Os1-b|Gl9L@OLwP+U|OHEum0s; z&>j$i)rEQm^~x~efVc{S6fYe9W6mK_VH^cSe<@dh>!h2Oyll7JRfK+46gBeg8}539%Y=Y{GMbFqiL*R_ywz z3i9@0&a3f;*y&#ka>WuD&>JL>_8_SGFck7)Z6bWp7 z0E*h7S|ZS@COnVDLYHecU)QEgfa^>Dgy8fM5jl9wzmzvi0>AJ6*fBM-1&aUj5$M zprwcZ&0t)jd`hdeKoRB&MKmY8TSaB7TTJcoC)_{8H~=Gp#znhr4E+%)e47O9M5bwfLhf?qOHc#l%)!o*FZKd4@w z-0c1L7?U!mToyOm+C zU!l~t#gi{d1<$_K?7{p;sDTbAm0RdU64U4fv&mEUDD`Kq{*~4`kx8T2Jm!% z1cfqRQvddBu7UHb!=1he&&&aiq9#vyXu#b6v=VO2&*TUjA9=2%RzKX*;}*tk-WblF zp{D2cOTY|P$wfwd=i!$9tsAp9Ev-do5F4hVoez4#O7V3yaRV>QIoR~WB1y#p zqk~HFuyX}otOd#lNBn zbKdHB2)547C+BN`?YsKo_VC3yfNb>nd#tr)Ao(i03SLv=W6>`biN~&94S%~0v|Ssp z-W*{Sn9CeAvpUHdmdzr`AYCu{0mVx=2BMp3Gjj`Y3BnS8xM7*nNg<|W%xjW39`|c$ zTkd^f30Zfj+5S6`HDkd;@v!JiWF)MQm0Rw4h{1BXM1p~`>jw))6mcYs^=u96HeTlO z3+tOJb5Vtdc`c7j{#`0&{EHCj!`}QZL3_?OBOfI}b56C^pY*It+$VKl>!TJkY76Q( z{@XTSiAu#NjpfI

U*9Y7BMVqheOb07F+lm599I%opoCDao-DfCs=uT98oK*I;6#QC9(+&RhnWCImBPlniph1GCv+1&_R{2z-)`>Zq#&ggxVdoRSw5i9B+^2g z5x=%`-+YL$uE~>>G{{)KnWaI-f^B+7@QWKCc){Qf2ag=08v))=Ai}ca({MO(0CfwI zUbBQ!XfCOJLGUXo-Fv39$RAuJ<8%hq3(i2ZOJ1&~zQX>Pv4gbjnDDh-acNq_?}rC5 zGRv6g3O=!D3w%Ew%7ii%AgYo(*$cH6e$I8;UIlFrGa_)+fBlY(X34oz@bK*rSm*mS zhp*s>#TOTsixXagR#a?)Iq(6obbnXLmW$L2$;RonhTC7@k4;RL=N7~iq2;wx6}eQr z&jV~T^^FBptTGHi>O#HD{feW}o$0nhGVKhpYT|)YPVw}NA1Z~`c6Oqke+;LBNY+`GiytG|B5 zku20&?>N)$dHIj_pn=~qdpZzUY7N}Y z&{(V#kx*JZdnAxnBtCyp)xET_cl+hEe(yStxFa3sy}*rzMeXsk8d#e`(?#Gb&8J2q z36f~Z=gq<2r)rvP2d;e#Y;k0SbDwa_J))E&FsewrJDYVjTnnn@>q|?A6tOJKvtV`F zE0h-ZQ0#kS3*l3SiJO_3?SrH=K;t+IbY?;yzN*ZF7A{EoZ@_eHb-gXJd&V12IGHQu z=l$ z>7)pyt)@sUt{%;t{r9_v%X(XRoG9=WqXOwO2%+@+IgPa-6aE8GFH73xcD;1PMo%B~ zxl5+zWMT>mXA4N&%y1meYL5kgVzX6K>owXU^jx+c0=cuV_1YL{{ zi~_OhMM7OU81jk&A~)#EgiXp^5j#1hw%QiRk*uXrnb|>AUesFtx}fB*Mw;iy+Sg0Z zZ+)S1H>w7lYE-6V7PBGrzk#T8xl3K6dvSHCd1m?h94pt~p=z&0RelQv(4Q1yET^UVGl~!;yDvY-~1l>g?~@ zn@&L101o0aTJFEA@rp;I=Umq6=9)O9$7(>qU3Jw>7Np)-Z+vh|)ah)gW(r=nIyxLB z6=PZYzukztzJw(Kux40JL)cypM9U4^8EmL?Qic95J$ynw;H=3?71s3^RF)AzB~Y-R zeye}%^8LQs_hxM6=1r0?&u`$s;(JtS1*R5;EF8gxb-}7h#x;@o|FQsfe8~|FpFKP} ztD8H0&y5oz^(mved=Ow<7Wd0oy8zmX>M=6*|8ez}QBg*1*tQ@bAt}<`B_)yrNW&l? z-3ZcxlF}gvA~hfkUD6`m4U$85h%^Jz-TiK#=Y7`tzV{D{Kfo+z?)%<*U*~xo=%@0z zbfQC&;zLJIrN39pvj?wxUbLt+&damQRnDaP3nAQwUlZCPa>Hzs!L-W*G$#Qhf!{N| zvbwr!P-xL;?Zw&k112T@;f$imcaV#v&lfHI`I5KnI=Z?}#&YVb_WMoRYs)nTuky$1 zy{=p`uBoaGBKcqGrl%U9^Vs>(w>z8NNz2;Ole!o;<8pvD)1qf|nV_g+*(_t(6lgxy z0KAH{kAHm>L4#s`@$1o^8Q9vW`EF^FJxoVFPkM#f5pC^vAOp&bZ?5ur_$hG7BQai8 z1{D{pfF!S}jeuQ{`cv(bT?cV#b(_2Ej63&|<}1%+yh%KKe4zTh@OnsEUstras9 zzf;Q?$Z}jpi(+GAr}x4!4S1w*a>hyTMG7q>&W8D4g5LVwwPd%Wt85HRv69by-Z!-U zm90C)4z2yTiR}tnV8@z&$4MU_JdKjHHC$%pagcIXwi0=2WNr-Me zr_n|qIj#G$?fGgfDEp2cX%Y51#(=T=)Y$K0r_!ca-^9>LG!4iOtir5B?(H2iqGW&9 z%At0XLG8*mJf*6uYbw00xKHk?M;cy=;E_D1%!X1GfM7qGN!;_|*Fh$V8^LwLuQB_K z%yB-m8iQ*(ZFExri!mx~p7KKVrMoRU_U9y)3wcc!bi32&_^KigZo@+371gxU58*we zdT9*yO2l$ixfz3b;OM0w_Xra7+R5~joS*5om`!GJ;cMu2k3Z9|9wZD zm#e_9PJ8_uG2?0X$PS%VQ1zfZ%I|TSo!?D%1}{w%dw*)L#jE5zVOan5-W45c*Y)B# z3P>D0lDt3>6B8O~$k7SkJO`+SUf*+HszrP!Dtv`{?Q1-StRM0OXcvB8|6v%ES{L)@ zKLEV~s82R}Ze)gdfY#usrxewTnP#V7%YGU1#i87fZx=pA`K(G9O|JnF`pf#5j%;6n z_-!TX#C$vI;yoJor5j@Mm8%bhP6JX)tZFtF0_Qw<&&JG>3?RFJlQ9g1%@wa;) zXI9dmG^MKx!)iws>`Qjc#ID!fj6G%P2>Ml8UhA%yKM7iKMr%k8QZ+9yyCx(GmDW>I zC*DsS<|1wdqX=$<^kL&K)Ygy9es??bSr^oi@>K@Km(pyHWdO=sKmJ*F`C?$r-1aGE z2Lb3DA`@FdhoOtC10eIVmp!I1taLPwHFj#RrS#)FonFOgg_lBj*p32^*B#6RDDE3) zqxW?M6+F|&-&OzB8Sd80V$0&{pW!48TSQ+d)?@Sg@3i@%c3CL%;ua{HJJ*ZblYfGUd&l!wCMeqFsLP28GTdPx){pb_{xkZ?p}NOFufrmJKvNL!4jP%o@%*}C;edqPFd!;?)xE2;g@ zitwI2_f}=A|I6luU&kC`HuQ@NIL^lIAIOah5jjeNx;(T`o+FO6*_kEpH-`^>TQyQY zH~?nhpri2W(D_{3zVDIdoZBITXL{_K$gt!+1myjs?Nr?BHCX1a+q}te5oC57_!u_E z74_9h>VH9<-qC37X>D?GSm#a&7=Hor#suXHn7lY-xa$-$#>MC;6W_>rg6HkC@2z&& z*0^tG?n{k0wW*yIFvK;QF09ax%^Eb5ebuyef0$3B0W!1 zqAI5JGfAc|Zb&7EjcI*&bjZLwU2j$|+oTkX50Hn6Ym=5O2VFdldw*S+dg0ZlF95N9 zf|*q<^_LT~)3fiA!a3CwFGb?(NXBSSv81C$>l6x}2lg;x8lB;}3430lA(b+0Md^Ra zy~<}dFpQ`{lTu74j*C?{c}=`FuytA23`N^|&s<6{(D5d!qbv%)^VR(I(7LoDS7612 zMGf6Ic9Auo$h_)w{b!sJ1yi1u`fpwJ*{6>CptaN6PrB7}P2~m@nFrNd)k>$=mkxe7 zhsDJ09)MZaHy&*h7Oh~Sz}op_4sYbvXtMd+-&$KfTwv*7=HF9Y=ulBxI~+G%Qr6r! zNaPSl?gazAI4}JjM#@Vi#!P z^MIjFcTwY$)9yr5(=f!MA_yb$LQKI$LF7ePaz;)KV`E{j8F11H&`P!yv;>pBk|^Xf z-PeNZKND7NwH@{FWJ^vd6!H`vd(WRlz5!;U{|PV;_V-@x|a-o)8%zF{(N5-FQw-7hc;E$b#Se z#KEKyMJGUu?gi#&f-mxwux#S={mf@oVu1dDr3c7pU5W38S%$Gud4P;5VLt7BA0*!- zO5fleJyQhBld>4j(w6RpGl_O62++|f<*|P@i(0NjqyWDcG{nsgi>K#xmMMg-?x^qM zKcFf+h>k;8v`H$z8n!P_b?Rp0PSNDIMv<0l`6rD+d5~bSGF76od-)D;c2-Ewct(~K zbvX3!Rx}-%1(#Ebgi}mAy@rMCYk$N2V*rYErx2*|Qw>b|5ya&(B6Oym?lqHAuZlJI zz#shqN8Z)hC`g~N`+{8ZU$z1Q`K-V3J46Z`Mw?4R_7}MXlS8r9{~afs{=egd!Q)h~ z<{=LVXi0;LGYknxdL`T3{CDte9n13f{ z5SLb-CXQgwN`Q91cZL)Oxl-ViGhsJ*$|ei;##HMG&SiIT65v5}FH%nT|9L7%-LxF7 z6gC~qMJeTP4v^@)wwnMOs#FP=uw0#3rX--xj`%ksh9QMtfm*(VzA#{Iy?7l@v3S05 zetm3Y%)Vw+?C#?)ri1=P{UyN#+)`dWM<6AxZ|I{;Sd*+>0I>w>quf;TO&n>1Ut0CK zpI$uOG=gjAZIw+UT*O`Vvs}Vui4+LO|HV&^#)kbtIkv7OY6zF;5%a{WG*-6bRLGzs z6>Z@Qb)$SXXrG38aS|d{@%xNTd3}x2z0I%BZ?5=z1=enY4KF$*Z)613KJZcCezik^ zV(I8605?W16~-+}3G$n2{saY|Y3Mt8SoZIk=74oCVoUjrN5W7(vJ<88A_h*3hf~vn z8>iP*e{f?2l47~^y^1Pa>o<2)9$!6dn70J8wm-_xj=0QYA`Zn#1D47i{8Qp4pAOBt zK6lb%de+qF3{|cjBINe(of01tDJ+#yho2n{R#( zP9K{=?ZmmZ|L#u0HeO>@1h$@K)axN?;hC%KucfaN#ljf<9scXoc*1^{Aq`sH&}cZL zB-Ro>g@M409z(&&B#q8tZ&`0EqC@4hs)xUoKvX`rEO|M=)t^-Odp#uXdEh~!4IGob zoCpfV){KdX?N1GS+Y;hg^f#_T<7WfZEK&;d>&+(!PtOs2(?YtkzB8`Bw4$jga7vrL z+d|Y*m||3HD*z6tT_6$MZv!cr`f8xtMbami(9l=D=Fw_VIN(4wl;}ozbMYq=Aje^6NPOedamMJmUPxp z%WjRv$ZTS8h~)cMVBD!aa@)b|nXAEWl6m~E#H1`wovOE1Xm!rSHsM5Jzi=IM!(Y^B zT=s2UX;019FnC)}kI`_F2NxXq;Y6-`Y45owYh6yr^#T!@DnSsKH$jF=dwg&-v~*Uw z;R0KP)jf!|6=<8uJKFy9qQwGH-d&bc+t&Wanp;Y{7}!$ zqwNSB8C&#{ZLQr2Y$oi-aJkT`7_Q#>%{&)it~droS-+$4jEags%wJ`4wEl4%M{Rx; z*QTwP)vCGYc7V7`#}t=glO)-b3&NBX)&nE_2uldXcPhDp!5uL|HgWCBwxl zoi%=zwI&bxForQEIVCBAFCgUfEr*@we#KHpM;9cbX^>;Pq~tJ+&eKGJes*UW;^~4( zid8xJc(p_Eg!~MjIkF_mK2 zyUE_2vh>e$2aq02hR_1(D<1widl;1PzB1z;z7_|V_p4{KJkD>C05wE#!3_2_uN0Vt zG8*GHJvv=@AYC&qg&qOn)e=ha=CY~|9-S%EZkuj8!Y+RW3=$r*`UY`{xF2J2&wGBm z-@d;S!#lf99P4s<3qi<*5%r_J&xbQBu4Piu8tdqcND(ZtwK0(|i>g}sI25|^L?lKg zXsa0*n^;?~W0W{!%Fq_$)-L){jx$M_{tdNiC(C)NxSW*}&UpXkY@x_723aPLqZ%SvRn3X=P#x2bSB@D<+i+v8{?->Q|<$9P4BT=FMILhnLRiArgId((Sf*U z8;Z+A6@mvS0$)CyIR4c%A0k{1DROB*L1`jpR~OK0)Gg`jlZZ=-BTRZqD0a3W0TmU7 z(odYO@6By_!bJWinu9MF#bB2So(=FL$6s=^Lq2J-R=1rL*r=~#SrMt*6YIRkv}Wm z^f)*;&l@LGA;XF>iSpU1`XnJiT4WOdBQ=P&$TPBr_6k;oou-uYVdW1EjqlbSf0X|^ zc|}1RF-CCL7QBdzKG%{+*R#>=wK;?gDT30@(fv8d!eHc`Ya;9kgCqm?_MGqeJSMYx zUsv1<`%T7(sP_CG=sUBtP2s#ro27zi2cKQaS6?)#mgyn@wFcBC^#4|6vBcg6{nNTe zp4Zf$?ug$U(%v$+keU^D;Zv>H%f{n|GK4VEn1`n(lP-JH$lDZU_x6EML5RV|nC(O_ zl6_a6+8Ds<0trai>3IO2sF(h%bxj+1sX( zE=-jeRa=2~WQHqVVM_cgKQ4t^I&q1A#1s|TXDP(;^%ZQn5KKAVJ_wSgRE{TQL*#-= zRG@sbalr``#lRFAImrwQVoC#UwPYeDvP?qgr;6uY`Q5*X%wDu7CoNaXVS6{Lu|RXm zgo%upxUortrL(H#!%-;%3*z8@QtSdS*Vh#cO@RE29WYA4jy67;`0MngCgB3KytYy; zT{pf3lt;NcZo$Epxxc?+e)A_{l(A5c^OdIy^&X*z7GVz{(_P>2@~YrT-R`JC=+o+$ zT$bsXXo_|O@=KVHf~D8v;(lfuVH;-|h3w8h0}L**a5x@^bB{_GFUcDWViC;Ex8F7P zNJY5uJn6}zTzKPuJyp~n`w;^741nWR|L79vC1Yi5>XFm@{xN`Cif~B`cgrN!O)Fnf zv%&&8@$~=_l5w+&D5BA4QDvFv04U2gJtJl(IGUL{tdnD;ed!C0wBBn}#>c_zJv}2Z z6x~mn`p!6F?kg_*26#Z^D&tBN2eifq&b)W{QRsM*&o z!lWVf0H&cQEVhBzz7|WPZ;Y+nA*=Nncksd#?2B3`I_aXCv`SLYO0-1fD( zH%Mrq<=17x8#4#*P8;vA9_AV0<-S~;rrWdO-wUm;*qs*|YuZvA-Ylop3X<8Yd7huv z*5CX^7c4bu+oI|tO3U@o;9H<{zMJz*_r5|88(6y5o|_OqpO4i3(zw@3t^K5P<`XUC zQrK2w#)%U5)F4(sL3Y&g@=&| z1Tv_Ae_IIc9VC67Hw|W6Yv=*%5NbWdeHRcF{pCAGhXoEIVeb6bt%aw)3g#G)%6i6I z#Ecf4@&+pqiYX#BqbM*7oP0ahX<9PcnQoRs)EIKYkza&AbWU}XvHKK-+6ofui_!xk z`7ooJa(pA=a!81yannltyP{@aQ70iyrlA66@Dz!zh@No_3*(qY5Ym84MC!-y`B^i5 zRjeiwICsFb)VjoBPc(wW%qWm<75{z-|2OrAU9mCsPuYZ7TJn7dOJu$;1i4i2tnD@TmGb#dQ?po;!Uzl9Ib+b z_p)@`b%L_CAy&jOonl2L0H#H+^eE^>s34XB0xp`%_9Uo?B@?g_sjT&O&B8wQDr&}? zDu?rCH9T1lTLe!C5A%|XG;`QuedC?uE;8%l6cQy2!=Fs|Os5^HN|WrDxcexgMC1cT zD^IG}^^HZK`Xo6@ux*dZqAdK5)0-SHn>LQxbPd}EZ3sjh=Re=%cdqa^+gy>OA)nQu z>=j%cWHK>1T-@9=R+7F|E43P&hHYk6G2geo>dronqc(`kwG5KgmoepsWb>_DJ>CYd z>AcP8Q0%`C8lI5Fpq2A_g`wjGZ{4r45z7{`scM_gKI)0r^!@pRjTzag^^?-v8d{t5 z00D(N9*AcwJH8~t=yYm7J7f9R%J_Kbn;@V<7R3st83brR6fuQSfEIfQ!V#ew64~mn zil=gBb_fvUV9Tv(ROc8VU)h%CzMxc01E9PqhSQks4XW)`eHErV~HQJknMC*Cl? zp2R5it+W#jOB{3E?x9L6^=W95hz#oB47)4E5-ZeIZ9R*zH6pLWeq5;5i zTCZ@f_I9Rn$f4ht{h+#*j=Q^m%>lRkUO=v}$p+wgdk2S6djYV&?hh|y8b`CU5-HI+ z*f3vQK2gaBFg&Ybr42a?r#2hmwTbfBoqhaK%g}94$bEaIfZ@k1gI{;18Ix<;MS^su z{7EBw0-;E(fb~qO1c6?#UebX~XRr@DLp4YCK9Z|^!NgkhKf+R_F7-Al*)AC53v1Vg@4WU0A@)F?tu|){M}-UoQ0dJD!n}M6V1hE?xHIwoPBU z6**0Vm#m>5r$k3)J zF3z%k#Kx9gTh(4;g})^Ad+tl6Eb{jMuvDBX_^G0bHf!DVs60tuniK$fnfQNOR_2cMQ zp}m9Qytk#(Z|jd#as+4=p0HEm(YMWgd(;*^()2kB1|&;T1Py2g>Q)qm5coa{x@D5a z>gFq7uAT}adL}4V4l3dsnH@XMXJnA8s5l&6Wk4wP08^#l#lLKerL}d!X|^2*LuD4V z9~)iWcFkBkbJoX24TzW4Le+>X>B5zvUDa_6BbA0C%6o@KD z>R@UFK~)sgFdBVE70q=2J5OK&RB4zOP|i-+ zy&uZ(PpS~OXlZwPCie|AIs!<`%IZL!9a#Rrm4Cp}AvLhIMYv)?JA8bgMQyCt$Dn{E zMLZ$mxy2OQOVd}}O*LNSJVX}Ba#5ldpJ1W?q8ADcK(d8Zd}nh827xr4gi%u{*%Vti zhr~lvu<@05hC?LCS61@+#(?-`$oNU=}t?O^AhIAO*uX{G@2|_ZVGV7Ri))pS891uUvPYu{SnmK`4f6Im4m< zo)dNWDgXV(xN#eQT7tXN!E!ejFRtYgiCswAh=@d9;##T*w`GB~n@1QICx>BbM=I+f zVgE;K(@@c+wH@j#r?rx$NT z#_jur$<_Z*Awt$B(P5>u#eY6eY5BlQoS#&e?_V1$uLLE$xnsw{@g*T8wXIE2WUmLD zEd$DS-ela)DbR__X2U*e`mSR~;PE1iilQ3NjEs*W(sOH*mM|#nn)U*%*)L6g+*}?PfQd$kDMo9&``~!M^2zq!jRXU#27;T7+aNvQ_7eZY=$z*l+R;ZoS=ZMaBVX zs@naE+Qo6}jd@m{LZNYo6K*bhZzUBo>X{&`YqA3Q4)M*#qxJgpp+%(K{i$K9h;JC3 zBe_cV&fe~lES@^!OAe)CQ#q2D|78JmSgF@1ZZLY;mK&pdqQv&!sr9X*@5n`B4L4Rf2@mOR!lrtZ2UxMw56XwjH-l1+ zL=>QIpR6dKG>F5f#JfSu9Ja4X@lZO8s+NHd4E|}n10}DJlFKVy?ypPQPqlOHhrnH$ zU+L`-P*{V@>D?ekp@I&G#RyP*jF^1-?JR&Tk@C9f(d`nx3#nH|_0gmF&-aoS1Cg^1 z5P3N?|BG_}(Q>>qJA9UE=QO&%uOD!g{n0x6MfBPfo=c3LG}PNyRN))+U3U(mDT=d4VtRIXyFd2p zw`l-ozc(pm*csqUg*~@~`}>s@3w}OcT*jm)PA6URjB_3%6R*r5QDn9zpNX@qh(;}? z84>?uZtWe?faMseOg5F2$7f&*8J5b6W=7ZXQdBVO={X7t4o3d~@v&Q`nm`b)8W<3r}7UN6hui1h;8GMA~YbhZfR*7#~@?@=3%22nXN$@ z*y4qf(nA&S$byo}ay|3H6RYK=A+4c4#hf@T`d=$vxKF2Jp(r^X{;gWrR^}qwA|Kv= z-~|}aYQu{bf8o%^iv4)vskioW9LkwL`5vqhT@dc7Cg?P(WY6S{ZjNo8*;a`K4GLE4 zBv|FEP3(?uoD{fw30&h;U4^3!lCnMsMV@bQ|(0aag0ID z61Qu+mjJ(q*mH(eX`em*`ITJVWw!~O=1 zAw`FZG+kb$L@1bN(Y4#itUiiRcoJhPUAmY%8~%HKfdyO4=d{%?R&CCSR!&{Rf_#dE zX_I(b6W*{IUuliS5Jh`;@Te$5Pr>eB{_BU*;h{ZlsT@7Y>VbBRs1NQ**6H5qj0#Z< zLHIQRNcoFQY2oBT%7lZ5Qnlme$UlNGXOH#Wa7^On1ypHaQzo2S32!lP;SZmX7ee^4?%Ex8xeJQoY6WYkUsXIh8!jj_+R1cLr(VZBX8THbGziO zZt>C?L9kf&()4K_8lVt-rl6~@Deql7FL6Bm!-ANK;!EqMW5&TzZn_@QUMcS%olL3o zI3$`k`P`KFmfc2R8X$1ywwPuwrkKZGQraIoW6SE1qV|Twl$B zmX$j_`)9trzKR|pCLG6a)ik&yz0q0qW{3}gpmAAohl%*D?_G6NN8$Wi>{5m#Ow|B1vjVyS)G;V_%__G_~FBo+_=?0LJ7ix7x?clsvR7!CI*}Cj)m&3OVk`!dx%V!$kakW zy{vIuDlv?$!OikBqV-(Z`a=UcA7!?v@9`ie{STonviF!bWqlv15EFr-P+=b=<>G3< zHEqt!yA`&C%G&w9zuhdmswrG5qq$a2nZva$$C#{Y896hy&Nr)0AS)dqrx8V=#|hHI z{#R3y&acjH~o;qqbFfLjiI-QR#E2{Kmq} zj1X~H=dsDqY?9&Nf32>XCK1Y~E$>Wlk>lB2&bTdG{k1C>z3JB)ZR?%3P88SpwtLUV zfNk%IU*9-s00YrZhKEo8_{zv)QZKzR(!t4|2HRsEI+E z7c=*3_$(?UPz)b?tk2hi98lLWq|Zpu`EhCc~br!IB7 zbcAH4Qlu}%AuWAGwNwe1B*3UV=Cc*XFSL~ zs*vfZVm%@s@{A88VA4mC&V(E4TNQ>0I8=+dHi%#K_n(j^=;;}lIjvzfuRZlrEB*k{nPIKJ!rv&VXJjy(8oXqw? z=8tI#Os0;uucU88qt?-@lBu_jP&lJ;8BuoOdXfe=0#-b} zc@_;F-KrtPEO~DaZufY)Jo^W|*ZaskLl~jpQ>hJ*X4KacZgsM)bjBHDIOkfrpTR*CTi0o;!Rimm7lOCUUw=y5A-+Cev z2^0BuQ*U)~zg_;5`kw4zd79JPq8Kozs2y$YI6Bn(@qF9Sc_XuMnD$ zVGy$dBy9~PqhU}MW{hh;r7DVtT=hHw?V50~KoMY7Eq>b>#6(+GTN|*>X~f$3amym~ zt%EhRcxrXGc40*<$|sGB`l$7$^!~{<>y)0JN#3HNmAiWoF@3Bpj4#H)@0M1?%ObQQ z(Rr4d^{_d@&_S{<_uLO^%}!UtCsp~Sot~PcXCU|Q#AYpN{pAVyf$7hDy+w^aRC@I5 zl*sRN&+oM{qpXiY2*t#3+Ja*rt z-OZX0x|2>T-hDN7Fchx! zC`%n`#wM%ujvpI)r-<6~JGI~9IRxSlg1@7Vvhlzixcjd?2VUsEDPFrlH67v3w7 zM>6TTz9I)1wzTv9tU*ea&1aAeUwY#17swkCJtnpNw#HbUBpEVX@4Uv*od^x!U`}5* zv$k-EVX`qMLX*IkxS#{jc24lFig@r8QXRnyvRa0*^xK3Y8e zF`WW{f1KNP+f9d8=-t_TgF4}U4k*Je*2vBphHk5=VdJ$vLhe7KH zi*^nEXVv&^iE!-BKUGWu(6*6+6SC@q%B}!J=q`c>4o%`nvF?;rmY} z4KAuh{hFop9G0gIFHTv^DrH9Ovng=r@CYkTJH8n3fK ztDigbhRMFx=7hwC=j>a$GJzbBxHud6NOs~&2l9fq*kG4M{~LcKE8Vm7{kOsN{m;iB zUFQ$s`H9_64Ce7l_P-^dS9?VYD-md&k8B+gQk-H0&>sFak2;)D^9LWUSCGhmYOCp8 zO*s1X^>ym~rdqx8C3bCUbDT+Ie>LZ{V~(=;&*wBMp4)@99&2m5^_wT;c}@d^`NI{p z&*@>Tb6#fx`hqK6E|M$<;zQ#8>1(-2J!)Vn^U4m5PHvi05cwjX9XfR|cf77I?)-TA zlCRlif@s5dUNWz#Wpp{@U1A=$7f_ZWfUYJbL;ffkb$expo^p0nB?Ylxwjs87&^)mg&}6B|VcH_e4AP zmawZE5FP#pyroSyB=^&A?ny}+m8-U?8WX~)AT#j@N45U9B(@C>`hAU5jhGEht0X2mu}eQUG>+0=Di$~(qVh!q%Lo*no5VJLkx92km?`cKPMIwGxSK8 ziMO)R1ZdyUZ=E7$1cV5z7F`v;u=XvobrY`uLx;xT+%6pF(`OvXn~Cw!XiB+;yJUucv#15dyK)hB`4Qocz$(=q6W) zN;UQ8l~)XbJi8plPhY9lH9>+s7#MZb)YdpXjB36$22W%ss#q2gPMktnKiPDPxHZ<- zh0~kor1~aCR{Wv8&m)QOV%xr2XZV4mAj^2&cqddj4JKDo1L1UOjz?(;8&qX9CC=>q zF;?O^T!0FaJAf-^_Vpbha`S6*^Lrhg1YUWUUE=9u57LjCyoIes$SZgPfzky z&B|BxRZWPA8@^Bd$o|;tGOWFR(!;p;*QNDbWN6L{2h@EDt}ZeWXA5}EehFj5uaN8j zO*j3qtljx$fV@UXkXJ|3VS=sy#uw>H`(nubQxt=#BsT4fGyk-K+b*49p_oD1Y6nh^ z4r_Y+KY6Ik6I_q!MxWWl}?Il%C}4^W{$l_%qnayx>P zpN4t7h8{3&q% zEZgLxDMN?hl{|}FfhjM+Ap`ckpG6u8K(oOV&dEvK&{=r>xF4%om6Rv0svQq}q69zp zCIUkA3z$w_doFKaQIDT?~}-e;hgYZrxdjqT_9&8a(5Su=?jkDisQ5YguRNl z3wm8w5>gfj>3<0|8b)A)vAp6VPU;9}>r$F2CtjE`J#p@9vI5?*Hp~D*Y^q08_>9a3 zqL_$>2pJruP+8?*?J$FE6H97C?`Cd}P~yO`KYbr`vD(WRJi-~6IiI60W>4>fXj=H| zK!fZd8%PeDi;3T5KKKumvZ!N*Za37yWRfkwIL2{n!Zr_y1yE52#q!_Qh#O=XoWv8x zf!X43eC5vGPK+h69`@%rec|*yDl)Ba9Vo9hSETpYyur!Q@8bm6C38F0pA|2Xt+KmU zR)8f<0judN$h61&6O#i*a#{H)4Gs=<1%pJ@f{C$ywuwWG6<>IG_|AURp>K!|!i=Aq zmxe{peDkyc(}?1fTg_+xdd_c_+^yEVV0s%gZIRx@DTSyfXz&!sE47^BAZZ>vs3sVkT=$KQ>< zd*QLYTdOBh5w;&pEa#LcSDgB@l^huG5Yy~^F%?`OnF%?cJFZLbU%2CL?07ab=NGuf zh@1NIdHSp9c6wzrR@J$IzHgQlK8nrnfxMO!aGcq$uOFVd5dn5h|8{AU6tTRvi9>;{ z;4HBxIPx0VeE|-a#`uJ3$R2|zBYTl~;7j9>kajceoEu?Hk zLu*xub8~SynVI^B7Xgv_@(rm%V(b6OK>ho2r(%H+IW~O=8HZlM!cJfG$k9#PGtHO97p#Mz!&O9CjMAh}y zfBykHe?Y&)oEAdM{66}aH;?JD-G#}+MLT|KN~3(KrP`6)EG}GN%!@)A+&qxDP4Z^{ z7{-UOcn*4kaf9XrylJX{ssX@$HMO<>#vPyAmJV);t1nvKdY==i{vdyR1{8G~QCFCh z{BvsLJ5d2KUNYrXde#DStKj~a8o1)gNtZ;rId4Jwof^poO8t|JDi|B03n1qDnx0icJ{@td&iPwpx ziN}tdYEk-%X2w17PsXG#jP{0%+ktkvLQ3b(b9HS`qHZ2%Qr4M#S&zaD3>>|KkHW(3 zbiZ{Y)JfRQ8>ln7Ofn#o_V0IM@|pFGz8}YAb1FDeMS&L2eaf)!9(@j6fFe=`eTUMa zsSSj1L2sn?a`oXkBXtPRZEr%^*ouNg-xJxv=vtl@8G=iA-uDp^>9&FtHEr2yPS4Y| zgbi-jL+Pm7(Yuh^`444ocXB!VAv3)GS_}J+v^zptcPjmc+R7y^?&LN0yVtUb5keea z9JDyIna0$=uiA?iiC5v=Ev-9f(Ii+Z>BkGhK2IepCvZEh^*ud;So{0?yV2H>nfDww zF+9zcg+5|WJ13lnAsv_7DS;X%9CCZ2=5cpvEpk3idO2fPT2bB{OnDJ>O3~*MIu5^G zjxJ(jtCAPS7CKN*S1wV;&IX^0kZEbVNI?vQOK29ylbe@t7ss^z3P_dcRKt}Iku^{) zg34muuYc>(%j5NbicGRdFlmV--`t_IiXEgzFg|_}6NFHvM9G4S?gsowQ90&nXZQW$7dfFu%m z2pr(TFwNaJ2^O}mzU5;UmhKO$V{Q&$8V8evQAvG34~~Yn=Mv!Qu;(C6gTD)4JVO(n zJR?#J3v4%V<|-In)jKfKBBL{kD(XpM;d6@D`KS@-iq@yern?eMQ?ma$F;EGTCx9`0 z-utn4%}&<|HPjJp+_kU$2vx`6Lo-qb7!;L=(!I9WW0;l!w=)Mw37@d)>Fs1v^_~rp zyt%)c1}h2q>}0g@54AHhGmOK~KgHbPx6DUXOV;ae+MK8wit%8sU~Lcg?0)Z_nl*`+ z2xEPG#v;)1)Mz$yRssrn#w*yt`&ZfjhWwpM+uteXt7bXD61?8GQUy39@yTR)5v+!E z{PNkpI`L8bGzNJxQNKi>g?^|?pFyUE^sj&@```tzaXeB% zt#ZVeKIw02{iY6udU$rBT@}SMA4LA_W_fdUKd7CJ8fYfQv=i3_gp;7N$>`@9wH$Fv z5&YXA11&$3WuilW>?>)Xzaw0nuB^O&r7=mflACx zko1A=pRM;Mi^1Q{>D@krmt_rpvE78!fcEd2I1*FCPLtBoRd1iy@itoQHPq8 zg#VXE9XNCd_E%w^kW$!QG+kIoeR-*fCiRK$pGyc-af@|8+IW1EIF}gO0Q#(zGZv5% ziUTkxTL!9X(5|P7=>j_x2NWlQ$`_g!cgkpG&+}_2F(>?I3d`b*XP57+m`d8DI5gA3 zHNUl{uhYwfEPv<*t@L~AyEFf5u|K;KUiNKw6bNgee;d@Qx^(CSG1V8>JnqR zFx7!-SWZu6731Oq@E(!vJiYjk;(u{nI=)S_mKj2mHEwH078@sn$rY;ohEW4o)84T=wbm{^Q$@IkAnUn&kI;@UE~*USj!QuHO@;*;ViZH+aGinwWL% z*|z|HimgO|h6W3fK0J`Y&!!4zeePB(v{|bgZPLl81{or4IY9S2L0Vr7SWAY+QRMR~ zA{6q`!FA}wZ1C%kV7C^sn={o#`*k)>lg9IyE*wIv;s3XUXyp1jFL8`CE4c}J8jNZU~Q z(D{gtv4-t2lzmLNjjW?`SfbxX08BW5@(I}{*fDw#ZQlYq_J)Rr6Yrkd8W5w)sWW`a zV)FpVGH^>~a*`uj&+9wHz4=G@1`HRh4##-RR2 z$$4KjqB-Pi|)s-6!T9g79T>CzTVE7=9gkEmeSeIP zxzJ&?STq+QJm;wA_WQiB8Qyrt zC4ayt46@OLHR#Iq-m|&NT|9)7oJghdy`5s`i<34m=xf)4z9;U>)X*Z)t`{kh{XUZS zfYUn6{E>a=`USCP7}CSz!%KagppPb2tDd0l&N!@DR2>(5A5lg^wDkd)Cw?#dF>`YI zW|yKHnk6b1uUR-*Hg$B+(K*zr zbM!hfRoBEb_>tr(`=@tDL@~4QplCu}Ib#KsG+Y5Os#pmnv2rR2jL17+~8kz=3 zr>E$Ta)Hef3=m2)j!S)R{#Ura(Fys@4dG5`S@>2NSAN#*dk5gRcrBMNx_f=1mZ_y?Fj>4cP zic#RZ_=sb2%2ia(Zt%S2TpT>%lw!bI9~>0JErD*FNy%A}O9Te8q7s0zL3@9J@HuZ> zl*4QT?FfZtlT!Qe{-fwr9jJQYBpZ&*s=}*$r(BKVY4+ov;)T`B$}U4`-k}cu=ju~a z)AiR2-j@S_auTa15gLuL+?8`h;eWyE&e-$}dP`&L6-UPluV+cqL!D$jAxTtqzB}T4 zvl=i=m0#V|rF9n(d7|Q~0v1o@nvNJKIBvlT_xqEly*>os_$ztAu{&$p-Jk!Nlt`c|UzBKwuFsHoN4*l+O|=KdVnP-1osCOINv zAp#>5qotLFKM8X~{Qed?%cy9~-0}9xr*uU6+CrSqIge9g*HhPhGeW`&zstc&a#xFk z!e>|nEA()b-=U8l>N!#R+&j>8l6Bm^X-S}&J-MO2dHR2ddds*d+b(Wb5$VnW>F$;s zLAtw<6p)lg8l<~RT3Wh61P18_>F$;W>DuT0y!+kz%Y1_$!(4O5TK{z%{&chs*s;%# zxEj*v+0Py9mOls>r2o641Fbb(aLN9dG>A!Cgh)qXOz3{#1A_uDsCT<_6(c@q3+d~VH$RwP?sZ5Rx*%u#J z#E>VTw53`cqg+frS;1He30Co}rFgx2onzX9opPc$$D>HED+gV&SmjE}pl+*mem7)( z8Ce&XwQsAW35+ssTQX>tvPOg!XRaTacXumS#tvIjs616Zbh!&sP75%Ef6=~b7g}_= zZup_W^x}01lLTXz;mz47)SZuy4_H0G7am*=BM*IZs}bN)7{M66IAgm$p(u$}`p0N$ zG(f75tKu_uH78|+mIn{e&<*i;WRF$ls!4K)mrbY74(R%1vi3sqeo*jKG;B3@KqBkl zb|cCSDDePP^eY9@;E|K}YM;qB1u4rc6GiMp${-39pvdkV{SxYHuh6dDKcSURe8wZW z+ZZP|#>En2*B*L`C)9SFiI;6bm1;JAT-$iRGU|I^tH7C<(8f#cMF6SxGOD{5X%P`a z0yFr44g%2jkPyp?5)H8+P6@g7bCN8Yn`|*z|8XK%f=(GHopc78X{2kVx=VK61&IrW zZVU%8CYF@x1YSlV!)_Qfm>nMWHR41a-5ZYa%z=Rth0Ev`Y2PGM@|MgOf+a!OAcen= z+$r~72f3Pm0t)V~ATj1LN)uD^_5chln!KeMQ;!Q6cL_l8-r&idw@XNiQZGK1@(if* zc`T!uhtFM`pB!^)u8ThLs!v5pcv1&l{XtxQG!vb;W=E3E%uS$D*_kR)2P^zL=`T5c2iipe5fIqVYea}j**Z%kvZBlRkT0$qg! zyizB@CYkj_8Ueb7Ad_gGntxunP)(DRB$2AvNVfI=U;iMTW%8?0UNZq_BQ*|}JpEr= zily$_GB+vr^UD1B`nt!8{(?QP2binwTv+(;B<^#61=7(#3=TolF*F4H8n#*=!kbIN z3j<+Tr-5$eXVw)|92Ekn#aa2|+JPG@#x_s3YtIH68A58&%_ufXI9JFY6eh9t?Yl10 zCVl3X{;U6&54(&cCW*!5?I*Q|m-gkXK29d8lgXcuf(69(aEdPuA*N^^*|`l;NSyRF z0ARl4=SbHDrT+A(TQz%^Vc&V}H|4J^>;`L7fN{QA6WQqhG5remkUW-HfEzXPWA;GD zW*)XAK7eHdu-{|tgdvop0^ms#K8D@feMgcbiR}X$Qr&#_w*WIux$*g9hy708GYwPM zc-qt=PBr{Zgo?LStxh5KJ{KqbYJEA6`+mlP(Yhau)}4)R&|;GKvnMQhWN@Q#uwk?k0*XPCy!ljkeH?tQ0iLApTIJ^4dYNNuc%tf+$>Br?7a3dgg(Ln>F?O{ z!x(lRMX^QqJOChCrQ^V3=dTC-H&~i=^!cgS-rH1(XPb^13EJq^=zf=$0|@7!D{ENc z{1-QeLKY`wQJ#NSCNb#ug~0RZYoGvfj3E&mv^aTY$r>Wf`yL=+(m;DEMt1ik?$Xq9 zxa#%Q9S8R{wnsX)gs^NjIE46Q@F+u~etAF1=g^Pf)=xvwl;&<1kRzQ5=)VkbL^8j0 z62pVfO*|R>)MjnDr_U(lElrs$GaJOS1XF{7wN+h4qp zK{^yAF7HR3Rr+S;x5Rq2!Da=Q^dg99TC z%rADIXuh?+9^6Zv6P7NZNm%fM>&&6_XmHW>2A5si`JkQyn5f((jV2!-{oAKvuiO1Rm2L` zA(2fmt^n(;@*0|pppRIUD6O^gzE~*5kMA@JMby^QSO;8ET`!NWxE@Etqvo=wPa29xc!e}!L&6mamjDk3v(rKpAW)Gh$DBuJuK|;)Q z&xTta)~UMIvyIT9oMok9b}j)ps1$zzP$W_mC;oY-Q&XMcPv5{Ru3ajJ;MV4aObc zUtP{W29fX;zwHpt&l#C-zJIfhn(ck=Vd(9c_-9pl4cx|woX|xjIY$uTH9PKBG>ay& zeG62w#WRv<(m)@6kEg>-KycE1LYhB(5@0uFdl?gDhs_ee$#XmnWPTLvP-Gt@Qyu<4 z(b*c`%X{{lR^K7hmm*@HjPWGFA>wZ|6S%2D@AmQ^_H&*X|C88*nI|&~aE({&4#2HQ44=_qY(tn*L@)Xy*!g6xFl=QO3ng!i0~&7Cw`k8J9~z8+Kq z>jscAIPK5JbOs>3(*fn>o(}PYOrd99IG~U0YxefY0DY*d6A>B66cI)r5>83v6h3t3UJGxooPsWHPjqRPIcig&$3chgv{1v z9!ha{8v0qK<>#lX?}nQrcW;%ShxlZeI1x|g0^8}_ZSK*sPqEc|^n6I;QC+NW9`DyWX8F91&M2!FGDQRF(k$r8Y{F6-v~Dh^E(;-Tqh8r}e=7_^I}~ z?&232BY)zF4?B@1CH$!2^UbWU#Z_7%MW1bn0(Ir>@g+3Mg6KSz-3ahm5^0b@pciSl zKk{(VO5dzYn<<#Yo}~E3SI6v>DX!DlAZ8$StPgjk*Vn8AmdC2 z^{;%fL4K8Byf%h~?-a(_XsH}_O?#XC#*;dx-v=_@O zi%(n&kG}0mW(d1za^YM*r~RiP)I+=mYvn!PT3KRWtFjc#ZHpXM>*~RO;19wTS7RSV$qSzYm$wOesOS+*`Y2xnyl7( z{MQ)!fX3+lPTR2v=`@Wlk?I8<16&-_B?|BC(wD`)J=b6V5Dk2vE-Ze`zFBhEL%<-L z?^{eY5@pIsY|1p_m-D#VwEz#rjxzs!??n(khgpz+-*>*Xoe$R+|HhjB1Kr&Wzq(eb zxa~gUZO{v}EiZw0-SF?6_;@k$QW<)MX7rq|u22_A!MZ?OPfVFC!}(VMvMV6sbxyzJ zF=dw_}KFnew_cSQwEWQYsw&FuU#$-f2RPRkyCGS5tPXD z6A!cIoe41Wd@<^A+;UCUX)RM{NF5{15B(d>d(wJICof-SW-XS!&9Lt{#M(4LdI%1( zLjOWYW5`8f2oa{zFR6^hgsv)CYieMr`}`fmVRevwn!#xYU8xir_}oqi7Vp-^HuC*- z=5Ob>Qi((GiXA*z)hB<5AJ^%oImD1 z*g`@!BPH-d$*o<4bJZ?Oro9z@#LaXGoVFq9G9@x(<;tOdS*Pg~$b6~nE&-!ZdC41F z(@BxljS_hm*?tq*F6jGk66`UDGdgt?K!%ovrfL6=6u*BJ4KH+*hKbMu$Xuk`}raj1oF7LfhpF{nl5{k3{l z9bRgQF*&vBNm#Qi{tEQVH}N9^KPrdxE&ie(l^82=WL^*Shx2n|ihN6G#EtAH#ubHXC2=&2%8!RupkyuG{QQJ?vq1htN#1^MXMGvQ z@o#?r2uo88AZ^i@Z4C}p%Ia?xpRX5}JcmfZ$o>cKqcWpU9)%t56YFcaZCipSP{oqz zlzy($2ZYs!6TcyHpCe4mhQA64*j^ar-02vn;=y=0nVV>}%{wtN0|rpfEUtMk&^?q#AjF}$rkO`_acGf9G}hMp83WYtf>gIu}I)#0oK z+0OBa--0sHcJYZ4aCGBrH~y~jy_sO71w0~1g@Df;&q?bAuSYhxJ-xL1wGZFgcO zMuCno`VNN>M39uQ`WP3s;B#Z?@%1deEm26^E)G6{W@$xalojneP|iUTOHym0i3CO| zCi$VyDXFQl31XgnBWh9bxMC?qK_z(`)1sb1(g)I0|M5Pp7rFhWCz63S zey|JD)q5wEONSMtQHn3d&eB%~H+C`J*pHHmr_dT3TI}uJ+9^M4fc%lc)(qu*MGY$r z$5oT>4CS4^r$p*DBa*jN{rf6&WVXg5SuYSiwup43RSHu7?q4 zarwgzEaDQ9sx`K0BQ`@mW3rz+S`7&<5OIQ-+O+Tes9N+R(Rvurh(iMm?`KK=n zsiy22q;?2sHBhx+45cmz<*9ph`dXdRi_~JQVX{^=Z*>dvx_4BI5C2f;vJmREZg9pyB(L>*Y3IQ6|clI zEoyuqAu^1z3BWS|1YqeyPO^-$iDH%3bdS6DPx^K&L$%F>6ICZqtfwt#mt?g4ZPJ_> zuj^2?6*TxMhlZ1u|DD}`ke9}0H9B_Ty`|3Vt~0Eup#RegV)-SR6OKMlH)Bs>?a%G7 zA=nOOKRn!tIH?gu+)qjLJDD4fqq}>bPybVPw!Udc-nc&B5ikUj^T-dWGIg2yHnq?` z+z91WXLfuMvAhU04ob^Ly&%=@`PtRA`{x@>5|J;avUd2+3^PB~z&7ORsufvIQ?2!mg#Oq9B z9^XW2zWTGrOwWptX-c{(?ATXPl{i|Z(0}Pa&FBF)jq3-;Pf5XfZ1k83b9}bYPP0HZBVL&k!V0miw!7b`4;$ zhv}@&N!yW3guX+ZIirp}{@%6F%R~^32Jgt5yYhnyD(W{yJ%E$ME)Qp2nM1TkE}0hJ{rbEzti?@!!`blSwGjBN`&IV>!@|b&VFh6skLslWf!rkJ;%)t=9M-u z4Vyiqtu62wVj0vWcPTPsrRi!xvG292w>W47bw8q#q4UJy$0)HYn z?&l_bw6Y5C3dO{}BeNKTiKbhVpk#IRRD6cwb48nm^`_csR z9b~+I4Njmg5%+UPkEiHc08rM9fEeCp4^4Q9R@v)uQYN!5YI*fi!QXYlx^^7=AGv!h zqa#@b8)(v~XNeEgf~tYIXir)~HJYImD})lp9zU_3Njrw-n7LWPG$NG&9n<;np(DPg zt*&Q;UWp=Utv{Z+_56Iu#mgY`RjBAeCMXQtWXGPouGeFQ?h|h6(Z|W*{}NOqILYdE zMp5=;VD8{xZ_-L4TC9vKZX8XinKk#w#=e@xYR_g`;1oF>*PA^05?QXrSfXhIF%^}I zdUZsi#8^Q7Jqb~4<5pC)FOy*~krgF{C3gSTP!xuu8RaN}&7#NAk3$(bCMkg6B>7}t zqs;jGs4}(kG%zQcF9Ov=Gt(ni$?y}rJk~a6w{5H1r+*(dIeHU5A@>s7GUD4yo(a|w z^;(vyzTSmj*w(RlPyF!56rfQ8LourBTceV`Uu4Q@LH<&qC{e7IL>nGe0^2bm;ULqqP83TriXOKB zXX*`lV~c^qAARddP_1=!P0kU1qEW*e`|!e)r`NI;N-Jxcga-sWsukLRjzSRz=6giK z=H^-uH=T;k;6vZDsNMbl;f>hD&Oj_uab_} z^um%B#nNx1PLrtRrKkRqdGJadz*CwWOqheY&Yl6>rZ}1q7FV|!6xoJb6~m9N-(Ft z|AOQz#i{VQJwxk?Qyv2dUf_h75Sg=7MtqIkgp6Gb%D#9v2B&N6ze-d2+5C%z>@b0@ z!u;AgwvMEk@Dh$r&Y!!WUi#{YKMZjBNEMxK34c&DFkl4k%>_(MGUy*a>Vz-!&w&Ee zW|>ohi@(tak6L0%64ABXBmjw(Nd8Kb1;czB_&;lo9~r#p`!+++L<>@b7Y!=*j`{-N zLwIDp{N5tq9?hNAZENo~*Zxegdedt}1&m3wqiMG`#>e6UHqZ4l1y*wHfLmk=5JbPC zrY{kc6o_I3S=gHZnMqV+rwG?=&9;B0@TH(Ok{F195fMidi!z+Pl23?15))W;TeqLf zl$U+weZRPxjYzCitge&|{ZG~diVA4Zsi{su|A?D;T#?;S%y*qORj`iSK)%!87Q))_ zEHlhzbonc#)r~b$Hq8UKsDvso>Fi=OY0{vnZdvj%K7Ov!hBz8oqyVJ+*Zi@&M(!_< z&~lzPULmn>A7-#~LfjyVhy_+rSOJ9DKG}%v&#@03+OU98uH%;H$*FYL#>S?fXIq?6 z1Gjyk8dbN@or)alHMbn{7t zm*$Q4iv_&2O+;F{2~fI$VxC3xnd|bkAW0$k=~Frj9b)!9@XUmT^Ft+X9J9kyLv91ky-ZF^Y^c^zFxNZY2(?^ix$&nw17PRuqv zEa8{;wrmBi+Su-RkOBI$VU;vV-^Cpc{L5syXnwW_w&e5uFZXDOrsqp*9_B)Ep9-vE zMp%qYg=BrOP?H$upe3nK_;*BNgsX5$53^24MFCk#=;d7;Fc;X zhMb%4(v%(3i;y(2Zqx=nyy${{QQ3HtHakRSSV){a9WGD=9 zDr8zrVgW+@SBHa_FTk@9y=Ce$L1Aa%19+b z{PXneCyxGEHKok|svjv9zO;%V5#VAkljV{;K-(5z(#+vd)3E7SdcHnszsH1L9y%)& z1-o3p+N6KG+Zz2fMPq50eebRVjUjD87Wv_H_m3Sbh^2|oVP^B8dC0vqK6f|BB{Mu~jOxK;qAa_2^5>>5q5} z8}t#W!~wHf8;a)+)e?<0LqDm5DcB_cohnQDgQj% zZogj`aos&Wc^j8E&_z(?F@WwD&^}LFUzYkW0^cOBNt1Y!PwYU44ds!-(?Dlt3p4Gg z@S5IFszpgSDdM=oDHFR0=Znbq-eY2GcrU+ab~_8h@P7`g266bEZVIhq{nfrFWItWU z4xt3{YX};WSgck{hZ$Gyv^8)sk3M0zce7UmDD_=-bf;>C7C0E8(M<}(o79WjM9!pe zv*(EJ3IJ1ZLSQK7nl^Qj6%=#j!h66aA&ILjfM!%~Lv!Nba<0w-^M#%T$XQm`*9SGE zc(!#G4h3sh#*xVi(xSXUyF<1xY<}P3`oa_~7J5g0{OjP0UHcwTd}Y@t}l7`-gW0g zPn+*m{moBudHGsgC%i+e)g<4|8=7%`8-v=ZWc(a`j=TsADq=^SiMIMl+t2+QmN4&Vb%O~faCvhLCx;qh! zdrRsdr_tb=X}A~hY9E-T<#Ye)zv~su`rNe(yTMOj*%W!)Z3iE$U<1 zLvm6fF2b*fgJW0|ILe4OToQ2{En8wc{9NY%OFclg<+>I)RB7s6NT;7sIpK6e#D@$qCDKA9RcA zg`9n2SLfe;8O0aw-G=so=6)6Ij;U-&9yG5?r#(dn)nx315Ywq5$43VP82U|02B`%C ztKpbgnptVGcFk3iuD>UdxD^toE-QXa9YYEhGnV%=)=l~R!4N~W^!;4f4nZZ;^R{7h zL$F^pmW*42LOtP)WE}Xn+T=QR;_H`SNiazyH_$YtL#HpCb~E$G%fXZnS*eKxiL%G> z?pV!)p~*=v+00c1w-TaRFIV=bt=<}#Z`||Q^P?N=9PxVdULC~!lC2Y~p2t)7Fik;7 zE71pWmMDr#Z$$9cq1z=L*TbtML=mAas#K=)d;uu6RI2KJ5irPf0c+=_cJA$ zrQe1*!A)J^59z=8xj70&b*V&T)rQW&LE@ZW*TVJA(2Ff#i*}8mk*!A3n&sQOLgZPL z?@k2ri6k7!IPpE|0_q{P1R6k&2JysY(Hyyo-nN|P9M62oYywe(N4rpQ#MpJj476U- zPPx~#;uIz&%Tj}3+D1One1?7*mkqBpm_I8J*EQ5d$HlbW`veSP9J~q8Q_N3N#^c?0 z{i3s~Q#iTre7Yvu+r_A=n4cFksuZio4Gi65b*_Ntc?-$KNk0k$^)e9Q$cSPwIUpRUwbm*@ zEaFR%R3?ct*@A}6O9mVMFK}N6bQFc*5CT;N+?nzm*gt=+wO@r%QJrtl0Zy`THLDc- zd1*%{d+}%EiwzI3#mA`u!ldkE(knz1`y`qHhM;a?XhhgP8}MTJJqy!KVlUef+N}K# zGxK=;4L45PcT$Afx! z!NY9#Gz;UsPHvm4!hjy1=L5B4k1tSqS}lCD>gv2W|1N!6&OHyfVsyFw3BD0_dRyU} zGgRdo$;Ze38`{se3YEg8@BlWcRBV}*STvwX_Vs^T({nlqQ!a zCR6C-S1<=s|9R%ovH1fB1yaPYD#(I)XDY?{cdEZE8Nt>9{*0;|kLc~~FS6K>l#~zf zxgTw8LJPG51Me|wU9B<-uLJ{q#h~dc;O+;L_{IZ)A)T0pN4t&UqCzW{Cw$l4^*D}RhK;ff9qK+$`1mxT>lzFSh~ zo%`IazB}kn@5C~YpYQ!{5fEb!cTJmCq}({VubF~W6FV%s$Fe=s*?n&>AY2GtoRxZD z-Z0qCK4?-n`i`md^~0sn^D569eAvHjcIq~~z@3NSSzX-{?o2xP%79`qHiHEzUH69? z>DzNcm`riq$a+^OXYYDB93fU8C)jd2zW1Fw0Z;*~?o=ycUV?H6}8Pwh#Jc_4*FA{B{lmKO7G)t&2JK6_W zX7l8Jzd6Y)oG(|87W3@FfSqjK2irSyrGZ=xi0cDawDavbfhZQ<{A>ln44z<>vyqB+ zKfh4R(24VtZL&G94WoSIvboy&PeJ#=qrdYD+`C#s&uLrMi+#(vJAj@Gf2gDAL$9C%*g^h&_Df&em`g_gA5u3GL3<$jqe^XKFwy z^RDNxwE07qk3&$~J0Ztqpzl0}iA_auY6Gd@uYP8*qWa^JE5QMYdXKQ=J;aG|Xp}!~ zJF&RWO{}zcJ?Oc5+-_ zq+SpTEgP5>GC!#^1TnW3up%6=NWF<-&X!gRs~war@`$4M`O2l9p(d&Dy`gaO1kBKi z?@9BdWGp#97x$|x)~y)x5GBZqYm}%|OvO>Hfte)lBO4&}km%^ye_8My!j zmCUC zk)rgHXCEstX#83p(sw_Aj#!54Rm7lB2cf4$2~K6a&12Y_$*?cP(NJYGUdo~h`siw& zrR0|JsZQ3;Icfm)5=xKVh(rLgWphiMhe|qjcE-*~flMGk0T*_GY`B(4N5nkzhM|!E z`YJ<)ocF3cFEh{Jg5R-A5qep-`whdHxZ&;l^QC>lIRD?*Gz0EpZ42-RG84#Za)v(J zw3+Yx$KgbO$G_^EgDp`K*-y^Tn+THO+-cf9&-H=Xm|Z22-YmBz+4O6EPZvyJup`o4 zs6aU5*nz2II*gSdy8qp$_qY+VxJeYbrwUa*?1~_T+ujtzghnc&C-;jZBf*8gHN?g; zA@%qqyu(bn`!`<#R{6uq}N`FTqbgVh5{V%lrW}*;eU48;9uFUx%aIS zntj%9o&7@Iz{Q%~gZeO;L`MI!vhXK^&#=V4ByBk}!EeUMWCD8Bflka?f=>LZ;4Znq z_-z=LOtHg+i9`%Oaa@7uU_IwrWy{G%kF;UWSXZ;iN~nOZ)^=;hza-2u$kWTwZZCMd0gipYKZ1SJQ< zYc;|0fiN-ha+)`?T5m%4KU>JCn-{jlt~(6E+TM@|x5iRbM@glgK?5Ba1xJvem|14u zeKfSXoYBc{*Qr5zFRUUmmEZmJg;fe%iWRYG6!p1y$Ro0UIZhZc+lBj6TB?BW=7{$$ zIc(&^uF*RC^F{mS-dWq>a=W27z4cero8u<(jqaMwC8u)&m-IMA+>{LYZ~BQlzfLIL>7d_xYA-;xfSqQ`Sp z_Zr^E(a|B1`3CF6J^nr916RyK}E?+P91sF2@O3g=XBx`2H zXyXL@qn4k~pzZ&hu24IBM+;&!(|nnR%4Jk>WN>!h%k>?;&%=%58r*b{9DMs==s({)Qu}dr_2;2yL5(C;5@P>EnZ~GK;_G?ZK?Ms{ zIqdwn{(!wNc`|d!g(Hr)7y2Ho@NiWRfsP0Tzl~+j;S~)%9|#B)QpieX2v!qo`D2{F zH?04s_Y_(rO&wT6%0XRnFr1vJOIy3?(>b8+!l57vzHk&H=mCYZsDJ`GgK(@+V zB;-h5@ooO(ydVm$mxJK}mPy3Q1TPc(>9KS&r@!X@{75Dz;hrZ|@e6~E3Mm7La-cyf zBWm5U8#EsK6{Rtq_dDr;vW2+q_$v#q3{jF{Lj=d^e2W{Vp3T+KvbuW@sNA3T*P*r6 zwk}Y`P4;zZzl5EtXnl3$->j5@v;;s3hn+OVIGsl|)eZ->SO<&Gq4nci3s^yvjtSMS z9vJ}6Q0q1(49E+;))PFUa-w($I;Pcn>d{m|&OheoidfiZ@Xf5(!w*aUo<-V=*MiLntdM7VTt>K%h}V>Qw_PQOK|{hcNl|w`{3q|03ca1nfq>)w1Celi0*2qU`8^wq}sadk+ zIJ^pzh#pZkMx`R4kQP2?O=FdQLf?VKc&+hTZfA}AAKq!W=QRRd9cg!{=R_E);8rj@82Y5Z*%asWwO-#u;hDj zR6aAaZ}=_Fg-U^>8dej)$vB}49mBaHW>ja2H{&68xFcj&t75HdZ6!Q_tDVB@u!hB+ zYs`NcL)#|oJ^@GgtFhhxdEajg$}TUoQ8%vn0zKQp$P5h()-Pv`il^=JlFax?@}{Ej zvakzU($Wqp+!BBE{F_oREPXC1{s?mjL?=xfv&hbms_R6ktP`Smq5 ziYC|%2wJxv~|4bi*Y{vW0gBAOYm(8o9iy>$k~HNWeu_FOIPht%gyzwJ#o zzs$hU7@R(0_8;ee0!7yL#`D2h)KTveMMx+WDKM_^3a9HB9$t9mZ~P(KZ>kw?BLQPcg4N2K}|%<>|N?pBFxC0T=;xbn#eVD$?1@W{JAX_R|?;=jckS}&pN2fIFmID-$e8$ zRgl&poyGM1UXziZK~&SWrt{|(`u+dZG3A zOi>&Kygf4LzGogae!5O8=2AsTND<|mG_p^AS1X6owVNE*50c%w&ST}3ZF~_MOqCl8 z1wRvO%X?;jHSSZT=or0`>>VW0I}`?OxpEapckOC}Up zRv>rcfU6zPn8$X*WVz8C9TKShlTtngJR}AGNq%Kn$T)lqTR|Y zTlNDd1B)6;(&iciCLaW>yh3DYv)ON!~fr)A$o6JZgObaVXT0cPtg(u-ao>94i9rUkfnyUiGL&O-+0h zlMxhy*&y(!{NR@UJaYZ2K;!Vl4P+W*XwyWT;0w3>+j!uzY~a_tR>BUmc%{gvfr^Vd z)`;*I#Ud$|m@;wPfKx3GdoPo2$nU(mAW?hrtUe_6T%o=5!7}?l`-kiI-wS>_m(r+4 zyw5G5Xc9+5VDx4QS?Z-Y?AKcQC`Hu1uw|J)?qT>KrO+U5gBsk5gQDHcuul=pgtV$U z>N0+!6*{QFq^V!U^p{QUD;^S_Rc1V0`cVb?&JLJulv?wIhsB=Uxernk)5$P1hMGhB zwjbu-?!37OvJ3BN#wXYzv}EPspekHm&YiYZtw@?*T`bgN&gEnfStEyCpcAB~{Lp+; z-*n9=MC%P2;-yIe#Hi9*{1>BwRj_mU8Fqa$D@Ww9M4;sPkDo!}F0b8X(fnfzMyl`dNo-}DvF*xxCuD`It?-GrAyXHk{ zm2`Gz(_T=wN-d95pg|(^g~Y!=tt^p-vEBQT$6_=)fAt{opW2{r)@4IoxeO66Dp@DVsYrCJvT85AFZ<2;I1--ncZ18CWk|V}^TNLYb&9N>)0sgxN9kHJ8&0}iw zSxAffevh_HUQqr}Bnz393J|PVvT+_-`kqDR)J+OWSL~}}yqchai{Je5ky8~bD2Z9K zG}*HTo_5GlKa}GXTQ06p*CfBPduzyMXN;!{jeD5mzn4?WKSy8Aps|3CaQyRv_t!ET zh;z>RJw9Vgj^oo$u3~Cwf%KG6VrJsS?%2h2m2dKwmgtjv^1FvRmi%Qq^$M+9kUB+0 z2n2*o=APzA`HEg)&p&$HA|fJ#?-xaFMrus^fD2?S=W#yAfJ>XZE;wtQk5G%G(W5aS ze59^Ac=_84JUD44Z^|Dp6-`A>XR3Q<>Wkd%hI3~Rq$c5rd)0=}qla<+h43^Kn!`t9 zIvx_Qebdc&+7;)#)n~}z3c>=2&kTE*Kw40`NeI!W8-|ZZoo@;}Vx^dAknnX0aOu19 zR=<7NV4xj)dB8=o)vYR(qF3O6Eml)k*X1xrFH5yyCQ~*|g#;Ibl_Xavo_NyV`NTbj zu3IFFJGAP(?e(x>VFBuT-!rM(K0EMoIz^ha20O9%gPO>qDS!VDO#&h`c%c@eE@32E zYvZkkMBN9rgFfqe`?&h-)7aP;heA9}yj|Tr)AKoq?W|MTa69z*AIb9( z`NPX(Cg|N40DjiZ+uCy1o|;p_>qQ z%J3i5ZFdi80!gPNjQ-DJ4O*RY9G!8Cttvtpfp=C>jJ7ikqB`7aM}$?|9=>UXcLhht zh>V$H@$VY;%$C@ShwL66Kg{V5iEpdKt)_g+mn+jLFhfSNorfE(MLLS4~mVFXT zMmv|d1hMB7&K^%5f>15K^oQ1lVVBXObw;91>E^j)II}l-?AZJI3k!XZmvu>~B|WLx z`Rx1`lYG6U>N)JuQ0|1#AkTvy8igxNhz7h5aZk7oF`!SCfGQ+k}) z*|~hVSteAG^7pnZZISmMUUv6yq6SEE@6xb!{&zw@=qu=^O7kH6Yf-a_O`sBp&|9Z7OHfNjeP zmm!tgVs+=&K_!@u76HF&?^3XSXIBcoyl9UqHW~PrvXIXvEH!@aha8+S_sLumXt|E_ zc3g_P7%Hq;q^`kjKu>McJ{jVS#x7VAoexp0C%&vZqC)m zW4HhL@cj5Cm>k~4u2+wBcESk>E%Mkze(T@E(uz+=cf0IjVYk%T&xQ7g|L4WiB!sHZck5`rNV32CvFt`wm+IrK8 zy5#lOu=G;UtEGj7)F5wiAFB`BZY_Z4@cK%%vS8-NWNZkc;IiXr#riv;j|L;}>=#UI z9v&W>kJ82m+pH2~NCYbz^rfzp$Tzhgd6k9W40j%^UUKWPA|Xb8>Z8ekcnQQB&EOd} zIDNFR@#~p$OvqrC%x&dG2xN59s}PlSy~!-9T!jD(elci&1*L7`V{{??TBcm~9o`vb zyX?g--KIv`jw=ZHzD1FQnbu?MpaFs%-<=WVBSvXGQWA2{9$xf!AQjaAh^KX{ai93k z9W5EdaD0~Efw$jlNzH*!A5Wd9O+YtJz?JpUpy?;wx{@%r9)ZddbRVz4PAhJB0;S;G zp$$ha1xqa9jr_Pzs!T4{pd>$0Clkpm{QwJ^dh7d-!JUw}m`-PdsPM>gn=x?gP<47$ z;6j%>jL398zIt`q#;i0+=ILAL1znEKthCwmh-P8_nC87|VP_XZEgb{CkYRa9CEYZ! zZVHvw6|xENeU2FMu*uJ{`;DAVg`8VD+>K_0`CPc*2(0gaARsflhK|pG&Lr*;Fx;Ez zvH7_Gx2Cmv@NFMY@|uiEKB{F_?&lhr&KKVTRM@!MF&E}sc&}U*Tk5OOseK-F-iwr; zq%sv%Y4j%6N`k{URYifu)xOK(-Y^(SZ~oaRYTw?6s|@W4t|LSaMA2*?O^o$UxA)y# zY<+mJIRx43BX;4}_50|*WZ2hs7VUP9CM_&^GyWy;F2mOM#%=g#JtD83B*|KzeTf@8 z_8<9f&r{onAB}znJ2eF0hv=2{&S+(*V=gPV6H*!k9?c3Ii=>cheJ)>)00Z8z716?ihlz41BamuPd6F2IIF%r04}4r#f5#h+UN_ zdB9n`N~l21%Hi1uvvzeA6kHAIhnz|qh^2SZ`D3Kpv_8!#ezW2Ip~*bV9z0cQ7|(a; z-g6xeOj?3G#BbA`$^IXz-a4wvF6!4-LQ=ZByFt1^Qb9sGq@)#*i^!v+sMad#yQt^SW5uZaE2v#4Xr8S!VvMk-9tb#G~i4)XYfa4g-G4;i` zvPk6JA3J$lT>wA3!HXC`Jq)8EyO-Sm;ZFkkeZ+0%|E|nnv&jaQwRm6IQr7@BG7_6*ir*`yVM@%Xn6hk>Ug@3k_(s1x}jlX-wY%+31#gWF|pI6om zhm^iN-|ERUG$`T)`G{H$Wk2t~{K(+?E~au`JW&3Z+WlNppSZFWZ?`*WYgYB|N~~u=F8o7i?`U@<+r?s%;k$bZTP# z7>6)^N8M+TbV5E=Y*#!~?OduyF^?!)s#wgT*iKCL!$PnqBS%|^Sdg0UjQS$Bw zJhn;+(!>XjKiB5Yi+BdH6p~FSvPmGNW=`b)N$|1X-{XRCb?r)Be-m&F*PPpKUH>5u zSjxVAs?;6A^}11OZuJzT-tTLtVhRLgr`|x83Qon6pE9%uAPp(q`guLxc{z;Kt?uTh zd3{t>?ebRujIwdhmdf{KgnmA#d=7g#Eo6lpOwmsW0)oW^6OAloC!4XSb$qhEVC0Cs zu;YtRqnt_wPfD^0H;Y~l(a*i(8<)GnY{+6}P*0DE0~gt)M?uAAN{q#D)v|7%GqeZK zS}q)^lxdJnar9yHl(ysZnfvNytTbt7j_Yl8Fzq<{Rnr@7_eB7A#)AQke0+ZgESWv& zE(y7&4OFRuvG0o1!bd-fst+9bF-+Zv%vMdTTtsc75XvN8h)Z6VKiNLv(xWbZB&9g( z&6IPum6{<4VAC)_%EK)hw3vFRGkRx_j(%ofNLE(gFF%#hGlzS=G-maO{C#X!hB03g z{dr(RgVP@B175oQ(Vnahtue0*9V~XjVF!EY4 zvq`b#zkb7`6^#iowxACSZ1fvk>KIA|WO4^;&1&FUF8giOe>ofL{lc^*m0RZj6UTbG zKTjjh1j;s6ZjG+N3{DJtwRDYt8zEQ6b`WLaDux1@xk@><_f0t`NB;L_gK9D@;O$Eh zQ&_`Y4V0sgV5j_CMm6eKt>}2=ZWgX<$bF&c)ygpC~*0VDIm zI2i{xq*soR(9%GfbO3GR+cxTtD%?La!Xk~6W_8@s6&vU} z!;(QeB`h!BcXx*B-C5qSB;Ld|x^vAPbugJ>iMCJDTZ9~p;Qu|E{mrO7*jY=NT7COj zGAmcmMFH(*p8H;eAa4FOB<>TU5D`5-3P!-Ey`>Fz6OZt>-%dZ~u_y91{1sLfaVO4a_(b~_sla{rs=CyS$5y#goQZz2P1}P0Ce{|)OWcYts27HF27y8@w zf}!8gR19G#f_hnR>aqn61)&^y-=GJ^OSdFHC{A^v1j zt3uQ)Ld{x{#Pk+kv`t>9$&{$pyV8PQ-RzoSnHpQ7C5cr$g zcQWPwc>9?go=S$G?kY9=WBsqGA8uu;st-^R}Z6WsIgoBq7@QFkqDvu?g_`e+qNuj0;N-=K#Td} z+Swvi26lac&ikHlCMJ?x9r|-a#(It!t(piwCj6@_;&pP9pr6Ft&e#183bmTFwuBCF zLR7+8yOiZ?e*|{ zB|p%{IiR%-9O7xavbL)pGWFh-1&KJ$daQsAx(kWW>xNzu!cf z4+NLwi|2CnvT40O-5Lm3*L^ea=Yo{+u;`0sTw%PZmQ|@zrf*7?Hb}5a$ywr~6&Zb2 zKOVd12)1YBz|ti3#6KvAK_$yk4{qBTFp|0iTjeGyo0ZdEkEvVe&)`^SDl(wpXv>rl z(?jZE$j_FP&-Bczo8B)HQC^wt%lOs2>AQ%Ddfyxrz9?{Xa#9P)9jYh&m8#t2mybyM zlWW?TyB80MLyGWy(^hnpc1+9WJ%>#xxT;qRdMi79vjWznp62s<`|bvL_kD5Zk=1E* z^;`U68i9wmpaixiumlKuEmu3*l22Hfnj~I(N;SOTY!P3?H>+d+Hfr;{%T#Y8=~rc+ zbw{ML&QM?^ae-sw_6*_eyrSNguYipto_wuGfX$M>#mN3}He}S_IS%Dr`l5j9;oEC| z-2mt&Vm2Oq@~B|5W4o@ahV#knHn}F9buh^>et3dz;x1{fx@8@V(u)($!eD?f^lfMmKH%3|)Q6qGf~^^)JtO99h}gG~ z^dgwHa12}HwxF-s4Wlh#*yxdJnT69P8;zqj?*6R`a3Y^n8BFpT;WP-Y_`kS39P?;u zHYZ7wy2B@|3%uMmEIkjTe}BiA@Z&Y%B5thQRrelO?&PXz zliD@_pS3{lnY>?|SE-P}xOiW=u^TB*LO~N5kI)1a+&0pNfclOqSW-Iq>+sab^cFmKeE7H{M>p6qqwAI*~I+dq5YU0ro| z+LXP@Bq513W(m8WU(c~{Sa$lty39F(XBy^}8NcJ&u#M(@>8zmWf`9Nxqs zn-sq$Zan1-U^9Duqm44JyPK$~Mb)&{%Qs9$ z_0AMHX$hU)c75|Cl;@RQ*h8rK%Oxr2jjZr*R{A(W@<{@Ep#o(|*`Q5$7Au{C$(2o@ zHqX_ov^{BczUWzfaYhDgi#n}tbIC#skYi=*t!l0BTd@%@ZTh4CsQ<#F|G0q*5&T&6 z3qIAZD{{8Fx+!wz6N5UQlxLRrHSE7Bw-S|NaF8^XjT+$qi6146o+N1gOq7do>BgHC zccrYZFJoeN!cvGjvy_T&>vy2MU&<>1=FWK>oTRETbWqaPzK!cu`~oAqUt^#Z7# z*Ms4CG&o7MvFv!irMAcot@Rx(J@AQ%jkD-5|}|;8jTvy54Y=B zh3XzSx}a~aSzh1v!@7*i2t!Wc-oi=JIJ7$ZV#`18)F2i^ELPyrz@99Ey$8Jyrk((^ zoev~Nei2Uy5}N!VC^(0-zM4h-J_EWqKmt}@1 z$8nB62LI1E;oZ*S0d}^D{-0_zsLZjOSZe%XDdRHywb|Re<(ehWUX>5;wHVo1pLyc0 zBB4+8q=X2v)|d)pqHI@19NxpO)Ae-Z`7usC44oIe&;9f+-yj|h%6!`-V4KThRiy4# z)H3p)DWGK9BI9|RKhYwU4H=bL0Z#-+Nwvit=PW^fUIU^nsT#e|j4!bALAyq~tbd%F zy340Nqum9keM5;ySkr3$xQ?&Ax_2PjGvoI~6(ylX{I+pwZx~j1XW~FWKQU&6y0Tz& zB{H2a;r-l_via0N9I^u>qPrl05If5I2!^%& zmeaw;^&ak}|LyFuOzR949TEkFz=!zI_zw;Dl>xsu@_JK}+GByGvdnIy|z z(PVV7TL|!h%20jScpQ0LMU#gUCsIc`X7&%m&eiqR^5rdlRk|ON$b8M_Xhv0%aH20} z2*1@pAnAvdzXI=?V9U@Q1cV}n&!Cfe2kDb7GPFe`&|F-6hrHZ_-Riq_oplw{zFO(b z8Ch~tAg9x*D>3}4i(*=*O9rjae;=8~kRvOV%KEwamG_wA`^PHfu!48mH0Rdy61fq0sw~ll0*_FS(ZU7+{ zur&+nB9}vOYefO;;pl~ihQ@ELA;!vICHaqkaYdw?euTuo1_vTL7+jv8{haa|C1WR!W_1T(Py#WNFezDW--(~9D*zN= zS5`=-EfU)wg4-!)(`d6ika?O5|>+pAN4-#RU+iBK@f#B zi|2zO?_tbrSLE5x8E%(O1xE9S4)9%Q`!a3MSCtpHDvHXbpZ6}W5#)pg+y%hfG8oBW zi92IPVjh#4ASMWW0Jccm<~AHLYr(HY4Ja8i80Y8|Q7QXWnD%{bx;06Hw}(v*ZW9U1i#EkU$E^?(xS_}IXg$>Yj3s+H)s{k&gcFs z5M#+vx8@I4_jjBxIm#6v;GQhZ0LR1nK7-m>EX6u2H_@h~z^xl?g;uA^<&rm_EL?X?*dC`2?&vFHC;2G&@Vb3fR zdg-8l&|L^(V{SJNTuCZ11^8nj=5Gf)a?Xhlhl$eTmSCxw!iXXCL5c=PW2o4hqP|ai z0MOX74Rq3WkBL?}n&KNXrl#rlYPI#jHC26@L$K?NG@r#n#61N^0+aFsu};)R3labq zIpp`HCm_lN&ft$eZQ*b5W<81w)r2CdMYUP>{Wz1q5#rM?MLJkW5ntE6wW16p3pEU= zf=4|Ul)y*g=$eaIvM^4XAa=ML=M*6u{p}czXX!6p+^z^3pd)m&8Zvg4)nJ(pP!Z!f z^kI_GU%f$)Ftw|gSqRl$(&)(Ay$cwtpP{g0uWle||JGdA`_O!OAI@!5CB7yTO(*|- zcF2rr0RIdBt54k7&yS{a%dH`ooPIyLdawE07Rg3oW_rGniRPezFD#-^;M@Hrab2YmGZ3g^(39aZG!0>$ut^pASZHO za-*GbL2j04v4btQFB{j<_$5<60gwx@mxwLCxg6;)NuuvzJ=|?Px|bmRsNw#xo0kdD>8hWFHhq#zL-GZ z9S;ZL>(T$x5dRa2V1>D0!H-vWS-o^B>9h^7{NwqDx?zA_J&9z_Rx}vB%;PMJQUFYUo&Dr^C|VeO7S`m(#-o^L~75@96u}) z|Bjfi_EGD${j|bo2!ESy;*Wmv&?iI3)hSj`{-}RNZXeVoylp4b@GJU|p@3560*0K) zUo5(h#63dMV*_(4{o|1thd%wg>fe>qyYq{Y^mnBxb?>v@{99ccJA717GpWA+RC*SE z$h6iPrfz;nqoUs+$ZHI?W%k;uo;9CbS?xjeKNRSO`~eG8vHk;fIxY*;X`lDwKME{f zkV{*%o!#IS)*&eL85&x@KK(yg04n>(r&+x<_tj_oY`0T(vR+if`*D8FmE!py{*J&m zzHJA9HL8Q3-7YKn_Y-4p5QUd&jJ}=T}yC{_!45inBWLB;u$NhD_clWmh3T zECX-N=1EL=LT*&a$S}m% z*7N+8U{#&GHLe%BNAPV!x8_r^Z03fiMFEjx>_qC;Vj4t>{`}L7X|+CQ*d$uAb?~6U z0q^DoZvt(YxQ1qoZd1<|&WE#R43wx-B^MbbtDYuN8>Uol8HlLWM@%(a4Qr43bFN;j z8;mMfDI954IdUL?2DT-r(Y`dl%a5B8OdrkP?a1U|#cK;T1mw_lDVO-M2kBKh@1-$g zkPDUBj;qD)hB2vV972K(nYRvm(?0D?ZAv74hP#IzL0*{70XsFh{??%E>NJ)(JzM1&RTPOHjP^4gD zI{(8ZL>F(?ci%0Q3PH;fz)iR9Qtfv~UI+4Pz>CFE$WOGql&VHjWOk=p|vIIx2NKpLoUbEQT#G6hUc^(P$vM4G~jl2`%#Y}ZuX`N#or*9 z%;6LoclI+(R-aC3kGLg@I-g4v6|$hmY*#E|A3e@u)J25uEb|DVrj;^9qBtLkMZ%_K zIkBc}F=n`T`8&-d;)Pz5173w{{aH%RB(b;+7;>c~!$dO7qy(%(JXNyO(y(5S{%2dH z1`9r?CyHI?6$+CO2k3x9at3?_YZ0uSK^bJ78&ul*qoBHmtibX zWjF!?rAi*xomA7i0nX9bB0d8RLnEVbixRnV)j~a>UEf29Dks@(#^f3M&bmQI+BeBm z$vwBYXyj>~?gf`XM@}4x0}Tf0$>`Yk2n$YQD-2TV=I8VPsv@q4J@RX&;3$~%;Nj^b zi|SYYh?jKchcSIml&<|tQdX{hZ{P-a`w8J1fB1#p6urg zFIJ<&PPAYe8l=-qh9{eVlRy_eAIV%!iKH#go|FHZDEmfS8~PIc8+kdw@oyQ|*V`QH z+g9Tfy^f$;xvi5*3}z2wte0f{=sMW_aJEJQK}&?dZfu-B#031^b2~cygH=i5R6d0N z(rJ&qlu;Z6k$i5;5pJ!cP7_}pukdC-wmx@pnHJfTiCt-l64{fe4|pli-XrAd8+dzz z3Wi+e>}IgYGrAmr2%iY=?C#>DY>Hd+yl?&(0(Uq@Y|O;!1?(M9)Vm{@>nm`7H)8up zB^Nz|l(Kb-6XYEeHe)66&PNQ{PHz*n#; zACiwO@;!!d@9G8+1kF^?ut3!Xpq;tsDx86dV%BkfY03C%j(vm65ae7AA_9BfJ2^F& zaUUN2)dK-kMbCSs4XR?b(%Q+DuO?Si0*enVw~wV@bkA$oKHG@x$afGTmm}DdGuzc* z!rj2rcsD}`-0X(V&bT^58|P5FGownCv*D}u1|0-3WOOxT%*`5WG?L?^=ooy18Q5wH zA+#yVWy;?fnc=n$r`dkq6Kgj`B__hbXy$&XSBp^9K%_^KH?RctD}!sXDVK^#wu4{jDCYi3%4YfTN83~&gcFT<8oWekhhkmzf5E4nJo zJF8Z9)X^_4k7T7zD7LpoqAtrFH?v*exX*3YVo9dGelmhRE$qW@!1V8R7UHl(Q_BzN ziH8cM8B+dH$S_f#!b>@b=}^SZ(4&+D4vQmeP`E5O-512p%e|DSt3#zC-kGE?lcQ&z zfxEcJnsJ+afc&S_h?jr5NJo17x;lE)RF+iotMWd?;vULK3_q}&VU!M4ixB+%-c zBcIn1m8_M^)77jd-$G9PC(4g@1n+WL?6>&hilbIZ%U&O^pc zIZEXQ64~Fp56vA|T(-vh=z@ihM{vT!r8V1alM=VFladuc$*iySW+nX46$sU9mmF`7 zLFO}uREb3$LKOTP$>nycOCueV+IqvcQ1$bY!v#oY?b~~KM%te^XpW>$MT>$IeJuHV zKiTjTm_nFotyHbnKyE*>GGLsZ<&(|ejBtdM=U*ol(fb=j8*u!-l1Q+%^$dLNNA^1| zk4UWPAbyuUeCXZt(}}0Ay7w8%OW(`0_xV}0ZXfCMIw=MHCS9@xHD#1a-3VILZ-@uc zYU=-6o#gbGf|%o+8 z>^oOT5IfE2DReN^K}{Qk#DM&J5FNf@V$Li+n}~is57F4l{AT9@0nJd;6=uUJY1`#0 z+umFAck26po#DHD-0I(FP|4_@)mJ_VWxF2KX1JZ=B=kdc24+Sy3lbzH1`Y;g53pUH zB6)b9c7}A^yV!Bm)69YzZQy@OCQ*TSqxHF@*9(A%-lpN{oAzTJc zax()O!arr|wR+xCZEJ~U6<@*;TU=R;-{EVYC|r4#)srE9E>E_LJd=cZq?FoQTbwYP@4c zpP&fzkHIOwK==KVdy%qKQms6%#gxogh-7!TrUmn6)qaiy#bxtq^2@u5O+$xXGP$vm zLLEzAO4-B?tVYFg5L~bh18xDN@I#|)+45BIyDO5 zwxHnrv2g-=-_gTI%DTDerHX3SF?0CBo%zrmkjoR4Vmdi-eka_@>@XH0?@L z%N!#BiqSBE1D^T&Z5)$qzheZhTelV&F&r}>xH+iNIoaFG?(pP0(S0^Z{1|(}%tU#f z6bgIku$ZbgY*~)Vx{<>hHT9-UjNUgUN6Ph&npPRdRsnBRkCGo3bI7IKr_LLlN4lJO zE#peu*hP%#JJ-5beWQ)s8M{rS6=w^amA1#sjAc_e`&Ufv44oy%wnN3c@c!CnC)Y0f zg{H2zu@7^rt27^H&squkqFG~Ta9-{gZHat`-)5y_zIAtaNS|VOR~FLr6lDo1$W<~Y z58T?gdy9jU6jn2yWK;Q(Kr_qZfZU_9SO0lh-F2g6^{eAH!OsT8NehzPS;DoZAToIP zE)FFkP$<7SJ+c>}m_=6;>-0@J*qNR*BFn8k4-Y|7BK1vJ zoY~P1s#|!l-$+d__5UDdoRCO?e=WnQ!E2W>;+4+&v~qHBq^P&SsQ;{;<#HZtC>9gz zVgUd1cA4>>$xZ5Uc2%NYpKkR%C_j&Eb#S(5KRi{+s1jC5#?$!xLC8}~}<@=7ostoTKw)rz#6=K&6?uyIw(Dp5`fr3k_mW^3|}0mm532 z(bV=PoUJBe&L*3T1HO9(*=wh3@Db&?yOXaRJG|nBJi+hw1~ zNN{;^=NFbYK}qpsZgo*iRwCEPojT!kbFl9j9`Y& z_Q@-MeV$smr`0l_^*SAAbw(B3MfZMP<^_ztT$}b!q!3pAip_j-++Y&BC!jr*sd*iR zS<_tgXJ?1z*RpO@WyL@8i_JIt%RR&=1DKfzL({8VeK+fHIy^p{(loyWj9wfVv>d6y zK?u!G${GQq>TxBWzK%s~#_nAK%ZJ?!f_&OOymoIZB)zRy(X#BG-vQ@KfZV;PR-|w6 zH&vvq?hTr+z{*VuUiu|=<(CVO`Z9yi-yv4wsz{9VGRi{ytI*=Od^51Pu7hfO`=3LS z>AhGzkHt|mN4TW^~qtA5l9-W4hJQ<5bQ87w6 z1@x&!toGtaV7-^4KnNuZ@oa5;5PI16EUBR8eEPKPIm*|FnjmLe_h<+rsrEuyGk^l)Oy#|^zbLVithh!r1yyC@X>~OAS+`<+Fa?98WvIr)u z5xV|&6L>n?Blpq69HN`<7^Bg^fO`fV$6GXQv3~z7>8o4U$}``_o7XEW^{6GxrQ)U) z@I{fAf@o+%NQ`V%xk?^{n*cBjkVNGQF|u}t6INC7E{s=2Z0Ixd%YGC1=TnK}ZMgWL zV~i@@>V;bD#SjJ-LvxVRz`{`ag-N3|Z}HQ>lSg3XH%b)2MZ_lr7NX6LjyFf+x)^Il z)q8G?#|V9u$LlM!(zAY}Wy;}&gSi$%{XJ^MM8_3VlC z`P~ED;$yA;9f7|W+${6d$?@N+syFH==KMR=eI&547sub8_;7`v;I(HPO4JUl$|~6Q zq9DZCQ^@$2+Qu|Skdn@ODSy3hz5qKjbHx%F$Wb38K8W5F$u5&nw$?~KyyLU{Cn+W|DeNBeYXrT_mcU4g8!slKc8=9TFaOBW|52_l~-JLTEnYHWNt2cmA2hg$GjNU%i-}zOFwR zm%HQJ*}VC7fqzG7vq{??{W1A%SxUKeUPMPd&gfPEZ-Cmyf+4zU$^gaeR&CtfXWRez z8PThcWTPs;1@@WJWiR)k|007)5f8bUYTqYwnfb>wha5fsv6w-8i<+VH1Hhdl9UUFp z-(Q-0tnT(kGJ~+{wpOC*t_il;4>Mf^@-l}1BTYu%#VC8wO{u7vB zDI>daaze=GU_`RCvbH{3DE$VIIilCiXhp;01ec*3gcLSosQ z@C~iPaFgb~{q-{{c{dmlhpvoZ5y=2I?CD3={Qfp9zgveLH7+XSV-zBffv@OD7<4)P zxi?ZzRmY(C6&#eo_SWNy>oX5Q>aOPs?cA{0*0)6NHVC6!F3x_;=}Cnu$hRwY*Yt>KgfuepPWgzcf@dFfB`w z3hQmzisn#5#Rm7wD^ndDW%(f_bYX;c5yMqllr+|*M6acc>>@FsMsLob0}p*;@SpVH zW}QPe$^Vhs6z{#ner}HRpP>3@YN%y=2x%iLJmvF_`qwiBF+Ij^ zzpIwXW$(F?l9lihEX}!c+R#4f!)s`kD^)-lMxaS-6pS8BFie#0|tywp*gr=3s_uQjxkD&^gVAX=D#v&?O(|@B8$9GEq6c zR1-2&ka#;NjTmUBlc0k3BF^7EkC%{Jt+c@yj>>7(+ww4xu0id(H}F6HGiEVbitMaFX|E(=3bvd*ca#urZS89P(#fEcs&h1XR+J zx9bVix^-MOY!0RsFRnzMjY!V_`ncKZp_*Bt-BNUX+5-ogBM`&qzw6sKf z$#}T{aCEK7e{*DiwU6?CtdfeSGD2oA9$~WI0Z^uw%GIyVzlM7E87v8@6OhgtgOyme z&na4Ma2bgr(BQY%_@ONA#t7nzc{?{40~ui}j1UAvPsFme*68!-zJM~H6w06@elNY) zno_0orJIDD$@?Uy?=!?+$JtL%>a6;k-Y;DuTTQ!JMg}Ef8rNusX}-s!p{xIEVNKbL zkKB;TO)=heRrqf-shtNjl7@dYiiEV2!lrKWQklDzrK!k;ihg291Y%{8nd@RFQ7uax zTwL%+H`t(jh~>Oe%KQHH^OkG%D^6V**?7a(-8Y{9WKv+{l_2uelXTTNbhDspG}R~y zRr3)xj469Ph7Eb&!42Gz=Sv%|ETG&cR|rb~Tptm-sx%@d`IH}xS6P;|>Y)AKXfvG$ zh|WXk@qJD061ZgqhB?zUu05e(E}}L+)I1_*?V|UwYgrORzFD@pp=^I1X8)%=Kf8(M zB2+3#0x%{3t#7j5wIvc0B(b|Ye;^`4IrU5ism8eKou`{hv}n77>5pl_(A?Y#)s2n3 zD#R7#<>ZCNyd)fW$aIN$m=_V^J#+!@zt}Dz_YHTjJMa@HoS(JCbeKuj)+=Ik4HLQ_ zS(AP;)^bbufiudP0`bFsow-7;&Eo{L|GisT>e z5}tvt&~I00)ryJGzn@69wFOTlzyU5%HO!zgb`?j1ajEIoAHK-A7k^7A4@EpaFWbSR z<95NH?R5aPJo0+_M;;Nw&u=;gCI*qXF9*R(FKZG3+aXFx>;$xu+c8VV$Qxn?S4XnV z%M{wYi1HDJAJd{t15PgW{?4`Per3xe<1JuT4T#$`uBdktzsCvFVMJOq^YxefDD1rJ z-bb$_K!gIuPXL!yoZ99K7g2tFmdO-}=Ldwu!7u9jb!W8;##lOXwb0UX=rh;z@sVWc~A@$(;@Zi0D07oFX z+~`9Y1_ROWP((-%T{xO?afSGuZ$AxoWYT#vBQnBv52nS`Wyj0gR&=J3Y#oE|2+r!0TXX$2O^v_d;ukGcU$WB z%G9m*ieY@{yq!IcNQpT{_8VTwRv93hwN3XWS1(@&p?`wBbsa5!`}bABKfZ3C;oXyuN zr;s#Q%r4rmKBMdom=l~xE`AUHegqlgxa=GqHcRrH_h<2d;_zCU7 zt)}R2Xqk5_KJBr@&wW54K{0TuYuN;N?feuAU8gt z!zNkEI(EwJ2Q?f$(*l)Cn_`wJxTC}ablU8&N1Z#yZ$ai%Q)?MI%kx?@Am}#|y;R!o zJP<_!Y7z(So_8uuL?m_aei-^MnPUi~>jR zE_PjSmcw`z42!O07!bK5$j*I;p|C~SDXoqEYk;1Ef;^aAAfn@{PI{2 zAH9%ozeF-iH?m?^*y;Yi;_kE1pk2n^%?!{JNiw;7@XVv52%`Yrn(Bco5g35I8Fc*G z#HEtwN>mI^IDTZe)jwGS$o@l+=8uOs{TklbpwLWGDxJoQ>?JjSKqCLw8?(RQYQGR@ z@A~#M;|(ThLFMsZq`af!b;Th^lnPpql+o+*i@fE8v|mErc@W7;w_sTQ@^>J;0~)yC z5cRL-RtKDu6b1@bq&n`gl`FZn@Lb~P^a)p;7PAZ710!!3W$ zu37pUF^@Qq@Ak{h^ywa_D}-5qh!Y5)k-@WZ7tiyj%zYisg#MrHyA3>Lv|UpGT1|?2 zIF_`l4-LazMyLWh%xf)eFwj3gFH9v*L`AJ&y)x{QVQX=L3?3nR&OU^V-H-@}9KA|T zl0Hs5gCC6;cH*}917A`=xkE`$ln7M}F^+0|VmrJ*RxIc5-@hD3Z|Rdud4EWGlT|nM z^2b%LYy?-fD{rB&FrCc-k9^>$(9r&5@jzU})3T6gP1W3*$YZv5w`n$jrtbdDV{u2T z`afBKRnoZqfWkz?;gJ*tcU30C2W%T1k+pht{hd<%Cwc(06EP!C?7BbT(^|$^R)}yw zZo;o=ZkFSaGppB@{oksv z2wssvDhKveABnI+VbZ_mw2j>y##FrV$(P#M!~0HIiiFFOjt`u1tQB9&Y5LEDt)8%Uk|!7flPJq zTTxI^0a$@^g9m^gevB^=)q**m=1GdKec^1us7~eC)UBd4*`RL*_{&x#7(wKqh4630 zc449W-pM>kz$4C9|6A^$MN!!NeiD!Voym8siUHG$CVEV`giJJ^Wykua5 z(p!W_IYz^b)%I1~EZ&z#>16@g=xuM287H|{pyV6{>Kr08zw{Rx?!`bq&hvb~+duYo z3P?Sy=3)%-@sUOe0pE#~Drd~5N*gP3vXN!MxZg`AmUi)c3S)BRdNYuqpey5WA4rGX z=X+i`Auca2FOpI_M}Ivd8O|1VYm2^?EyRkHf~Kbq4i26=bYw_G1nS|C74z4DXrQNN zYH`y!F)Kk!iE?uz^XB6t=OGiA z;nWN+j1xu|Cp~2|v#fCIbB5L7{-_!u5zN948?&(}SwRQ;?=j7Yno<} z-}bmMMUrXJY!R~O5%$j0O*d_$c^N)VwOu^-* z)h_8--5h#B5^*tu-#rY{pjgbdhktm5eAB9XVUQt$y7g;zrT5bz z-RN#;aaN8hLv_8qe`Mr4i+V)OB#^_~w!@B>&3ZbzXnFKk$B&TGad~`=qb>)ylKlSG zHL5;W12q{dYccMmyy4_Uu55Xp-_f@Ms8LH6sN8%u%RlL#<3*;!6e13~$gCSWh-XpX zR&+WG!Q^oIkK@E6e4vR@UcY~x_ygvUgG5uOI0(zA#v!6UDXju0RPax>aW@26!>yIYJPnvYXS8}Z1C&c7 zlQKVaJU&n(0HN9trq|1jceegxk3Mk4+AFi$fcgiZqdjXZD#itfJc5lqkJly-K;i=k#)I;n~@3gNO!k$S?Lw5}?*X>4tR!Susl9%!HBvIh-l}EVH4!`^z zaMA+ikFWQ|H?Q!Q_4XH1pbEx}l>I$N{2@GFSyYfjxdhNVg4vKk!JrFOM{YYt%)7s{ z6Qj!@n`!9#%wWP`;0Dh}%&(=NH>f%u$KwM#mFJpY-xc8hk;KkHyPerE4>!FuX0NNt za!IJJ8Ush0 zoR4yGy?{XQD(Ggl{SQE|bkvtF78t>)Cz?07ga4<%o3!Gto&ijSJ(OnPS_JQnsVR81 zVLeXfrifw&Js%+0@6iF3XcHS|HE~ECyfq##g`|M)^GVKb_O4d&_IHf`VWFo%qw!IA^p#uzK2c>B}wHzVZ7jnNkj*|ge*TKP(m zyc#^){S9i>f=|ue&w9aQ;kPR{dTU6do>9k{V4aY+;mVIKS|&xKMX;g5qt$)oR3lWw zTdd4tZ)+<`Pd5(6p(CXLcT0P#_w=-w#Msg@yb8m1e}Y;yr~e{Bl+~_rQrbMbIO_## zSpmr}VJBU?F>2$yXQ<_6$9>6r)$_<|wV--R6se1jB)%JCAL-n|N4am>7mS-RedVn) z9!TI7Iulv?p!!SPhv| z#_&+#$OvtAZYG_)ps~)a!|ly;lzONd(EirilPI73I=mE132U7{tmBJMu{b#3;gWd4 zGh-z;IL`?KHs1Z)g(vi=%hP-c#u>SATSS3xxkL$eXPIc*x4co|Xntg;qH~LL$2ivR zrF4%d-K;UY^x{Z%nQ@0$4!L8)vNCZn=3+%G49+qpVL0z!|M+P*6J0jU&fSxiAvikb zrp(KhrV&tV6h}of9Ap;nH*DMQvi0l^rU95(D?gPaoPn@xFkU((m4@|RpODUI7h|AK zyH{&tFxwjgM9;12$2rpK!Fw~c6Itp5rE}-B_nzmTlU{4hEC6KfN&;eV9bZK2wE)W< zFmx*pN2V?(+Z@V9ExTLL5%vp}nq0zVOq2vax2h!}NUJaS>hAuP2C?y91y23@oQ%jD5-poxrNl+wd^R^HQ44grU z%dU9rnsC%g8ue@fd^C~MwHXP?np+Z3ZfYItg2_e}?pa+u_bclauLp|ak))=Vbssk6 z2(T_Ub${XMU3g{9lsW=xQ6ji-ttGIivw%PTw7D$w*2h8VExFs z9C7Bh=!Y!J2`kY;g1n0er6uqhPj;44gTa%b@>Jx7^#ybHM5qtA=6UURrvBgJ_57{B z$St(jL&J+Ui*9o_G^(H|Q8d_$x!9b(4BgPmc21l_wO`7&cZ1ETY}{6gT(w&1lg1)y zSB(B$qP_tHf^LLd*>aAEDtP(|5ODw^hmGjp)?Xk>qG7S;1{yG!(0Mr-X8^kz3p@Vi z%tf?P;0qAMsT3=K8|~ro`r8Y)FX^zr87&Fzz??P`JK(u@eEAI~4>Xf7`Y7cJebf#? zzC{c#s1JuxDj$7@AVHZEX)k+glLdY`)R9wVJ+OxzXVk}(%c5p3FZ`WAT?P;l@Kbv+ z8I%`-Wu~r<%O2y?AUQJh1}_b=+{HTQe^ncHi8wC&9*GGq6JF(%DQaS*fX`bt-KCW} zU1^A#-toq4ofpI?ivo3Ag92?S@SS#YG*l|Ac(Xod;+*Sa+ zFLfAHfUQh0{*2pJb#M&&0}pDG%N@<}4B8TUHkwgo+;SS30qo68vV3<>wU1LndZkL#Pr)3_e>omLKGroaOjoU|W_57Hm$?(;; zOCf$%&)uIktL1kSoO%gkU=O~aDXJT163R1#F zffm&MJfeTPq%I<@h#Knnp-GLJWJk62BL(JpxyT)o*V(S{$E%^&@Wo9(gtqY&s7}BvZiJ$KC_*kRx*5V@+qbgP)Fpsj~41jQ*Q(% zS5Y`Kl$mQxPa;1KJRwA)fi>B97Ek}c0PdZaZ^9iNN(;;xR(gH8j>+E)G)*FFUlb@3 zXdEZ}6B3&r%!~suj;n%3Eefr-go}*4I*^<)Hyrhi^3?)yjFN@KtSCH&4pCqyBu-sv zkt-O510se&X|lfQSSzr6>7mP_Tin(Lw%s`RpFOJ`*FI6vJ1?%8ojAysA0t%#QejNw z{S4hJNEhiE#a2k`J!Rszpt=};`C#P}54pgK5($ykXq*rkTMDnzv zIkwwpn)$2lE9nH1JXRQXFl2|nLfSA0v=P%E>bdFw&6*ZN6|(lTh@L!HB~14rm0dQfkt% z^hhkq`0*q<_OYXDVWlr6z90n&uk;wVPzRwB9d1a4j})Zrs%_unTmcbiNio0^FR1VL zWP0!Rz~g%?uR@<|s%h=0hrK`(!8hX=l>i2E1Q@u;WFcpiWy-qkZE{7r2d76jyE5{e z!zePcS-*##ZK2MVt4xy;wDxl_}9){^YNRW)$^(jMAZ-@AVK z<4toX1zbBDixE!htH;Imw{yK$lDR#sqC>&uz)xp$7BSC*PKx_cgA&+e^z$ug@}yNg zn47f9Jt8{D#%ZX#+u~UFU$1<0=9(}}B!3*_zv@)G4rn8Mnb%AzIUKP4GYG~Leooxc zqxCl|>uWS>wV`21X?-L+BiA!uscC9^DwpS8sKR|Hi~9i_lR7=$h@mrY6_y>xUO4D{ zpge89Hk?UgsGJe{jnO^Z&VfKn+y7m!^ESAKI7qIlQC{eL>h#`mBxJ%TZ`}K$ zt5?Jh2K%Iuwfk>ju&sAWcWtj%W6yA)(p67xm*lym&+`*i-Bg;<^nePPOZ5;`!ux0b z_d)ac-w`ufKNN+P2@EA!_DV&W&Zp+NwDh%%++Uy~lR3sWyi;Urg+B~`B$MDJv!y+< zLWib?1t4fpM%|29P?_GGlhp4{+PQgtbU+gNU491h4HH*Wk#j*dbajQaWgFNzc_gG) zmxG`z{63!GPM>!Wz#*<5OOChG&Zr(slS*$su^PP7;?m9lJSf7|JQ^I%hlPrjH-+V$ z=gkq8eNoe{xJfp6N85NG!EU{cw!a+ddL41zcK@&bx&LUgWAHxm0k`4K<9?3s?d`1z z54=a&hp6srsHBSu<_)$%8Y47CfXiams!0pVvU!C9ZUh*q6)=YU-5)!J8eqYJTL}Re zRoE52AV8se=fxt;Sm|p(>U!*|0Od#QBs=6PUk7jkcYs00l%KG!t4rxC+~VRQHLHK< zjwjW-_)h8dJiceuBaea_AQs>tg(k_8RH;X{kLQ{Ko@9DCnAhRL0A0+v-8C#3*5WCP z+WLAIlUEr(w7I-#*1C|)VgzjzEJ$vwBpO1=A1TGPLB+&Bg0ovrees73jLhJRR4{F{1c+Yfa+%;;+Z11}(dJx#L59XBTovbr zGXe$Wi6uniPyrSK3I+N+xDVmPahCD{~+_Ozz1{g0oz2iS_bKi-U z&#+3yvvxE9Yl>_^r*saURTHoMpLe9623u9l>swpUgaZlne^ki`9~{?y=;}Za#xz2h zb}3Uc&3WFpnwKsBo#oNOBtc^Mphv$vyQG-CyrNKMN~WY7p0q_}N4g+=#EIy|m9@P) zF8@KHrzU?;l8)?0N_1`R`z!%!j_-wT&SG7MWf8(yDyYb2&2ywkXRy=cktuqB~W zp6VZt&{yV@4dmW4L8>4L?MTiqyqpN3zS~V?ff+S$n92 zvnxs0NA2}Pa;m31t(xZ)ZxH?S$c~Fd1_la__3F_JrZRSpZ4X;kvOZEsY_@9(WT4Ec zRUDVu+Fw=bO5{-O^7cF8yXe0%&`QmwT0dfjuI(dfTLXA#uo7kTOi{$~AcW>b`c+c@ zwn3Z$xFm4i=r17OBx7N!!mCeYtk)(#CSl=EB3J$2`Ad{+Q6x~+v4cvf@P~6^F#;SD z&_FbfDT%l^i0IesjN?stEwE`h;B@9xGjMTK1CuJ-4}k|0>yDK^m#gm<530ZuRe!%k z0I?zPK>=no9LRs;foM^VWry+Pk50a^-5p8n6pDntFQXuCCeqLq`vix?P<6%S|V{WH=9MjGZrn zJuv$II}C*D{K56600XW(i$o6k){8+@YHC66PeLDUI2l}jYdstVWObu7i%dTj5kA?> z!O`9J;obS6>-Fy4iAj5IzZCw+jN(-%h7|}trh<#g&hC)r=E_# z@L}G@U>bmy$K(FazV$s>KPL|wV5rBT8IcdCA|w#1LiyZ}C-{>&tc@*763WKR6@Mih!C~7|`=>aCy+L&o8Z+7JR98@gYyt2I(dBK8% z*m`*s%I$niuOBxaqm;dJg2b%jX*S#;4D>#6H7rSOD6bL{t z1z^P0Cm)D9Ee&Ibv0x++drn^#Tw6VFC}k3AYiosb4gm9GU1Q^|F~P?ByWq*mNulNN z{XHk}4Zu1A4olz!W`3o{v`=6k0%8?~8+g|Pc=olOo#8BI)Ax*k8dp^XNC?0kmA>U5 z-M(hR9R?e)Nk&zDut|0%1cGNN7D`+Cu8tGJ9TT{Nk#5)I6%4QpLV-!K5;H0hbpYc+ zu7RccWZGgje1~MrEdIfFcm9Ry6f$meo6s)T)w;_f zo7aEeVlUGt1c%=q_~kKzAw;CDyC&3P{d2Ck_kMa`^dckfm<(Dh0$8cfG(J#osOA%l zBtaAlG=P{N$D`6B|1ycz0u+Zy$quRd22W8_Mv=dXMD}|Hs=vh1k2zLNI9Wy;Q5EIF z>OXcj)30yqOh&<*^Fq13380t1@$Ul<+#(EMtd~rY58t3Ez&y!LDFVetFw;-1~R(F($L_I96{A``(D4CWs_kn zS+{{QOLkS-;h!TN2NO=`r&^8if9}>fpmwsF8TG}MQPD(JBOQHX%kHXcpQ2tEDpMmz z)feb0TY~4PRZdIBBcI%HLfEnBZh;2pdU`R~NHnWymk@qAyRn_%G!$PjBZh&)o`_X# z8$od#aLR7RrrPuD9_q7u5wJpgDJ|+24i8X8C5Q+&w#Fx~`vcRUl z+Mr{=ftwuW%{UlO{eUg2 zE-GBGO*Dn&WR~7g)qwydn@Fma&uUuHJH0J4#_X^i_P+aJE4kFAZ$dM5fJri+-hH9U zcsKlElzP0)D@k1|#*C_tS8tMkeW$C7xd}@orCG=@XdNgqjJ#Zw>oa-|eW6_HbSogm z&@#i`vExaDu_W<1rq;ezd`Bh%>JEbLg0nxpE&rET2tRxFI)d5E491s<=Tx1aeVG)kI>s`aGSY zc{Q=Al}m5C^I}ZPG1A?QRB?jowdSjunfC`Sb>m#6TwPPk7KMsnS`!@^d1;luf6n^i zsx_Bas(EJTWaCk-^Lj2<#AEXOA^}gqo_TY0>4w}zH*lh#a_YTlK%9Ut z@i&AaFGgi4t-AqK5A2@ph$m<0cMF9 z!+{~^=wt?Mn`TiY#MyUo#uh16fNF%3pS1n@bmP))3zUEWe?9<=0Q0xILDI+cpj0RF$$K@O)c0jkQb8KBdcm3DUv})h=F&ccd zX%yud*;5r zbyPwGY)!(?GWl@W-Lv_myla#=ojh)$M;bv4tXx|M{&xq5QAmzOc^g*FW_Rq+db!Qxvqp7T%Rkd^Vd`O(bmlLv9zX4O8-PK^!osbjXV`iXbmTAIxJV@b0u~y)4EB&KG#0%^`TR;#y}Am5 z_mR8`qb^Of3KYST)wNDjSJJi?v8YEtfs%>{mu*`-aAeJ&pxpc^7MDallJ;+rYX*!VTo;f>h=TV;~u9JviG<7x% z7ww$(j=!lBcKmSi{X^WBf$)>UNj7K+hk{_cyH+!_4px7tGTVXdf4l&uZ=+};6r>8E z*^|ghdV7bv>(8E6j^vFx;KL&Fob#sy_mkQUt+hd@gzYcTNy91f?hdP2k_z!*QL-rU znvvwfTRXBuK!dJB@tXq7D6B>+A8ON#_0mw*E?=3alD1SXe{TN=E63ZU4L=;L)Ag#& z1^P2;vT8cejEv9J@kkmg^bA-%NY6x&&kiiuV;s0Ud{Q0^TIF+geV$6X!UCl#{G}P$ zll$SWm!3AH`%@+T0_GikI+zHPK65ZYA?n>duP8ojcS?5JoU1PQooM;VUg>VG@LhaE0$+*T=&L-p8}S2VL8m z;PBNU(z7(Ik#fF%&D5D2kLxi)*Ms*5UDx|bm*5$@kfW4^xY3f0gi%K@Bnbd-bDE2I z-4NZX2+k_=>ks!a@H~ij^7*+Xj*i3U9By1rlHPf6=v~#~d_u5BMfdJD(Y#WkgO@^# zkn9xAuHcB@fAM~PaW(PrWWUMH*lQ%;s!KBQPJ+?3j|8F>s{LqQXZk>z$a;LTUnX*X zeRf~5{`Hgzn)}bRuEgC2Em-s`;F4j@Ei|x$P~H6N36DxzVn5RER3GO8g%ZMBci4!= z`oNv@dHahCRL+45F9UEl<{V5}amDw1?lZ|b|IWUvwKeNpyRrAyTz$QKA|&2I zrp}4g`mipgsUy_8|17ZUX@u>$xW4uFV6Y?fO7wvpeGL_>?~&wxmH80?AImRUvyi7+ zab0Eq4r$4|eKR4TnDL;gU$MbLs$KP@dmN^beJ3QdO#ZnO7&m1@JF>w!7XV*AS+zmyux5En)$fn z-7{j3EIp9>xqFbEMH zN7Ew{KW!MySNH9X`L}W))(fd{8hX%F5PpX5h>FCvO1K91C zbqyM;!@8c$Z}>i543LdjEvIDgFlCi~iYzz6q_MEXD29Oz?O%gsj>sj6g~}dI+qqg0 z;wSX=lD0|6>J|aMUfy%EAY!Qm+{ik(9S@u%u==pzI$Z1i!pC1>8g7+oWtlui96mO$ z4u!uA@0Y7$U#TNDR^k)Y0J2L?2@shc7=UVD;lszrH>@->GRotIFFu@@Aq^|5_tVDN zYWv3=6h{_{GIrAUJL4G773^1S>f64iO-mXr#97!(^5N82I5Z`L2pNq*%_*wa?74#I ziJvV;gt(lM2hmf2sKe2zc7}SuQeP9hUV{7Gr`ISk+=Ol#gb#%(;Mk_b*p*R+8kaR-luS1 zl1~Z5btqu{rj4UlQ5^Mq##%R zt_A&!r_D>CVmI2YCsK`{dyE0>KCrg$IgpV)o1E-?*>)@D_@}r z%}yx*FRos1x?(t?#9+%++iMzA zTH_2vE&30a)0VZX>M3K%?gxCe@36j?UlvU$y`P)<-8B10R`esa&=hnNHq{!su93lj zJLt`8DDBMhRNpby*8632baRgP(Yr3RH2SAY5eiHw>HEaCU+^fEy=3t=j4ED;tv_8- z&05o)o_2z!WwS$xRt))b66DFpF1ZuClji2(^bK*8po2Ih_$pbl&Hh}?XgqDc!S^`^ zdY^ZsN)dU*tgTZnxG|9k1WyubZ(HI2w%h4Xv%< z!%nZetW9l7DkeBOpAwj3!j92|YF(Bq((=h=ROc6B>pGf7bnH9FfEpFgb2RYz$2j$7L3og#PRmu>UlT!_!|@AjoKaP1gX($)8m{aL(eU z`9x`#@tVQgEB$eju3471JU>hF<(EQ92M}k(*Aq!84zJj$dO_=G;aW98iBcEdzE8<) z91m12^Vba1#-l~i)T!@eb>C3Pu!_)#-~%l?AEN8(nQrY8Gmnle_&8 zQa`^!?Y(`k-U9ouXezM^?OBggacf~boDNXaBpXx}W3ao~cv~l8Cd8CRRmA`b2Y|-! zm*j8x34&VM*WMpz{sx|7Jl_-^xu0N{cl>#{KWnS+*4UGa95HjVf0N9u4G@)8RZ^u5 z&n^n{#NtnQy}J^`~GCYmaKhwG`eDMe!7_e>MOUA``~aWS}&nb;XxJte;e z)a?FxwD)^>ppLZqE-_>%`TX8nT{NFU92TdVU^=JZj^Y(XDHexBb=qwfEb#aq!-MKy zdcM9})0Cm!E|MTmJsd@RId~mJ4TsW0@T9l>EPi1VzzPFaPY=ZY5|4fmvj)YJ(cNGA z`1S@}MxPD+D7ERkhiYfnaqStT8bRCU=2zCBul)-K?}MuXzaU+bAYvcDLNOwT7(-xC zyoPuwHnL*hHRfO+#2~_rY=jw4L>inoSB@@$>Zz~1n?Ww)@p=Usy2)BwAD7=#rx~lK zuV`CK-@9oV(_8ntA>gbz1NO;u6}F1mnx>YPuu71(&wQtdZa_zi95&a})`LO68Vi*Y z!A`T^3*M^ZK0V)xn9rP1m&PxXzs9ltFjx%@ zk07FsS7Y2Ys8lW{htodR%oUBePU7<5xr;3ud}9Yq7BaR%F%P0|Z3InR9qDIBV=%Fq z@ih+A4Yyb;XM+BAbbJ%n0)Hm9Y&Lq;CqmhrkjvG)-^Rht&nMdU6HtPkWGNgXt5i5X1)?aggJ02~2EuvSw6agZC@?Qm*2)50 z$$J+Yz2{GdP3`Y`@)Fd;$1j>CEXCrykyO4`M$z1rp9w9sm5XtW1g`rMC?Gwx^Wh^I z>9tf@4`UZsSMxSDjDgR(9Xl*oEIKGA(OgZ`fF(T&$)*Jv-8l4uBa2Q1r*aO%G=Ni! zgAzSN^&pDsWw#&WgdHrB1yT~5nEodf>i6OtjD-=0>i6nuZ^ab(!D$*t3BuJ)KvgRV8O$dwMxk1XyOAe%wY!0@l+&4iT)t=m~|jkj5$d0zE+n1LaT zRC^6+q@qH%#V0sYgR6`KSA2|9#XWt0n)NK1LlIx7dx^~*W%vha`Zgrk$rt*N%0U*z zP0!DctKt!1B0}9-I5BY5w#Y3Wrr2aYtne>030r**uGYEQ43eH1ZaQ_dNMZaUr9M`E z*}@XiW1B{9QXquwW!FJf2<`~4xUZ&0V%4Gh^-WIWA&fA!JY-4xf@YKVZcglLa z#~#4Q9Xq1IIIR_abrLXBqI9$6of@{2*6o)YJ#$h?c%qt-pv{)w)uqs&1N_&45USAD zb-%)V8z{U3_h$qEy2Jpg4Z6fs3IQD^l)g0jyZw4^a7z|MTi#tm5E=MQpNW;84iu@EXOE-e|mo5xmY)YLVt6m)Hvm$*k8 z)hiVcFogjX?wW=`eYxhQ20=5ag3#xqTX+Fz&C)WztG!cCLd%SLVEvR+lEv#Az_fWUZ9RI0>Ks|n_t-(IXx|kq3DT5~b&A9c-ODgo9NzQSK=z6- zoyM7S+GWR=X?BVcR!+t2!j-e@^a(#KAs9ft=zbTp2F0r2_5xCbOp4QMAJoA`XXM-* zz@z_IoX3+;;b^5S4<`&X=ElDUc9U#42(_X0;r90ri4PSYAG#Aj@}XwIm^FR!sBu!; z`R@4JdE1NP`@zSaKQFZ|ADJhzg}P(m0G#(sR}NFF*Bvcgh1}~=?mLYoXAuwvNROd4 zokjF5>|nX^+9w5IPw}b_*RxP>en3j>=Hlb63%IcDv$6yZ;cL)`KlV3XYgYX~Isi9q zaQ>hrXQn(QI%Og(u)X|5_KAh`X05bR21F!!Dhi-EeJq##?I)yzbk-!oTGj`$rSO&1X$5lWd#1je3q)STve=ET8-^C$^Jeek=3ujaDFI5^o+`RL!n@uwxjgTW zYE%vhD?qOiSq)$`B|&*cFIJ*-ftkw4LgEeUf35m|aZzTQ&2InDw?{X45^qWa z<+Nd|WUAV0T@MM)RDE`@Uhkf3uBof@3Ap&!luGI}HlTty!+j~h$PU41XQ_EVgYHv_ zgeGhw+F^fWmH}n8?Qp+!Bk32`;?SSBEl=V^&1hPitwaYM8KK=$*WId2kFLg5csINW z#ynAjE))L$Qht0vkjmB5Sg!durLAuE$VKbkTe3%YFQOjRj>KYG&-72rM|w1lUM9l zxL9xkmJ%;Nr0R0uL8sGW#PEQ&K2iHvO$BF6eF9#hIR&>&bNlG@H0?O;b0F$lcapw+ zpG*E!QRqCO<$f9^h3D4f04Py`9FhMU)n#Uo2s#be@M@gAYGI-@m&UQaf%sWa6_yVn z2|jXjU9att;iHFi`n!zG#!82MXYKcOePFdk6A{3!Fm&@uW((euw?<&+FJW2Ak-@&A zxBhl17BW*=-aH?#fL8y;GLMs@L-1Yb@A1+$ENo7R8Hm-yG8{uN+ACFiRYYcx4OAq@ zcl!WJQs0yiEcklUU8GlSd%>o_Ry+iA#5ygLD|w2_YT!Z=UtKPRgxEtomArPdwE})M zbwJeYuKX(R<_Zj>XfZbfa#8`5N zP^UeUTqZ#EbM`#c**>gjmsmn_tG=lzm=WPfUs0eue&zLd?wOoK`W|$U3qzFjOwwAFE!ZB3JzFfbAmme@wsj1V zP)t)YX6b<^U>kA-JnR3se}~xDUq(ho$YpxCI8W*wKC%I#n!7I?}(6R`8TII(e$*=3yYH{3-^h3nL>H7FEC>saO(t00}Vv(IL9? zKQjRHbuRCpr+FnHkPp1%)>E+)T`8ov5xgF54<(L_w?k`cr zZ*h(({&i>zOd>A&&Px+l|C4xM=i_4IvY$yX@BqHeTF|>7w@wIudj+ehG{)613aI|_ z8vuV05_hLCWR(HR-f$qqmc%@u%051`20zp zVU1*2T;!iTjSxd%$!#unV&0b(ZsbA_X2%;(Hw7>F{aZWh$Lm{%b#^#hV_~&V=A%`4 z2M_o+A4C*=`)N8=>!&`!C|ulD_<{o}ke6G|0`d+oR%TqbWlp@PY~H5czG2LC_CF;f z@JUn)OVuH?@iwz!rwHf2F7!Btd8mgr#MC5?Ab~5c*RRH=Y;8qt1b%=|!rZ5I+#%gI6) z!G>8Q);snP90-mmZTP^Kfi+g}gZdFuKyJmyO)y4|iaVYG!cS?_su;=nTv6aoRgTqt zt!O_*;8fhO>lAEHTo-1TlMVOf};yCYit%zj_gr9Inr+k?J~)EYKqH{#C5@57p4XsbBgK1o@f>-p^3+r-;) zuc!_@o+O`qo4g@$We+_DO%Nrk^$Y81%+yp?0%rf2qa?tz`F)XOL2o2}vhOi8EY3#)@=b8$~SOyfvL8Yg&1oR8YCn|U7xv)vMM z5ll^sX+w7IaJ;Lv{U|YAIq~k$Gk*Sw4kCDd7MFukW;|BkFR+noH~T?IcmX9IoX^1i-5xDfc3c8CAlk@Uh=>aA+BgMSJ8rVLE`ge64F(FmCzf zM9A9KxAd; zE38*lUJeGL$_;u)C#3%e6aS021k?gW`w^zD$yE=QI&ai$p(RiP>x-7jJ6u-r9P*dN z>E$smG$F>aKJbR6lT`rY0hh3sHh{Vz0~P zZ+py?)myjIhQD9$2pU$qT=8EB?~w)pKXH8L#Swo`11z@-=B$9l()hQ;E)|S~LK+~+ z#f}@@JJTTaa0MOs`5&9p+4+XJ;j}Lt9T;GHnETdKnlWd$p?ar&NEXO6uSlF^aa+|k zxkf8W5r-j-;S!94B|)S20ftZRm@i0D&~6Di2Mm=t*ud?g#BlCyL7*2fgm~vgP{5|| ze`lMe#(%$9V8JKp1u0Tk$Joy!#mYk8#Fr)LD1=wiu1UM6g)w*e=f{*`pOZUg1w&Km zxCOfrdj>OM>_3>Rdvh$DPfSycvrTL7@i8qP9#BpmkW@{|zgByLQGRB0vlSp_MXiQOR;D@#nT@#pmtmBjV4h zR4^G-;K-v$kx8WW=e9|Cst^r*&tMRtf0FiCg&$u4RHxM@v*rMI)t9qCrgpaAY|5br z%Rbxs9Px6>y7H?X?02-#&1SzFn#Np}BxVAh6zzjAc6_++tW58h-axj*oaMJLB%DHc z9WGPlAWqRInzTgTZ|e0~Wk_ZDs9Ak!C-7{s+NoefPj5U{j=ar=g0IhGgd1?pWU&Vz zA)C5qM{e0qM3m9?O&?=nIjzSJW}ngDnGdVnZ0jb%X)b9mfj)~nAyei#7n`d z5M>9F%&LDOI;d{RH#J;%eLthx$7|4oNV`FbicE#aJz79D;In!&f7{$WV%G01Pa_tQPa}+9? zR54(1=*+SZ`it^EW(Cg@>IPv>&^-xBdk(lMnau zd1ci(d_Fa?f?5EvFf;}54*T=)-d38La>{!>wEZL(;$aeyhjzkk7@EM}B|D(XVwztkV@x7_krqJ4zKaZv=k6N{HvahpG zTdI^i2iy1(slMJ`JtlN$xxjZ$<>a9E0Qb` zDwkvN`#1c&daN3*2q%N3yN>)cZ2UsuD0~tV47l_(Ne+U?`2tX(;QxN$^Ym2mui@1q zlsQ5Avk`fER46ci^`b72zF+hCM}G|g5w@pJtUoc=biRX21_taIp8yz56rPw|1lXM@ zqv`Fv)Djr<%Z6M#v==)0P$(wmxeHsmLN0vOiaC|K?{AuW<-6VhG(M7E>B^VL7!x>~ z>Z2@wA4?xy`pBq|&srfCUU}|Z=$m(V2LLu2?W+0z?;M8Zstz(RFfa!~q0~s!a8m7S z12+`FWY1+WtAo>_{K{Bs!O-j%NH(ShQ2CcOHq2dZ)2$b(Rbq{=$te(yF-#>B$Sw4y zE4g4gP!2GDzf#jZ#UmJ%<1c$kR$shO7a^S@37v7f9z$4WkQQYvsiy*CZk97Xwksa` z|9Am(g!JP#|8~=#QZadc0?eC$>9AtfA_wFEY*{ZF+S+& z-Og~`vjoQW_f3KD4M^XgNNG(_sFNNMU^%ce08S+rUI2J={pZ!YjQc;M|GS*<3X47p z34Ri<2)9JXy5va!d$wvt=q9BFTt+tTm5QJQGPX1i>$N_hwLCHdwtO`tiZAepqzJI1M zNFxpDAGmJ_ty>IPNEj!ia46186Qqbgwv20vcAW}5@g>rmdfJ9N*2%@omo=+v33Q5Z zy1vdKcY;zoFL^k}U0`%F>KM(pps-kCk<(BE7sVp9_X~qcu?WWi_VAx6C9@MpI=We% ztwc?<4Vw>xUHf%Vc5jt*T|q>rPV_0#y_=Q#_zg>Fx-T}eQ8{aBl63r*cu3zTFgZkP zv8by_^}nOXOJiZ?eYTRxqQpfRhzh6iH@VpRXCol)P%&VaARWs2Ta`gBT#XPZ7?ThZ zP8K>bYFgnc`7<3%AZ|-7XyV5p6I48MMKoXNdWP|1j+W(H=2O#hGf+R3uat%2rRAm$FB<&^?{vJ z>UxB#;2Y&{tCawT@T$4u!};3Djz*BmEj1;@!iEdDJ)p7r#!CZ7PkQ0hjS)I8$clt@ z0x!XrN9bnV+;Ps3aVTJ`xO*PN8t3~&MxU?YmX6ryIe39+aXiV9dDH`%xWF$9YjHim zb*RlSP^ew%bpNWg?s=iNo$;MNeUmSC7E9bw-oJLjjo|lhx5L>~oaA(I=o^IksXkU0CvP_Ht7IdGhjv zx=8vaNrtxv9;3-iJ|S8~-SKFfBVjZTtiLXr*@TJP~S zZ1ECj@gPkf#?}jcO(RVN7zJLCe(L*tQd85+A!$E6qS0ZzvBlg;kYC^ZJ=Vm>v$M}b zsL<}a)Oo?0_CP}ZNDvT{caFm*E5t?(3J4`?jpdHf(zCwlhPHP)?lYIZMg`az6gDtD zDIzqQS`}By4mr*Gd?V2I_E&pMZ@72N`-@hY$#cBkI~A4q7oTwNUuJyX2Vfio%!>Y{Z0SIGP)eZ5|P zx3{m+K5GB{ZQSE}%v4fc=)3ek41eps@KpJ1ZQ^?7JnBq1;tQ7XZ6)|_A7PplsV!V^v7 z-2%g}Tl@GxI7bYTfl-kjS-K+38{%_2I)Lv-ydP+XsN3W6JIQr)+F=Z;Mh|5n@^Oe) zFBm%L@*tW=($u-AU%8k$46*2#n7>E**(~4e8?}C(#%16i?JejHZ4IKYPepr-*s2xw zBa&$*b% zh70QCBy4mREp{I#_|UX_c;g?x`MZD(B@J~yi5C3P>e_mNI76XHW55aL@jk~e z@VRyz{vN@mB_WSZA(4mbQ7XM9s$j?V%-5d9;|g6|i{M3u>ln&hiSFsz`OtCE(7;BH zAjZ!mJoJP4E3p_q&&W?nW$mA?U|aa(GL_1jR8vLbo3+1(?UO}SG?@ni;Ft%L)1p*$ zWDBN(q&LvK;`Y(AX4o>#16{#R*n40Lli958J=M0|-OB7Eb+n3z#wXuf+{{Ps`U^x* z99|zCf4lz%$^Zl$a$3{#o9N|gafJ{>Xl0F+{e<0JqwmKVbut%#2|E*7&^d>?I#Kan zSyVL=*QT;c)a>%>k5N)EH8N&YQEzG$nz&@NT~kS;Un{mw3+Cf2G9jn;zh&UUzK>87 z>_~j>c%!LW%yTYf(%_uTp-v+g=;1cBcZk;J`zym-&HF$cMyL8j3GqaA25&bQT7_eA+roqUB;;%tQ!YWCcDy%s6s9a+FO7&c;2PO8MAndM3 z&nTF%H`t%ZJw>}SsHD`WY;z8qz2^YIrbDuQs!zwhp?(+D3#tO{RXdCgN{OfNmbn<$ zpWJf%{hhF5ov}nQyYw8fgiN~%OCp{{Aq2n!*4G)AEs@|U44%b}hCyDn0|(=Oi~+zG zA=6d;x)rOYu>4Y0y6S46#05Ac*4AV>Qj7NTVXz;QgJ05yGKcqB0c*A*{)VBqcjn$X z+RPPBA)uut><@kZylBBbn3xsz!z6(?zuZ^W-I%f_>uq9u7JQs1fS5ZCC1NM7o?hsR z{6Gi`Xj=wC``QemvO_M~d-!7f8i-|7p#ptf zw0v{t<~S3Fg7OE=678&}!v0O9N(7Zv`4CwSIGJkF;n!(2>G;u-csu-*o-rC0^*)h> z(rISs(@x@+tbc^_fz3mF z-VG>Eh2Z7VU0K?D_dY-9K;Fn(x)i3VoUteo!S0KeeZ!i=BlneK(B0SBctV=_-sjwP zg}J>4!)C|&C05hAiiMz1*XKbGA;#Y4jpnx`_F_v#?|u=T(q;pXA;vyfC%&P19+dewh&@$5IqkqylKKJ$F` z)ZKR=fBfqySX|Gy)=pMX{5M%6)bCZXGy+kanqJX{Pt8rf-CT{U@BO zxu-9%e-q&pHg1%DcU0y1)ia(-Fls^NRv#S0h1$J2?amR}zhE;sQ?^c?iD-2sB8`>#cJB>AIH zfhbsHn4QkQ{%Qrf);j?eRE;zA%^EN#bD}}QnuYP)JJR(*tP4JuTi!4ijN+dhF<7MC zSY(y$n^8#jM~50t?I>|{43jDJ5otOSqCOAo9qL|gialHwT)cac^!)&2!Vr+8+WAzPxvIWO@7{j*Y)=NXvK;QUf z8A%m}&}Ub%F>Mm>{?Nr(R^xkRH*atQ+Mdku9ZX%PdnAo6-wy&Swe+5UA}Y<7w~*`pJA(yI(IhC zLz~zq02_p+z==0@GKK%e)LDi_*??bO5D*ZR?(RmUVWey5mhNr@q(KSk8oHHE=`Lvj zVQ8d=X6PCkfqi^;|GWETKF)B>#oW&w=lss}^P-Qra6$O4hj5D18rRSAHg-kec=dJ= zSXk=m>(inm1Gq)GcUUf8f%_3!2$BPU_66e6XN)8qMlB%|&R#5|e;MmN5w7CVCt-jw zXNp(GVGI!2s96Oqf^YwmT@Y!6CD${*i7uEC+3lsagR&cHp1&Ky_f+~0^uT7pR{gvy zW-UPFW=v zf340WUQbFR8Q}uvgWCCSrFtCoREy*U>BMIhU?!T?r%4A8Vs^-G&cFAU9NEy^_-h;J zYR^5<>bFT}pqAc?0z=6MpYx1+yHD(W0C+RJRGeGo$}W89cC`D>K}+}i7P>0shbr3f zm(XE!NL?a}_k%5dBn-Y_;s<%WK&~KDh6Mn3Kb`rBqWn6SA6i9{!Y;^aM-cTtp^UV(CH-w3+t$(NN!)Ykjg5?T-qq8MP?`7^p4%GME$KoxBNoD6AVTV z_5733)&xN{<|5*YPpfGb35bT1Yp^P4Qj_npOAv?55{CC6SQ{(w2rW1=8voQuN0YDm zdTW?B6yr0f=r%Ok!m$^>k)t!z)+0X3hbGIL{nRJNq`}X{RMXH%Wzf)y#tWeqmzN`E zvA_JhM=z7cqVV~gK|$eb5=-YgXRLG1CRv4PIk^>F+$YYtWY_~j6AGX!Evn?o6qAW? zWjyO7Epo(tFoTNiwP$C0!Qr0Ys`~W98I~;eh!TS;34Yo5m}1 z%3e}?0sli`Q#uEBDPapbzT~(T>{u3;_|&xqP0AA+(}N09uht1-OfA+S*2@ zrf>n?d%v3!KJO{$4NC>qM&D6iGK06Md>9_`=C?W9kB*!4)sLqyvPHWF;Z$AmizB2E za+xn$o`1i~1@U~h)_1&W_Vz@0{uNxCl%p(}+^_2(KOf){8-FS06FbEq_)#TSzmFLG zy>GJc<)5G?%RZY*vgA~}{Y-u9X7XLy zsxkmX-TX47V(t+<&)o8Hy=3|6X90e%`k~AD#k9#9*JB=#L^BMfnO6XlN|`E0z5x7eaw5=qlr)wOy{$t^EeIzjgXeC{u)mpXHx_~LdJ8EHz& zAQlrJsIE)FzU1yF57&v-s3V%oo^YGpOM!*`lXs+r{Y8=o&nm?sh?~vpnx=-4@Dsz$ zkpV@=Y~A9?MBs#-uRC`4Qd7uLDB&G7`upG-iHg~0<-2ubV-^3RmK|O#;)CvX3u2PE zpWoBG`!@2*D^8|#;eYziQ?}T?!fzV;rspsOC@NnUf1)JFH$JN(uwwQIK}M#Ex}_J1 zPiaQX{fBH^es#e0=2Loeh+y2m`+PtQ0KU!%!o96{`M1w3M#3S$w7sdV&G%GSA(E>i zlCX-e>%2yPx^#Y0-=c~EQ&Oqy&AwVjNOiezQL=El^hHWIr$T55GkWbJ_FYfUfxwa| zMGeXquW#Nu3hMZ%gN7gYgg$I1X%jl9Ff^Q_oa6lvVj0DCVB3!ThXj9fSS$8gFBN-; zCTSQ2ig0~h`Q>Lkv&~$jz=>)FSR9T5hOB3ck5|5Uql)`aA^=Em*R#Jf*X=heX!n0k zpv=WgWHsd_sTU(nAYcKea0{8LZJZhWJ}?k*Z6BKsz^6H!6X;1q=I;O!V#a7%6LCDQ zaFvxxuHcxF*UCT!PsxH{YaEea9lIH5B;&Beu;rBIdL@V{=v3@4r5DU6Rg(!?JD>NC z)S7pn;(wp50=GoP=?W|A=&Fj0T_A<1ZK3R=ZpomBLpXr-fVyw*xA!N0o5ZRu78g|B zdSQwmbiI<6z)#Qh%8s7_{h$5;fQA%zH^-h6C}0%AldOQmcBNER?(ugyg(&I~SQ4`w zS$!`-*Rfm^dKiCTUGnufJfzC#e@R)<##oAuM##mL$qd9;6lMWOR-)`>^!O zJwV$0=lzGa@q?f+Janc+9>~Eby-oqTRM9v`VgJ?ZvrG8gP$vnFyNJO~clFo>m%0B( zHo3%BRt<$nCUJ1cH)+Ax#;RV1yYY~1`%Kn@r7d65+)~mD`+`+7XS3jC+#L!%;z9x znn1t!-PGoxrYjfM6NbB~_|fiHXmK(c{AI^4rXTan+`4X?pa|F5*3yijo-d2n7Bh#< z*@m5x#5v#XCH(jbF)9YKqNiWJ*TO~b3`7c3lR42PN_6 zb;Y`R9xZ#Lxw?C8wPIrlf*muzA&{-!XO<7xcc_?J{OIsX@mhWSOv^TmAP-spdn+R7 z{wa24MYKJHgTLCi_d|+X&w@KycBfy8FA=F?y&sFyS*WE?Ye+4|bfH`sQ)N{(_Ta4K z%c}Q&k}&ZIs+Aopcdc5#c2V0ddC%M&e>Rz#WL&w(zTbq0e-_?<5yuQGkxV{+ zbNR9!%haakhj=^W(YCs6T=s1T|4wI`s41d~Lu&(XpBSrD+&p>b?|Zn~6#Qb58pTOjD5FqP zCRG6MA7P%?LYL5pbrfH-Zu$NH9qLG=470G8fp_XomXtn@Ez8=kQ?M~gsLWP%#PiRLqu zWE=J=6;}v1A7W@J)T{j}=g62fK7Fdj@fKaY^EUqNQ5yL-f=l!P_3JHTqsmWH-fyt- zqyzj-@?0u)+nXt#c-kT>UQQ(NGM4K&bto+x9)Gmg&EnG#EbBcum0~BLyMCFkd9mU; z7nSGzOEfm5V8RF_8gBXw%=_4j=OlF`fo^Y=?t7ksjW5R6@aPU-jLt=K2+@DVPX-60 zA!+nWKI2IbILbZ#(fP4`Y2mLcPkp&Vd5PcKXOT$f(JktFt;>FhYw@i{UZ0sKBOiGoc(oHMJ zsgfHrO7JJ`G$JPZsr$qd_`{Rg;WsM&tZRw;0OElYpYo1yZSqwp>$QXql*St!S?rBv z&aBi=q^e-mVI6FCZE^V*y-hkl1W6BEjhilMkF`mf?Kd?0BK-yl5i-q_9r`x6-8Q2K zk5;VDQEV0u)m-$W?UtxRq|l-nu|o&_6w%R&C^W|KoAv1$slDg*1so)>kx%s5+-Oi) zHC_(k4@VXpFAwsgf5EQetHQ5B#6l>=9QqVknwkV8v|{4vHt1z;egY8Janh*0ggQzb zyt8o;m(vWmXgD|D^d1V)7uQTKZdQn&D{@9`~m`cCPor0p3sN#WLyWV zT8KP@!K^#_FZrY`3R;%dz$0~-Kf?3s>hIg}+z{_!@B@ zpt_G1ir(-z)+J{N-7$9`^pqquEc( zGfaUXETgWiafAm73Sk2cILmOlZ}|Vz$#wS!?F5 zy?d=HdW+Fi?Tj;&*&ZG+xJlO}ASNN8CwCJ8qqcFVhn~G%pPe^ZA0MZjUZ>l|+K7{u zSEc7e3G>3Wv1wZR9;-cq$j-^3;57V`Us=4|6+l*H5lo~M&m=fW9b${Izn$P3$&jjR z4!qpR4En!iF9LR)8`+ycr0wSU_UPZ}pfj#i)Qj3a_M!bpP0VEzhK_zcd>J5H{aMG= zqJu~K%D~u$;dV>^P|MRxs*V&ZaAvWGuMvN9vpgc^apV~hvXzmTYq$GLcyakK1jS-8 z65WO!l7}}?dJ4bb;>avE1Dpo8(10)ON2g2O4@=BNx&{X8Yin!SqI(67B~T`isUP-M zU9}=`~lXCVMNATz~h9G ztNXFp|M5farodyx6QmmSq@544)*#?HFdUeFoUCqMXd8K#d#u?WWn4W3>p=>Q81Aoc z^dTt1_c~b)R!e}Z%}VWmlvF1GzK0EZxj~kcSN=}}L^s<{8)>fjv}5$+WWFJsgM8$a zZ@`Gx@-j}W{x$O3!%4~Vtf5}g8m=C^TP|Jq6qXy{4}9U)Zy*_Lka?|pR5rUj!AbwC z=sff4_zjpX z5PE#wF&}7{T|)c#b}8ig&1;FD>)chrT;7suYx*)(Sg-Vz66}MMkGwfs$X(h5E0+FP zeJ8{`x~ICoAeNx+yVs5?=|=cOsp1@OU>;9ANJ~OArH>NbZ zYtUGU6@hL2vh}^f=T!4lr-L(CuOnX1cQvQ(b%}2go1x4Kgh!lFwEKf^b5dtwOQw&e zDK5^C?KRhfw@p2M?GFk|$fJc26enex>*MW_6KuZ}u}P*^F!z|k9UCV*SBWBIvLDCR zS9JKUkIWmjd1Ywpv#5hZPWWj^-yzwR`ITEf7!n~EsiwasV_;piL9%=(lB2!b6u;8y z1byN6NUYn@ZLG?s0cGukIw&$ZKV#qb`f-(_k+0ov`qmUgsi{4iU+p@+GW~+)0uT{ z&youzV!Yj=G9<!E67QGGNH zdU=6UC7f9qZA;LI4^N^4o(8GEBi7>#+s_h4H#uo%rxWOPm^@oNqI_O%%eCuk~%4 zohr1ohuoH%2AK6rE8#l3U`T=oZt`4Jg>!@kwqT#@RNcZ(c2l1cq6cG+)5Me})n z-P|=l#^mI@4~>qHR4L`tTU@{NGLi6fkZ%4)h&O>N^LwoMx~0P>$9iM;6Pnhik&#BM zsjri65|-`Kw0$jK8>-bQpfKCKGPYl6nR23TDQPCYDFvO}Wykqe!5+cI>9}ACP1V|B zMpaE6-{(`MAvHqZ!IKgeqnX9LmTqaxkt`$Jc49l;AAbV-eNYM?A?(gPcK+>vV>R%Eqa_Z*n)ij@O%Pj6bX%$-;i$TGA-CGz-Iy)fF~z zw7px}Sm2TwCE^9M(2to^NZ3mUDMTcUwzvGBf~LDcL`DcP(O6Yb zv`(~!YjYh*VAU^W_9*=^b8YGpU|K{# zzOtts9>cbenq7bd*REfM#CV=;UFWK~7Mlv;EqRcgEG5OUpu2h(HO&Hza3!p-m`tF? zvYMXBqYDfPY$hZB2x@s@yI>d0kztw~dRkSU%6RclEQZn~_^W~IBFi_+7NP#gdPwCx zU!%Z2N>gKQ?}{2ABeSLQxN=7R&ta;+%)`q#w)<;4-4e~Uq>Ak9<9B7qLutzK=sLE@ zg8nLZA*i}zo#_)HrShg$QrfCui?B0I>E+K2)a>qA6XG#%a73B?pIK7NKQCwK?(2>E zfIHEW;c1H=mxP+bl$FfhbnA||ZXVfoh2E=n?{s#C^9s?Zs=$J-p6c(@^X3mg-iOs=2Bk=Hih=03K)|6KpV8#ip;&g%Lc;v>zk~OBN}AUTnF=0 zXooeTiW$*m5~3EpW8A%8csiA`g-GHYps;vU9240~*fM~F(UF&k@q>+-Y&<9EVlA?{ zy&W*dX(YulCP~R(#^O2^|CnP*RC49~rbUKIFvPO*NGfWZJborhyNC5hgxJmN2|J~b z81ydI=dg?^L$_~akkDmynNE4W6m!6GL%m!IQZ1SN){b=onTYgUMH&}1xFT|sxDc&u z(k&_q7X%q3ws)AQm9(v;-e_>-C}sGfi=O|i7Qt+RGf3m;&|aZNO&b~$F`b?7d|Ln8 zVv{ssUCST~nv`uH9VJuzBf;t0K}W8ti@W40`(Dso`Ay}%2h2EBM-atWz9WHm&a9J8 z!5qR{Fn{Fk?Je&_T5J^-hevu)T8@^G{;bi#Lc<)R3}0GTqiXNEz27IiL=<5ccsk3S=^gV3S{X_~opgU{z7XvJ{l#5{k{qO5&2o7xLLbnyy4aLwpTxz`)hf5X?axJ528tsQ~SKM zdN3hI6bcD#@`SVk-dO6L^gu-f5cj;Ka&O6#jk*ypg;W6wo+F=G!R?{L`4~l6s z88Mi6S$1)4KYxDS4zF3irinLJXMXJ>#|~-3oID4(K4x*wThF35c|^<6(b$wXOnr|! zX~N-8Z8ai;OKi|rbgez;teMxMZ)6{>IquV23PG)*8Kcoe4&82#NHQo$nOsI5?-#f< zUeTOrQ}HMIozI}RcmLoB=8p^i`=@&xYv%7B9t9{PpX<1{3yY^uTm@GoJnZ8}MRpr{ z+Jf0tboVZLP;$Mu@C+BbewsEy$9qJ%Iv<7Kjj8GN!nIozXNZ*x5(cas8mUj*nrL6(_S=-z*S_g?FU}Y zqGNBrwXB|K&hr6$`z@dGfoLKi2Sj_eEA+qZN#LkD%IJ#mW9f_QdZfqya3E<+ZD*%j>ZUjre0+3y(YqGLd z1ULu`EzMHGAAG*!_1$x%+Qf$tX<79(I?U@kbWNz#0RE|u{{BjoR$@h@*|YiHKUaNB zeB$3XbX-3nejSC^CI44 zSOR^ZqPk-kcAQ`?TsS`lw&<}?1@-bkMJ0j~rVlQ44ai)1Nk3l4Uf(1=T|9k6>?osk zYKuM%K+lV~0;1&dTE5cLf!*W6HTj!4&kmk$=7;ZD3eJ!`g@88$(9GYmlV`L;(xQry z;Owj)d1GnRgHt5p*C>>yU0pr;O#|@4rR8w!a@~*44l14B{M3sJzqj;>nIq*wjpggN zi_*djm7UPnXZ!9JYc`YY_`}5J$u`Q4y!);Knp6^%pZWG99>jUvRZx14g-C$&?4l(1 z`}f!(yP%i)AAc$Oy`vR;Aj5-+sn`w|l6)st*~&G$g55G5ry1SiJrO*mb6EPH-bQ6K ze#)9Akrofd6S0tt#lj0ErrmDwG{wOAg9NKylkxa5b`|1OtQz~J|8@j+D;kjAOc6hn zm!J=`2$tDLKh-5F&HBna%wiXj{jK(UV_7OL3xTgJ?FhBah|&^7TV1-+z{(sQ*@iV3 zAzy}rUYKxXQbts0iCtw7D^43qd!v&NHlT0abk^EOKj5OM!f+hl~jZZq$3|2VNTHqH~2 zv5nMRcdR+TuaqHNfv7M4`zFbqLXsN$xRLqw5i;b~s|(Nw1ON9NwPgRSBMo!J7U}q! z*>7eBA*70h=Cm{zg4y`!1of?*183`2k6ZCiRFs{8k*cDBVb0CaQt~9Y5aEkPIz^4s zsP)9{o3-?wFi&BP_v zDKm$4!0s^eONZy)vzVm$8As7~(;3|_Wjf=aRYR>0UIu$deCY0c*Zz~? z;zJl++$gh)L-3G@s){V~PJ5sAa4z?wG%mH2)G_BM3{;Iqoyqv+malW%GJM4(gv3h; zpEUBB^V9KXJY@)NI!@0Omv8ztE32KUMKGrA70eVsloUM$@y6R#^PmtIW_x?H?h?#$ zF=kljV`iIm!Ye^xN;-A_`=zIhy6p3!pi@PxDQ%BKV%4kRb|FsPWL#kWB&|N*rJMKO zoSkn8ht2`sreB1$c zNvN&$M6!53_d;iG-urxzsZ;@Qes&BNMW^YRKqDJ0JwSsb(epStpaIgCk^sA-HM1_+ zwn{B=P(P&Ny*_I`Go6Mn_%G*w6%cso{sTarx96%1q}BU@{CY|Be~n{QF#9MlIP-|z zb2GWZ@vtD*IIX=>6E>oV8lklAKk4wq@uS>=QU+vr=qWCh$uFKcU-<7a^Ozp}(UCjS zfU1A;a~VC2c|L9J#BwZ>mg;ja5asmIC%{Myf(oU_0DIKv+3mlevOy?~REh?#vQ)Ax zZ!rLxOtiuXk$5TrX2sn6>yBMpxC#YQ=M}e^Wk5*sEME`xpeTvW!5pqmhPI znDjoTWSmDpD2MA9HUq~Bmf`2Natw6YKDxm^iz#XM?J27thOnLe*^0sp?MA0TGa#R&;R(}nDhzIn1Cgky zzIW-qe61<6U8X7u78_IRv54uJdF4i4-x(0O-e9URyURQnCZ20kRq@rH;Paffc@D0U z>C_l(QYGZTwG19o8?@COG z=ryl8YnkM;H&f+$&WFP;J>j=j_iwvH;E6I~ge=2yOul0KaH>J)JF~c;Ikc;-5)*98 z3QT9P5o(~Z+-qqtHmc;p0^B?}e#vl^+6E9T1`G)+zs_OYQK9OlSjq_+FNp?@YkJsG zHlsk9o|~ER9JA%sm$nfkn{a!M{u|#mEjQ3e3STiVE~d>Zz9sK`aI|D8`LjtINjCRpGb^ zC}I^!B;0~jt>B+|b)%nPYaK}XknZwwKY2+S6?yZ>4wuf{Y@(O%ZUR3Y+AQrq7z64) z-MfYRWc#Y2YNPhSESIif0No5^o#C+IWt(Jg_)mU>NTaiy)_19v%}L$>YKX(-mCb)E zlflO5i#Z)z#-UK^-C_#t)My7XL&H_e3mC`ilS8-dNzoPO*XrT1J*?w1mPW(-)SGjD zHMN+vpR|r6MyL|^JuCS;{?2hQ!Zz+5bjcD6A?udE&&FSejH5lw5=Yxyn}(;E-16Jq zDelHb(}Uxht2DfvQ;y!F3veB{jvzl2`X*~IRj}_ATx+r(%w7F`xa3})2TAEGw0fWH zwPogwzMluVJ2=0E;a19&e&$P!hylRbzk3n{R=b8ZZ!NU8BSwIg-naUQk%pJzUAOZ= z!`1$`FTatQSC^I6#!8_@5|S3t0>Pz8=v;yzP`|!n=HP{hQ80>ufsVktrV7zU3aL}x z%_w$N*I1@VjpO4Z$Oz|r_4}_;xL*tCrV2ymf(@Ei^XpkL5>16UBHEs3mNCqwM$h8{ zV%GV{Ep7h!+@e~#J3SR4&R+$u1MRVWLV3Q}aWh2oTz!g{FQB~DNec`Lo1rIg(==wYy6fzOxq`;+93>!Q^Sz@JNK#KZT}1&xPlFO22U6DK$>6{6 zW23iI5vtlPJZNDwRj}>Q#qIt-y<2TR7eA0K2@I`$LPG$fT;BoU6kyP(&3lS?1Fe#Y z+V5&0s0QW-7`BzCf9nt}#XHWo_pgeL|9-VB^$g0B{k3nMJ?J-2h7zHUZ}!F`14q1{ zZ_qekZnr+M&AW6ssL^-3?pzXtTiYk+xrAa9&c|T`9#wUPamE5j-tWaEzla5@p~2fO z4hwG7=Ks1$H%WY!j#J(FMP@n5IxSooOpJ($@2u?iFX$KxSiHkE2-iuoxoy8=NKEZn zJ68U1GjqrSbU+Prf@DBBTwYoFmsPucFLndScETNyvw%)`r9t~+B3+TSCj-qN@fwU5e&HRbQ`a}M z@NOkoBzIF`Jp_m$d=bRtYUdhucAPvlt7}3#?OYLah0H?RySy&hK=|{`{nE|%phQZ^ z2S1&atGD-eEpZ&O8Oo`+gdbU{{1M%~OR85|32#kZx;i9++EulBpV0yW!>Tc-l4(d6kGUZAse*Z@ z%TaulT=-|iYa*4p{PqU|%Aj*F%=g~t`1tUnk9*kTh;Ts&#km$9YR~qVljzfLcR{<- zaMXdxrkPgP2-*zUFq9p!sBc6oHdy zjxVmNgC~30+w}`wh~?E=hr#qWzX?s)VecEO2Wo>$>R$Ew)=A@@YH3R`8Ldwh2r+!^ zdkD~y)8y4ud*voC?@`g~^&Rl|-70e$tymtM6Pl%(bOLH2OI{%AWm?fM;#;Kfq@!rQ z-M!G_5T1|pGQrFz%pP@Bd-K@=VZ~+TKg)+SGX3pdFb37OLcQ?+5P@OPz__v5m+2P~ zy~#=kUt=H9XlxaD=oR?bvM}z$HRIlZDzYd-e=Mx5S{$4+hHpMM+@90`AUL_6fMvLN z>By}nNU1sPd*RMTm_vsj;#F`dOUYOIX=3>9CqEREe{}x7e@_oZES@?h|lt=>)2~6DV$_ebsXE3xc07 zBk`)rKcKp9WW($jeV@LG&J#1e2-r2R+tup!>Fz=R7}rLorzl)=APbVvOtM2nH?-;qMNJ@3il zXmpM?RF;S#%#87P#dzT^Scz)9o*_wb63wH7JER|~jjSCUaw?NF<{7Fx&(MO-h=L~L z!XW9ZcU7w!2$LHtN}nz6?8_~1nuymY@3R3ajTzMLGqR`T4m>xHj?wjXZgqNWJ=duU+YREWa0%@TVmaj%20eDZ&||+-@Ng@n3T&{ zW??x_?YMYIyIHIbiVYd2X$}|I!)lA5j$DqpA>fE4+RFZYdnUU8Uw}Mn4F*t|zP~q1 z?h`B9e7d+2(-ile#l1u?tn0Uv!vC=QD*k%)!^+yKFICq?$!-z=cd158B{{h zjX?bZTr(^CgcWnQN%}EqfJRGzZhqqE#pB=!)WS|dF&&kq+O$C zA3u-9iVpSB4A7fdJ)5s~YJTY=JqVK+tMWRjs}K5>q-wlg%am)%8(Sk*>HSFMd|J_c zC-awCBK@_3-|J8DKG#)VJ|{U#-ef<+7s!)r-P51*Z1d>C)$3bwgv{7fC81>w;cuK1 zS4EgU!J}6FMy|A0vd4@>9~SL4Za_s>`LQ?rJ0)%ev~dxky#mN2b~>D1-t6ro2i4u< z@U9CM%=KDHvnVtMO)c7+-$Y^|b-~Pp{d)bou1fFObqOk@S*<;5zOrD^Htd^o5E$=& z>UtfH!53;#Y~5?^lCvU$_rtL5R|7LJwH5GwEh99^$$MJR5xWn+h=n3?iJ*b2e{ii>-0+E==;T8{r2ID?qdRcG>6 zHUx`*IMk_(H?U8*#a!kVCh=6UW!r+IZ!>49Tf!r>AF?epr+$4N(JU|S(N~1fM@Ov{Ini)n^zlkol}5! z^m&r?RIfkiN$i1=F?9m`hifQ;w^#9tkPIu=*=7@4kbTzt!S5N??2&A}nQk!~k?vTK z(*1)^_*`ZkyN!?rw*pIfx%~(2CyInF1ljCuBe@LDGv(>O(s3qPQS_>(f~=bBZk8)p z@da+L2KfZZfuU!;R5`3KaR;NZEMgjk2($@^AVA<$jX470IJHF4W~Tr(k$W{Ks(37? z>S_6!se)|kkGM?qpNj9)17#<2S%085dW{R+@*KfPqNTrKqa6J7F)vHt1f7!FW-};j zRyH1mdg8BtE-#aa8aS(L1ibR-6IvW#eZE%`pOe-s{i=M|ZIYb2jLu@jytpU)r`>+{ zOyam@=5IE=GH^JX%Tan8B>pf{Of$v<`m)IDjqKAL!epAwM6Js2HU*{DC$pkrpW~~% zxc7Eo8AL69S9zgBxF18WSe8k8KryIy?)>6_Vy->hLF}46Fp}g=|A?|GQ zTPWikhPHY^sBHc(NOtkNqr&{>HjCMuHvU;)J5bLVo}NFq$wg6euaF!NAgbSf6ZCJS z_s+M&jH!rt2X>jD8U2|2JCXJ|z9$b&6jl})U^jQ1I=J|0=Njcax81u#2n2@?L@{d= z+Et`?y2D@pOD7c(5m|2YjJDIOX=>`(R9#-{4O3Ja)EwMoDcIzGIQ|Tn%=vPk&Jo@Y ze-=8W3iW%%(ZCQ(+cGe;(Ly4n61QI!$+vBp{a`K$m^;U(=UNwb*8E56|s*0(E_{z zYtVTjO(A2#H7bYSs%%c4+y@Yqum?jmiSxWvsI;t04lXYaUP2U_GuqwF)fB+m+JM1D z9pAko<1_keIM(1CZ*d_v>Y$F+C5i>BWQ{z_M54Ie7cI&nWSBv=z>O(-&+{tGrtNW* zaRJ?VQ^(la%NWx}!THoGKBVc-Wemlsf(2*%JsHFnwB?xP`fA$P@^&%#&M2`+EOb-6 zbSgXzaq`preOfGlqt zB%Pg+aD59aX@=C+b}9s+))^0{9FRc$?}UlCs@x8)L^{rav-;zHmSdH3(f|pyP5Gfv zBB%9{%coaDuAJ;jm?2sT+-DsY@Tua;Kg`Th!05Xh%`7AkkMnC zT853RubJiz*EISPwvFM(dG^{0OAiH~1e}Qcy%c!L%(=cI_ILs04brH`$XY1P)=U}D z#PaOd6=$c)FGhr5Tc>W;%6OtAnafvC7v&P`AYS2S&{Y;LjbSWKFYVR|EUtU|{s!(H zB$TmwdzI=$ak^F>A`ZYF*j|9<2-E+qqqECtf9z0#ey#g;Iz7p^Mp^G6OAzB6PEQje zyl>rg(yP%88Bvx@gcv_d_+xB0?no8OF~u%irA(*H3Zk+yl?;a@F%_OVXlN z^B9kLW;(+sbT@2B5FJOiV}G+xm8UQ0mXuzs57)&!JOt!7Frapx0_kWtHfQFvJj$A% zuDqU2fZLRi|^Ql*`-r9CvDigQjA;XTK2SRREB+Dd6dl=P}ot`{}0z z3R1yvI@|n@cNt2=%8cR_$?5P9@6i!giS!t55lo8((u4o4ymqYGrmaD9{CVsR07| z28gB9@s&!Z2j~Ow8L-VAU-byLt&nR9px9viU=&pBu9p=s3i~F%5d%7yNVNweo%-y-DW!Wm4& zoR9h7ILp`m0zvsV1I@5bT9gKl-Cx1vc+wK5scXE0Tj`7gLdxO|m(0iAIh-f=@4dRu z-^WV}-?x;rk~6Umz`jA}!kmEILLW|}#cZ5>rmNo^Ec)u&3^GFIf{QkS&drv`{&jT&|&yYHO~J7hhF`5$OM z?i&ORdv#q3I94@A``{zlV71Ie4he-f$F){?y9Ul(9lg(Tcb3S77GyTeMepV^M;-e( z=i&ui@l{=#Q`w~aw8;}|_gR9RQpOX+QR8#!G6u%XGWevrB67R{t3+}!VG;ECa=1;JwU=bIeBFsU3is;z4F(bbH;&unpYLj#v6|-mrIQQO4=*p%BdbKr zDGJmki3{;E12#H_B;T2GM25zU6sO6G^~6!rOLZeO<=`up#2IwV(9#598kB*>Pvdw{ z!}UgiRWnc%?|ATQtud4X6+)6<@^n_zD)_1}?`&hS5@sgiP3GvY=8HA&bZs0ExX5EY zJvcpng%f~URmy1Ie^1e5Bf9&qqCfB>gf9glR#Hzdo%m~j9He(sg^GHq@GY0?K=PU@_%#I8m6ue`zx@6fi)&T_937QxKQ^XKjV7Z?lvs_A{G&GBla}= z)YAjwTq4WzsL%cg>e2dF)k3SD&a^~IUcF1f-U5#_lrfi}YOtMtF*t!)(w%S|YQy39 z)|jUB9tEL9UH8qEl~uF>)F}Ws9rKH8pq=1fJo^uCI?Awu1cvlBn4;w8EJScq*4n_xM52CLAAIXMgYNL3`S!+|;p`4?)-F|xKZ zmKBXb3MU6TRscMzjz0jsyv*_9>A3E2M;z${;5O>)dwHGI)bZOg9R#nPF;Q-wwiqel zpkoaUad0DWh8GN)o!x+EDj+*`aft`M^U6j53kd8VRX_Wi0IIA<(QlijV+ifwa>vsm zT2+nwgozmjRzm5;DP2`PJ;P0~#~TjJ%yLWH__7feFi4mEHA@AC*9mO<`1m#O9sQH& zZvvCwMcebrMs#|+Oh6y=%OnV4@b{dk`xgM%vzk>IADv(=J9m60t|wk;PRl_YKh*E0 zQj+zKGu&H5MkaWC1ao9aNsdpQi3zL`Qwwwxb`qvTPBJ8@sN-7Z_~s$81FJS@sv-5@WqJA2~jzm}_n>y8;D0Qgz3@%k1lvI**Mp z@Dm_${B&0Ew*5mCcFzX3E;afWfBAtUJ=E2Od1xF#;MCUPLiTbz9%Z)Gp#dTe+nT)Q zIg%uwywN5Jp5!Z?XQVD4D-~TO=n6Ofp2o!+6Ct4B1>wSo))BlgEL;|PiQpJ~^<*`I zxH|TwgX+q?t@l^g*OP9Ty$vTrG{JpK_JmM+^(i%hw;cMk3Ki+>qt^6}lBu2vl4HNB z3mH1JI;iWjz2r|$dqU7}s0r!o6S(JQ1&IjtN)%-4-7#*|HVu^%gkS=^%3tae=t*r} zd0Gs&lW0$W4(26NVkBHju6O%3AflLHmU^&n^Agoy$(V}WbDGsVtN1&63BHVso(lIM zj$w!wAB^m@i6JJ0!IUU<264D1^qo}FAt30J#1;maoY1H1#3AH2L02|?-p%Pxhrq{c z(7S~f-D+fcjA5N`UV0Ipya(EokdWs99+y8 z9OQ4J7t-^_Rb9S1UcTl3@!9!>4w`}gb#;)u7?k*;J>6FUk6>4Ddv`bC+PQml5=N05 zc#cyi{Uv=N9q;>TItdc=_nYi{n_zoe7{o{a^;YnYaDwD^@SPG1PH zeBXZ^h^TXRhfnj$V4^Kbk;4mJm}m~cM1dpcvk zGXVT_ryi;kA^)w>QgE>($;-94c$(rAaCv>h_L#vO@QC70m8h0W_*%{y+0Sa_gfS-i zFe@6qN!Rtz91eO?&9&m~>@zKZ+6o6Jd^3u|&IR+)@}`cBX}^Ab_0O#SvmPocmukhU z>=!=|ePP(?AKNY>u(0&rbW<`7bYS5Sk)IAk8j@<(wR;gELLjO^cddGH?b(+mx#hw? z{{%PABIz@rFQ^3ixTN);{9jembu@Dn@XIV!0K~M~fK=6`6T$Ck1c;T1_Q?eEI@)iq zL_A&u_}Y!{dPiiWR#sIe6tldLliL++6L7eeTCPwKXI0jm-IeG0)vmM;X{*`t8I%n| z6<{UgFR$mG8>RtS=47{(>mFSIXs*z~snL&xHfG=3=?TO(wqkEi`;W7~iQQk9cy=%Z zf|gs|!^_J7QGCJD(MMNTadrG_%U1#T#1;|tbC1_vfpD*z5V4!*qEEL_L?6}Tzg_xn zL9XAiP}kGL3BnJEC;K}|^?;-AP+q<<%#^nUC{poddH_-b4N4$FASfy5q56qWFZDs` z&p@uzyz%Ep5}bBLmL=_j5_Xv3DNyV);Y{-fW$tNTGJ5q~7k}?)i-R$Wq3P0_$ zJY|?QY=nfr};3Wdp&&EA9Uqub2VWya$RQ4pO5(iRZ=|teArnTtW-y7-U%=f`kT%$CCBXt|9kJEYQ(8q(-Z&!R)LJVV?4XM$qxNsC0 z#^Yb;Q?SXsT=&;{N(*~e(rIxnymYXP*y_&eqsh~kmqblIcS)*K#PMveim2-9>Lj_@ z_hb()ra1E+icET?QB$fS{W9}8e+AQrwlEN;x0|%+t?OAdk{PBUjt-{@ zY^t@@ZXsLi#)j{SgOR!yRMAjSkbdAip+@$+FuCoC+Z24$Dj@%PtEV>PPYuTsE<+Tq zOcXxc8oFXr?)JuEr0+-h4^hy2d5%bknu)1Jp0Ku`vBOd0-1YT+U_7019G%{==U+dH z>({lc*bv!`g?q-OEK(ZG&}?LeL|k-z!Rg-C80>f0ufEe+_H9rEe2qp3?!RjDrIbVu zzIN}1*IWd=_pK83rd}(0;dAXZ?uY+cKBSK6)Acpf8$%k@JZvI&5k~83WDKorF`p zZsc5%nlvbFMXlN^z-iI!({=R}l)rS4;0I-aj71&~D@Z~&82=Yo6Xs|~a%>`lF5&b_ z0V673GU9V%?w$vhxVlR1Aawg%mLGGdH2SINTBp?iV(P7fs%oHqVJSHv(%l_`ba$6@ zH%K=ex=#aYmx$k$sd1oB{aCC;)ti9GRcOp~aNmz$5yTmGk z&|%CzyYpFCSw&~_IL<=df!LqpW>q|Z%SI_nrX|vuY~ml-Oq$#RTDM*2^)Z9>F?+>9 zp}hi6_vPWx!e`>o0$*&7+ee_{xmI!=(e*c>s1*Oz=>acYK0!h13HEW_IrQWt3+@vV z7V|H}QWK$Yc;sVxH?2SUe0M2X{73cui{V2`?q z*mWLW;;q8X%VyW`r8Hhl`igpH6-|V5t^D=m^>R)hw99oJ{jkopQq8~q;5R&i-!l1q zw$e~=6zECtgxgl zgNOC)L?k{#^Zxr-cQMiX_+|f-6*t47+F241_}sgF1WZC!mfkC5Rcx?Vn{v*O7r7Ev za59Lpk?E-SA!xjx`J7UFD~N)bAX_^ zb=itEtVbw88(e&@(1;s<39)iy38h^t(zLpQ)gMH32{eft8r8u*=LioB-7-Z+r60_F zytV>V!2*L$Iuw{kUxe}+7uO5$6$=`zDI!9HcOnMY+#$ZId4lBef)hmt2Y;;i$goKa zx2x={1B`^WvfjPE?%e}m(!*)*tDTYeL8`@}Wgd^39w355quwG74XYHzmJ)nAYXTZp zdY%thfGn%@ViQeGzsCt8xqK|Hk06e`>U$ zEF}x|6`rf3NDK@urKp1~5J_nxU;KL>>bcw7G5XK&_r}onUzqbUkn_t4*X#Y;O+I)S zDCKH(+A7?JhB#4okx}127hGMEoA%b)0pVNjhSz)1EI^?`%T2tY`Ss6rhZMCNA0Z>Z zOR1l&tv0Re0H7hmye)E;k*cn-;Wg<#k7^uviNODYdhQrKt~Irvg!22RxO7tNl<-X8 zi#PXEwvJO9LZ` z51R?w$$%I|b@;ns7Iecve9D0r1fgeF^Ap>Lcbz<9@8_xap2MyIw+LWX+da@Wrd7gz z`@8+7FZ}454=m(O0BsD9Y&JPg?X!ayaCwx8gJ^%lFMAMS%9g(14iBqmK}@P~<3rN( z!1DG>+3yb(Jx%#Zuu`2OeIM_LIcH(M6ZrOu>nFF;_473ga2_~MC$*ZEYQ{Doz{aT{?ToqFLvJ!u)T?2S1TA#u z)w0ieU1z;OrO0#gnd7RivDecs3uV@|or!q3506%lL8v1y5esCJy~n(;-j{DONdNf$ zZuAnF{xf>wkGl~5_mWgBMc!`^rHN3?4dSxHJ;o51u*UF1gsL0NPH|}NCT>+vHS~5K zv9Xv?%lY7~R;QTq=c-LsmIi8QSeImjgOrYMe1DgU!-xM$q)lq9z2GJ)5$lMAYG33pS#=YT;X=@E;U?7!SFBD9t*iug6s+GUYKYKUkFhF=x-jdV{7a7z?h1Gla_= zj6&%qUh_KW;z)fT?cT+-06*CO`rH8pJASM*5LrCWOEJM-?F8arpolu0L0V4Ot3=|} zNF0t9O|rDNhqC5OKRgBgqkBE?eRS8zqO6MQ!edD_X6}ALt!bQs9H>Wd+GuS4;|sw8 zaGIz0>Dw6zEj?qISnDb{2E6W3&&EPxOg;dzK5+(3FP4jMDiao^1}gLDKx11qLPox) zAHPE+3=Tj)$R7ynv4=v@sofXhnaKUjthBU(vXyxs+ke02>PA8G#%%rd90KvgP-IFv zphw%?{2sRK4NxyJo~=39qmS>SJ(K!1Wf4o5FpO9k&>kc6{jwbEMy&b8;UnGS=##M_ zQRlC?Js`jbU~c{FYi25*QDrq5UjfPBuu@KJbrs(Q_d$YbysQr#DjTGJlhWV-nPL3N zwu3VPhY*EsQMvfS%(mol3h|GX!3h_OECI1-uY-u*XAUGF zY%-eHq{xP_am-7C?>0~c1oVl|lmQqf{w>-n;KWSu^#RN4C{sy(p1N$AM?r?8_{Ob+ zPuwfYrR(m0&ulL!kjM=HuUi364l!&w8+?7&#*d$DvV@(Vh|=rW`S2i?65@HzEXFHqcHby>kXi1P=wkC`esCD7|WFOAoKREU$YkUblF|lwRV8T8>nUhU=|m^&I7cSxw#iK~}BubCvZf$b9GhW4QuyC^VwTY1*)% z*!s1fLhthjDJ}`=G;qUAb(U#}%qJ;K3rY8J z{q2rWFc$|hlLb}~1b&{&!3=~-M@;IPPWI;$gELFxwNXz)w8P&cmQHy`;g~?^K-ZD> zNHH2RNIwSx&UBRVmydsaHM%Ol7brtav>w@7_okCANTg4>k?f$3Dz)A;Po!iAkz6VDAieo!U;*GX)+J3 z*>hVxzG9@}NGc^_IeR(G5H3XW(oohPwfE)c!eTMbyXg8*Sczh0(R5iu@zw1RZ^I=%k`CMcA735064 z#xriqoQ`z+b!+39p~xlGx3mlao7u+pjY(!$_e$@464RG7WVWi}ALxaN2=P=uJ(c!C z_oLsQiH)T9H$Uoae)LevDOfn4KW=UVFr;*r?uiFyS>3dhQfix_9O1wut=56R%w5k@ zLMP%$4=Bf6-A3`QN7D;`QCM#cdG#R%Z)hMz`0ToAav&BP%i8k2bDs=>39CO!1tr8TqlzmVq~ZH{p5b#pU?A{~vC zjB!lcdVr#}ia9|#u$R|WSS141_~}gI$&8P7UE!DZ;+l9Gnqph>a!K$EG`_yR*KD2; zp&tAhT{{f%`tI&nFmCw3WYdnK1-M1xPXzA_xmwB+D}yBfuNI@p(#?utQmDetqE^}E zu#a{xE=uwwm@|b1K`i5&YisO{5*@TVNNX%$`Ma?@mnd-n}*K=E= z?Y$f3#F;k`LQ;UFkv<-h)96o0<3M15UmLmoKa2H}4&+Js7OQUl|7iiF1+59>YqoN}W^My=9%y zYf0G-@2X7twwXJdEan4oJk`$W_D)33y-wq$wx?QyfguGSk#X{Anh4qssLWTx^Gh5zZ6#Mu~D z{y6T~4(z_dG{m99SSB+NbqjC%99t;m3rZPk-G6r4j<&z_JvYm|oglfo5675BNTSwX zstSYtjZ9wG(WbgoIHmV7CzF7VvW{^p<8X`BBO_kZ0pihmU> zH;x`x)@Gr18H%L_JvYn^apezz5a0z`B+0(ynpBD?=o}+(wgBJjQYSW?zbl?O$wFW*h$M4JZ0TpQf<;DUJ zcOm`C_O`JSdTo>cvJONBZz9r$U>D@|Rdzk08BQr>1DL`~YbHng-bqY|7JuxEZ#?^&`Jw~ylqNb)kD&-1~0mx2j z1%sW0!$%{pVpP!XW&f`Klr!KHeA#@H(bVknKgI-J8;6qwIUF&xW-;K5arEPiY#t{L zQsq^A6kf1P_LzBS1C3mzm`-)ge=QYWyt{{shI%&H^a~161MOkrlEvxHCH@aH{mJ1cFmMF<~V!tWIeGSs5b{QpP* zX1NRn=~%zIG+uoy8!oy>>}hR!48nGU-TKmBnXom)n;s}XDBED|N>_Zu4VBBsF{Idv zbN;GpN<@v3CXX=>+2?lY`MPvsrk{YQ|Meuxav@enQQhLd}f32mZ)XMihz` zGpXU5mt*|4{u){Mu5TyAq0tCOcC|UuQAzszJa&bz0id63i<>NxH7io|FdeI4P(~61 z?~(0!|2^`;UeU{W_g)2VTsAN1*s01lw6sWdZkEzV4NrIqW1$C2Fo@+?Q__H^cN7+X zqfwOC48biS>}d^GELh=BTN206MbOjOdCKbZ5rvR?6Pi^9SEX+qtff}*E;M(7nfSc_ z!2?aPWvK&w!ZG)Dn47zIw?aTpPVg*d>i${$f9Wc@L_93&tHJ$BY#qP;M6Gj#t71sP z;>g8(rmtd?;wxmPQy7u3Y?7YuV){V23QvdZJyN#OiSW%=hR`<^URZBi3wk_f)$nig zgj*(mdG3h0L=qFdj{>8-0LkcUIm3BOWhK}`G3ATnUn8sg6K1*5(QAQE`sYg1fG|=C zn<3BpkYGATNDAQR!oL4;us0!;yPn7Pg5`1CE?~dCB3}2Nwr7`$2ul8LBeWYbBREy} z{I3qU2oscklzA0lGhJz zU71h(gIoGOm>T|DOIk;5#eYWXhNZn6x;U)H;wf{3!iYKQ(E_&AGJ0F3T){7Sx6WE> z+TSYO6v}9TC~RO|s(U`M0yGvTp7*$b>}dDm0-b^DTq|ABiGvVrOdm<_L-Cbe#nJyi zq+f?={+D8 z#GX@HOL3QC%Og+eg3O&ly?V!`FHz7yGz2p*aCA)sKdVOPP%a$` zO97u7kWQE96%6QMP6`bypZK$^ZRy~RIMrr$GYl*nC>?So*|Le?lBj<$0m4mPOYbH3 z7nOsffP(>_`(F;JY5)+_a}mZ;kOG)i7*XDbw0DuByoUpxMRDR0zugbUfZAk3b2uPJ zb(ss;+IhD9l07=7@?Tc-0j&#=63**L4a#)|65HYc9t(g$9sv=1a*2jVDcNVnfBj(} z3_3j=j+?p~8pI5ji*0~#NV_XfV0)JQS|c_Zl!CESq4*8+Jp*=0=5G1%jhbFfXg|tj zhoy6&as<5P;eR2XVMo1vh;@?u|c!x1?&s3Rdc zfscE5703fD&wDJCEdvu-jfBa~YZLZ+T4_yl{C$151o^KwGwSU~QbH8T7@#l>Oblw9 z4TcR6J$3IRQ(KD{DDsKonH4&tDYpQnRrhjVUwrA?B<+)tYYG?YUEC&-X(Z`R z6Cktp6Ttv&CrIe&HP@<5v>#7TpdLIvpLf`kFx&G6>`9=7tXB{yO zvtJR&?upZ4G%xN$Jn0zrRc>8BIN8;#1zdPX!uNcykiciG@p16sq;Ax>Dv^vXP$NqW zWg6CrY0){lm=*(pa6r=-Heo5jvfSU0M2+Mefhk#|IRNYGMswNT}5sVWjTk>xaf;fQA6S2)S@ zG|_0EdFy-fn*r!r8UQ+(*8e87>ObrpI;c?PDzdh%aW?M$lpY10+9vVZ4J)c$4<;*v zPY*x#{Oji#4ZJIAZZ_f0#+dkJ&q=A3v^(X`-1~w`moF@nLkAq^`Y62qSDZE2sNXN9 zvzJ#@81(4&b7NFh!FGZ1b6=(Wbuda0@#l&_SbNs;%|D!xCaWdGf3_<%DCOEJ&lGw> zvF&q>BQJ6QM;4H@rG>{pGq9VWwB{)5>x4whN{kwLrAUdhTiutAOG6%qFpp@kHwPY{ zoNV(rHvFk{H%ndq&WMZPuTjLIlf%PrmKT)Py7R(?n1JSxTG-U`^2yLOoaXs}U6oy z`-LAkSpUq!9RDvcyGKL^9bHp%?(~-aKcSzLYQoXSV}cR3>5P(QbWuXOsduBDmhZ6Q zwxO^Maapq0tYp6MY35%HmsfUVk4XEwjnJG(z@I_Hd7h%jjG2xMj>tGsFgdXrQQ-aA-yI6;T?UIj|mpl$)VG@KM zOf3fp2+0wE(OOxFE?&@5$~3g*#jBJ8txs#hi{WS_M%x!%6N+yL&!V#1 z2a*tRpDEuM4t%;pNt*>`QW;R)%3F_ z1={-?k>`d}x=A`8yvFmYt&Xasi4T|_s&rxKiXK6M%@CGgIouJW-xg+*SvLSPLH4y+ zm+FW>Ce|gP0vi;T6t(lUJ{htf5i$nDt>HE21*i4%mkt^|v#>`Z=k!Cna$rja|6 z6?P|L>l}E2MXm|n?(@2UJ~eoJcNfI)TTq`3_6LQ|xR3NjnvRTXukj3>$ct*Q_F$yA z6ebbp`Q5vtFSVO17De6PP^QdZ-S{QoNGToG(04=;XigwA0oLz5VN@vi;}lmdMDZ}O==O$u41F@C|AR|-13TKVvRS}M5}xh=Y3uwuPbFc(Ijoyz;rAu5&8 z`vjp8??C3Bz<7;&iJm8fJsq@FsW)%7+Gt1ykcaB>GVb2>fOH9gIi=qaa7c{;*s;>AeJL19vZu#R%Pl2ujAGbqPs0KT&7XzGP zpT{2`SRxm^wH%VcvZeHrQUdX+d>{lhdP)omKdK5r0!?1RUR|#IQ_#;JCz9{f(_`~1 z*n(u_B2h?7s1t*E)vO68u#Ww)ynaYhomS&`SB0w}LrI1;KF)oD?L*9I0@!;*;6CoU znUDTYj1bBTR5)=-)@yl=pXNMtciPt`HM%}-^Cd#@j$9QA2D(q)!0rcseVTahavR#& zz6;I(|2ap{JBcOmaY9ml;n-a@krrMi0rLo!HyRDq&aS*t`ZLTdI5dhX;al!PS)21E z`1LaXEs}#sXxh=KP(d-wOpv&tsbTCZTXBZs%67L@Z?^=aVnt)l)Zcf+gTL0D40hc_ z4xS&cAFQ*xFZIvR=mudm&LgNd)&%yQxr-LFF&j}EsTj~cXOr~(z2Lt}GN}hAp$Xrj zEZB7dasVFhv*%>su1qLB&b^bGfKz0Lk&2sGF{Jr}hdGW$NYqWY;HesT z_(`4JI!8GH+1|bnzc3+)tNf>_S<}o|2${+1+$C#V;$-pKevBBFW z*ST!TolVg!YA2_PH~7i1)=(^m8(BX3XKS9q${(k_4HP_L@7|HuzYevA9leAcr=ZOO3UYm|tN-$4_^Rkabkkt?E* zmx^R$z}mi_>!|&dM?gl`<2MPA5RO_VzPjh_XNDpp#R#T$p`osRE)sgHwp&3~ny@&Fy&trdzK!Y!7h5qm`XKW?op|398`>7l1^ z{akJ7R_!MnV6ySlfvWUDcJsEd;wi&AM%$(uV?yT8a|eGIihcv@b zjehHBqy1{6k$E6P2|!Idwzj(*AOk=Gry_W`r*6iRLjQA#!MF>q)Hk;89-S|vgHC`V zo+kjp^N`*9NEB80U#kzW{3cQVrv!X8d8c;KKI0!}mG7SxYm^Th{p^44Z7jSwRJ=yj zb#AW=$>lHwVLn?(DA*|KYCi*6>_Ui$h|N8SE=6|Lm-JrB&L|>TuM1yT_Hd;2X1&;E z!q#BEVJWWLhV>qC)ovv(qU`+7ITP^Qz-GuY76zlKu9*449nCg5DTENC3%8Bh#23SVBSW8#rywT!H!v z03g}qU<~oKAbC+ycy+nT&cRb4;fTsMg9cUmz1Sr)BW!fle7}@s&pA50%L;jsP|D?1 zW}J8&q!V7Gr*2kvL_owDj<(zxQqT48lRfsDK~iG0q@ z$H!>1-j6tdlcK7JpXuz>qBfE2SgawV4Y-?e~@?Br?A5j3pEQK={PTeia!9(iIn&Xy{8WWBc0E{Q(98R_wiL zNg_XuJddb#=>n4P6GvsGs116bswPgEa{eKZqVd~eHDO$h`?Zz6dA6;6#%W+Ey3;%> z%n24Q&B9OVxiL$QaKGW!WEbt3yaMWMZbH>2pzglAoPEHcCJ$V01hLX*fB!Z%@R_*! zvff{{WW4L=7F(Ydu;-GHWE20^!X=NC#7j5EF)eb3KjVK%_AsBG2T`B#%NSA4FU(LJ zg+xRj&CG4tQwT5&d5H_#VVNs1VP|*4^oucKc0C>9Fz1DgYiaGzv%6<(R9>)#xby>DrX=%(|I6ZF6 z3q9-RxMMedFF`<_9jwHNsLh)7J2Zj(DXN;t^)>Q(|C1DNGz!~vIIZZr3w9Hl0%BFY z>rCS(&UB|3>-(RpM8@H5(o$KgZsK`^JH-9c#T_4e$QRj`Yo}M%gykqcE9rJs)+>E} z35dn=VoY#U&=k*dYYT8_ZO2oWm{+qVp`ylDPn6_4nh_oo>zQadO~*&QAJt20I{L|r zZ#3XLgDB#bSA(VB^*nF4@jU+JzY|={2~J&qys%(_v|1=&`9HSBF~x=4 z3iOh7GJ_)-!PXqgbUivG7^f1|hCd3NNhW#Ygpij-*S_+oqwp3lNi+Bj!m4 zq#X^tz45Mb@&0FK&(qN7X)0)-An7##@V3TCQ{}kEj6h08>{{1L=#eW6_XA(^UvreI z6xnjGR@z;6h~mqOX08QpzZgxyUT`?z zb;5c<6WV2f+O}pRx|Wq_GOC^mgJ3bKsEtPNe{UA$U0jU{ShU3UE_WWj_;}b=0}>27 zKd0Gg_2z_!*_-Xq1p3SZ&0sA8c}o!XuvW~lgrmXc(P0amC4^vy&)YIOKJbJO;^avXRd`(?D<%?`KKn$D1t(jMWb2fUzfc~Z~+XKbU+yzUb?igH)lu+(5(ao&mZjw|J+3Vq54Hi51_C>9nX)F35UU3}P3dQ?v6v-xk%TYUGg*_i ze*fNsn1(R^8p-H3t9!e#T)&TJ-NC_;Cty~Xl`!_uy?QmBOR-T51ViL!)^tEDFFS6E zJk63i$nEKoAUCMpdk33dYd|A!+GUr7uk<%(=eSIGu%Jnd&XFSa7cMRacCH5+17&EE zK?jOtUL7# z{cVABG#1z~36#%ijnHR!4|q&8N(Pp9LMZ7YBXIQWOi4a-EaTn#vV}KXyc#k^i$+NK z8$AOw>wQu8I-}R+q}F;vQRe0rk662-Q5lY6S}pJnv`dMR^AA72!S>a@yGS+jwZf{Q zp#;HWh#^<=;2+UXG!on+IBV_NyE3WcOjaUI6U>)~v1EJN6)jP%3gBavVT4R^w`3N& zL7tvd>x6g$t+>{(72E5t8)-l=;~hIDy!-2QJxYf7%^IK&{q$GO3+5v-$WRJ7^>JHi zT_vxh8Xlm1LD4b*JF(c|s#<32WMSNwT30%4B*rQ{QQxBFGBP`_9%E+tE>ccNlJz)J)&#bZoi=U!3u>%#eag)Ua_ z{|p9TI^5#{ua2F`Opg6?TwtkEx0(TBe*s=|Kle@odSrxkE;H7NFxNo-_(?svRbQj@ z5J*D@P}f@H-s%5XEB}8t-H0tRvip#wcgs$j`~Rl0b&mcx-X!V)c}V4zm5J~3JoQ8X zQ8ouLDj=>&NFK z5oO)93^Ld~p3vby8;Z?M=sgm}#fIz5*riB&BIT~-U^S` zdom22?iQvg_dn}C%xh1UJa@ligh#ChJxici#bf@ea(FIU+ID{lOz~~yKW6NOw4j_; z!~m}+h}X&*MNVOkXr+Lp-rP9O@boM@g~oc*G4)2M94B8WAGB&3tHsumUEw0~Y6q+mjcr!|TrO}RV6QaJWx6Dn~RW%sN; zbFbq)boM?X_YIlbL}zAV7Jp?I`t=yK!<4A*HWW0rnAK|Jm91cj@Ky&jS2UJnUPj>VUipMBg@UuIbK_HF7 zL~u+5)*2Dql~I240?p~&g}elI(L64{9SdG&GY0rWX0xi?_$`sP7bMo{a(dl~HCrh` zj}z`a4nW9ldmUTYe)#kSEPvUc9FRn)qB~stNyQa>v?J878|wMT+h0|DFJ?#sh)ewJ zP=RX^NI|e!jsah6-p+}+@A$acjT>ei4CD9CGu%8ytw=KdX)@Be85WF$XHBgLj+$VOS;N+@dT&o|5DxF>?eon|Q=KDZgU?74+^;Ur43 z8NZE3%i^iWQ(Q5ymrHX|;qT$=kto(}TNX9R^|nm))tb2#V0Z*onFe12O~wRyj}__# zsO^4_hQnCOWxh#v%i;fHb_j-623+)uS2nQ{=s)A4^oE;G?F zH8hFf$xE#_I)t_%560p;M3p1}HQ?svejt1O6Syz(-1$850k@1V-_ecnAqDp~XE ze}0_T^tW3U?}MTAgmr-%ev)zBh8xVhDa#x|*R1U)z?yye0WTwt&dW?yce12)yL9s$ zQ+y{m|CySl=Yg{K?WuPr|MfUO=|6ta`E;p6uu!guOG z=bG_9Ogg0;ajiKps*At z<2mf2QOPj$Z=P2eC+cfQZ?n?1A%xC8MCfAF-;eV0DfNAgC0hyz$q}i8`gH>fcr}8q(QG$eYO)_hXqjSN=8!`biNRdN^?=<*o1GqOMmcF zqMZ9eoSr?A$WyHSy0k+O{jEVPW|z|vc3VUrgVNeMR$E&XJ26Js%JC(WzuI)mND=PR zd=u5>c``oZ;YCy9%nYxjFe=fquDF2ja`zI)!v8@%z1AtK?evji>4sm3znj@R>v9Ex zx3WeEWJ^+AGtmH&&Ri`0hf3Swxjw2;L9M^(Vd-ZZ*?iSr&)PEA?&a5Kar|# zt=!3?6&AnS$BnrT93FCO*BU_nO%Y{O(#CO#OUp8(<;|-Fp?`PL;)I}Ci3R=65}aAx z5bg^bVR7+-AlG$2;tm|gq<9T$sAs{D37?>Jby zMe6=Q;N_Hth5 z^!BUBn`m7i0M5OD^BzZ)=hxz7{qJna5Cb!@Ul{pf|zSaY7g6YXOc2;CPNPvbv{3517k>+%!}Vn&p}R)mlQ zjYTL%(;E66$Wji$hhK2NyOWC%#fk)3U<$Wf$w^02Ihv;kd{3SJG<{CxHaWD&5%d1L zsX=08%$RfV5L<=aUYppOJe&K_+#H3?zK*_b$y@u!tHOdttSc7RJs$;H6x?Zu= z4;~Y2x)QTz(kVj}n*rk@|HAV3X5P*;9lJONJAVlpO=qMv#8@zy5lrX|BNDnBs%K`+ z2wv+(74A$Jzg`J`XrPZ0z&%ig`+DFnY@Bi-#BjtINU)v?GjLzZM1=@6sW6( zZoSa@?{d3eU!iZp|K;eoTZAzw(bMv2s!|FL@|(7-n>qQ0yIM`F;aH5CN~s+3#S8zV z-*il`tn_+)JOV^<&wXUiFk8L=vTZk26fZ2FcXZw7shjqnlnuCge7d*7jd}pQ*}6v8 z(C{OY3|%f4>rJr>@IkKUlT21HVFy5%7gqQdGKeKqla|1cFF_mEUYq z2ruyO(4KJnJI-sWB(?V*uB!9aoJtnhEM^2`VGn)p1h&^TG#)bj+)e)RKa(soKpVHa z^T+^2s@Y$Jds5@{|GrC*+LtI$OeyEoyIEEIUO57o;M*zGQz8=Sfvnsbic=z?B_4i2 z8xP_AAV8ktlg>t|n_H9Iov`g#&*eG3eN8MU#WgN{($!4XO1rsxVcZ(a%FYg=?rvrb>Vr@ zC2Uc=48Zs)(}MFo3|$ipiF=j%gTz%86|(>uB`(G1kBTjG3!xt!9figDdAxa8aRA z1L5(P@2R6?ht*j&B4mfC`Dr56Oj8RiOnTLWIfR>Oe$*!uS`il&v6VKi%#)+6jH?kJ zXvkPRbT^g~AJH?+suiZfAF;ZJWnyDLhE~#FOz$a}Y)*5lFRrYa#8QwcUkoP=A-yQ2 z$F^`yJLc_Pg+&AY>abMD_<&ZKV$NJGB0C^pjEMN-`+W!!ZeXVYycfmg2L~OR~+Wv->PK0;xk`1qLH#r@YRoms7)Pp+GU%6N{JXUOesG{AoOywK*q-Hhls4LU(A@Ci~qPxNg@pc~vp!U{8_V z_CvH=>i37Nv!2=BTdf%Ak1TyJoIK(-Y&z1+Dg|Qa*y4cYBqd6z3}7nC7Hu)4Fs9po z+23&)Da?ZVN*MiXg?r?hYA`A#$1CXS@2!F6nes2O97ytRqcTaJ+go4V+LS+$sO~%e z?5Kf<`9m!&m9$0xIEub><|bN39raw|>G(<(VH7vC#Hq6P2}D*1O(Pd8$u@EW8|$#| zn5VIKGSDYPWJfLcyAM05!^7{YA|Cvh=x%OsG2G(BLeL8gM)v zo4UIdJJ-8I+<$t-JPmDakpdE9{IQ)KbQ|IqN4yejnIa%xFX04~oc^C+Jf-^XNg+=9 z%n=%d?TTxssR^QpD2xDr6CjEji2fL@=(_0ZgPG>bnxdW4*n1d=13V*|nt*|doVBYY z1=w*7!(L58IFOAb{kWuv3X_NME| ziIYbgFy4XO#;~35B1c5grZ#>EDN8^k6hfA+qmYA)8H&|P&Q5N1~*O|AV z+$G>1iuAcdsWr&*D~Q;!flt{N~1JVUjWk*SvU6l4eZW}>#mG1gqZoJ22X1q;Bl0k9$XW`~uE z)9ne^s(Qu9bjM&`XhUtk4w}18vWmRoX{*SvLb$tgZ2*4 z0nT+DIY6$tYCmtwW6eo82!8jtS4unMS}8bLqP=EF+U}JpodU0GL{m@sZqw+!mWbL0 zGY3QP^AonD`+`UO2Z*b8B@}w>aMJ8ys@%}1C#Xa`0(=R$D${(xS;q^wv6gEQ;*WTj zuA%wxVpd5*@)hl6=YEDon~=%&Yx}(3U+X-ME?><;Qnf;WVC!l|=V5g3c!@cu<`q(s z27iB|bFO(JCUTB?)mUXF>zU%(`uFC@{NKA+t#OJAwl_P5Y>!Y^G~G9GVc89=Y#_y7QK-^1Q>n01b5`hxo>hz^{|GVYNWmnqsYi`8 z@#Ce9GV8fLPjA0krK=ZjSQStXU@b_L`fUX1qL9O6X9qydbIb2M?HG$=R%8$BpNN@SU!6jnTEoY zU4UX-t?L@NN6oX>TwiVh**=-dN{8sD@CF2(=p_tD7p=Uh2b!a597_Jbo8+#W*gB3C zmg5=+_VQs~26SkA6N77+(S?Yy18!h;ueCf@!Vf8QvW?zHQk<< z&GfWi(Epj5z-IYiVrFL-4I~W#qYF5Dc6TD^qehcbe8yu^KO_%z!nD&#e6Kh*B>o=0w` zmn5Ud6t*?@KMmW7VKN-uLU3A$Vd`P86Le9 z*fJ9&FG-gDU0?(L1wVF+1SUjw<4q#IH7TgteFnPSp+e^#Pfuw+dAZ9qM1Tq=Q3fEH zfuRc6>i_(SuxtVnFzHKp1qo;ExmVX#X(LT*h5vydmtMjQej;pUcy={_Ae>XN;xr2Y zN`TeXjl3tOw+>t4%@l*XlOd= zp>KccuezN}i*(s5NHrw&VZUupv1-+g|B?e~Ij!psd8_?3vgGZ4bQKbw-DH zZ`30$TY7ERXt7ml__^1SNsJg3X3&(CNBxgWJluA~X zQISkj^2M}1bRJr35`|&>@7O9c1)=q4ErjwyxX&BMPd`j%F9?&4rpnIhaWDQ26zdT} z1(wZ==OaY%+M6FCaExsbj_D2`pa8HT_RswG1}g>ge3Vy%;3!N&+N3VxkQ!%FdEmghQ!yY~2DjZbD!Q$KM94}G$>!yOE zl_}}^8a3WGb_wSbX<-qJ(jf?X$vmX>QK5#FyMAH-pZUGW?QQDcAKoF8hYybYOG#*6 z8=1XT;^>T1VNG}{?EM;ffNrHY`LXq7KCvZ(hSX^AB{QcbH8MGE zAKAD-QCRcXaM12i*$%lO7#VP(!}x@;!+yQ1f?m_*3Y6a;=Pn=XkmWZ24^w9qRM!@5 zTS9OW+})kvZh_$L!QCOaYp~$%PH=Y%?(Xg`fsNb7xhtpMt#^MYJ}KDDHP;xuw^rp! zAtho;U&abcDp?Q3qDFDKnNS38Nlqmd*bcHGIswqKCe_WX)m(-NH&cpim+U{&{C7(G z2s*xu++@1eixsd(nblaIuxq!h26=rc+Rpj3=QQG6Aukzpwaba)+ZM1@bwm`ayrBd( zmwgZ`I@?&?*;t*i$-#}~d#(a!1EV*fF$U1_O_*_FO+VabSIRNmvv_11R~9Z^BhwD zX@_`ELhv19>UHF%!j#r=YIbVUV37QzWYFqcA!2*=v^3cji4MexPXPF&>UGLUli?|j zX|Xg7`H~EWKSIpljlxMAj+nnNI5!!FgU{Fg3JJoF;c_&W%^#CP8L2i9c88Z4Fa;WYQdswJN1fxQTppGI>x@;u$wb zMu70-;ZHFb4Z4$Iv7b(ZeZ6Z!WjElK5-pdo+h%KEa&^Pn8(BImSt{0Y&Pw{1vqwkEa0 zuLp{syCMN#G?X2p@X#6NnshF%Npd$zu1$}K)^q!vb>2X4!g<>*b#Y4A_x>Up*c;N^$8s$e86r}#DKa};e z3WH7Y?>#u$9}`U5)y8NdWBa`O<>~lKKqWHdQ?`25(0)%)_aX=6a9v~`O=x`T=sXGZ zBA+wCPCGEG0}<{4vjGyIslPf9_+=gzpAFUb``7%1Pkur{VsYTL`*UcLc^3ijin{cK zPv%LhnW<^;h{a3inqRDnEN;vY;Isnb_$xNqC(lk2_>P9C1vKG*s$KGD3|P~EXk@A8 z7Bc8fAhOd=8Ka`A`X5{m7>>un0XgbTt<{M|9VG8fBJAo{Lw`=?yi~?`%jx)ak4Tq> z{2&d4(e~Ue5HoJHWI|Bi4nTvugd7x;uU{!(kO3a~At50*UVhcr37h1p0bjqscVkn+ z1*+k-lSr|i{j5WsjyaW{>aMjfSYcxphy@4fxL~XngtEb^g22 zKg8+H@A>uUS-=nWK~#k=LVVjQg6kK%d}yMX@;=aq(S#L?^z9P*9#t|HPlGU33oEsZ z_7?c(9SIRFU31WYy;~hC%YwI(3RVKPpRTA5(=st{FSNC!)J7~19q^)knQ%mDkBl)n zJtxR>iH&5C`KF7|nuU2H^}&790}Plxyb~FI#B*qU8v3Z7F2|5<);6|GB-cY7)=0EN z5H~6*I!Kdq>GyiowQ~gEK)C%5(Yz$IBg;vZzRl?#v*COyu^uz18Cr>wGfInJix+yX z7dkTcdoyRj5kEjBVgpH`C~u?sQ^LIny=zZI{*!az7R-av9Ysb!_ms4=+TO~LXwTe z;j*QAMT8Cfc2e43h8^7yH|}2nd@1z79`iVNvLgIm#gF!Nvu<#ATEx&{c~mhyoQ|n9 zs|P>i3M*K2AYF8*W&URM+zm*yRAg%A6S~>2&{a0bC4CpBWB}Tq@Y09?Y(@m`+QI)m z-nC6kDP|^&D%v;*g`4k2M{UkY5GfPER^}E#3S!1Y5xHhjc~Q-Pe+&X@YQC%;Ou=j9 z;^N|4QCAVRhe1jaYU$W>E68&Zw;A$Y4}s;VtvCEUox`{YdTvZ;YivtkJ*odu6w9gY zl{$h|T~!4Tg-l(Wn=G0$Zl7Nt-Q?fQbeC?7$CqaZaa0qhPbwX+;)WhT)jml})w;%o zSq{FH6MrvJvgoc`^TMGzxJ@0ojX-CN-XE%BQ+^ zRBbdXpab*|{`y0`PHy!TN$BQu>PF&ytBZ2PDEn#LI5nTtmVN)v(OaaGx!_2`l&?R? zHbpC@#3a?24ttiXqJ|q*n)-&9rF<;{>|FKB6`Sf(R?zD(|1=X(uNINy(z1HftKD8y zuoph&;GSREGc5DoP+n77XFr!5pbOfx)pgc}{5M04c8b9tv z=q1!}2M>bO@yIj3hINNGCkfLKj$)z4XEC}ThvkQ=(;oux34rp={Kd7Tj713zRVIur z*&%5zQMX`rxz&W5Q}qvJG~Uir)YrkCHj?SMq38IrFJWpTeuV>uV+o-_lF+7*^dAG4 zWrFXBeq);I&Ym^L^|JD>7t@JTcz(7a!N(yjdR2nBEu0=M)ww^h3IRHObq&JJ^`m#q zo4fYr<5q5j0B#~l)g>C8qr=x2{^iSm&zgU)2*~c&FFupR#3sTwzC+o_cduDv&USW7zUaVNx$dv^Wp0-veiLZ7 z_K-8Jt!Kz!OD;?V5-9igoR#7?KCiw6L#k^364t;l9bi5Kqp2zoglFP`PYjE-xdQ>Q zHibsw$y@z$__wDGJqv3UKNiaUT2?L9=2S{*f%Th?HKUpgriw3VUC7lJ zS@V=giVh-q?xsQ?ei#d9oRp2a_P?AqpZEK5rXw3LnrykNbY>(1-Q81~3<&(vdRlIIU%v$7cV z9)Swl7QRCb-~RUY&nf;_T;CHJp&|R&>y;_rUz>wCxcFrv@!v5kZ4sFWsKDGGT@Jbz z_7lP{I-X!auWS~?EbGLx795&uY*biOfU| zw`c*S-a)QaQ2e&CJ$wts4x1qO+f*GuhGrJ(4o|Nu;a(NmK7HaDZ-GHalb*`t31peN zIaPRN&c6+&x%G+H03uo+d^1gDTjV zgWP$N{^;)3fx$9osN)dB5R1@1X(X37?Q9*IYX<_KwunATEAZSuZ}=&d-BaL$ZD%K` zKa{rt)%Hm{sxUfi7-6<)E@q#D+M{R7n>Nj-6f_Ry&zIK_7cvFbdp~}aXJ`=b%=~Vj zc4xAa5qKWZTzn>u8lM{5@~HGR406Q(`?0;}8IMrHqSAt$)$^6}HR(&+vlk5^8YBm* zGW}PSKg=1b(grs2^&PBW+666z4}G*Z--*GgSR%Pa-~}wwRo0X$j)X^V#2P`=x=#nJt+{-7yil(97r&c5%hl{b$}0(EDa9_dbHfca}A#hf&dI{>^i}3sW}`? zXb3MDEonwYy-D2rNjcDHrUS7_YE-?7xJ{I@|9}O&^0=gb^vBeSAW_lmvZ@yQ9mwy* zUWxVQQ?pi$B7W@9UL6<)<}P0%El-^j5W{(lz62A#38p=G#q)SF!S5zKPj%#C|J+I& zIwf1f%iXYbx;s(Rdt3wro7!pgu8ge8m5nz+?_#BUE06G`k{N{RoRer=t1lDu)zgaE zlgK`Jv>1;Tkx7al^{9qtm67Sgh5f07SK|u;lF#B6XkSZ44(0<@mcmde&DD@Zf%IGa%lFkL|ajC zYzA_shvLM1zKj2>A=KdhBjV?y)U+!W8zxs5Nuc*E{iBJ#Am6V$TO@XELsY$==q0f| z5zR>7qGl+~tNDL@$5N%)immufJ4hL($W0JsCQdpiT3eLLdd`WKq)A7AJ%RYO9unEx*e%=6@dq7+9p&^JyU8g-SbWXsE?Srn-2?>1_nw-+2^An@1 zTa!g-YQ9v@!Ci#+p;Jnjj%YsHp(L+#X@E^rGdC$JTss7a0Ei2cT9SuLItN^apJjxI zo?vMz)YQ&)|AjOTOng<&H~%*c{%;iY(#_PF-L%2DA9hwyAg8zwUxev1 zxb{tO_?{$=Vnip~1_pAf<2Mmx{_f>vta`av^-_ky3$SI0QwF3ge($Yxl$yzLrnt?v z8)Q>X4T}Jad?VqZc;9A z9}a)Kijakv(cb!sRBf}B>u|+jWgMKb0M%Fnxs?3Id8O0f-|LNHpiV(epM7bY_43a04u}t!hX0gB?P8}kaHy< zu)@vDOE#$t7Zad{;S0PP3tCnWM`LVVwOv%2x@CxPUGRJ`I6N0j(S<4>09${5f9 zdKMTLR46^72rZE@_7+qLnSp&iRFA1=mET;Oz`{60@5`7(UZ*TXJ}<_R zL*MFLMSd{mkKpWC#b!&zsbF9(au>|^J4lmT{|+J}KET)uP|xR3V<rXkK$}WkiX-a+gem;lx;1m+AP-A56IlNOfSIL!L`icN!%SrJ6TBJ0-T}mITc2 z^=y)EsAFToi+;)wx}zlfEse_}kG0d-AS;Yuu6I zaQ1pH6m{pt#C)>vvT=rk>?l~gh0S5^olR7a`s;IUHG`rRTx2(I#S-^Y_n%Kk9PXGc zEy^%VQbLR^A&^h4kC}Y!LV|y8H}^I^F>9q}dHMGnc98xUY|x@D9AQzdu&V;rdGrll zKj^fT))4lrBe~`$73V2ElGsWSkwPRAClxin*_M%T5L%lQgk|8;MUx=B0frPS^V0T0 zSFF9y%81Stp{&8-6!Pf?X?cXa>Kdp|@JVpH>>|ZzrO>~^XEFY27<35J2rFT8GZfO& zfa2T7QStKFMFzr0u@Z}*j<04_mbZs=yd(^*5R6MR2N3L~w;TJ*kBj=m3vBJA$rAge znS05NoKUIP1T@HD+sk2{FxxK>=R)v@)F-mN6&r>D}H!D7LvbEPT>MqlWHL>NIs5L3&l8u+g2;! ziG2d!Km4W^8lnCo0BMm3rm;i8339U_{w+BTMKZs__pBpd;W5!P;Hb$Eh#TP3S;sqS8c`4+6i@ye##-pL59*S7K`8dQ&W44kta z@Im{Rdest|>iY=+t@qAe)*2rN0Js+8NuGF~q6iwu{_UX#={p8Aw?cXmz@;ddzUB1+ zUXPTeWz`haKv43Ds;>P7c*@D>3>=HUT4!xIXS5OqaUC*u3)5pzfunvTHEO}h!pKGw z`j5MLpP=Ti`E-nedN?EzYehSTS2Vr$fSJ~19ookkC=@NhTlnauEp*Ds{?X^mxx7Gv6V371{m1}z71!>3b9W>EnkQ)S z!xHdz@ZvS-g>U%&mE>sxHp=f!|8=STZDXm$@sYJsJmGbt!{a)fEjfxU zg zy1J$Sn$%;X{&VBOwi7P#isUXJyY1?6>%8Ft3du63HWw;b$qo+PY&m}6)Ph$SOdSt$ zp7e4^u-g8Zha!$TnW9d_(uE>q0QSjgF=3HK=!Q*5?4Q&tqK@HX+oV?ecbXZ}sP8q4 zOYJcqc1IM!t8mplH3C>ei!z7eyc#wyaLK@yA<$K zo)?ybjM=X**uxV+C8Z^DHAzzOfMA0FgMT*_aJM|Ro53WHqw$32eWm62t_xIAIw$pg z?m(%t+mWy$WI1R7X7m})>De%o>z|i9_DUOS-t&e|PG7w|VHj!_v8IlquV#I|9wsc= zUlU-*@Ok;6O>03_$$zYre>)s;N_#ygTsq?4+!Rc~Z9x@m-u}cLh(=V&&nyf=`|Vgk zU*uBvxq(I|Op!&IJ}A;YnbwK*!AVP-*chDE&Q+ZBNO<7N#d&8F&D%j$G&?HWyi%Lh zoLE#)$Du3}n_ZDLea<13!NQx&t&~uN7xbHxM=381Em)qS(lw*5Di9`m5kpPt2P1DZ z&Jhn1vADSMb}$^nciK2D(#E`Njz+}Xx)h?{&@?p~R^I~=W^3iS8L+4cq7z_3K7VbTEuj%Vt|7%B3cG;}$ytpG za!Qe&;Hsubsu#}Il+HwsUzUd%G&o~$AkU|fQD0h;#K*0)4Wa4SsD@InN%zbVx4v+0b~iSfnNc zD$2b;(xauRSt&HpAAvT$bXS-ZtUXD||L*-3TozUAw5k)?0=qPvvb^!2!&pW&rRv6I zWlS;p-D4(if4}z>{eOOSBOjl@yM@n4;Cqjo#-+zeeQ!*@(!cDyCcK4{<%(Z;2YLM6 zPND_P4&S}w8~MBjvtT->o{VWJl`tkQ?jrZ?@jgDdzN6d=;l<#@gcu0tcXLNNglb$q z544}+Jyz}73-J=uc0cIiQja|ZmbUe$%238X3oUwGIGJM?SC=~4vyMEgT zDP2J6?=UEmCj4+jL)j`ZTrxhfjJ4l^_oDg*14o^%V&PyQv?CvM%SoYre$yv(4+jgHD}ex&CQ*=(%$vSHh(77 zs~Afx))$%j5*EAu>JIhm8c1OR3zywvk(28=#Pp zWUWsgDUKc3^%}ifVg9Ehyf1os#1z;3Ip$~4|FkklN*GzKEw``z3=y8{VBqN50%Tgl zb*G(S=nz`gKspb&m>=F-9tCK`wP8qy!$PrKe($r;QA-{80gLmt$_ZOl#yKDRt98}CnEZ+Rck zt3o1N@X#Sj=YBf3cWcLjbo_vh+obdL3&9`fxpy!1YMtF&I_?UDx&b zmZI1I$dXI{D?T6Hm#khd=?j{6zDEef_8W$($zeoK;C7?4t zAaMo`d*BkB@^JF~J^VlL_SS2g&~H`%hUFaxC>rz+Q{JwaE+6)CwvVU0qZRn?xamQJ zsu=luFiLo^xh^Mm8p);xCj~(D`})MXy3VU6;>wWJwTT9l2_H}cqTk zt`j*ECu$|785P(VmIy#0fwazvMUR6e$5SRvv`S4!Ue=(}uOP z*y$7#?>nY90g;~bH!OU7Ym5Pt&JrQuv%upNo%3?VbT!U41rQZ$)gZKzB189Z2&L$> z<5Cj3-4oFWfIMJ_e2Q%w_93q+hukRNW2C10qWhyFP6s&iV*MjVYlhBkpQ_=Xl+2sw zx2y!@Uq3Ii9%er=XOwm&BS82$? z#w)|MyA(q%vYBmd;7r$dnd{})rrWr_#76@-2Vjq`3`gO=kVyfrCF4vHhAvmX0#L;M z(anrw1bWlz@hPNae@J)#ZWP@v0im&(u1GO`{Avy9*jz4f7iZhhJWx>6(y4%d$hl?4`S#&UcR|J6RV`>Aov90>f; zfXDC6od8;-d+<kki+VCtt4I) zk`@IVviUQ<_qDNty`gb}tn{iT-bq_@&1OE?#K{vLzB#9*>uUc*VnLE}Sa>>QvCO6? znD3NW&zyb5$ovA&!D?k~3&^ZvGwBSFt^R6l1ch;El z8@|dv<5HWAC~*v`&QlFNB9IbD`zMo8Sip(p;Wx|*W*y=kh+a-M>Q;3%20k6=za3Qn zOA))d6ReNj82p=`AWsJj-}dl=f{>Asf#~oUXJ@48%f^qpn=U=SSC=o@LVl-zeAjaR z8os7)>%W8E_xjp&SUQXxywID4c<*_)28iDo!pW>urf{`KoO@i^@dz{4H_vP@h)?%K zFQ1Z>S#cF&rBREe3|0Y*ftPS+Ffs<$OxO zjrV|Lmo#z5(r#d5QMmtGwFoht1xvZan<%1h?DuzwqprUPPM}3bAe=bKGt2&YcJKPt zzg(h^6dxboi7Lz~8hEtSub6mwJ-goD>H=nm{24$Y2=q#$7drf89=jU7ux@d<%W2-R>_TMuWKy`Gh8!sYpr@e5#XF#EZPY;!-m>&|le=e9WFlD=- zUus~oQWsD2SF$}ti1!P2&c6O@gx?6R6Dm(+tTL1(_iy{T?_HOh&)a)cLA?lvfI*o|cAK%U2Z-tJm{q8uZRMNJ9$WNlO^IF#Br?jXZq01-FYU(X`m4}4)XB0lg zD^hUI1@(`wvT1B<+S(7JHJx?R1Oq^R7i`hIuP)aw*B40#>6Yg3v_Opwj zi6(k*c&@R_{c6w7Z{#9Cv9|9q8H|W+Kgog@1uVR0EJTavgaLL1Kj6X!@^>4ybJpOJ z@^m1u-ZAL+QvN;z`-boL;P*xfytYnGo_}u5`XY2?EHssn;~mdtzQ%oIQGjn^8OV(} z&sn2Kh{a?Bk&p;QT~k;HaC-V_#gwil?0gfF76dcQxma*2*twNpX*D3VkqM+IP&Sng zIheX02*t@|y4I(Ws;CV~ql%z6gFz{3mkeU!WpDV2i)>oOVb<10G6m0_P1hidH4<>F2|0?0+J&}>h;=zG}Pp_pCtCO3(hafn>%9` z%!I<#BUjWTje9Vd_VRj#L>*m#Z->6-P5- zPaPWhi=rhqMstezHfr%qlSC%prWRkHYFEeEKG!BQawv=h_`V%r!~ob^06M3eq(V;O z*X;Vp;)+F*t_z1EBUZuP?aQC#DNJ)e+?X4CBADO9>Zvx81SR%ZBoa{hLfZaDAFU5@ z9%q5->%Am*+hnPdGrYJQA|D@yre@?RVzQ2%3X|&6p}HS>AKCa_kI`yp zY&x3y_NNVWMcsT7CRZ@iU%xo8Wjy(N5x`Vi72H1@k6#w#^?qX3zr__w+h#E~$#Jb# z@Px`4d>BAHS%sme;JFi@5~x!zVEqWoC!rmRLqWpg zWGndD%4!gR-CPbWm7bT73wZRhcXpsU2weaFW|esVGQe0croJ@bW(eEmg36Dfpg)6o zB(>J%hX3do2x2XK*UuVzUuT@uZylbTMB02N3FZcV)6~&Lj~Cf>3?2Zlw8dc$rZgHz zYkG6{K81`8qET0^WNDBHoe8$Uwsd7W%03w2Hp?K7hoJZPeKAQFyy`~>COZifQilN0 zXzu|SNn2D}a%KR0p6j))*EQfmu1`8v_k6CehN+ocTVLOoME~6#yy14Wc?0NlKrfpY zubUEYZ+ONJ7o9Jd05Jr}zyR-E5r93-a+C8V%+<{+?#!?eoy#sIBE)%)Badc;rmTB& zZEcI%niFUSQOcv~Jx|h$ir?&`D=1=dNc4RZ&nKlX7YJ|9OES}7(^b2^j{Z(9FpEk- zUn$}dOT$leK&dY6X`QjW`t^s!apbN6lreLDrg}qoBZoX(|EJ-sPME=O5W&IrKhryZ ziSb|bJFMRb!%;brMz`hZqe4p3MWdY{)KR}9^``*|daap%cS%FLAI?I+_X zqf99^1|?VlC(+s`2?-r;za;Z)k6-#vh5ES*Rx==BG;;z%Rnagg)2pgMvM|-4NT^wl z>%4-bMid7P{+!h98wn@{!B;48brsJ10lBo!2mxyX>rp8wQ)pnD$X!hfLWmRXucZn{ zr{hDg$$5A;zmPMc7&&K~+S0bU5#VP{9v`hR`N0scwyqt(DXl0o7xIhQDK&yQbp}oV z_QSWY*xAmwt};Krppl-CggN0_xRXC|<1?d7SDFrEi76MfU`W+ARg~$Fv2kwMc#RQc zrxi<>h^nibVwKZ83GG-CogX&wd);r=gI~KYR8&2pN-)>(v2g{P{p*q&s=4jma<46N zVh43i=m4okT^X*J?&Z0U-g)Uoa0{3@*|jg^RdDVm-&^?suWP>a;0= zjwqr(Ey4%V?dVZ9Wgia05>n|E^or13j*-0*1&duN_24pV*Uy5d&XRt@C|V8)#Kc;* zt&h=7+Ybs7CC}fQ4S6HC-C^Y3{)NZ7p1)c-_&Tfd(Z80y;A;sau3XJIilMYKJLJ+( z8qr{hDP-2bZio1G>@3GmJ-#h6o1pFmDRmpxFQTBn9cQ&R!~_6tOK)z$5f!kl3A z4|f>R?30&^e!aVW!ye(r@r znd1qmCZt=Wu9~r|HVdLAvs!LL*eD32CAR9aI*0U*ZAhBfYSk2i4EnrhWZ2uHt`&Uw zp#{k_AFtN3OW7I z=%_(AV&Asn0{;ZwyL-gNTW2%J1yjYcB!8=;VVwIZR4(SUozm6;IRHxn-D|LF_R_TIjpYf)t_MbyzXj4ZtWBANRA7X=84)6>be z801C2E#H;Kao+srhP;NbS zjgoenZal2n}m6F4t1Q- zI`JR`X$`?ts7suuJF5rySDu1d|vMD-v70)whuQM z%gV^kOyDR}kVzs20^aPq?Oqq{f+Od-cOM>be(#f~;b3UA-+i%rG5`j#7j z_&(!S^lXL1s0VP5vHs`pq>ut`!Fzkg@f02u&lZIR$Vf>4^z{Lq$gC?VrYo%E&x@7+ zvV1!oM>jd|FCU-xJ2MPH=>Yi)sL5ESU+*CMrGl2K*)k@G;A`G;!CmOoTg^%s&{7yG z4358EKh&y@$C$0VpYg`%duEo$=pH^bf*7KyM9GZS@f9a!czKJoR3-Pi?GKd~b0f7o z3qI%uR%L)O=j+kBXp}fCVDT-98Eo!2X^Iisp^xC+jOk^LbPNRDk-x|)Z{s}*BX06m z++94~OkP+?cIJW_mVI4l<#)Y9n^++Th*yQL>|Q;)uRDukZ6Il_8`=s z0SYOaF`z>7)<^sz2sFKrz{Ydu>S}k{+#!ooQ(9wyjRpRqBY9y)dZ{`7%`$x!bhn6U zKzOmz;$$APu@T{Yg6$iX^S+|sa9k^gLK)#P;H^$d9(KbqxiDr90byJYq2nIv5)dEn z!D8N&x}8|a7I|z_prN~`7Nzp#=TIG?TL}Di9R@~H@f^tht~7%G@fNAWzqm;P!%SEY z=NdBTn8XHKR&PYavSqX!W^ix{+%dM+>#$y)NqRm@9IQ3Ab zT7D82uXSgwTPD|IcO~MX{M9Leqgt|hP=_6Zptr&BF3K!B zocU)~SdY-7k}DYbE3?o_Uiab*kVVP}f?ms|wyZ(L?^xxny?W20l#AEF!g5p6^^Q+6 zct*8tUcTJO>SU3kYb_pP{er@(Xqxn`twSwsJ!~;T6E_M%LkEc1$7PAb((8F_AC zKbD63lMczG+ln9Q&O`8z&O5*Pmp#9R_WOg#iBqZ0yNQdN7{7O)!}{>FEHW;7!E5W3 zhZR4k;D)vkwB}(^d5K`J<=og?RA=TpU5}%B@2RO9bD^n>7w5JHx>_HtLtQB;3UXdc z>`IQ!kb=+OJ?`y@E@y$CZw)|0Hzcya#8yJ4xr|fsNHoW|?_NL0!nJC`GD3;*e3K4M zfTJ~xoBHFs$6{w;84k~@s^%ma{ zVxM=+A_=y#JaPC5_l7?(zDvO2T4DU}oKD>5&c0uSMWy**k`g4mU#8aH&Y4q|k`Sw2!Y`4YoWR8{gXh z>EB*0Df!-ance^igqRW#+$4s-tf5219Aa@Hq*7W7spN`SfUO1!t(wVW7rq4D$9>|6 zzX~kFouWH3xPa1w#*=T?O8;`-<~t|9Z?-!l@p1>X5?&-_97`OksCcaB1kK4VHV0Mp zaS^WcDD&f?KXGDtu!O?80P04LR)1ZTSStkpN1f0t}OW} zrF`xKS0?$_*Dw9vg2hXqt78Q}0PHRm575bphCjYckVPAt)vwekyxtZI$yF~I3+Cjc z;&`Oq->f%H1+u|NNlG#gGEg&SIgt!Fim-&|4PxJXnWlrU2&M@y0eQmLG-MwOA;sLZ zR)ytRtZa=R0TCt{rtYS9o99_|`C8MJioJ~}SAwHVa;f+Om+_ky|EDd#kvKC{0Ojy0 z=V5uOzTOAd*y$-Sm4Psp$_E9;7#l}BI9Um5>#VivTL(6td2dk74GboI>uY4zn0Dfq zA=7}cnhsOI9^&opE#R1F_Q=&J-BlCoshN<@ux!oZbo_R{grSMreIk^`p~XE$8$ zk9Lpc@8D|p*Hvpt#=p)gWSE9@-~J5OEtyEbbtTC;aU!2e~D!u zajBJmxP%q#HC~HRVxsdth|@y@6%i&ARr5!9`lG5D@Ju;YIPBj*7k$dHES-KTFbdMS z?*lLXnIq}tgNdwKM?dm-?^Jmf0(J8Hcpnj71O~THN%s2J$OU}=jDteCNKB?`0oxwI zq83n#yLoK(f?F5(%1S#PP%}{*_MGg3IKPgKV|6N_L;il&E>tSG04er)nZDzbF&}Q+ zFiwV7!Hi`7N4QgRvXtCNvOAX6WZ)t0aX-q&5AKJ3++HyEIIN{^X?01%8w{cqW-6!r52Nm^z}ffMaPY z_C$_S#mF`vU`zd{)hVo)N&ldf{=0`a7%dLl0`Ecvs;R6r0&R!i5@W9nPan5LVD{1M zg>W%x0!N2bzD69dk#sOT)Sryd{cW?7Sd3=bJk_&CKb5~QcEJzqfgpuyw%aV9>AEoCfB zJ#tAVVup$+aHMf+SWk`>k}$fe{%lX;3eZ`@z8X7ME8n z&3NVSl#nquYL}Nyl*+tT-{Vu*s+`9z=b1MQ#*^Q^1fyin$j_Q-^NDW-^csRyB}a$h5vBPZj~NYOyS# z21ky2lZ-`=k$ro{*LjfDC3NTvhlv_=c^*s}`_LYie|+5g>8ra2WAuD*3q(pOB-gm= zE;i{aJ{S{t=qX}AyZmsN+#^s826_p=YY?A_6f7l16?+f9hky<+()@SD2A%>!BQwX& z04>t{DncKa1Z*&09?s$B-A(hrvU?Pu+rRB!H?&{JCwW368>L+bx{>TMgIlJQ{;w!aG+m7tSYuRmX)BGX(St41Qc@(S`@e7dugL-|R(3 zMSa%uel*SYzLo;6q7NHeuexuy3hx+4z5NCm4BMH&O2!E&O9_JiOkDxV?|Z`7ci@pqkdjEmQu;KKD zJDOz>U{?;}{OW^Eg7r}#ETww3KEo1`j@rzn8fx-rTf(26cn#q7E$PBXJ5MY1J zvi1~1t8R_lJE`e@d$4C(ug;e7Q~p6dR(IgC4rGs#zU%R@kb-NrZ+YK>!NPLATL9bl z;u6;H5|;md*|`0F)f(v6yw5LX`GGHdGpKXilQ$~CEcyg-*v~e4%iEV`^3-FBsG_w1 zS?IPB8;&q=93o~!z*LhIF9t}+i_hB#HHpbVmz|~RNWOIk*im=?h?R>LSxYe`%tTi$ zgsxW7Vmld7t?EyO-jvK#GU-4njgfLr5go}5RhFm0qFlQ|vP@(pA71qY9S?mg+e`N? zj$rv^%aqR`(+-w38?s1ZR@HXqBRp)5X}Qnm0#4=+#LxRfsp+)JAx%Y&93rr#+j&|) zQ!JDV5`lzT*$Ctw=zzi(r#S-MINHnWw#@~jr8*I`h6m1s^xCr7kYK#?7Ft=Aa0&>h zm-yl4PY@)=P8dE!V&C(wHotxJw?t%SDCxsPqe~DN^5~NY2VtCD6K${E73)JEZwU7J zxT7zd0aL|MvX9{ygJAhfas>xe+#(#b2%=&-O?cp_OacnDV;Ti0Ge0~qedgXGqL|nZ zuxjxLa+~l@{c(9ls_wkUoAl_e@A5-I!#C|W;v_vD;D%kq%d8)}3yS@0&0;y|%=&Y$ z>d#OX1Zq3i+C|_%uGr7Q zZi(y!q!HS0DR>dyN;i!z6Nkl<*F5}o2f>2wqfPITV9}CiDzQvTTyLSYqq(h0s=_Q6 z1!>xq<>lP9vwxyl0LKqdtH2a$A7x-JmCrTd8qg9=QQrNMF%f>_*A!RRqugv&(OSZ~*7));tLGic4n41n$i_s;cw&2c z{tKjv7q4dZ2jm5TpLSlK~d>t3;p*rG}zdB#@KvkXN?PwSn& z_=cFop7-Ap7YNE3w8Y`4?HB#8qFy{&%sn+>wU;D6h_Up+2S%e+RBEOIi1;-=<0ngG zk3?1iGueX=rW}Q3tUy;Xt~QSbdwmtaK}WW@U-?AB2-oo(OGg(~E3r{aaj-_Cz>PZk zOA15`WctqbY2!qyc0`B$+iXTb-36pN%eJWBt@r4MR^(Oj^(zG3d6TO(4A6#bCD0P=%%_g_cGl z)^E>TGzVfiL8j4(4Z>Eg^56P@cW&Ors{}$cVJzyG%ixRpwl+dJ)EFnd4gz0lJ^YEE#M>F{QGE{2IHd>~eui zifGWlpXxq@8$dCH3u2_J;q|C}$9t{ps2psCN`UR&gz`+AR3;#wMIG-MNvAZNO z#DqEd<tf>RpI-)b$s?jbaFRu_<+p8g>x7? z388MDj6JX&>GD&Bpf9T zd2HA1ZG7|#M$Yc2%z3fYe}w(fcY!^~6QoR`iG`EqF?qO%rDa{!agDGybNCUUk{Z6N zsWqCAbzb%&{u}ZGQ_4!QvXG4Ennj=k;{y=Fu=U*i0e3U7*es(fD{HlT#&y|TxxcAs z{j=)FYg{|YN`U0?4lIEI8=e$ewAGEV;VVKH*3W0DX#T0%#p@Km#}t{O=e-yqB7Ot> zU(X8GI<1cInDjvbQ4YkVbULJugWvr^-O?3aK}Slp5TzOz&`G7JtLP2#gmLm$i>O1W zfS+_O)05S_VWzmmv7i%iT+0&)AMJq4*``Q|`cUo|1!Lk%iy2!j*m+v&REcj!1-2a5)f{qv&Sua3y8 z!%$;3iQ`CbEnuiLn1wVY1SZvaLwj`og|kee#7GudYe735R}hbNK;C)n=bPkP450My zppwesqO_vPhPynOQqCmy5b)>qO>xpfL*zjo2~950{JdxSE57&gz+dJ@bFT(HFI zbWk_RgBP}7RzTVQ?TO6&Z(X->9IIFu(W1Gkx{&}5#iVCwFNAW%Fu3X-mhsZ-=|$Z? zZ-JHj%)z_PT63ie;@I2W))k2?Z%rgxtZ){qnOtE*vhm7ItS^YYyZBXyt)IM0U%QAP`0aK28i{!*%S;`0xj5 zoKohKJb4TyMz}}JYGO*Nk?|ik5reQr|89GX>zY->84@f#J$v@d*5h1!r19Bo+52Sg za3?4jBjwvw5T0P88Z#fhnX6FEwf*qGVOB3jzDF+~S+4bX$AjlXT?$t(Qp z9C47H^mEyI2A|tb@o|cY)QSrnQrffYO00!d+uJLrvx9NYH>&@6YFWM z97AaE*ks96+57PaZ1jwDqq@mWA?}h|>8&@YFk$}OO$V$`e7KTX3y3Y4UjH~br%bD^ z*=63;to##eezR`aoI5Mmy2bUC@+9pb?Tq@56yYif>6I8c6Vk9GsZT$w-~)SF%(Rpk z_2jT_bTp34I*rw0SlcK6LkcKo*_a^7|lA9?dMQydh9y}d6M{aO);?FXK!+Ko0IBrDC;%`3?%SLO55$j3}STfKh0_sLf%_KyXn?gaP7 z2@>4h36|jQ?(P9Xa1YwJHS*ri{%W6dzAAoFT@8KrTx-rb#x?jwBu5De>@=~f|NjfR zl^zHFr}nnSm_{*HkZ?g`dp!UTp{JP5jdX->PJrf0tlXA|xU9v0BT^ly4gtPS+nUnZ z6NIU*9(!S$Qd6`Vj2er_B@X8f?iTMnvq3M#U6&hRjGu(n)L)!8Ed@z6w%G@;hO^J- zKd#i80J-v5)t;B%gt%QFe-SvI!@fFTP}2hBug2lr*EK)DlJj%X=hwN7-UvX{wEHjK zlC5C29dtzr*sOs2wTp*`$q6`nA_Ztr|M6n0M(O) zf61Hp?ZC`x(i}awZ@f;VctA{Vr>-cA*|~-8rF$*In8$6{jDU7>VCzk2+h8rEw^AXf z;J_fRq9VQF>_3h?U@-<@kT481of)iZEEDc@(Obx7v3l}-;EM~^EZoM`*nU${BW*OT zd%!4KJRT-i8?lhB(AkNtCAFX{+@%NM6Uu+lJ)N*S?2e^88DPs(emVjy`v55Zm}gv2 z4OLtE=5DP_Mv%2}WB@1OrjO{jJy zydGoJPqGcOe@CKYX5=7;9T-I@{nh=0`N+XiC=AP%Z2tJRux9R4>;8!eE1 zGiMnkia);fzOnL)aj^Hb_5FKEF>j9$)j1kNY~f0;sMZr##QkBcEp)I~9>lcSfF-9Z^0k`d0H5Ht_TaM+;fxS85vMCbAC{=Yf0YOWF zZrMCMNqx1^?}p55xRiOYiPaTJgu1e<*>ns}Gh@49D=|8&fBZv^&7@3xDff~nQD0jS zP^iE4F@|D6m1r7MZsdgW{(N=aV%84$^o=ts6s@89ONzM2YnA)*{XRpTPkWF`X33F5 z`SB9e+Ea(7SiBwrSui(4pFJ#lp^Ns952x~BwUMb5QA`WG@J1g9mhY~d6sJE_!fN}V zL+LgzlZS_YXJGCcftV_7>x&q_WS#XwRZ^N-9$FKdu)`$sVFNNARcCwq)ym2d`~0{YcMP*ug+5 z`Fa`-PtoV6Ip}r!*f~q{6Z7NW2S@1br-ifYuruJ?*V5LnZlYP=TO=ArEE-!~?H(%{ zYY(s~Sf!-1%YOm@d{%HXtSp5m9cA=LK>yGjv1uFHz~j+KN)-Bu66a<;LUwf)RzTW(t)bZj)J6&I3YJq>!|c+GjLROoM?6DJfO>u5N=9l& z1g_EHNMS%+0(En3J?R2HMKsQ4dm=A|5TJ*>*`a~!ND3L@|7wwB943iCCw|S!gh)nO zl1Tp}k;_wk)9RA}is$~Alw9s`iGH%qsNhZgq=QW-@n>96xhnsGEf0-*v}+Y#n`@ux zDP_>ZK`o{|=%oCiKEO=!SZD?zHIhv?mka;LSVw?A4ykB>I(y?svf)3_B~zKxHnAfl z*H6L&xSGT4dHp;EFT)9m8Q=Fhq))QPmWK4%{(04>4G=_N1}L(W<6(%r^mA7=`=4Y4 z#Sb16jq&OVfavO#za_<;HA++_M`p6Fy-Wu^8wg)Dl9jH-VI+;FlS^h4A)MQ%4{Hvm z8k?vqqFtrgBpR9vk7p^dDO8(^wZ!v@;fpkIMU@s8sk zuy%YraX@^Z&_$+POEyq_@&TK8_}!4)WfYA%FjYUki)u^_dVF4K2b|EJdV3Yy;Z=K) z6`6}fw}2LA+W8$zMd%KD0Pb_yu(=oqaegLjyA8)a#bljTAdOsuW!uF@`?UM4&}h(u z$jgKOg?oWP`q3I(o(N=hwgCW50;_?C&aDFg`$+vi4$rcRttI~TX@1#0!bu1Aqhhi* z1bCTZHM5jym@dJb$-#c|H=+**_aI{NwoVT35NkJH zhf~&IKkx!KB&q4NCh&c;9A=l;&e4_3?j63IQ(Ybv4Gn0Dw^iQuRUW&yAVQlDJr7qS zM9x);9Ie}r$1ny@Q(N8l53kcy@!At@HTHld3ds1N)5Swud;VIkDz2J=1MH8H_mmEA z_@o&-^t`t2Z_GrGZbq;!eqRrDcO*y7(?U0qb^?9^;OJnXONJ969r?>2*ihUY^7v;| zc;un?J)mR5$<&FPBU5C$&)J)+Zw2mOHhuE`C|`|i+tUa;;DH%3h|>9XK@W>?oY7Z} zhtcg6LA`|il&a

pJDY@$*aaCxMEjVaZ)7Ce>p#N@(nu<5XrXAYJ@TXGm?LNZ8Vg z&5ZX%T?=kzbbq<11PNtR&_xSBPLVMDjaFrd)5W*PRYs4?e2uvEc(~$ouk$(oWKs@W1UzzS(ZtnLeYzH44N|#<90m6zB)bx~9OU%q zGnZya4L%M>S=H90(kyVRrG|3-_UQYGzcTz6c8{pn=tJ!w?}R`J%69f8e_c~JLg3PQ zoa;&Mrtj0_c7|_-qH%N&qxAP>tV*<(X zn~}xT!h7ed1J2`;{^wS$2Ndt`GQ<~KJ6CQI$bqpQh&L5|x3G*z`CSW$VNqA~{w0xE zQaT2yxV%4Ib5nmC-<3FS)sg}$bTaNJ=gQOSH`XbkHW~>Zf*Eebz~0oeG-0++;piZY z{ciy|$79{D+O9D|Ma$<@gWs{FD0|rNFuL3$mqyF{(1Qt{@L7JJ{Lm0 zN6R8sX|HQ;hm8W*jJm!{zF>)hub=c8G)uBnZ2s{7sr0{nLeo$_^1rh;v9Xvtun~S1 zoI#Fmpw%`rVj;4)`q@6Z_eh$M4bU-pvpNMa3~278*bAKNKMn2$U6Krt`5zJ^+$EvzbDR8;r}SB8DK zs)+2ay{^9B!D~pI6@B^@vp7;JEF*g(MyKuRIrYcM&22<&Aw;!2x`N|(GgYm7Q_Z}( zIxaV6xF+ciT=OsX;3nuWX<4P#wc+0yP0RQevW>AthOm5YT&ST#Twf8PkKyD)l97(N zqvBUL1E3Y9b4T!rE=u1DXC2swk-tg8$yrk*F8nA#Yd9-4b+4NQ@fP8_yR{;?^DxrH zca-Fzw#@Kx_&ruoFK5f%0mZ%5xKob3KutugcmauuX?>j{C35Ey~OW%YESgor#}5jsqavL0}6Qh=ggmb`CJUna^@*#k*fTo{>I`EeZB4;5dmLg zKsHjuT(=3J4}p1jm;bre+so|x%clK3?vXmMbd?}`Mi+V6LHp0xT1@szU)yz!1k9*AssgDjS8D`3~67{B@~Pfe5@YxuU(EPLUBk6>;>jDW;QkvMfAU--T2D%M)_xA{zown1Xr?* zfqYeZx9Dcwfo-XZ=W9{}1tR7LH+kPuKzjLsL4RQ$&d>IoL@2H{za=UarQ7}vBOwiSFN6iD{m=}LMd5d&ca$)? zCzu)5EiR86?YLABOWEHhj&zAYIL5eO?V~G2$ZvhPG7Q*$yVA_cJBRo8-hl7!d9WZZ zcyoACY#zV_R7Z5nc32C_3VOA^CDLkP&0fa|grir8+pTcPr};lFeD0k#P2Js7%!J6* zgcdk{UW7yo7PZiSR%0D5u44r8$gslis50t9_g0R!KkMJ=a*yPGs4u4HPjOsJ->}m= zSp4v{^L)|ji9CPf{P8w$Vfx51BaNr?b;Itm_4UkQ?#qYX5q#iDnn+^;+Buh-=TAV( zM}PvMmUC-;A^hOCwAV_aV6C^zmOpq$<{0mDHeuECe9(JfZvy$KL$-EMf6gw&P7$wu zJsj(ljy}xpdPuHLuHkTAx2Z-H@ldF`f0G-DaKN?qM!RRGSj{~sCjS>BvWc94x6Dt5 zxW{$qaU!wbDWdjm3m|2q^%QiEPj=nzCV;GMa^CJOVtLA_yD{WxJr+{c`BH!H@W=$? z$kMn#=icZ_?J)#+L98;eao;Sv4H{;pOub|L^p5``?;0lmrt;6boURRu_+vjrhe^BY z_z{mY`R^W*MD!3JuLs)#!RJ88sij?*cF3xE$Seu}qK81h1fvXs7^W3=3?@T1k9;tC z{@=_IDnm|SokYWsvd56eHGmu6mZLiJHEcOjmb?Vco=xd%Q!0i&Qi--h+?RHr*TfZ* zpgcSi|D=SV>pfl_Ad;PaU_l^C17i~|0Hz#UTrMod{{Z}sd?PoWHpo&`Lw7u4$%;I? zC+^|`im0kjN)!izEOc)(^=0&U9D{MG^| zVfEjfG|f*V20v09v9TKUOyvo9hd3y<4qCPpGAn2jQl(PIaR4cu?{5$9Fa=LjHXwfp zr4_ps;8LTP%glf?Mv~XK5qV#B24diDWq^5cl#a1~6tHKsX6geoy1drC4LSY~rk76M z95o>Upzs0{x>Q==xk|KJm2eE=$Z~<)pVJ_0cLOpF00k_i)-}j#=}c;6%$B3r?t9=G zT|^G>svFD!I{JU(b3#mtd^bq-%bm>FQ zMN`SE8=yqK-UP!Il1MtIWSY~oNz>|gkWW^9SUH>I8D~X`aO*$P;kK=JV{(J6pQf`hT~33y6UlR@mJ4D3Zog9F`gDCzxURYaz!BIloHw1n-p+e) zpkV;vUUZ6UQEiJ@AhfmjJwbg&56qWy3zBa)zpaLCT>>FKW-piLKk=NEqKc|HSp<5w zJ|(|d>6ypw05Pgi_z5WmUxSuC1$AM4W`VOs@YjazG+N*#OpS5(b38<%_XuK1A-f1` z&xE@O_sUC;N{*7xQAeobBuimwVYJ;Z;N|57B+c)COaZZ82upt2_G$d)$)a3Qn3FyzfAp--9XLxw%XPXr9R+6K?NEy5C+X=&7D@Q?fTQguKUNoui* zTnQpK_>dR_`kcZ<-JSXw(-N7e!XoOlgXMh)_7!`}9LftVz{xgT@0aa&@r%tNrtE_I zaW!C3I*c6Q^$lY~{;+4s-m4=>*XmObL7lG%+ew!v*}kr}NGI7NL|gQDk^D&RQi>HG zA&^hsfpdfy6pD#SK_dQJ)=F)HimP8@8JXHBSAmUoKoiLxb~98J6@2>fwwr0N%Mv6X zg@sA6j`(j{LI~R}#7g^)f3+JQrDr>;TF;-=L^gIQvfcCrb!=jf6%jFt} zl)+rx1tEW4F16gB&CQX`s(F1**^j@CGLJ@qhe7&Bz(;Wl>TeOYBr`-!$}p9Fr8QOg z7HZfEA3DY4+fs=0wRxoU4xs@F`OAnGi~kGjQU)oJ(WB6HxV zrpxzD#xr>&-FkmRdm3|p=dNLNxg*wDnZ67Dg@r$;edd zObpELo|454N+mz$XgJEK$kc((&cNGhW-q@_zvUZ78(z}FDufv}dK9x0Cw*6ht#WI~ z>SLmQM!R-M7}MTP5k-!vDu|IVSocUnq7jrZ=@1H3*$NF2I>r+d0v=(e78#IhU1o|? zrR77W+^xjl>2|I1ymeKf!6YMul*h*&77Mz26;OH9gUIwpI138=a`JKg2(7R+ad+FF zj2S7*L3?*Zw+-yeLmtW4EO2Gz8OHpH+a==q&^IeFbJjdpF@!->k(r9|k z0j|&Kdf7k|to$=HH5pJgd+>ML1i4u~)xl6O70xBAM^u;N+^3nCxs7Y23|(WSZvd9X zH=eaUC8w<}DZO-{6)D#mTf8Oh`dQ%l`1*dZ)!0}+KK~{L+K!^^LMv>?#f;kydL6(6 z!pjB)AV98hJSwWn2b{|7;o{_$xS~ivT5{5HH~>=2E)&x)uOL8^5hJ}}=DC9z0iHBK zr2^!(L4kz;?3CnmdoP|PdY(IQxi)5THvCYbtk8O1}yJDb{ybS{n6Un-3`R~mNHLbL1Y)PkJfWq z3c!{^w&3|C;j`O-^3euPH#(8_Leb0V1!h7D_b?w9CU6qQotps!5 z9PGk$V8|V%TWRXrxp~432qyJfDjnADZ!1@fwz&?V9;Jm)N=kNKl zr;=W}!u!rWu`*11tnR39^Y6DbUCY!p3gEU8$V)$ad$|4@D8 zCh)cf%%Xs820)2(_3&sC1UH@_z|M656*2vwA*h)L1mzq%dUj?w%TBt{Mb2lwHanj!W`t2@X<8YmG2!hxacMtF-5F^$Kqwj8^;J{ZIf3QKV>+2nXTtk#1=2uRe{H>8^I9KQezpxBR zj;}R82U;;_#NlzEK3}PCTbVxcWBg7FyM#hW&%MH&T=BUP{X2R#q~qc&TN7}A!|yqi z_TZfCAU(87gWHI0!>p#c>+vlSXK5!DulJ71e8Z-xIc5U0K}xO=|xo+{<@7~+1GHTBA zGsRjlflfhB&47qmj1{~Q-v_#tC7Jon8>5;mJFE*vm;dNIK`AqefvWO%+y&IMjHdY! zd@Ixy@BPy-Wav!3VO($Yn?Q(M41wuDeSJAi7{qXDY-WwKYX1gnc)mzh?qV@n{qi}KX#5;mAJEzyG`-bn?R zm-fVEgdDvG-ET7MCIiv%kUW|deemDbj4aYAlwhdH{tx6I^h;o)G0$Bx)gxPQb`XS* zSGB{ici?64!>VLXrBFCf*ik0UB1m7T!|_|lETcvnhD1)V4x44g3zg za78S&JUyp32scF0#-6<`HMeqFIaKlmk1X?V023pi##?P)7sFv2ZzSM_l9w0!-iCpt z8O`Qs?kFW(F8fyr>5KR3P&!)98@MG6q;qfrU#HS zpWDN6+{o>w=6WC)H|WVZAogN}XGDcP^Y5uzi0ZI|KT=Z9$HC#~g?Tx}^~Qa3o%h}o zqGzsGk6Gf=1T&VJhU5e$h~7;>ieShV{MgLao%L)wpM}vBDVO?JK_r>rdQ2%Sd-JL^ z5D}$yU+w5_Znc%N&3BT86$evvd@%0K^5Vs~PiaR2j9CJt^QI~4rYR}nbt_+g#!4!z z{pd7zylu)>&=ZyQfJ$+G$&nR#&8|gN*qV)GFBib-FWVCiVvC>smLn`W@vDJqyi~JyX4ez_XHl?VlHioPN-J49c6oX_ z0@Vd&gc=tdeLhE*fy#tdlrv6)txkQjmE{xug@}|URfK@R;1KUcF+8TOOyi@+KFx?^ zPmms==@vSj#|prUXjxc|eWLPLZPep^uF~)xkKT9Rt$8Q7tK4crxFYtgw=?r z;n-oP7^qmuYZfMno97M+)VEoG0Piy+dtY=4Rw6Ty{!Pv;Y^poi=`xKGh&yJg33~qs zHinSmnXFO$ML5Q@$aR=Q_%b(B*i7{q$)BL%{T{~Y-K7AJH7L@rSmN1^Y}M@_eO32V zDeZ5Hf#2hKtGrZ5U&k*hDiBg@S&*xSEo`ZwYTQb$XzRgj1UjlChU*=Q_Dn_C60vT& z4E3m0)d!a>s9;8?t?t3n^CO?*@JhpgCn-i97cO5>ZKc)KHPhsT5540)ZH#HnhwnuqOC~G*%pYLQM*rUP+5^ukM?z|gl z#Y_H+sXX&N=UD?3g%?;K%WFf}nbqoCeY^d(zVt3$FP{Q33pQcuGyK>uy2q}lxjLdOEA(OeZ?6zj5`HIh z{~7Q1Gf3But^K7HW7^0QYD{Ys##~(xMEtcA5W7haqR7W20}=?eALMZwsLv54b{Ukl zmkaYw+~YDrPT(!e#w%iz$I@PTo@&_~jMe=_H6HN@cDY^|gZ~+dmvbmpq^akR9!9ThvL-GQs&TY`xN}_m2vT zWt484gJ)kt{vNhYhD+5^QpZO~0yZM?w6V{aDVN#CX4(XsWCu3*#`eqmZ zoK*JxBZkdu46JSjG|Pl>AGNfW$Q$+EjL#dRu@H`|9~#mJvO;C1PJ)`_50j3bAfj7V z_or^Ve>fDpaO#AN8M7YPT@oO#b`O@QYz05xNgm$!Ff-C$0}^1?GP;A~*ki)z?O6bB z0rFBUkhZ5^z5MbExpymE(_2d|JKDOjU3HVgie=BCWPA5OA@ynYGS6Y^)VXVXI8SN7 zE92^oq^Sxj=zs(xUY4GAW)CUm^J#On?Dxzm*IQG?hDB3e76L1r(y)9X^Hh|q7Scj5 z6!6ALeFl;(UY9Eb{>0~=p7VR0If;^*5*wo^@y`OsNdiFW zRJ=w!kMlaW%3C?JD20<(2&+>Zktm6xpNJNI0!>s599TRr=H`Gm2LFV_WbhzjArL{SuQ+NlhGS#q)&}%d59miE zLsxT!KLA~%p_aNg@7o&CT?NdJ2Ye<|bF)juDA)V+VI zYDklz{lY1fdn0i<#Ajr{CxC3HkA^%uIw9b{ul8whW6i~PUuM7Fhc3ue^1 zh~#s$qJKXCLXbd*o1CAAXhAc)QS}{2!FjN$LSo1@VsNg+RNA}5x<^;ap$V5I+iTkb zpp}tqYzwTam`m748dbB6XOsWc0?hF>@{SH(&*;_S9=#5hG;@~t7id+<6V#40++G

|tEZXdnFhcjNElLN1I!+R~he<^*}R)vs~UcO_}>dl{8Plrpdl@E?u700+Lxts2gj zuA#V(kVEplIJxSBN^m*x-gww+G0gKG#;aQVT{iEzY4!HMH>e12XN^zru*-#)ilbD% zGVqEr7FFe>?R0mqD++gIq*f4NX%Rfm=HT{TAyE+laWA+Gk$@<>WY>pn(oZCqJE~Sv z)KsZ*h?7Q`jY`7#m+J}w)N3KdC&J2n4U{&3!Vvc(3s+p7Tx;|A<_yhqH^of*-(68A zpr>uphH^zukz~))ju4d!V=N8grTxty54Zn>4Yp6Xk*V#ym$+Bnj*~$M*A6L~a_OOt zAN>2=@0VLp9-!I?!V~{QABGT_966ARG8+19B#AgcFKRERh7B-YyQgg>B% zfy|5yR-=8Jz(Wf|pEnLWPBG?}6jIt!#h-lY^1I}QvV%;ez=Vel#jcsZ(efjLN7Mi7 zWNrM!z-26oj!e4<^$7>F9i4)^os(D1+%SCE5oyIzK1P<__-t!C@BOr3u7*}YxL+Y< zFH46_Uu_pZ3z`gGG5i4hhW0L0M8HYkNN2v)BtNR)P4^;V@?3y1oXX)AJAq*vg^9_) zjT&{CJSJ-S)z1F&$#hi2`@32z+E>ukKWmjgFPxkC;xHpI`bBzQr37>Et)-OJ0CI|n z`e#yYsiNcQO8Xe;ICqSrP5@%rxGOtSSc_Wvd_ zEFoye#9|of5igksu!M3h(QLM+aYLBsC61_Nd=*P()YMp|<%FN4#W|LsdX}t3CX=dB z!&B&gA}Vz={Iroryv`KXO~4C@Fg~8hkvVbl%=x_ki=KKg+5Yl8OkfycP3f3vlDa|H z$`&tvi1&Na4t@2SrX`mvPN7ohgg1j^%-oFN-_U60U_&I!--RxiRM48m(>v5MUj!_T zlNI7r2o)3e8AZ9)1TzokF4&|@ha2-|eD~XVnBunrvj>sKqKPs7J@cJ1t5MNZ%IoLx z=p_~K&F~~+YiJLdY0~-dC155~PDX`XPQ8*f9j(i)`011R6%9MT|60E_Ur)P}{&jk_ zqKW@vF1AYG_w|(}UqxR{lZFH3SC_%MNiFpuOkzhFbewCmXE@UBltOijg6cQnyH$I* zM^QCKwr?d1Aye9#Md?u93M*e~ZJL{es{J1Eu3pdSu$-XUJpLLf9=IatZ)Cb|j+&9B z%S2~kU#uSvbtf3zKh3@pzb^$nwK7~sS8##s?aS(J5`xihQfIi77=TQx=*N}!EimRW zzJZ>D-CR*Vm8Mqn2lg=Z)Md8p*m<+y`bMv6>=A7sh>{w8ltETWPjA6G#g5O6?ffbx z=chn=6yIv&l`P8Bwx%G`agLMu{66L^C zm>@DfDou)O2se=;Eun>Ym@GPDRhpi4unj&O{m!XZ8!Y||q(^gV=2Qh1R%f!uHz*$F zO&J92z40eUAs%`Ev^4>sRg+%G+FnvAM@_nzn6 zh;-q~GG>D?5d_~m*-!vapH;JDV7irIkAD_GCNO2wO_j4(N~T5*CM8Fan4qMZ!!(>8 zlSGOx>Z6ECPL*z)o+Nvte;_5k+|27lLG|^I7a9oWF7RtvgyAES?}H$~w4fl4^E(>j$BxbWv&`cqUcQY;_8c0@IhPa; zO+EIbTl77gdC@;*;r`y&4De-R?<3#PMOgj%&t!>^@30I}MPVFF__rfmd$?9kKw14y z07w;0DQ|#DdsS4;l?+S6g%o}bm81*|$&R-10(bBbpu^c|#C>zWSgv~TuzoFKGpp>3 zONZLH_z3jLv;Kz~C3ZuW9Fz#$p*wZ?om~21u3^pT6^tj;oUog}x53`M5Tgb+`QkJV zmNI+|*8O1`Xc}rjjzS)3+suzZk*WL>Si3f^4k3@)atwh&2h}=|NXDd+$3{j*b~m|l zlv34!i&_ZzHdetSte!TV2g{$g(}TnRYph}hf+(`>LIHUQ05$|&ZbOM9yuEF`LnPHa z&O&}$^fAVai~U^GV{Uk947#5MoK7Wn&qFaar;jlt%lb_<0l^auKnB!yZtLIoHiDYEnu*E-3cyY9G?v7R={IW8aCy!OjeT1`Sg8Hjb-(|1o=pwg?8+w z>hNLH&-tp84$&umPlXn%s##JkER~zn%DCp(<9X=l-Ies+uDM{`QXEL7Lg;U{UwPbm zTd8FuO}HvE{*WC{cF}uv!TomZ@b3Quku*&;P=7D&G9g`MX5vAmSG{0Muao!ir7L;Q zzu$&nzHRu?sFJ_!!RS5CyY?!rRb%%G65- zfdN}B(2f8g9bkomjCQ?f{@x$3U>(|T8~MB9qhPL;Hy9cyyzN0GKSwP&^q56QT?GwF zDwK`CR^U$$Uu^9GYHr-Ag$Ty?)LtGw1NYEW)X{Q%b(C$d+JB) zk*R$M=1ukZ!he@LJOD~f()tK3_6H$SUFra7K=sBZ=-DU?gC1);I(wX$nA-ZFI5-B%3{-$KQdLc0Q7$i|CYmIck64B^ z?19OaMc<|3BHZ`m1h#4T)kVQ7Q%v(%nckbu6@ydnq%EDba z(L*`Y8`mSfSIEy*+yt0Lozkk=PNBFfXB^^y-|!E&kejxZUL?~3O_9p;6Kd^Cx!`Np zg~iEn*vS=*cUa$Z`1ci zXw&ydNFMF#HdSZ?!j+d8MRXd;A z+aK&#dvhV+%>Hl7M)2%vbnB7o?M$V2+{GmOg)ng=*#Y#wVweV6Nx(w1OLP4oV^_Mb+G63J)#zLpVU(OB~Srqo=Ne|J|0tp6_A;t0MCC z6)y zjFM~-OqO;>jBc&2>V3di*1y>7p3LZdIe;sCE2;N=@$HR_%M;|?>&rbLW zQG6Qtv*E!?&}$3=l)OSRJ@xPCaa&nzTjARQt)AOc6GC5POJhg@WrYUOzlj#lzb1b^zCBrEP@o7Iq&UD*>p%J7u zlPtv9n@=SFRr^i`@D1osPGgD^MHxm0DRw6APFJ4_tRgvEq^cng&OxN&48xWjKbF2O zse{xcfy5!7na$13kxuiv+PXx+zVK!$$%dW<>;6`)di?g%2 zV-JME#AA;M;1%X==bT!Bm~WfFcVLZR*ab=g261JJ48XP($U9B9N&q1UR|2|D4}KD0 z>;#;Bz)64(3w&K$T3csd0`re_?J;Kd7(-i~`cWWuD$GwYq?;kQ9qB{Oq^GbePU}OD zgpYRvJC}`0%N(=+2)4Hop~EquZR9HiCE)J_6o0`$my!vqbXQ^Jr@yk;h#dK_EWOkx z1jJf5BK8%EP(~>Sdb{&7$Irf&&R*{%bSv6aD%l~A>{0mSQ-x70>%*!^I?4O)k>b#t z$I;dXp4b3ybx2HHG4`{kQID#5*bg_Hf!Quws>$V2TyO9uZJYr>80CdiFB}X;UhBk` zlKM>Ma!i%+_{YX%gkjWRt9N+A+fNoe2g;4=qoLn%?I~>d*gxo9sYSb4{&2<~T-&G{ zB{JXQ_0j&8dgQ>);8pp^rl9dltDZqhAWtg}Aq6#QoF~PIv?gs42UPrr&xgU_sZkB) z-rMov!*0`j8Gf7Re7M*e-+k8iSH{F9eYBtB2=B79I~FBbI+N~(K4cLXZ@lMM)S`DK zdm>7G-gl%dq1}_ce)_Mc)afs-eUKAg7s9o7uB?Ac{6g_h0yes{31m_jvm)<;01EAY zY&V;fcJug+A42d%yFE?G97ml-UeY*4FBaTqe}p8iY&}w#yf3%1FE_R~$7r)J<2x8H zZ}u%?eVw*$oj!=cYx6hD=&mN2DBt;O0KU36_%e>{Lilkhn2fY%8r*v$^O8dpG{)_d zcj7klx{dp~pV+yiR5qSjq37n@G3&h*5b75pL~i}=RB%N2xR#94m zwwOT%Ua03P&KYnH4pr6$K*!Lu60}dd{sw<7t81GQ|3UxJv@9`>&ak6x(7Ol1Evc&d zhasXEh7ruhsdws|cqw~?m`9t+{-vfHxY(6(5sVyx^mfC_Z5l^Rt4(Cb4GeY^!@tBQ zW=b!VtvT+M(tM`X)tL>-tL&u<6E6?um7ilIpH)Cb^Fx8R;NfX`JhKsr$$+*zr(mW@ z_$6tp=j>h?*&(tLWROZA(+zVi2tzD~nN&7T`2Xy5XL*X~&DrqT0GId9Q>BMK%YW+7 zdwArLkrX!j$p-2;tZ2J#)#F?XXXgZfhZnsIqk(o~@1Hx%z4y2pv7BA>i<9SQlW`;y z4&7g$ce}lEmP&lul&fUkv9Y~-c&AQ9E$tUCkadL`5g?tyE)5F2966;vr`5?1iZ2cX zNA-sS9I9mM|KKLo2OHj72Va72zA!}Z8pf925R1fNwRDV4+{uK7+Nz2+5T?Ouz1JqfadWlX zP{Q5RSrN1+QQ#s8NDEy7O#3cxO*cg)Fx(zDaPIc>LQ4!W;}MI1f<=m;`&tHq>dg2& zzyNt*HG1iz))Ja&e5BJm1Oi@x&!K*K;oJ)ltC1!E{}ElOw52~A8wWt7r-1hb00Vot z*r*JUumP*j^6&B*Q{%yjiMFm)WBFff0I37-Q($KYhr0TDG5qhyBE94YUwIU?0tzn< z_(?yLLc!;Xo@Ne)3jgBAu$%d6cx#67fm@XkcAHsTe}RkgGl%f&@yg@C=Qpc~YqKqk zK%R8utFeEqVSt7dK+a34U7kA!<%m3niWE*EcjTe!X_I&9J{~Vu;G=%Fj#b#PZBpOm z5{CM21%D(04lqsRGS8Ip=P z^EouD#hPhGbfZJ%_c-d!tjr`R(DYKUS0tv?@9(S)d*CcIl1c}iO3oFe$2$jy?{w)@ zKTS-eQc=Z%S|M40N3OU4CW+^ z!z~2+lZvQd<`>NJwbn^x!;CW`AQpv9=Q#>rPmJ=Ne0uaYd1c&_ldf$1h9cgCgcuSj z{g>LYC2}uOn(D`z-GZV;1v4F4?D$8x)xtg^>kE;5*L+t{rt48WRWxQx>z8(a*95LO z0+f$key@b3lkLqxF@KaQQeJKfo#Nz(0kI|aXD*!!z*y0PpXVNs#&eH7Zlg_7l~7JUIu1g1>?M8 zI2g)9kg||(HL>i(n3STdhy-GNUUOO_B|~*Y-Z9apKJj;Yx-3J7H)nxZ-gm@SjMI)B}W`q z;;NXXbDJQI;@3>6WhdWYK4HsGIoS~ID=VZ8uNnS>o^khA|KSL${-`1yoR8VB*kU(a zPMCv@Yaust_LYW_?e5|+x9`Qm@^blp7f2g%Jg%7JmY;}$67YYUXvIN%pj27vNfVC( zx=z#B9nOL$l$k$Rc$zu{oOJBA6AhB`a+OPz3s8eQ=+)dQ^Z0jIhQ0+E&ND&oF*HS` z!^NY(Dzh=6q9Srn-)R(IBL4{4r~HP^+Igcp)D;)!qhbRCBML7se@SDzm>pww9#80e zqIPTOUHtp&`-@1XrN(BrYhHDAH682w{QQ4#c)-~KH2nZXYHua*eC2DI4Zg4!MELwM zDG>C+Ta^$5n7C8bkw3aYY0sl0QF5ir6xCzXnHR1SJ<8Q%rvc76KAbK|((Tgor5 z4exYtnj`dn&Ql|bmxW>!_}pbD zWrL}Fo7zo846eVjP~iPfQts}u8hQeq8TA`a3t~U|f7KSzx)YOKceQbXj<^KB3l>-p z!wU?sS@IHJC%j*Y90Ii2CjDwSw#S#7*@CA4dzN#j2m#0gx;zJqTe5WYu>0wZBcu2A z+ghu$$jxcN!{_lQg5LN7;=KoeN`?8KE9e2dWy01t$X2CSbEIntG#0@0#Mt+kCfEIC zFz68tZ)@_#=5w=9#@G0wNbO4C{<{M#mbMcAHYCPaJk75pgtulv9SBpb9)Ng$ERtxL^C8dV=sbt!V}CxleeDm-jnGSY_n)5^cgvSXyVW|@$T#( z;-}oa2VJhMjB_-NvI{3bo^Fwn?$$yRxv5^0QUtmxFKhZVmUDh>wZBw37bxYBFVT5j2>VXW`j)||9T;@^Q< z1TW;jGtW~(5N`NqedmcOV>Obe{Y+#c{EAg)0?$_1*5$`~F`sRNm6zOg>a<6UcH^L# z^BC}=Zm(hqJ)t>!Fo7U2NzZGZh&4z4+=lJkS6T!VOanTM>1VHvl>%s{RFC zP&GY$&OUpuwVo}c%2b}ou&Df3d!Aq|*NmZ=+Sz7_0vtP=hdKV&(CWaK<9{LjewQDs z)fbbdG(Sz5_=jcDI@^>YAtKtv5Gr=OG(av!tNpWLV?&4Uewhxwtl7g)L&1O5ZWz{0 z-1oAT{}l9t=**~dWNr>m7{3u|8l3)KVtpBaWT-Kf;5dCc^^d_p#fWHon!8zi zauz+aTnx40>lbJ}SYDGNDVF{WLy5cgfp4_g^-0XJ<3Y<_^|R<4x8fEQ1a@q82wg_~ z?;5qGS*4RaBd~jU(C(G=ak@3h7CrZd2Pu$xlJk0EKSJLs07d>0T_<_*R@^y=V-TG{`)pPGI$M;MS zI6W#bZVBuyHP`~lanI=gUh7|*t*dOwAXeMQKkNaCKt#vtYT-IWT(|X#m)aAE2VtcB z7wdfkC(g@XOWeZ9Z(|_Bg5tbjJZCRK17Mjx$h{qq13pP$;|HetoO=e_ z#`%*QKxMf8db+*`cm@HvH(>e({5e3n)8^lo@y9hblw$U`w->Sbc+FFK zBS4}^$mpnY9)sR5y|1pcbANwy1Cfk$AnbtSrU2W-g=@)#;ha>;aaZ7@b|$F_H=01HDkva8p*+3xrZS8Hrur)sP+wDO)R!`|vJ^xSgMS$* z^-Yh_Y)v(*3@5pyGnEEwOglzaRPPjCmv3{glK8}Ep@<>s?(0Y3HmyY%BY=qrkZuLy z9&Ca1kB1d2F#v(0M30liVfrKFilem4v_@caVQH~o5rnn$5rFDyj_Vg7PJABzGoqa! zWWqro*l?!m})fF5i{X9x*~sl3EUB0 zf5dsj@bRKVB*wx(hnNjRv(o4a?mliVFSrfU2cGplR~o+%E8Q{YRe-3vqBxt`IHA0l zz~%mws%EI!uxFx-2Tzh$ucBw^TB0WF2qa^>a#k8!b@lCXIb?azpO5dD4!_7YxykQJ zEb2;aJUeRFCGGi}(mBTI3B9>g3k3S-AYh7~b>zSzi^t8JJMRiaC;I6TKd1-o@79j` zo2j-Al$)G@ZZ6_C);|5W7J#}lC)4>X`Ef~CY_NEC-T58F=G|TGz=@R6eP+zotV>m6 zWF7YN6?ui+`u9dY!D?Td5Y2v&+%VF^RdMt&Svo#Jr?Q=B#38$7 z*WwsR?WgAxKcSvompsC0---3ni@y@}ekP|U`DoiLOmNv>>AOPMg>i>LkQOs$nW4hp zl}^GDn%I+;q-UeBnW|gfYhW=k|E+_b`P%3Hj=qS1va!P)g&dcj*;(8vOvz~m4y6B zd!yHdXpsZaG>`#`pS==Ko%^qye8%=CIfM2`XrKn}v4s6f5l3A#&FQTRU2Tl?zlqd!sK=zqc2RfPz^i>( zJBD}CxLjfppZ$PxXf_s+NAb^SYe5L4j@d-@=Jz13#5+2hxJ!D9tp~h8ayT#?V_yR( z@bIJax_kj%GB-J2H((n9P-?{iZ|AQtJrpIhZv|VIYcj8AflupL@?n*zMGPQ)WhzpN z`mI}EetJcU}M%Ubak!D#3q6TH_oN;9+nPelyb!mlPoZN$w zCX|TNY6}Lr8u|D*`X_`%`g~Oh!uN+YL{Fbn*^Ow}6#pi7ypo)Y*wRgJkw`ig*;9>pyuRMU-cxgV z0s1?$<=XgNc_~Rif4P=L*#8-b8M1;v8$XhF%C|0>3K2~!5f`Zcz45HZl6T*F1ssMo zvxj0=LIQ`20drnA$?skPx|~hZG6N+rQ9wLCa1*jF1$v0U@bcvqc<|l;fO0S@7|0C- zbRV|1(ZD{KhiLr6O79NXuYfjcaF9{8cBimMtF(F_Q2fWrZqGmfqvi`9kVF^@ARU_& z)o}qw1=e3&;k_Z%@;fj4x{L03!F(-+bEAaRS*oAPp{^4Wvl6NLmqIsW@wE0lwz4{j zlQBX9`@enf*iJ`b8Lck=)?GXa3eZd4mA1` zMnVhK%=^zJ>S8^MK~tdNGAc;C`p<&a)j|?NJKf+3*spnu)=tMu_F^jmgp;TxOdl9n zYoR~F_LW*1tPL=B7c!IQkvd{COHL%B_CQ5!BiKRg60E2%|4tt|XxyVxvV1@NT(PyW z6zWh9s^$KCB8OWGB_;u*r^94ir<%HJs0y7FXO@`-7m(#vF@5_cuq`lgRR9pbzYpKt z)6Nxp?TAWxeK|&LkSB*`k&nEqb(ofawmYe8bH74v# z<@{7&s|)w6QWkBo;c%1vQu5j|@cp>Jqv=G_cj-mwIFp`JZ=dB&@Zh%r{tXcK$R2@0 z@jaap@)F;l_I44Ilc`HzuC#eI^LDx7{Xjs^3242Sj|48PGt%j2qvS*a+wXu!_9q(u z;Yho4*qSGgWh6{Fl9QL9tbuMKs;y$5L??R2ecj0`^bRZ|Np1gGU$ENmdizr{(%Z$c zv6-W11PVU81|RNXZbT9m5?(6pH-;`kZRRoW0XG3zaFu23a6+X@s>;&NO{;iUjH?G< zqq9(NSd{Z(K20wIG^^>SEiAN&&q`+HBL(Xp8o2ye9{Q}r{|)jHfdI9_Wd|$<%<%SYjp%BnD*66y?}i@t8_~JUS60%_yVlN;y?#D&?}z*i*u<*u z@6zldv-Fd*NSr!7}jBwk$n_neQlRENn{3 zu=hz8X^MF!Ch)xu|3qJx`z!GF3rb?zfRh`Z>(~>ewn(mhVWRxL%|R_^p?DEq<;fE$z!_Vy_^=`ClipQ%6Yf{H>XJC39%Ow0wfM6 z?LU}ap7V(89Lcn!Ybg9zD#li2FJbH8?LQH;dCh=tyvCPJ;`YwYai9VZ+=o18ee7iZ zYPm##8^s0Gkcq0cc!k_4TA5S!o=!4<+(bUR%~(0!K||H5=sCSc;^*!YPTHjBeHxAG zblFALO%eV6x|ylZk~bdzwzA6%^e^qW{(x@^O3Rplm$sikuM#gyWxuANNHwaK<@4_S zsb#do(;>;5%}hM_CX^$J3Ye*QKbl~LE;kxK0?+P*Y>g&UoF&L+j6Iwj?XI~ zl_`!^wm_lolObWFWP|^^C}Rjofj+UyQtW|nyH7EC5>7=A{Lz{?cO}NzY4|3i@Ys0m z?Mxrz?yY`6RXE5zh7$F|zh+qHdU07+W| zUxui#rn9;@ijq^|vNBUMvk-we;CInE<5$nwBgPmJy zx^6F_!n)?}UFPwtRY>R1&7Fe=QltaVWGtR~Impv2xxLbm&EaGs?qjGkYB6Cl)d#qA zo>)+FkOOz&WE=rL47!{gk0;KI)=+U}d!zVDjzMuX4pmuAZ>B+UG~gaBoz!pCiQU264b&P zVrr4`P7WB*9tw?LX~ixtQYRy&186-Q zvWS1&gm%|94U1;e#2;SCx!In~XTg>2_Ge-O6o_VR_|jkDt+3$hqn*Cz4gXB!@xJ(j zpQdFdec&We%aUJD`es>Q{?+71Vd{pak~_MBKdgh0QdVeb^meVZ#*6(1(J! zU1G_$ox@!^!#9k*(kVyQ@c^g3G!U#6$c6sy-gg{>I@!uC3tl&dldOmmnZN-evhYYLK z&WeOF9LCscR1juxO`lNL4qPJxQYZ~LN@pIYQ9_;v`T>{VSQ3-v*)-FYhX@VG9dsrU zPZ>A^y*LIumoan+>czr`7{&9%MOxbHBLah$XwWu;sEr(FN47`cfet4;O2Gq^1W`qZ1D$8+|V*h9s!ZUQoJ9RfG2%jp%Ty$QH7we zP6w!Lm?r)D%IQ!e!ILUCUK{gIed(hiE*_Z6lO%V%A40)f4n685;-k~lVF`!Gh*ei( z-_a%b7L)gl0`b-0ouX?Bpj*>rsh2#h_DE69I_Dr&J>b*FO$JO&cxIo4?bVcucC1d` zatHh*onK=z=sC=FZ$A}Wk4H5>O5@7BQ!1X82^3Q`HB7PKW)!T^naL8r$_~faoc4*x z6z|;=AICu&Z`8)1kM~rrUC{XzN4i2f52wrEl2PY&R6MKSoF7?wKg+;QOy-92y1D8pR8V)Ay7;)4vwlt@amx6frLCpBu zmeqYv;454YPnRXm5>pWok`iGe4?kl?Zwhpw==XK2PwjH9+y(2z7pv8;39>bkiXOIq z(2cnmBkGq~6&%w_qRNgRcGmA<7cILX&wy!__bBE`@LVaWug$;V+PcNDKBuQe0!TvVU3c2Pk;?=%zegw7G?H40zJ$o zUk=eZv zf}so!cSMt9?eOiygoQ@Z_=*a9=sXi`iqs92v_ZR8$@Nt=RkLwUjAGokmP|$AJ{x|c zszY2bC$nN8`Nmt_Xm$2YxRSIY;I-mz|9f3QI>hmn)Jt`jw80Z4EIsHV7gGnz30sHb zts%j>rbL{P95qQGvHFfD_o}}AP}jCG`DNSOxCQmRT@Rl==R!C4{K#sg*5FZ2D+luO zAkbDNF^$pIWX-BxhGcNQwq?+6-5UT$kTPNbnV8Ao4CgsKKZqUhIxI|08{fwTN;e_7 zVaqqF!Xg&ZZhn^oWr;shFCSKnx#by~Uk7{B7%csLQ|E7QABOpjC=MNSeW<4z+@~Dk zrD@%=EDZ}z3XVe+Tnx-lEN~2{(sl-}5yHFmq*-12D1LdH_2u}##4qBr*A*KT0l2V! zxN5G=s^K4DnLU!59;+ndL>G4PyI`tYEr`jk(M8in7$ zQpo3xi9h3n80nM|%N9M|w?fNG2I=8K%;n2)E_J_R27P5QA7uL^M2%0_QeGk*iIQUS zK2M3m;~Pq_=tF8K{oU`|A8dcD6)NFY*WdxfYzHTm77@V6ntYd4d|hte@yy<#tXiG8 z?`mF5r;V`S6~!$mCHV_leL(v9ppSZs=1*x?CSyKv_$mgfQx^6*mXa&S1)h3+cs&sg z$yJE|BiColYIRkbQlo!CaD+17RAdN?q-*Hna4K$a=RQ(UC_8~sThhsrj#RqWnu@_s zoH>twts>#m%f@WB#CWQ(7xZ%7r8A`&NY#kWc@sHjWMZ+SK6lFfa;2eNf(6^TFd;B^ zBher;LTd=@E!Nw_bNyrx#rvxLwON#o$V>VQVQR#;L7d`8 zVwV;0+i~LV)Ije;`8Gr^>+YX(pmu=u3(yuj zpISSg&ft}`rW{K7AABstm-t9fQ)1dZ+L9DL<4HWoY8fIaCSioDgFzRW(P8+>t<^shg#ZUYHd1JON-QkcT6%QP6S5E*;sC`M3t&d) z>FmuZP2;u>mb+W7Z?67yfr!TN&3&bdXoxcfpp&8Sn6pe&QB+_%iGmi7XsbhlYdLYe zjY*6CF7mJoN8VINTL9s_Pa>1TO7rWz_}i8E_~WAw_3WF+Jf!DmOZs+|VQ0Jkf{XU; zS%ZF)LrrVzGOPugi)WL|5}>Urtg;1E)f!(~4b7SYbLQE~%cN}oB~cKL&HW5WWGqyH zbJVKTBs(Y~J>sIrPLcO=2!LpoiBR~%)Wbs=eWGwp5bUuwbB6Uzk~ zstD{Is4FB>u#uZ|ih0Tuyr2NnzVazkW+yqt+)fm3bgjt?mA=?kK+YxADHOnT|e%8>kh;=1{ zz%+VzEn^}qH5X5VQjqzxjB+L)>F|cg-wtywrZ9G+X46oT%bG7@%_v(9= z(76gFQXYCR_{p52Bsqlkab=LHtJgeC;1#5J?Ieao=~?V(=DMWo@uBJgO&euD$(hJs zK?*4NI9%lBy+|2#{dfneYvjSn@uw zn59^u@;&)IbC3UeT7ZA4gq@wtecvO^usW#Sx`gxPTO?xPRzoVp<*C8{b!YrF^EZww zM@RGouQZtj&6IWhVXkJaj`)Ypc}WCG?b}6CvA+mpZ;0{Yk2DsV&LW~x4Dsq{3+3*i zNu0sq8>aSQoKfAsD!F)Z{HplyC=W*yo0J`8Y{# z$aIYm(KEHxdhKSIFb};y_qEXW_|Jv^4x<;4Mbz>2|M}PjV1NvjFe<6yBT0NQiE2@WqaA0KRSZ4%R((h$wgY6f zaQd+QczGNEkBkA379au*aIgS}rhob|K@kyiGc&WHxz&}Go!wMpz()s&AMQ_q>6juM zUVU@Ao=LMsaVVzO&8+tN&CN91zKqvZwWE8dFZJ%J*xT~U6C@k&+{A|TXE#dO6m~)% z2%!{}jmO1ESA8mqKl&E~%kb8#-o!vl&=i)gk*TOWY2y3$QoIBDcqUpqzcxQ(!ul+eOuApI=*_X@j|x&lMq0#hORJ#E9y?{^x6 zc?BVI8lP@Y-H|&HDoA?+(ze(24+F(Vfw)tfbS?taZ`*VX8+UI*Z=)BRlfu|ujYo)v z7RZJ>(r?Z+)0ByIK*dwrAYOJm^HCMhs#Vf{qbS_@=b=i+WkRt5s5eB6{Q|(}m$)xD zeFz4&3fE<`@{?bUjp42ir9v)0g1)7I)`R=(mmPk5n-GvHpTZ^%(}1QY-ChKzc3$~U zmBjaMNk<}L@1jy7lH@@-Tol*@tAz*2Dva6%e2b(3GC`XjUPtF8bTBoiU4nI4nDA=H z^FZ7`!9Y|O#}D$4Pf36j?sf6)>PKVQOmU6Y$5t-b{eYL=w1D=&;ktaXR z(oG5fkY|ce+B!`_3NZn#g$CR^ghc*u@X?_2R_s!@@4m$PsA-#_j5-(}*E{zwtrYEb zgkiSVTd&_vKDjy2a6cAS%`=Su!j!-!^91`v<`>i^c-O9$Kiyw-z0SV+ux$hk-(-o*L3hTBTp|L= zi7Tz1@rQ0LpH715#C_FqtCInsx?b+}i>-VMX$vs>trG9UQ5ES1_!a-CL=4C=>R`>d zJ9He-rKyzeD2KX4Br@EL48@FQ^3ni&tqrga(y_;34dWcYE2N2ea=TOxXLy9|GcYko zt$nA|V*p!()JD{=GzBAd#CR0EXg+*zlC!<+Ie11YkwP7fe2UkppGqNu{MCu9;sa|Q zel!#PAmStr=($cf%xBXzD_+bd9X+*R?^X(;D9JW5&XfUmfb+*pgHvp-Yq`(hAeZo&@L! z*N=?Duocw=RcPO)U~AGkx1}e@tsnjWKiS|O~haTgLC!pzqpAE1(trk5MLG~5 zllX6~U3*SkRp|o8w9Wqe=phYQt48s@5ePu!^E_F{n4K8?sk`^Vqr1a; z^Hr6jID6+aS3d#Zt@!P_j}Cy=o&hi{74TgFI7(XrmOymx4<)bbNjYFB1;|x7$>Q1H z>->v0MFwkJ`?Om~NF~vnoShlDZ!r5hE@1choi~)RNP(v6qq)+Td@Ak`EfS);zFl=y z&p{P|d$1;)rNMnMb%a7(7$g{!JnHk#f6e(m5QZSEAP?3Ie?bjWF;!EJ`?62s+$47> z;tb{^)}t)78=8xNj~O8(UEOYgoJ}61*B~Yk;X`ND&vQ^|N&|7o&Q^@G9(wI<`dg{) zxZFRiq@AN8ar`h5EzYI#3M3B^3sKj;Hjq_PPt~`A!L7A-PO0y!$A9>9rB*lKITEWe z3&`;+d!IJU%Wo5~?k=MnRM*-p8F-ef`~*t;tCN5HNe%**kPxuO^KkVuvQ4_i{0+9b z{T+;qx|5gJV1B&VF#F3CdzSZF9z#mf=D@&!BGNSgyZ|x)KedXXt@!2!hQq_UxXakP zeqr(;TiX4ZHGrwLsi};~JB3v65tg0!9TzM#Z=7rvr5DJNqh~m3*rH%nY`DNnonOLn z0!=Y3{P0*t7@4OGL!G7MNKnDIO0+G+okAXQjiODG%9>-DZvKmKXP8VGK)rZ<&2h*b2e>yOi>%?nhahfZIb z+)ZQtB^m-*vg{xKf-PVq*a}OI%hZ3LJCwRj!lySessK@gac01qw|sh;7#{#0AOiwR z`5j%n+=Aw?DRawEDk=w~8Fd3<>I8{xMYDZOQ%`RYsZACRFFNFM@-nWQ{cXos$hUb1 z3ld4jMi@02kcQPGkfUvHgROr>eUej?2tf2@R}~;rb@r+#XR!R}m;I51EOAwsLIx9R zN;vpxWMz5`E)=Hu9YYviZWo-Kjp8L!@$Ky81Hmk;(&)b6ACUolIYTXAa(nTI-T&*M zoz#>v5DWrjuY_tTS$>S88xWWe>WmAz;jQzNRez5v3$u3DP5*FEoMY+F|5=ZWgPERz z7Ku;IiWduOCSB6AE0?=Vi}%V-2@~&qNMRo+0)=cp3HZFIZSzSTRr_x0ZMM5Ep_!#pf)YN#}RSJU)5oUYbeE zj`GQTB2jW+QiJIWWX3v-E|L_a5!3Wsy86Z=!)wKFq5y*9~?J^D>83kX3pPi2^e{ovYn zw7;<>u#&ys<)1R`JM4w;fGU|D8OVLY0yovsHm<^E;{6*cR~Ej zI4_c=a_G?ta9XbbG49nrx1Cisf82JVdHr3sLsRRDzCn29e66)sR*wBr@a|n$!Sta< zDx3vxZ&|vP*oAt)9=EunV7W8cOE;Ir+6qznp5j~w+C$J&h&_W>fR_r-?~-0zar=7% z1Oziw{~jS(nBf#8%&9O?U=zP-0!$ByIdWNm zn6r9ri6iiZ-`M6gVlmfI!UcWc^?uv+Gg-$sj%!RlDr`>DWGaKM<){{>1ne@GHHoIA za9YiIY3omL9lw50VdLdSYM`ZU6b=l*KfC7ue(1zx`B?zfzD z+}74kLKYt$p!*?5>-)1;x*B6vUjxdo_AIg=bhmpg`V+3sUSdVwMvUflJDrIXZ}Zkg zP$nFp#xw&*Z7NQh{2fGLFvZHx*heHBt6!)lnndTu-k-Kj%&l7Um;!O~BIAH0&jcW$ z4=SIYuVDobM8HdwANw4pPU!J>z!M*MJW;?MA0La{_9gpmMjM+05#X2r4I-kJZ7@nu z%1eoc5bdK!qpaVCe|#P13H6tFS^dts6vsf($uX8<2L zf@}EDZ5}i1Gyl=AkKJe8yq3ntE_ZXN3BR8x zNfko#EodgG?XP^&H&wr*Z9w=i&hwhi1n?!2Xei?Vp1GOWIMk3G-+mark%Syp{wS|d zJ9x;i=XF!e-EfN3&HG^U*bBO$98)2|P53}Q@jGEND+eivwfNJQs58AszzoE1BXOjc zP{LM)Xgyy*^{qko-7&X8$+wTI42p;nLKz~Wu$1DN0L5gh$ipjf zngfOPKt(3oV;mg=(o(LQQUNMbu!>r!Ag-CDX3?PAH$s~vEU<@c%6O{%=weW%=o;UK zQ1opE4H5t&n&iiFDhzmX)62_XFltdR>q;=kfja-TzdG16@mqGK{p& zBH!JR307%loPs)ROY_B^6dQWO-q;O!IZ za)xeM`~BU#zn7Yj3hgH(Dab8RfaVz4qoA#OAPF`Ql8P$pV~<0j{b6}!;ZQsMjxD~R z9-R_55riqlG30W&lr)Ocb_08S5Fb9%ynS~6ZkxAu4sc&gAKsixVahQ^$jO1f17MM# zVBHd^0*pC1fzz9a)~qZ`*Md(##Vq+Pd~p$8mQp}WZ13EwErIWp?HzIx>`uVSshq{L z@Uh;~;PafWSjYHTg9cx(Iakd?@$uxskg+XzyA@eXyBF-=hx^Fq50xjar2M@i)IfPX$9QwH zi2FYHODLOHV;nmSH@H53sEktuTwx#g`(fDD?*&MKeF*b!dne3#PXsh@G$~JwR8LS9RDUVsCyIP=s zzN5vf9{oKPA90;eNxCSBp!_RHKS+;jLxuvewWL}CQ(0_=_SbthgpI7!{c9?YGp?9f ze(H!epR+o1oAtkf>o&qDxx%NAq@J2}>~(kr96R2T=e!vq zV*Gq$e|DpO&lmS_ja$JQ*UdqGO&;gk|G8chm*8d_~UlvTIc@mESU4)O{Z_1Q5EUj z)qCKMu5jddTWBTwF3l<=sWJ&6&_KcSuJNlT4hJ4+Sk1I0O6Zdp#@KX$mfoNk3O)y) z36rF;1NJbuzNuSI`~l?PxAECPrO6NFXnlydzw|+{M$= zlaW$@0F`a`x@HbrW)l0ro>18yz1g!h>$~uI?QXlNxSi!}YsMn&St<_3?CB=X8IYFd$%)vE9U{!&Mq+o4PmUr&coMk5BIUi`Mu;l^yYpdZMp{kHL<>Sy@t5l< z&h@=3!;XEicP#FqSGfhS7}MTk9|4q+ZVCVm0Ce!}A)@jo$B(>rhk*LJ{p{Vos5*A? zciM)#ztO=FUD;P;8hW}wnh;qob<%m@7XKD0019y$w55*~+quTLyhOM6=H zg`pd&q;JRhn?DwW=AK}arzbjmXor<@B{kFzhC0iYzzkE0Gw1J+r6B1vuoQa0+oMf= zIY+x{?pH^M|Ae(3c=KM!f4uX8UwpLl!SRKK-$A6`j-_OTu4~46aG23sm!jaONA|^Y zLdf>~{Z5^D_uMV~ntodo1<9E9y&4pHDYSE5sX;7=D%9ZDOueLhZ@aMBrCEdch7 z5DY5*7g_Td)u*S5mC^FuHo+sV@u$<2nGU;v1AaZn@_oVT*D=$!#zMH*B_51&vmKe; zSXhJ1)aa+3`!=R=zjT9Zn>&wMwlSX$`YVE_pyeU&ywzi15@XFnrTh`FY5=W27$T%Y zJOkT+d3Kr%7>h*?!w~m{GNcY;c!?jO4Gm~y-q)Nh?NEWwa)HD6o#*(t7F~U$6{$00 zu15uZ=kTOJ-`q`vJ-Y zz6={|q3pnY_Wr2?P(M=V5Y^n)|GZO61&PwT0z2L11IZz2X$r~evYD7ze=D{C*~ z(I5Drr9~O1I5}&Og)LzC8E6lAu~1nTh)a!`1u(ar%eH$=q*n`O@fUx&$0vwy8SEw1 zd0mz?HL+x{dNkV=1V<3w!62 zLJi=#84$az;dd(ogy$W1?U0&=hA>V`#{8#7!D(*}E2H!xpdJ~dVpcYs-$^FK?jC#G z3)^RoGX24A=kK3I0|G?mfUYsg2!WaQd(uMKbl!J7G@d|h1r4_0mvO_km@m!NGAW!y zsQ2-2W9u?Vpgh#Ne9lC*0}4#B2}R-O7vm@Q#yNfgF#(#na2?`Mj2Rgay-EU<oFa6x8Q=y9MDxpdS3j&Tem~1miH2(f8VP2B&ybD&~-U z=WLnr4cW|(ffybQ1%O0W=<=uC-Cw1{qFR~U>!loLqwi&2^LDqC0`_w267MU$RaW3b zMX2L2QrAuvy!Fyuc{L;$>M1~1k~|nuo-sjVBcykUNPB)pbEqN9{&jBr#g1Dg>WO-6 z$fq*Pkn73E27#4=FKRsCQFlrJP_fmR076gFda(4;d2&vGhu~QWozv6TfO$QVfrXav zB}ym@p1|$mz^H-@lNcb{k|*i0bjK+$r}K&YB_bvq#&Vi7k#hrPdfTkZ-f=q8EMTwr zjTekd<1DSaLy?}+SGs!|VZsLebxL55KIa8DQQaD9RV5g?BT==S`E_pnSr;H;l$6m8 zXz#M{-G{%Y#rM30xn19@OAn$9^-|X$vAH6v6A0*3H5%K2q0RKN?`L{x8E+U!+07I? zoD|?8YbQ9~dEr4CxlrwRO*?lSs_XQ!6M1_aCwg0k;LB_uEUmSNbEQK9AhdiAO$B!)_{IK2x-MlgX7|4iCd5FiRO` zFZU*m=%sYF`~7e4gs`W;m~+eT@gVj+4-QcZPhjmVlH&L z_2NeExVShq%AYw7oWfOVQxhPKBpO+H&?yU(MulUnTH-#v*v@(}xi<=lxEb9WSRm9XW;BkocrbtQqWTKYwqyYC=@5GT)S# zfj!ys|6Q+iLJYMx20b_S^lIUXmIDOtQEEeE=I^wi^XNMRwc^%2(1ps|)FmEh5WRnJ z?jU&98T?%n#d!9wv)|<@-A=yjFAsv)S^!WLc6NCh z`#{;EoWHMoAaG;`Un^sx^Y}_KI#tOI%a)G%$dL@lQ-hL1d14u(Vh-K@TJzYYbtEGJ z1IE=;(zUnOySlo%4=a(S{$V$Gq_$n$qeVc)5tU~mLdFhr{XH?3DAV@HQz%ERH5eq; zA8yI!p_QP@>=dpdvSAE#ppqApDLSCInBb9f!Dh zlsykAhka?AP)^Imxuwi0=aoTIVzZQEfLP-NsBaTBT(!&}He64I%1;OE zbHoHaGVu(iZ~1SU$NkUdb9|0U=Vd$$_@=i1)x~S43#vNkcv3t`u0VmS?f(q?P_Ajd ziP;?JLBNsuUc>hj9JN^TWv~|J6t?)qt?g&~#;rfKuW$d$`2%WZ+EuW|r-t3Ym-W{> z1Vmf<=t$JDr``2AU9c8IWz87Xa?Qbxr~bgX=_XbBvQ%hL3NrQkwWa7nm9X69)8L>y zmPCc0vHjk1XgjjW)aOPMhqphJx!u5O0?{W0GqRUCFY|%%#erL9e!KeX=3F_`r*0)z z$bJ$`l9+c7R`ib48bsRq9Y7>MGAm8DP|PO=BCB{Ha>e zSZ#(EF%09YO7*xKU#~P$LxVDzD&+)Sf5a~nI0YpzOJ>+8-TXlsCbZ_Ffwmnsv`M8L zp|YXyCp%23WH*ieWI~&2MW?T2jn)>w#5Q0U>`N+b^%69|4RAQ>5kVg)l%)?zRDPAf zgt%tYt!S&IyjREwqp93#L(kraLyQDz6vQovXS4*%FqfYDwZ-vO&{8@i}=p5zmd{7Rzr3T6yx%47s@Kv5@Wr}CGIuTwffsv}9J}x8N zm~MTNH6xO{vN=yjnfK=Mx)e+G$Br}fV4a=&YbeHy3z_gBsq<(4&R8Rnw+&J$o|gm) zHL1(g^+!Iv!6(5Gd>O>RH+<7H-L&`8Hzo?KUKy zIr_r<2lqpt*POr&v04YIVm6TWG)a})hG6^?3DHrV>wL@eEy_=fJ`Q!5rwrD@u&$>4 zPu;lK$Oyl&tc|j!R-a9TcZylo{?do}MR5`6!e47R?yWPF9PEmX9@WkqWYpBt(s{zF zOS-*+y=|Cwry||2pW|jkMc`Gr;T!xd7Wc?XgfApSSY8tI=x97b**p} zc^=GPSzf2-QYJg|)|xo}>#Pd?Yc->$BjSi7M?ywkcQwJg=N+z% z-SnG}P^IEQ>r1zHd;&H(G%&|qSzXSbKi;%Y)^B4_e0+IL3Y!vI0#qL%-5Wh_7+b+N zBQm=^Pj}fg0Hz+gLFWoHmx+09evWA3B%;|&0Md^a09%L~8iWg7i95EmYwJYDxN~V# zh$%l=u^N15H8&FYnDa~uK)lFJtX=>Nme4jv^3CPQ_>I3$56%t*m%tZ{*P(*y=F*hF)qnh6=ho*C_k>sXj%|K(mL6F==3ZyB3?6#7xNQSYPk{npSQ&q_3T*3~$L zwaq86{6;4-O89|P)|Oghxm)K0i)rwk32e_dIumZh0&Qg@O<1W=i#LrPmN|k=_jwP! zm#kYQRVM#T_@!+4md3ZhTK0;yyJq`4X=3YX!%Vx8@;fJ@pa3m$akOW{b}fj1vWG=s z?C|c*>YIb%e4le4fD!%eevFs%yhEQFPCzy|3G5WEXjZ7JpgHDN4Ofr)Yb(S`THrT@a!czUc(S4MZ#~XPg(Z2ZY$2IZLT4 zD%vn-dsWEE-3s{3I{i*{eQMCggx;Fr_yK6{CyA{CE*B#n`sl^F*6*+Da#mhcfp+{bodS0t&zYf$rJ>fEjwv$C0L1p#$k-nv(6r0c9pc4`Q2YOwI;*IvyKw6(9n#(1jdX)_cT0!7ba#Vvr=)a9H`3i9$Oef` zY>@8QG~eHI#u?+g@InR`D6rOg<}>GShMDvM^~sWqmEj}Xx$6UMqmjhN%(UceXxhlP z$~2#&c+SEY|E!);C(uk&D(lk1%%P`H&oyT9m6rU9|MLQP>{0gppL6*MD%(#&*zl>}LNJ#4d(7Qa?dBs}@8eQEKp6vG_h?#tcGSy;x|hDXK;%)dn6Y^Akg_a* zviiz6>i2|-fe$1#0EkTk8Y|nt5g&hJIyN4WHc-^?M({@WWoV=8$-()Q`l~>cFAJ2ips6uh`r#M? z>YKaAzMxaDteRv@7@)U%uP8%PTSw-nOP;f{GbGQ_(XsZ=FtY3RWl0H*mscGi1ai{< zy}t+8$a3||Lxz1TqzLqB$U4@5ljX)QT*lPC^j!}cfQ>k65(J;~jU5+HM4phzm;7S3 zD6pMw4tsU!56Glx{Vyn7f^;n18W;oCgqJIih|73{oFw)bRhcFMgG-xtoyKxzlLNKG z8k*ndWuSAT#}!24ZvF!9aD^?yMU0Zu2Dw8T#~!v!pEv<~RhTnB6m^~eD|1>y-@3Xt zFq3wI8@jnK{^ontWCjrQ2EHI^c9Xz`bLb2!Y7{X+pHjM$soI5Xcpyn~k$<6j;!j() zXIago`8K52O1j=d6D=6VU54EmCe#gZ+v=!o83L}(6&cOP@IjoQ3K3{@_k|YJx=rUx zozB-gA_MJ)nKuQsi-Kxqd~Ca~z**OOv+k}ETuZ_fZ218Y>RJ;#`S{xZ^mru))0Zhoky)|tB1Mt~F>4v-4|qgc`3++O{Z)YRJ;myS%Xg1HlKctrq8z{F<4 zvpxk@hbpV@F|Lb;vk60`Ch0lLQhYs8iQaZJA!7jrG?COSEU`Zgg_sQG#sV^dHaSM- z>Zab{b;eSl`rzC{2%ah?4cC#nB_=uz7x0SO}Em9oxt5OP|B7; z)R_4hQN@zR_a=|8GhZKGU=4)}-ve?Y7)-9Cv2g6ss1w-PI;gM|!_OTY)%>L5AIRPFqBm)*0fGH#RH^44IaTefOj~5%yAXQuUdEM6Q7<6 zFx!BlOmHLbjPI752JTb~qg@X67}rY>AZwhzuAFJqw0a2T@2x5#4g3?m|Ir7z$&)C? zH@hZ%G!)s0I8HZDd-qsOA0|_=U=zY3TQlwWDw_6oyjjAku?*)`9vPi0-Ie%Hw~y&n zqD=&D;89{=%r6JAho#^p_^#)+dytP`$fT3476t3Bq^pO%wDc013^i#WzDJi!Zc8b^ z#k0@-WV49e?3##@qhAsIef+OrzG{W*F1s5WpRdbCSVGr8nwn@RW?1lj@H0&qjMC~V5FzOx$8i23!Q3zR4io3GFEWi=YZ*J5AWG}P=?c(8Fh>s8R%4q5}e zoJj(S!>_12kEfnN7@ENZd+C86_x+n4POb|e!hdZ$r6~vPPXE@}x`UfV>t{^(R<>#N z12qCa2oX2mmMinAS-vyl8bZ~DT#jc|nyA&6T=q>=Dx3)uH7C0%eja}*lI{-Jp|6~4VUDZ_BpPOup0<0fmiZ>k(3*?1wY2u%%iK|fOKXx-V z%$k30KE_o{+Y>ajucX@L9kB|#d4K*P_+HKw&Q5>L#IgfVOB-=|9|zdBAKr{l!t9HJ zR!0&48-l4xc;9)G-*!xbGloPpe(gJSm%v+z2urPsP?on0RXtYv|Ghm)-(%oI7Q^yu zNoW54rT@1!rMP!E=CmiP1$HaIatHvP+((+;!voLBZ*%)f4Q-xH9g$Y&GUcu1)z#K@ z=9V7-iUngVQ0MCG|5@brw-)dVhqxP6nm#iK=7-6CTXcToJANTQ?jh$leP&;7_euug zD9xO?3 z;lqx9%I0QwS4uEC^>`st@kYs6rYB-*7Wx}2PMn>w0}4czX^?N{{cKY_aLWKoj}vJcvLt{Ha7z<;^tiYe_EYdD;dTF%37KmP7D+;XK z?enXdkq01obSl(4@*fYpb0N980E3T>k5rHf4p2VlM6N&B<**;0igdlK{=g))FQJk} zcG~m9{RajC8ga{hV*_>%(bs!@7OX&nOHjrf!UK&KqVv(~ z90@dXIL;<~Q%JcR%2<|p{R_OYHrz;jHo zN^fFSS6n#u^x26STLFWu1WvS;={!Gc>Y}l14M2wW9wE2;LG!6AE{?Xj`YgDZM3L>h zsUfxh0aEDdEPf+jWn}ZLV3f4Q4+;@ExB6xK(!KJ*{bsfrRmpWoI}|Fr7%JkbDm0sONjuYBM*> zM{d4NFn84c8D2)dk+-Mij4eL?x5E_jv$@SjfOrn&)l3Aw>o<2_&WSC+FwcW$SJa0e1LE3@M9Sf$yCHyD<`WMk>-Fc4_o+V5Ve@ zY}+b?F1^>x$%fGSAkojbyE`(Lhk&0WEQJ+=J0fM6d%$1Pd8Lg1pco?N6X{6@nloVc z>TrKT*nFL$aCtg~rT5;K*5o3TR>tr;l>UTHPb6jJW;0)xLzVx7tSFkt#Ne z(j*hZL~6HQghS_Z%#~4cm6`N9*!+By6$JmeIrH%_+M&Sx`qXH>vvH{7BW#cYDHq#+QG=jGyMwFK8Ai18V zG#P+Cyi}-Ne^N_^-JHzPneS zj8{7(Sn>W?D75KoW{__S%OfvV6}cc}sdD8r9m*CO51OHJYyHcZ#cgGYU%HBUZM)V5 zUL({8LL8;>ErMlzxSgYAKR*&IAH)mM_Mi`GWI5HyUwUNFVv!&IXH%DXySiZRXmhJEY^Me{P%{>?}pE! z*eS*`<_D?a@PLz)fCud_h5H_ZAHw_nLJgP-32bOntK>t1QMUtnOa>2qI!w^!O17Fw z;rhg?ea*T3z3%54#NTse1#?rr51rw^asZlV{l)yAQtj_+;AjWX1a4oT_~)a93p{9) z*&ty3VG{IU{W{WjPr!kEn3iO{1QGdDeiMxOdr z9cXvO#(@C{7)WlOUbfhBt!w$?vQi(YY34FJtVc#&`X9~uE%@l>J__YWSQlW8aRDm~ zu(s6`;*IvSz@g?IyvZiV?Ya~D>{VA~;mX{D3+a&>=&H&#c>e?Uzzj@B$_UqJ3(4kJ zJ57V3FCBmz*tquwvw0+*_DnqoySub$>DL&`5H*IICgif?b8^xcWGlfktna_}wGqQ9 zx6Tjo*tNbuJp17(_*|*`c|qw$H*xLp9!E`VBCGd?4oF<8wi$CDVCZkIfB)yc+tw<4 zpE8wvoom_ECWJe*w)b(xh=zNQWy zaQH#3MJYPD>WRK-l*VW$d(34j!4)`kQl?TG*=;?FOAlS@QYEjV;PfpY^iM=hH8~vj zUA{Y6ZZZZL?h5PoiQDFDbYJg(`mc~J*`06~*=^xH{W5!qglrg&SVP3|eu11|+G{$2 z$vta*Fr*KgfGh&3pc$hV_tw^da4g`L`9r9;>)VgF-!0oij-A!a#U0^^7TunNwpdcw zhtUEH^7~=aZSIUr;d@0W3uQV6+xc{-9tI>y1A3`%?9G}rh3{Z$jg$ut28XxwWO;60G9=~*EhyVA8Yc3a>wo;+EMn_!39G0517#8F z=kan4q;2I1e`}cSRZ?b&iDoY-XaOS-VZvBVZEd4ItNdb1#wbhdj#y_Glryk9?sn?e zxh7ml`#7qsy=7(`oxEg$HSn4F%rY-DWN*O{Z?Ao?C7Vv?qKU984-COq48U&;aD)G& zk~{#`LZGAwK@r|}9B_s_K0XH4l#Cv;D`3}|c8vmGMpwJRbOjQr5DGYc*5@&wD~m&9 z@Z+4=P`I? zfiFPntAn86hxl?9T_N_&(|nk2-DcLpXU4rYge<4cfN7@qMDKZ_(X|NF+^hz^u@2ID)@uhz=idxdZl&{#SSd&3;Qy4JG`{Sp zhDlr0N>b08Z1;@VkNqvrswaP0>l?I&4A@o_&eypNFEfc8MHIswTp5n9yBod;8eqqfp7OcU4Ed>j50lDPMjoWW68U9fo#N091R= zV+XxtAX)sa`As?Jro-Ph3utv6$cUn#{uzLUkK=;>UbzCb_hkp;{>Akwg9vwovDwD+4 zz^7AGdK|*VGML9#Qm~8r9$gg1os%3!or{Q;s5|&M6kdv^N1ubM zueV(*iHr%xl8aTXNfG#&pRHQs+Gf$2ZC)J~#8H+-f8+nzMe-+@M5!&?LS@!0d0vSw zyg;@=I=068MX~zbW83=%ox8u=2exJ*D2J}>oa=4v&hS;*&WCr{%xN^GLk~y!V_js- zT6z7nXuaR39@0kwq*BA44hLfTkkr zbWI@H(cIfRJNiiM-R4}9zB6U|>V|ejx(#p89{<%~Va0$4G7X?a8$bnq&!NkHo;zR< zA!`BBw)h=@O%D*==V~$swK)svcNCuGY{d@iJ4U`0g zZ%#=)Pgi+?(b&*_N1%N3yxEw&6WBRu;5PR31a7Y0!BU73tL<2VvwXkCQhShcnX(fl z${h%dZo^(f_gi?}W`Lg_w0?eZ@z;Auy7dI$FXeUG_&MTZNyF(pY8hMHp;lD_44R=z zz@k3E`$nS{&%`cMCz6fKM`=CEz_q`1*$KOgTv66)BsEdj!=oWQMF_ze3lyHkNE?lk zG$0(qAKQ05!of-W;o+=3NP??b#P1O0$@^|)GxzGEj0H&#idEk)Cs5@wxNRMp=AQXL z{vxTUqdnXd^@F;ao3?2s0AKr=~Ep2@{!wPoh6EIA6WQaN5h7vC=;+Ryb0+FzW!YL8>y(0+31Zm zJpaQ?^CDxBhE!3Ya^FXbVB695zT3~eZ!hPNMrkrh6BQTcAbF*Z%!I0=n=HbxNtMS#kamzytY*`5V=USqJ_j@La z96`~huRFm*C2FR$J=z*F!mL+W83n1XhZbv@*1Zr+-+J{*UUJ- zSZW&DTa_|7`kJmet{wwOm6wM~-viELJ-&R4rS;zG@R9$yPzqlc?g{wPDnLIsfCA}% z*Gu)UCQB14#){*REF5e|QOnl_V!xsHbA1>T2DlT7&q!-OHz-4DrVj@txacQ{W(PZfyMZ*u;*H ziqMm8&cA0Ae5u0zxg*3QlRx-gDEHXDG(}clPF&#+Df%Hj*D5MD9+fDr!E1l$8ok8* z^;-P-dyIt5<1Sxs+hk)$zUWax{5Tn53}Q=lAp}5du_`rScV7rfDz21J=q3;tKpqqI zEx5i}RJ#UTI*E+2F0-w#f&Xqtpsq~fT^>Ok{3s!CFageIN1(b50thp#SxSBz>;wSI z*p$`iZ(wuLm#{-kMZl;&^!jca)@YItcJ@2n7b*jiuaE^{zGcv#^>t|`JQ3*x^T5EK z+iNkUClmI+X3Q-}Y^yqSX%i;zTy`(b){?4`sKVOSan0kY6jGl?iwckJr1M_Bk&3G3 z>ySS%coPRUJc++NC+x`5JOHsp1=8?qeaq-{r*ORl2WOph(i1g(_AH_qboJOAamo3h-g=F;UE+uc=Kq zxWy@!Z=5d2mHArn^Ua5YE*5WU@9M+5WOFgm{s(LqeOpZI3v=aW5JCnfNjhvzPu9$9 z(24cyjoMo}>lAPs1ICADz~>8)1E#qDee`Cx5k89P%8Lzej7tMoWSZP}7YhUet(F#+ zBs#}0lixpAP9d@IAC;T|NL_pz`R44OMS(se0;Jog57{#caNP2 z;O@T!OkRk4-&ptGp2c6YExzSHz5#~!vEb)1pqvhv<$;c}fZQ*<-;@pElPU`QVn-|n z`X2S(04v%wT~h4(3OGXKi3n3v>$LjBz#piT@Xfa67bwPjU`1cXZJ`6Ay$1L4iJ_P2Id8RMI zrn{il&%F=(o1;W>skAo>R8Rhkc&#Bw9Mlo&1Gpv`lqk#}$GS+j;SA}s70sAqm>fxH zL7EnMWtAu>dRys3viJ;avf8ZId8!pdOFxz$)PnB{V>}hb4>jD;kySNW{FL_UF-!*@E>unv0dn3n0F0pL?jOss#hY_TK+u5bf!yDPGKJ)iEQF( z(%eNPit7=aM0s>YJSEc+vkdmi^-ys;Y(&E!flHEPIT!&-F|vY(a_f5{8R_`4a6eA1 zUU0XiE1$6w-SGGKiKq54a8W0vwTqrC`LAv!!qg-RpSymT^@hFA_W+lO1>fhWU5AUP zUOirjiXE&zS00P7-1{uFQoJT&NF6irjRc5TvIfVWOzFRP+B}=CRh*w4p0+@lldbM1hg?@yDpaRZW)tEM4aNFp||T6iaQ%d9*Dp zxt`^d0r5a*mXk&(3rzm&RniP2^?zOfbZ07juGKLll8?FU-)7Gj4h2&~A+xWZm?&~# z?p)}R+UQjd?~3y2_))Jc6#0bB)(s#deF1TA_s)GYKG!gjCh9V4(PyMp{kvPJGSywu zDb)4&0~J{zwSLDj8M0N;6T2Z4uNP7OfMx$S7RwWdAj9}}c_M6jz2$qk89j!HGm4Sy zWtD!*TMFG~nqV+2^*VrKPmLezre;zzSe&ss09`= z=5Ga11E5Ij?5wG=5v!ECIsV_(TOV}$<9UGM`8^;rG2(H*N`2=Gu>t$naH#cw>H|;h z*L(a4YI%VZ+UFb)$ZPv1lVG4HUR{i3hKHl{-${27@k&exw03WvJ}=zz0-6V=W*9c< z$%b_UA7y6PAaQv!@@FC}I${pBEP0U+gaU7>7rT;f`S9YfmJj|ieItLGK+UY5jw!Jo z{_%2v1EQw&fRR(8C)v2uEfQE4UtR8t4Vb>&nnHSP#f)0^1+MNzd`f08=%0h%_QbXJ zi0nwIdT0`8Ea)Z(uKRtC;FE?dI=>h&PyI<(r4biF8fz9I5-Vrb&%~onz3~^Vaqr0alkK%*DbWaJx_8SNYjf`q`mrV`S4z|E z`5owU^GJU_f!2S7e)4rz^+i(1Z6r0WdI^nHc|wErLK}+ zw8DcCz7qavCsn{EPmMO%dSYutbTNNQyKB&3B;nJ5&PG?qEs1g+NGO{sK&@aA`$$Bm z5O#y!cXaKmY?K6mKl&9U`3lXa!pfSvFIRskL!k%KzZ%CF(vV$CflCPRt=IQHG6Umo zF!cPDY{RMD`nh+}_F?{`*!ryKd4LJp5R`20S8LPsSi%q>>I24<`eoE*0dfG01Z@8G zU^wkn$v*)L!+(Ei00H2oe{d<_6?EE}p~>1r2Q=o;0|dW+=3RTyCm@9rOk1;=rbs#l zyd(f|c~0z!6~M7OJl)%I{}!L3Q%Lnf>(ysn?cblBMW=YXAA5M&e0$-uvjAS8Kv_%D zrmX81UL;}}KoZ#mY#VLJ_8Y2Fx;DGkF}0*7;kvPM1s&3*UC*a|J(EWDCi~lS9#kk# z^!vD)vf7~J4!=N(Jf@3Y7~EOrZVhQgESXf)V+qT zKY?8&N>=6it!(+w^$GO3ZnJYlYfg05tuskG1p1|lQ%c<@+!IYn5hs(A?6C*E(C^jP zdwB<^df4=FHzv<4|YwAPq{$SZy zhvy3(9|y*_88)y|i(*xcBnsZjoF)WChT~9+O$i+I!aU_L8zp{4m`gC0E|pB+E+jf~ zI-vuYDI=MP5Rn7=S!+)CX-h4>m1yegz+Tj5h&m62EAH#7>}s0qA+q zK$h|;{m|Ps80DELy(Ma8AlXN;8xYP@|AD+VB$1lj|H`$kesgD=CFyGNN4?we9a(p} zaYsjFqgGATI6kVhBL`*1Cq=nEx5OF8X!n-2+;MJ>!G3T%RMAexBGMVhWQ7 z@1XQO4|1gH<_On2yLk* zuvTkFf4h|S#|QLKPO3i~3aS2LV=1<}szx#P0FqXzr9q%bT{A_RES2$ju0s6bkWZn0 z?Ub6vU~cjC^$yaH6|(tfAkS$xMrWA8^q!~eqlf0qX%DO>8)fxHFP!z7XhJJOs4Nxm zyH(nG-_$u7Lod%wq-5;Jv`SxfUiFzGkh-{ z{MCx79jlSSCSnS^JMDL`oPgeYs-k!A!RzMsa=C!>Hgl@AdJfHGj0Jv} z{$+o^CI#J;tpD`YrC?WxJqyPoVZK{+kY0UBBvIBA*&IANTrfr&aQ#(^` z9r!**eQVxuBB=Fz7jo?7bKg;&#P7(P2uYU7vzEl>;s{IHwoomFee&icgkusf16Yf4 z0CoT<0&UskCG@Cdj?0XlqCgod>2NQ^2EKrQj2-^XfNSOW&G{(ni)mdHOGN-)65}~@ z@OBv%K9f_Ca$f)p|Lr?T8>W|IVoBpUyuldbf=aI9pP1nj!ukUC{}NoL*ReK`9b0{e`#aeAZogy6m5y^O5AEBnYhKI#N1Yf=nC`h~d1ARWik z|J2YD`Q2ZE(v42vYayVxN}m-7eF@keLGXZ?ZR_vM+OVrKAI8`mc0m4I1%RYWhp}W; zMD0d?&mR!jjf1V_V6ASrlP6idmGw}tuf82^B@K*HD>mIMu`otDYyzH!FNBt>ys|(+ zyW+$~mp9;^-1QB5z6?^-Nyh*M<Bu7`Cn-p8%4*N_pZ9+kex1hH$G|B7jGF`eb!ptWGe9VMrWTdZa=fYL_CKeitAzY+^M4NCf{FhyU6{6akcMkAK$ft*3*=)wRBE#(2&?=o|_dAfM09U)i(RKmUhA zKwNbL0Aw3lTbB^jb8W#j-vA+4ruTk?Llakq4EMHmQVN6R!$`4Ju%LNum!vHw4%$}j zTD|Kp@lUD4=~JXEY_9y)Cb&Kn>DDl7dQ_N59AVfWGE-ySG_E2|A4uQMgP)<#W6sb1 zL8lb2C{lhl*Gvkye{rd_Pa6rAdJC|~KOM4x*bks=9DR?XP7a&f1Y%EIlOrFP@TO`g zRcSTyw&1>4r=-Ygqu39uW%57COzYu%bQ6PlnD`>bkBTe`p7B}9 z1WFM`^Ari+X77kRmLKlC`{w%I+BvS*-VXX~ZJ`Ku;?@Ru@@3;$sKDB#^{Z1(6RSHZ zR|YSsGW~k5Z=AG@hqQ9)-9afbDi_`1e-ZeslXS41qxXXd{#{ypkGb8i`B~r2IDAfz zbo|1_=7R6iJ_wU=wmW#Wxv-BZ8DXe7!6V&zE+q8@YssX2U!Zka>c_2^!-|64kLtn3 zKwL?BeAWnAJ=#x%HA#XEftUN}pav6+VY+zqq_OO3NFjRmxH-qQb>Z$KZdDkJi@jap zOGmNPduF+@GxWFzn~p4AonJ#PTveB7KPI% z&t5LS*XiP#c1ps3=-Guk6@RuD<$IgU@u_#p3d(+Hm^AA$EbmPyht+x9@H;ieW4Byd z`{IfvcnWBf7YRotd(5S|I_B?e^e6kloT@*6&iFIM?087+V#l;QEE!9C%Ux|DPT@eE zjjXMbP}VXXyQ5foggkTrpAIjx6sIUHol&(x6MoK==y~uG`ogWRH&h2~|HiReqQ?eG3sdyFPJOTU5Yd7MIIGVUajwpGD1k zp9F9dyydY@8maC zO(vqd<_2A&A7Q`tckQHGSBy)2#npuQ#(vCHcZj}acUiTR!{BnzShYfv7x}pamPm4b z%DkB%_&t8*k=NP0P;Y%w<>n(`wcZp12xQ$Q;XEW$kd~4;)BXDEWwqBIDM1eOL$YnH zo9FFmm%gI;eY2+G`5dag$jBT$H`qy{cZ85jLi=#(YZrmtosqccj1i8Alcy1CPPF#6 zwtv-4vx4l#9sU0}sDL%L@9{?;G3~J~3?KQx+pFB$qcTYn{i0@7vgn@>l^wYTL3=AI z63j2WIKO|QkTG?8BO#9xr>E*~UkpOZD5u<0TZXLsfOs`5lM6WNdvbDx%|0JVVH4}2 zhY;|HwaY8`Wlu>+bwJbb8|A@9<2qhdgHR zkcW+ZZY;0dz~{i1|4BjeTNbapTasUfwZZY_$~d#%J|;{$E^8KQ=>nBf=h?C*!n^kO zp1My@ztrZi6fS0qiwUDB=TIZG4;bq{7QxRFwrH|u5xG{#Igtvfa)F9mlmAa!-@oF&8aVW;S)8^w=@%UP2lmH}*@XNiU2C*7~W4 z9^CRT?9M!7Xr3djYpRaiH^smHBzA}|CftVy2^0&AT4I55O0X0) zk=5*2c)|ow9C?!5=wFyPx-Se&-bRDz*oBaaF6Dvwu0tPJrt1wDY;k2=ztYMCpY+rs z)Z|^C>d(_k6I;4m6r77E(!jm;?$>+3B{=KM;Oe7MBYHU>5NL*cq>5pL(}k%rqA~*#KnB!gU@YuVS$Q<_Qf>X?Uy48)Pccb?68RhkO*-`SxCE1ffb?|0D2YZz zw==QCP>||`q6GwnXU@>{bdxc=x34-=V#FF#PSs>CmR}xt=FAj!HtOfP*P@p%x_|>k zj=`WGf39qY{*0}ZB-5~8K&4V|MRe;59whq%h3zmw9M;92UZqq*)2*F_KNmPtUQ|qS z>;vi`tE92VTv@a_fE4_qn)nQ0H(3>H&e`?nGb+TpD6JhDI={;9+k6UUIC^cmO8F~S ziwiQ4{#=;Br9M{({)u00pp$&ZV!HS{L*jQEd@DmwDdzWTURhssaMB$&(QNDn9!B62B*PL40J2%lLuME$rb(?9D~o`^{JAGh?td^Pgkdue&^I9;S+fw z#A%vQk|wL1h2ud`=lGU9_q@Q6tU)N=&2fmvE5>~*f%DFC)m_?WTfv_UJ<~tnZ=|W2 zrF#Oc>H&kj4~y#pCKQL2T+5)8;7fhKZ%ZnY`DK%o3_5|1K1wvHB1`u>8fGu3cZZ8z zTz(H306`!s1*l1OeHh%ujA*XE2foGfoA_q5IwdW?-RTqrUX>7@@cM1mcE@C;M!^b2cxp%9%uMAk4SR=>=Cdpo10_V{lgAQVl(OVyEd(zcaLYB|dDL-MECBlS|7kvj$K=eZ`-CF$|p^QC}R!Vt}OmC7r z>C}I!CcD!ZD10D}Z4rGc#>v{ea zW(8%8J!*&TLus z^!dTt=b?=MetdC`x^(O(48#o+L2jvzzZ)aGr4fH04JFANuh&hU1Zzr+OmN3&^I1%| zeZMAwgGybV?ci3}YL8l)?YXD7IM*S{#_aRw?|fu8|4bQIT9X!)3}fXKEM?Kfl{2qm z=bQhgOWZ6=%MB?0NT>k}c#SV)jT6t`ZlA1Q<|C8?Kkjb7iPiV-H{1Im@#i7@h%fk9 zpjD_!-R+oe!p|tx$Rx}lhtdFK zPP922q5QV~GcefX80`;SXU2Su480)4hRM zwxCEb>D27P|6jG^m4DI?hM9b-_IsRB`lzmPR6(suAEaC@UeA7c1 zkA^hwIPhj*il>U*!H>r19~CX^D|ZA2KW8vT6JW($aH_Z7l}zq~j()Xl9e!!_WRyl- zsIBYK#kn9awK4!9_z}@QA0hl?&8jG$p816gQGIIdPEdeicRG)N^{N=X7zy|X zDKHr8C37GWEPZ>;pqWy%2)w#By3KJ;wbTs`Hhql2{8GDWrfcx^bvs2sBx3@+_%cVJ zgkYzLds$G}SJ^X|OPP_1rP8lcD!!XI#cLU*lU-bDpgGHV)##pbwN`UGd+mD_E z$)Np1OnE_019ShkXAJcd(F{htm)`0R49k)%IQj(XpEk8tmxCV-lnEW~8oeesUN-jM zM{(h~k}gu*WOH~?VKZVCwGIob0DEsH)=VCS@#^@>9~~b%C%y!}16?}5*1zTUy&anl z3d}X#VJ4NJ&+0K2x#)ym`pP4u;~&rTm~k~BNPb!l+}#;EaXRNdKnD!+R=%@7?%`|v z?VSSPLE^YGdFqOXdkztqYCq%PYXonn^Iu)1DXY!?wo$JQz;2ON(ZUA!bx)M_<`GVF z41gOhN52YG)GDG*NVJUjtv#uk0k6P8wS-j|ur0`5`+0c3 zpzry*?|VrX0Do6o2&^2-KTMCJ=$$^>aGdO>o!SpLxMVpwaflNAhQlj=glV$0Ro%A_ z-U|GILZ$n++2-^7$%vuymkjg!_eWg$8FYTQkoy;lmR^$1ljdW7lcT>iP@ih! zyC>dHYdybJtMV!S#x#0qHn~fHIb<2Hw$zRpRiIaAn532NTg1mM>?Em zcG{=4XZs!hS6aT*|OUNNN;oQmU)%VTZfgKf@D&xz9BU(KboWE#jL~3P{w=O(Ac5h1++t82)O%q^wwOM(%%9~{P*t#O3I(!gwNL5>WRZYNeLSW#WAyYHSrO9!E=?$P02#s3;6X zU|?3yeBkyWV*u{U{eid@CGDCE1pGJ{I!hr}MONzS8l;$kn7@D2#Nra+x$6Y7DU$U< zMX+{$pmR9t^CN}c5O2eKJD)Ek$N@|}Kg;|z{yX)iDWCMMe5r$maIC>l&JbyzxNG8b z_zW&uvIJcGw0&Ux9({=(>pKzf6OI5Yj)&I7Ap8Q)PH*A()+M9Q*|}tSd6{Xd>9j+V zn%Su=ItZ5=`G5Qr7+xBG;0g>CIw?}%CIQWHe-9QeAn|l?TLS0#OMlaV**v$XDbTbf z_Vipa$KvVDfDq~IPp;^5^9a-L@!`6i_5^h8n%!8BH zvS^b+ij9Pg2H;5l+pGhn4Ip=e!|0Yx+eUpCPE$@&^zarJ>_R_h*HfHt)&^5NodFNr z{{H^9)w%TZpoZOI#+}Iwmg)U#nr64nDdUVgm^C%ISpH2v8u^mR7n^& zy`$fOtAcs*vAgN+i-OIcvfp_!X{*xMk}l#L149DM zXrmsJL&*-M8l-^^dFKuZ(j#(?#m%(Z%<*@RkFs}7nRiYrEes&zdu7<{t|c=cGz65x z@M&Tw;ZG3vpTCE->@xgt1{=K5)fEc7FFxn&3YX#P)fo>E4gm`E zJHWA$?t5w3S@%x?1ROPrp{P{%fBE|+2zoCfb-_=x?+#h}(@lw--#=4v&YLr-g#K7w zLi_P_UHB$4iJa;ajf37jN*L!_uH&lCJier-BlA0k$$iLdeLyG7T8!pMTDok|FuXal zW!buy@mJ&M1j_b}a6i6LJ?sEY4FfjvpAAwwy71W$W|qs*<~;U}t8to>(-RH+R&I$s zB8S_95z#YtY$p|`hV}fb8+Wy4zIC&^-tOB zJN^YC*Ah`qxUAxT)0oIVrH&3a+W0jnc|)*=JY$mF?x42Xs~VXfU;mc%SwFUWKa6nn z0&kx51s^~niNB^>uHOLCR2qh#AfL}8F+Q}|d`L@xeGuhi8+)fLMSAM^*juwnabbMU zF#lvyf6Hid?P@>g?Vca?z6bK|3?k9j+@KeX>k9IASAjOBMpiBhqMuuD`3gs6C49K) z@rcw}$}V{aE+O3d(Z`QMucCb4AadpJo5(=N%O`QOz3+{!A7m^_J~l6Q)_qz z+T#Skbq`9CuEP6X#1Qq!t$B!n)uB}WlIFMuu7)vO?wsp9{X_>%UFr(M1?j4-O-5v@W)-~7FR!kYj0{Iy0eC<*C z!H9XMJR0Gv1X2)G?ck&OjY^O`V4|KWn2Lm_plrugH>`ju^sZ1oN}9%cG1F6h>$2d| zC;uUU{4WI)(~sC=e&>rJy-nIF6tSnyxhUHTyv33CGOf}h*i4p9ZZS7hUkMHy(AlT* zcrvq@E!`T1D9Ms(0d`abnj z+$cC4o99cU4cp@~{P?;O-s^cS^v4a1;7xqkzvrfqN{i9`=YJPPgrV_5X;lhm^M=hm zJu`sKsp=}>f6n{D3$tlqLPF@=vSOsn<){zac#(pn4iVq-^1<66!z@b!TI!}{0nc>R z5bqkCM|Cv}(_txDri=pa$jXsN(mVpIBlnFMvG~=*sLG5c-0@AXi4_7wh)+Gm#*MKF zE6DdhG%i${OuDs6ds>uY1T~_#p1A5|h#*1kOzMIUv{XC1Z&fj~o*LWC)o2RYIdy)u z@iXyict|^dr~C($IgZiRUg9^0QV$q{`eH9MceHQv7XZf&nxJA8Fh7y!@;MRLlDKv`w`xk2B`F zez%Rl=ol27%uSrYIs5-;ItT8$+OBQKY-2ahj*Z4>Y};1j#Yc*$dS7;bD$aa%SQaOO$w7nuo>V%B8YX2fN%fsO#JoMRge|6vzy=J z`13T4@ZOJInvgi%Z}%J9@Uu_^K4!m7SeoQE%7%Ri?(Cay&|J`Ir|!Q)pJ zNlU-=7QLr>aoJ(&dA8{hF_;p)$!6Um+&~@&!m$LF!lxeQwyE@deZ3;d2BO<|loW(G zhCFG@Krh$Zb=h@&F|P;Pjk}H|?iCVKkvp2vSYSKn#GO%WIrRdaJ$Pa6Q>lgMf_cYvL%2EqDGN-lX|D^O4hF zQp;=f;TXTVZ1=ogt1(YBX6zOr*T2Trxk9azsP+$y5-TwZU7@zQe%gbR>YjD}`coiC z8UrTJd%lB)T6^6<_%y|qcia2p?gc1bUjyrahPtnyIT)Vrau6*P;g%AilwW2Na#NUJ z!d1??&<5h+MAwAS9XAEh%~RC+SeW5 z!)Ku@@8LE2W;_~vTi>HkHP#t(ecCBH>ebmxmO#B>!#>SuVDrwc_^PdOX$kzi-DT(H zVUbt9KbPfQS8`F8q7C1nwZFVxiL%=2($W_2&;0tf>6`EE%~xqx%}$82dTLYUbeG2` zoy0jt6EjrOBr>a`iXJe|t#Et`w*)!>T-t?tW4o&rKKJo?TUU3hSjjaRx#y ztn=OV#9FIg=7?sE^OeS=kpIVsZI!;Ut4%*5(=ZOYhiYAyRhE3rnbB zO+{V!ok}OGM0mOY1&h-kTG+r2=(SvX_}JDHeu4u;OadIT`-OTb(Kp*^0HmZ2TZPE; zhM1VRd9Gc!WG|?Wj6V>6$j9-OCM9XuS}GzMaFK%IRPRws2XmR6lD?@krZU<3RgbfI z?A?25UE;@&h$)L%(*f}$EgiI0<8}eS&e!>{;a#=3|Nbrrs5r^QPUi_h*_M_`_5}B4 zEvo>S90)W2pTZzN`rq;-ZIxuPO6Su-Hb7>O+%YDwmgXdymu{CjK6b;fRVP)KQ#UJe zIvkvtAh$6e+kALA9JOR=4axm@G#=%jfuHO`2*`|axni<;wa}-~EydY8f#NGng!)i2%0UALj&I_G?>~A2-P_D-(71 zx(&YBq_Vr=`f2-Z81&P0u^dj&VVnh?6g984=l+*l34hEmKy;z@+FLqEg<9K)b1C45 zq(dGVd3w{@$sWPO)e8;f z4WuRTyO)ZAru@1P?gZ>pV!7(UYE-2AI&dF!mcfm*CYcqvg|XQ2AlFpF-+ijn-sAxylc^1WF!K8^+-(7TTbFI`uW*&+`2A3OmVfOKY&HGQ)}O&l7+ zmcW$*vvwJ$-~Cfp$z;Kg&6F$o6kc(*1~lm~u%+k9qW=Z~TBVdhmjx(Q4Hix86NT(lxtlaZm5}T%nnvJ#jy5Ufww} zv$V$AIl4HbjQ4y4y@c2vaYa}dw(|G@Rp zKNWn+|2~O}_vx!WDUT!HZBoj$OVId_oeNVMTw}e_1yv`)16E315$)OFdxYOXH|dyK zBzRrz^1KL<1%KVeI7rzAJQh83r#jz|@gh3`*F z$Cvu@_bo?KDzZ|&tiI5wz?-xmlZSsgyRA;Rp}t;1@N0_s703HCmw`!Za}*dBez)Uj za7!HBtky|O6CR@rjxZ5NED@^0Nnxu~L^`xD!5shXABqfO$y3O(ZAc7AET|mAtbvd= z?tyViyp0BT-&D7K-G1W8u0E}v;TMA}T(Cr*kr;qNVRzHi(74+8uQ>rUqn6g!VXXwt z0Qn7I<(Zn22Rv2cl!m}%z{)hRU27gW?I4j=@C^UC%x5jgy|<2380>AyFs;=dtdzgZ z0h$N4lYoghC2bz!Th&*fqA-_%v(@Eti~)FIl+!4?rfWZ|eC_SKJN>WTGQvLz$kEE_ zq6)Xx-8X?bacyQpX)r}>rwjBA?;-GqRPD>oSf~N%=q6!|>ec@MZ#sxa<>kcX7ujtS zZ4e$s*5hVLn5Pj^);n6s=Jv;jI;WD4@9WScLP*67vOeZIn?Gri@KlLd-MjLUS4b?w zy&T?lFTA5aPz7A`V%DN+&~mGeB*g)l64Bx&|DFeRL??A4C=RW@~>W)Rj! zIWaq&kKAeps;p`{&seNoNL8_9lbE3c->iav%m88vN5=r{lQ*FrXBzBXJ%~L9;S;;} zw+e1v!D)o>Te4k!uLPA}Mb-FFq?H5Snv2#UEf<6D$Xmrj#)%gQ-PmB|i?$xCBH1n$ z>gVQ-&2Eay&xu!3;jBOVO{`ObK^v=Ckpvs*?%RSXQ75ipx?Yz*eS>eI4k?EhLaWff9^Wl_z+LOWRQYMd`wZH@CjIdEwog1@G!+f*Cv~ z%iNULM;!={3Qf=$XiHX`T9qtp3M7`5od#=H$(WJK87#Z}iBz>?vW+G``5-EXV#U#< zA;73(+rr!w77F2!79HMqxl7L#r~yIPE8U^4Dj?31w1!vkoZjn#)a?8lLp?*&1Vq#rg6-`GMdMeGo zYO3)kBBH+aB8sB3lt`$&CkJ$jLHH^(Ub%ws9S>TO8b>bV?ZK`^H*%Jy^_2xedSuxa zSi^ESwh6)Vl%-QL zf(9X$v+{NLvW>_$YZq!O%!4L=W!G*$DfVK!t%%A9Af$+_wzn zFyJ>Fg>(s{5TJ%s%wa&2g5X_hp-+2q=k+pe6V_4jz@17PVHOgFC7udM|5U78DkBhV zjaG;0#9#6sVxbg59$4@`tpo~AW`=3kDXt_Vpc|J*SsRdrQbnocz}hh6mI0p?X=ni5 znYD%nJkUljl}bX9=K2gG(A;i9Zsru3J#}^5_&cLRt=sym2+4BWk<+}Xr%%?F?>@e=^1tMG8Z{K;X;YoPvmqR);(2Ak( z)m_5Tl`%}ajM7r&sMy1TiNWjN^1uEB9?pL#3$_+21xpG%E4~{nYk09*QTax7(63n_#&ad7xv$izBB^f zH1l^+2<7JQkhn3MzXt7l&>*l4!ofvf2O<21A7z;@lj1>@YR z%lsihY4v&|@YMdheC9a;vf;#X=y~H*S65E!b7zYS_OYV)`7->)A)$oU+KaR7uap!( z+=^iZkW@L&fZ^3SkPgrv0>dPp_1c8e`D51FGhc_wTr&B>UVbo6r#L<228QIx7+Q8tZZ@T@NFfx6pw=~M}#i`2Gh_S>v zd&^PhkF<<7eu;M9@Bt1`4~3fMF?hPGX}jC7VxWqVk z>M~?abOx%9g0A!!$Cf$oK2_JfZV#J;<*|9cORwG~ip-^3?46rkxOkx4%25 zu`kkZi;yL8p`%nM{;z8$Orz^4!9F_tv~-p^P(Vb!uH5l zWz08)xYkggh5(H?MJ2n3A&g3W!dJfD`u6&Mm#k1Rw9`NJC=nB+;g3g)(1+lAJ1uh( zmqe8XY04eEj!t}s$|~Y_ay{Rqh1sht#{ zv-IQX#;xioc}u46{o)hjSGptwN|tUI68>#%NNIv!jj%cN?5SVGy`4}r1(mYL4W$lqyQ3r z=;&^Yup2`ee#6|i-+1vBuLoQ;q#-*MhEKc&M}rtY`5Sz~=92yyhmWV?u~S{#CM24l zj>7>@>NVF~n=dxN0QM2cWeos;0=#(C_!4GRqXD51Q4S24cd3(w2?*g)0vEKYN5%u1 zZvOxjPmF}NN3b@-rX>D|psp#ql$tdSu+|8jJ-_nzzItLb zDOh?&W1fB#SsM7VmH!z(-eS8=2narerhDug zZW{BRlJCk^+Myg*3q?X}H23rGbdp|Bi4_;KV2dZ3=17*&j1uz2gK-#7LUeux-K9W8 zBK;5+1hsN9E-zdzXBKFvreO=-fMk^a)&FtIA#aq>3KZKu5u>LK>aiP0b0@C+?A>UY z=Z)jQpITMB43mq5luR~Dlc>ZK-GGrRHpn)F7qb{;$(y^ABO*DXeLK~@#uLs#Olf*?alwLDnE)aVTcdrZb@P)8y*7w&2GO^4fY=IQxEP?{-m|74fatp843uG*d3f+}}N( z<9sLQ=i+IC1ns;}l*rABO^>OwT{8EA7#n%bk70PY-Os1=6@;VEaO;rbiMih0Rx1H1 zNdO8MF1WAF*D>hhIDugTAe8BKxWxihY9Inc(*9Y#WWJZU87HKW;gifrig;)oNINaD z#EEfc7l=|-L35Wi9=Ht8jmb5bUKe_)?wo$}w}W)+S8i_3L?s6M-ZJ^mta(Ja+ixHt z5l_S6)HowtqF1APxltP!(uybJtk6Jm^vyHyb@-ZV4?CKtRtLXz5&6B(=L6Xyb>$!X zH*i$>KZ{LxvkMBze*Mu0^b`2902WntWcwYj7z^mz0D2=f55cPf0aD5>krIa@v#AUh z*M%y6Fk_4DqL=)_U*lcKyV|XN{s~2dKNjg+-C?M@jcOi{&2+5IBFGUYfpIp=)mi4Y zx#Av?QCKBxYRw>N^3E2rBV`>i!i-1}7$L3VLiWJGu=CYQ<1gmH!-ucN`1A7h$d17ejcoX56*U^{Wyt;~{Zkz8>7dene1&-5{r3ojE-Ghm(SF5%GCpHn59taYe}KSI=0uJNdMsUTE;iTe@g}nBJMiJ?LFw<3wuz(~K_ zw}zT?+-cts&sNHZ5s{aS{0Fma4<+QtnKyGOm;}qecl9%ejO=NUZYH7 zHqoWP!^OHOprQq8{b2*f$Oz2PJkt|Wwn@4{Yvp`!+#EM^z^2;R;W7Yt#jUs1pFfEF8L9}6Z+zG3Ir!xks>RE+$CQM-4xVFJlH1KW*>@tm!$LRE)R83 z`5C8KnG~Upa9-xfjowHF+b8_|7aHXpwcaAFc~;U!2#!` zV_}Pyj&KI`X`y#=*(MSExkAuxp>C$`+f~^*1obQ#Da~%8s ztq<;-G&8Vy%(dr^ZMk+-#eLqr}_n-sHT~|#!SVk+nVvL<-mBOsw?${3miqr8}OHJ0~Fk2nY*tzG;q((JBMogPBMy5ZDYbtEyT+Aqx>DOJG})i`0`wWi6`;hyf&pM6_S%LetpFQue}u61Ysd zDX?qBB+n%mk8&rVC7*s8FIC#1{69|{|jl6S7xFQA2{QS)0;!lrh z5?&4Xjs$Ry18I;;K$6FR+01{f1God^fw(7-GS6|=Yxl`q<#J#nM1ce>qP751uZz!J z;qI;jm^Bsp+)i|otnnW$+PaY>a;r%E|11DD#knz*fI*0nYYLTFa?HC-{@6B*8ib)M zhG`UOI*%Y;Lw$D;BcoGRSZFolwMZca5!5e)#<(l3^0`8a&?-tv?{#AH)Z{6oYW>ZF zg{cRq3gscj*@C8$aZ8_<)y;z*-;Ya{=6;^w1gMaKl_V+I_j~UT!>-<{;LkhnS7xfr zGEzlpDV~97v-0g{muK^ld|Uj9YD?ut8XACAk#9i*j$4;3WFV{e2hxUP5|9yENU9$_ zXb!mv**nIe*=0=2cj&I| zeT@;d5m2!XN!L1*>JYf`kw~$stSQ?a3mAc-3=wA#L>6CPjQF8%c;O)%W{w}KQKLilGdUyf@P$uQHh5o zPG>}X9Ps87yw{LaU=sV4av|j~D$o@}JT*Qt@ks0&4<+0VUiq={dYBI|^-3yx8eMYxPC9?XJLwv>`g9FCgZ%>6{H*l4gsjjQeO7r=1t&yzy*A42-3 z$I@^6X7C7^DZ{(=hpl)=H@Ola20LQVGSmqsJvgkSVzu9^!E_F37_Z5vKxuBfpX%tb~dqnb($sT$n1QCwVeZVoGFzU6$O1*KfS1P?AXx+Xhk4x|AS-2TVw}`s6`fNs zBxx0-I)7hr=6~5;yLl?HXO4rov}JQ31v@yEEc^xj|Cn@u zmjOUH!(pbXOx{4WGRgMagPI_VlBE>SpM3vX9QHku_7Dx5v?&=Ld|L1_?MNs&uJitn zt`zR;EChbIqj^B2Uf0YjNimOP4Fhm|8=i+m)rLLO-j`jAD|%DxPFZaZg3>mA3VJDd zvFd9&O=`_ZdG!Hx=AQ$+QAQ}#K*479xOl2$u2OMy6G^~(*ZXyX)kYEpG zu-!gbpdf?M<)WpH)KZCUfw!R>S88jN#wUw=+P z1_$1=@QrHglhm`fkJL7dznjGicS1Q0H6ld0c%iX7!(u$HaCOIVMb%eExQJ-)7p*e^ zkdzeFFdO|G@aQ;22($y_cq@!j16)Zn4`kxQCSH$7m{{ zgN#3U@M3`?tuSq0-?m_|K}+0EZME~wBXLsx2(R-4+labjEdewuPm+dL7#3IjE4R6g z<3@0P<2?^D8sAJq$odT7yBI5#UFxq&T0K_1f(|!+gaGoReV(_rKt83Rz(>r4iBvT4 zW%Qy|wUAH=li;Dxi%_&cCk^cS(rFHi&dfti@`^7ey~B>sXFP`Dy=BY%{jS{A&b#UC zPIrg!fB#(TD@j!l=l_KGm4-V8F=YQ6qaeE%{9*}O$E%{?^@@GV%>iBfuzsVJ;3E1G zZ>QP`ddmKI)_?X2ZjAxjOL<2AKH*ELd%M08bY-sE4v%N08jo*>HBRnkkNY;4SHr8! z4e2Dco}U-Ivk-z=u$zCh&fNt2KaxFFQ)HhdW$WsBpJ2RL^xxl=KK66v^=F7C`Hfp~ z8lTFT+?FE5H+!46BP@eEaT@i+`XU;%3w-|UI&`%E?>1R5QI}Q2Nx=ptBkYJ#O`^< zIkQgl_}vQm4gM!pBSnLcTPZI6kw#bJ=y5Y{lq3GL&LH4{n?Z!qWsXUUW%?@F{~1z; zzWY%!U;Nn1e~*$5{Wjb;svO}Z(MxFM6ec^+o}jL$M>n1eLpN)MKq_gFNbqF`838wA zCV82RE$H|bO)NAy?Ak0U4qL@4Cjr4EC58Kv)m%Jl5WsYcu)0oCVTK^wvE)s9Cd#8NP7kurP@PWK-(<1C(+wyB+MVlYw; z#+UDXMwDFwdH#ZSMFCVu_aCEO4$L2 zw*bdo2lsSdN`wZl3POC;ca0DmC?{8_NULv}?nOLg2g8rg?433vREu%KUlGE^JY&m* zHw)0a_PP+=Ng~{Hw7mp94eQQm)_i;X6Ru?^*)_83#25@#*Jm{D4lUdByln;VgJ#&7 z7JN}d=bF~^&wbY>xh$ulOARDVVh7sGiP_8BiI7r|{LY%$T)mSe?Z!x?eJr)Z{whPb zyTmjkX&WdLM7M+)OA^+Myu23eE3Z}v8+H!KTbdHiMn4teA3em1^4I;KM0izweTzd z92c#1JI4$A3(z#6C0S)X70|v3r+2j6FRiTX#D6@-KLLC|Z!CZ=TQNDz?zK)V4!HGh zmzI`{I0SmJ%$2YR&gWyjxDAN~4CPsDpVJ@mjQz14g8s$017r8&68#^l0WkE8(Y%jWdhQE@;d;1l9=tJf{%u!sz=@SE+xN)&$P!UV<6$IK3LlxJaP9~e|wXD0Eq4F4X=?iNn%2btR{Kd zYlE}JDMug+fF9)T&@}+Oyz}vS+g96e#ZpIMlfq@tn9<4=>hRmbDB^g{}~+um9mWz_MLzMbnBDyO@TucB=>SmAfk@LmcN;S=L&_ z@8F!gS}}X)w>Wo^pf(gx=qfeZn4|$r6T2Y2m$*7D%fpQ}aWd&0!QEi|V0+Xm)tldx z=RKFqH>gTtKghAs_Tg*g#T1T9mLe4}4M0y#d5Y3GG!gRN*)X#`P>*@v`*X(%N zWFRS!hE!3+RkO&#HOt}P+!Qa*Zrad~|DF3*SgP7{978&*UY?wp z2eFO%K*T1w2$Ai;lbDK@QP*%R>}`{UA*<)V;6S0z;4k@yUn~%nm6gEU>_5aI{beT} z=?Bfz3zc;L{XHiDIj+jrQdbAaCV7XI)zvruu`CT=cW?=T*x1GaPz4~2lUS-ZF||Ri z`l=}S1nOb*msQ5X^6dMo)maxPZ_JQ9fZnp%HMZv%f*Hgu^BXA|Afn-W<%YBv_(L;d zCoW_Z<{*F1rrOJEyZj&&wYZI1gi*G-jJ9U)(5ZzO=E-h@$FS96Yf)5X* zrEs&x_sV#^)f$CwAnXxHK&`P(V#=Ry{<6tcPpPGITPD_Dix!#l!sJWE$@)dZ`Dhh# z9S@-!{V=S3C%pVSp?G9;n?O8sC=lL|6!@X zMg2@1ly`Ku*_3yVCCB3e9}A4|w*|jmvP()IDs$-BD4iY%w37FALZc%J9f)aJH04LV z>2Dgwl^D3vYp9zMd!mg!?YMMGI$K@emuY12^{1LHpaarl&Ex(xk$L7Vo?*G${&o4v z?&as?w^GXKU$y|&3CseTAWp#@`+NM^n+6s>D!d z^;@b*;uyh3WO8f~ktKg`uFRRXSjTh4GS4%N0XeW=p@(FlV}Ufqj174KS2~Fy^(Otn z4t9;T*#UgAm(+7ByD~!El>@@$oq5-Vamu=WzdluDC6=d&;s;$@DN-NrbeX4F9!U{X zqCZj0xERuNuK8Wczu(ThL$4czIH_KAx+nM525SV}rOKw1crsVRC9K!ItzT>qE3SD2 zc|W)%8e9!A`=M{c><%D)In@Q+c_0Dz%MFUm!9nZVx074GK1}@%(}srIz82-bD(4%b zoMQn-1e^-20*oFseqZ+ZAC|H$Zxx?00) zkt#`NN&_e&3kz(?gM$*9jQQF7F=(HZ?9PhXb}BD(corFye`E?hkT12!`FRQ^x@Tft z*1zcAgLm>SK*xv4@Av#O9(nB_qJwPHNxS#X<3eCppHGii4~ri@@OB`l)d#i9Hbp4@ z^f8%yxc9t!1CmC&JeTRG%_-=X=(`^(x_rnHg6D!WP)UlWgfoT|QRDznU9+VIyphW% zM~xpI91m=3KUvbhvV**2t5rv(h;+>!nq;Aci^o@gV@IT!J?)7VmUHDIens^~9e`&9 zrp^?G4(7R9Uthtm1Dmf1sSnGaygVh=_DlDd0e$jVsE@mGBbAqC}_)0=ff%Rt)_08pRE%-=b556@Mrx zWXPc$->bAs%caFe@?r!Ad7)z5_ZTZ43*6;_rR2qg+}@n>-X=@64L2bmt1A4Znz{_!LTmKE!Y zT*STeaq8su+lvSLHC4k_l!TkUU-x_rutqjKh1w55ywkv}=Kw^Jt=~Y_3SgyFx%dva z0j%uK=aUNHC@*X(nMYJH1nPRiNpdzN$%x|Gg+)NA2~$!zp>)C-08h{lknN6zjCo7~ zU@BGsQ@ANfD_jI)&e_K&Tf=9>nLB%mdQ}oc$rh16$R9M{nW7HrL#*WTV21jTp@Dk$ zcGGZ7c41-e`)7+sXF4k#l^({A>RPEDl7!wirmW14+x7xU!;H2;Q7lq{N3$CH12bWs zmnW&RUi^s9U^}<$PXWb&{c6?V+6;K3yK1C{zwgWSrgNrcMDBw}ichVJM+JTYwI_(F z=iO6yONbDyho+|)@3n5@XE7A5<1m?-QF;0SO*B{KzkaG^WMz2!_)yo=%Du34KeZW? zIP{~gGW_B44Z3nl($`}n&r^YWbSX5!n>y6D^|pkv`m;7@mJ0491p@;`aF0Vb$w`$p zSNFSLMsSz&xe~b;xNXFn-Li#L=dz^a-3R$`QLe@laVsqI)b%a5&7Hhd(zNgcM4jq$ zD=X!PVW*;;9I)zPDx?+QA9t-s&Ewi(z5dQ1pEKtf?HmoczVG{08snzEJWwOv72`LB zR~HIE9esfAi8lR?Y!zAjKydKTJ60mC@016MI{y3&@JM5Z`yRA0Y>7Gt$&^)^ZqoDr z)&ppLAe$C1^v+$=d4r^k#hNL{GCX_vAZp@!D8O z#?wrC6*z10=m38w|F7#ghT(+g@AY}SUI50mTX*ir zXck*EUNA_?Z)=Zwe1g*9?H*||v~q%ztI*%KO)QN;QH)ej=4c0%fJ=Jn&ZBo)=ieG0 zhn+ltzsO`bq!~m`|8#o!#%Qj6gX{lvXltmDv5z^&abVObsh##IT$D~1E~43jtfS3s zo8M&@rGc(A+XX+~Vhbj>=nF`mLjHK7-9RrRIAnnQ8$n1qNV)%i+$GT0ju&qPvZa;Q zL6@vwysYEl*Kl+>EHn%nJTAFgX}FXowo=}{-Qb>A*x(De&5w=EWC`Eyn>(SM^~KHI zn}1)$7`O=)2MibyLGU%8P{f!H8WnDi;V^;fKC;T9Mf@MF>?YiVv*$x=?N6Mix;A1m z7()c6jD;Gy=sJrU+<{HFdxj*Rt^|-Lv*5R1Gxz)>rPbDP$z6H*-UuYz@kNpnNM{%G}vT%;wd!k!5ROim;m&=lYQ4K+cfbH z?#z1Dm}@49Qy2%Cn9Mn8ib_oW>qk|e?dzGV%=C9?IAP{{8udhpghL)hgBOmCp-=DN z-B*jd#n+2{L-4KXVrHD1*1Fo`h2Wbky5{quG@k%@HVfa?;62h}jUGj|J~SVYAb{(2 zaSP}-E#)bs8!M$qiNQnRx?;_+4vg8wc^vv$E_IT@>}s`Z+`yD=rp5dn`&R+X&tlXH zH2ixD18xoi>d)Nqtd!HC?sJtD;RD7UH5hX(^+(2jHRl6GB{VX&kk)e}8pOxsMPbWk za@q%4mX9~-9~AS;WW{648{LyuUJ>;4DHvq5*`ARefm|r3MAIIfpF=QIbwU!zlxKL0 z62w$sGtGmZ!*Pj=L}ythDV}Eq`MSBI0z4I?Sqf(Mn5hIAieG4& z&VQXdRJjl9h8LZ9Hw`NAKkoWG`k#j>JDtg(c@$1?_oe18)*_sMbJ~DV=*NhKfx4tH z{qI8F(_tdyI9Y5WNYSR5rNZwkuTWygkA)wGgv@ay;k!PPIFgWU8{>4+Nrb9UXvk+# z@ksOi-auadU^_k+Nj;cn}>)QNwHmuVUol1rwdEqS&}! zuI@Ghx)@u>Cgz&^3ujT^qH@kL`q_8u5eZ@|VuWF7m$e}+7LD2STS(!=DJ2cGA)*{+ zo6K{FxCk6HWzuh_cvU7Y><&-AK1s&gCBw(CMyyQGuceRZNUA+RE3;RNK|c~E|EqqR z>9l317pKsFx+H$hO*X(r^$5ulRskD`P03itfot`qYRxw_W)yE+6a=660byhYz{Wed?y19tv_LmcTn5d{izPIn0EmdFTdS0t|F zESV?IyuaT?x&j*rCuFSnz0(`0v%Y0ic4_S^D-BNYep!Y63bo#-%O1YOA=t?q<1GIr zor=ZB{QT{da%nFa@s&w1Su4fE@0ALGaDr zF^Kp@{>A=@Hf=p4-_lf9XEZKL;1wY&V*ozlayCA1Jt62a4INWEyn(2~f**aC_U7iH z04SUyWT&}v>V29?-8@*Q3rvHb3}O{e1xqWGH!NU?qYHgJ&9r&l(JkoQ@H;FD?;fXY zpU4!aXoT|iSrzfTW=1>=aga_`mz_)6YI6jf5az* z%M3=#{kWVv;9PF}^jlC}D?^I;dN>gvPg6@ghB;wj)c3C_kroXsu|5nx0Qx-@n)jy> zA>q@A{}?Z++eqSxWMW3;VR!P$b~LL3D^=c?H-9m?9ETe^I-P;=J{m^iiFgQd-wyvwWFbN^meA`qY9HeJ+06SVB6wHsM41#D ztv{RrqjRRAqF!Udb+UlERag6P_2b3xX8qDHeJYl*`)Vh8uK{W~Hll0r(aRnOj*JKg zUSw8Rmc=|$HLR#+d9`EYx!5(&{~p%wHkgD}OVwqL7}zTKOv*TfN^@>I{^&h7V}@2$6z2^vAHJC<`A9kLi}|<}dSm^yPMce#Sgun42SzomOv|)t#B_FpLM>zg z>C`88@6Kp)e*Q3`VY%TDHekj?avHkuGTilrbjFQ96kNI4MZ)r2^uk;5j_cb=(tMHb ziNQ>@$lMXWdx%{M)ice781*h!;GS6owuZR!+?cZdwA$d4f2e+-U|PZqJ%$^&KXl3f zoi?*NttbnTp=m0U6k@IaQf-OzU{OL7(U1FL=t=kICt+5AA#R?uJL~pBn%Z)$^wgbaJK$ z3k=UCvIPN+IcTw#ApXKd{8@c`GU>>F*u&wJyZwc0DL>=-EK*X1C5hmWo~6UrWRS#` zBt7F>nIBDX69Ms!b7|$De(mJ?Ab~Q2VQ~ z1|cw+%s5aj;w6w&7oY|JVX{RJ8RG>e;vnGZ3sMI09>pzDB^i|4CWzH*Vhd3|;3Z6U zx@V*L;Ch*TCle7XZ^`p1QH>Z zmHSY~;Ra}*{};&2I|P~$#dn|oi;DsNI~DleCH&~WQ9fzP`>;B6w(5zRY2yS*_Ncn} zprHEkx@HrWBlI!6@X}FBDYDv<*Fjx_Mvd0d6``AV(|x+4MJ;qFNd=FTzudh#iVTXV zy<89ivv8T^DnV+K^-=aKyT^*YNZXVE#vDnTlj3}oba4%aGksEjno}?zdm)P# z;_?Ira>h2RU%RUp^$#SFIGr_4rvbMxNIX=md-0O9ddY|t@ z6Lq06&f;82Ne0U{3ko-FS`H|Ee|m7;uP{Hv1t+ksT^f$zV^qWoLI^Nlu7PS=b@Ik_ zqtgQe4R~Zhm}={qgiS(~HOZ_YmEt-+M(^zw?7m`$NJhncQ0~@j(Kh!L6~ePGpcrkd z`HT00NFkF~za_SrKIngo3_6=$-pC?_Q7Yy4OqKX3&ZNxbG$j? zj;NOvmf?aY7nVk2Sxx>Yyp^#2Z%!XxdaD<}@??q4aZhX>h35t~U$#(Nqp~S5kjC5> zMIHq3`C>+Ri1vv)^A4-Ev0w}HR?(qsY^55rj2v-2?(D~`BZ*%5KJJm7v0t? zr0|)*&h!}52mOe|F7U~ajr*%6XuSFhcGeyLvHsI2;)jOWJcg=g5eyMxQc-jQoTW?% zvU5$k^OjUY0ao8YtqXghJ3l_|49rzarf=Cl^Lxn`z4rQ{ z_ie~I>*qJf%!y2e(*LAIeL540{?9cY#~ugErD!rNgr5>rSn}fjNc;RX;Fo+jgYB1< zF-_<_~FLEf^*ZNoDGGtLft@kQ^XNlEMk<8fO84l7Ew1C>Kt|s%&C;+Mc2iZNOwth< z_!ug3I6a8j=N8;G?3C1?GG@A*bxv^g z^WMhN$gTQ**H6gs{It~b*S%(t)wtgSPtCmOHB^SIT8_AuXnlE?XO=eEq zH3FY@^J4G$-(KR)2CXlAiwIfhbc6s_`xTHI{f1!REYWy@ix5* z54kF$GCx%m)^CEJbAXOZm^HsJ84a0T4U|Z&!kYXiq5MY*JnB=8Y3$bY)wO=ZfSxiLt@{r+YdsAeiw6fn28gaCKb+iGccZo>h+t=a& zp+ko0FEMv`zh>zu)zM|dX|R~PAIUfR|8w{xsU?@NIx)05U#{wP_+@Idn!A4pX0Lux ztL~KzrvARLM4oT}BBj*fu52uFk`QF}c-q%oT3Xo~j9d;qY*kCJEj6BYg>mX;&^Kd#;~sLd{H*T&tUxVu|%g1fc2yA=20 z?(SN=K#O~^qQTutao0j{2^#qFyfg3q_Uu2I{LM`6weEGT^E{3lxJ;}Gvl-z?<$(S4F_x~Fw0pt|Sfr3|c(p@i_kCK$X>Ych8dv2n zkd|b>H;RsnmMoyTq{%YHZT&33V+JX8KHmlY%*6L-Pe`unMm>lZnTPC)EZiQcKRLhAf=|y zt)ZD|ekxwCMV@88)z)O$#6-DDwC#sv)Q&9tv%H2h0ZY8YJXwrML;bpu0jzuvTn_(R z--T%C`OBx*-T<<`)z2D_IU2|pk>&yGp93>m`;w>WprX4d8ONkl4WBohD?Ssd`(NW2 zpmjNv6irf4_;zh-HXj8}6^g5)ajQAU(@MjCy48jmdhn@gR4g1x>VWtelA;A?;g@ygOREBBmj zX6xlcSOWMl1hQ4(ce?ZuDk0Chwhm2A0yJSL^XiyLejF9)+*^*L`vh3ZUX*WcZ5=jy z0aERyy!}gAUH{h7+N5TBj%bfRPlc}CPDzCkBXrC>SpYTN=3c0!eezP~*D2B>V3-wq zCtt2Nu?lI65mfJBT?zO`&41FPARr!I=aBRe4m4j>>>nHr`M3Z56Tv@rtme^sxLri7 zd1u_(N}1B4(B+HXiNnd9Djl_QtBbQ9IbNmQzn=6(vi_0n%p}hRQo9j5AAN;#j{trk z!i**hckWT%Q8`cW&GJ)K-}QdEWx`W0ywOflc{4*R+t>&h1`>+~`!~Ih-VfkwxUb~j zOHq)uvvx*9?iA8=B0Z5ZjIh91lBAp_y{Z}S$?enKiZJ`MpJ1Ou}KK6nll@*y8n51OI1b za$&4SQ{=ZIMv1fQ(WOnL;3<&gqfY-V{guzAE2U2z1Tytoys6$~mX>ETg#w`ZE{vKh zQFWpB^4Tbz-U1qsP9WlHhBkeXSK+*nsya;yS;bx-)}tN37(yj=W* zk#~h_lh`L*$<7c-ch{VolD(jI7w#U<{2n5+y``6;gS}}r#(AXDj*-oE(Sx-{X4@5b zD0Ag-&3vdfw&ONhO52C$5bliPS7mNFx&TuSF=@=Wt#6iNF=p-*kFfCElNZSd{Q+h8hJ0 z_+NfS^Eeh_1{mz(mNIgwv@sF^5urXn%q^s+^OH9*_3&}|=w$L1h{=K~4>`jW(MP0+ z#OC_0d&jQJ>}CyBFW>@DWj0U*c?Zg?o9;E?nYBgPbswNIG-JOs3XO${x~jL8TI9~@ zv9_{GxV|;|*CGEeZ-RUWKp&AP%RtPQA5l$66#0K;lx>MKE{o!N-M##Jey|M$N%T0mxa{>@ zE}}mtnt{lb?HwFrNx$gnAU!p*lc{Ihj3S_frpvOfhJD+5k;(7cha(MgJ@35?cwzj8`^B22G`wdXHsrqH4TcNaU%<^_k^V<5$Vypv z$yS9u?gPGTs5^es-@?|se-Ac>wDvbH{Z=uy4;ke@ukcEZjih!xu2o=J9ox@O_M*^6 zmUa`KM8b%HCw%H&eqb1I6dCuM2XAtN5u>}2EW2lM#O0$K16@_qYUjFjN0>W*&c66q zy!wf5gJU%6|8`bqJza`*S@!Hctdozv%1o_K-m4V*c^LP8&3(h3j*u4G)2F-A_L4Io z^gUKuNaRzRPm{Kn%d@uQXv(4~=7PFF6i2Ni2tcQoE;|nxn|;-+;&6FCjqEE zj=S(v+#YeHdD?&A@nEoRNH#RxfDRqYgCD@e$?}i70)eeM0N-7AUIbOS7wdp|3Zwf7 z7%cQ!3|2B-cK4t|u~Xc1+1cOK`auwMiTBGMkXptpIE6dt#dC+%&HZ1C>5X2|J2x?K zx$n)(rOz*>ZkmJB#cV`W{~$r$uMAZHAI5mww_P;6!puO&dXUHKJT^U(Y}xfnZ2K0F zV40lCIYuRTO0j#b=gZ;-2mbO>?jD{^dP24>39HOHQEJXdl4e69Slsccml+2M`d)q@ zDm-XSe!yj)#cpk`^|aK|uStN86pmhAdK!B`<4=y0*p7h6`eFQ^@ezXelZz8)1t6h`PNt>A1KrhexQT;d9ztD&Tk*&X3U3lZhSsP{wA>=e{OJXZjMv(ZJLIehk z-tNp^QMUtk8S0HU7!w@ta0vJtx?j~8%W&;$S=5vaM4}^5^D`1w44dA~N4_4z=*`Uc zmYNs`)_4M{oebM+ZI6^Jkl)4u8aMDHxF?DG_aq2OpP@tK@h#xUO44_!Ru!9<=hm z8;LTCM#$;TgaJh-uc2h^E~!|WoK9xu+>}WDdeLwDk#c+U(%&QD4sokB5O8UD3{G|s z*#XQoaot$)wuH3&{Q)Wlv*R@+g!t^Hkwbns()*ET=}ltwt8CH2TcUB&r9rtdvtir+ zvtRws5kpKTJ7F)!^i>2phVab^IiC+RBmJU7ASadWmPBtvAjeLa;6gVS%sJ*0J@rPY zKXu!GWjsCNEHwr8r1=NGWuQ$ro<*;O-(f)1A;t;%>$C8kBVT2rF;}!($vtM!dZ34{ zM2pN9yyY{sqzh;J^ll~nRoXmJ=A@t50p!I;%0rG7_n%k+`>&kIGCLuSFPjah*6)VV zkmc{+AW&0Hrt~;9&vAi*(yDYQ^GW|V90L4l++~=44%Z(R$|wo0{Yg8;c)W}e1YcGP zs6_l@ZUq)oZj!j-L5)$#CL4|1Rousxrk zwl0+ezaHyd2e*?=*kGgapKpCSFb5qEg~(RygY&ubb}M%cr#LnIlM6rJ$1ZvYI^p3V z3*f_gvo?qz0(tnW)yh79SV#@YnRI;rl}`0F^Np-XVnl*mFWf>~*oWn( zK_ueO^_c$mFY4%;_3+_2KrtUhL#$oB5eule2E!>}8<3HL{y3a)k*5o3|kS5gj>*uo}tSBFJ|KrkKw ziOV6?3*SzA=cAid_quEc^eDqEFaBlcK}deso}I|uF8B=6s&-@Fyx()lKu%5iF(cnx$>YPg;wajNrMd$O?PWP!uoXkE^3c>xZYWjfo&#kt02BU4Vr9%p>dP0h3PH* z#w0b40wQ0Ex(`)n?QZ+&C%%bxwGL9~xt^ywW$TRyhZhCX<;x+NrEvGDymp(ZqeXzURx1%!a((j>#kbC`3MB-B}kc!g`f9 zF-m8*(#XbOv?Av=K``5Wa+0V08`tle`VVVD^nc*R9 zt-fs!G46N$HoL@oCvq~#m{tK<4jwT?U;18XX(e>Sza5(xk+2mg6F3^6kt=KkKF31Z_%`{OBbe%7uEk4 zOYbkeA@T=Wb`4s$0rjqUc8b#4y+3`oAuSK5u(Kx5Fm(JD8ac$|cyYRnw1J|A+MP>y^?%EIs1_?np`%0=52xYD8?Vy2~;QNfv*fUiZI|0tIT^)>-mTg zJ`|r_ci?E|7luw|RTOy2*jZ54jIz)7SGp90+r~@aAP-2FmEO&=*xqC!Rp~~u!c?Z; z2sjV5=oz2n>YnK-L^clDLu#!FCo0XdE{hCmiXeynQks6{h%CZFyIS`|;$2ULJZpU; zD{E*S*xN#>6k&gpMl>-abjpibpMYW7RMYEri&x__pQAk1v>s$uTdDTDAYIqVJnZhdnHg=N63?5E#7-?#a{>DWJbQ8q(7YrFaekL{L#GiBY> zygX~swwj75loK#W>AQrM%SB3S(VaB+TFdfss1Yq; z{tRcTy6&PSxy9EQwKHERrF-O`AE5TW+M3aA=ie;;bqsu(?Nu~ciZ#4Cm?pC`a90;A zQAR^^;3b%l)CoZHPh_?v>_QgGy4_PTv(aJ%1VHex!M#!1{NwnuO`f*$+WL5O+)-8~ zNU_Si>#KBW;pl^~jK#DjVOJlNYJo=J2cOCb#QY2zsQ6V;VTe~=IM%@}0nZs=RECR- zqZH-CSgWV12918Exx9j8Zo<>?Hiw4F3Dm;1WA&aGfh!4Hy?^knA6iRlJrj-8*TdyZ z@rHR?eS~&nEoIWt0-ZJJo#=C}(B*pd@Su%Z&FAoeX`cJ=O4j)i%fg>G$=_-!gW|IJ z-K)Q4A?voutdiqMHJH4XI^vPfM^2cP)F5%JsdS(^8kd6)B`Q@! z2$tWoD@>UZp=zL0$Gs^H1NsFr+cY+Egbvw$*NditHy!(z zI{zZ0{-G}V1Ji&x*?!%GZjksjKZ20`s!+Aa*wZNv7&Oki4O=h$>qeSVX(cc=`HFbP zIT2_B%h>)mInBI)kPI5eJYM0MVpMV>7E>SXYdr)WeO7_0AeXz<@e4zC{-cayc93Uk0&zdWtbZ2J= zrjCDb7Y8H;J?%nched%mN)yfH>?#E~&@;%*D^IdoZ-sf22Lar#_yNOOosNI(wKCI} z7n}P_S+pWhx^UU#tHs7DSHNArolpy-5GcOg%$?(80`qh#$?<@2GE z*#VN!qEg{F2yXq7ABuq1ig2Ru-PO9V3pwsFS0R~Oq%q0}|A1sP3^z>>XZd-dC#Gore?sQ~i z(T=ripEt-mbSM>=->j|LR&RdBN6)nisC;^qGnYMqt0Hhu|8A|SBeXD|>%_M=v)L8+ zq+%wmI36SZ7_{-*FCoC^qV!`DUY^h=co55iFNiyH>YTESjpfJWcoi`g((7X%82{i_ z3=9S<)|UfT)|vjUJINExC1fT!N%O>awuj_T$^M&4Rkd`|cIPgpW1Yq)YI~ZedbU{X z-DBfI@jefN3QShzC)|X}H|jbY%Vf3jj&iT3AEen2gyzxyt$@c7NVWK`QLE}mZ) z{peO$MhpwDViUlye4$akIC^2CD;An!wN-z+;ylRew1F}#dT}|T9&$FC|$6cyN z*c;br->Vx(C-JP(+CwmULu0$Ge)k=co;-#Mp%Y4kwwkvGz5gu7Hx!CTKp^r{1MQwq^ zyZeW+0k^7$gW%rVQ;hN#kN86N@qx=R9_nQHRzOG3s@6__1g5)N=IStZbhnd=!J%H%=W-9h2ZPd^yVu3@{&=LlI#Z)4V4XC!v9=uH6<^ON8 zuX<~Q%SjvuGowj3q&Th?AY~oeTi&F?daIuPOP=tbFQD}ob9|F;CJt5c+hf% z(O}_KvWgCLDy$Xg{brk^)y+n(uvOY@e5}Pi6r39&sONs_;XoD?CS;NS%>sbB%$|Rk?fHZ}_&lB2N=#Zd?LdW-PA<`* zZW;vC4A7b5uG^TC0BEUPXtXEbftY`ZC8capfF4ssp#_OR<+JalOpnoWB`W*&gT=4i z5&U*vH&^82J?;bLm{^3UIwddC1wJS{tP^P7Jv?&<+x0j6EA#3K@kbn{FN5ONFyz-M`I278ssB2q7hrpehP*W)LD zYafbd&`8Bg{#39XbuG1Ij8eX!XnBRlq*9PwzRv??^_;D<$naYq{LgWmr$98I9}fP@iJI^(Y=6k%JB?t$J{k>ZF3PD_Y6hkT+-Smi|CfF5B&^-on!V8G#@iN$ldekadf1{(wh|B!kQBk=s8S_abP6y*Z`HCB zqt~^nWy_sa{z`6P3AEI}Sw*Np=o%((Y9Mj3*(Fhjb0uF2aB`M*8ui_KbQ?%@{o8<} zz0j<;t-w%}q%qLleB6Kef3CniOnbXj$Z(8!`Kc~q7iqfYVpIY1zVc|e;S&|n5WVK+ z^&|sxrp}My@U9ZR#mB;4CJkw7d$AjTe-qc=LM;~Yj5YI<=HrJEOa*s4kuv^%2P;kP z+h1_EXkL!5n%95r=0AE8?FNz+mZE--E-{0rx&x^7V8c{7iV0nh9mTJe-NNmYh5SNN z_m+;td@;Cax+M`~O*u4%fu1m1eg7ri9U=w!&DapWot(cXhnj8{nej=ntv+tWF;H`E ztUbu#Up2Rl7^Qf%-Ku1S4$~BjqDq5)LGgz4`4tLb1hAn#TaiRy;#J4 zf&B)8Nb};hJyszqOwy@qyVlhYKEi-OGn)P zj6>{VsA$0^6kK>1!>gnUF?xbxv2ii2l-q7HrF}wfDH8*jbXfd>yDg!8DOgYZo|

wf)!*DC#QEyu1fE8tckBXE20Uh-ogHf1 zDT7w-T`C;*2K`m}#vSWzSH-thP}nz55{F2Upw$>t>QB62Li8aPRQdl*!|^!b&|GWA zPnO%Kf>LJ1KYU}NM2OIfOK3t}>vfOojrOzH{eJ|nL?n2qwQem8m{O)s2KX3-ZjU?= z)mn5XMY)-EKhIwW7bVLKB=gyp?#Sg+dIE*)H+a5GBL{-+^*VfQG8UL4T^>VcEDA=S z%+2OdJAGFlFQWdc`kr48?BYUaN2Y;?Mu3&g{fR6`j6WQaI2dIdHxRr9Xk9UaUwZ*Z zNseH+1b{poURv*FsD&DFA3r^w>YjdWU4Vzl*Z2NSV(0nA& zX(`O$U-)5yAj3%34*39@KnCn;RHT7;nSfh}?S$U@9@)WdfRk%rq<>l&{g6^*Jff-g z;+9rUcs1D0qDoa!Imt%4;Kx59Y1BC0?4FZE=Hz+z4y;|81T81$mGwznUPfhFLT`B! zvHpPZ;cGcrj>i$U2Dg)O=htq_-+d)p?HJl4zT6fn#`3X#z%7yP3?B*7&eU!Qmvab7Sq6ci~kCU6rh zKS_mUCEGWZ6zC)>5ak_fA*m#0(S7>bkVY9dfWAxtUH@O64jsE*dvz#q4x?lyQOX^` zygjq16f^q+$K`rLPEh=2msKRdBM4GfWl|PR|N9mlQTd+>&3dnEkMLIrmI~evN6-(k zr5`7!Wjzhxz{!`}&HK8gGKb4QRJ|!+FM~y<_h3gG+5yTrVf+z1JuNLORv8XJYa}Fa z=B?EFCw8iy)!sD0cm6H^)9L||1ibLy*SBB2QeP^R2#Jy|ZBws^P+T>5=|}3jLSp15 z|0(v_t$(j8&bVlps*!0}_ZO}2tE1EdwQp}>sg&>G_iY#Ty>~&t!Y6+2LdKX-*B8y= z{PEP%#nADj0L14WGG`_h&=SOH+8tlar2pN|+dqaY=tRY-L+`1I>WNaj^jnrzcNiZ@ z=_t<#iNj&s$H@yPD^adiN?~sCfIX-{ZE^Xk#@f;`948)y)rA zYbRCK>L*URG+e#(j^s)-rFtgS5w48K%*`IrL@uObX*N|el!m|C?>nPN+X`bgdtOv>s8`s|ormF6(QuZWA->N13)td$!h{|iC21Ju2 z>F!{JiRl(#$>u|yx#mTH0SX0->N@&Fc%*U!OI2u5Ih0WYmKvs(X(->_N_EyV#*Qu* zP}#E;73>&dOA*fT3A-qb9n*)qjSHW?G8iHSXHRn}2s3Nv~C@u>?>Znnn>y*{8h_fF?=k&NQFTc+kW zoGu)p$kAdxG+619`O+vXjAeN{Lg%h_cErsfw?rN3#>Z=Q zMi>p&k3xzjqL=dsOU*cx`)Z2fxRfmXy&8g^1N`?6gTz0eIgd16hNQO22g3hn2YFE; z!wC3C$1AkqH*Zaf^iDw{Cv@Bx1DM!Qjuk?9H!|zW)>-q%tw-D#66KgjOBgP-@TL3` zq)bwt`U&YxTHcxLtM&k0J|g4R_d~n_%)-8A+Y>HMa#BlbK9%Z09m*zmW4T%a$WDAK6EG*MWjs&N{9-o7sV z&T(8b>QyKbZ;$K~`Pts50+zdJ?`~dctNnSybU} zuF;Sqk`Y7IbD8=~v_&&)p{KUW4OebQV$wr5xf~Np2K@dkzJASDGFmq}^82#$GWYEP zeDSW4l42Ob(N%(&f!T|Q9*F)T;E~!(aw&`Hu{6ctt$*>Ur-d3vg#D= znG6+~XvPDuHT#ITOb>EGo^m?~XcA9a?;<)EzE?+?>?9r*foTzig0b~qhLXA)uLzCwV(F0> zm}?50tjP5>48rTo`||K{c{+Jz9e|Gmk=G-UUxnaKs+89O!MmMo)mMfpNeif@*92ez z`VF-NmQ`yqBNav>fz;rEo&fAeqxU1Gr@QwjQ9#fknqY$oLpE9FU-Enh>uPmchIu?D z2k1TG_bLY&akHH(=ruU>x?}-Ep6;U8D}^iQX>vzw`yGhwak!u}(IYIw13c3ktCjp2 z#^LAcU(A-_=w#YEaRC$;nV3^<34+k-1>cEaUz}YX&W1$jUG|JH1)t)h*z)+zTzpN@ zM(4!h#9@o7GiN+fJrA$0bT>^;2E@)^B|TWttyiywF!2 zyoiG>Frtb2-uQC^UKO?c;{M8fEsqP5{eb#~(NdQfkKMDO17eO{ELucjCgYsg$>r)9 zVmksCm29;zkAlxeNNi1R@h4Lxxyg5{62s@Gr-N1*j;wS^T;-L%BTm$4RsV(#g1w~` z2J>eJ+Dsj%6fQ|X2|@ar(J$pILrW0U#XV_0y_feGb8k`PWW_Nu|G0>EP}zf$#=zyq zTq*>m{PPOaYtRAW>A$6}a(Gj1><%1)0xxDI2KkC_hqPvSzYPU$D@epwloCX*p+;h! zGA#t4?Yc{=BZ`Y*g?%6`|Jh8c<=X#>np6~ckp z9`O`wWN}-d`xCjKo2eOTD{W_7pF1t~o7|H9pK3ZIS&5diWD@Tp^Wa!`GiUh2Zz269!_W|FW> zU!(oNmQW9M(a*GckQ}TWp=4ZX?@+B&CcMWlQoeyZcND+hqvfhIPXoWffo>Ds9cf6p zr)g0VTR4A$f?~6tg1LSC0o2BS9Jj@MCnJtE|Y+UXoJDo)em!%g*UyIFfRggyM@>{4(z~nLZn;FkL94^!h%*Y zdckEz>ARo-U8x_JnG0K=eT*Ri@Jq4D8plf;2>}5LO<0w$E}3RtDaVh@_siTdq8=4) z)BSUb;1^~9nR974j4a92QLbR$ttnz~j+N1saoM%C9*RZ2EZYlK`KNKKFO1tND}E0} zG1OKo^uRH~IjkLTCY5zYxj0h^N3(~w3+dN0ZLnPp>l~F;vgwKpJzp(+$TIA3;obo1 z@w1Bl){N7l?OU6Y252iKo%onsSy5F-i_;@hvpmjPXv9IS2xaAMxfHGajzlvb?k;svsonQAp^rRqTQv%xjA;lrLA@-p-&;%1qzsj66 z1stm(4f5)k78VkGbt&V5%&&>unQ*h~%eO6wQs#;hHXJYbGrWEd%W_3rX_`XJ^lVxf zW32VcbOhaXY6_afXzA}J%1*pT*l6W(oxWE2%QbqH`{Co(k$B0gf!H6=_oN1Zuc5xF zO%jDXW6>ydxbmfm*6GRr*;i%LbG8FN(3A)W@5EXqEtoq`Lm}g_rLlYzd>9w7Y009) zWq~}0HC#}nX%1&g`vYs)8RKloc1z&>Y~R2|A-pN%-Sns-=xkr;;=(g0LXW%+1bdpv`b8Bh3)t$hsLfm~IVQR= zYy?BpfFLYp>Ds`7^mLqz?@D30)7H{&X0siycZhdG*Gm!WfDX@`?-W1l14@dIJW93pyp;3q1rU#HdEHL`Bwd2#|3@$vXN6?ViWrU>KUw-(!hawsmQ zXdekaEq+1(7ZNScI46^WwiCy{`{r#p=l!5%-PKLwMo^oeAMWZ`75ci zW2$abma*N+N#1411>MHY?A5|?Z&E>jO_!@?xhL4x6Ukw$)HGG$qm!}KO}c(Srpv(w z2*pYD;GLH8siM*Illm)OU4;#Vq=2x&@~J#n0T{QhZfu zolMW(15Ul>`zLDA_~V;Z7Tn}kH!NjRs=9~Nh`i|phBUuu)52|w{qrVt70J^UnCFKY z0Aq~1u*ZXs=Q4QJM5GBNc;Q6Q*{0|cHy1jqRt9|-H%(N`TB-F)XEEaAC6jmL0}xfI zX>3(hUe-ol(3Vp;fjGWqU=A_>%n7P_dUB`KQ)KQ z;;22!x3y!Uz5FmTPi4-C`5-hOS>WlXnl(XpUzRD2mgLF#NFz!_-;)Km3;!^Nj?;Xr zXg`~QDaiA)w3_ww_s|n#?lH$eOz5c+(6MjN=YZT1VoODMW^x_@@lOkHF)%rTRMKFLf6%?Ixy;YIAZv(=`7tw9`zhSO z01q<;N^K`Vq*ATpSFU1&by?-AYlW&ppqcHKRg515PzoHMTBqkRmZ3y%)5+y~&ijXC zof2n1ZRz`RB^d@vxFZCi^`&2yRlNJe)~Iq`p_izgu`X(*IHsjRja^p*h;6PJMk^OA z+|&gJn%-G}hB)F|PYLjCN7ZrP%k(=giNVF9D@?Q^Dy!(|o_bY3>2^Mm^yu6*jFI*b z>&W5<_X3S&uhdm%cAZ}?%P~dOH=8YMj7;ESm17G}t1+jLPlPfWa*BLB=^SmuO-a7c za=AV5{rboD5#@IO3F1dkEM6E3z@9yPqs{~i9Zp@j>_=%O=*n;en6XBN5bo@9#a8?{ z`;GGKTJ(MPeZtukmK+t2;&X16=bXC8I=yhVY*i_D@&dus1WPtayP0oPb(PQIfM=6F zeK!!+?5*Oxpg>qt-@|o`QJny1JXDVfHPcfu6=N~hkc99roZJvY{f$q^vxMdIb9lq+ zFnZt_viQW}=cmySa0&^xbqdAB4H7z!(bioVIYZ&*l>6x1s-JD}B~5bp;4)1B-aJrO za!$ndVfz70Gm{{piJju#r&)l&E&z(sbr=n6gkosXV)O(ska^Vk-x0WBilW{hwfe@k zUqs8%tC#$9b7AQxxqrNq0G@0&9ociyX%ld|D9UA0B;7SNUQa_tuUtQQ~_^SqpQ zY_RxX*FZ+`r#ZT7NBA{JtLe*qL(m@DALzN}(WB?cz@YnpbksJJbv60!-x*k%4=c0r!(l3q9j=gJ(PlnS zh`tJqw_UB zRTKYiZnbd2vELTNHDH=WbNG2FKOAf0Ba+}z zi7R_7dycc*MW$jb1!Nj5XbCs$e3NukU)xn{+Sn4hNh z{TmELu0R?Q`*}UDsf?JaRRrm-pXPM&E^Cg1QEJ)%Q1pcWW|;01fu3BVB@f(VY}d`3 zStnb(WZ9atYN;Eb5v_AKs&sa-6qz2y+I#)|2<&)uSxxi6)OJ%t^mgD0OaWm+L@I{* zvXE`WaXK^tp^4JXv5fG-pi-r|ZMCxyIwJ176KfM9g!xOTiF94yY^68oON+0pn`+S$ z=^97rgUj%K-l6AQO-6r_Y4i7GSU!r9^OU7HI~%fq`7{CCfwfc&+;r+>?BW<6MraS~ z*f_K@k4G-%Arh3tc4JovsGX|OCt5TJ%Kju|yRJ7pk?Z@f+rtkVV$$2FHYDt{3B7}s z_x-Sv$;TebC`oO+cB|`+f?=u{nUH-9DqlJox63bkn3KbMRsdQQd;0A;$M{Lz9btzg z<_#FUGtMqOV7E5un`#_CtS71ru!A}pKFuM?iwH+m`UHoiI^)Rg1_uA&SX0c=f1&`+bN{*C z&(N&Cmd1WND@9g~bpHuU5Of**OxdZ{BEHaZ|?T$G)|1XH6%W#%V8 zC^lwVs;?L+g>V>gZ`vm|>p_DX^jz;cpb3$PyI&>_{Ij{hwKQ4J8CjYCBn&v#TtWI| z?58`-N^p{G_4y&NcroR5J=ZlkAbC@!p+Xmb`BRJYm8(zP;5f`BuD~Dnt-V?ULBWvA zObvhM(jP;7L6gMz`q?71>1h1K1=U36bqw*enVL}dQdM}MYdK%ba6xtTShS2=GQHBu z+KM^U0D69YK8p2fxD2wubcu9cBEw>}O#w@7;}>63^9!+wxbel)*0!?Wtnz-mnY;X@ zltCGR?!16}WD|pvfk8X*je!fQSt@<3lXzBeY8>Bw8|s_P@1Bx?Y*ehWQSqgE=xYfd zV{^o$p|P$%zLO~9A3>YO`Im9jpi_*I$m0&|yJr`Gi63i}<)!(jYMKU^Q+Yey(h~ZS zkJ{^*tQFF*JWI!FeW*}1-l0+%GeA`5oO{W>6JA+j8dL=U`yNDMw!C4Pov zmZy=+3^Fms!uPxo;U-Fd)m*fsJ4^#b2ElkQ1BT`gt+M_ z&~5l=B``8%_mJs#RH05=4ZJuija)Npb@`7P2xZh#U(9Kf%%k%$+Jt$KJ|kVjhliP4 zQBj%A*qHT#et-4R>3O==)zNz}1a+NVs?Go}^qzl#O>6Xgyi5ZA-ipuS2j|Gjl}|5Y zjuXof73C0|mu#eI{%;n*HyJxfANg+_#kSSuA6Le5ujri!WmLKsfana9brKgl)x$+V z3nk~v+sv~1o2hVncR1ey_73-hCO>kk85tYNpSp2u*3`}=xwNdRH$|wm8tdR zmC$hlx_lh!+tR}ulTg9-h{T)iJF$w(u6hY|62C*0CcKatj02qhH#Q>r+1^}Lw`T9h z;q50ceLf*%pe}=x5qwry9T|JKia&v6LwN}+{AFRugvB=1N(vB8IT zg?Ey-ai({l#YSees8;9xtI97Q7i$nhOaG)FZOztobmA1b_rSCOhiZQXaH}(OCw=@* z9~%|Kii|CXKotDIxQ8(Rg|Q44ji9j(5Wq$-S9x``+=F?w;KQek;~>NhSUU@hppk?4 zmFt-e&Pp-!$c2#7(5HQ3RM{qSOyn6Mwt{~6o-4HP-ZpJN z>I7azP`wHU@((<`CcP8axk?pDMw^e7zqeSb#-lEslRA;q5|fe^0We7H)Ebv;OQK$% zc1(^e)CslN3E6~3eQ&i~hmZTNgg1T%g|^kfa!;HfB>WiEmWX=@*)h8MHv1}qR#@x zupY$0@D5m@blk0S1IDI&2dUGOiPhk@*AHu-P2e!pkum`nM@?vldPbApop-fpFnPae zbDKJihO6M7`<2@@rpflZw%`9|!IUI~!Fsv-*(a!SJ*o4;Kf;&zwS+njdxna@cOblC z9AF`8|G|cBMGLJ!O+Ogyl)m@5ZO6I`?1hi@L&u4xkSy4S%Z_CCGDPm@xscYoIj$fX z`xnVmts80>X_i7-bgT|01mF^I?B2tnaRAVmUl0I#Hz7UYrHBB6%q~Q1OkIAy_FR2L zh5j`d-2j3usV3_ns#(gtPQgIb_rKduTvz!L*Ie8Z>oKKhMJ!_hRx$%YEoj3&MonSI zaPeL+<9XtZoi+6WBj2{M{K3!d6X~jzIc~J8j2!w62SFh?{YxT^9*)8@3g&GW;#QcC zGNB37$H(3?T$?ZCD^>!Iwpn@B>LIf*?Z7LWc_q_gg3`dZ099ff{g1- z?}jJ;W zDdoMs8qEu4%F;5wmC(lECqn)?YR!MoGI0tK-M-KNKG_`_zTu58e3AqoEtLRrnIp}n z6;v{YB&(%9lG7ZSdff0(-qaLIN3JJ^mUiw85bmY?ovze6nK{}l}x zN|>7qwd5A8gyQB+%Bo1tFf&;sD=nPqpq}lcIx62KIqJRi>7M?HwTVR-PII>nc6vI| zFO=d)@v6V+aH9%jz$iCvV*uSKHF;(0vs8iF+oW}nS+SD90Yp6;|KHztFst6)IEKB< zmz?pxawQ6ZegTixBaP*Sc*R7mN!vi#zS{cR%WJlSms-vfsGPLKI}qx8{zSB_V7=*y z==(vxg`>pbPVgMwD5AzKi6gOTv@=9kbYeV0gv4LNkegs^*7}WwuY^3ay*c5W?R%!( z>BKC||3}qZ07dzL-@;pTNq0yiAP9n#gn)E+FVfN=(y(-QisDr21-O$yof2`cdKIhdd5I4b50`uVkY>xmZL|A5Rn7d2<@x^2DQq3rpb+%;)thCIu?ofu|p>zQ@53 zI44~(Wlv$Do=%!i`Vno?Bc#^{X*5*6@_NcMzDs5-ET{=-DNZPg{eGsfl=ca*HUHvGoKw#xi$lYb@)#(U1R)o`6DrUm2T$#VHbbI_d!nFmkYP3 zM|;K2E;9$f6TeE$gpUtw;a6M5&CNmi3#;rO5k@mI=MtNX=ULS1gCws}Zp|_pB(`&8 zlZM(lVf~iDC3f)2AC`>v$p7jeCn?jB=>IB(6c&HkEA~O%TLQZucWc!eCfTDI9pM5h z6QwaOf%c|W*>ZGrD)r%-EYG7-`Ifq>&^|(myPBw86K0MAYuB6bR1716AH;~MvESV@ z#1+{V->k8%p4b*6^?Tg$;@XwOh&*dqF*M@|ZNE+K4u^!eQpjGImvtJadh1y_2x4Lm z>^+Jb43(8JUln)y&Ki=6?DZfA&FIZ&Dgfve&8FcIR#1o70x5mdQV=vl0ZIkj(`UyVuRLs36Q^YL6zEGG7Ahtk^K#+?-2_ z8;#*T2IPLc%wn;f(Zdx_67gmcXI*&_)jbpnDMv?uYm@3q!)`~d9eEm2~s`Q;7)O~ z)McfdDzW#y$X;hz0DpPBs~2S6(twA-<*GUVvX-1!T(am#WAJrb&i4H7T*kXJuF{gJ zaJvQESXo1;EL`<4vcpiBfLU9P49(lf{y53U%LoJU1m-!y)TA-r`)W= ziLfO7puio?--V>ZZ8?T@Fpsk2Cx{6IC*lHCu=l!`w;9B2Q}?F>d*3u-R5wf82R)t` zR4oo@*`X4=3tS z^E{u}^APYxqCAu!ewX$K>`T?C3!kVCqq)K{tR?$!I$Q<>-pTr=^jE{oszsnz z!qv3Smu%9=754&_{Yq`W4Yz5Se|7D_I+niQ-8qwZ^$08J!C!C4W*=LB{Nn+dzEz6Y z#`7aC_)cZWOPcw>?bqdLn%KF;xP$9N09pQHW`=U0?z^9OAK)H4GCJz|{(bnBUp%m& zeXh?%23Xeb{vm3t)F44ieY!*`Bx=Umx%HN>2Z#Uz71s{^0w*p>DiuypO~bPA9X5iy z(^_o4?_U&{&g)lC+0mf~C$wnt@l*o`&{sUFeQ8a-meItHzY~KH01dO$&zARnkf#&Z z0v9l{+-Xr=s@BBzF!}5r|F4s5(|iW${I3T6`y-C=+O}81-tlBTcF7r-810E;zN%9# zv{;sR|0-lepg(cI6?LvPKFs;7?mr7UuuDhT%lLhB4&j*~cL4y)SK!)lUhU z>xZj;EM0sPMn(;tKGPw)widkdZ8g1HoeDhs#tH(9+(acQ5s*jj?dF&^KXl4WN)SuF zMf;)}D?=^+=wSC9hYmhh=gi2e$|$i zF1!lHkKMh!A@utkd!EJYM|+*mCcpsFGOUuP3>gK zrUTs}0c=XU7Dq)0cSfM%CDc>Y*4sQDvBdqJlO!^|A)B*FDQ`MQLg3^-jhw%ujvbfB#@c6dAoHz*BE8&lQYc-KF+oxWlKf z9{qi1Crj6W``lG&L}P)nh?q}#O7v;1LjRMGc^R)XX`7eG$(TE%mb4!5>yTXjijKbF z+m(3ugX?9!8=q`hN~DV5vB4g@RcfcCQ=xb|F(y0I8P$Cw!d{K+(ZYa{Ma=t#P!yFT zQ#J~qCV+?3_QUJULEOag>Fi+_;L0R5wDVUolVaFHhd;HAjSWZCNmmHQmojV&3=DO} z<;zP7m5F?IY`|xJ3lsz7Kn|8ybkcfyP z;^^OtAY@MjK|w>WpLm4k6IzLXRpnUm2j=a65%RAsdx2d{@^zAZkf=9vO@+94o3Zed z9hJ}~yi$elHRGvr*X9HpNC?eW+bU|3Z?@!zk8AuZXqW~U|J-8t}0!<5Vm+Eo*7i^bbt31IVaRpkZ@49gPRaUyn7ZrE;#ufZ+kznh` z<)tQEMVEnSg-TxZ6x>qb8g{{&uws&m;TKkgGM3LhV>X*P#s)Jw<(k**SpBiVC8SrN zOQYjq?UO+K#o?FP{<hH>xLWA4U%EI;Y~avh-H72nT>I zayTPX9hm~(V!3cHd?0x#7t+KoAbFM=n>;GI-c{Wab$HX{U)e$u&h-qjBI_MNI31&N z*>Luy{EZ-dA>~>V55a1G`1rC$Y2c4DkEgR(DQ)Z`Hv`2En%n!}#REG=z-qgx`TdO0L*kBaQj?Ql_?y-v zL;=M*k~sg12+5B_FmOqhO2ShXKo@Ikc(_i}y(93DS|GAaKiyfG%3z6e8SxhhmdYRM z)#>nKN7LS2uwxB_Yf4ya=H08e7{6-Wa>d_hRt@V=EYjs`nM2BDw`}-f^G8+mt}Nrf zhY+>U-UpA*9bkPS?ZZgi#bvQM(F51bK=hOd45@-(8#Gx?FE{m?BVP3Y#_F0QZD|dt z8ukFzY4-G?eERexfmh5MNlx*BHR79`x=g9z2m=ZOVPDedQCk3Nef(lM_(7;Y`xpK-{RX?hwqH<_fM^U2ZZce#M7 zs;Y~R4|b(MEE!L4qvMY`y?*{G>wG7wj~{7*?uOTeDjVRk{foyJ`*U7rTZBM~sWt4^ zS0Wl-zH9<62LXb=4v2N{tYNBEke$J&bMAPx1gWqtx7u!pKy)ozn!MZc5K9A;q{j3Y07%QPC8S9*VZxlR>~n5s2Kp zo4=b!Ri5oQprgO;qs!TySJ}r~znK30h5lXC<)sjdmYmsASy`_l-M_+BOA)mAFIN9W z*XnD+7suZ-l=ZQX3AUK?bKJM@e#%=}&j?XDFs|=G4_}gCzK*FldS@tQmv6__=B|zn zGGZ5GR{_6*zT&JPhqQ6#e<7KSI&o>y3e2Pf5cJ;E+pV6Apody<4dJoEPD=w$idMV*9s z(?INQd^WPl57@aKZ@;+FQiQt+&^CtSy&v@2r1i`8+usT}ljSMz6Z*A(-A#HUH}XbVS({ECHdhswzn(cw_l|Ov&*B_KMD6gf zX^9U3R*Ig0k-q|;2k4oMEl?VHZ58-AR__fy+A$xG+Fg`z1f#AX)ef3>f{GQ|Yzh+42NQP`COp4lGn-zv$vsEiVeK#I638W&;_G!DGq{O%xl1ZF-j zL$k$G<3{3}>U2pP`Q^3~)r_Ucv)cEPt%p10%<0Ry!6$6^cISoC1kALxlGk6q`Gd}z z!OkqZ9$B-!(@Xmv8-EQcHaaVkVXkK+R@y3qU5wY3VuSAeI>}P9X2* zvWKQ!xZ~meVp9*hjPLX3&m87Sv4r8yaI+si+RN3I)HJOYnbh(O#84}{F`-%syE!rf zdhyT(K^Ap7I=Yp!GZLWoL|xq+cy?0v_4Nr!NF3&tD{&OE!JQ95&F{d zz<*)(FEXgZ(0k^{D(jET>!VGMqO8LBF0X@Ml5p6{sw-!$)yebq`P)c_l=SR8(s$vc5u1A9w_{a(QYgrleMC&fvytDiaSFX&Z-0xw z=VrJwgf_q1gYi`B@6mZNj$m8F(6-V*>*+#W%ZlQTW{!>jV^EyNLb?KigVZvqzu&h_ zw#uE;*C)H^TBSFMcSD=tcdU47);lh|)&O;m>6TT0O3W-2Q)jVS>2Swu(UDQA?v^6( z&u5tvLZ_xy6Bg*@sTG7>@~`O=M}u-I4k(YF!>`BlIX6$c(BZAcrasEEf8{*4%xMmo z(l{`xJP}2rH_Df$=%gRJ(zrXIM;^zqBs zdruxk*K9=VJ>PENO)MlhSw%-{tjPoKr?>&G%9m{AEI^5CW?BDbv*KS7QsjHntFC4P zRoJy3dLRK=8+z{Pmq}+&$Li3eJo~VeM!owDWK6p8lgkbhicF4pkNqt_fuM|?c^Yq% z-8yuWhg`jb53x+TbkTJ{t7+svN zAHyCmf~nuOyHsX3C#N7p9alkWci|0BA(zsg3LD(|V;;?Fec-JefT<0Y0bb7pM<+_C z>v;F}(;Q7=R~2OLgZ7D`+fu93FASd`Oh;_c0MGpx z{@eXNR{X!NERJMzbMwnCm0~IE(vWkM@broXi0JQ?MolhmZppu?bjx+F_kd-0VCq`% z1t_u8Q+EK_@ZwRBe0FT}U#&@tB)t3=v;Wl|Cz6zY=6*Wa#!$^C3X*c+&Xxte^om2c z7lNk%z-b81B{ejX7RK8Q<7Nlsl8&p(-eKcIHO4P^F*W-PL*#pW(F?;h5x>xJu`_X? z6b^rXSs@N3H|jCIisNtj@{=)19VB5gOm;2u)NOZ%pN3KA**_{>dnQ+K@Ftt1*wkEqW~ z+EEMC7u6uAKX@(MzUn=jj`J?3)FriMjP=3sl1!YhVMKEiV;S<1>&MEc>SAN z9vy?m4g*qs;(wvcNwuLdE-$CRjzB#T{0^PM@jrE&Yng_7t=#){DkWIPGu9@0;D8^|g!OOl7vHY~QCVeg!FR#q$ewoll z#}wRp_fKCSeMePED!%UZ=f2IxpV+a1t1v^G?pzszOCem6r_p`X}~uBSTbWJ1YJy}&8`Fx27VKfnO65jgnU91=l5|3)M&6j1f#23*^< zopn!v=Hfbkp3F}Y*@ZLx_elFmN4P(&_1SH~A29gzsMfTam`Q)b&Vc9h1jj$r!NnzU zy4}ivRkWhL{UzXfHg&Gw^)D7Uss0}@O@vH_9%;3a3eH|b4_R~fJA9Iav|y*OK<@SQ zQuGL;8)M1Rl^Mh5pQ@`we~s$L2Z_lG^J0z=w(;a^gRS1OuP@D-Ecm2a#>=8-Ax#CP zRymgn;%Zb<+T7k(yFy)U5+gkEQeQz#!A11J3pX*H^zrB77V#QwC5zo>GnazVd=8*` z0^Egz3l3g8&$RYVa1MWv=#E)u4o|xAUoi>3eD6L_|LLQ32Hza8Yi?41-A+xvQ_I7k z+GS@;NP<{f)7a~v_6T?GR6gF~_=gMXn%D|(rA2~!i1o^%X6rVQn4q%xb1xbYxTOX0upk_#*Zm9QfQ)Fn8t zq7#NR2{dtwjSyIS_(g$QP)$MjvsSAB_eWB__Im1+76o}X9di6hs;g`R8zCIb-jRDR zZy+D=kzBcz%5=({yi}Cq%42UK#ZMloEg5u)aQeR%wIwc>?3v5@T5pO@3CFO;o1y}t z7gf{2+0=WYJPL zP3D?zgOs^-P35ch3w3RC5iNKpdSM^$r9sLwV z4tHlyFZ>&XUs&bt4`IVGUPJl%5aL)`w%qnbr7xP2E*S%TnoDq|5=KL0s1)rI`OH5)18-9nX+!L&NIo_~!qB1JWrvXMA{mn@yOB7o*sJ=Ak*B49hINdh zUlBR2SO?zYQat29!7`!S?>lo?$Am`{+sY;=c_wRQfKc%*P3LYG$+ z#TmT%HLf6?f6N8To!f@WM6N_QaClv(@Nhx$iMxKdvG_at`7fNQzA;=*7gY1RLQZ}* z75Y0t-Ba7u9fwxRa~}`A27P;OK2=CabW~)Vy+A}EE8e5B04mtL=MGyB3*^T}z4NjT z&ts}K)}W1(iMZZT_K9veq)6ZIOIFuY`IzJyW+u$U47MkjXV+83_q9gObkdXL#qWs| zj9+h<^glx4Q^7RIT{^(6kiXg>OhrO@jE4!FoiW2aB2mk#?q>~U3QSk0df z{;Gs)^9t*zjOPYF_ziIWue9m0L_Gdqst#JK2ZJu(a8LZoQ-GlWZo9#GtjR@VU)GtG%J_g>od){L%= z7N+|-n+{A-HH6{CawlK5WbZaUas9GziV1le^GcouY5<9O)N2_u1Jj*kxQS5A_ zxcuq60v}G%TX?;0<`&~o9h-~2hkh%>)iY&R^%6JyA3uKlX^R~z=1lu8eQ34k^a+z8 zc|Jyj)?S~q!imPF4={#3X1YQ~oLhW(N0zc&UIrmFZ!ipsBx-Fcdm`p@h6x~nJy%!4 zvyDH1*$co^d~lcli>e%gw^OnIPgD4gsaJVg>@a1%#U>kbM0PBy+Y@prtzPG?g3AhJ zClhpnL_BZfL`(gnWd5=XJJjI5!q6H}3TUKi24hRRw+UuQG$>GxI7lZSAd6rIGQyupGL9`LPBDMncs z$0$sYC+HoxTM`_`QeeKzk5oVL|90=ljM(Ph#X0ZX#HQ@FCe7Soksktj;AjT{11}+@ zo_ZHfW-{!ust#r!mihN}ho?lY3B_RhK*vSBMFza?C1tq^yt zooCg$Vli7x;{&sCu8$2GBa6Xk!fMbQ_Vz`-Z$S({E-n=jVwsaIkv2ZwZEs*s5bWQITg@J zUVLj1RB$GjC7eDCEi7beJC1V>b;k$Z0mzAfW=H|dt{5cO+t@$`OlmPdAc`EnJ>r1g zQ{Nuox+Zr8VxNr}0(9>`f3gu_t_&sMUgn!x{d_JZU4{pLTSF_C2OggJZU(W85=^E+&X&FNMZ1W~`e%Hz0mbAG8v|mpu7R zcc<3p)xe~uG0+z*c6jq06c2LJ_K55}+-*7Nzt+jRM4P0isLx<2TkFrMm@8z)I z+>5rWr>Bs=klY$CtS1+Bzp|VY&2-yKW3Phnv&BcDr3x*W`5jekCkID#4Dt6--EJt= z9c_w|&<=ug4|L1FpncQggpH2GCy8xpA)B_e?{Cl~$6G?XVGf%R+*0C1H^$>3W;ko& zl>}p4PSv5=p9t@IQ_%}Qe4X8IyfWyQ6j-?1ZdocH?JlcJm{X9JXQ#IsMrmu!z23je#DnLcdO@Iph}MunRX!p7~I>d$FvsYqnN z`u6(9`HSS*Dew7Y@`{8!S-pK*FRaEQwl?g-+vtZgEnigL8uH-=ea~4B3 z>XJS=g4)hbf)o7DpV?egaGa=V==Lm{om_r>Cw<|BLZMvWy@MUT1YGQZNppf|M@WC05(v%e<||9vBXXxGs}l0b zw%hmfHaFOu95(4mph^Z_*?j2`Uhp)!ftfi2#}oB*HCV!uJ1_UrOpv;iIr=L!>m)Zk zBUTE&fJh2lYC(tZ;AA*bl|sG9@A4y>sRg89Fmd!Q@cm!^S=@maf>r49#*MB4l#(K_ zf#2yWu4e{n)Y)~`#7Dzf#=&LgqV;bX^c3cbl0DO2(g+KA24_NX%_|IbB#6N|%oUe&sEnp;kuPGQc zMcrwX;`S4RwF`7Wa(W;{H%<2>>8uBuI#h+Kg&D-%<_tUhCVz0l$bg_D7&;&l5{vx6 z&;`gTLAwoSr2e=rXor~JeG#neg;FUN=D%JA&BMM^exW1Astbi!XeXy+(7%OzV=vBs z9@M_?3mjAYq%MyC6OAF>SK)E)%Q8Dqsl`c@9s?0PD>bPI!|8E8j&zuXLjT{5_92Uw zM-M9F*y=F)^&}7CgMRcg*>Oxkkv2^_9gRu z5&2)5>^2C~>k^+)f zuTECdP6MrK_S=wB->alaQeS2p&Ux9?H5EpUDMQ}RU z`=?5aP6z$Q#%;{&#T*F8QCO^AdvMJ{%u)glL!EXh{@wzge6tq(vT9t2+}e@Dy@i0U zw_CRyiH}CaY;+Pv@b z32AN4b57Q-<1Q^#3a9q@9y2~Dnacdf-kP6R9avhDViz;JoB|z3C+k1U5AHnGF#|95 ziyneH+EMIENfw?X<_-GYAsVDCB^Y(3mxgg4g>SwSuk5$$bMfZwD>SQM$%UT&p;D)_ zD*pAHTZ}jpTe*xFKX901$0yVr{O!-VO@{UZA`9 zb^%(J*gCG-rlyR6_g-F+KmkW+*gL+NP-P_s*nO7wqi-7&xn@4G6S=={H(i~qGy+H$ z05yhhyc4e!sA%{{g$9R&Kmjm_%*RNlMK!zEp z3!Pj+-7a-O0VEk{T7c%H?Duoo}4N8k{Bi^ipy$};x(Lf#0oQ%>KHUN(c|xXD2dbg)1SyXE3%;^ags{U1Z!!~w8_-R-PM^fO>-h+m(@4- zULx^jloB;T0_Nf=!={zNGA^lyDnm9AI9Y2!8k1_){h-M$0qVI>zeJOZ?h{#gA$5;l zgKDs?WQxX{F#gxEaDRu|F)BPgg%(99rT=e^Bx8Ryw&_%Je#1Z;VyfHajTSJ2;;AKsJnV zS1HJmi>{TmZOS`Wk(Qx<`NFSS%KtT6RMS%sQUwaiX4BAdaooI8@u3{}epH1(AvCsp zp=O+z3usHGVF5^x24$Nc)FlU;!+0EvkGoMm)F-;}utiQcKr}^!&E*lTe6`g+!WdHd zDw%>K9Yq19yvDzskEQkSFsHqidU!=Os3<$S3yJsmkmvVCNv;&7Np$om+3%!5TrD@+ zUJewLCJ2AOGu9{r%Ipd_Q7Uv$6Bf0LMFXR{_c zw;Ss?SpD1Q{#zjf^DkpmgPxHnoq%3Bsdc@TRl3)Qkfp(k{oM@^uUQpwJ+#I;N{ zH8nu&oowR@^GQfZ0NR{9OAFM+MQE*`Uu=e{57vJwqICUAU4?5`XJ-P#!TOc{eudf>gyNm(-lN@m~NdHC{Ef`+Y#=zJCE2Yl=o!n>XB(+JS@!e4?^54QRaWv|70a zzr&*|Hi5LZ^QPIjqvYoA|HQkP6OfcDbUDRPf8D(feHUX;oey`@5<(yl7dejdhA#)D zl8wFj-1B4?+0fH^{@aDaJGy(owGHCzziZ^`|zSpSALZSK?TcP z1&)dT#BGAnt*r3maI$u7h z=Q2}&^v*IJvk^&fHouQ{cnQPBQZ{^@ZRx-MMkGj zB5&)StU$KJf+C7bz9d=mIQVKL=6SFYA?|@kL)T@BJ04*XBgNZb zK)NpIl~Km>#YbvZnLeUnBFLY*R}k1E=KGfa#a#MXS)%)+Mm+8LD^d49?T6(fhq{%P zCTDa=*b$n%)=?b3U!rg>t4`Rl#U zT@!6VAH*@Va+T&w!;JgdKwEMJ`nnsQpKG`2X(&3)W2@2u5@@R$TXCD=$3El+6}`S# zA~SBZ==uB6Hq1~K_^kz`Vf&v|JN+GE5{fP0_8@PS)zLXxC^W6?8Ui@8Zyqj~*5S|4 zZDLNR-rWK4Ae=7?k#)S5qPF7vuqlCw5oX1dP-+F9&g=u{HzL3P?3|;@)cK@z+Id&_ zK-yrjr)FadVQ=LO*suvef4I$ia2pWt*(qf^{;j39JlC;5ceG3pNC9loo88P#9RX*? z+%GE^@0ssM125G6d8mVs|BH4G1`cr(N!-*+#N<6(JwO8w5AW2xuD3rQZ>t4Tb)G48 zhWodFvZz-Zth>kGP_DM>#83WkKyrK z#sR?P#WR(~|C$59>-v6~`47$1RIBG9AYOUi|4ejKeahoxQlJ+poFTdV6F14A0Ez;yB{N4!Dz#ZQi=8$6e`eVac(D$l{L z%V-y^i!?j*Jt=O7|9PgpBwLqeT+^S5r+i550^$-mRQCrPc_P0?auoy>t&ZKe`L=tk z5BWcSk)V~`x8C<%<#-7v%a6K1gi`LUh(1J_*Bv<2OhiTnBn7OHDSKTQOnSJ^XleGZ?L9x!tS70Do;$jLDtBiNbJ5ofz{N8WmpfITYz@us{T8cCXnf+@08VQ&+ zD)a{%buC2I*I9b*`<0T^#k4;W+DNY{G?=UbtBzJt zT6fLUz~+wUa=x6kCIoGdguq_WUn-RcVoRyN2)QqJx=*l|{UA^4v-9ZLuP8%G(J|f< za2wf}8JdBG)slL!rsnUG7Z-oz-laN_)ugGz65hbFF)i(5XX_T$?tXbj83qv5f%!Og z^?Nh9NYdDUhF@z%*>Nv&)Oplx$A<-jcD~M23lHn;blXG>R?;>4HwEHrIx31!$Q*qQ z|0R$~hlm8cXc4<%%w)`C63lS*cB`ic4m2YpWW28nK2W5R!rxhj&5a3)YrUrsAH7u1 z5HZS|Q(x3mpwePsfu|t!=_c#gMe;+(5kDA}WhN3azNWrkzIz(Pc;O$)D(zK*Bt6-u zb6>&8`Rk+XyY%W_`m z_Yn{Go&S~*Ixc_ktf<|usU3CRh6IM%jN>wkFDj@&nVSxZ10Xm-0oE}PY3 z_~n!QsL4dT|Hs_im4kL)5Tc|C5Kd@>!>Xx?>FS8M)v=n@>%tOkI&F zo~U^D$`e=2t&8qyiafsNpHzLng1w|~ zaZ^&fep4!iG~%ZKaWrVa7CfQA?C??`YJd6VD z=W|ZH=PI-xqM$BB#hmL8x%P?C9UthdmNn981j`*0lfz=u*7~=JnVLp3S6qzuZqTW; zKu^6a+^4-pgFXn5pdlhvKy-vVF<_Qh-BA^gq*7A%Ir_pY5Gl5@ByWEAxA>Q-za=4l z?34k=2Oe_BQK>~$swr=RN<0Mi0(c3cn1$2^f7LM0J!W_-HQ>qjn`YgF|A;-Kd$?TS z`uAf{h&j!`9PEf$VV%eTL6ztRp{a+kz!j2t}T6U0HSEesKd1sOEhOED>Niae*MB&#eP?yGljwBS>iVTj+V`o7{2}n{& z9wm8D#X^caj@C&R-&~OGaeZx6XI~O#7W{&ozL;2&rQTrmV0C}42iZWgW-Vor7cie~ zq(%Iol0>`Y<0YO_mm)}SSEOq%)9?2*V0N8}$tXo}XHq}HX2%BQWmw|8!Ws9-%^ z+U3sRg$ArKeX|bL*s*X+tayQWC+*S)Np^WQ-xAJ}+qyZELJ|AFwE#=|FY)w<6nHPB z&_!8I;oPU_qdhGYYsr5UXJ_V&UWi#F=;)?v z_!{H%DmaLjDawXH+m^eBV%s7&Y^FLDG(KrS!8bnYhptERj)Q9`mh9UFm06;pg<3-&$|dAVd1XD+w4FbKmpcyJJ=bUcb)ej9wRFs$=p zs)N{LekF?S02n1#)-w))v2$6p^R)FSt=bQ7RQ!g+i{SRR+MPd;4w=oC0ALM3u~ydB zV3UTxPBTfEyud>@&#jpFeU#1di~DQTk{ob-d3_;SQj9t^pnYvlOSQrq)M4Y|$2dY^V{bZlMKa z>nZcEmC&Sazm9}Ad_6n2G{5zgQTV)8y`KY6S}r5YbDei{=CNHi5;q1wZEFKg07pDS zXY1<&2!T?!-yYnP*cN~O&jwGmp$i5VFUE|@r?WXlLMw(h_}6Q2-M{)n`dRI9Ki?l& z*j@Gvn}!JRUxMXZnFD}x^XxfP2-1`6e5|q4qV{`&&VtU$#m7HlaXDiuUd{()ZRgfa zF>i|;o#Dcj^+u1UJGAXunjJy}bzW$|9ef!ew^0TxvHY8m>DMAP-&O>ePDN_eQZS0Q zt1@m;f2|FsLt#N%gj5DGs?#Y2cbHZ?FS;AuAx1+<<~l8V#6W@wdz;Pf59@~8@tTCs>6XNYXwr%d9%gwhSwENd`%~mgEZC!Um|`BQzs2s5hK1& zf5vOW0Y!<2f!rXkX06RAK9^x>Hc;&W4GXen3@|R^@!5Nglr465c7W_#5?V9h?}E|| z9K5D_uY&PD7UGkz;wSe&U_Uc){X^Y^ol?M2skJZ+M|tMem|focki(ivq!aoESy|l) zC1(v!mlG>d#~H8uj%tsFGK>YJo9rTw$S z%NKK(VhKyW8RRm{z)w?LDLh2U>NSXdXrhCf!V)x^9r0Wr*mNIg-_n^fU27Flv+qYp z4Y1nt2&bnq|CEQ2VoW-zKhFgD|&IB zX7iy(Q-nD&FF&p_(O?y>H&K5Tfq|4d`HR+g0e|VM3>$BqCTC|RyJG0!*$bHKeNR_Y z{9=bF#|M4p9l_0wJG)irpXyLYP88qK>x9*>pYfAN6{K{HsX^t+k9r)$r_Og?5#$bD zua5Wzsm)+VmKn+?tF6L~2uPYeYq2MZG|6{JH*fG$KA?}Pw{Nz@pY9I|`N^1YD7u~mewv($pv_9Z3Tpf6>jO2)3u0Cwm zUk*LoRsRyi9|ppF`1p7BVmy!kvGCAF=;=B(n@wNl;poyUzJ)4a9WbiY$IA;70wV$^Sgf7vw?SSJVIxue$3n^v#OEzD7| zQ`~_%a)!PBr4IXr*dN#tMm^-3+E%AOA!HE5x`gr$k+iH zZS*JP{#+BlE&|KAauU}Xx9ev2ENv(tLtl2$-%7Qi+7Ew-E*#^Fc^!f1A1?cjqtyH$ zqY@8d6%AfHrJw&p1XL!LEa-12I!@B6SNho&5jMHr==4`V4)+Rd=ZKHPt;p|H(R~j1ek!j0Ie>t+YY?1|K&0LgX`^1 z_5G87&9~oqxtXj%`XzwznffiF{OO$*J8}fS_ED_v2K-dZindyr0wmN~g(j@t_1iPcAz}SlGRO5M-b^2qUg|X%o7ln6D_t~ z`qCLV>=VKJFb1e5Ewy6i50c1FN#NZ6Ep!8S^QJzTV5*l{z!xnU2+0i&WMH954aBI5 z4`94kfVHbN4k{VMNjx3;t8fa_edsoDuidx8YQ|&}byeAbn%Q(ctn}U8u6jQ+?0-GZkX;GAg42IYOcHLyM%z)>>j@2$3%ehEope0(s8fZ}B%u?>iJ@ zC$!~aPmaJ(pWwdidRO58W9qA-+6uRIaf%lxPJyB=?(XhVio3hJd-39~1&X`7yQR2$ z(ctdf#XjfUv0nlY$y$Vw%>T1FC&2~%l0Vwr7biye*Vi(nSE4JL-xHfcQFKiCU82Y62b7xGJrnfXnLVggPfjLkA_Sj>_@w>EmTUs~D@$fvwWn@| zq*nDEIp;Q?zyY$t(*bvfY*IdQ9Y+DE(DLli*ftqava7>HE*V=L{HX|we2F0`dXOI9^ey3aWSc#v?{VD^ks`;4uXQ%wQef9)W2_K zHUg)tAQpIz-igz^%$pMIUrT`RSRa{D%ouW$av%aaPS zqe^{v+1yWuXLLVG>$ClM%J=9S%8x&om1@6ZjJ-ICFQ~pV<6X`~*eRFX( zx=)QHHxbKWIwc9@54H%;a=U*U(zM|EI&)a&Rvg`9j+nn<2aB-D@D>z}^ipRL2-ij+ z?by_3n;&s`Og32MrT(Qf@Y#I|N|LMU*5BuZFI*R5l>l>@M>_<_j*uaCJ1TAfCbsaMC zm+Eu&OQWjDah35kX$#5@dI3ZJvUR&t+Dey9bcG-jWy5GH7BU@zjdJK9^Y-7;fTmp3hQ$Vy^ojEq|4|85| zo)=?YaP?ky^-wuY>ku+B$Od=%a$%rVRGdzh*(!NmlhisdiJkVwQGtX@PnE{kh|EK0 z4DTu$BKJ+2`}C>@OW+XjyHWES=z3NY7!!Cid&6{Fa|!V68VVJ7HUql%E*0Jm-Pm%k zK>#kUt?L-!@ZI5nsdLCuCicj&T1Nq+8wRqkjcHMb(4ZYpSboFw)E^Kty zW#7;OPxlS-d#UpK6^WD6lj5_K61SfWwBT+y+^xA?Rct(N0Pz+sm!nTEI*yOm?7$L} z$d01fNdms3(!EhEPkg>D>j2a3xPE+$f^xvRw zJ;;j$9=0R#nQ)oYCfKvzmtY4I3pVwQkJI`S>|tg927g)g$M_~f8|Q@l8n-UP z?18F1#%|^94_0g!B27ZJ`Z;ldk83drtDs&ZshW@P!^2jevMCZlD)%r?Yj<7*GMY~@ z*zxgrW&y!WD)K=nV+Po)@Dwa+lW1MaLUVQ%E~G;w1!G-lJvFMsmc1l>~CbJ4d4EI7$~}ro}IE}WxSrw zGI*)&8nLWJCuGcMn+kS+UiQPKMH2Ja49deDn=219N^5*1qz(}bi#A=McsT1(Sc-s* z3xU5V279v<#Bl2zT#DGrulgikTYt_8jHD1xIi3O&Q6d@Xi2XXqT$e9#!Xh^m{H06| z5|_C@H{HSZ%UXg*D8?9@=lV@?EWL65!nzoM#o^l=3H3*>W=r!W`!s9Lw%YpMD;iH(?ic;F9@mh zch!84LWg*N9=*c6OC(#k(U*~2)bF6yg!*Y*u-V?Q~>`_)Jdy|8U&~ ztEkl7vEUkt3BJ&_Gq}a7-KwIOoAGa4;Ipnb6IHcQeN-ys@Vo{Jnmwm6cNYJIuMKWa zUD)pNq{gpX*Cn1+GcTv0!zua~+2N+2iYSL^kaONbO31>s8GT_XqI#+^oJ23aIWI53 zA>tECAnMYn25M)wkIo`+t47Uv+&PDzG`6y^!5zGLqR%iJL3li zDB&W*;Tqvai^~@I+O*cy_1%CM9vbbQ*yVHhC){~Wd5NxG00F@J9~tqM2gr-aY|&0=PS4?8(8|N<};^uK_+lX#(TdR#C!c$d_nY8Q}Z}oC}L5V5>QRZLWbH~h}am6)> z5h!)|JQ2Z~0k#5MvOxp69Lq-Z%B|_~_j;x|@Xz2nmz~I=Rvh>(w_F zZ)tqype?wt3;m44lO1i?(@$_{x6)@!wG(`Pzn<}_Sr`MaVQR3%SwME0zx6dNRB`9b~ z8e(6?!?Dg)_xdigR*3ALVCe3$dDQ{Nb%u+q@nSd=*(g2PEZzwG^Uvu@`d#IXjSW$I zO4G~!ZLX4#`97QGU%p99`aTPN&=^$Qs8+{(hp}~MPz%pwk&Dw`kxlqDQ6I8Xv4R0h5MAYt zGrqsV%H(f{%K0Q$l1uV(C)GI-7&0;jhjntXM9wT&`&Riu1cS6)@O&AZXv@C6wMvq~ zZBl>+(I-Jm&^WoDahl7-=we6xBv*+*2xv|*g)b4$ z5EXsN-*G61<%vhsG;F1x$_3JNYxflv?Za4wN%9%3YB_GU;H=A<j zRor=U&3V@_Hxk8^mNNd_i~-~E#F=z7HH9KX-~p=xBXJlmr&Br;(Y!aI0X>nF6!=N3 z&rRd8OQR>%wK1eA)3vdm(RrBReqyCJwz7W9&VS#7cDeDg=m+w98a&(M>D=LYcAD77 zH3G&Y>~C)RUl*bh3Ol$#q2WV_!W;1tf%`%W88&~oJYj<<5bMi8(bMP zl{^O>jYShiIX-iO7fvO0Q=;^K5w7ZkWcIIh$qjT!KZ2?%~^!lS^UXeBStevC-{(L^FO&R-m5~IeT;U@a)=|!f&7GX`$+cnc%Z=O#dB#* z^m`_ENz(_^KN;8Gls`QWdd|I)hspMf>$X7AR*v@UhE;gS`@=A3F4&E6)Kj_OY2NWI zmT-|`7rC4lMt$F`;rHB{B2~o1-B9YS`{o2)xo{gY80k6H*q88lB}Y0M;8pU#xM%$8 zIjVF?m=hWkQ6S(hI1zS{+v=I7GY+FA+aBDg0h9X|TGH_L8I5!B zx9yBsnU>T_Lc!{pvo`9!HTm72mm(S2k>O*IR%5Zl=68SQb*H(VJ9w&0ik6!xb z$4?PI`0*t9s()q$=mfX?mR$B&R;v>&T_)dAGyX$q)cu{05?L!^5Ue>tPnqFqrKGkw zicy3$-6l>c-Lcq@%PSZmWD+4g`i$yg{HvGE>x4~N#{W-0N~D=@mB9vgch zMtNMg?hgFtp}2z)6v)`Io)Y*4l#%WNmDCfJ?DzO@jRw&xSXhDm5*-h|bL6sI4g3f~W<>WXh+o_5 z*|3XPME6p?5$6R@ILv;adh^7iS4j9cZftqJ_@Wsh&^B$>5iN%}ojO#8{Gt+^D8vfv zQ6Es>p@S!f9_=1XULj18h_K8Kj+FBUlh|`7!Y(ct!GAfQ4+opyQ^LOabsr zz!|pN0t7sUwzj7zap+7Z-W@zp?gH3hXAmVK4{%R_o``u(04#C2of4{5>6)B$nXgU*07#t$z~K1{zG=;w{2wUAyPH>ORZDBty}D&DnZ3W- z><}dIb|tXyw*JsI@noXGoF)sznI7r*?^-|?6C2MHGFE)at~>wB5dj$288#)!g;dWd zV~k!XQMt0|UCX|j{WXKKrN@Xl@FLsg;a)|r-Pz8sLKZ9)#oy%kR#M>LsW4KwKkWux zef&tvq_49Li9n<8HcCDNaR~!4d4stjakdkdsE_kez4D0m$a9@zI$9B{HrpMdiJEt3 zY8`^-0^*}SE(y2jEGeyKa;>Q#=xL0euZm=le3!Ih{DPV>PwYIqqCM0Sh6Ud=1BJvH zYjRDbj6Zw434%?R=)2Z@>#UX{n#dDY`L)Ha2K+kacWshb)y|2?4H$(Lk8uz4mk1GJ zsQ^yoBaEsQQx7|>Z<_~c&4}I-0;bRn-M$H{tlT##?DHTlT=1&#U%gonXZ((;V) z0iQZ!npcA)*=OT4a~DR-GaSGUB?|N62N!1cm6k)$ItI97h?|QL>^(RdYIuiIwZbqh z6t5`KA!ciVmip=va5ahiHQhHt(RXibM=P-eHA(;B;t9H-V%<KL15<(M;D=n6|(#5Qhs)K%yh4f&u`Fvyas?AoCs znf9=)$TeD$X&X9RpMj6hXR-YLCJp}+{R@UJs*bnLrajbqB3hTo_y zxb#7#$rk~m3^ScRiM_Hu^+5LZu%r1MIjy=J(q3^9M#XSC?E!OWQkSfI+}~mqUT=od zh>wHjks}CqEcfaV=0Cs+K29%fds6eN)e#Cwn8hh5s)La0ava`gFE`1PDi6r#{bcL6AU8rV+B8 zdmq7lNzNnj17N9Y>0U&r0WK~;KmmjJlGn^=cE6AKl`%9l^pn_>e~}V@Ev=02LyBLT zTjy2Qdz$fI06fv=dld!BU=MB(Q=tXNB-i7MZ{OGND!^uPK(#V7GYc&(1xyxot29|k zUZCQb09W+_)H9FG0QkkVwLi2nfHwi(eK=Fpaor3!IzaUVLf8O_-t{^2B7R%xdVtk^ zN>{rC*k;1<$;rjL6Z9YNCa5RZp!$Dc+0=mYx6CW>>4(=rHc^03_l6(=8)fG&OVv6e zWK!raBD?M*-(TCl&lfXdEL^oh? z;_co-_bhArN+^mlqV}?kWGnymgjC{^f}$e?uR0onP8nZsAxmXt;+eUtqPyIoGq=Mw z+mI4W0krPK2zbAIiNY%Vw-*R7`LHrq+Hyx*aNS+m7^MO!`h=Un_PzO)i;v*%n6j5?fn_+x z^Ot-93r&S#X)pWNMR!@UKLkq(><~Qc21Y{#5v3-dIh3egCrTLV=+{EUDQo6)8~g_U z{t_cxhG@7*!}+lNN4qW$@_zRCY2U7(*XH{qf`47Vd}2~({O!{Rm?}@bs`~-T>3*=E z@tp3oa>RU*>ZhWJnU*u1?-a*!suc(T;27@y0>CNkjM;qYP z2`P@KH$Epn8f0Cw+?;$fssA(n%7Zr(_^)Qec<%2llt`UQ1UOgN)_waZdPoB=?5Wp< zIwq!uHBa+VvK=YqQ*{;7W}T$yM5grGUk&>K_Gu6MNg?n(I@QpOC%l#w7YH8=l@N1@ zd42h07B#^!zt3%lAQh(u%e)+(eG^2{_e&Y|9$ihWTO&KA}-xDB=wkN!sC@asY9m?5wq6CRjA#?6czjnG!i3}I4_viiClcX7OYwMGS?`&5Mbqj&T{p6}Mp@k8>*g8?sl&Mk7J;XO zV|;%t-TMon<^en87MF2rQa9QMn;IJdmRV6j2LXsW00jcRSZ7;g#4j{NkAn*iug@Mo zk^uVlE)um?J#qU2s(X^&%bebyN~`x!VF(a4baivXixvlnnKio+FA)dC5%7mN9Q`5b zXs_QoI0)c>YVzX&Qq*r8c79JQ9(@Gs?^WXAy#N%Vthy}dcwgre@6vQ`)7}A4ad5#L8eq*D(}Mu{ ziguWatcR$#*3fy8qX9}%>>A8|B2vm>7%NCye}l-Se&&qXunz;>e`zfHi98sD9CD#$ z+vT(ZN`l_@VG^RJ5Hpn%k&T1Zd(x46HmT*jNtGeW>D=d3vsL?{)jGA!Bz@WHYdhgn z#hz~_X1y*)%WppQlMKRXEJIYMJCHz{d}x8^Q&Ey8bn1t(Fn;#2h=ov{covAku0zy6 zDh1U60W-#dEEA@?a-swiNb+&}hC6o$%_)L@_$ufRE1tAZGw_ULZP@DFk=^dM>unl# z5%4{E``hfL6vHqk@%N}m>`o*-F{-qc)E}AnOUQB>?$B{r)>qt@8zmZu^rh0y;sTPT z14}J@!ZbcpC3B1tY@8eUjM*)%j6-LX65XGVD{pXEV+(~+Luyi7P_oetlgymoi9^c@ zhtzE0;$+L1254}e8;Qg=sxH`#7$=4~bgr@%nb7~-nOcFFR81R|p>VoPP4-{NhFwcm z17Cn4Ny(uql^M6e0|*s~%@)}UL8(q4Ro861Z*dL`9D>Lgi#2&-5IE41rEtGP&Gnx~ z$V)Oz7s< zvEIHH+`{IQop6khCvmm-b^-@^z~J-70;ke52Q7dNLjy_17fj@m^`&qyb#sS0u#82! zAtc_&Q^+8184>w_r0(-$b2{`7r>{-V-p7a=cDoQs(;y`mA`E!iR4x}Cb}K@@#(|7aZCFQj`E@G!#i~(ZEN9~*qxI4QA z6q??+0-!LY8xEv#o0&yKb*mB_k=1AVS-gUKTFM;vG1v)t*@N)A->s#2@s%7{SUu`F z_R2|!H!gl2BZ8NzSbhDD;ZnX>3aZ<^j}63Oi`A&^+au9&7X*6wc9{*yrKQ=)U0jXw zC?oJIgum=^^VAa$|AmbU>VC4eMNT8y!!1!#t4U=TF8?!(h_CW9Be)^CY{AuIWo3Qd zzXIstdTRE5VAi|J!?^?|yJgdkrOHww!|7^1%vJfaow*P3xWALtl+J%voIa1NK-Q*n zmwSlextHPm0pypB({UhXZD)7I;djOH9J=x1BY$RnairFjK42)M^y&J^r?k}2$SCN& zY5`*u1-9Q_8k(-&1*?64)&W!zsIUJq7Be=UO?7W;Q!eKHp3dGQAme4aH`KsDfEL#i z{C5bMFcR$BrO>ru=dWXgtfIn1h>C{{r`>E1X@m^$;MU3(-xqFx=>paAT<+~3!GGM) z_d}xxNmnp?|D7Ihd3El4;i85jhl;R^zdk376dWRfJSLqudDAc7duQ4=VHq~3|HybB zDd!m4*;PIDto{dg4JdQxjf!VF`CMk-UHL4H=?;b<;Q&yPb06ToUM)|jZ2()hTBw{l zyIauQb@?x=U_g8QKE)`ili|1e&64(|rR)y5>!lPyvtxVIFP|aU+Y++_){N^sgPN}# zMft@&l4z?R)oeqf@1biABWh5|k}dhKF_KK94xq@AHVRz(NZK^3>(i(s?TP=G?av3Y zafwYyhz?&NW^nzm6r};-Mib=Vr>UV=Q#&~Jd3jl4FLGpm+s%ak81n3%A)Oj3?&;2U zaFA41;q9dVT!J}^)#Jy>7&*@CjsTBsV@xyH8a`d?zL%|*>{v^GpObmxLS} z&jJoR-YS|pb-^CT%Z(p3%qH%f|Ex4l|E62<`_sjaaXekCoDpM#)Sl+?q{DIEO-2ck zv_sO6A>uN52kVpy;ZnBK_c_YKGsC*>Cl|rvUi@{L7Th`OjU%c}XB;o;_;kFGN1S_#=kK9q#${e!mF$j1bPki6{Sa#`H8Xz?id>3c!b|HHn z#NImj%vT!rh=!T3lDUo^U)_zr{WfkvYcACB7goJB z!8K`FvM(1_V)Pm)mm!mGR_YBVJRFisjX^&;eO&mZeVmndgH*nG-;l&95MrV=uPjpu zhgU&cMKBJ|v)-alQA3I8r0Qv-U&>z=5UyR+TqmDU$x$#)KF+iQMTA>xEhRoK&Bd~p2v64muQ z9Gdov>e^a7?hcQbDE{szM@N5&a?v7xLyy)gNDpdLBZc1aJ#z3@1npuo2#uK#6`-L& z$pG*e9%^VNw@bv+SyxVs&#}>ea%mj4t0W*NU_%6;t^otQ`2g5-^=|b=4Y5pSF6|Kz zdDCs&+H4F0_W%ZdNAK$;n;f5>)^>DEymz&|_i&uQYj55MeZ&T=w2MniTLTQfOc3w0 zJ|Nuh+BPQqycgP*R&lFqYI>0L?t4wiTD~H}1qqRneIrFNYO1sXY898?EAJpKpl@Xu z0V!m^MCBs+i%`G&(Ds`Oy8+xjfZ=Woix3kM0%(m5dHt*MOD|4mYz~l{+pVzkq4B%G z@$2c?3clKxzj_B+yr7^akN>51ybSYInEa9OV8qT9(8n3)cXeNHVI1aEs}(auL0rrA`%p4&~fmua{m0bJ4*A$z5_S5V2-M6oSvQqAzA9S+eCg@>l?za9~Qx#CvtiRT{CZ1XOSJ`F%?oi6`q(>m%Se`*evIt zaLrCw%&D=?dT6jhF&PnGN(MeR5VJPtjQq$pta9|gfghOHJ?u3lz1vab&}n^y^45|Vt9P+K)!Wte?~u># zNz}TC(q;kjqs_lu==@Kb{>A*TS6&8}hI;e_XCdomFKnw2rAVD<*u-~La~5bAs%9@Y zmo#)*?G|b^6{-PPXh)Zn=z`z?Ki85D!+^B%9OaZ{AI+|B)i^5->8Y^|AiUHRqEC~2 z$^?OTbT$HdwUEVe|2)^JT1`F=woFj%-nST>+&8)&Yw3VfU9E#erTNhyN>O%Na~Kps z+E-G1c$JqgsxeG{O2hS@6Vu|ohQjNmQMMJ z{-%~odOwES?i{Mdje{?C)IZ9S9(2AgcpNI+W^Sg!!2}xFb{Q8f^8XSrT|IV| z=*EmJpxY}o)$d*ZWxAhZWBP9}zFCHRZ?wd%%!!gXX*aeGp^<2QU=j3^>?BAOqqY7Ic2t^~6)D-6EVE zo}x-?HtQm13+#dy8@3sg(R-eI{`Yo{`Apn(Z+9;NdP6LnL16bve;@_aByMZinElpD zfFA;?IwO8Ge#r&z*`ovwm4u2)lsMT@t0_=TfYRsAJE-Y}1RF!&>V70q&-V`X(D?85 ztN#_JU%0BSuVw?YumOp`*x!qV?>+xSCR>YxYsuGq%Uw zBkk*1`fjd#&j&-gL1Q7*B^VD$P?U`id)+y*?@X6#9n3k~>?BOiMs*r(2Z_?>o{+!v zy+3Q297H@%1tO4zI4pY{H4F*{oPwDz%fAF+6vzh=*Upn29a5Zuw7juv+Jw?;LzDNF zI4%ilnXd@$qGPP)A;d@nXYl9nU9cTc^S96B=rr$mWu)@$%&&u;!{os1jVZGXkJtpG z+l;CN_T5bx+>&8D{a+{3uoRYO?O0CWZ!U*gx6xZ?C2B=IxvcOy<00fULmOl3BS~DA z?JsvDV6#M-QN}hob-q;Z`!>!|4Vlon_#|5=j!3;B@Np@4l9`f zq0W8;UPEidsKH4Nv?NTo_B$*edC@j^sHIP(MNMH z2Yc%|pkghGhBl>ZIhc+R{6#V$qg&Ay;<$jAZGF|Fmsx(4-{0O)TVLk!Vk{_y@2rEM zAb4T21ne!Z=Ch22Z(28|X=;?v{NT8K>&zt34J)9NJ;WiVIE% z!dH1RA^P;UL`U@c(EWg$4qI9Eut z=K;PV9Mdah-1FFLY!W}eGFiR8F8zdl|Kg>KF%ps0UBe}5_p&zJk0p_Oqc||eN3cPG zPi)Y@iDQFW@R=&(Vv)RRZ2DFj#>nRTpHoVsB#jjuR%S5MdYP7~Zf+lnB66U}pG%Pl zT+u&1ZzI%~T2pN){wMUd9Kgq0Q3cR{Of(!1rzuKHxAi&?b7};#m~ub>h4|!AwWNMC zy^W>e!#N_6zpct8)}bixBp@cXe73gOb*QV9%ga=l;Qn*Cmn+fg?A)P?v*UNS5^2SiD}Jx zp=B`ProovyPIu19oLXKxqur5=utmeIm>Dsp8)>5{^%QTMV@?3-{bVGMfp*IrHwmS- zXv|4w;y|g;h~Po!g#*zZIc9u}DWp5gdj1;cu#7%P3&lLPE_sv+f(_Z+LP)RejBh&S zQRLj3J(RV(h9*$Y1=IvRA>yid<;k4|GyV&DcIyCR5T8ft^yCw%fPCOApWK5-|*H{;VhAh*HDyqmW28`52oE%5+yZ zCM5^t;1taw42;pIfkO$Wpf;77e3b8P>cEQGpkO4(H4@^BYX%5DkO6!Ty#RJIV6wk~ zK`%6Wn%`l05^2Y(Ke+5BFrXwaSq~PUr9~A1N1FX9ZHI5p=r?!?qX^QXgtgOcizg?Y zBpS6!5>jhhTgTVu2e{&}+8rHdhwp$U@E&Q57LWe-1Oyo!CTkiR<|t5|FY12*R|FUZ zAS1swmA|*C{M!m8emC~{nYOXPJ+-u4UbnP>!Sya^pqQ^hcKvTqaB3h$w}2p4=6I3^ z;jUj-VfDT(WL9@E_|6z@W%P6WQgA|Y00W75>#QBA+DZ*w+>LwO#TlNMx zUha@$qd((bh^n0S4-}KRF`@J>MOR5*p>Jm|RJ08#Gd{EvHS=czi|zP9kp_z$$XIKL z=D%q8JV#L4iKl$#8usxG-#fTX!`Ujp5aEyWK93Gw{*_>`RF}44DxF&jh26di!oLqc zN2G2VJS&FHqx{X2v>CYgYtv0y$*We$VHRIR)0fu^qIuUjA+6&RMkgsw1}iMuXiTd6 z5i2yY|3qTcns}WSMkP3u8(_nm=B9c59gmK`qcQ*S0S*C^OFF0QPG?{f6P2`YKKRup znW8$y+jr+>us=NQjs!%ALc?V;#u1Jw#NJf0(l5};#ZUPl2(vZoL85pe>&Ari!z}EC zP79?xLofL#>~=Li3Yw~hT1+iI+K>PlqBAjIPMf|75-TU?H=F~WCXVr^Fiq`mU-8(h zA7s*uJSApbJ5728Isg26}xYq+pR2P5#n`FHX^=v3T^Xy zigQF@{a&9?O3gsT&rPX?WK21t@YE>_=K7kLAu5KruR<+Lh}$XHtvAXmKzUd-wzFMx zF+&%lC&RqGjYU8GkMjl$_r~f1;cMf*XWVWX&sVy~-FY(9s7?hY>6o|x7d-sv|>93Z?vpWEWf3V<6s zFKN2sN4x_M5!AZ|E2QBk4f@%wPV>HYBSa1awpNym#sfyhc4nW7ih7-k%in<+4j>yW z2l$>qdJaIXfb#&PmH}779Z0PWv;xzv0PYVYa^KxnAeyq(3k!H5kpp=&x%Aod=y$<} z-zRQw*?D+)GP#_70z+hO_q@oMe%sWjR|Bj$KZgIPXQR@*?SDE5@*){*S9`r=ZK3@6 zzOC4vqMp65rzp1$KB?L4>=emsEH^{7T%5g|_aW+^{+cBX<5+6q zUt{oCS&zr{<&b0v1}A*Hq|`(?&}@R;ahN_%i9R{t_DK6YZxspTeV{Qm#{xa(aV${h zC5X~srtg7W3OBg_mjxcuQ>oG|*_|IwQ4Zx}YA4Fy{lLUyl8Xrx*@+MBBHIEQ_slaq zYsS(Y^a(Hs4Kyy8WS;*_Y1Y>-x<6yMh7XB=5B8*wox47h1Wqf?%exVz!FilbW~;+8~Sd z*zxmFF)+W4@Qo2ci^Bv*RHpy`vH+sfwdiw{(;ZjyRL$$RQMxR8%5UiQ^g-K#=tpyb zgb!z&nj;4Xbu=3K#FQs}vb^f1P+!-sQR;Yy%H^X`!cH{>Iha$gnB8SCPg%%=7e5Sw zRvg3qwG)tc?5`PbNDQjCRS1tz3Rb^>CQ0ed_;2{zG<*?{==SD}Vtw$BpHcr=D<^j# zyp-5NsLnASGf;fG?=1QeM%Mw~AueSYnyS%Eg;WXu?_?EwtOsRT6q+rY?ej`7?Q#Lm zL;{;|{H#G$P=mQ-vxRXn*?nYN$i^Dt&h6qxQ{B2W-t->(f*1lso3l3cm-W$#mGNy$ zF$!|Yv|NZlm~SWXs?0w1$6P>ua*yZ-s1io}Hm?RUO!}J}OjOyxpCkNewR)?4qs!e3 zk>{6m)5%U2{Z17MB^aA>rYNSYi#^_CqCFzlJXe zUF1ai*43?KEdFXA#FE1^I;vz9f-B?4S&-=#HAtV`8E1kA;8)IlP9O+II(^-6=)4S^ zXsg~s13+Mce_j(vWI!xb>WGK}u48U#X=QAy`|{6*WT3yt8R&$0=HHy0Ld6OhjMuhUWBT>WMqHk&sawmhla#xD=XH6OMqoHUF}ST3A1 z@(4mL2Nk*93in%_C&Uq+y#L0k^=pd}!78anof=VEF;S{>7!zy61eH56ss!v2vOKKZ zV!6Xrb3=?)7uUCKNJteFUoY10sifg=L~KO-DAvZ9{<1|AEn?&?5gX(#=w^bvk+2|d zC))rgEW@1#X#WBaC{3PGOX;8b+CP)fN0C+j%=?TY!cF{qomQp*?Q2ex=;IGo2(l0U z;@`^2S+=Wf#YiPv+PZK>*YJ`#{!3JxqKb_*|ErgPwAM=IycP!6HeC3zsvehPImJ|_4MnSV~!r!0Pis^9jma63-wxj zdF2Hd-(>tlfU3}y_ICq zYwuDH+v+^9;3@TmRO?hkPH)oU#bqU$YHGYLyv*q}`k2}hErZ=!hgf0{&;L8wxJWow z1sbP*=9xmnk1q^n185o;B^%@jLRohA0_ycGaEJ7m}yjjas>jpi%Ny8BpvJ?wvUk#gKSB z5q3%p1^;SKJB!6IVs+*Sb@C}#7iY;4^p)vk~tlOv+MxmCBLDozaCghS?SKt9({sSg7>?dgycz2#XDs|h0H6}C? zSv)%k`+;Mc%kh^`*8(blNH16;f!X(`tzdd0-+Kdq3( zGObN^x+7zZaVTZ8w5Hpoh-4eATJ%!rVR{j5fzQjU;KAOI=HZ$zRa?S#B`cj4#Amsj z2!8+t&C`YolU$WZB&n)%D-iuML@0b_*JmTY!cT*GjFQY7^rC>540*~%upl!|V_RF| z$1`56LgFWvHYT;9(b4(HZ+*+F73);I0`nP;;h0SHbKz(;DeeVGvrKVIu};uAOotcA zIRINCyF+z-zoW`4r_dDJ_P3x5nY%Rcqbi}g**3fI5=bky0CLcVhHr)O@VhC00AFU) z<=S_O?5>j8vsU)BKopwVHA@R*mY~{zFp^InvQJ8>X-u>zk5yJ41tb{eD8iRmuNXXa=jNV29UsIMl3#6DPnpH(0Qd9Ug zw)UhxQbp64QY?`kx>>y0jFwr;D*pE@S`39LuxLEb$`Qgt3LAgAMa_ZZ9N-HCM$c4VeYozbIh2H!sD9IIW9AA)- z2{$8COWn64%Y~wcU02u<&P6$&w82k>G1Z>%1HJnX9?xCa$>Yw%<%t&GJpm=t7*fh1 z=I%u73g&7qYBtM4Tm8XLe%|j?vkw8EY;@HymD3WnR}pN_I{#?lnPhvxZ)=w zZ=lhnmKKvHyh!gk!R~F6k@ADN+!nIxXJz<8hS>(QKWH?Ixe{mwLODalzf-*^f?*YZ z39@&~1$^W2kzgysi)9kQoe_~oDJk^Qr(3Eo%)Lc`^dAwFoiyB{=(S-mtN9uLRSSDf zr3k?yU>z<@i=WVDZFqU(=)sU*aO%72?~Fw&PbUfdr;Igk34`nRwK?miZB9#PDIW>5B9mbzR9A7z;Zc(6F59?DDl_|ah?8A`^7*H zSK|Lf9$C`Q5h?9y|GZjk>*do6NJPuj7==TaX}9bKwgH#CoM@s#B$ zF*C@(K=3mk_2c!|WA@Mng|IB9FC4-rrm3;UKSMNMC>mrG|HD+=pS=R(gA$DmP*m6u z`5j`8K0qS=?2a1!@uQ=fbp{z5^~jGCT!s2yay%=xfff5ncDqv*{bT_oTM~wvh>A__ z9AyI&t`Z?!5dq<;PQf(7@>$$&s5%xhSIglH*n>R@jzO9VDQd46M*IW$bOu$w+!D*LIvrIgj)dEN~d1QSY7%L6(SpQ4b*+rEle^8RgrIZbD}7U&%G z`^y_}$z>p-GjWoX(ww3Frs|@fUEmw%Z{)C}o8X6%Ph-Hs9uLwOd(={kF%_FZ(`w{XY6;sbT^#J;liIb~z#kmm4(Gm3r1W}=9a5e;Pu>>TF6Q_P9%6qTkVbBNb9 zXCaDXp8fQ4cvKJXdj&EwjZ6vV1mmNSJCp*jO(4PiB@1lb<4& zi5f-}m5y4Gi4NSRo5+5sQQe%VCPGe|A@~BXG_h-#sKZSWa#@a1?+{A$iszq;@^kd| z)`F^Gl#pTXs^=n_6=*a@&rM3NH5wpco5hr{cT>8{&!dtr&) z0wxU){Hn}B3u2OTbo^y-$ndqq*8;~P*hxR(-dpVuCd%~ojyr6nCV>epO3R4RiEt5W z55?_JOUY=8?!Z?#MLqUc&t+n+tfU!&Zl5w&@f7MJAGZ73+nMaiGzZcOI<9$`Kxg0b zQ9$sPR9OSz@4s^nj>Kb<-u3z)`D~tq&P-gc>gtUJSU?P*? z!j7PEJP_H#m5|I8D*79(WnX;nMQaZdOk)lA#BB6}D^VoHb*KA4giYf#?n!$!j~Qmh zS^BLZ62ZN+T(qC-BGV%)U!qHP>urWW`vu}H`RNATjG6n!?qR~0Ak`>OGb0WyNm+^A zG#BMCDcAs!Q=RUf-~u-ZNjEra*i05JYi)J!?|c$0m%5!J*}|v_XJOd-<}ob5;dlq_ z?mrqFa4+9ap2v?cU@(v4_UALc#kV8=92EFCdO?0r>;D`ycbq_B8F4^1E`ovcNg2zXs=q;|sj|63uq)Gnf($0X zz2;`Lnq({S*69+6EOwi@z&(Y9x@dlBMmY%BGdyulm);2Tqsg8qOaYt~+#PKD&HfGC zv&nTb81Nsyx&Z#CTaAsnwjFBt_gL6v`#r`}s7~AOo z4mlZoLuYLI$?eria~w#99W}vBWg9k|vnHg477rq;jkwGybWtQ74XhZo9KFYIwsJ1T z`=J%`1i*l)f4ma>&0=oh(%fXXl<^nAS&-s6)*HLu0$QGxg!X08VP_f5o}!w%`mO)* zr3lj-qq1<$#YSa5#$-|k6fkG)h@*AXa=`h7Bs43M_{mfxZ^E;sJxsv`Y~V4TFFKEgA5JkVT=4H5#7yHb=hJfD;CwnN*>P1Tf0(&6#;L zNXuWdg@2tR>NzEx+9RP{KM*^v58|0|7q2qalVPb;UF^SwOsLLoM9HS{Ivdn%#h9zoZzA*4rRrRG9Blc&IcHRFxq__O(n@N8-ZA<@P3O)I9|W0sfg`@BA9r$6CK6p#KssS{LZn|VHbBDSNk@k z{;8~JuyFZtcC~i|%QCM)!n_A0q3S8C`J5m8xxM$pB9732dAzd>OEl&^~ux8cw~oH_i_$M5G^09<{Mw~oKRhG8ZE z66<$hI;{VWR6T?retozEiwWj$ts!*Y0vHgY7kU^@jh@~4 z_bd4``M~QtAc@gTmw|`j4XMbA7fZ5Srjlz;CGUaZC0Juu`bYzsI+9|o;;&M!iB>dL zReZ8GC;gTz1WCdLgnZItsCOKoYlP(2!@Q_j-~b9}Ut=(KiXlsl3pGIPq1$m`njF5B z1gzZusEo9DzBlQ1cOs>f8(-Z;xShC(wDMRPuTMZ2?gyblId0!%Er?lcKKWok>_1!M zQL|a!OKhZ?==h$oq%OC*95qrSe-$O{066~iM6uC~HN|xI+wtK$sk68I*fPGCzMI6w zf6>(&Y{P9O(w<68`L#haXQiEi$~iX`1IuW-{8!_|hWvE{dvx@0<~^)FEFveuT8WgM z`hw5p^Y&u-o~MO$2gH}6k8jj-v7xx&7gMtPd<}^b%=_gBM1u`kC|E+q8vm#~36tW! zjIgyQcFs6{I+i>;k>#PDqCdE#Oc(LOc+^NTJR1)2;_YLOtvgkeN&Z>n$<{jnRKG+q zWi#%ivWt_2z@FCtmv~gx8*oA#?gbO86ki7ILa5y?Z;9rhk6z)ZG`8Iy>5`6+L4{? zudrC4CjW;7Q(8iLco!=SJJ!q5Jy#r^LoI3{VUbZL-l(gX9?zAiqO4o=Eu8_DbmeZ{ zaLIm@4`-#q8ka5a0b!WB11HQ*t9DU}j#Hh*YwX)TvsI0H(VrOsRFS+#LHTP)rgDn4 zpu^O-et+yyJw!j!q5*TwRl!?HBWI}q^M;pcUc2V>9*GXI`ZsybFW78xn?r@+5m+1c zw6X4&SIP>q1Bhg0t(D^M(z=RkI%s;RfA?P; z&n7>v(c89xlT38&t z@V;&?$c!_f^u8khYOqy-W-2IK{e5mt>O{Idvp|2N0(Ff1*L>*!fA1S^92BW9N%itS zu&$dqt-msyG+0+^2_mtt4ZL03BJah~G^>}}ycqOQNYIZ{OC&;#TScEmec=}uRC|f~ z8ce!>f#6tHu7pw;ZTXD%sr@vCB;PZo#EAl}qJgndng)bB#lTfmR&WH+PLnJj^ZJMU zVCn+mh&dV~BVlpI*zOH-h>&PNYZ*4i;0A|BG^5N5w_DKh2z&Ef#IR>vtx=wM=w&Im=}-%ug3>jO}7)F zgND{Jb{46?M2En{%+IjItlb{-LG)Y=1y=Pp;o0uK0J7S;@$^^We;Mz%Bk=gadYu1= z&8g}wYIea;y4^pq!b6&dFJEGQjB#HjR-(vYOtU3Kkw(zGv3kBy!=!(nyb!o?zzhOQz>tH-x{Gnt6xf*Rinkh?P>*+mFsPG{3jz zolkElqUswa8yq7|h+j}01PqLb^W_cvcKle>HfV33eTl$zm&y@WePQ;EDGI8FW+4<* zP`%;Bl@oCK7~K3k02n^K`=d!P*iNSBk##8s{&BL}F)?++^^Y^UiW;MY<_N-z1cnV8 z$20sT!$ZJTEEWyjNaVIulS7w_C>#Je@kfEvgVg#b`e_cZ2&Qq^T^-S`)NB)75Khd* zB?rXT=%1d%axG?Q_0~SW%sRZI9S3}#K$9CY>K+xaK9}xzM#5;dAXe7w?R<_E`cydp zO)WDGeSI_KqyoFM9^en)1)~Uq&O@6Q+YkiqFvjr#v;Vpg72dVMEJi)tM#Zp68kV#C zy(adG;3w|@Apj4iJ2wRcd)4{Bjf={!?^>h5!$Ww2z$@N03Et3vt!zE+X_0JOvy2EP zxE3pmS{mgW>~Va@@2?4qcK z;`Qsv#WD$xOnAd%7aQ`a5>j92ieFiq6j^#std-R=QSNWVT&PuC@7p|QsH2!fc&5DerLyt0H2zo#&>3OTe6jFLM{jYDj1q>yM*;Wt_Em2N3|QUP?hVO zkKIy(UXeQ(8UC}fP&<4T(s2{V3D@;oMJeB_i;b;DB`$Q=hPvcS(i7Y6FEk-?-A7h* z?*ns5_vfG%z}7V$B9BCIi6{5AH+V+lAF(D+d?Mb2hyD(8HAPmSBjsW$SxIH96gFq>Sm{ zAgN7&(50SiX~!0rX-_c8utTGCVp>CT5T|OG z*lutV7~p}ha;t5Jf(n;7l@wl^CQojTfJX*(m=B*)#{y`rr5sOt3K_zr;{CJlJDw=&mOvX$^5O@wSkv0}nwO^!C0Ki+UK2xP;;)L2EoHu(LWj+F zO=nZ-p4{#~@y&@=vRC0P7J|A^p*6nUHY0f}bPLT+iOt#px-D>UnB=$PBVr}E|FS1g z`Hd+lg3S1EaM(o|Fs{{#sqFjavgodl^8(~UA}*C)#Oml?gj>%_CDjo;SF93SD_u@E z+^vsX;q$uf^sC>a;iFT1FA%rQHqxtMpwJ<~l8-YHK@QIj*9h2g@OIXGM#LANO~#!b9?o z29Pw}7F-s-R7rocQxoalqb9CfnLI&NiQ*V*Dk=-QYbS`s4Nh&rXYq@uyqDT zvdlgQujK4vt+b7Bo&$^?y$yqyjN^bMfXLBs{5JPfE?#e_?nAz+WuQ?lrj2(K|fklT2i>N+C34R+a5d=1YFlH=?L86vys^iR5N10XzTmKKNIWg~Iui zPA}-v-U2Fkf5pRWY)HwIYbFCzDLQbp1~Uo)aK}nKKi|JJhrN8Q`~4NV6%Vp>tSo*k zs~j>{XJqMe*uRwYQzZS{7eMC0;)&h2%#_IS^_S-}%cuy;9T}n(M2{bq*ew}NC^9rq zG+c7dd;*$-Sp3%5y-arB|HuzqHz^QxPHQMEFUXvy7?p&R{wh7+5%I+$aI%n33=d5y zU+h-=nXU;)hvu{N4UCo9orao3WzaN?Z9%mL%kP+@dZZ=jb2~!E?Lb!bp7EXo{&^+7 z+Br9S5Ui{lSIH1+8DhLv7vsMQ|1S$*&xUHpEJ4y5OhLWTq>on|N*gnYMo@`WJe>HT zefIclU}Ru}Mc{w0)oX+2hBgJ%bm{sN%0*xz8P6v$x^7+MG0lR(!o}Iqb=z^Ja9IxL zNsU1#1bIr03B=@#s67jFq9q--{Q)Ic^oNG4#B?7V)!HA-5flv>fb0t%QX=dhCz?Ybg9TxN-%0=c$vMAUnj<+6Tkq z>wWhV%)j5@8Ve70Q9@%|uYT}Nr@+FVWM#iz1GX+(uy6J2uiDozp}2Y-QdSNe&8kew zQ6+b8GTfE)9M7IU*917NZELS?K42~*L{l$<#1JZ0aIkna?MupEz1J<7h+PGnnJt08 z`aWNFl)p+_?yNvGUVHgrR1?|yeA3_vE$x@X3Hs_5iH}Z*=uJM^&4qh?{?I{2z&-?R zdA*hj`KLJNi@E(!}FLP z_+|f=jK(!bpMxv*1)A} zGB~!a++yY3Vrp?1f9qCm3;xz7;#nxCe@FCj#; zcWJ3Hq_xcEidntuL}`!M8XtputaDMiS#4J}>yoY&DC%;^O>ON6<_lnDmhGX7jn48Va4LIRL5cz=6>z8Ij5zK!7wn`Ld4b`R!$D~pYp(I~7>8;M9+u0}4qGXK zkD^vmdPxY8?EFQ-t7l+b8o9!ZHPuuQdpQ1qC_j7CJcwjVU>SjtBs_Md24)5s|JTNa z>H`om<===Q_6u?6RQ?reC+m7}Z3R^C)C=rQxBWkr7dmDc`yxA-H|2CSfv&rcqyf%N zY*AYrD=HZQjV3(e-_-@Ql4t^ysi{O$E2bmod@N6p(<%cWE5|Mn!JP!`NkY)zirq~| zgX8e+LFV{)%5&e%ERvX=H+tnCb>V(UJv`gsgcuQ{;g$OI!URaHNPDUloqduzHcR9P ze6~Gh{{f$mY6lbiBZ7wSZ!6|BRo|H<_R*d$MDaC4^u;23u`luhS*GjxcdOC5@-rGM zo_4)h`fg~34TwB`__p4StHwt@v9D(k{H?Syo${Sdr4AhwO7JItz7P_2IhJ8ht`Uk56mb4J1SjSsaum|TbB2Lp%GaKu76f+$7x@rpLwWb>vEoT6Yr zD~TpPcn}9C{!HsH>N+~Y>eqyO2@tLoQu0Qpp)KWmv#fM2zr|4o%cQIwHE=i(_cY`G zZud>p*N)b&WkRRgvn?R7{6(sTj?zV&t>)W4Ai!SrK;=wj^5J@9=J5CynNW5bC0-RV zjGwJkkMm~ThZd{L+|;tfrBMqdO{7B?&Um&w#{fS{PNb@ zze|h9Bu%yg))G-;hIJLa^%C+}84G>ZflgeHC-iVR(=k%202kK8vY|$b5f;iTW7Aqz z_XDvv=y9;hFlnv>txg5#jy5sN^o-IggE;WiAJJwp!Q5L|qF^s@b>K~jzh0;1*Qj-- z8qM_<-Rbk2t#8L)^H)OyxV0!}VAU9Uhg z3hmnHzCtsqBU|Bd`Q`ZYrwdP1voqotB@GXCSthKcXG?5{K-QWq;WFZBK2#Anv67AL)@sV%ycUxCUjqyyxg~3)zM%iTbc)C! zkP;>o*~JKvm17`Xg*4~thmwmZPP5ROaqOdho89SvQxh0cygK!M1p3^@)e1aPk^AnE zd>#zj$V)#Z$G$;5k|J5tpHo+7)#8TcbV{xoxc`$j1ob@=b$&0}DSq9-5- z3e`%nufC~Q6&^?3*%P&P33!6(UOjWc*AP5y5=)h13L^C$$vw#O#f^{KlONG`lIh2{|BNh5pBU5lS6 zY=(XT#n_oq?S0s9ax+Rd$HUOZhKB7hhjG)+5z`;tdXq1D{6M@zEa>)eOQ8prou?7} zRrBCKcWrzxV%%*50He~Y$=nYd-9+4vQcJ(oB~|+J7H7YQadhXy(^Nhf`?^r$F{V^T z2Hq=3>Fl9uFUA^7Tv`Pd8aM_HAsh!j?3o@7)h;hJIy=_rU{n<>^sq2mPozZgXPzap z*$aQvt*~)tEt9Q(K}Irb!{*c1oxOMHca>`b9r{+aJFCpUIckFkOeZ5qm*q+s)r+Gq3_KBoe|^7Iqv{ z3y~r`i9(eo+lZ=;#v+n{_8_?vtA#Xom8i_hPs2T-qb6|?3}reh19mUgI}0(q;7a|v z4czsLcROeV=4H7mq;u0r_&&Ki&{gv=VIrJ2=$x|a*ihsvfaqJPu6U5ZHhpVkPf+K| zWA<$ZQh%F}5PkLwdCbu5XsUeAmMXO&;_~lnvQPDdH;z1@E{As3Y&8Es7--N_$yNV+ z$3Hvp+^;;djO`UNmCQU=2sobVKD{utKYG6>sQK*mCiS0s6-y{LcDL%?zc?8LQ%D=T z3(^tKZrlUY1zt38_kwIIEWw7Fc$Vy$ap>dRUz5J|81B^fO(lwipdWE1PgsJu-(5S1T zSP(0_lD{I!#|b}`@Liy=W9o>Shurht-B!O=F)<5jb?PqHe&z3L1QyhyV~Ppcc;zYW4p#;X~}Kq8Au# zVkHO%&6BO3rI{heBTB+v45^-t$XjoD z8p{m?i3cR1SJQ<+)4di)b+(2nQY=CbW7ZQuaVINpZ9%_Y{P;$6OhSO+WmI{HcBs2h zWt%d1LnYW3w^8Vbv>1x(+U>q)4tDWu<;8+D{kk9}5-u6QSBL+wU(y%J@GM{r-ePNJ zF^gbvETEEZMqFAeyV)Js&bF0EM%V=oBm1Yecvrd!rEh$Tz1F3V5yKYIufV35Y_0Y; ziOp!H>oRX%Q&_T;_6;>bHCu)J^ZP+SD|n}71#&sI;9sIaqna8I0$?4k;?U7ye7Hrc znlZ)Nd{+G!DOOzB5Dpi?%?PzPrr)zGiAGQ&fua=LoqJz&nIn3vGrj3Xekgbu_~{-> z0eO`yJuSm8r z`iq`t{O4Q0)S5>QjFw5?;c-hFy=U64V>B|n?prmd@N}DhpW~LJEBl_Sd(1KVEc@0g z%gSg@t>MP;jxR{~(BJ=%JQ2G0X{h$9lTCpUo_^dHa&y$(FS^vQ`}?p8%bBiatoh}) zR|_r1mJRZ)j$3IX)T~5W$>&FfJ5a4lf5aqOoivsY`kw4By zXj>fgOo-E9(N^bc$(hI?3J~Vmo$L3stHHC{rQ-%+;vGarqP{9%! zm+Y807QR9J*xS(Lh48y}AqRQ%+;CN}-xAvCAGx+n7z(@t{K43{{jvYjq*P|8$zLcY zog;+(uYY%ubZ&krZL1f{j(wqP_EKVLxmf;HG0LwPl;AOxUG<%)ng%Xp|D`DRJDsg1 zVpQcEkSqabfvLZfbekoI{+Qaf#wW}F?r*Qr7;{u0vSK$;mv3Mpl;2HbZr{&-a{v2p zn^4Xud#H!IWc2Jlmtv3CtJ|6KfZ@v!$_tpPIV~?1qyJt*0NE@Nf?j^Z&{k+%*nBB0 zoHu|W%Kr73xjq2(r2ika^S`zg!hP(ma#VvGiU+bX{%NLBgLG~K-AD~N7E$;TP3TV) z5i+Byi#Qx$)kZ)TF<#E~I0`4(%Uz+4@?hW+Yq)cP!q4Qcn@#1{ChC*HOT%?bpQ zTi9;RD<-Y))_4}sW$L7{-808aWa(TOc68TkW*SsplA(MJur^l{HgQ5lNFP24(1dNY z3}8eDIfo{|NI~OAYjcS0qo>8d>~=62HKIQKG;#VFT4(#mquu_rdyRUJ)Y^c;Uhg%o zyT=!$6Tnb?HI2C&m6y~q%Bok^U1mMmhy_Wm5TNb6Y!Gg7HFk+bth~oynkj_0=Iolv zBiEmk;)(Rd>`2gMVbdd7_dfes^p(Xrozd(kjR5>t=f7ZW`vv$bY-oFE4m9})Ysidz zq5e9&{+{mi)3S=_8@KAA^7)n2v?An%K_}ArzVHy~fvD|1CFo&0{GP*%HOL9*M_#W- z6R0@++#idQ{Y>}%7`Y=uKyt;nI$Vcu=Uyu{5b@{d4!WH`T<9-m&*&Y@ z4J0g9q>!j&v(*kl-(yE*`iNJ0ei1B$vEn@#e8ZT7Kdh;gV z9!aFF;T73$msGG^$z*9SiX_ZM@ewS%hQ_pr7{St|Lxbetoi(dQ5Uj13zGv5pMus3j zR$T{uiCZ zy1yLSj%S2iZ9$+>d}8#0SU8CRcR_zsv+@H3&ehw>oe7{R+UaP3%}*5#jI&| z;YKBg%bFI?Sc{z36t&-Eq7aossD1DV^|7TvVa{)QhxV6vtDtg3rSOYa#qYE4#laMwj3)&P@Yzwso`rgamIg%IX=t zj#xCAR}qGXJVVxTYne=v?m804K5Nbs$^&BA_ej`Wf^p==`75g$hSYQ96`gMvPz4aF!Rd3RzoWkD z7qI-|AzV17ftxKNfne6saDs;qZ=V^`B#FC`@91|iBS3*wbq2vHePP}AV%v8o$$BB! z9~4sck`IJdU-;4XJ=V@-ykJN2{gL9^FDLdY7IW*kVz&^K)}^ol_#>jaFymmZoFc`E zq^x8dFIagF6i=9YW)w902Ax`iL;h5giubQdyL=2U{hITv^?ON_JNpqIQfuE>h%aE# z+hh=}au@gnXqQFIA&2nsE_0PszM11v%b_iGQCz}ha8y3 z0rvPW@BIH7**5(AH6WNza(8Q+o08CgUb;?a(R)aZfD<)<0LDtj0h)6O9m69dj-;2Y zf18EoI-xp^C3XscIl~MjRgD}Nq z396VALUZXFCn6`nno227(p{M>G5!8{jX};X{hm0gVXp0@TCt`aJUAM^lA`?#q&zZ!RoXrgWKogO+YA< zEnauPN%dHi;eNpUMRmC?7B?S&$7s`#XOFMJrLK?&jkHz}-L>n`kDw5sX5g)@J7zeq2EUJl zB*)I|YSg&fiR^70LWgJJ!R=aMDZVMzHxTtU?^6e6?QEr}5dh{#aQWJe>5xAp7bxSQ zgLvna6%RUh&k_p@l(_KD$DS4)I{EuO!AmH_tTNSpO95GHIj?=bZRQ1L-avQEIA*}7 zY$k*wS1)?Tvh#WnU+Xd{`Y_5-869_E_la{C8f@+xL|vVRWx_Ebg5EE&&BtW|(U%T6NSeAT!`U|D7h#O%Q?mmlIa@vgjSi)pUe^g3ymcjfX# zp0eV2Ayy>nG3Jkfr-w=9;RA>T82P|>V`wa9A;A6Q$+dy5%_0)IxY`OpHEpGCQS=Ay z3c2XDGL?oB_A=}-6BAe|h$<*e+Ym(YD6eLFf`Z=l$#fA4s_RKb4K6fNI(o6X70^J^?`nC~ZzQ=z{(DpXWS$!(@-PSw~A-Hhm$#fe(hgA_}tT zPwD8NC_BJY^O|-j9<0ri&V1vWq^aJ1|F`_v8*SgnYvS4lC;Kstc~g`sGv9~FC>A+} z8sXUEa9mlx&%@F>66XX(mxaE{3N^Il@+S|W7nsw(v$uzqxku0MwN6@nJ5LehhaNq5 zUsVk(f6Th5uui(I$kW-5_`Uv`^$GQVSQ0)Ck5bJ2c|W8F-fPW!?s9AYM+9y{WTPM=I=Xj&K=r6&B?U)hPz8qDrIl z@~>M;>xa_HS0FV|KxTL!(m-<;kDA>PSvDp`f5>e1tB2sU<8tOpw{x|3l6C>VF5$?oAJD5;b z3gF1qFyF;6*1OFv{xaz9mS1{3iroDUVG8;7e~>=qF?|JDuE9!Z*@(f!LIWjo z8n$S+@M`SL`lL={IoQyIa7Y>Dm-%5a-BVrsK-y{k0Q)zei{bNF2STR5_NhT?r*%F* z6GNQowT1Cx&6}I-2oK@EK{)tqKdjk+mmyi_R_E*gB!v=|>+`L}sM$}GRU{UxjF{a5 z)Rbj;*P>Y#VBBQ>C{|z<;cYRc5k*z^r?JrJM2N^G>Tr^ZB%tNFkc{zyi8n~8O5O#$ z=dMSq-dQfH=m9Rl*s=QYkn@pO*t}lwq)-L*k$#I{^uIU0SU%B_OHd}ijBve(8}eT^wEe!7b>PW zE?0l{nsOuU*?YmyW5w>2p%(0B5jaf~X97bGgI5q%Z~;8~h!de45NM3Q470B3ou z>2|$F1+GbcO@VT#{w%NEcPq=7}e+ zbRDvv$v;`CdfU4A?q zSv~g0%ry^p?KKdvi^@0pF~Ywwi2E_$%H}NEJ212bQv1aGatzDECNzDw$IN?+@yg5K z9;kYNt#k>gFxWP_eJMoGJyX}yIY_j^H*kCC@WKBH+P!5d7W{|>_soQ?ECWH}1H@;R zPvD$S(=XBFdu$Iu&QpQ{le3$jswbDRj;L+@$RuqxEFAr&TBm|CM_ySnFM1Wu-#Hdh zd4Z6#oC2q*7UuxT#=fY$Nn+i$j8fzIkl`-TRFqyW8r&kg)cjk_`OfMS%e=XNF`Y;t~&j1+~@*Q zN#vF89T%X5BVa2lwaEIe36w;*Af3P7AMA~Dv3#bZIpr^+aS^V%EqW1<1c>B_9STb9 z^^bHH5`lQf3AFyK@J({(ex6uyn@!ChlKBGk7Mv?QI%mE2 zfJXSMbn~IRaa}F;zbrs7ejoV1D(`>K-G(7!**>6-2uT-jG<3v~wPouqyTbVAEaqV@5{8nEgCU!w)EF z`nl`cGl=ZyQR(bBl9q&sA5g1J@kg3O0aE}DCr$uqXPLTfB{Y+g$6O03vU4j-&X=oyVH$tpkK9fUl?PZ!y zRpPpH>I&JTd}80w5BEMp$Q>#1V3JCCQKTjd|I92nfmE8F(lBF2f#5adzAW8bW8O%Z za=q%5LEm%%;Obv?V8Gta$ouy0Bi4whk!*9`59Cdf(Sgf=x4mF=lRJhBsJnZ;IGq>Q z5?%`PW&FpPM+f=Lsa{sM8a!jvd&KQc1eI|woZ$=-Zocn_#eLfg!F?|rTn$jv11J(r)C3x|1#~*Ck=QuY}b)8j^sDPw5!bvHCfZ-#yV7fgYK0LD#ge46+K!@ zgJ4h7QUdvwiD^)aTHpjP6yCt$AD55A#8b!+y>JYNgVdqJ8AbahG7~m@jFy79s(V@D zr%5XFqd5-b=j9nu)ifB(u9)tyVsEAL7)S1)$LRZAl(}N7c9BfKQ^vULHripSp)=he zv_Rv4{w%}u2IY)c13$(p@E9?%7Dt;W#p4wJXq5}b$jLKA#&M4cZf6FI&3^2&Moa z+M474)~`dYV{SnJ@hIM|YK|bLaHttrz+BjJ&u@RU$kyRnS@0rGn zCul{P{bU5@*0Z2DsQHmCkzqeNq>bIG$-v?@xCZ3j$+U!36%krv(yYn(+cM~?g{nd|(Hi1MkfUget18Z3u?5l=Z zA8isAEyZ>-s=o}bXQJ~k&X&P_;ER4uArBFLpxCTU2TdJ5Ozo%4 zJ5y(gRl%NmtXIP6x#%GO>JVXwjr`JS9Fr!nu1FKF-WAn``!C)S(QkqZJ1(+z3T`~RUubNH>P)=;MTTpJHPqwDyCRbK`Oipt^nI|b|Bn==EE9_9LdI)4 zqLL0JrEN;l|3T=;k3K+U7f!D24n}8rS-0msW?}JEVyX90`TtNELg5`X zm-eeQKO zi4uy=uGiq~n&NG$M6syVrSF;!p_pflhwQ+rZN!H#ug3mxphbK%XpnMJ*rC(ho`@!P zDnr=QCs1)>B2dPWKrpg;+Mre|6OUMb)bR)u?T$9Eg@@#i{utX&dLAVtisRDj+NT%b9X7Jv2N-Y#gZrk4$s zEVlp)ZvSw^y?dPm6|B^1v4~E5?V2&t8m7^XYXQ*yj3L6;>g=(-T;aNHMivVT!Y<7I z7VBGmfA%AClBtAlv=r39e$<7a&O*Shk_V6+>$A(-7SVxIG`o=K-D28ArznBv7auP_ z7lrsitk~(aAxX4Iss`IEgjczE{?Zp@zk(H3zM}Pmsu4X(9Il%*bT$rP;*6$NXK-zO zmBhR6*b;8!i5m&iMO|C+grov^X;Dm}3+GIlX*Srz>dkniglx(V^$qw6wU|iAXIT8e zF`E&Ts$;OO`YQ9S>!=JpuOJ>OF#s3&%dmGa|8P6h8$(wOljFRuR`U>@Oj;oh2>KNe zRjd5dkY$_LheNb0p^Q>SCF@7ux5aN*;{r`ny4b z{iY2Jmv#6}XVu~(O(RuuC#E{=_cfEMznpQ_nO^!UQz=rb7jTd%h>#(Ud~M%1zV(i6 z_I%5YnP-}CSn;+YN(TI-jUH}VnEeTTP*F=bFl=X(Elt!vTc-3~$ion`3DTb zpVT_LU+izL`X^sdnR>LzF5{oiB$ZFME6k;&W%-Bme9;@3AGLcVys-*l?n6F5;Z{Ef zeCE47u)!(rOwYsdXs}20P*b z&8P9ot3V+Tasy#T{vE0R3Hp2B3f8i4;C)JDY5h55OprMUGH-O8IEVIlj6@!J6?SBw z@jJRVsQjzabnFW;&gLH83h!Ntv9I-Y3f770oJ**f0!Mdpy}PsYc=%SA+2a+4zHc0* zrHuFM`5|_QnB<+~rqtSok(aBG58GGxxTm?F6aPJU?~#U9B4zQASPv6|#@o!ytP zC~&sq3s{;Q#O;H+!{7aA71kgN#=aw+fB~5=TGZVC- zHN}POv5l_8e={F#W_r)x)v3{Uq2UYmeYl!>DG>o zsQzhsR1fabPQsJW$rW^gS^EWC-?V`|%y9aedzT%b&+YPVNZhnU;WUggsnIEa;EAyY z@y<(@@*S}CIOy#o4BWH8*V!3*uJ4+6g}|cn$AAz-FJv5+K=O6e*U@nfQ=9F5pU`x& z_3f9CDrxCO6Wc4~(5#6=wdb@3wFeJ}K$gNKED9|~%x|L8LOQJRYUKG93IXYHucUcH zoN#Di< zyePXT1MgG)@iv(9(T+wI{o6Y=T-t}FQakL@W zLXe-+V#iMN#m&%@w8KO)TnrFINvO`CyekO%H&h}0Kd#Q{Kkm3|v~e0cjcwbuZ6^~O zjg2M~+qRuHNn_i#Z8VzT^gQQ%F5dGO%*F3wfA*gBUCWGa5W0b*Ayh5_QbVdl^}Kx^ z!V12VCnxfLYhPDSFMK>X4d#O3yuekcB^~?(fq@7OUpEwO@ea8Z{)!wg<5dszJNute zDzTIZN5*Sobdt;Hzy+ySyFybfpLBj8owgg(ekW;_U=n#4<`;ORQSC4oo2WT_612A? z@gtKY@*Nq_ht4gv_~;A2F#bX8K&cA(2EL|pc2OO#v|s%do)Q5tDlS9^`DBA(P+8Gx zt{d_|skh)^;jvXAs1&;j6T>yk5!k8aGzG+ru*F@LbV5BN?S|Q)Q;BcH>I3+#*Da_r z4(wCpnJC}V71LMh}U6k=YByZ^vCMU4Ut*!g@984pckPlGcfpICw# zO6~?DDR$82eXyf7M*#_4L*63Fw-7{C7c4z?6;LC$qI4UWSo$Wx$OimsSemiDZOA zgWwUhCkXz+V`zbBx6XVSk?zD zQI0hzW=W>aYS3dwxEl|?Hsa_PGUqqM3V8CbH+r(;{>a^jDBFW7r8kNx?+v}(7%{$3L!$hUh zPF+Il{Cg(5b?DKVzagM72l{pqijcCD!14j5J)L{B-^ck`Uv6Y-ADDzeFAUK!bAQrv z!lBpQUpf=`^Y~cvbKEyDAryD>kCC&*0ivmK<#i5NU=)?s3%)T}-R?_(#|z)lBeq?$ zzxkKuXaBkP=TPp7*VXiez(5e;1LWl>XjR~usA`4jeiZVev-1mUmujWbYri?aU>EV3 z)r2kM?#&);+OYeD%)|vUKHKQ%@$O+ zCNJ<4M%`#AXX9kOlp6KP+Y&_Cy=Y+W-ZW$E|1$7CF8_r&LIv79{w{o1kJB`qfIDC& zGR4nJNo=Bw^6i|*WH8L|^BALNz&PN&!`tsq-&HmDE9{E#@!CY|Dwjw-sRI6!SFRmw z{t$%lS8Ct@b_2}&n((Lpdr!{?1*C6?OGeP&l-QABBe?`}G2ZbAmaYg~^wszm>h)WR9+>Hz9{QI}f!}Rd}aqEG{X55BLho=SyK|w6_vNNAv zz+1O_2=9P=eQsYq&&cESls956)wH3`G3!~YE{T z6HVK#o`UOG?K423z(@wp+hIqW@(rn_I|wKl4LJy7#sPJ6yM$*ZPzUBhqzRleJ4T$K zqm&24OWNdj@#mli#?#!RR&%h&T<1FTZ%X@cXKaS_pU-pRBZF7eM&#+fa8zA@4IwzI z0^sJw*A1#NNyDIL`CuLR85l6ol1r-^MT7}gmPxc9tjcl^ekAwc(k!Mm9>*ovrYY^b zK+6a{FWMzn<%X3I$z7YVXODQGKOZy3EcwQab)v2pS~KSSTrEQS27btr1|e14gK z-{O(+HyPG7>zH7$P2Tdr)v;~`_XI!Qa(M#f>}oc@+aKO#uPS79T4=IlnKLkoQLy@v z3-!^-d1yg~%7b0%KfZEO-7J~~@2lFdJT~kVUXFP|+F4c9iJX%E3E53xeD=u%Vy1qU6+jE{IWJ=;Co98$Xt1HcVL9BHV z$KtCH6?hQeWdrRJT%$%v8wXFZ*#x7tqnYW81Z76JKq^``IiTcS?nYOLST5EmN%V&; zjfw{v&U0R~^o7a-o;G#_nJkjkRzVuAag`1u+$4zm`iDa<87*w` z4PhGm4%~B>v-1pYO_6KSnhKbhroNDufdA~KIl5Um7i3KGuXZOL5eUV|^$t!g0b_+T zEhEhlLfG*-%m-U8(*~JC7C)nGnc4-7J6bMe?OjE)js1EUe^}GzW*zC5p6dWwzAn*> z)`WtmuRZ9H*%t&_f6cG0*=;MZ+wpwY1d^nLt(&=LSUl5zT=iW}H=A&s4hcetOAUb9++d}O zVZE}DKKF-|o5zXx-zlh%q}$p-EFb;1!hT1@jpOw1lhR*&D*?}~JZ^VvR;>&!H+aci zj08wx!O<8#3YoW@G)!!Eb&z>I?tg7Q&(9Q(Yi>#u8B1W!hj#S1@y+m!HzReS|swJWX9?a#?-EX((ON;&&MUit&_28#`3l%N@KD#9xiJq8DEWR~CG9ZcGC=b_0 zPrGh~Pj#=4#g2##HO2Ll@^PwUU*Fv9ai}RXS7z?d30sYBKvq&&DI%k40qol zH`9@n>oCvXoWDN!xARM{%qdxTJMq?jXCaCS!;V&U^KE^eU|jiRCuNLVSn9}V?BV)X z*BF^i%~=dZNsJ~K3#u&=EKuihGZ)-zgMb>; zF4^4*ABFaa$Y)iBPed((h5Pj0&7gC%*@i_KEcNsPmF1R zBdIH_xXedURMjrUE0*tH4mC6zSJ4V@hu)lyl)GA1k*Rf&?YLt^cZ^`n?Li{)IgL0|CDP2OTBk0=b<6}D zGidgy`O*k;sG$=gRuILUw)X>51?KmJj_4#7NSytHk9S%uj&iv8Z`*rW5OYF!j2M3v zGRV6ArId)d1%JMUlPE_dR z{WL;0Jj*DnD2f8uQ&Q2-tuecZu^oNInaIrEM6h;VG93PzVVAI$2fy0Rh?u)QlKNN_ zz1|gqL%WOMjc|;fjJN~GBXmG0~E>8}tX_K;#{{Tz3z z36Q3_b}=tgz|&U`(LswbnI^RbOe3>s8MR>eHQswr>RgdEAiNH@2oQ;^j@_XLhAQpa z5*ijYuZ3?$rHb-fFXZJ0t#&_-uHk@N^dGp#RV&o)!3}ODR(>xm(Y3OXE8Fn_tKX{~ z0fd%u2HKJ&DitG&j?Lr9#rN(Wv!%3#$Lz9kQ$XFsFkW#+T4c=0X!{3lH5&~Bi5K+r zp;|sW*J`~2Oa^#mfYoy=jkDrcu4c9MHU_5*k6XU6)x~)el6DJB zrj<9yYe59)go&lboVtXRUq(U-JOVc@fh!$Fvre@r#Y0c9VU}WWHA`6P!iDCsQ=fDj zzC`khr%`#}vTZ#@-50tpuQz9z*3rek+@_*CERl14TW7We0vib;2n#PgpIiT}Q2*VD zJT^Zo*0W8s2pZAO*@P`fOIs5JFJVMTsGK}bnu1upaqx!per{v35&_&vJ8URky{9ao zuSj{fJXQ!SlWDL2%L2Id=f){JeyLDwcpEDUeYfay{)><=t#I;;96YCY7%MvRpc$P5 zyneY+W3xK1x&o^*OjAtl^4em1v9gqLsU?^6r?^W;n)%x_+a!vjT{o+S{gKlt;ULQnkXk#w*UKnSCibb}o_q z$?G^PAfKUgi&V;NPKjzEWqM(WW(hsJ z5*#WSQ6aUy=%KI7w`Wymr_qFfR~$4!T1bUpEA zxy^+4ct4~9u8sSTOll(3^4EJ>NE60Kcb8J{p-=nI-m`lV|d%LZ{mCFB=F#FlY0n;(6`?+z)UqFIsY zEwYST$k?O?_sx@0A;yKw&f9C6Z1sq8c_i%3GVOY0a-&csSYr~}WNFJ;hj%YX3s;BN zGcp$DRHp>G=J)*-c3a1WAY-Yd4)BB3(37QG8KT6@6dvBij@LR1|9vQb#iaSv!9i)t zE#o9CvHKY&m0I+dYDFueXlZKhjRV4fD{R5Y8MP1HcJTBhhuU9ac0;pyJ&QI*gC*`7 z21x_dhku(5Snf$*+wgaETlt4nw{+yTze%JY1sLe|in^j#gv)$bVlSxJlSMF6~vmt&(8 zZicL=LThc@3{0Tmc-@=MA$5yzSho z-}vEQP;$zT+G(`rsDjqWF z(J9~?Wd=l!gg@Uk-+*l7x?*m&MlkY0)G7A&S^Tj`fZs#`VPDs;(FU7=c{IW!9G!$q zvsa@Z|Th-4V1_*5i60dk_(P%M(D7p$7<1%A~$29BiP>lRj*y-b0`Mko>jLrH}2)WwFgT7v) zm76@iq$@uNrB;mhtO5?HGyct94C7Zsr{?%s1nw7^5!cOLN?@9M zU9mlYs+>m~`K3~w`WyF6iD6DZmlf^<@~-LmS@Qd;r|`6hP%m@fwK_*%^LU1__fvgg z4SVFy&~r`BfwF+st-SK5lV2_;O!>~l;Zt==0OE>pU*KIK@ll%K#7MwRdgZv_{`ke| zW%A3|$je&1feD{)UJvLHsmvobb4Q$FC_9`CD-q1dkM8{!g2KFyDDL66dy?$Kn2K93 zzdRSt-~%R2)yL*u(cC-zi$VsI`52jkYs^B@R1JAL?8%1)H0j0E_v+T3M#5u)jB6d} zO3J&7rob+OA5YuJI6cs}3naL2Y12-p1Szx)mLfohJw+KUdOY?{9R$;I-QF z4K}bj=RhYb{$Q@)z;O4n6&{CJ59XRrIs4g!aCV*-GxY5t<}%+>m;g)}k{P1)RS71b zbRpiSo^y6xL$%VRmh>eB_Usuxt7;5XkWx&m5|%Yfn@19|P||XE(#lUS$T$>D;D3V> zJ^o{HJ}gP&1^ZS^rL4Yc_^Oc3k!=o5NavQY#itw{cT*I*8 zHCqW;#~w#DE}75(9LR;)y(b*75`QnRUDr4xs&&9Jc&a8~GLI{b?0l3!6$U*@nEW>f z5RzIVjj13ctw`I4`4^YWGC&XxGY-Kj**h4(U3U{VQ3OCqvvlPB-xtj*G}94r{PbcE zQt1Z8mUN2Tp-_eIdA}`laJ*f>*2Ogv&F~2YL$jdF<-D=bWWnOH_a|d>fDY)`6(Km1 zxF;o++>N&Ukt64`yb;r!?!BiSVzY=6=Olqt>`H%n8CZ?eZyKU}qn|fsT4mMPO^x8U z^Q?U9+)%o<$@=IxvyKoXBNz?~?P#8L%^+qdvGmgv?vF7V*OG5YC^G>F+rx+^$Pcet zxGgx7nM2V?e$rAN(5647!59%l|X+u~K)}!g|8~K#BP|YrIL#J|PK1 z3aORE&JUt>!El=sb)jrr+Xr@(@a^2LPvHxcZyr26pF<*ai^$y9glo9_L!h`h2BC~HeJPXZ8g`o8SdTcG~MrbE)}1fBzNR+657VauBF z>R2YzdB;Kwq=GN-6tiNn=bFG$_LaO!fPYuO8)0S56SwAbGxmebba1l_^fqiT!(;4#w_>Kd z?FUzT8MzgT8M?UU3AD)AclDtn8nb(W?99-zREl(2rQRA!T0^&l!Z7TNU$||Vg=^*P zILaJ~Y5PjjF{~5d)%yx?KV`j$qRNYCsN5zM6jSpY6qA0NVRCA#Ad#E}%t5S33{Li5 zmhu|eXX)z~$d^5YlmaD}NK+P3)<7#?I8vinMXS{%>Wxe&$01xC=1cz{Il2-c_Fi zYnlJSZ_;&~adutz>k)tIiZE>grjVjK^y#zI3)MWwnj7ED z6zg}B-kbEr2kuIZd&1eb(0{cZ$w~1V7r8-Hf7jdE@c!uJaAkpKbaEp(uHG!20<7>5 zaF$Z(rcCQBzF^`H2qdIFDv?!~^iHh@J`J0nD#4c_cs||~i)5F!13?>)7TFl(guW}D zFa0aZ4+8uK`!;1Xf&b9I7*>M=2|DA=Op#8hLxfHiU5mG)?9LUVUF80al}~?<=YU*e zpF4E}ux=*}S6r{eg_uXo&w`+PDi0o$#grJIc-OzX-qUqE%DTB$0v-K3UoTE%m+TKK z!CCG;kD&g5HpnTWvKc&G>-QOt&YxUEFOZj!ey503ahfswC>m) zh?#c&52bbmAc?yBY-1277yBxxG2Ij%F$m+*#RrQ2+{^!-uU;v_ueJ7N_NV9lnzqsY z-}4}O9LvYu;fdKz%jjOG_vI1i&QO$FQz5Ut4@3{+pC^IoR`1#`>!r{qt`^o6wv=k< zynR9;2d-?W?LH7EctW2?#z)mOzP+Jc7y`}D9U3t-xXuADB;^PEFQfe1Qw80l;l1T~ zTZK(X8w0qJUIOgsQ39QNQ)u# zGVAO0xC!0Ocl9u+9grLNc8Cnv#Y0n9uJAWW*;^f z5Sk(Qls;?FLxoPg#&|8Zd)o2Gk9(hT1N9G4ywR_~!WmKdZV+UDX|ehgjGXUoJ^G0n zs5;&_h<7~@b_H}+-e0u=vqR!z!Xc}wimI}P>hu&~Zp^`{CfIuIk8h~?VT+xbFhNYS zo-R*}RQ3;_WafVp)9MR?HG)K;jKzT*Aog8Ru9e?yUC+848qv35m~Oz+oYJh%RqO-K z*HKpSZl`ww>Yt?|x9-sr;)FCY!8qyxMY(x=rfSxrlYYUCAY8s{V<-31XwvhTWGHwO ztCr#Ob_BoIwR+b`NV05&47H@^+dpDJaOI>ur}MSWpnf^u5ZYrD-7)&n{i{I&CScnj z{EVE!3t4F2-KlSW#s2DRM&tv|FZ~u*#P|QXE&peMW|WeiB7@hxPye72;Se+^Tu+4v zDBf*^{-lr>0*OZ|O14BavdUWh5nMF545A31<-lPDDze2@C7v!gN>fm-eK+#RE!j-s z&SnU;VocbA$a+-cJa~U+7)-Tj(BT_ftczeJ)VeT~JwjGl^g%rttZFH6(}$zMT8B84 z$DgC3o;8HvDLG@|y=+3M$+{G^`95aG7>`W5gyk!q=jv7+YA<|PeRZv1LX$n zlJJzC4QSPki#nNKgr2w`a1i#SY}}Hi}r;+bMlUeM>~| zPpF{sZp(sU1yyjIeX)Z$KYD_oV%kIJVSho5Bcg(5QA`e%9SmgzKx!&z#7rc0(GhxR zY_pl)8Yl`-SZ$g5A6+EJ8ReKHPS!}c?sqV1usDE=GZl;y4XYZad2m%SEm1`7RiNsB z$(&82Sp+bb-TCRT?lPfL?Eos9VO=Am#tvxF0cO2s7_+F0g$g#C3$I!8ADZoL#9^W@wFOQ&r~pQg4-BT7GBZP;ZQgm#G!<1Z3F3dI0`RkZH$a#WfD4xW?^l5 z6~w_LYrj0>1A`}Cxp{<^*H_@TIj3R?!ri_HWUzB6`Z&qUI?lsRGi2mp8OoL8h{C z@py)5(-ur@cp)h5wM_GZDPVQI_)KGXITM(7@1IFs%YO{ z-70r9Qc*EU$yiZ~i_kILXdurjhSrj*Y#L~o==p&#Av(^`s*KCuJ_5$72uYj74!A2W zXwRX3ancVYVNi#g2&&q_kcY+xmqn#`KbytXpz zTBz7%%I+|U!s*mMw83(KSzwM`YEuMT{y4d6$9imLaZH!dDk7!Y#&OcRLIKdz{!52)pg*U zZ1E_3FSs%svxPLJG_2n`3u+U$Rx1Cbt2-`&o0`#v(Lf3Py~XQSM=+1wkm)VZ>KEXU z|C^4)v{6dF@e-xxXiN5q(y|GXF*(0;-S39HOlAl?jN>>oDOy#;e!#vd7D~A#aeU_X z-(O6TNBG%zCj>=fZflbV_{uE{&=h&eA7Y9rDKN`5pQ?{?lat3j2)Xf~G;d~4EQcZA zlZbd4x!HlA-=6V*rIHW>-obg3eQ_@36GA z$)+C3f|LCsN6uXG;EW+s>~ck0oy;j!6cjlNuaNbUPoSVT#>H$h4e;^ORQTn z$ZCq<)zBE>r{Gpq7ms&5Zq&M>&7OP1%Nsqa4@M?!?I5^BEFVGfA@$v-(^qUQ4a?1< zHr4};_P%p}6juMgZf<*PiU|D4ta8EQFv*ikOuj_59-`#b+A}QOAE@K>Ub_WM5 z?*2v0Q-)jZKLF6JBH^L^{g#(TUX2t6gGl+a1~t~I%oomYl;_-9=l(4>9k)>o1!sn? zK}7?)dye2lM}eVX4q%{&$dbZpG*Tf_Y@@5$dnD*g0XgVm)##*koffb}?uvBP?elpU z%b&D#1v+S@N$n8eC(0sCpPowyxCwz%yoAWt<)ABiE;>viD< zy`vN*j4<@tKm!z+L~O15i8551;;WutTWb?eo$1G2k;C`^ciZf^sX;d>GvL6hV zB5a$SFh7i9@>C~Y6zi&e;#o@Uh#hBU@QBWAQ_L z>duQg&X@{hw@rnQF2#~>o?rzgfXT(WMZWq3WVx_1@E6ohHMV7196uW92{oD}qln}P ziwhC!%hZ3WtT&<`lbp8Ztsr`Jj5uqUc#vazHEkZ6l=n>-*Bcbk9hH!eQ~OS2t&PTgH7~`F@bgEAS4m~t-o@@$}P~}Or3ov%7aCmavfO!pThQ!qoJxC7)!gEAKiGx(r*ORzX7sN^VY35KHLN848Z&+cQ?jrAGumJBTL#kdDYyM$iL z7wS_f;yCNv5_|tdj?u@X#+G2X&8r-4mGZy{%B`4L07vc>)1LTz`0Bs^Hvdp zK4#41j|5rfUO8Gdl69;^L@fcNoAAdA8jCvBUA{VJ2hSHv@g5cIo@~*^m{2=pj3Wf6 zty!aXv+Lv_~)i0%CRLsxg!uUJZ6z#;^fubosD+*t}Zx$*@+#$CDKo3F3?vp8jmKF1 z(1e+?QF7`=vXiU3>K=6P4|gR;m7fviEMv)3Ua4DHo-A$VoXO}l5EV}o(Se*h8vJ3l z7{%%~9+ZHyNvbi%yw26G0|mrBP-BDT3o0Ai_ShFCoO^C6>O)kJjH!&zeVP{#FlI(C zHaNf}7l$_-8l~C}9VQY@&S^wd`3r?qp=ZA-SB}p}M+^O3gWU}b-YS{9&8z6;X9SPf zphcudT->i~GsTFbnL#0{98rbPM@Q5nWIWKUKn(sD#WGy#C*7lwPR-a<Ppd} zBi?4q$U^(1liai6!rw(YnY#yEd00hm6o6mlsKU z10V|rFb%$$fl(==PXdc;sHSMlUc)OO)kJRI&>q`at!x+!>%|_RmSe zVxTN!zP!fn<=45$FUazbRP%uQkP++}TJeUTVB#J~_~RKz_*<3T#Nlu8<&~1@mz%*Z z*5?9j>+1UEVSV5$@AYDN5GeSU!Ef#%Zf@tzW95%t6qkqbYQMc#W>$!4aN)=8XBLj< zyY&}}nQmvaK<88}7z5wGoDAx_$aXwhzxK5Jv!{e6--C$1ZjBF3)NU)w1F}DJnH!?+ z$-ckVJqS;Mc1qv-ojw5y*7-?9sZytuM`5z76EkDcIGT>Ty7JXHUt>KW!28zD3k5%& z%$JZ+e%By2WzW;T)2y?b&~m`hyt=)CPZZ3{KXPn@ssHU1;;8L-{URSQ4lifoV2yju zr(K@EFTjnv_quxX4x{eKUQh()u?DsRICYx0;rmk%;{Bk3ow;e`eTuoO zfynMP(kr|zgjm4F8sZI@bsu8HRV7#WCFTD61pw~90mw}#9v&lTp_OX@M5ygLNGK*+ z=-Qc8z=`xIaas z6<#0W9vY@oj^tZDO@1AA`n8`HWHODj#;u%X?i49q$UknKhfVDT#-;m_aAR>5=Sc{ao=WYg$T zl7NC%6;X7!V4($VRISM^NLr9iPy)$PsN2{3o!S^Mgi1-qCV6GvCxBw-{m>FEG0|XP zWy0MD6@p2_u8@N&UbmV0ZC{0vEp*W;!6vQh*&l)cRhFTTq&nl`AsNK~ZD zm5oJs>InToK^)n5J{s5#*hg(G7FJXRA1X=kgEVvvu;c&(fJq>FVD{Z$-IY0jK{uXcl z9=ggXTl*1o*dK8WuuUxCBaxUhbm@?1XRACHcP&#!;>IT#Vnl(o{1|IIGPEq$PN@ZuYDFmFUb0vGW`3& zM?cr>YTb->&JduvlmruNB8LeyWaH@e0%@~_x&c`siYc_I$QhZ?vNeNBBhLbC_2M7t zZ&+N%Vt6)vU!C(=N$BaAME4-75qiVE;X_f7B1KZVfRXr<4}xsCLDu^w9G+BVZ`r8P z<%5RNv!~+IA=L<2ZV_W39~R%LOPuIB#Ba7(mos;u zwYD#3v+LXa#owD)>I=IwfeYdyLOywMvvRtpes8|)bdJdHy3N0fu6MZa1bu7m$6X$B zZE7E~eBihVB)RPg*bgk6aR_)K7oM&Ue1oGBQNO-_?tW=q+snPYGqg_?>@Jw91pWFoGV1PiE>!8>6X!`dHdZz;ur|fEbw$$iN)d{#~m`iwQ*IH4@`DfBsK6%Y?sk8y?ETCO}_-#WV`|Nh}AIBD{Q{q=08{rU;o zo_HR1s5=e&IvZvJm6HGS(mMu&<+n=wcF_sPM6~7+*}_4r;UW13i!r1!2mASsB0RkV zTFE!1n`Kua2Kya9v$#9UfwK|iv)C%=RM7!8I2wrD(;2msXZ5e&GgjaNfX*b^0tI>-1&S+>N z&<}XtC>&Fp>UwsVrr4d#pt}a=H^Fbhe)5z;zRCvr zFF*BKYq9H@s6YQ&M|EYTz%=12-hS`&?elxPOkFMC`13&6@1!)a6t9|I_}gpuBS{aJ z#YNH~O4jdB(fI7U=VVxw1L%uH7o2 zk8icw{V9usd^+LFYXT(z_XKvbJUb3(dUO|;sX64`7bNonr%GYnKX0k8$lSN!`^u?R zGlp3(S^x_fyEKXjE4f|eJ!)y(}+Gq0Oxd< zd|I--5VgR7{%Vc|>XcLIik8%}qTBAu%(hGMqi#ofl8;LYWan8E$AQ}6N@|-!W|s%} z{BM)e7lHuy;DfeXFl=1|t86cO%Jiw4gYVYu8xK=VPMAwfZ|fQ=n}a~<_w{~il_uqS z4%{=>HRf4LI1_eg--K)F=FEVZEv2zV9;hC0Q~JNfxXf<@PGy1U$>jxM9T)=-Zk`by zU3Wl-A4(+atgHSKWaqwcCQsBD*5nu*p)s_P+cS}`L24%u7km2EbrMkX<7KH<}4ipb=Sw3_% zHPcT8_vCBv&8ZgJUeW-_SbPb4qImVe?f%sdM7$%wFnA+x{yf4E_$qulZWKBQZqgN_ z2<|llyAe<%!GT$UH+UIZiMCMk)haFldd zV&CVhSvkqC+_mN;zN3S_F+uMAq2T9Y&dLbw>K?eAb{=`xUC>y>C(!bj(?E;llM7PQ zk?oCzm*l9Z3w>&E6(JRuQ`(Cn(p;U^6*l#^OO4Dl8JZgeUg$0^0v#F(`(%G&Vz7|L zZe+B+v!ZLdnTj$Ua{ggpq?ZO~ap+TAHylambWMAASwf)J7ZTIGtOZqP;Xb~#cn{e34>7xL5azo$l z{ei3n(xFaK%FxUrLa0PbzV?T(@||3Q)fxSnNcmj+0`)$^@jXimJKc^VnkW@4bi3^$42c{fL$UMJgIoj8#BpEkq&cdWogn~6!vpEVH z9PkrI?9E|=9HtMXF*{3-l&W+BO-uGK=YbaeEc<&7i;{I6ibx*9Pm^(5yqMiS|EGEV z*i6-*oC+Bd2jG{m?+uaNn)}YPe}LW9i1+4mr#C-sb>r2LS zmmBd(-paP`KMTjd613ZN7kdegs)xlclNn2n?@X6f{;y{vP;0}FY81qI^G9D|MVc%*HVF&?5L2$rr0ts_PKE_>Uu zE;@5`!iM<6DL8_0;fOZ}e}lJ1R$*@NJDX*6#0|M~7otpHWaLTE_um%TzG0go)VR1M zC0XKR_ev6jTc(!Gs$;C|7C;$F{gOr{ouFU5D(;s0K;NGs*J6FL%T}&kOnzQGjC43G>Wc`#ImNJRJBhSN4WLXMI;(W2pSH;RD zh5%(;a{WqP*HHfV5V>Z7Bi{JI&L%JX>@ywucK6nWvRVRejOa@xydeV$gIeE>I2Qvd z+DBUE!UAga` z@WaD3~IlqqolwKB$<{qWRrM9^>6g*y&gA5}N-Wv<$C$ zdhvm}RCmQ4prz{k-l(q782X?N6Kbc!_QdM`pXKX@lTxOqlc(~4HAM1Va zMwHA>y?TQ5WVIq0Sx?BfRWd+dgKTVCT6xA0h@uYycvy_`*t^8B3KB50S^z$_3_5+H zjBXg5iK$(cEj)0vR>s=K;X!Th{)lI4Hs7;+&u+n}??F0uGl1q^%kA=QR4PRh1tdV) z+$F_YrcBs- z|M7nSnLuX0VSiI_S9yZ1>I!NM6Se513#=ukL%TLt3(DLLI=zzV^y<7sn=LQdZGf%A zD$@lW+af<@@oVoe3s)9a_XAn02NaE-rW#|!&er>oP?k2?=dFP|d0U|Kt?zp~urk~V zGJjLS;zJH>3Ps+bYU26LvOu?2F&gYeV9?ab4eU=_L+e%-4SkdIS5;9-t6r%l(-|#4 zH)E@$Q7swfMdjPflV|3nGD@)6C>Ty2a^#yR|#2I=B6&gX~blv9( zzHSw*KJlSLh(D(+f<1$PVRzG6&yO7CNwhTbE zpIfD*%(Vm7yKWLn zxVOW3v8nk2u*Uq@7gf=-3jCmwb`cyE(V0cB7)evN77JJFqm`ryNLWMad!lm9z7DcO z^#2KS(0A5w4R5lMS^&-#6nnR3+qGaws|45dax=TOMIJQE;e!0A_R=xjk(UD1iDC445`HC zgj$c{nAUp)%@FP4bb>ci#8jxMFyc`go4~3InaNToeA~>_zB*75jX%}T9Al%xyAI>105l#*&M`vI`Yv~@6Vl3o|Q5zzd?9*m9 z&AMwm)(Dv~7%33xqCUep7gZ0YgI7;u94pHi6NN%DrqV#>8BKQ(gl-YAI%e#y;Kkz^ zksC?bq&{w_)4CPUqeLRaLayV%d#437=l7VlN(v2_#3I+U*)}3GV0m`k8KqH2V1k+f z*2MePV+dv#?afUO)!4v}(YPVbStv0`Qsg>}>P#)E!6vI&OJ@Zhd-VN${!=een$t|j zO2>3rDvvRpR7j7+jIJWEh)o&H3&6R#+Z+{B_fv{gh(BtxjCXMbBes7d#fO=#e!IaH5R9S?yPZ(BZu&HGsWMs zJKmsnYd-m*i0il=pydnk+0)iPxRiCrJa2dAa``U%8aGoz&YBZS?~Vn?==U)l_%_QaFrt(UO~D;rVw+@wMn;ApX{dux1C>#@i^% z<~hP#Jx*CHXLr_hX;6&BXploHz7s@|6T_pQ>xe?MJnI$^-Q?m@0f zm%LxZb2-2#sS1)a{&m zPl2OI6{*Kj7X#|_C^G@@1~)D7lBIiQN|6V$(9p?m&`h6Zd;g8tapoA(|1+%j@8zQZ zHZI(_f$2SjuMAWFFSy}%=rG_j=Kb7z@*GdUyotH7%DW!^QJ#A4_km*=-p@H6V%d#= zf?v4w1r&IWz+~ye?D9G8VTYgSt@5=SPx25~cX!Z58wZ{=x#m1FFyH&RDD&fW7yjnV0nO_zxW~_|KLyZ z?3aEXaj)>NF22P3xR<+V_}fxY9>30o;xT^h@|fSlGGa=;_Z0Xp@H&<;f9<>8#qU4y z9Iv~maQlf5eUNJR4Lly!*$v`22NXlXpLMmVfpKpTq&D*YDu!&Q%bo z^Hi6P4S8PRwP6Q?V~L-6;t~}(`BH~wY*9DhF(x?RvzJS1^8oN5Zhe{m_Vr(9g8_X= zR~UT$+20{h@*jTSqbvGBndX3R$ z#^rP`m&vDP%Aut{YfwK)@iQfv16K_ra01+Y`~;7lzlRk!;NN`uixgy(Y*4X^7)KE< zl4UT;pm2tJkF8K$d4-V-;~M0TW4R~Vld=oEn!rE$wQn})c))HtM3S76TyK0N|EMSUH;J`608*P<_L>WUo?qv&X1)O+ z@S8W!1^i*(Ev+3?PjE6!x+X*U^Tzvf37)-|0qYq!3u@bouD_eFR@O{OTuu z>(Dj2;5gRyCrnht2hA}Hb&#|o0v7v0;Y}~cThC0|D-a(%Q;o!kF%c_ux|b<6L@m%bsalEa4lk4pk#ITTP=6!P3e({^u8-6|-hC&yAZYX;U*ZsS9tPRVoXh#%(^k zUrWlPWNWKHScCd5)U8GJmmNTHDdsWHgic9mlWiXaO6&maK5*^OxpI(AA-_J~V2I8^ z&30qc2Dct)&Mr0(lU;Iag-H&fKy)c8d(9w%t$rDi60#dH3s3}c=P<(`h*`3|Pawrt z6U+4LDSnh&RL0sKLlteQW;xXEkZLe+Q^ zL=XzB?a8FfY=Agvgq*KM1Xho~4 z1g$Z~6QoY_w5Yr@i0?vJiuSC=g5+`2+p4E zam$OlRYY?F8I=*d$-y=WG+m39>1H3$cus7CwG*s>x*UQc=1Oe(i)GXZ(_+e!sql4! zSP)U1PVu3kBNn3$RiQR}1S<#?CTTo1L{nyI$psQQ;9{a;bf!GG&HXPa+gk;Krk}Ht z@^Upcp^TYjm}_VQo(x7U&KIbb@%|EzG9`$?$U2!>2Q8V@yLfYnEHh+s4s9}mdK#_B zY>riju@Q|D?PAR;)-O>j5U#PhdN(`QHd&Js_moR#goC?ASZ|4elqla4@DXW(S zRX!o*VYh1Mg=;`>(;$%+0QCf&MiPlhnkmb!LP-K|l%+%%r4^JJ1^lV!UE#n?KkNvZJm`IsAK_o6F=9mcMP zX6ZW4X6uYfh*_az?L`x9m^G3XFg0pjYW~{Ta55(OX#0ixXEB^Bk`G*?30%xDbSbhv z)|O~)$bFyD)PU)LGzcCuYrdLDT#*je_Q)jz*WmnwfJ2POn1=n)kirOAR#3<)rddN= zjm=&s6GvB0GO2f|Xk`n)upp9= z>oP?aRhPAMG_s91<5^EjQll+qwx+e8455xz;bw?Xpzc_-?xjX-9o-bH$0h}T%&avj z6W!w6Fmi{ai%5+#&&KOEtYKI}gD2o(p0~!l@7TDKMAm6D16xOo#oElhd2{n^)_!8^ zw61jH^E&02YW^DP3yjGR)kAIgV~ReQIf|rbV>XQByX?lirXe7qn}~QeHo9a2RLM=^ zPr5nWjts>T#GuloW^Oej0jek-kF_;{{bWZz$7_SP80|#4-R$#k&!Z|@l|O*pp1WCS zeke|5fgmH{mSa_!U-R>SYg#)-AQG*o(?dof-tX4neZ2tsreo4Ja=|5{Wc4k%HL1Cq z)61tg8!GNT^Dxi6cm<{6qv!A8aUKUF{K1P?csW1MYQE18pMQ+!zVd&fz<0dweGI#I z^IKmYP=yCs>y@nByg|tT;bks#Ya{)7_P7K#FfvoY?i6I zA7o|tA+B7WaOt&YImb!<%7gFacz6ZxukrI2p5-EcmJ!Q5z^=WJ8+wj%^C~OFE9~sPKv_J(07Jziv1;&7@*&PMW`Goy zUw`6vfsA!lIK`A#o_LZH_~CEAhyU&K7ZEnN`1}p>{JS}`V?+xxqmeQkMQS6V59W;sj51|B%_DH3 z!$bR8b8xTrX6n}i0O}$LYG%2{x5P_*gE;T)*MCI_1Z~>Tgt^G@aMr0F1`Q7%v%d8n z|4l((-r4i}>us6k&At@hv#J{;5r_;m&TmGbKWqM!Dt+b9+`e^fksHfoI*Hy2SNI)W89ad@ z$`j9hX?Ew%^aB$4#wXG{-He#*tv9P#C~Ms};rb7-WTEhIX}Hh558TVS^B=?y=^X$7 zAOJ~3K~&{apIl{m?Llr_`E9^)th|#`*;!7lKgvs+ucHKJ2{3A)u@M&!6LO=}vXQ{_ z)*e5Q5olP(k)>pH67*|Qy&DN8v-R9$GvcAe;I*~#uA&)E2w27_`OJsl2>3l3N8@N5 zjiYfij>bDIkZ!|Vl{ecgnXmKn|E?n}WVVgxjm*#ozn&V0lcXLY+CES3j14R^iA^ib zVk65hrLJ+#!QA3Q*|0OqUpZtEy#Q>@vi=sb`x0YvJ|$HwlHYcP+A1K^CW2%q*@l+3 zO~9FQvQ>%1zk^BE&*Zc2qtMJ7uQU6^W^NO$CfP@)jkKwv)!^*)c3#yVR)y$deo@u(^GDO% znwj-&REq_os@RyATRNtzZ5KJ8bO+ZSI=rmbGlk$X<0yS7fyR#fd zOG&Qh2u%}74^kr%5EJLeiosA|#l}W>+U%M(WlZNA>^5Q7%$g(VHPV_n1r8|E)TV}W zClWenqRP~`s1Ti6Rm#H5={VL+Z-1hWv7D=QGuzh zK$_ziEeU1-GDK_##bcLinrsgvo)DBWF9@pGyhI!DwZ_ldwd8q;ajP^<12*8aPByzq zjio7vcfqeJ$gLZFqh@CF8aIY>kk}-RxD|sn`Al8e-gegH7@JeO5c5hUOL?w7Di3WJ zYgZ6DSYM;YkY$#VB^oUVZWNazA27yXbP_XIO_wrXLVTA-N(MpMA5OUI?1SvRHl{2b zxs|8z6{}gy_mok3?sN$=)3cb>F4EHY{la?NTCzz56>!4Xu zSGTs>;G_l<2x>7#L8gTCoQppn)!Np?Tx2hMX>I6XO^&({p8*>Gmb9RT;BfAcn)fgw zF6JHgXH8oBmGoI*zV6xzbakO_@k#Bw;MicM^ZFr?Ugpj$Wvtl}2_eQp4ASeWH;L%@ zlLLP>S*FJFri%8KCe?Jw$}_GB4r51Yoi_1VtU3p9NyNPw@r;8}DQ#WXlI#vx*}ruI zcxE}@It#Sf#1hYw$s%YgA{hDv&G9aIn;60C@L-MF0?%&-%6vJhvyj#zl)Xr z-{6&zlJPp8o2+i{amtRke7w&N08i4e&kJmGru-nm9|!IRx5){!&)@ov$NAOIJcVNq z#vAmP|8t7{$G9~9zgau6#k2dcjc}dM^7^$W_#BQ8pM5;p6B{Z@URHx!I)@#;!AjHc zBlmtM$2+_H(z8FyHZZ0l0~)%7;TblvA3?K^uqs!%bMk-j!IxAt5cL6{7 z=zH-OUclUSivR4wCB|Ja-r?#26ZUCnV$4t}LGEuY8goOAN7$HeUnIvwHjy zrdv5hus=D=T62jod5z_vPJv)N@&fpf{9C!6E=t7=CMBqGJOvs*Rc-LSwzEI19|Cr8(M#rKW21Q4}pjYKsrd- zkNY|orfl!OoLV8Hd7kOF;z-v~B)hf_7ioSa?jOV3=*#%vXY)|GW>#I+8p()OQp~Yh zjC7)tmyINPi4Mx~Qu5JBC=-jSn_EN&uqN&eoR7UNBL*WeIt3ula=eSr@NTEebUIBv z0fTBc9zZrpC#xhQ$1BOLN(s539!3GGUda?k!vzNWn>Yr*AVpXif{RfeS>E7W>KEvg zMKT0xP`d3*Ab4z;QyUaw9j`MFxa8S3_b!SW)iD1Du-3p&-T!eiWBIEWeubTagM9uL zVD_-$VuxTq{q8rd;=~X%u(rC!?%r;6=IVACPsTFU5AwSBx zT?3wkOqmoX8SmfV`sUNX4JhmQ;p!a9WtapABXT~AhKs-l=%2fX(T&eR9vDqxSI*_p zVXWLZMzwu&;l48z8y&{`<2lD!a*S)R1PlcwmZ=+nf$nSxb>zk|4Red^qj5Bj#?d$$ zN8@N5jdy^(_77%{&YF0OAdK7|^d-Er&5Hyg8?IISE~t6yJL7wn7ovhSbfLNv27fUg z&+_j=b~80-iN)S#XLn%ZU{2gHo$Im2x}t|pc7%w|yL zKz<7b&p=Xl2y9!-CpL3ndiHtUg74tsW_$t24yi$*5nHV1)nxt%4nd6TB^f@QF3Y)<>7L_kQ*2A7nhV&)B9 zH8H<%p^+;I9D!-H1Jxm|#k80_S#z7YJ!afyrgNtR?cyo1p$k$WW(y+|#4mvsh#3;p zBVn1KOA$oU3U9}#ItrV`IS#QoEXKzsqhCjZ#n^sQRX14E!!{2i&J)b@czct~W(f?@ z2$bnE8ClG1rolTizkdjcNRY+$(d_!KW^*sve!fx61TxbIx@ZIyB>kLPC?Dsy^1lr7)ebXiA?CW z**;hKnnR#3NwLwzh>iQf&>-ruHmW`}1Tx96nnxwJT7tyWX(=#bF*1(U-&jH-9>mSN zqD;w5AhT0Mgxm^7M~I9NQ)6u)RFPh7nI_ZuUQ~Zdh{_k45==u`K%RS4hDmTdih!$T zXy`;+`g9*^VvipH^Jo>3opg@h>e&$v%vo&kWXbY4i(s!fLXZ^M9SIs5OavJvLrf22 zbBs}p^907}eT($oO;r0zY{+;7GecQOWCZYD>393FCo%EZBBv40>ajH@Tl?v76(c#B zbda!)4`U1g?=uJ+aqTFsrp(W5Zrw}F25&(qZP#sSn~DK10kw)K_z(dE$#Q&9rqd~6 zl^}6V^D6kD5%iTP3T_*)s-8xp%0q)8_}E4$%4F3oX-#UM!^FI1RmH2J2{m4$JAyGT zf@D5pIXg`$YnYG|#8a6~CU%cT1hqLL+qkU8=?Q$BRwhE0luD62lW^xl_sF6`UTeZ*#s>WA1ba z?tmTRH@`7lV9gTV2UJ7KF)k50$ns3d;%5wTT!vPIY5iw-aDaSb@;Rgfd=R z**3@^ND8u`2XlevxH+la7vO zjcA({tXl|vh-HUj9Jsl2jeF0ZW%$)SdTZ}uv~?#pvA{iCX)H@@u+KLA{&5Dwip<^( zYy(3!@?&f^FO$_{Rw>Z9bD`dYZa1g5vdm;}L@|xgv35Kpdh!e~6in!I)!oDg2b~Hs z@Tz#)u$obz{nKGBS4_Xb(X0(33R%fjCwg+Mo`93zX6o&x-G7BYKkmpX?2Bc z>oP06%7C0}qxaD3Jc#rHSGF6rmX2|v2d`ef%sSxlWW306Ht^$uL3J893p_#-GR$7i zalmnd-N`Ey$L?ps3R^2@*w11n?+zA6kA{p*M%>-Kk0DR9&N35nHW)D+euZ=0hH`R= z)&44bTbBtmY!evfFbJ^LUtu!XW)iL<-ESvHF_Q@sxk|9hWZVh7n}K_nC9cuzZn4ze zV5h2>kTGEi7-7R0@(n^*rQR8G3}qB{Iceh3Gu*FvW-@hLvnSZ0MCcM2WAJ#nnPNd!8BMmy>JY)u z3{0_0nC5XWK#>U0q_at+Fo~wI>&Y5*IEy-Yr%#4!*EeVXuBUBA zeF6wWgGm*tchh80Yv!(3Gz(*N36oDVa=T2KZ99%WzVqqYno;_O#&=0!5CS4$+XY(d+a2 zwOs`08qapvJosU)fD2%R5a#n@vz%O(P*q%T2@H=;T}s@OXA5`ttQDvbf{?Wre`at7 z@F9^I9b!Th5&QTfS2nMcnMgdLFbPmy5ZI?%!SeP(Ktdwz@9yoU`Oz8ZYZa^tS)v#3 zY~5rH7&2nS2geA8t=6E*Ruap1L~H{FX4a+k8m6C?;CyZES0f_$jfWhruhOu z**2w9&TgBn+cvT^DPZmP{Ma;E=E?-Jt$8D^wT5o<)!L7zZD!ZutlmR*!L#orAQU|a zjNhW3PUX6^0BPC{7?{&kld^XPKu5(Ac9=ltW&zAD<2<#B9BI-f)h=YMRx^g@fqa?P zzOsG&*V}N;nwi;rYjhxgbDmijZ8EDgA9>sjC8e|mO@Nhv3^4i5yy+SYLO0D#vW{$R zhh~6p`ua=}ofJA`3!#vU`G@A#Mrvz~II~hrYSPwbR*QqzM0;(v*VYUqXAX$Zz>$>k zs>z?o$B-Opo8hxvn`P$L)}9{$B{kF+-a|r(@zJVW-6}?l1QgWsrm(hPPl!S+jZArL z0DhvQcbUoXbp(qsaejjYym-)%G9b;@1ubIMw9Y|J6I&1lXqtu)z*@3&tuz9Nr7A2@obY9Z)l-W(UobtmsgbeYS^#nEfm{ zA{o}!SnDF#9HJtcR`HwGwHAMG-2`p{y%yH-sKN|r7$SC(@`ytsQW&zVhzdv@5!yNe z7q6_Wh*tNr)}JhpGSYfuW5%(igQ&+z1n7;)uz3beAc)M|9cJsA8r1hN^?hitgz`ni zjxe&E@}|ehMtCV^B&#F`jJOtu5M2YTv2Q_Q3h%5AQ;TRnk#&a5vg@@-E*3hEw`kY* z&`m1dwl2t0jpi3#mq!3N6bqp0B&`i@W;JXyLkaT?^mp9me;dC?Z_U%zRQJZLa+f|^ zeEy5gam^&ULKwjWlQOhR@~j&hrHgfuma)@m_f!3r#b@U%7uhWMnlEM}zl~$R%{;~C zw~6JXkEEr>Rq?(sN>=)LM9SdJ8Ln`RA9~+^!T)>VIQye( zoaQ1Qf8RQTy5!lf{tS0>0qb|j*S;&MNa1&$e1;M@$37iy@V)Q-cK+@&pW@oq9%D}N ziBDf8^Bp|Iy1z-oB}yv(>IZ*>r=EP8 zX07DH?i=h(D(XqjUs(Pq<^B#ke2xw-W!=JvngKQIoZ^ij>^8uLKqF8svnG#Ys|~W= zO=^=f&i^JIu2BqrmhXL_;e97>^5tu<^Q+fK3@O;B#$?YE!WEtk6aKqP6aMDocX0R4 zP5%1b=lHv?US^w%jQQsbrpI8q3|M~h)i*f7HQo<=^o~3E@})Oew}FqJ4}AWW-{-2o zm*Vt?DaIdWb^m34`K$kk|K!2%#l6zui|$MO>ziL>iyM47@AKp{6HXBcXjgd**ZZ?9 zpFYh$_`~0(;114U`5;T&9Q_XG$hqt63NOC=Jk#~}U^*E)R|5?tlcr(~kim5fyIc<= z*tx+C1`MeAA6|M6&x5S>e+cW|#d6u>()1F)Gq^;!?-bjzOJIYH24z4sz6kj~#dMGJ z{4RgxJxl!3vkjL6ybS#9i!ZZ|B_LcDa5X%T-@^}n`}fg=oBZKtex>!d;hu*d;Eyi8 z&i1}#;*aBbj2<7r9)CZR(H_F1TxX9z7*6==PR)zJ8*Ff$?_+iKLxg6;VDnYr8Wq?0 z3c^2p{Uv^phLB)3>J9(u``lKoc59Sa6CZ&_98m#gHVmU5dKExU~!cC?;Kp^mUUU`aq4LaRE&+~xwPlMHdm;KR%UMB}zvOlS2Xr1CQ1d0V5&maU5G#rix65iC_S<+)N5$!aP$i8hZ zfK7F1R0S)C3Cf2)<1JRa@1(zS`!DF>9z{z)VtnwW|G$I3w;^@i1`SkItTkw`vk5Ho zE_LJH6f|xPtPX>}EOa(3kfpitG%=UeM@J8ne!#ced=vL)vA))5z?F#XN>u);>P%&9 zj3Ic3Ya&=&O{YmQ?5QWyR3Ak0be67(S}P2m4weEKPaBq(H>md~OvaW^U%bEu=UF>` zn#(t?W6cUa>_*2tGX)z7p`k4)ox!q3Zcj!~8jlZqK$S%C0h782hueWOWE&wEi!&x} z~+&Y)5KF7)r6J(iA@nObh8{0jLW+zbjG)%5jXh3{U z#XT%%%hY~|vIX)CZt^0%X2>xtCnqJ}!Jp>>D-8Rqd~I}*hU?J3!bql2cPX?(-HfR( z^?>(scX^Wi>fbWuB?k2k`b0|6ao~|Ve}biB@8&a4{~r5X<3zX1Ll50|1pFS2qj5Bj z#?d$$N8=q133EVHTC2y!jgPraqj5n2`%bK$wTw!=)&@_isEp7oX2i9iFChZH-LFD% zIlgDI43tpBW6F0HfP<9DYGUT%Tvf5SfvA$AvzXiZ9{xPivK~34h;1`1^9VMzpzDG8 zj0#&HD#RpP;}!r`3#Ld7@3afaZl+C4h6V`QjT>k)w~NJ0!0fW9#ugJ|XIxX}uk1%P zR_G=bT)Ck3O-51R956u%?`4cB%%nZ8oGlz1cC$vU$RMuPX)(86piL z;~B7|DyWPTlY4GC8^Ms>89;{$-Uo`Jz-ES~Hn=9`ty;yHfD0AYT8y!T5O86NdcjB+ z$#Ozy2zDI75VaV0oZzB0sdXngUj8uCs$r=A79TF*sli$@QzDY%t09@~VtgOP5p)pM zoVi8F@NS6M9HTv)AK~R$ur-=mq{cX`jlfax7QCXGL70G3N^9`m6I>IOsQ8#WOSIhe z(ts6wlhM>3YjW}eL_97`Q%-P(n+n=kI#~x1PumY{V6aMVU1gbb+YlsWYT zP91-Uo15F%;ArY89dnYk^%bt{O)dF%&5Qsom2p%zd0N9ve1c|8NWt4yt(G8dq zhNB7HKGee<`uz^RsZiaI8MMh(SACZt0kKn5>I7RumSr?x%2K&Zr_*IH+GTz17&=vIX|Tc5$-5M$hqV^36-_my%s1Fr zKZy?=CewYUu8ixEoe~I0XmfW9d`PT#$*?w$O`#Ctu?HWOh9Vf7MX=1LbxRGwPcSxS z7mHZLm_#J-I3M$n!L`n{h>fHQrAB>DU3rcl-(dUZ9=+9)Nj1V)lgKNEAkh%l*nk*8 z)#IFtB!3GuLzFQ^QG*}T$qg7`G#OxJ72A~bmsS`~_sQ~r2FN?gXmXui*+Zv&y5$Dd zWI8jDS5b)&)Zv#7sdnSuv;kfE@4UM3m5y%OrZxd9SHI+gktD zsO*6;7$X=dz>H~{T^u`L6R;O76&0dmB=d-B%#j8x7NLiP9@OvRWceR6t@fGNpP{i& z<1~SC1VS*;raxsn>q7fcOxvIIZ=(hFjT7&hX(!%$W{4O^mUYPO5}{e5swPOjm&iOh zs!^S6$gyS#Lm$ph8A(I4V zziG$$a3kIwvb>f9uMC>3*3Q@)o2m#q9cKX zW7Oj%#?u{Ej}PYd+uvg2{>=;2T;X2&eD0}#LWhrY0>}41*ypoP{S#iIphL}n^Z2(> zkJtFepZitz$ymbiV}I^@80FlB%5DtDahvzz7o;}@QbnmW7d6*2$-AOJ~3K~y6Qb~QHQ zr(4v;b;ivW?7j{xgZ+M7?_SR4@8yY?ewIIaDJr=x8W`mTQq>gBGqu|&F=zLupT5NV zfNxtp6`_yJ;kl49<_Ce;$xuI3!S?+3a0@~0+A7cWnE`KDu=V@$b;bZ^iLB~0()mp}bSEb}TW1pfNnkKsF(zyH*ixCvAk9356W z-$gKwQu!`!a)tYNgj0<9gPmXCBk%tX&UDW6Pe1bp{qkdstCOtDWd;n$yY~>vV-#KG zwX0h=uJiHldzdFb`5c5mPMthQEP)byyBNH7LJ^Fv-FI^U}HHIeswfJmjmMlx@jkXXmI zu`l%u<}xOdyWSpP`^|kO&i{QlkGc950)4;!$TEX-DM}}V*&eBr_gGtB;rfmJgO}ag z0DtFjX1q2^Kxq>68;RCdA!|WjCFZqS19fuSQb1kWlQBEKR-qdAG)j?`kz`AZllZ}p z{Q$r5o4*z#e#{(z&eD%L3qH7b3>YlX>~C|LB|1#_@$dXG{`seWg=;rDK%b@MQw;Y5 zUU$GxZ(D{q=P}y44$TdngU)MFJv?zU1#-Y)Q19o2`rwnsR>)^}jxa=d!A4?10rWA{ z3%wWt>Q=9iv;#9shBq0`x!6YlMxz*c*4jTiSJ9!MgVF>1wVULFA%z#l4B4Ab*-uvT zMRgs*E`GEH41fwt4CRUct&o?;7*}Pi(ajL1umRkQeAjj4o;L_ST{?SvPS`eJ^T$QJsAe^3dK5WXTOck;Lp=5b2h6_Py%bffAo>ZIkhvOzIlc(UKCz><5l*! z&W}9)-Au+?eB$X}KLUP_#?d$$N8@N5jid2Sf#1Y}m3ju2%`B5=xs0+4k3WcBVYis1B(P+Wg7{^6?yq)iO1>%t7_U0oC$CZtpF}Df2SFwf0*CZ&|Pu zCOh=~!@uLu=1QWXL&T?f)q|U4Y9u6!BB{ZQQzXa=LR5^Y6t^jSCu#THPrt~;xpV9B zJ?t)M9k(r^3w}8P!IK1bmvftI^>3~iYOM%crN{x`d;!Rkm`fOeQ9->#XJIoz@QC%X ziVs<`MPA&B3C2VvsA@4+mWqjLE9O?Q^X=Fi5S}Tp+YCXPn1$LhvfG^I8EL_DP+em% zRuW(w0c9iIWDnX9LW3qHcm#m`?DuJiAWSfd^EJ*Hf-f=QIM!yMW4wzXYy>n@295z^ z3vxM$1_vW#dCHH;b=T}wdoV&cO_icJ+I5QlQGo+-U zL{k(kO0r}{gk=Yg6vto^$61s_a)8({gdjl{BtQTmP$C6#tS}0!$Wd&{p(RU{B_`q` zOQJ||of&fWo|&HMz2E-cUCvTfzx+{km)A372o4!AKo`(>-TmIX_uR8o{p$DK&=8YV zZj2Bu8kDw6Ho?{okzfcx2wrinq_B?8AK*j8Ny+NU3RXOAcSzSwz&JDp#FUh7ouWL& zN_CE?HDiC1F0@M0hl6q83-bm|fKi3ku#F&_#pA4vLh;z_a#1eeUvz=SUMMWi( z5Tr$=&N-=7QrKw*Q8hJjN;Aa!NYDvJN=n&41R|SsKH}^U6_1z-K?&kOY-$E*pbdsj z6Hz2N3JVyA6>tSi8!+Vxg*}PV(#CNnVpLc&pqq9?Q($a~m1L3Hdc~-q)+e_B^-D?! z@~(fOC=B6_Fem|{q|DvIVDj|e#SSAeSwBml^BMHWb6B!qTeedD>g(1*kt@ksnuw>v zhsd})M7>a(hRPI#5NNtFv20MLh^+~6!nE1L2a69aMpCmcsL3C}Bz3CVtccIK-)i&u zW09M!r1@NCb6w6clNs3mdiip*`EHri#X^;@4oqZixIw=hCJ-xx9R1)Cn{s`l*rkm0 ztWciM!_di?mDLr-2V)9^iXQ3hcuyF|x?sw@b;#l#i5 zX`rn;iYlRi(YL6H6gIgN%+$cId5kc*X*{!+j9;Zu`#NgS94!!{Np|28u|_dQlij)* zAry&_5+kZLm_%qwS#6TC(ZlN8Da8;WScDR^ht-m%Y3RC!;7ED0;_|6$5fjoHd}Nrf zQ73&1+QBi+FPd|SeP|GBGz_zaaL5h>i)e+UvX{mE8ckX!m+wLG>Ggb*jRRManCeQE z9wxeZHZ^a=&H8m~vZb?W7S1OclOjGwoh!>FKPy5+6r3itr!YY25moa%?okY4ErsjR zGedg4A%OzvYPwJ)>u&0_CPasr{*ueZavfzBHPD@e#3ki9YH&HDTVu{=R0BC9GK3T- zF`Ew-(J3+4&Rw>W*Cik(X?R2o&c4Cg{aZZl>u>P_&#=P1+{cLb@)dS?iu2|&QzlH9 z&;Z-rRm2V0;yw(=usqIabihIXA+B+q63e|r9-v_or>xYQycllK;~b~@r`dJyC6tcq z)5~<>3iq%_V2`l&Biz1unMc{=_^?OE9yM?c&yFdGZOAFnk;qGY$Dq#%GiEcE_(CYU z+q`+TYjm1AAQy|uyZ1Pb zFL08p9OE{2_}#n;>|^LkNy}qn=*7suT}QFpZ13S&dx48<$B16Jz5NWZ&KSj+HJI!& zuxDw?M>%LW>EXG6;r@wZYf{qyBYGHH(*@yhH|^z~|hZ?+Rd{F?t37OoKbEqVWM)i8I|eCF%FN%UyctXaArEKpz( z0&9bU%aev6V6`IpB1hUpuzudFuoQUT%NMjxBxo#cn~3p+D=-MHufJ;5C-eSRa!j!_ zi`&B*I-mL#0-U#f&W2t3z~0{W(11lgl*KkE50L`4=<{vf^;~{mJ)%KIL7mY`2 zX1{!k=Kaeu_&aM0Cc?+UIJ=-g>FBG)6By@U;8`Gc z_U7$$daNb-h~O#loB=KZXNDC!J;!voLbdlemaAZU;LfAYz<3AC^9a{dUNZ%jj=+SL z385NNbC|A^9;ehX0~*!{JhrjR^=rS6krUj@h!O9lnH+<92s&nfPyLEksGG=P*D&=p z6~{P6%3HtZ<~AGCz_r~mQ-qe9Ri5R9^f@S6*12&P_`N&sj=SUTxI6BSyW@@4%+uT) z?iLMVm8C4)ne=4Vr1HteRdSwBcmr8s(xvP-H4BTtIp~;6@0q2bx}*m7C)07d&20BP z%{A&E{hS$PP&(&1#=+vfW-8s8m8=BF8H=efo)xa$+^Tqy2|N3o;Yf2cW!%-T({%S4 zxXXD#vqruai#)+NdyQ=It0t)})qu&@1BYtPQ_`6&vPl`RnDlw$8u)X0V~`cW+J~?P z{`CAI?9Sn_%g5qNh-#WRawjm20V4EBPx?vQk&F&1c8lE?XDCZc-4+5}Pq=ccYk zBwweQMQmbpcj@0$d9$8!ms2LEP!t6*3c(vhS1IfT%3?@hD*<`Zrau~U?y3O>2q&== z*tnfvvq`qDp~ISFV;hRgZ2JEVjeWwj0J8>VO|)YoHBmeIJx7R&#wi$!$yUoz4~fy` z2ENTU&Hz8=w4Eip{d;1dKI!o50CHz^D*SgP4M<7$kem&?3;R`gSif(L!y1bdB$T1**U<` zFYlxA4S`p&GN7lAVogCSPZQY1nROx^!d?QDr6P!=O}tuE`zfnbGRIsB#8?ak&Q{PC zI6XiiNs?3{F!3O{7dpSx2h_Fmkj=r z?oE@_{T>go!q^0;g=ny*M_KhzU(hx_gElVB@5U}H<71WbrI&n!^$yTC%?|-1X?{`d z=%l080yP%XH%OZ@KttF|*~`TkF;g_Q)P6*02Sfo|)Y;+O`11p$jqG~+qr2-_H(njUzRKvF=?(0$v!)F2FrlZdL*Xr z#TdcN?6rj$(p;VXxNKY4aoFCb>J>Djf|KhP8Tg83yX1k>KTI^1Vz|ebZ+r>2dWy5d z)9i2U&>2rP=rNs+aoR%z6sBTrWdjjqcYlWvlG0h1+j8=Hgkzv<5F_HYQK{3KCi*p+vtLis^Be7sCxB3_f=LPAQEPmd*&ORp5}kx(KZu98 zf{H=y7BEKjAmzHL%U1ph(I9>Ut7|y=gwPS#PwT(B+*tco5gHfK3^NsS%(-+LlUsmT zLkO8%m>mTqI!x>nV{(EKXOcB&bR<`2la%@Sj}S4E)b>h;%0W`R#9ne{h&fhcR%b7{ zwWMRz`F(uk@H3ceNOQi;8RyO>Vn}iY@I<;ryLet#3dk^BTWJzOC}uluy9chpilZo- zg`fJj;W$x0&-;5Tw5t4Ic@N{!QlwdeJ?Nl!Jpwd$6Fr!QU3W?gc1vsY;{|F;JuHbUCH13 z?2`y*5N`2XfA|Gj9;7xEZJh9@SD&Qkp(5}QBTnGiXkNs}n*aT}#{v%l|Nbce1xDP&(#DAOY?0pQV zIAa|j{nBT6h$}?k468i)mPfgHt-sGaJ^F1g3JZs}~^r}5R{ro@XfScUQyLfW%6SSPzEw{?qH?2_&J@zZm(Na>fQAWnGVZ51h zD>1lI@U2hL4kXv*RHB)M1+(6PX?<4U!s+#O_V)MZ0I-<>Su--;9DMe7fWH29K-(GU+ea8u zNgoI_dWe$hP?`4=y4R^?xMQFCjn)HS13>c z%*vEZVw~OQEomJb6Bp2Rc82eW^QTIdW`)S&4Zj{fU{zLJxNw2p-Ca80vh_z!(Ir>}R!Lo>xb=l;P`+urDz)0C_3vS6|->3X(!<)_m4^zFIlY#5DL^JlhNqCByDFhVV$Kwl@e<(7(k44DO8%w)Q;mx}M-7V&o6OkZVW};(yur=aMwW7dmp@f# zG1A9MKV>n-v>kD74QqtfkJB|bKD}~WNg+9^paEkc5R*#Sdc@SIwFphNIgUh$7>()Y z2(+O=;~^3aLPOyIQ)Zi}WLcV&h8>Yhh#O%1#iZ1+lCbt@PztmI@#*<7YLY5f9THa% zt#G=YESxo9>Ek$?EG^k4#C_Dv>`@&UMXbja1{+sVRT{s86gfLq%bX_~lPkA4oGXda zq0v(}`zcQ~c#Kq7BU#l2-nYc=01aD&IHjXTs%#goVa^=ZnF201?wzY>n!sqXP3Z;{ z(x;txI-e}6RTWP_V}o@<=_1bbh|LPq>4eqw2DBkIt8`sUv{$gE#K;E5_7JNyK{1ma zR!YPs0*HxIN~sY|4G=FbZO=oIK!5S5=@_o`>FP+`f)~k;UdVQ#3CLp!P&621$wn)L zkckB*t3VU5=4^>I#XR3yun7>HS;S>)Qq^=E=cSPXiFpB0=6$cPx4{5z8DoU!RVAYejj%H(xO@i{ZhrDw#vr9*@7sMF4P3TI!(?8Ge-nlVI-|BUL&i=2Vj-86YHEfb{cnBz@DYF z>#VG=u;(|iE`T(&ahgDNQxalG^RDS5!P4tlP8~mqYGgW{()tDsA=yjIVqFzXx@VV_ zp6U|mVV*`7GI8t9T+>-}g$J3U5>qa-324j>VYL`P#Kz+o8;RX@GjK z6ELVJAVkFG^*xjcJf}tN4xQ|#@*x_O0itEHZl?h4zDixR9P}r5T*Etm^o`VD0pmK1 zQLqtFOZ16UV9Y4ls;i$n5X|E^R8W}`@u-YY>QpnSW~UR-7=V(}o}@4*65)qQs%I2z zJcYHMps&swkKcG>`)f6a(>gIz{-)28fR&;unAUZ&M~@}y12$HO_K{fPgTYvbUtK~ZX z=Zm+w0c_rCfyX$t@jZwuVC!T2+{N>pUtQxrefk!E?B7Cf?Jwd+mw0;otF(ND$Y#Fn z{u&$MEWh-{pW#2d*K%Jwq!(83Y!MhT7_|J^vmfPnPKJNtD<9&(3L)MAc_)|;;7!AS z`SRc4zqrUi_>j?rdDl?+WWVZ0sXgzsOVfEimu0cfw0#Oo#VG92vdK>!Kgq@Q9zXl? zRUWlhIPu7N{@2f6VY~b(x??BVzV(aT*!g`*MoiZ(@{2ED;pz_TQPH-CIf3Rn<^C@d z7%*a!XLx`c+e6;W1`l(b?>qIQtPWr0pI-h5=XjD$Hh5uYE8WP$KZHra;Uv&!la_|o zCF|BilmkyikQH!|Xf9(-#0R)Kg%3Zu#wvzP^<`(Cz*KO|tZ*h?;)mbz7XI-Qzr=`( zOt^>B=YA5Vf!n*E!-dDGnedCZ3triKiH=uk0WSu0MB9#lW0d{xB$!AXe;nGRh$T4G zC$|GjKNE553=EcOoty3BbeN~HabB(ib4M^;R`8CO>fgmmS95hfkLfpok1}o}FTQYz zx=l6GWSrc>oFql-qi=hJPk-jql=*q>GUPcwu;tC9zSiw(;nZxB<4!h~E!be#Uk7Q3 z<4DUWk&2cg0KR&BvEhwbU@X7R*8q^^bpYU5Dh4)d(3Sr`sD1@Wdm>$&yT&)zum1%W z<&-YYpQXew#R3;EtP!4^8I)8A8yHH4gFbs<3^K`NtR8TJ)!``)_HWX4qj`i$TF*l! zXQ#bjVI4j+^vWJ}J4JwAufo?&-k&V!VsmwT7LMRbbjsVx{fPXuHb#D^?hcG#NaswoIlv(J{dEv z3SP}Sf`9K+pVjUj{*3qWOnfgJ<$3m|d)RVHqf?@kn86Fw2md3;K7^BmcAWubvZPi| zhwy8k{8P>Vf9E^j!GH6_mv|8vR~1{$ALYApo1THGMhe~G0pMTzu0O}58}VCD{VoSo z>{IY*8b0^jHI4&kfxmll!tnSR{*&iF!3(4a7-!sF;P>vhJMNCV56;TNBVi7%scm~fubtkX6-;P#=qkKoMff4kTRn+5ILZwfd~at3b8o5j;AHCkCBQPS5dXNG99Ow9b)t-``{G` zLyY!QBU^hEvXK-_Iw7SzMk5uLb<_)13dFRiJp^s(0)*gE zdq~e&nod&A>I|@wC51VbX5uJq58AXTjbX^37+|b2tw%TuE4GKx6(qJ8zk{Jf>IYM^ z=hmkfR4c6Y-b)iF9Qr>cHZasjSgkHnoOqdu-JD(BImEhl=Z6}Ry;&cG=ecU*&@p{ z+i ziu(moXJ+5)y{GFU-p`cw38Gc)@G&G}Qmhts$y#Oih8fvqmOWKv8~LyVummKvCXT3l zkKk(A>Q?b!0#aI3I=nUX)+!pUsS1l|2U4Pbo#+KagJFeX@fNzSp$!Q@b$S+@63moN zrx|F@4Xc@IP)T|V)6G9ennUvXAdZ>y!we8iq@py@=$&2DnQO-~5hkx2Vn$hATjAS4 z>4rH|)F6dVs#KYvu|thX_GnUJv;=AKbZm|GSd}3!Zr8}cI#qd!!@ZBu>`Y;}&2)W_ z3D2;(-)H0wsVc*y9Z^X^3`(IE2^RH+DB-IBdPk!M5{Y6NJhS<_=XDp>H7E?|Lc#P>M^>XH4C9;cM*i;|6R`KZ9Bel{uu@NgV5tSq$;uGl2kQkL{4>2a7 zp-6EQOMz=i**eb8ZAdd-bW8O}A~9$v5!OKaDLR1^|6sxyiuOH73AOzG|F;>l%g;hy zb3_d$mPiz=4k^u$K#6Fi3js{B-IuI>Hgv>zK;4cBM(G%Vv{+Lj@pw|hyIs`eOzAiT ze*?XH}RvK%{xhV$=|Pa!2V^D}*@4go19;P+(Exp@_LAp2f2?M@SBd zl;_ZB5K|>*i5VPiH51*wJ;zCERx0Ii`&m{>IOq(1^%%Drq0O!NX`C{3j!-E&-2wx( zh1!GAQP44E$`mMiFsdthoaLY{nVQoK`VVk@yhFhbA}2Ar#;D!qG;6r=9&1c+Oetu& zhaq7yW>XyPWEYpAu)*2|j4OCy{2cE%eSsTSudxC2PMl`6wT)mANJ_u*kF|i zaZCd=MGXTXPHLKXfW@LkNsJwBXsLjTK6ZMJ+LjO=qGO9GH#pm0AiAoFXcMe#=^&F<&q5vkl+X%2)wY1HYL$A!}J!`Jd8W0pltP!+N!xY~s z$~Hw&Fz!Z7fzf(ox7%g|xQBhBt?2Nyyp^53v@i6Gr~%(EnPj-~BrV`L2y3hihE$U$ z5#Z3mGrEj2JCIS)(`8j1Mq&~Fzaz8twA3oKFYShJ5{ zhzVk~cG<}VH11<{6_Zxm`Avt+OMRQKA z$q_MeuBXpLK_OcaFV_Gwx3^ron5^WEjz9$rX-Q-`lD_D|Ba4#;`iSYik{88<0jZLY(+cFGAUm}o~`H>uh(V?w@93ZR>D=xuVB zzMya(xF9wAw{CJASi^FIi0_2K;31l}1Wu>9nH#`1$ad;`MN-|ONrIqi(>`bRT$?+d zF+EBr@F4-l7R|en6r_`qtX)3$25hr<{sS~PqA3#)Y?6BwvlyX}l<|^Do)I!R*&teE zdTw%x(IOr9?d=^3ad?GcuTNVylr)?MN>vUAj+bo9^?cl?HqPL;r<`TV%`ipBj+V2y zuu32h%^@Lfrn*d8kbQbFvYHjYju8#Q6xafuEdw`!J>X{3K+&Yn)K-LO2*sGL%eL0K z&uUq-%9OyAlGD7z1k)>M>RncW>F@w=4cnA-oFX!!js7n1dw1L&cgNjvcibI!#~U4H zks&zaNY0eCVUQKSWkxT$g{AIXdHM$58r0bk3 z*|{JtYG%+)M3&aLuoM3_@PFIt)r0ej(6A-MiXzbym$Ll^~8q7?2HET}mMXc#F z@!N++Mty3H|F@w0O2^3G(m>KAh1&}Jy zQrB?$+$q}0Hti@7L&2$27qQxL_2wn4v-F2UO0z-J9x!bW5LH%s16Ed6xv{&7v6jlN zV0sQUD|8{C5yQsS`v#2ZEFaEv57Dc1iYksw2T3(Ezv}x@r=hKLZ@`0 zC748lP?7~_6kQM{WC6OVgq+J7Fh)_y>f9KTNJ53EX#;F+f%h$hNVJ*&6iMpZE?SUY zdNxdxvdJ`OWK*C5b)XV*Ai7Q zUg<=L!DFjHD-%MT=EmDFfh49SGC|ZPEAo)mkj{>h>MxX8jV0OgJuHYND*4_}y!S-S z&$;M4FHN;e8BwN}2?HI75JHc-u2G%h!)PXqW$tn?n+LT@cJidTT9&g$bpfbaN%MY; z9yNlRNUKR9TDXE%J9=1*>xfZP12;M_1x8ECGG*3>SR&ElWCd%LAO$`!&k&Vt2R;LB zMOfsO=Q&>^cXR^dk##|r*M}oOmoELkER?Sb&IO`xu(qTgcUZBgHH7F>GuA315iuQN zCA$M8AXPDF)x(%TX)DIJM;z;)=N%7z2h+)fr(bxI5GJgi>d{QLIP7+jaurinjK@2; z(jq}|QK;*N?c3W#T7L1FWy$JpM)(q) zs{ql0sL574`hbRXzZ+A6aX90!)*?0~)>4#KBO=x*RuW+Zb%+&=MvNn`+eNZU4|xrn*SOg+ z=1yPK`Te>8d_^55T0{*!H^gEX_SXrGp(-nC^|;uhjS*uDg7`%(D?Ta7XT(G)vWiJE zfS(;x(7E#H+je+KPB_416`mffuzl`LeDJfMXFumq8WIT!pPKSkp^XW^C`ly2sWqr6 zpf9J`d^5{*4hM<1xDiqo8`{xa`*@H=^%{RC@Tvlm|FaX!ul*ZIoj-(|=#-rB75 z*3~s0c=RuEqS)c1fBb2F<;FT~9hveRZ$I%Mj%yUa|NQE0{`RqT9*{#;MJa$&a*mN! z^zfX+bAxRzM-MBJanqr!ac=!b5Gro%e2U0*JW~p`*^VE@#CKqNKg6`|v%_b&;!d-^ zGUc~ky2LeBc!lqvxAtx}>V{+OAK~^NXPtXF?WaQMU-c1I1zSGVaOUg8vE ze&z>$f-hYibK~kEyUj1s51ya6_}2-e5#zy_o6QOOJj`3qKFCWqe+Oli_4N-hnqKFx z{rGKu`#1l4RG?#*gX_ODhYmmV+>2ZQet7jf{^pHTkM@;oHT*}Ho@Ib#iy^QEoZ5GyWh^MdYa#U{wyz!0&u{Yvwd#g{31=* zgdV)?;P1Y?!#%*?{H}-j^~ay*1+H+J2k6tWA*Yz~5EHhz$|3*cGcWR=zv&`F)9}F; zZ}TLMG4JMJ(s7y_eBdvB4-+l<@W(#OX#5K_6g;K3dGpG{L<#Hy7l&`>ec$!{)Ww9~ z{KF3uVwDGz4U<~kjlX3p!uHr)|`$WSN6-?9btva7}1$~et^A=o+imK3J@X)OrdLfy#G zZTM@zURiK01w(0EiYovPBJ_radJ@^F9I@{BvG;v1fAB|tl3sG$FaUP)ZnGdc6AgL; zCN;n*oEsp16J?rlSW6(F+JNom#}nh29*So|9j;UF`Fz|(vc$CozMZBhmI1g4oXMYK zlXb?`3NhXW6EPLU=@Qp!R=S1+YgYNJO<3Cc>H>J1Z+A83k~))svPJdW{Hy9iJ>^t> zix^yg! zVsJ!F;J)CK>Xrcw5p`|;xdF<62_;I+z;^uVhd+-2R)FJ7*yE596*q3Dv)=FZXzN2P zQ~FqL+-x{|{0G>X?$E~1Lfpc36_yT2ZZiP~Wr>+a`aoYhdij2wy2RrpKz|B-3JM&x zpJIJdhCT}X?3+#@dsnCi%71Y7t^C)Qp5;1MIo$dJ)#;xA^A4=rV11=yXXl>*&(JGw zP`A&3>5@Hjm|z*=iy_2A+(7WtFyA(n4U`HkB^{QSEu4E)SOUtFm5ipFZ*e0jEwoy)L0-;S6OPy_F53_v zX|~TA$VECfa|a;1yjxY1^8j=9trnmIgkiD(jjKq#0h(-2#T}sTI@nz_h6IFKpR*pD z)Ufv(`J88E@v<#*w)dMettF$A+6O7~b!!)ZG3Kb+_ef*if9)pg>^$X-mzbGVZ$;D^ zbt+AX`K_=slMd(C#`a6NF(pw)qZrmMxsW&YPOE9MCQ)17|>5?BAhqTXY9f zlXnJWhogXXK3-zZUz8V7Img+jjdSrzK6jbXEfKLZg^f#gkCv3< zDYFfC%sHxpFv#bt#`tym@ljmuXx(!J?J(vzt~y4P9<6TUtYEBQbp;m(7=$vOqNi`e zIYZlhIw?0p%G);9VrW2ap)w(8R+j~6Wfzq{NI;feNtvN!i)nF0qeO;8wHR7L?C6;) zHTsK=Xp|WtUQIy7A?*sG3m_w$%h{h@fy86<+&Ym7KHetiA=W}s3aTY_J;1k;Gk)6y zD#(nmFjM3ut7m6ns$+_(gieVuVvWbxj)_iD6*{e{gQxLT0ujv%bfF^lD<<`Xx_+D} zQ$n>1g=1IpGs ztJwi+0zvn(wgx3qju4V%-`qa9!QjwfXu1hv#>oZ3&gQE;FWPY;X2g{Q(5hl| z2CW%_9L+m3Hi6Jyn*(h*-RUU zi6ucCQ4Cg(=HW%v1U6;DQ&Lq5qAuqjyE&m|X5W_Vbu|M#OLL(vlf0H=6C$W5hQOe| zLFqdBi4e-yS%Y8ivzpgwpnns}Kar$PjxEk^ zVB{ns9iFQwlG#q_hCe$FbF z!)yoHL*ifoz?$iz)}D3d)g+ee5r%lD3K2Y^Kbh z?~Krp8`zq1!DmD?F%H#8)F#CQ%;y{PZMiiW_Rnx_bd$ju!_6Y{YgZ0<^~&ej0uFQf zqF>s(Ec`ayocz%VXpygTS0N}Jmx)>=Rj^JN4j;fbk=;?BPd;&zS9uD{4a)usI|KrI z{PcT%5O?)9;!g0vm!IZKpSg|UWejV4wBDwV@(vuguinOH`se|$zfyAjMx=kivI^|$ z4St~bKHhrYJurQmk6hd4l?WPJ=)q(RlbxCU=5b&&qZ#tR@e_>NKHJR(=hxoH>S)3( zTKcQU*at3imerGgftR;luc^t-sYADFn55Nz=TouCEW#DO1RW1or* z8rHdTc@s-TOUG28GYP^$m9*-om3FNc`N$WZV#+G9`nP~pV2^GRh-$&5HLz`AGjH|A z+QXBKhNW*A4m&otl2g)Y`z9`&-5^~1EskG5p}6Tz>?&vBLfTD~0Cq1pog3N=k6EowaM%rT#TuexLdZF*Ifmp;1+vY@ zFSDM&3;^pg*}2VLUYdlBF2cY5=O5t{fATc97!aE(0hDw|4bCT!Oz&`h7M6mV7pdk>b${q*p0WPhwRKWXw z=+E&xpZsGyp0d{?)`3tfwnz$gA9onob#CswoZ-;@v_B>yX%#1E0raS+H5gbC`0;nW zk57H(GmH_`H}hvatzJD+KuE!HI{wDH9_4#>b{O2gO{@d`jbj`hPALJ{-j+%CR8xBpwch#UUeB z9&EjSaObG|JvNj2ARpFsg`?xzp@=*bJg*ANmo8xU0DXP=4p-Tk)d?$$)o_nCRes9r7EAgRg;7oE}`w1&o=n;23 zxSF?DXkQV<*cO+q?t(TrYOrpgeUGv3nevsIw?I0?=7YHEhOS?|LU@YHU^e7m>h~4W zFY&lVlS`zuAk$(LM|PGX^w9TIjXub=24IDWN2D4yml;g~OCwYR&L^CCEbU^^Q`a?W z9cCBh`|6|!10h1LIh?&f>WqcEjkgu!W{2tYptw2P4QV(R2~W<7?;|m-S?dC+3~D3i zHLB-B&az=-dQLH2AuZS&lh^j~sCbKCn1lH}Eep7>#nAu?9vqOh`=qm@Dlj4Ar zP&VxXRc)-+r<|Q1ak&2^(QUYU@+RJQ^lpO>i9WAbYs9=TnvC&2(x$gKTlS3V1I!72 zv>@g)wt0=KYO2F6`%g72{TcNr;{`Tx!HN^8jK&LU5tR-{jaN^wieMcr#IFZoa=_*4qYh0W;>;sD1{{89XiyD^20RtP)l~I}sv6^INKr6)oP!{9%nkT3 z?@;wa-ddR()a9X@J%D(W!G*0uQOWm%<4aMER3U(t(uawo(gra{c8)9{-c!4Z#*Jy* z6g5FS1V6&OXRT+&+3br`O$X;nIW_?&iKZGeatDYA+q6Kl!&fs#qdDznS)76*gX^_O z5m({!!85qDzOR0Obprpy{vS z%#p&H=p!OZc1m(_5M0ZAswOxKG&VsrlX7MxV>+XtepA8?ncfn5TrRHdvvy5zo@#Jf zL|dW;YQ>>l=EYDfz7`%3D%>UQz`zv6P$|V#yL_&R4yAC#@~A`wT;j&XA?5}gqmq0% zCtfSCs$}^IWGf=p&TLKwcx_Ao03ZNKL_t*6$j-q&o4zBRpA%73J-DjifGro7v?|#Q z6Qyn%nyN;(TXyExNcVca`<<8g$TQE7wI{XE9k)blapO#@=crDoT}{X}<7&cuvWtkZ z+?d$McDBE4y+H*nq$^QN;A2%w&hS zYG}Uean2FyjO2_;ITn`jJl9IBx8~a!DMKx67uC@sNDYs-f!_v2XwKP_aoBF z>+~rhwLRKsX7wWti85qMUkRv}WS1-3PgyUD$$+fxh6snzQ2OnLocS6-a6|Kw=F(IW zyirMcpPYM=ThptNGIVi`9~tJ#+D~&&qKL(U|J1xU;E6;hBlni*wOiimcy1QsjUU29NFN=Xg+1yoY2`W_#52so~Gw#ahxLkvt$A@jybz% z`Ro(V@%DRbggq|UL78zuOUDtrESZydzV_5SaOAB=E%xL!PP*dboU!Fv{30(_|03>5 z2#OZ-uyc74O(7iOXPH?BiNfvf&1Gd*5i-zj~Vg8lON~s z{qON?eL?0Wpyr}}4*Zi?Jz~2$0uDHi9t|1Nh^qN8yHi0gBC);0$ac7Ye20BJjt#ko zW*@q3X^fk76%~+Kk#vPRr5_8iA8-Kcnprg?$HbNu3RK~oF>uThKV-%VV-BhrC)5O~ z2zdmtWlY7GmZRefc7Q!#y*;IK-{Of|&vSI=K0DWh<Mo6>Azd<3#U}9b6RMp5h0*jw7+h0_f;~R$fs8j8t%`inW}_or%@Xal13w5asfaq4!dT>?$L^1c z`F$95Yz^4{@Q)$7Xt>e(w(N(!Yf&qYpxk?EJk~n0D6M%6fD-w`4 zHGvKB^l}Hj1EW1~XV7oiNnANUJA3F+H%OW3@;D1WSZKEg<&9vMGkn=0s9lAGpfrr> z@fZiq4P-MZsBsRN_!HK-{gF;zw{7uNAUOYkJmnlYXS!|s`@0_g-&+dsBx=A`tJ0)U zfd(a}j!oZP{oq&Vz-Kv>Z-Ci8KSr=Zz|_Eng!IqqAQA~VKJ=+|ZMwxU7(gf@5VAdHCA z+cE2YL^XMmdB5fU67D@U=B*=0G9j+t2G&>)hs{l@aLCza$^2RX*J5civ_?T1%mBii zYm*xsuV106jd;-^)&Mgc6EYVN0=Ru}TUtFL(G3+L#pytAW`fd`#`0lVszWbCjVnzD z(xG%DBFPOm%3wHgxk#s@!DP|)ATDCMBC%yQ2+6AuP)3YWCgyGFNfhY&h*#J>dyiW( zrVcXfz7aM-6XN%o#}oE)+pE zZ^!ufai-xWsw?{bebk*XA3ejg`ZtIgS?d2zmv2+?A;!&h%=au;$0S|SjKKLVZGVAU zN2rBSU6XSrYH`dN0r3tIha=-n3EogqqV*+z$JLmX;;?F8iiTQ>vQ?Pis}U(1UB3lq zRN|=Q8qQVZd>`$FvHK9S*-h$DadiAT(o{Haj3+l)tRawT$#>o~{1_EWy40f1&s96ZA>u^EoH$SHTj2 zlCzp(kNGXV9C2@bO42nUfFJFUEOF6a6yd+lqzK|B;2Ux%*v+aR<6Id2-BVYQuG_G) zyGyj5t~sTbB_RO0N4gbJl~wIZmvYuph_BW(z9wtLhYD>MG*wUUjcOV=UfpIkc@E7D zF71-#I@z}%?;u2y?qTM^M=EP*@*yNg&|?}m;V?W)Gi!MJ_{${MqBg~e;=&s5GLptf z8i6%bz9yv}vo*~qmS&2)M^o)Fp1|q(2|~@ay+b^iv$GSnam{G5Llx)bb`8@l(UfWR z44dT=8AY;gK(-{(kP911El7G)V?lLaZWk>NF0zAy_|#?)TQgE=L84iv=|%+cM7C`7 z9LtF&Cq@x`m&Sdvjsi`a%!nVRWd4*Q2Pnf(Ug=D>&=SFC+3qK+D*kWty%h0qHC%2f?6uX z&xzZHC+8nwb$-G|-)B}`<)Ynkhu zU^TvSXy>uTglp9mkCX>vs^kz6J4iEX>2p3R`H+4e@z3MWEmr-Ms+ zMW40==cucSZB%mKGOK4LpHMqu?wC|c+qU@m9&LNUsOjkXEzS4|+Rc{T23!hkHzUZN z$t0pKv+b2&!q_|d*b&DO@5j_>520qml2v=gY*IsZ+`s=CnVL6_kI634_)SUJvN6dT z5(#m}I2Y7y?_1P^NKforcB&mNE|xrXu*2Qk-$A+)?l%|Qdgc=xpTAS`jGHBHl;~M8 z*BMniBIU%hFFeB+zw{=}OvzOT6||jER})mm*sz^0rpKG|z$~r~5LG0== zaYGZykZqcpf-X0sa!M7TT`Ll=F`rNAc%M!;#JoVIgf1FF?S;lWx^*UqQTrZonVgNR z#Rb|_HJeo7+&&^Ti~cT4{uV(LOLxgOAz7vwC0y9h#h$DVS6RtV&WePLB*RjXaAV!# zbxM<-z~gD_cQD)HV?*Tvop8(3dwQt#rznoT?>=MEPFA|rA(%sKo> zS;TwLYzgSw~FgvgM4O)RcbbA=)ziVhj3528%? zz6|6?nk4@@k1w>5m%9yLe1F3R_%omR7}smZZ+!K8Ty$qc+0{MR!^p6f*Ze>zxKv6s zQwt@x86|O!@(OUw(dp~Jhwzg>LKwY3?Vl&>hH!Ym>ASy5BJw}K{3`!9U!($l{%8I& zUwG{f@2$>QY)+W$JWX1>&M&_3M>*`zxW%_o;LqOj{OYSqeh2sq&ppGxe|U|htI@ru zIdf;cb?Gro#|4ML zZ@u{j3*P2^{xt8t|1v+zJzRW~=lB*44e#Dfz?iD~4$~Wv#XYFFL6h!KvEjpV#Kpy% zIE2&vDX$(WfB*jL909(7Y3NG-DLW3HqUU4&NiIfvd~N+*E>zIY7^lmtb4(i}9V@Q8 zl1Xc=@iU+KEN}85{=1j%vA_2MqwOKLkH5?(sY(3_c{ueI2b@#!`P(P_=|A>wbF)+a z?r(mZ)Ag^jSbqsP;`Mv?*x`(S?=wF||GjUqR>(U~bDvkad;WD8ACL*05>b{U9IdXA zYRdT9g4Ko6Z})&(+`RcY?%w?-eF@(nPm3V(!l!y7he1s#|HUjHNXRIBy;Mlh0A*9_zltKCm^| zCK%I`5H_X|9OE#i-FA$q%NmZN+6Jkq`@}daI~36u;2(bb%WQ^Sz6!8W7&(Z=bt{7b z_NvYHGC}A^&33)Y1-{Hcudf7ftSS!0JOiEpTC%RFYRG*B)C4>o70A=2Y0w?f>v5?8 z_>xt8x`0DqR1%_@RwF+3$wR*P>i2kSbBgPGG+$s62OavMrgSZ6c^MSMj9@tGEA%oT zBYG1$>A@mX;4qgSk6(THyDWe)LiR;?FFCXo5nP>9kS0-^gr{v|+P1A}e{CDnwr$(C zZQHi(Y1_89|Bd(~HukD+D(a@e{3ENE3s2A92V}WB+?-_Y-94w<9D-VM^=}tmBiHv%Uq8-wu!rqsXIz%PFB{?d!(}(Uv%0oVKinfQ!b{?`! zO3qNMGjg(dTSJd<_vG2fMBXq&o?qG~U{1vc0rmQCxj<30v?*0(J z6yKgfyaMc*`<|{Z+O;C&mE-vsb@eGv_p!_LM6g$hs*1kH&T><_Gp)b>xkm_%E-qYId7jh z@6NRAw8!>`5q$l~sH0XPd~|mh;&#c;1HS4_g!bOZG0{x9v(p1KJHTZW)cNUU)FWL_6&BP|2rK0kAB8?;tnV4Ms}^i$>r|d zmbZf z9z&iWny+GL8Pp`|2!!Tn5m?-x$J2+;!w=L|#qlDYEpCk%J&DCVhgQY7rd;c5X5Qgn zCn|i!Ov*{7lPx0zEuTddDgfpzNHLw9KzrUnrjj`zy2>zGM4j6!cH+#1_E!2=-GEgL z)WBdF4I%)#(0&k5PDr;a7OE%(Y+QZ7-4@C*@E*=JQ)Y;8Z6VlHI8eKR)be*$U|;U0 z^&iqgI1c;EZfdGC7_kN%os+zNBtW|qAJh^-;SRw1p2uHhs#ZW!A7zJ(XU_#tj=JHZ zZu9+@U>{;W=J`Y>TzPo3YY5L+okJd7R{?jpD>6rYT$A&ADPe3jGlcY|;VOvUA8 zhXA`cEYm|IiF^d;w{>))Xe!pC$zsxu(rFX1GBq$We0fRi#VP4-{G4S81zJWqskmVx znq4;PnZHMP_z_;okk*x^8QIPJzGra^)Ku7xhCR)y=@c$!)uN6b%k2Oc&V>waep)kCIY zn2F6DN!3H8=tMl+;u|$={T}$oqHpYcr0Z&<#h#k_I5a+)7)C%8Qc788o`BuoYQ4Mx zl<@l*&=C6QD{G-^oFfnwbvuxFF?2#|_&$#qGq)iAX|QMOGh1_4B=iWhBpX6{}PUev%oL1FX7OK%?M)#S!Q=8Um zvsX4_ChZ|RZb=}`I~k&6!jQ0bQm98_{9zkrNHMPG{O2S-c#makr;;t`9pQpGXuwpw z4ct~74_)K8kus@EJ-X1(WmIq*S1&iu&AWZ0j0(!#nZ$Rd5(KD#oI@jHM2T= ze}FRMu*tgN_6(ESQeL1E`D+W9#6d8_Al=K z70wJ5p=CpNV0G+A1toQK`me60+BZtmNVp_Xg*2d0!eWltm2Q}i3RpFc{s{0>X@xvn zejKtgJY86Qn3UCJQe}pJV~+`mk}=GLX{GHxw(jz4V!cmNm9sPdQ}3s9FzK z6|#{>m#>nJI+!GNQ(xSMia_UZU}U>21H+^pdD6bu>Kw$oQ<%7hYd4CCua9J#irV<0 z$j&RUL8r#v^E0_*Bv-5_PPY6Pc&{feQjgduVuLYtH;T3+y{ zuy^l8x3SR|cl+OAkbzHg~}2H1T`XOU9xQJLY@ ziWn0D`21*iMW_Gtu3+$e1OL9h()C1m`Loz5I3s&c$U8YA@BKxN@Pgm{wo+#H!clW` zTmj(y2%D+r?4GK@!JotJ9PN_c!(-UzGZM|tGne&!=9kfRk7|EQaeKXxF1~XzZrmg)e!YgU^bRM zqW6As>wY`DzGKsfzIBw=UqBlyK8JtBuJMXkQJ=r%ra`}0$vGnbz&}WNl5y4h8PqcD z_Izde^m{bYxJI{N+)mYSkbO~3n+j-y{3*%1&V6a=s zdxbcMdYqb#;jvurkj&zq+vf1~p~!v_=68TkGPv~qjhI03tLgayx1hZmV7yso?;gEk zzd~~Ji`j4wZkhQ8qNMH1*{dW!%_53_A!SLEE}Df9`xBsD|BFaLK#H8^ZURT>5K86a z^*7&yNRW=(X+`Gz9AnW6<>s;?vTcyca?mmhhe^i<^Vkj2Pj>a@I8~PHBg^KKs>P34 zmofGv%i%-<#`PRTzfgWqP8uPwWjjaz7!mrhxB5$=&EN+20C$vc$ony2(Rx_@nbm!Z z_$Zo6DOIKMUja8@^W)D$UD3*Sn6abK_HVzjSAdA)q}pA?_u0(tw&xd2CWYs1(Ou|6 z5~pG{O?j2g5#wglGU5#AAA7{Ti3{Z2Gt9Gp4n6&TUTDlk(NC z{y#5HS`^F$Jm_VF&+B`JJ{$uo!I6vG1xsIX0E)w7x}aBT+^!25iaf%<&XD;5)T(t< z2^}9hYp?GOD7xustOozOvGvhmM@?D(%vD;SNQ(!_Z~8yg($$Q1U?oA&HVDY z8pr{vc;)NFs%p!ycu~Z1m&wNsdm>*dS?xa-Oxde^B1p z+=X}UrF^mS+n{tkDoo5n{?}T#jaNIPLlQ`SyH9*Y)6?tEu1m@CNUwhtEAA9yqzy8n zBoxT9N{Pi3ZW1t`49UKK7iCI+jV>-m=QbAB$BB!_b*vzFQ1+mQo*|6TDrP^65ZjK# z8V7E`EoVAilio#iLq8>QVU6x-?3lvG`OUKZ_Y1hhNq6%bjV!@L?FI|mJ2QA@eu@3G z8Jq1#<)(0KykjmO`vkP|(7E+LLY8vsPxyR|Tc|#7!|kZ=q{%t#Bd8X*$>db9D#_=ILt>bzV32E!C3i!+)U-6`?8Q0%;$cX6GG zYzP6S`M(YTSMIO1sOyOuuaie;#ZiQ>G-{S@h`T|$2+3+(X9_^`wb7CK7G=es9xDA3 z%0S}O&!4l74PgN^4Odj+PoTb60f>uOM`8q%!zDnl9fmW++YX;auzsEg%lB%zz>Bh! zg8Gg-Zar5-gvbG&-QD?66g5&3bon1rzWEx4Q^xY2??6|){@-pB4Euyf1rn-gGlvo| z2U*sjgpJMEq$f*oY;1cm~Hk|D^M&06Yo& zHB7-`7(8c}FB*CM0`xhsK8j|x0UHN>Cz2AlY4)f@Nq}Ii2-C43Ei3393vb5;S|NNk)_y2M~ED zewU1C$k&2gsM~EYbv-kPg*96oP)$)=2P%(jG0_>9uy#Si-^Uj9#!?zPyv0C8141X4 z(lq$;@4jya<>jINV@y=kLa=4-f3?Zn3LHcYEyTH~h?LPVSNtRVuPuh%QV`+As>z>DV5!y{EzKQ=!nv=mHq{_+qAX)bwt4OeEc+wa?=eNeqkPzo(s&E&h zH3zaI&Ww~lpS=O6Go->XduN+C^8uB&=N0+Ds<3H*8^T0m?1ab!G(kQPjAT1{T8}=Oa3C~PgX|X}>=gq0~2CC`DzFkop zewT95;WtBirdvaIJhB_xwI6mf6&^K^%>hp4`C~m;uC-@9trkf{EQ-{o7Hgy!+b+=; zDH($T7E!82a25`kD>9G5K=>YfVKDZ4JT7y%6sk{EsW0>t$J4IeoJs6YQ7=&mg@yjO zl5&tL>67GJZXg+hgoOEwdLWoLEFq?VZr1joG!C6j2%LRueg!(j_3W{InO&$hYXSF% zJ7wfhA;&f27zJ?pjeaSdj2&m}L^?}tr;=$6+drVNp0=kp@gKooODadYt6+ zMjSC<#KD&_#>~3BX79oW|%H3w)=y2noQMbE0^+3 z@0#~340an%E~~3rn(h3I`Fw?U4sx;yWGA=bDl?}h8q0d(8O@VMDGZQp;>cr|>X9_j z*_cGp2by*Z?eGiXg)5T9O&zjD8um7kg?VSh2{^87KK`d$(%$eHi%tM& z#^!OHnv5j@)-PC@h{53P^Q$W5f77{v>`IEM^g&T-hLm;ov^TWqA4s2zTi5uPV zQ+22JEd&37HlUNYp+2tZatSzwGvZT_A!<@d3;zu-q!Y??NEIk1ozRNB`}l3b;S=sU z%UyZ+69%*8Z#BS_R21xvHW0EuKIBXd#GxM7*8};=AH`bcE|rm>Ix*=fKE@MYCW#Vq z0P~XxSOt=yibNM{W!Z;5^%S4Bv*7x~Q{y)jhd;)EvNISwa@7g2z!Rf7fc&)?pkIyZI$MT8JVq(P=(v1q#T$8f{7M8#r#Nlu)P^8~bP&->c(l><=cfQGFmKWlVasCLML~m~L z^aUqU8(6ik)X$?N7owBnm84l+{uWfDW$!?LDhiu9ddo9~3*&QjAzeNwy(Q+#0sg>! zl1miQp;;@2JVm5I&F`{a%ZWe#j~mPnyKJ&5{rP&Mm;?gf-qu#kq5WvDdlw@?ol#&d z<(+$ujI9mw%St)Vpn#OA+bQd*QEw3dn(3;ZuW(Y zHO}c758`~#gM54Ne!tYhuSOs#^tFJa_=3^cy?v)(m+cy-tDn#of#Z0-p{)(NG%tu8 zEW5)|YC2I{bx~3DuZw1-hi2=T|8;yCBlxh}5bche?mQHXxjl1;^^kx=PFQ!;p@H*o z%PP%P?U>1=U&aFsCrEZ)hAanULVmz1#_wz*vb=oJ%hY7W=&pFtAsaVegDzfh2tO@g zo`v0aO)2VSivfhOt~8!<B#)r4JVEsRUFzM)vhp zc#hPRB4~&5Q)3E@HiUT*QX5VqRKuoh{aUptJ(i%s0~8j7)itAt5{-Jzv;>>AuaiH) z4h>;^XiDn~q45t1CX*ib(Cq~7S#?A(*rAXl>M(?wfI6K=nO5vl4I~2V%$u2Ip7OzL zwc$-5*UMD9gS!~Ppz-mYnqD>ZLg3|)P_$XA3Ote%jPlaAIJRfDcY@J*o3t##1ZSP_fs?{pes z=?g}&$jAif+uqR(N+Ood)R;0&A(z7{6F*MU^(k?e^(mcfJf46yqUq`&E!->$0~Na2 zgeiD!KL`2z9{pdTUUoUK)XPL;NCeGU6hG$<v!PRjgPnBQ05q$(Y*?c<5Ms?Kpi+F;fLr@ThzYWYZg+RiD zd_KkLWMsm~uWui&B5)MyE=x$N@1I20bTw;@{P<3DP&VvSBs5g zqD;n+Ty$l^>cVPaGIO?z(u1fmJeAQ1fECgoP>mdXI48l1;tZ|8vTr`Dr|$ML!9@pG z)Af4qWjA*swm;Y;he>=s|DVHvFY4A-we0H`Qp)vjs~XMv-H_11lxmG{z~KG_+ouwn zLrO#!waGt%+P{iYLjd`OGZz?hwNF6A;|+kX0rqMdfy?XCJcY|}=gigioz193_Ysi) z7@PC%MQ2PcY?o*W2j5po{K+iht*N0}UCdEB^W zYbI1r8fo7r5^}A_2DGkgNRyfL!HZ>UFbLN9Tfu+zPi6&T*^PpxAQ$8t>Gm}ELsdc9 zlWlyMvb2J*<`^#Xed#MuAex-TZ2Yv^S2S!*QXbRt$SoqdHLh}dxI-*{__xo`)gGq zrrV4>og&+YZ{8Z=Nb?2rzg_CF)Y%TPo})`~qhW0QbOpsvI|)RGHfFUi*h8VTU63k* z`!z$8CrGvlndfLcn<7Tqh zwXRV{p||$sL9iVh@|MQ_2HI8lKyzC34nzR*Br~H4^g^378>6&GEVYH~^O!8!dl-R~ z8OI?j+8uxq1_c)i-`VjJh6Gwj#~^kss0J~IKffcebQ7@_S*I%-CKdJids%RaZbBX? z!I*}kh|o?H*gjcC8D|JEB0hQp%$$i0xM=lrarbGq#dcV8dZe&ckBe@Og)SUe{V)-gCiP&S*B2fl*rP zC6`KECYmGlryyi6l*xk@k|q^h{F6B8%49OLO+ZF$*r)1e{>MOton{}K1Hnyk*QtMN zH=%L?Ix0@)PdWpOt{TbkBzd-HoIHN3*9TUU5xg^*Wq)|VlT~FDBp%8MVC=%GUY`>- zZC0=d)5(2lQ4w#3%dn6-32VRHl+YxCSi9pLdf`*caU)JGws7Q`_(^o8UL9)!uRULa2j^c# zKSLI2DoB>F32g^u=TVw;U91l>uWpAvPTl?C<51c_BnQJ07CNY~Ap*hY_uiX6VoPT* zpg1FG)~NW%0SC$IH7KFHMj~-W&{8qsS_(h#{yf^1pO;84^#>O^Z}y_)OfOE->pg>3Bj>Mo|)7hz|_kT ztkTJtPb!Sr!~ZsNvU~)eLnhETg&uv&7LyQ!}l|P zBY4>0Rhl`kJbQT`XPUUByl)jfXP;(!&C#UCvHbl-Oj;R?5y=RzOO6=7s@%uHwpL1F zl+dc_9JKQ*Y21IpZ_so6fF-^~PvLW@ov0p@PKkx`JswuJ9WC!d$8Ld{2pkKxjxH3iY zWvclzw>(pMYYb|3DraU5(o$J~c-mH(4~7!Wyu+Od#>-}5-eR~P^jK8x#7)6~r?khw z#}ZWQ^kNAbftuq6>BtVEr_0wZ0SPN`RlhXKuG}i=9k=l@5vA4*Qus?i=4?spps%q( z+E$v6P}8$|Di7caE#_I2hMhr;TRewS^_Atf?8XFrB;Uw5_{Zn^)t-|4-MA-=hhvbB z^A~bPuM77Zp7)oej~Gm;_RtSKh6yNm@;Q1Q-}BcJTcB%n>lgRP6cfUhH~pUuX7d$a zpKyl``n^#%lUwbtPtmPD(d=)E-@f0ckH;@_3(pRn6!X))T6#vYd2Ri_tG~5&?3@qR zIXWJ^G}Ehr)_>vfdHrb!GhwrM(P^G>(0}LlIh{laoSfBpv+cNV$6wy2Irjg!eUAt%MTfSzg zYVTcVy)*nlT^w{Y7>M=xIAFVJg7rmGZJp}#xjj+G+g>$j&^8GRub4WgS*TaaD%oMS zWZLU#w+9W_A6%pqJMplbLi%MvTJkn zTj#~io`&4d#^)OFadFH$BjdY3?Q&OzusO5-<3{itis5sK`x^iB9Qg?`m+(HivCV0= z-3ar~ogY7hL#$b)^l3}Z15_9&MC`zo7KKCx_GygK7Cu*A<6L@Tz7!^8eeNio89^7w z*4MbyAyrAr90j6g_a;Is`X+br;8whPDF>2l!+ky$?`i4;0OR3Rrbw)YR*$G&W@~HS zQDRXQz*WJ_y|S5Jzw4quUXBz$5M)2e$j4T%@mfv`r3XxZX|$Bq53)!D=XUy!c0n-JDpP6hoW>Kbrvzsh;&R>3Gm6IWbb%u~; z<$2cMeBbTc+d2Ju!%BiYpcCk(lgCrd2YjWx z?S?1u?~PPW2f9(=YT=2Xl$O#68}fzOX}%=>E?4YU8~{K(C#Z5~5{LAd(m>c4B$~4+ z9YrvI2Ls0;+tBAuI9Me>6OfFOb6v<@Ib=j9>pa_A^EFL=>Jk{OzOE}c+%XORvaR!O z^ffTz6T10z`LU7EGwC0^-{o7i><0QWhhoBbpYFrEe()LNO>2pJ*s@aM8Hn-%Yswy) zd2IeD+Z#2iuBV*x5bWaMHJ=|c(=Vt1&%=zGqTojDpYp4?O`gl1p&yA+N^^N>Mlju@ z!FPthvF@p2PL35*x}|%3{vh&6PTga*r%2oyPqG&?xN@FJq;7_ho5z-iHg6v~3 z=>Fr8`Po+0n9^}d>jNm8l#X%dc={91=h&hr_#WHkW^N6MPU<=A45smNfqO58(FE81 z+K|mP_0=_m^vH7?a4oWg&F%8Y%+2f-&7)Yy9%y1>`*oOd;^bumziRyJ5QK6g%WJtb zZOw^Fw0?P7a+Z4VG?F3vc4g}ePlgWvI3VW>&X@$|*0OsBl4D%G|IDk!cU$99rDMsu z>3=U@aQ@vkV0YeNrSHav)t+d!sTtu$cjzNry1;b&myYjUc!U0>8KC{`+WN2fzk1>d zQFlrB66;A5z5fW4)G<@7K3bvQq;1W%xK*gyX?wk6bb%GfWc)@c>zUQW{iwQ0*D zae3_OB4QTmQ&JirXqCiZjDyZQgGmX-^{ziDy>+GM77EOUUKi}y1B*{O37s`oAw$r_ ze->*=9+&pO&Jz^ocOU!-ofp!{r{FgiVvW7bcLKL_ZH*K8hu!-}9az=#;wchyOB6I{ z-izcZOn$Ubzf?vp(1uK6LQ|(e`P?)*K7^U01Kb zteY;Ryg#Eqltgmfur+Xb^sFR|!Cc#Eqz^V;wOP#kWPYYh2tCJrjyYmGUj=^!1N~Bk z=Gu9J3Rir7)vU`SCS;59H>Q&Mj#i6X5Z5X zOdeCDMA6<|lGaD9Qgaev&lMOor%muiddXmwb2L%{N)xDSkod=@`}6liY+51H&?vZw zP@xJGMDkRPWAb*s;arq6odbiu_3)j5Q#_Gq#3GVFuS^Td2ZBevj0A^p(tCoP)DHfA zdZchI^l{{qf^eLD*6AjiM1N2I?d(FxaJ%j(W@sKhY0MuYmT+c`9BjOksi?7d`4hHK z6hQPH9ss6?1p$|0F5S~f|r;xOh0EhyCmnC!9M-p zA8zIP2n4KcWeoQN*$PvJCajoh?mf?bf zF?gI{O}7nBL=S|Av$2V>pzVqJStip&C6PkJkWSIEFFkSjH1gST=4XhNyCxp}1`M;k zEg^a92mC)Li#Cjw7@mKpol`#Q3Zhv&O~eq$*Im0{qKQHtqTipgS=m8Ji&)6y-s#zY zp@g8s%$Q_amyW9`@?e- zjb`dMAvr=eYK@$BfI_Mo`z`?)g4BS>xCQpsPC`AxDkn#VD1H%mrW&d1)pSNaWi!#w zCEy_hKi4<(j2vz?Jfz?#!IeCi;cb2Xy&8Xhy?8QN<#tG`(9{=x;S^;sCsRiSB7qCTe_n(TbKvnDEI0?lk|r zusS4@AsXpy*?@@!A1KH}p;602*uwiC!w9EtDSf=>)HgILr4(2Kt)a|QFoFY3Lm4G^ zmVrivMIedwQ+m*qrAM2QU$D@q{9Uv7^_5DL&g^jzR2(G8Lv~{Cc1ba8p>g5<9=2kH zb?5J*b&}NkDg^gB{api9B%X|KvgQz69^o8&*!pBnt!fYYC^ihwA|$j3-jNk8?eX`hbaO zBIJdG_{D5KTtZ9;a0h>Lsfnr-uyP)%5Go)0$Z+t|EZQgvC6Lzum5(~eyAv1Sq*AhW ziZ(&gkjk0POQ;5kNoe?D>ni$7R0$%u9DNW;SfILW(|?B@sfqx*z{7#WVGM|rMaW(- zFqAA%o2Wi6G>QG{EvM^9T-Vi+l9;uq$xxTp6(AGbw_7(RADrQfn6$VRjb0+znKB(y z0#XcYSky-s40;9pS44BfE-QRrs2R#L`7^BGfKJdZ^Grg#`A%zf54MhTq;>58BDyQV zV2Qf&!DMwyo%i9c#sNqTh-~s@@D)b$Ec`*|y?21y^MD24{jP;`2`#jwYKRfEOCktH()|{gRL6LC=XAy=Iw;%}Y=UJ2K9j%UG2GxW&SMRPjbU>1Wz9m|3fu4e ziDNEW9e7k5sLQ_!w__omc&ICJg1oi;77OuIkwHJ`+UJ;kcH1ouaoF>^3!$N?#PhC5 z@}ucJrnc<*s6a=hGOIggGpYo+PPK-S!g{~Ec6_9|r*~!hFl%b9y-qvQF%WS2)+D($WN zMxOR%!|L6GQUsLZ*9XLw@R6kVDT20v;~k&AheyCat>Yf=J?pDh$2eo9n~jQ^+A0m` zQ_WX8tQz4w%zZP zom20-L#|6=Oe}mNV!Y4T+iV`K9st9Kx4g9BwI>Z7w){{OTeNXhEhF#jswU!v)D*m1cP^vB{0Fu#UhN3cgYcO*|+e2ss2AdaB+@W&DCzeWh7O_E#8X? z5ht2rAtNbKq$x07UWD-!V##Efngl`8VHFEGM;TDu;QQ=keGFf7j|jU&Cl{RV9QqDV zwKd-)9>%)YC5i2^38a+#fRu*ccv(58NekX{(UcEj!;1k55!Fsw2gP0{!F2g#P|fGPueja6<%bBK`Y8Gwq*q0X!tWBo?w}zln?$Q#7 zdh!8jha+1NvBt$tqEmp?t8~AY)ZVP+Xr5Q@t=F7=n$$mKAmL0=TzGqj5fW?=It*?= zDnRy&RCK~<%VB1q69CuBjfXh!*=Y`Up;Kt3J>ZbVV}Ip-t+Q*w`)t7-e3%jL@#^4` zy|>kUG(cayfAi6wkYnO!tg7Yb83~(R#P`nAy&pXyANgXVy=|z=_gyw4$tB<~iRNxxN}pEzKo)N9+iep(Q^{ws|CqmQ?h-l_gHvX{DU7kVb~oi&|N z>mV-m;Q7jYG2po4;2vE#OF%ivaom^XVs67eb*tZ2{8_R&;n#6mnAwD;p7+a!kcci+ z;hvmA@c_w1TL)Tho?urQh>{$I zczCK9@Lr><;H2Vm!Y!h?KQ>8{EKO)W;+y!KRQBCp;a$rt{#_#SRpI&rXYoty0$~!z zcT~yqYT|K&%}fF-g}bxRSn`TX)7rlLRo)MuB74D6NbLdxghok~sJT2(@(Lu`S#(B! z1x)p=5<9H9XhG<3Pp}Q{G8<2lM(B#ZHY}UJOa*ff35h}c7A=_cWHd~r{qSxOzHPC3 z_1x-I!XuN{dlC`QbVwxNXlY2n-cdWW+3Ihd)_yg_j87DIyz1HuLXwcVO2J`XiAs&u zQfoSUYPXPm{TtZ^NX}z|!P6->);%BvjzoOA3e}ZrMCkJV@xC^=5wrOulvhGVxkT^I zS?ZR^>nlcvd$(z#O1Oz80WP6u%T;LM)u0=n;Mg-`d;Jm~u zKsLB!4H(=}78D_1ppvyPQe>c>L_#P0kzF#JsrB{%+p?Deg2B)z9;F*0MU+pWQN5Snc9RG29l-7%`Ax^nELb1Uiw!;+4oIsblAd1!D{KCN|@FeQYnotEK z|Dku-C{gM7)PMi=0)!36?fV1fke#HG+ewB!>kXGcYufFGi2ec7Y9DbNno7fSl`x3! z;zT4PS~%WliPQ-sCWhSQnDl7%Yk~MHqYvUOi3k8~>IntmAd(n@K zK?}&8qbtyEe3u zk?v(O+Om{42ID0Cmo&&W&;f45{V90=c94yY70>oXOWqm}VXfTe}T zb3XV>oHjBPERqWaeT_<%I&DZWP!XRi zT`wK8OSaP@yo-R#o#;$K#m!0;IofY#4_Cb*bPDE#>d&EMJjdl+SecALLkJDikqxPY zjHq0Aj!!FJ^g6}{uLHH!QT=yqYMaF3Mmvrf=LuT3m=W7=^eeCm6M3(7Sy8TYEF03K!Ij-g))n7mmdR$kFhUws6;enMiq05L4$CSoF) zYbb}mR0rXK7%+NbZeedAUOr0{N8$sbkI&zMgWo6u6EU+mm52Xi7&S>;P)UGF7_|yq z#Wo~g?d6+%3C}1a++l1$R7f=>vy=_vOE^hZu?em-NX6xgT0=eKiP#5`10+_sj||QugGr4$i`-13wgCx7zlpeLY+iYH1eO;?9t42K}GK`(%{k{NRJ zf!@Ft@r-CCk&e(ULC-bhsB51BPWqS)$>HA4$i% zc(=HF<&#}QB`al|-ArC-EWfA=Q|`6MQ(hn5K!M(-c==rWZ;A}EbKH3E=(XK}hG0G} zL$>Lf1t=?6mLejb`NW2)KUUYTj!<-hkNt32C`3lQxH zEv*~uFKn1L=v)cB!+fq6tu{PP*;D@o=it;ZUqV0lyjvkKcfK)AQ1>HKubM~o)9=dT z@Z3sYSZA8V%-p8ny;gio-j{F^2IKS5W_q2X(CD?P(J>px@YJK46zC3MJ0oFn1Gt^> z)NOx?PQM(6og_V8eL&hm!vWcw($ye*Z;LQEK>w;>#(pTJN3@=MHc$ zVdUS4bGiPaskOZ~m^%yfov?+Gd%-+(Q^%A4#QL&a@pcTa8U3^DHof3it^!$EbZlbnr>G?j#RM$x7nF=l*W5*R@Ed?`T z?a&5lxIZnCqo`WDzrjup7v*hf3A!3*&ZSzsAjnx^?V62e*(>RfKFELbg7iv}lAbq; zmFBOG@*gWr&$XgUC8uI+cC&KsY_M?SQOJFRYR^zIQR4i&f#&i%Mrw5JWT9kH2D|x< zBBgIR{+Wb*eZ6kjYn9rt19k(y$m^(5cd(NYtX>L5fdefamLZZHJfc2HW-7t$2Z%Xl zn}Uii^nWUyzNPUGk5$)%^(A}D6rNnz4u(z?pWmg>r3NpwYPQO)Wsn05=k+xVo?NWd zd7mN+ZpMMSPPj|DIC=(Z_XwHCz$HVb+WS^;{YEghi5xiVCB@x+-+si4o&x#a`|&=y z{%Pxg$&xnZgwP~99r`|~s$Ww5sxJF-^~!taIzdRKKcbKi#DF)csUf40Riccc^SEGB zthe-S^n(r1gPH)A4EV)H!qNvGzCvW2i(SRB75!@YY}P;^1spRe89EChP$03LG2;8|if03TeR%X_R5^4+j>N(4 zs(m{*f3kT*9p!jmv2Nw~&{uC3bKYZoe^z`4;{EyPVs7z!ZFwDo(V20&r@KSU{i2xj z_6L%+v-#u#b79gAjQqlV_<+yHw~I~|ctY-Z-;>=po6XBzLB|=o(=TM4@2G)rNh_b_5XD5w-xtG6~E4-NT*sqKHR}pr(zsm{tl`{;Y4;sc~EI= ztS>v^VPJkqE*U7R?2swn+1>PFR4n}oMKgOd9K=}*HoxtKJ%b{Au9(r5FfAp2w?`sfLKz*#MEd)X@$05`M81$ zj7|v9YwaLKPl|ntXNmXJ<&qB2Lg=wt!KvgyjM1eoC@*`eq1`EWnW$rX46m#%zwA@Y zXu7G%@HRReahsSh43LAR>NAqni0TmLkPL)zm+Q{hkqHh;5FuV>clw1H#LI|4Nsh!U z!^R6t5si9X)*|K~lRze{vw0{vHH~Lam3D%cO_Ux z#v(<`qyoq6PB~HnDu7v(0%>@#e77KWi<{dGHI34Q&@|Emh83&`k=_;%7*ifpKTCBk zX}zUIq{D?dVRCwN^{Bo~n{U%rX!#le3+-dH5r>-aq;Go`F*2n);vElQ1%mmVel7tBaBKd?xU%Xv8r@Q;ygZz0hG%p=gd~8m2}2lkP^nxLnq1lL#ON^b@&d$`2Ko$(;O8{Gm{GZP6qBB2~R+=j$>2t)BHeh@xadZuv$l7}2? zs?#dLou@e$IB0tAufctKTK1fAErY|6vCJr%%8F8T@gxih3AMX^Nnrs>E_VizTwmD!M$UAEOLdq8)}=t$TVR5-;WF&?KVGpAvBCNO*a16e?e3bXqJ@OkP9R zu+T6J@zR((>DGTX{+~;beGsO-=>rom2Ae1Vnz#pMWyQJX z8QpRm4|#-`lVomQ{4K{-AS$vx-AYtb+vEaP1MOVTD9j*)A3CScEUW= zFHgyyBrho~Qvklu;2mnbrqDosK9h5DD}U znUY#dk)Jy8iK2->|4$2;9|zbtsQ*0jqjCE8dZgwyK(B{cOXri&vvTeVkBJ#not$Cd zjgSa0PFg>CIc6?{uAd;QMq=v)w8_`fUyjiRlom|>67i<74{;MufW{As{Xwa&K?K~N zupF33tvE~4Bq5ZWM8gWswCW~AJa#OLAJ&^mNNsccuEJA^rYOOs<13=|8sGNJ;fe zn%&cV1`b$hQS_z=LWpovz8t>`0Zo$kdD}!W5et}k3IjEUAy~Y=B|kYG0}4Nk5gZGR zNSo5u(MU;9?j?7bVV8YOxpri|&_kJYVuS2%@9dVGNZ7&=TZa5yreD;OF3de|$WwPw z+_QL?2DoWJ%+RCLzgpzWSv7I}pvYZ=3oej6nYt>0=q(Uc5}S8Id#10J*+6vr zAZI`-TTDy=xw_+*4{A_o77yxHIK+Wd_8I6DF?GG-Xu&!IV zw0AiBs8Uut&N!4abEj28A4cn$)$oR94O~pbm}qcy-KiT3jGW0e22Z(6B!?Wgaw}z< zCyWO@<7gzAagqfTxD!xT$xXuc8%FCnv?EXwt7rW{xCq-j@K|Sor>S6F5ILY<8P+PB z&&8G)^oIe@8{(@SBD79Sh>u8WdV4{+IwPyp9NPLp7L?bG>c?!fi&fXU1CdgyW1hc) z$gdmUl7U4Fiv<{Mjv>JTK}2z)4K&13p1@Rfiw!U|b%0^kX!xD8{&|V0F`4=1WR>fL zJU6FjEVull+SRn8z-tuMMJf=ad82fhWNyTh?bMTc6K8t_aeOL{bYKu)jHRI8)-lBes`9 z0qEJQKM36a0DwS$zq6)HAfRs{%z=m#hl^k&@A6}P3JumSWt4`9INyQEDINh=Lfa$l z3hSigp2I+;C&z{veR|Afz+OlM^ccSq^NlxsGwi;#K((mJyHA|w8Ew^ey`)nRcK5`^ zbjh-iV722aqQ*Ov)MzUD8X8-5kn*2St{vav`|wBn{FcD4D6}XRi#d6g6G9;PKw&a` zj5zPU%6kV)DJnDriCY7=461_RNvwSg*aCYS@G?p+ z<7O?w14Jb(*i1@%ffcDJV#ApZtX^5P1Olgy9cN{8ok?4YPZ_0cB|cLx7z<#?X8r&@eojW!|voOwkvOSoP(8rFa0hQ-LX30^#Ew@veZzs z1iZx@Vvi8IJX^WButt|9a*!Xa4nfQqeNwU=28MKhr#j235N;@n37rb&=55Qt&funV zjT#e%5Q>{NtU&A`{s=)iqTWP_g*Zf_?koxGq#mU!#>qi;V#i!YrRx%t{juN?-KO^l z*+GgX;if!KQOS@?Vk%1z2E-81k`q-bXs2A>q(+u70HqUnDz5X$ICBWFX zSlbYShnQia!CFg}3vJlJ%N3M{%=E}930|Ekt^aqB*^r-Bd=pr!& zLTquaMK5K{_I9~Cc^aZ((Vs(KW2v!=8kKie?mpt1h;^=0ql1!&#DFpe<$HLQ%2~!F zCAyUcFAklj1Wq3URvIu7<6EK+w2i}yCm$qbYdiNS-(qxzM2naTFAC3)R&p#knieAs zqCHh^SS(sbK_g1DFP{F&h+0o6vw#aRS(_^9lzoDTNuZ_*810jVX4DW3UZwsdx>Lyc z28jhK7KAAHI3b3LC>@c206y5QU;oWQd|d31qs5vyO?r)>(Ke3Ozzh#AET^Bbi3BoY)Fk zJ;dlfN*0J1j2k8kcjZ%G4N0Xu4`ZBjD4k=SrdAFUH7azen9|^y3QUG|LNgiDJF3ah z1XW;tg;E7g1Z7H;1ct*L7M`F3m5LO-K21GE*_>X!%!#Gb7#VPFy~5zR?Z|1=e1uzM zG?rEtMk~jNn})^if+Nc-jN36y zDA;W)9(wc?Tg5srTzQf*59~}g$Ya6RJ^D3VpX~7Q@l(w5%MAO_+69^=dgQE>$63@Z z=Q06`QrX>2nqVg>2IeM5U z1#hhJPEcXc0fvCe5YtQj?|?KUX&w;~qFADypiGX|4(}7GAw)_2I}0qFqngYR$%xV8 zq9uluuN$O~^98+ZL@)29XVvG38nU9!&>Qp_SFaG1BOGMYiUSH_o8ksUd9+INw#I`r zXw)HTO}Z!wV%d#hONZ(o6$*$&H#??G>L`&Q-C8GVR47msWO|7#AE2>B@3CzQ!JzCB zlx~rH1J4W>I@b(9qQaO!w7$#R4TKPh;t^G$yNp>CRl1fw;zN-@RJRM_@d0#JQucDZ zx5cYC)( z6DKHvs8b$tidYD5s$}OWYuH$jh!%wkis-ZCcH$@4;80oJIjO`O5J^-VIKPNV5J&9d zD^L+)Bw|xWa7SuP&JF6&!9j3DiR5KL(^wieMT<#U?52;_8t?rZTy{c7IsiJ?2{{A@ z{!BJ~JHA+fSq_7o`TPQgKuzH6*|($TC)rsXgWi2G$+_Ju(G!nd6E^EFvDo=lkPQe0 zMRt-C!-uisCGIF5W85rgn6sF_$berZ<0a-?Wf?eY|2~bam@(%Y-tlhArsl&h{w|k` zZ)MyVR`I7q|dSHQ-lSQ$NCzU&iY%^5S5Z zQS%&mujcEIKg@HlS!&MEmR|$$8+kjg^Pl!V!4vW)J*BH$U7uVS)O$n@PD zIrC0l*}0p>6kMzWA8MbYXyJN{T&2Jhc#sG2Ymf3%7eB<+txb0L3)G7OHT)X{F*v`; z!0oWj+j!y14$b8MCgTP2m1DfVw@y9G*$xZt1HR|%S#INghI!71&iy{G(y+h!JzO%& z)a|RREynccKgoz0V`l98l1Rpo2@e6^d(RP0jUM2cSI6B*c z>R)n_FR{iZN5|jH^YfDHM^4k^JKz=&ri?}xxw`pjG&{Ug8NTZs-^*?OGK=+>sH!HB zUvLzFY7@xZ%5jeOPw}>Lg-0Gd!!Ld2pD_h|c_%awwZl3GTx6m>yLAJ3%V2Of^SxKu z+WiR+a=Uk2T>a>q%=TN}jMqLs!wPu)sKQcmY)Y14kwL#Dyn6m=jjjZW?W zeQrA^;?7CNM0bz~kEP4h);9oO2{(4$Uky6cTHlCZ>RxzbA8mk@6f>lD399Lwg$^*= zqb!;4!n!^+PlJCM*y#4MBO)3{(^<`CshSW{w(r3M4fU(Lpvt}>S)jma2QG% z(l?5Qo#JDg#_$e-aV|w4C41jC1(phgCQ(p56QUAKh?q9VvVtL}VT@oof?+ur3^j8= z5N2^ov;90QDVQ`jstpIW&NtaUt8Vljh|p#V*Lpmjw(V*FG#COo)nVY4jnG)=lPrdN z``g@oyyW|P5A##!FR(Lz9rzqak4@R$n*OPV?{HJK=U?YB@mBrhAfhWnANEZk5lO#V z>qAwQiHNxIc(dTMc1u=Z&cQ5iok39(co{zjf z;Sb#0^6eEooN07MKM6}Me^onSuka3_@7b5A+z}}vV3fd@z&=V*@pl1>mH{$ zcYzP@{6FlyS+Hg2b>H{pzXTy1v3(FZ0h|`5Hg{uJ`bTvo8|bPPDcV${{g7 zf;Tffl5uOzeK+tQK6EdSzwjCzVE?Ui=;ky9Lmd0K>N@Xkf6jAWV`FxaUGC<{+GEIz z53|7*zp=B+A<^YJ-=Un2xr2Rfa1kG-7~svg25Ob}oxU4wB3E|y7@1e;RA0yNIB*`B zdwiXtaQytEkMXabdkWnG(hL4~M$K3G+aLIG{_!`zj#(Umlb?W5hh}mCZ)*f+h;uk_ z_#U=5KFJPitndxG<{-cD;0e_12A7rKUv8Y^^8RHU+y;Jc*X_Dpx9fJ@uG{thXT3u$ zdTYVt|42jc|0F~>fd_urf(5>{EKJBmT6h_J5J+7kRl7VjcM@!$5Nn`9WvxB)JF|sv z+Tz7P2+4v`sRY>g5N>^TAwAAlD5X#;BgTO9O&UhgD4Fby5s~Osdd>DxNR5mc^-R$( zR!}m>xG7GI$aNnbj^W}0C*J~5Aamv=!GuQoHHW%2$by5$_wMs3|%T6&%Erl_c_j)k%ddMMDstCe9%AfHj0rSQpT$LFzd& zuA=RkWW%a25M!iJ$0*A#3-eu^Ysm5wbUQ<`&MG_m7ZN}&9a7r27sohI4JvOCE)axH zptqI@e~J+yB2o*aR@lZ9gCx@>gaTJ5HE5xGlzNG#nNU{_QI>SN2WX6;vJ;9dL&+}I z>=I>S?8cBGWRA`()=gP7`(!?#vXqak%LK6d;BYQbWF<}QsQo_WKw*tZU~k;R$_0~X z(JDt8l>l?OjMY=B=qbB_YF>jBG_Ig$?&9I>mw~{`)qjg!no=7p)))W)AOJ~3K~!5y z9s|*NI{lLA-jpa-h(>^w>`f;4*e91OlwuX97t9tlQDh8y8WAqAIlhQ+14LGkcMQ%~ zSQpWmr>+fUCnJcrAeIQx$C(ZShYXIwO0>zrtWcI+>~zM;N{$p$j7V@)8RiF64x{z=?=Fc9316@knfA2s%fp457NoUdjuES4l05 zM^GorYLOwxlL{-k1eOLz&nq$?2ti}LA?7n=9*Mrh8cj#9Q;$7`(hv>aj#=ug(JxLj zuNHLV2F7iXArU&mSV^As=*vFNIqKLTLcyvyiFJX=)&}oBawp5hVcxiOj(lmE)k8-R zLa?>7iL;Jl$Bv-1WH%qF$#K}Rip%KCV21BVt~pcmT3a+f^1c2j@V>$ z>?(&=*V)*4oh&%|cF5`FQ*3T~=8J|>o#MdZ18na-NA0Hc^g)(a53{p%Jz4aH990Gu z`6i96&|#T8cCn$x2Plgk)>-CJBV10;oFYTx^G!l!5<5>jPmXSkCXp z-WYINKEjdXYrHW2EY{S#fA!xd_8J~{|A>9DjgSX$6?9#RGM*s?!_4vW8~++xD0VuE zrf9gZ@m0!RpgH3(3q$unMt9zYYQjn;+r@7mF@v7Wh$>J_`y3d(3+W}pwF_*7D>VI@ zMc89Ck94yx^J&d;rw`7i7_BK(s_x6S;YBF8Zgl$H%O@ga&dPYZOD4G6k@R6X~T;T{o=19>)#%1skm5m88 zAblsHh;p9Z!==7TWd>smI%>4)5u9o>Wg9A!KD$tf$Yg>?ibz&u1gEHtrPPXG+h7fy zh$Rk>6P8Sz;BfD!sOySZ`~&K67L6sLra93&lr}VBO!PTfQKBU@-a#}dl@WYF2%r=w zEfFrm+hnz$D?y&+)b>1;{b#8s%r{X=BbfusWX5=Mid;AodBi#0y2#^EN+MA!H6de+L1vUBAVa2n0lF6KEY< zd7J>D9U`Xlhg^Vcknx@NmaPgbN}^mOHSR4Jm;f@gq#B7*Il(7hV(`hPS*VDV0ih(p zL9X)_Y_3sgRLqe!K=3$c$ny*#BaN*IB9LVnQY&1LDFWlqsNxq+BFh7;tsY|g(yIhc zQZWJ|moL8zOaO&gIZd=HET)2eMl7y{Ho1766N3^pYnaqyX7!s4xs&^QN4VJRFhT+w z{LMQQOT!iZ(F@o3=?5R?p}idj<$(X{tqZ*Too6Y5pL*AS%s;$*8Ari~POfnF@*8Y( zjACVt*Z0S)0zdhIzs2Xjxj~N)bCSqMkA8^r)92V3Ni3Uu@?EDH_m}vupMI8_gJ`-` zdua)O&&hjf<{Lcm($nm4jR9~8m<|)BMC>5NX#zvu^k3n3&wh>@jQH4^;P^dfIC0Uk z5KEYN5F74fZ0FpuUUGVIov7#3)q(%+mQDg_HY>!Dc@bg_Za4z`+Oj^|Sjdh@fW7{1txrzIzx7!>_&aI7SUNK(fz=IYjS z2pnA&jKhe}Kldzs=G+0?xqgZ&&#{XUvQ1G9WRy!?=JPpk&bPSujqlLlaVn>~dW6M| zN&DIp2-nz~Pkw z3#|p-jVPL$q9sU)0Hf9rAds#p&YCo~X99ep!e%H$8?)s94FJ6#R87<1y(dKfC*XIH zKyqvPo|Gs7Fl2S`5X~ZE7B{Kf20o0TonHfiroHESCJ1B#V|@ZX0d$DTgCSj$i&w67hIgKh&M?v9Th8{)yiZ4(MKzE|0TguQfW7wK(T#zh zdGtpyV#;T}{S=M`9Rv$8hT8ox)vqF9_P*uZ|CJy8IL|-%G-v$`XKv;(OKvhUMQms( z(k+!c5uhXyjpLIKy@w}Xc#-b{@4IV_fgC|-fb;B)uO<@yzeU9#0RD#`0{Y&pOl5rR zV;|#-U;ZLOD74npw)x?2elyEhfSHWZtwQ?8|J-AI_VH(_tLoMdsYK9NO%!ch2MwAI zjrHUd{LF_x#%G@T19Ak7&LJA2j5H29z_7*HM@~_bb{|m>8Sgy`*74Hip2q%2+>sl5llQr#5WYmTqSGuzIRmVHkeOX! z`B24Z^HT`A9AU=b%~yF(XNhq99{z{3&vTuVJhb`=o;v#_e(Bza*e!PXt?yoCAXeC& zuF&ZXsLM!fJRzp<+5*Gz9{=gX_w!cW@LR8+WtW_W3c((NP5#<@-@{;jjYeob|N17c zvCG$9dk&SK=G5{-+|!?u3(te+$GCWjzxeL=@afmT%wC;NN_*^n?7{bN{-u|&Y%<+E$x#lldGOsdvICO^s|U`o zIvr4``?*xFv%lYfyo=RB5v#}-&pknpH&~|TDc~=kyn~+@b}3@G4gB7&+jYBc*X_Dp zx9k5)kXOFr@n#55JN}6uHUfUX<&tYvygucQ372TOH(xspC^$*qE#^5@NmVwe$FAh4~abgLv5iC!v$KnOvRG3QZwwF zM#+LjsF*JH+Z^49kO73DF*B_7WM)cL8?w&LJmr+j_jUrIOXo*90zQ2&F^#mXmp4)f zf{Vnck|HOT$XFm%Mp-U1?5yEU0Y1ZtNm{suWP_$e0^DzA?6S|O!Eili`$9;C3zz7mB}iVy;gpP-2J^A(&|ETkbyN#+WoZ%{fh{L8XL zi4vzJ#%NqL30N+d37vHmGrUb|v>-s1Ipe0GmI~49lI1xw-yoa)1h`8{H(w_PO{k~H zVhdGRl-Bq*(^^W2&MZo&i8dloS&a}1CHrZe6bw-qyt5D@y}f5`1zDh zSD~dsmjk3xOs7+#oFcPGC+py4MWJ&lZwR76>xlLdMTRYNf{J(th3=qb7hFaNDk*bK zz}6P}k>~`uT?Vi5t|Hfv%fNhM5oM2}8gf$K%QP(5>yN4Il!N7I3^Vrp6e}8pSI8)k zQKMvmQbUxE)NW3U;G#;3Ug3x;xd&*K6PlERt%L?;aI$U*Cj*E%#?%NY)A>P?N$7M0 zDkSA=%qyfapfuh?^cgbC@G8R^NpO+X;X0Y@VwxFcS>kNP%x^Oo=In+EH*Snjss(g_ z>({TNv?PdjStS1CtFq1n)7c0UE6TD@^p4G~8yL}Gdmirti$zUU8MH5mRxq1Z6gm)W zz^jN*Y0DCV$Cw%^CBX@V$Y`1-5jJEXijY)mA|~M635acmsLBWgq>NNml@!rg4_gOZ z9gsrP$xAY=h|c3|!e6p1CuEkUlvoX=i4-~z6{x7G79ONPcKQrEs~l=hA|33ZG7+A~UwfQMH6@JQnUR)|u5@8U4Fne{jG?L~nMIe`o*Vv38vBcn*x@S*@2aV`*= zKyW>}-3-AF)5VxU8EJft4P&CJQMychg3ll*^1MS{3{hl6ImLz@Y>dhNS+vT|Htr#{ zAnp1_IuL=%P02+=p(RBYa9R+XIg`mHcE^%zRYF!Eyh*CikopxxBFY5Opkinv60%!y zgT#pN9h5&o2Tu^!vGp8Z9R~zOXOC_-XC4+mhrt=zF z7Xl|8v975D*rv@%hc@e76GM&&1c${q7a;^vdorz1zDu+UoJ2%V zN0kJV91Y5>i%>4*tT%=bb&8<)Gg@80M!wy!qBmFobB+K9AiD^52dIEKV%mprH?e;P z<+~`+;1&%hsCaB*Swr#`=kUBtmlwIO98htEeo<03PxJ7;W+n7l;uwdsk8-5>KcU$m z1Ga!=z=UP8>=H+F%PFx+;4BqyFf_Xy;W7rey1mYb1KfY;KIWURaJ@4`Rd=$svP`)A zDuW(O>P-%?M2~|kBWURG3J18hcL(#?3Ywg=Jd0)%OCU2j*3Ka`%!}8lO-;$ubQmSI zU+->i+$b65M>tS97K;(HBE#8LUYd4U^6Q+80j)FUfVp*Ox2ZWxmosGQ3MaBN3@eM+ z*rNyR0Gyw9NM&)9eY1-k=8Ps=Wb~Lb=E zreOszD-k1LXA2hnM__OtIZv?Q5_I1{Pd5nqB-2?<26&eu8tM`*)bOod#@si&2{;tc zVWt%>FOXwFj2#xNVSpnYh*w@<4cKjejzJad*$OyBWQ{2k3bs(p3BWbr<>3mmPM59g z7pY`PCL(x4J$Va)LL(WcsSSs+8Bh}87(bVCw_7W8=KO3mE2 zF+uz1SvoLe97@EZ#@S_1IZjPj*lC)H6`&X3BerqmK%rm}D&{oUj>a!;K)lLvk_~h& zhFpmgrc4nmA!HvIIn^612*rfjTof2X>1UfW!ls<#lMCdVC-;x>^cwv%S zStX)lv;plU1rp_43wJkZrgzJLC$L8nfy(w-PlF-zs=dECqVNKU+2h zc^0Z=n1gLU|6LUqodp9;I2pnaCYI=OP5=1^q!xGU$ZLc9s0`Lvf z6j>E^>4-xVF%d$#3)(#F2}3(zh@?Y_p`u&%P+PAv=q{1-8rB4?e*@$d2(QrTZDZZt zlxoZxfqgP;zYB{Vja>syAh|-#3{@HYd`7W)F9E?G@8NoNhLV>#+`9v3Yu144@j>7O zdJu`5=aHFV*~5y513+KG=4j4l|0I_gW6&t7^!v*`MjoXbGmeiv2Y?HVS>z+)p%Yx# zyue5EJ?M;~mlE2ueg4CSZgrEfZpdpnx)2&PtauR+y*H+o_HlNC(hy_<@q|p-#sZZx=V-qRArsgg1g^#TRg`!i@Eu8@AckJbW|niL zkO&b7WC(wlXgY*Y6I4l5dHSq&9gN4w5vqVFYIJTfVT5%PqzL4NYLy$J1#)Ogx>xeER z%0AJq5CzC=fy^dEGF+nwK1XX!6ai}zP?cw0LP+YI;A@nU6xlMisj;r6FT0!&$JuKt z_B;Dn-LUQyqFxYHKn6vu1Xczr8Ybcmbnz)N(PeM8M_CW)%93bi#9T3t6<&3?KA&Nv zAul94G*pWbLXF6UM$9dJy+&7`q;_L$T%fXfTIh!cZ@UPYAy^PXMHHSWa)?VQ7fG39 zGZ_UQM=WZ*sz7frk%4(OqVf(A`jnlLNxezYo#Vt?RLv$)RG4f|QED0|C^CaHdng?U z6qretEGzp9YSZBJ9wL;KO$ToxO>`7_j}>=-k{-1^PvLtk)$hYO%^uGqi<-h6qL~>6 zW{8@cLxDehdK5G^8RX;~y< ztLRQtiWoAY&d^!FN{gkzc*z)JQRAQeUNxQ`Uz|1Uce*HO1p8`+dS}idH%O!GPL$=8Gv2O}C%ZG>dk75?XMA zTf~NMwFr5mUJEmg9OpYl#L!2_yp{9%_6rSJ~DeFu?h!z_v zR8Ryj6Uju{TiM}4#-xC2b2o!-mRuHsz+}yX?sYlUNahMT;G> zX2v|L=ykd@eoByn8jBYeFRl|~hKo4?Nmlf55p1ZjZh>?&3MVOKz#dc zN23irJ3vN>3l)(WiVj&(Ae>`bZDK@&>SQ#oU@MNO?H0PLQAMBH)VO?1+0U8a3H5o@ z+!5n~K?$XBSpOOe-%vNZ$k0cbEy{jL=ovzYbee`9mRcCBS9CfDs4Ih2bIPu#QP9R|>ho?jofh;wDb9sWL?CI~^Qnm~ zDc~lBEvbK7!re^*WDBHgne4WM)7U1R?Yzj4I@vLLnG=FTM30gsG7JcHhl~zoUJzo% zqTa_xOWun}vA}st44^WFkAHSYk6x(hQgP7D`AhHpIX?9o#6v6WU;G`qLNbT}&2{AT zUozuv_W3cixR=#@!8(y&zV~5z^VdpC@9*KWXW8IMt~GE66Hcmwn0?QH z6a0(k&(RqQj;;=|I~5;)V|@lif<@JNPWiIpSx2|wE1J3Pl^H)CdAMvSg{8K966z}EC$)9CepXTxN=ZIXT zx7=m8b^=!|v$^#q8j0l~)DqYP6s~y6^yY!McG?sSbQ8`ZEfb9Oa{r-pNbPeVKF2dF9QQS|V`=I6yt_;7y63PS+W~z=%4bRo=9`<_I2^ zqURv+e>`)U9WL`42U%ZxH^hBRl|J{!-~Z>iwm)Kg?seuY2sm~(t^x)^A|(IChd#)_ z)HMB)|Lxglr~}OAP)5fpIj7|k*Tb0W5{yddqD&NF0&j=>-o&NDJHfaAo7a^z&&x!% zZOP6-HQ*#F-jVume|);^+W9 zx}tNIsco!WGmoZ87^TbQw)J8pZpdpz$e~+A6xbUUwOV_!UH4&{}C#m z6GMua5He5%#h0G>90y6pD zl>_Vs%WuDNE;&K~pM38JY3ied{$q4sXt?2yGm?QD`%knqgjITj8mA=9GypmK+q+EI zrNc=M>NhaWC2Gd}^RI3YDJh8z$oRrb&+%^Hv167AJJj`o_KXy0=3E+m6?mNqj$b_S z5RYHkV0%%4*`ji90Q>m1mpQm{5V5tOR0W4Q#iaij=V#Y=h-Ef6H<2BS2hQ|vr9)|HlyCKe?U0WfA%g3gtWLpf`cncRqgKDd3O3t^qku89eSlQZL-( zzTV8x6G>%4EQqnkt$bdY)SfZK?=_K*Z|Bnz1xmK*HaEeK)>bOUNQ{!;RRRlRNeq!d zV%tiJcF~wJb|onz6mnt|Ni88F)-Dhsv|vz^?1ID`p~tOaw3`MunTApsb;{`#9kx9EtnJ~ zQAi?+NS2gOGD}l3$yQs40HMv=iw0vN)k2|spQaw;l}(CG6N%EJbxn*OEg;xHuuDJ> zZy;tCDFT_$_$K0=CQ}2tWe-Hdyjoxzjcb>=N`s3Q;Uz^rAXtqHhP*71IxP;+ktiKP z)(9$cDG3&o=%%c{+)>97wSEyRhKQ^{sU?Cl#31P91Lg~l%rwDhR?1am^fY2jSqj#A z>*P|gx4VVTN)8N95`^W_?llk=A0sY$f)J<{#0$<4l_H7^?*##eRSixyND+vn^OEHm zRXt{NyQZo~^t(N*5j3^K2aOMrCeFb&1d*(hC0$%_N#WZ_mc=nT44C*SS_Fo1i6Sf* zMTv8f+zM0>DB_>eN91v%bFe5?t|;FU-~xzL~_ zx{x?qVZB2U@If-2*OV;i^?HyGan+0v1f`Zl?PzRL@*x~iHOw1B@RCgR2_7035OIK# zk=bm5RG>3SWoA^>oG3x6z@nZftN5D)o%XsM-a(_^-`{1hG(c#r4$OL=! zE-ZmAG`h%8R^Vhv%fBpw4`foKb*uD8Qt0HEU`fAgow9?Aju0(AnsjXvfN%r}UR6wu zB~uC?pf~KWSj-X9r|Xo2#-;m#lpTcB)TRMELR%U?OL^ipZMS@|*y!*v;JhR+I|K*8 zE1KFcoo`^G#>;^6B|AGicxh-l4X8GEPD-S2?Qd;zqzJ(wLTqm_f*=zaO1K44IT$!b zn`4$(Cm7HuGUpjCK`bMAPZESAw;9p}qO>@gBt4KBRya&_DB;M;v}LuXq0=d;ZABv{ z$etwAk%gP#y+zBM_0=_IJ5%)t`!&*<;3vF27eyLf?O z*>jFpDOO74v_m5ttA|c7wRkPEHdhc;5gEa;d=wqzmLBAY;IX8bgB<0Uw(0A)Cdv zr3y%7(o-Qsn~jZ0e^wa+N3bbVJp@6HL#qan=S-a;s@4&Mh=?K?Hj0`|dQ22}-jQ8@ zE9xR`c$Ms;qQS?CObZUJpTspiHfJwmT?JW#)Fz2pT?8k|Ll+q(EFw8c738BqN|RzZ zWO8%%#e&+s0m|XTJguf>%EOH@Wz}lcLx^OyvcO%M(#JW&T^ z2t-O`>?J~+j6~T*h&uHkF>5WHdHZ`6uI)i@#*4gd`+UnblaWICXvpbk^K_hca>nq`Dtr;{CKrL&6l z6G}N^(d^;OKE`hoq(|!jQl-qxKcn?A@hxsP&T@@jl0`K`HaNilbonVZE|&~Ce}Uh5sZU3( zav@x2x$iLZH&F3KK7QXFeC^ez*oU(W7nt-reux zx6XZ=CE%Ctd@pO;ud?JD{`SEW{O4Q0$C2#A?01f$XDbXs#lskW{CJl~^fz$z8~l@v zivR54N9bOv*pUUlPQevja?Oo->6It2z$$lhhCBH8&ipI~RtLQL>=XRz!INCA3Z9*w zqoJ3s?SqoJA5k0VBatXPlAI}qR~d*07J2u=t7N@jVO|@4|HaQ>smTFBLk~~EVHW%hQDwkOAVzfc zl*+|hT;`4_!KayZH8}18e&nt@`RzB)vq3@RX|}hX0J(?HV8g<1eCwOg)r>JH3Niwn zY@dmp(n!y~fdBG^XE+V~wY%wz`;0o}4A~~MsZP2$1*g#fSK!eqg8F=(~$+un|F=d8BV({q<78Wclwd&}( z6f}bZf~A-Ses1X=aw&Lj|17SPxLO1Vx&YS$ju7+;#2$ee`zI3RWq7Q=%7$6Bbag+%iY#;y0^^B7!*HB#X+`t7Vj^kRf`#`1vbDhzyCpA{MJkS zY_G?SL6^U?vCTDIBl^p{HM9JW&wmqe>=D{uf*rQ6z04Bbl%vfk1p@mV#2VwpHVW`$ zOjO1b-k^aO&i;2yT^H;T5G9IjYUhb{jRF4t<+tdx?;sOA&nMseF#rAY&rkus^6;Z% zjbzR-yqp2gf;bED5c7Eeu?@b*x_XGI4>;5DwJVK#<0wbY6+$IlSWq1E8Ag>^T<9)|I!PP70aZyn%?PBMD06d)p1b~Y}d^Kk= zxxpqkxG?K-$MP9=Mwb!GcXO!QV~I7sJMU1GXDEoQHrF@<{Poi(d7sJgmqzR@EwRUx zYn)_h^@A|mXJ)P^tUoWfXp*}`RW}?N?eWoSllQMKk$0CEahNOdAkSVCoT}bL6*Ygj z{~~vvd5BZ1b6$CNpOv*=rZFMLM$O9A8Mb3H;9g#on98 zN|v7IeZOxxTdjA$z0Xe0kVA19E+IwAk`>#bB3XeYnTjdLOOX7L#0U}uiDTrC*ieGR zavTLg94)XcK|*LbvOv>OD3g>ZZo`=&IU_E!cTex#cdxotb?PkNmOs98yPE_V!LXIs zK)=96-R`<|&Z#=5-t&I%^FGh>;%E4s?oxjF`4>2DUtpE9)TCGp!B>zhz{a7;r~mMO zq#;MKWP>Gt>GThf_1?_UrDyrU^*}#=l8@hPF=s!(rTP-Te{lIe@OwY*$Njh;_v3!t zkAKnlUV1+Mdl&NIUfrd8z}6Fqwwr(s9=-NNl%DpY1d$O!8h!8#NSC6+W(1o3 z5^ocs|Oxf;}&>~YyXrbSp;{p3a^okWOWzV2> z%|reIEe)^O*O<8}xf2Yer0;67#f%~q^pbT5XE}6-)ct43@|?wSMPnQ`+eZ}=SN2HP z;4u6$Tc<|s+KV*9C9h_mrgpIO$2ez@P9Z|{bo5?8m}8wF*JGUXv|)x1om{&PXc^lQ zt7?R=Tk5vN%YaS?AT%yygb+yZggPS?Jw|zygs+wj{bazG{42D~A*v1YBBIX+*0=Z7GO(0VlO7&RH9w01lBji3l zw76x0R4MEIReHq;C5B8UM^t_nS5+vTfD9BqKDM69h?yweUF>*_0fN31(TUzIe=CHYa#=IAW@{Ui1kyR^HpiCDG@k)`zH z0EEQ~iLe=IbqYd_&5r5GJ|BMkM@e?qxOQ|6Sz5kt>tVb+(G$O2BBJflOydmqhuTHGRo;5B0ok_MIUf-Xe7!*qQUza zK^RP!c0*$pk<_uo@D0^}0wUc;6tdNKt>z7z@fcI5QTEYVvK{W(5$6~>x zco_kGfsE57!DGV|heCuBF9m@*0`nmU6mga#i34vU5JG~dV~R%<;hy5R6U-DQ)_ivc z9q*}q@!g=H>10Qf&J(!%+o0pXUAG-6n&{i>=~&6)&bEZtIHT}QNi<=ZaFgxi z9NWp9z;(tw#gc}cBTiviL$hKXgM*jZ>>2tz%s}QSf0=}1vXzGF8h9)V;84LJljO|~ z8$^fTC16LZ==3bNE>Cc5bAwIbHubD!9e9HUftpNN8cNc&obqUaVo7eFV8MHty99Wd zv^QnC*kPXq%V9zV>@lTeK*5+4MX&NWZsG7We#VF!WE`-MVr}p!x9UUit4yjrdTO0b z9ku$_)MYS-EKD{Q7iOp{RDITyPu62W{?vUN6Nb?+jT`6SBCseQpI98e+X zanKZOjUHgM^9tkL1rOULW91kSxM3~pLa_*rl5?~Sc!Y+LnJ}76(15O5)`u5J=QA{? zu~xy613O1y(6o3Qj*OJ^cvk3%lxgn>(%VqhGzKmMPd##ucK2oM9AE@;4e1jc3grTM zrg5xAH5-N)N}yr@xYl%)(s=|4mN$^gig7U}jsQa@<2df12T2KMPCtyl5`ZyS3#?O& z*O{@)w46t9LP5{L2#aBd{>USbT2!`A1Ecc=A0MuT9)sD?w z1C8g-w(jP?6KmDZr~FRZlrd-Cc?ZPd9ZC>ORPgje++5X-MMX7&jA1cCs~(d@67#QX zL6i}l4-weCGgCvCj>A2uvnzlU*R9{}y}+^n!xD|fcT3CFtu=UQr#t=*G!@~_z2Kz1 zVZDWR$%*Lm;M_Ss113S$})qScTM z;oJH%j(g>!!4G?#m@r5waUPacr(%&L-DfVp{q`l}{nHAV1-PXIy{!w(kB(^2EEj^j z{{%I!5}DM0e0+lMNfH182{mf~^m~T+@`$86ufj!EbaoH6@9rJW>J&SoPqHE) z}@ELSA^QwN@?Y8K_dkOq>)j7{J@X~C^LX9c)fK?o(5J|$VSa?%w^ zY6#0iGQg9d@r-eV1}uFPIgX4(C)li@DJP7&-OX%8+8wD5Ed>^VWnrTu$?FYdGQ)V- z!XdDiGynp^cDGq#X&vy+;xDDsNR+yJG(K!IXwC1rMa1DImjC8t6Gbql%&)_A0X z#1U1?7LG8V@g}Yj+##>JhiQ)$Z9W23K)6JK!Omuk7|_)7ND64?$V}iH%Q0}>N>+Ls zWWzJa!x@r-!*a$c0>^evd*~=}oatp;t=~X%NJfJO`g+KG32j@U@*xJW6dX+*{bUFf zNSU#8(ZXimTby&885E4lDNbixzOh3yTBjLiD7Khx85Z>s7xA3hOz5vUEG^T?CS`al znFjAFj5{XS3aCj$iVU8N7H=XcV5J9U8S_>^v)2x=WCQ|^LxP;el$VTP20GMO-at{) zqa+6|49}yjX2ENmDw9q{q2;D4vBOPX?g0P$aX;?I{kR|Z<9^(ae|g~Vw-w|5dl&QH z_S*0E$oBw~@9_x^No2XYUSyMcLG%>urhnBG6ZQ~fcs~FJ1SDPBc#ZT4!4w$h z$@H8=CKT#PkebH7i1*9bfbD#i2^pzcAaiAazrtZ$>AvnjFF9G5RJwqjZzlPHPFYh0+=tzX5qhETK^>!Or(lHx;( zZEJ+>B$q`-Pzr1tm)9MeOe%*Y`cyk>2}Y6j6nIawtVqRx2QECs)oT|KzVo+D61-Fh z>+r%5gu^;05)D>kjl)Y%ZI&FH5~RcC1{ZvEm<|DJEmSp!(*uqs7K#Bj95G$oBy$QW z3v{knCN0uQ3b(~zWyq!GS>$L;&iuhCkQk&>$sI(UMs@kq{YKFXr0 zn3*?N*k#3l)abA&@>Bd;?N;rT}7gDv{W>Wp{`phdqk3@5!i1Vd|9HBC`T)`x|78N z-}y`Q^E}*}W3|C7J;68*ZXaNimZe(8)a5+hwqT=JoRWYSSlgmh0zzVKLvSfBjU6Uy zBS2)7$9S;9VsSA~3W?AOQhI{*AOcP_c##sYNCh4P&PGpc>kvWVY>kqAf_0=i!3aZ0 zVmqvG3S5d58D0dWZ&9McNr#jM=?o%3rAkyWVneKx7OPx3eg%_u_5rxa_VpB14FIGqKnZUBzv%*)r6BFFxi0IkM~eFf}pW>L6HWeYpF}mn(Fi5*(V4_^4iro z-u1z@NHoIb(2VJ&LkiI{w}+4!T2bLb4Z?Q=UJ@5#o{#>IDUd`klqTL1e1r%iMk(;! z?2;6a>pm;#!|2|K{p05$ETejdw>TG&ttQxYJc5t}ymGNYEgGaOad?DFK{YrogY@Vm z!#LPKeidgWjW{CF0vQStkrIT$dr2?tvsP?Ct5C}vYb{blPe2=LD&`m$rQwD0c<+!Q z;FZ8hN00#*qWywUjzpJK?Ge&9B)LLqMH>X(8njZlc8L!S(n+LDNo9f80}{DGk!@hC zj(&q3pC*Jj3g-!g;0apby^1OeMEegZGyxS^`bn2dL<4AowAgSW2_Dr<5EjG~0tDwe z)fbNt4M=_0MkL5P$}!P$;zaH_HrPdo0RP?kS#}C2IyT`2UHuwcg5r+1uk1i!(e1-^ z+p#1nqX`D@8oZ0wbZ|8y)F>sWjVDNfQXpwS8@#Nj+e0SDEmBvES5tzH05Kv(=pi9k zj8Uk}@c+)s`~NQ{e1qS)_PdOzXo2g?PZN;*wGR#X!WVvx*Er3&*_-)F`vQ~p1!VR( z=!)Cbb$;pM=jm~U6xiy3r2qM91bqL-#)zNY-r#G+X@2j@H~F=j6ONd$CH@?FvdP<} zBdfo{Kudn)9gpz@1?|>0zx1h3ljFE~^dj%zE%eyuO%IOw$FDmUazgI^fM)MCw$FW# z>+;nKT+Ws%_sbO@B9IN{e{;tSbp-+v-Fx7R=_6@F0#qvT&zD2^(A^-D!WQM`)wXDpW!q!UP6+XJ|nZn7C*v&x&LVd zJuHV5ta644yZnyk*=RZPG zUT4pImEWGXoB;xDluG6tRqt(`@l_p=1)9@XfE?lpZOGl2dH=(r}!``oPzo}IQ%TgV;s?^SX;y2IlTs}kMSS9 zbc=H3-2^*kpwAQLZ!nn8$q}TrI5Io{03ZNKL_t)XMv?NPAN*0i^u=EV;8$O`$Ucv; zy82(SoK7gi-{WYcDD8~B4sgqQFt4C?a0U3eFTctGA0{9CNeT(`_6oCGzW~{FkT(F2 z5ekLl91wV&Z_fTY3x*&BiP$9f`xJn;P;2mcLu;Wh12R$?Nd(32VlN$KBuRKEwEYWBZc2N8;uRhJ3 znq$%7v^6|L^hvhBF);OUhV{1#Z>2QT5foI&W^b3=#-xQG2aBS0S7n8WA5fBxd{12FBjA5PMHJMRwmn4O*H zff?32Y#R@tZBERmB4lq)hMVshq7QdRk)pB<@XMc%637i;JxDTqh_HJ+_!BFvt|SUs zJSN$Ifc*g1RtuCVxQ*j7pJBDHNL@lrk3X8K`_D7P^F4Y-;X8;1cgO`p;7Je}W%IRY zD^kP{y6?Fodu_TQ1S0{}#~6DTq}L4?OF|@fk7)P{?|zD}fAwqFS`*qnA9?bf{QS56 zK3At2vC$Gr9Zy^*prU|*>GRXuZ(`?Q!X#C!0DS{xY9MVXTOY;6tRPr_hwW}KYzbHo z@aNz4E}6d@ez)zr&yt);eX&KKJ-?0!!3UE zix)Z0iMAijHaCz=xz6r$&+*sZ{rw!wa{k^ce}G^8vt;R#a(B)n<3GdI;|9_xgc*ew zph-)_%t7T;~#QFpO&-tf#3UaKkmo< zxF7f9e*AwBcch-b8(@4-chx8nu~-*rQYY|zN~ z=vGwz1oZ8IzaY3HcNj}?(j<=zVedQXVjtz9Wdv^m#OH*KGSDLa_|RZ12wBI4k}L_L zTS(zSmL0QJxyV8k^5D`sK)zwWzSs<4)=1SFnH*u|48vh;Xy3!AK{NPBZZb5DpQ36>RjX#pa+w>=c9w zoJG(>pa{+b4i{QXZSb-|NQ;o7W0XbUO(h~W6HH5y4JdNWvRROrhLKCz7U$TjON^c& z{FpWWPC|2=e0YdAf`NUEQdp+FJ$zB4T8S1QeToQ<8Ar55jdLx=PkB||!sJWbu)!P2 zK0736bSg=tp>5uX=TcU93tFtA)EWjy+bj^FM}MF>cJppv!Qb)W@*)8@iW1)fWMXLQ zlBG9zQ4y3viVT&HXb~vY(x@qcIbKX?)C?z6TyVI|WAzSK%;!)+)3_syDY<0#@tI(z z9bQPvAUgTGF)QOWnuTOO-A5#z^TYEQlSvdI@_}+cwlRb{n58*^n$)z zrK%Mw3HZdKR1+DU-lK#f5gAGF1Qnfnwdj$eNCYI(;E0L=&Ks-`wARuBRwOu?0U0i| zcy$Qc;cP;p3yifK*Ha1tW7(X;DLqw6+^ANJ!GyFq1k0BOZ4*e|Hkk{-hD)Jw<8_bv@O~YaHGKbgpS&9~WT;d7~sb<=n z^RdI6N5PX!B_X?e9f_F5oLfaOlKmSR^W}Ale?%c`_kLeU54r!esPag7KOn9Y7|S*1Ih24mwkyD~C5VkH8-hXmDK zQz5yhb`9V5D1$@<^=&!!gn1r8e+3~S$PkCs#9aVF_$xza zIGh}ILo##H{v45|xHi83pqE%mRF)vv!?ihO2(;#yrYew0k6IXfQb#)szZNC9{bA?3 z{;yt4nefr4ew6e1E-xF<`@1UtBf%W$Tm;&!S*S#%`N`JZ~YV6<{|cY zg}?ZL5Apj?U*RX;^)9yEl(}>K@87yg30zniBX*8>h=eCt<^3Cvab2zO@@~a(dxfVS zc`pxU@8=UQ{Q?b(u;Zq&Vg;yyGmN{lnko+KmC4 z3p{k{2iV(rj&-i^?>_n{$>IV%qY?9hFJAi+uV1@CpFRHI+0XFN$DZQaw%}vWewDpO zks>L$!nqE(KAqGUGN!<9U%bh`zdboo?8O|dwooSHfrsA0#mh^4F+nv~Xnn&5 z6K=PCK7QjC6$?sE^C#c_ef(rQX94`pm%qpkGb(!26zKCmOg%l|)7LL^`pjwiD-ZH# z#6Gt!P57B7AEziSFV5e}FB~L{&%T3eH-D4A^}D~$!x%Pzzw);4=f>ffv*VxQAG}wA(u?t z1|NU!c?Owa+JQ;SMZ7LrG!rZ}TjZ-Brl}uAET&j4M!-_Mjwm4a0;<3o@Si^V9_Gy< zKYRTR7ULPd>f>CGA#`%kQJ%UTC|Ece10@zn_`sv@V5KmDE*$pT;(;z}T znqU6X*HA#oSu%2#%Nf?Ka(ehUx96YwmkjuRFT%igBN(i(w)SDFps6OikS%f5oK!^S z;|c{!Dt_#TKgjPs{WLq3$9jX*Io>uDQX(45Fixowx)%S&hq(d7g++gco9n< zOJ^LeqeTynO%3BSJk5yBoisr9T-kl${xv>dr&lpHpBQoCBUXZrOV9 zamv*Ve&K~L0~(`hl!J#RHJc*vS0DOweC+a=mIqmK9fjim`oibwsW^La>;RRqdH(I} zU%$da_E5g$<6r#}frL2^U?*P&=A1qA1eb2T8ozuheh~*ikCuv-mV{{;KuOwMQ-l_6 z;R{cH7SnxYXTWb=`#P6^pBb%jYW6%{Y|!UPN~g&-5}KVo&Pu@r5A*#iY%=C52ed9B z5nH%s2%=zZkn(Rm^f=p-RZRLM<*{X9H+f*|2PyYH&aXWEWeh!9GzCwyfoBfnc@I}F zdF$iv6i;p;W*WFFULcy{fa(I8`y=KOC5FYskP#BIOB z3$I+{t!LiPKfU!5h=eE3y^VwGPcsBwdhW}Ve3-T3EgXxMz#Q!kfCkSP!#b838q05e z^2@9c2V&m$_ye$#@qa$Ei{<_F((~*t{uv<2lZ<+4Sj={S5dukqMLI*#eMLU-{cj_g zYCiYkXZVTHPxH3b2f3VogJa+d>rB|b5B%Pb`*A<+$Njh;_v2p>)4k){+c6nVK-}+I zl%FiHbY#pRJLapoTikGJ?+#p+})t8Ruu{4L#TPUO_1kIcO!3ZRi@rLj)GB5}Ytp zVTx@fwOL?%jY4rbYyLAC1%m0^5F6KdvaipVUX z^<-j<5*qI!cpHHSOO|V@1f&mq9vp)-G)ZLm>Yx!;;bmlz zTW9DE2P7tX0E0MRbWu8aAx~q@@9ndJJ?F_$k}tabk60S1;=3@A0TrBim-}oJ^do3 z7^lqCgtdH|>7>RdDMEtr3#4~o1%w(EYOJt?P~olO%FWkt7QCJj(tu7BN(gG%f)A8s ziEqGrg$yae< zN81ABBbecFoib`>~WRixOI#lFoL81$mttY5Jl4N9UPO5V%C1{;TS&5Vq znWQ9%#8pd#h&e?_g_S1eC+`U^AkZW_M_P{whRRM5K~dDF$deweFA;5Ezy`(`^dMk@ zA#r^gW0AQ=1RpOih~NEB@?5vEU(XwoF$4UBn=c4=tSD^OS}JjRqHqF^x2S@$Zra4JeSilD*t$1jRh^jm6%GP zM1f9nWYQwj7NH!Ku~_FY-k_W#ct!0?4r+%oc^p_!eTu<4UVGZg(wG`m2$Y1%)KL}U zq;3j=;Cs=+Lgav;s-p+95EAcQ1Y1RhlyOimD>U95Q=69vUK4zacM2JfsfCjz($!VMc7Smj2Oxd_Zmk?ND1#TC z+LR$yB@WvGoe1u&p&L9{k zr#U-)gLHb0)4a${zQq=TQ^#j`5IA>KGd3f7!SQ{>2Ku)yUFVV2b%q4CS@4!-&iYzH z#fv~e(kqyj`y3JlFII@n`yHUjM@;Jpb?(?vn%k6!txJsUA!|oRyd5~rH<)mfbmx6Y zEbpb{ZCAg5JDM@teh<%wH!%}`g4r2#WSY2qWUS(<=XVW*c=k{2# zZDM9OfrJ4^oZ}^WG|Z-_$yQdVF(gyLgY^+dvwa5Lsy0-IWU8QX=h@{Jx0(aSSk86V z=>Z87a>~wM-W7eqvSlNiv(xNg7=j%U{0!d)HVM2PcxX0d>Xwn+>w&DqS7paejMrXc zVS4EBA}3);%an==wr+5vIl`}RPy^&8t%XEDWngI?>nkG`>=DSKz_F~5>qGqhlH=oJ zG(9w6i~$-54Rw2$F`U+c4dBp3kXr$m5Z7znKtvN~pSy8Lk3&U&R3dZIJG%U~ie{CR z)9CONd9q|t{}U)`XfoQ+Po;N1^WgGHGz~0 z$jNAz35&{ip1BSY3`$4}XL$h7&U2-M+;;&v7&2@ub8d1IxCUGo4HP+8gYXGiQv;Dn zoMmuRORfTYXIHpQ%i?4Pz|(z3N%yW|JrMgL@jb2z!Bz;IntS9JuFP+7r~?P81_gcz zy_JVJx?VHhoYUu+k_(X495yvMQRQ9(xdCHR>~2Mm5tSE=hC^=5=U5DRvctkoA>78v zS0Q~NW~U5_X=L;kz>-b&SmT%xAyl;WZCW`a!7vc82%wQH@l1&f_eQj=o!;j4R&lMm zNjSfWPAe>qbst5!x5bc6nbKQ%12{s|2S_wNB#1@J#^slJQ}P7gIG)q8NuNiVFK^-5 zX2~HHfi>N5&PKNJb)c%3Yy*#FHLqYvu`CX6qkthLdmJ&VhQOQ2nPEePbxRx#M;iq< zhMMckmg~Siuh6oAVuj1MH1KW+OT^N$!Hl;6bFMMxWe(*TTqzmIjB&5etT{`2qHC|e z$V@<*jxgnn3&7(G=uz+tW4^@&>ij|Kc0$S#>s1-YKZ*sr)gcWf8H+pTBLR-eg8pcY zBVORN|7VC}#a^<_Jb4pG_Av+p)JH%1(f{_b#~zE)g5quw_MQK}ANS*a+>iTlKkmoB z4so}7zx4WRoI7{!k9lu`kNwJTp+!K63K<;IX{3viPg*F1lO#f;LLk@{5iHt|N$ulk zw@zSzkX0wIV+pdxOOF>CM~)A9ERKai$Ob7&q-c>rqyHcF-ZWOy^gPeI-sRhBJzJmC z+w?ZmvvU@bLrUaulW58!DQk&g%aI}}aRM6&;`|6;ApYSje}YJ`odiy7*_L7(@hT~l zwOEoPksPkWA!mlOPxtiRr_Ww{)wjJ{etgx#v7*EX1d|9nFVMh26}r2s-tW}+yw7vr z*X=c0dIS}o5>HJ~hM+9SfS0mqpothEG*So@9u+LOs!=KX3>i{nh*2UzqQNWhg5U&M zk~Tkk*SIr-Z?f_LWI!kjvO*{WvO=i}sSQ$A4FWmHW`K!mP^@>4xFNy^g%g4xV}i&C zLJ~yTG@*Tl@@<5RP|~8}2?CEdeS(jh4B*I;d+@O$$QtYCI0|B&5Q*NBqvg?&B91!< z*`f}LIyi!^P*IFFYxum6vumWPM}{ES8WRGM*x*d(eUzh^!We>&IlgiN!2-h(vvNcf zXCMQJvT2z57y)QGMN5OQEo8_LAtnU1L|A*Aw0Jco>5Qn{5p^xlev@u>FS5$;>VP=( zxtRPkEB-MS_BMsNOzzU5D5z5%7nad3AbI9m6LVI!_ z<76QCF)FF>aRUnz-ZeG0b_7|YwPHRh>8jJ@gOW}QLhaaWpJh5U$TY*s2HBk?F(E_< zm(md%n3>0v&Gj-a_A&7k7g&=>u%6pXXM-gQ){&>T|5h4kLe) zDhyD?r$V@^{C%7;tD2q@EV=RemHI0AeFr}mG*NH-oBrE0=V(dvv*kYX}soH3lH2KJ0(()Ne6d|-As=KU? zPjK1r9>g+?CSl@k1EQ-(u8d`(w5ALNPDq68Qd$RbPTbN6mmqD%vFsElx6W}i9iUypqrJyC7O!(SzfQZA za-sbm+)y_H7v+$Nq^wG^xW$QMr$|FeLC&;0;>^Xf-1_z|EAkjw-s4zylAtwa=6KKM zdx=ep!F)=uy}|k3gH3jBG-qn2oZj5RmN|8mqZIhaQP~QtB#YVzCrDkFczlfWoA)s; zw@FQhC)H;-qaS8CyFxo;yf6JxE+kK|JG@0J&N!J}q%I_LId2e&MRSC%TM|owHYGX^ z%wmTS3H_o+TxD1vHS!Q$A~Yl>MHdmm3F6SBlW&sR9#&N>{Fp^u(rd30i-g=1lu1q0 z5=0(E?TKjNyrT$1`f-BWsTdC?9F`->BqvXY1XZD?fwssXi^xv3xKrH1drO~VoY}fa zWxy3}p4j{ZC$p23`8E1xgAd9-&m+B$a5#UJy~SI!`t62Nk$ZHKaO4)Ow2#q0=y752 zC_m`_eIDvQ#S4>fFmI30B0{+?@ubHF$7z*aW(&il?^vwPnZ>t|or=k9Le`Hls-o3} znct?24{*^fW`_>|03ZNKL_t)X)wE4#-Y0Wy;%>=qd4)xih%;dY7>nk`iH@BhM;^enb>2HV%*RpLhRD9!($R>)~rmS1LA( z^T@Hri5a?WsgjbR7~v90B?`97D-@jpm7Wu%MFi2Hb{j~4BMJ+;!749BXM%tX5z@7g zK{cq|AV9=8mtvf3YL6txsRc&ncxegB;*`ZlmP$=IEN-%&-=a)L_;iej>gE<&D>~{J z=Qb~LEIUCt7DTp>sM<)|C6-;JOK@e3ustHxK}(790aY!#|B*rH3MY>!mA0^w@4$4EufX0qu;-W%3Jce6y&33;F36jDp9s3~2E zNFuzjpbSKfd)H84Wr2%xYCU0Zag9N71D{TiU5gcSj3`MGg>n^IdbCW?bdk10Ffk&e z#JWug2}&eDiVsbuZor{*jn*Z#o#6>c6(f@ruUmK(;UkBLD}HzX65B*ch1G&P5?1Z;DCNDs;_V=a6W z2O{p~B!;&Ia-vBiMfh}yd|ukiLb4p7Hn>Soj@G`3@35X&X+$sxYtT}Hi&3;uVFeX> zNZJUZT%?QH0mv zFnCp>REhQliHk_w7OH9y@|qM)CfZO6TB?o2V*L@QoH&hfIDYP@f9~JXJ{WP92f2LsCO`Y=$NA06 zU+2Zy9_Q9C@Z{;^9P>5b&U4nc&NH`yv*`w{a=}P@eq(W)1)5t2uXAnGV50xxd!FWl z#c`fG{U~1=U1eeyI0DQi+lRYs+aZI+HD<-j^e32iyF_eIMY5 z5;*6MII{u=iv_>*uM;>pcC)dl7q6?h{>p_s+9i zV~dG_DgJauYWksd5 z6GJS9?9HCX*_yNU?CD7)JVnz$6=Op#fG^ha0u#UZvg~y86$8vazTU)YXD~`5m#lKoaSQIEgT}1ZkVi2_RfRqY=btJPEeJTRSlH zNutjpvim6A0`ixDS7|`B|F(Kv;Sar;yMfUPSY;)79Ia!dw$$|yNg%?|L!hbfIQF-P zEO2Pm!iI*tl`2R>;6MG)Pjb4o$?Jpb1R7`l)!PR=v~`k~5BE6)WP62yuR$x){wj7n zCBhLQFrjhmZXfND1J51o@TG(Ow{w+UkO)$w&`6>2YS~i~jra^Saq#@q@rUWjz^~tY zlb44hW&|bybOap(5BD}%Svk!=zws-4;N15U9Y4;s`DG5x>(o@VM4$J)_ru)YJ3o*a+fR{sx&Jw)< ze8yBV&Os zB1E*(KwTB+&MG!GAl`ydlb0Gr%o>KrPu&CE9!B2FwmZ+L-p9Kyaf}^OET8_!2YCMK zYebnO(gv*Mr@rsUcTmAu(^-p6~zVBVf z@4M^W_3nCiy}RCB|G%H}ig(oX-viB-L^VaK7eIt?J$w*2KOrEIewE--gfK`J2sv&X zd;x+`I4|)*AqhC?zk^B^3S87Q{FV@$yUt&NSYn=&r3=EMrNl`^kWDtO^Wc0y3IQRY zf^X=3B0`H8DVF8G1D1ui5Y13FNYUg21xKFeOVqQ&hsL!agl|yK(qlv8R+gc`J~ugh z0ci4NsoD@yyevVMplT4l868XAG~t&{V@cy2Y1)J_0z(ipd@zK%0J&^SO9^7x*b@O6 z9Eyq%3?XQoNKwn-wTQcz+EGuN>`;*wB$0=ZAaYaSCzoU?Gv!Co4S%?Z*G z#R)CdqZ3xB{ESM}__{*aj9A8Kr4ZH==@yA5!PCiV~J0#@bOi| z(lJD6+*2Tt${?kok{Tfsq7WlOz^Vp4X+lMNb(NFrXGnDhYKK`}qlsDTt}?P?l-5We za8^x}n? z$fC{T7oWt7n3u1x}?*Tk{L);Zno3R~?hWRM(A_ZgcZ#tR~y;DhD($ul@<+1}ovv@=d@our6U4sIPH zRYX};Bq43k+L0lbQ&d-Bl_yCvj4{}%LVAhvf|az3^mC*Emj~KWpV}UAxVKN@Jk}}V zG({v4c>yYk2|BPSCq!32jXxGKM#2gs`Bsnc^zP!Oj5TQj(PxrClIG zAWk&S8V(K)@N*9(Cmqc-lEELMe43B1*$kR;|WFArE1yQPS&S6T6RSJY>UJ3KBgFRR881QRw?s>vapCKWo6|!wQ{)1 zkf|P_kgWFl)bpG~Wt=#%MQ71tQCGB8pIXeA7c*k5>GfAR(Lau&qMX(Y<$`H`M4A|g zz;tTn@q}u=z$#B2&4^V-GTR`GEoY9MVQ=>~_iUbEa=42~6Rb9fX-%SlD8bJq)A5YL z7feJ>zdFvkIYqJS38x~Gtu~2iQ5JK2yJWS~r?u1Pth<08Smdf82uX2N;|j}1-}hm@ z`08&`*aDMOh)9!>P`QdK%n8aMq<*`Sd1qDg9XdoK^lIuY39kM2<3U(zQzLas9CeUU zL~uFQNu=+hq{M|GK{`T6@WSDuFhwgm>>jjtIdJ{9Xq*+F)6`ln}encfJVqMYcXeQ3#>i{IENFjWn^aW0p zBwdZGJ&9VyR4MbrfEXu2R?GRy|AQeK*o4ju!kU}jH(eJpnLi~33@J&QRM2qTQ>wVvC;3s$@Jem+}W66@@JI^nv z9r&g;Q8FNXg0mWHJ+AU-*(QxsM1acFRL+C85IKmNAvprlBxAgjvmQk}eD*PPuWf}-?)P06o23@ z@%_CNRjqRS;0d<)1S3);w|IUqXOAA2nDXL{XL%Ut15Tdjne-$V);vf1+x*(#28Sio zNPM=%D@Dd>j`%3s+_(Q48zy6K`wkDXbYZg3&g`p{^pQZfnK6O>nAyx2I}(H__4=M(WAr9zx+k^_>bszKY^&P;qp5iXUb{dgMH13^)5H% zgfPC%k^L?F;0>T;-qZYNSH^5o@+hw$_{Yq+LW1WhprFf3&+k%D;@HL0!?zxW%5o{c zK}uk-mJwAYKl`31`FpRtNFCo`KD@!7f9O-3NbZ5S$L~G&WlAEZoaJln_wdb2zs)0f z9(wozx}%RV*QcoVzRu9SOwKKS^`$XdWf*swi(H^)zlS(4p&Pd`ixr^FT#opkzx53^`Y~e~adRp( zmGBrdVm7%!p5(CT0;gybSgUtAxBNDFW$!lIzzz^N2iCyoh;>!*xo4lF-JC!fb2rL1 zBD5aD=2MjVI*ar;JG@0D8rSXoAmgDEe+rHqniu%wL+``3ru=VT{PiZvHUo;&oVx#M z%7d$n$1egm5jYePxCrf6&b>9GnKzYAu zXBYt8V55W0nlqKkLFRZfCg+gAOAWX;z7dPgCxSSN$u?NU#s5j6aBySZ=`I5 z$jf^|KrU%!c8MY8?Q|-ICr~x#W(rnmT-!0Q&jK6G8Jk^jLtwbP0{?j3rSIG;|A-z} zxci)Z$H4dQ&-?6^zd+1IP8@rhp86<>+~#ol`xvfrH(EMpLBbkSR}(3N^9Hx%jQ@?V z{Zm@NI`AVO`WQt%B8mmS^xR8tUs>%S=~~6iT1qDfE$#N!$Y5wHOErV^4WS)(Wyj9z$=sggu4r_D8b%-M4w6j--~!_zg}{LoWR zv6?)>zx>J<*c;u%rxCSWXW~l!&exyARt7~v$tGjY5XEOmc#MccS_I4@A||F%npxW7 zZ#?rYwrKLV?*rfqtnw1aX|ac7bL$@dyU+ihoTcKwfA~*w{`G{%`5~@mXPB95Kp#P$ z9ai|u+k0f}vBH}?eg7wUznJoymwufgy9|7j@0|dD_X{`iQW4r0m@f_(G3W36!Snpp z3kml6m~wrc{@MkuE<6MFnU1ev!k9tzG9`CFz<@S??OT^QiKf7^_u5|G zZePAlFFwytAO8%k{qwvqcpoErXo(`YCJw|}hmI6=Wr&mL-z<<3f7n~}?)q-)c)q6_ z@b3P@$>yI7;!;<^--8wl0To4E!6X>AB=?1y1hgj!G<#|Ln z*g*&aHzo2DUmcdX}QE^q3|I?`X1hA2w%Sap-7=2 zH0}mmLhury6+tvPZ$5x0LxdGnSVw9>VYfloO%APS8e`#Zc3TKI>)ysQH$z{y%*k!M ztHBEbnh@H}-^GC_Kuo~3iMfy9+Bk7QU>{GpJWw@_IN@XDGG|zbY6-%t5z>K}p;dzS zp&?HOkb1N{q$yOTh&@DDbO_Wgp%7hyicn#O$5Dnp_&zPOfl>>Mc!}T(qVf#VvdBD_S(7D70DJSKz*K~^|DWl(+{DPpSZ5EUl~-@_RNu7!%gC6awR z!G$SN8lgm+(pX%WBH{od0^yOOM0kM={l?uzfyAKh(iD-)0rB#fDLg@VlxSQ$LWO0s z-(hW&n~d>ICogF5O+!@#*SNPr!^e`L$zW`lWdY?SA~cR0E1Ds$Lvm0LnEC~&gqpy} z9x$(`#8QwbjTZ?>4JxN}IfrtOc~apu7-1kbL@Gw-F}g}O8%DX zlGtdJiWp^g7^#v%7X%ZNRx9+=<4oO{+=0*zSvxYXaj|647RXc)O=CKuN9|S9z=<3p z^;io*O9C}n+GVx9L9A2KQZvZ+xpBv1aJW`XUQ{UAMz$j+YMXR*%4_z^f>Wo&}0jH>4fv|!!PN|F`Qi|Be2rtnlMwy7HOh9``V0(Ovpab+A zwKH6wTtRt_N)$BPDomsa-_~uECMlV7+Su2qK|$6{(Q4+AW55 zf>(}MMT8Kjts&UuytJ8Xp;RLdvKXRNp`@gCHL+;nT+)b8RD|_4b(rI9jrA2$YRW>; zW)-PDWheNd4EB(p9$)fB<7J-fz0T*Gwt$P+`$pXZe866YBx zm?+0WmiVYdCjqN1nM-*3?4Q6LDmKov8O(2yR4a7G#~DtxQEfpcBb={ET*Qi9$Cp0s%A*n2oSf0-BSA=9HnR0yof7Mtb-pX~i4t$2ms+52qwm!vb{4~9O zm#aI!(%k>tF+y-nMzEYNbMqp!?NC|;Nf+OanO6g<>X5eX(#cv34tG$4G1@pnUXY~s zAPbP*(W1+Gc9xCx6DTP-IJ|{j+(Bgl;XKpD4AI)akRz2sBoQt+s=6eW0-3}(zd*>8 zqOz3E5Op+>76fBSlji%^x(Y8QXuSc-p^ZdWF-a7GHwa%h1I0)ol*URhx|v8W%8IO& zGy)6fNTec_4MC--D`abxG8iltDLq=`2<8MaA~;2yfGY!8=+alKXd5%FdbnE9PF6u? zEc^%?-Nfq!K^h1p$SGDrvc5sE3h4scIdEfK9jHq|?G;%TEn_sIrY=(pkU0X24-w9I zjF$viWT!AzIds z%iO{suvG(=mNMY61T;dek|n3; zFK4m`S*QsEdmWi9sC7*#TNpHn=-}OVN1>WCB9I~Ja&>gTvEJkKd*}F_Xa5iG>wJjP zAE(YA%KKW71H1G>oU*p*~-=f1! zP62=R{3C?!3a`EV9J__3bMi-6DTn;z#?fLi41^VTJ z8_AIN@sz0C;Bb=g#p^?!c(4Ef3Xw%E#VQR#|b{Ne$7%Ym#1 zYJZ1n_*LK(V&gP-QSV+_l!T*6jUYk-CKQ-(#O86&!QLfYeuHRjg^pThqttX}-{i+0 ze1cXzpeJJNG~$7+hxxr%U*n!rk1`)Wk67&T15Z4_m%e?ealRr++9{=7N4HOr=QX#S z=U2Y+7B+&pxhok-xV?Kw3&nqY@iXk)ewBkLXGWWXMKet6o#4*pE5L+|xFH-Y&*Twg0*EM6&84cqN0786)y#trByUHdS%PQTXR-v}hz*^s zkV(q_^rdH51rBaqrg!TyfANDq#Q*+{-(vy1_rv$|t6#lL8yFs5<(Z?ae2at;r#Si8 zN7;Gx6%+*}V}dhCD*nPpKgO?r>30z^+^V5wPC|x7@P%)_jKq<04;>EZL@77Q8iZum z8j=Lksv;o=_7MIweI6&nkfw?+Jo_9%#^9O=H&V%g_9Qv{2Twf2Sszh2!QXo2C1Or- zYkv=DF~?Fbc6e{^UY?&GV_tOVY&<~0kX7xNP3PPokVSK1Gh}@EpYss#=gvIAKfHCF zpZWCDEEWU)*)wmD0*8JDVb9V{j#E}&;YHNJFkg>Q3#t>jO0 zD_o%LK7lVb5pIT!1e7CY!+n~-hXRR0Q?Uq!IW!RpE6uNr<|f$!{_N8q;fc_sX`1KqsLja5CS1V$?yDPMNw01 zM6{yH001BWNklGi#KnZ3K--T!yjyZis{`W{Sw-;re!{vRs( z@6vLv)8tvovcW>iV`%BI(G7wyjqB8@CbP}8@Uo2vGpwB8@rcmEqZ*Vm27*Tg(Ksc7 z1d)RfO<_XRyxkDtq;K55rq?(uwQp3wP1W5vE~H$3R-PbgLTFHbm6bTxLaN4zf-IJq zz{|tNa_AdEX!2IY-Gj#xFC^^J0o)u=giuSIbBgeiK!Q-7;4|9k7TzY*YJx@KWP}f< zc}qy7Z=4x&dHfbZAVffl3V}o-2tqf10D-}I0U<$pfuuwc(4iUj*Ak)-(Q+$z@0k~l zPS)c@_ac%hhw>^5Q$ZD@WQG-UJQY=Cu+AV{g7G;{8>I47;Rq`O%Eri0lEi_qR92fJ zAR^niNx}xsIlPUKA|ll*M6oA#cR(!N&*JWIRV_2?Vw8w+-eH|!;l_wM;8@_5N2!u& z@e08SEMt-+!{;&csUxTkove?oEw~J?GNPamA;o!z6A?;ztSgbhf$&R|XXCh*a^ARN zeT49;F_DMHZF4vOw>kGV`OHBC8a}H>C`Sl2LWrf9K;f6Wb=UA65Qq>Vh(TBcjzEQT zvbl_eL#u$+5!N{7#U688;v#`f5(?>YQsHY!5>gxmURtay@j}p1n=I-nm8=m` zlE@S-V=|GFWo@+XFz^;-V>~T{teKY!#$rTbG+~hw$C{yVym5Gy&b+`TGjvij8ZL-t z>&Pf&-kMLzRS*dEr*=LNw9lxjmF z5TsaZDe8(|OB0O6x*AVJr`=_~KjhN2*AR(fn$LN2{0hoPjNK73RkUc~V2~e>#3Q1X$IW74W2=~<`=^V)NtdWd;7V^>a@$f!k4$5@vn| z%0cXKQBAHU)IPAfP^4u>l+?^!4mzT?HCZZ%+7g_nsx7ZvdX2Qmc=K>bQ7(|BBDGzP zrzc4>MPZM~{RC$X#!i{}BQObLJE5*T;q-z*zRlIa>+G0YtaVmc>#kESju>tquzsLCurH!M8`IJ%w_{bUD94(K?=i_ z-B&R-fJ!k2R%9RR6|618Fb7lK7#xICeXs9LDBdj73U9{KO5(oir1HPzSO*#O>B6$Q?M@DXX0qT@E!H?G>I z-UFe*htP-*U5uGzU^9Hk393d%4XGp!U33T#a^#ZE(ufcJvI*AYDd%R0cN(p098=IW zUPyvhIHl1dA&Ps*`V=lG3j&{v3t zb|bV#=malf5LxruWD7*T%!72x>j28a(C@4w%$!@hFEOz-=TAOLJI&ZVsEFGsqf(N) z7~N_S#|d>+eAh&>T?%?kS*JrHW43n&1iI|cL7~W^2YJmrLYFQdKc8`P|C@m4dOhRI zHmBx(+KlM(CUZX}-E6VAx*%^(8}xxen9&cC4u+GonAcBoFucO9ex3(g9SW~8<&68v zIY*NNMvS@d*gAuq*IA8obd}TVBrvx)At{#omDw5&hMb_{Mmga!aFb1H9zl|kaf{mQ z6H~E!X9rWg55~q{{KGITj zMl+5=0a=GNU@vq@qldY(->2_uCP)&!iLh5WsZwNJvy-+NvUocdHN=6kK0Iae zjLD%_Lk;K4#z=caK~9WIp(-b6^CnF~=!A7~iYjh1t4E}iWU}Uw)jq?UJJ34MSV?jW zg&R>WjyMk7ySBl%xx|uBz^4H_2``NvTP8LXkGD#AYbkv5~}vgD62_2MVIZf{_F$f(TXh53Kh{5NRb+vY)U<_o6VlPs=KOg4R^lxOnY2Ye(ZCrTY@A= ziqbNmI)%b2RNXrJoc*o6*0;X*d*7F>^AGUUmFKACgVbyxjl~B|-mj?U2N+#q?Ewin z5r-z}nhohONE3W>%mnDs+eL*e(SA4cd{zVQ@U{~d&Zm?EOZ;5vBnF0nS?nojz7 z+$2yn45?WaZ_x@+RYY?WNBPG^bNK@T#Y+l#C$!w1H<{si4w;My?JbP5C=HEk7z|Q8 zP;*3wA`YW9biJuZ9zwu#V%nn3DiAKpaSeFx7|A1iepM(9wm|cfJeD+^FH+cYqbakNL4KSWFyG~x=xn>3+C^bJRaMzas&lmE3dB`J{S6Xs5J(uR z9OEnE-T@zFoy~NW8F1~^6&|DWQr~nHDKH{u;nwN(KSVw4b)`fDB+I!$(dCB8AwiZT zOJ%+Ja;o=iLRq!Ump@&L&NeLpRvf6I;qb(ghE8cQ%LRwik_%^^U}wHdis4Yrak^kI zw2ZPb>P`=d#^cddRp6{e8*_I&?GW+aqJ{qF7I(O}X1`0B@J}J`bT9t*;(ssx_u~Jj zI{w5Z5c+%N%kLdBAKeyF9unmNQPxD4gEz!5B8meF|0-JSBE%{|bs(V>Bcw`+qNEMQ zlKId{(g`Aj9?Go&5cGb>t_`D(Jt0!OuwV{R!jXy(5iM9eF;qm^F@U86L5d6AU6WEE zq$I=uV##Rp7S$77UF_~@G`vgZvGe!q3bvi+T8tep3_LLkgj5}yLbiyQBEl*}ixA5q zpJ+f;pbsI=JOALA1HNNoMBTBrpp%@AIYNLGbytkE34#A6^a>6M(Rd0~VWp$r z3J5LIcrvG1soxJCO7j|dIwNy|5c_y>fd++70*RUvjm3pXv>jX8>xw8E5}}Y9Vp1U+ zPZAxXDKRF6){rx#@qtP%P--0$A0{Ah;wDklDA^-1iqf8RMNc8``W>?b?>i<;4;dVu z1vV5^q6Xn`QgmK6KpC~irBB5XQxODykn2OuGZ&Uk%^|PBGGj>nj z#wRxj+7e<;L=dC}(GX+BClra~ou&XXgmNftvEJjYSz7&hv6;!RKcO-$h0Li@U{lg;1=O&+U$YyC zu)y?cg77FmAa|?0Km9>Ys(lWdmXH*PAPB)x$z5DLrl=!+bwJw~UOIk}MDNkAA7Mqw z_1PY4$r`2g96L{w_GkwS+Ga+odaS2s*_eKe=u>W_&l5A)nq0tFQ|x#fl9oDJR3ea0 z5Q9WxP%?ly#5y;T*uN<%7oZ@@OC008o`UFcwru&4lk4$=mxWKA_OEghI z=ua>)V;t6yR-p?;RTcDB4MrFq96ZEZ*Iz}B*J=EWpbXLHWO0=TRz8f4DL41tV%}aQ z^@4G`!9Z@&N{!E2wAH8zy!0fkVS^D)NM4$JAN4@aB-^E@a(d+|(|C+b=d^l`S00@v zG);rY;ZjF`rHA(oCt*h3@6j$As%C*9L1Y4vMSRZ^=8*>n?;{+6NfX8!Ln>7T9Qm54X9wg!cTGW76sRoF*CXnpq!9~x`3iY6WK(Zq(w4Lqthxob5y!O;9JY0X6t&1x>Ex*D} zbIfJ+F=Q0X+P4rkvN3rdo5?2IvlnUo9%nbtQ?$PGZ#NR>=Ja$*rZck8!xVuqHJq>C z4?=NUy~M)I87J?fC@tiH{7Wfga@V5K+4E6?P3!Z00iw7pNVHXtT7 z?QqVlzQ$}`655oREXcPu`Pq~Ijwa5z-n)WZbIfhR!Ttd%Df!@IALJKb{YRv3g=*Y% zF}P51G~H+A>`K?nG?&OUkgT?-#FH!%Ozcr5npv};pPF~1od3|tPl~N2QtHkQ!5Cze zI6r59{tXTmo+y_fm)Us-4D@SVtwjcG(%?i*(l)5ckd1boff=H(OcwiyAxNEK)0Bx0 z1aT9W3PkLqgr=wtY3-X}hm<-pNYB#97AGrYR-xhqlXS`iu8m}I#5mo8W<?S!LZ()p0*1B}dRTuo~xU>Z#9qnsdC65}!k$vXXH zh2hGWgX05EiUTkfl%wzqoD3w1M$~~U2&B{qCkR1dgGQ>3jL;UH5{n1w@(2+$#w2KM zDCGezm9)M@hK4jI#ApZ+d>kN~RYt|f@J&LiuhJ$*lsX|ug$yZ@7KQDa!K6hB2{9pr zQ`Rh~{1_k04v^L}q&}je#0H4ofH_!}|KJZz9T)blk`1wIhP(Sdeg&dLYuhoAT!P^e z13pa@iiLWHR=(9)hzQ?VOGF1G9kcv2r@lK^njVwc~BIK|gj zDcmkZgS8$XEJ%y?k{AtIXCyKus8xLJY1AE(4M9*e5n}q&ygrkQ%&%k zpjG*voK5CD%wPY^U*pX6mKSd9^BWV#lmu8X9v+a+Tej^ETjS3X>|6XFzx73O4k&TF z{M;Mxz^7myC|Ku{*#rFgi@$&Z9+B%@3scSkf8z%pBE!(97d#(*G($g-Tm|K4h0$tR*$K z_FrRdZIw}WnVWYKT3XJpJ4moLdj^p($ zZoT!wQVbVnZA(<*nGqqq%bOGIJ_!hFicGYXe}Zj$Q>Z$J!YNfntos5~&Hav=~krd#dfkHA-s0 zotpS&s?&A0%RkrtuKn!0#d^K}9e`dm5SnhuS{~CS5QHPx3Q)x8nV;52@<4R$?_h-f zX?*?uc}?eH67M4Lo!wRE4IG0+kRVW<0!Np`bo-Tbv;yW4RK7(&O@TM5<8@}!Jq!Uw zfv5Uoy8XWkC@tRg(eKu4-o3{uT-%kx#-o<$^cqG%)j5grD^K3Sa*JLHiw26O#xJ+u zqUl)pkw}nmk}9x}_j6_^6$$W*-~ClA;7N!md{cLm*LpMpi>0yMXL3~q{T?)BcQK%; zYYe)xOt^cOI@LR|EJ>*dUc#*EzGtBX!Kd7kEwg2N*$c1T<^{q##rq{f8=mz<}xDfY+%m+uloLwxz#ZD#X*Dkgks?~qSDc!B-BCm|i6*`z81RcS~@KY(kl z65NEcyRpoHiA(vb5B@M;zWQrylTxt7pMB)t<^$#eUwvyq!y!E`@-xr;CK)vo;C+AQ z-{hZs>$ez@(z1!G6!gzSqDaz~WcqC~8VVxEzF-7=mgZgm#uix@srcLv|0Vw6uYHA-u4$>lvcG=-oa4^XIXsV2@HRjH^7nbP57JK= zaD^eetZ)X0N1r)!X1OJpyONQo4T;(;6GO2qfc`F{_&xsq-uNDk{K;PbUi|OH|6UyK z#s6MB{-nnE`+~cR>GZuL9}7hk0wEoa0{n~+Q=*7i*&@{*UKc1=;Dbhr3Wq}naEQCL zveR!Pqe27&J_Qj_F%m^5(@d0j(Mdpe3>wJOb$k>cjzON_L?_K0mxmb-VnC3LiQ!SS*3p4$ut75)m~Kg9s@^(|PQPfHok72W1IF zJen99Og2YLMRY@|qGm-XE?&G$h>F{9?RG5R8f1v*AQ0Bm&MJa7&}yXVx|(HB1fh|^ z5oCa92?$!LJ0|jyWzm7Zrwnh8l)5YW28W0df$cn=S$aw9fR{^)>&P;`il{niX>U6& zu$7(|GVo(W1n&=U(PDxi21nf-qUDf0y^mH(e6xpZJdfV@gHYG()+g9dAf3hrK_FtH zL3lwD6p8O7qJ?nF9^wVA71(HyBE!iB7i=eW+FPKMCsvBk7)I$jl{_Sh8ku$Trg05@ zB==u>18O}Ik%4ACbt_b77OCoBU3@; z8&nPJ&3VT83Qbxwn;oG`#f8<2+&-QYn!u>n=l+Kt;Q6<&5(G@@BWMF!jaeI1bSFo6C_mLp-N9f#fyvYl8yw?wXB#G zwA4gz5y4WLhH2K4Jg?&oojfj_U&1(+DL|QX!?JH^`~$f_XI~5)ekB zj6z3=Z5%FiUQ$XJR@cVdzP(3iJmX6jQATiU`!=F7oX^f8=bi6mB}$xX5MCgyq%jR% zdXR#uv?v!*%FqUd(HXIcRCR?gHErFXe2Uf@rzIXmw1%>DNC{al#W#YcXvh*lnr2i* z!HpZ&Xxf^U{yICyyR^2%R8qHPXCXA!%RM4ujKVf8 zd&fIyp|PPM*Ev_WUnk2_Ah1|e$f&5Ig;Zg!Lu-w10v?Nu65$mxCd42hCZyzeA35AT zqHJsOUVDs04!aOv(uZZOBvxWneJK8TPi=Ej^=bg$o-O(DfF#_8f%@Bz;ZvkqIZv z^ggW!qzsT=ven;U-fHwBVcb8<$pQFcj=E6M#5uESg0CDK*$Sg<0~>N)eEs|6RHRv_ zeDKN}ub^Z_PoX zp^;wE77Z?fm4dO@fz>S;n) z?!kY=f~1l;F@pEY9YFxJ*tm~#EvZ@Q_6AWcbN3Wt_gi4W7o@_H2tndJE2__h(ftrT zvM@{zCnTd)R4OU$92<{ONkA(LqGq%jsN60vBOR?1nmJc*yo{F%l&KN2LNA%}#0H}> zdRYY3`Ccbt$i=mb$e6Kv=N4@NE29k>;W(P^p@yqe&SFJF>?=ZqI?k{$Lzvj*f6*Y& zT_arVWT+($jmNenuB|ab(i@JEd1P7%tPR8)2vPwRje4En1POJt5dmg+{bXAI46lCW>+i>bSc=_1*Uu_O~koo#tTiUBz@^yZ4En7z9EX zq|`_qaDGASXPugj(rA-(evq+K@DWj=jY0@P9crAJq7p^p9kY6Zkts6mf$eku+517K zT-|<|>2#0&ihfVdCW-k;e)ZdjeAGYBM>amsm6J<|VZrg_zoD3aogpoM>#@JhKYBT^ z$S>nbDVfty;zdflc9m@XFA%4j*!m7XHmJEg*yg|7eVKpj!H@CL<~I4&m-#d2;bwN3 zzw`DgPrf`M@C-Y%9nPa^%zgCiHb3&vfWLip!7XlcfM!U+2*(e9@ZaOw>mOjYk#qg< z@A3#o{HK>*EL@@$Z zSkE59y03Fw?Q&cl^6aq#BU$JHU#eQZel#OFDwf9x)qfR+Ed65Mk!>ELm~MuZhnoSZ@IX9s;mW##_>3tgLC}N>>0+rhUd3m;QH*4 z-B2)M!GC^mKz@3brc-dr!wiN~=JT&|Xt#;n1i8yjQ2gCDUZ;m-c5_C_fQFhHhd139 znE7MCu|0jRqZ>~@u)_d=J0$!suf0ODglEP} z)*tL)mdCbMXZ-zVU&7HRAc-uxrWSLXk*K@nDl}L`C*Qohf9)x@=z+q&^XJCjEn_9I!-e&7MO-+D z1SF0?1ieJU+U}!h2AvL*C^&U6257``+4T1q3V$S+I4)~Tcmye$oRm(@#^bt1ZQp_R zu4y=ol7H~RGYDEL%<{G`aLni>k+yyB{FSxR%Nz{)X`j`V4R-flAx4-^12DjPkDz+j zjDf?Zn9Gp3kY~~xh$u>`J-{kD} zO@91iAE%WgzVPf9n3689R8yPCfBn?=0GP5v!v|Pd`HwLw=iulkfomYY%j~e?|NQzP z5@_jzZ%Blr51dUL13-sOhAW?@EPCis9~;lW#DFe~3>%{1^D*l`nA2jF-Rl{~+-Q z`ba7|e=Q3(V1&amLt}ARDgic!SqVRJ`x<9}3&5pwTl^0%K7$7S&ZFn}#;Z>;U8X{GW^(}kU*ue_PY@3IgU*$g> zJ;rbLclp0}uApz--lqQ60`DW+zqZf*2a7(=QBf!4irQ>q?~o~$95ADdfn+Y^cb1T)UG7NtB5$jgeQ=~ zV8shGu0n|oR1nx`@yo93AT4t6CNT!)NrQ8NHoJln(5e!lTz6eOZLkO-P%;ona8e;7 z1m_?)YSp6Tm?T^#gqj$R5xz&_E~8zJbZ-*ej8?yfkQOJ72*TohM6>~wRUpfENiii$ z3B(kT1QsaOBBcct@F8}9OU&?q6%~zb2|gmFCdxpF6+$RPGN()$uGHJ$r^KP9wUOiM z7$I|X4roV|%hN(I5PHbqK^nZWw7TmYC!QY2mPOYk_^Xv%`Y(4<-;%Dl-AQ^jpcfzm z#6ibM4};DNS{`?~berQFLnKG3GxYRh$QUTa3p8%VaBWP8k z-4*P$Bw9(339VKv>N#8Vv2upbj|r(Gwh3u-hI8&w-X9(%lnu9bu29<<7cX3-Y+j*} z6}b{5zK3ZwdB4w~H>TA!3vJnp+Z@c^Mwfy*Uyz8D?eZn6-U(VrtT)hTjF9xlC5!pX z#F&%z5=`PzLX+hUu0EiM$FxqPrjd~ zX^LcyIwzSmj;9ZH@zN8b<9qTcLe_!Cr7S7s9G?Yr$dPq|_KHD&i1Tw|7?8val8mF~ z1~|(g_AxTSOUTjzLG+lNOvv(xLZMGL-vaUQlXJWz$l5+8I_L=dy2_)k02Gp{t)3j z#cYC=FzQRLmEWb24Mo_;#lVrOa5~abA+%y)15r4vDG91UB5>ZakTohAS{u-D6>393 zkjE8zp-0w~jDv$ZLruW?3BuJRaY(EMtyi=-^6`*N1@yv^Eh1;+1Bhx!TJ-qfg%8vA zBhS43o3vp{6f;%^0$r`Jy7&N#qN3h9q#jQRwWdi6jt3QuxAdxlg!0}Dwd4Lt4Jv+ixQLOhzyd%U{i~VBN{D`5&C|E zxM*1I4>_zQaj20drB`MQ-4H7)%rxPH{ZFuASJ|6hp>3v=zT_m%Xf|5rq9pNxG-MMC#6p1oqXJP5lPIk9xE2V3s5~Z#n8c8X z1ly=i?@qdRJY2g{B{~FpbtFY0V}_6#p&OjGn6O4B43`EYRz@ozS`Lr5S=2k|yvFMp zb9+qerkFM1>C#tp!p`ymU07rM8`4bWo0{1ImCGfksr_-b|q1LJTcs;%Srs zpAoG=Fvc0UE}p|D7UdUYambo`5UDkFa-Aj-H1!hnl{?*jP6o^7GzeH%BFK<_6@f;? z5r_sYT4d(1))SZ!)XQB1q^c0oEz=3V1pI#&>y^071;Y|zlFhs1nE^FhHXha}=|C2= zyhs3OIMUYnRK!7&_o->DVY_gO5i9=@G1g7$QZ#E3WDa zLW!0ZuqY9cD1vnzCC@{Y4KW;Gi~}i|SAw?5=%uTeG{e`9R7sR*5nhr-Llsw{eQy+r z&e&tNXh^7tX<+UH^K#BWRgC4X6=tUwfV0+%?dEC~w?a{?o-P92Y4*yOchpB-SIJ{reaV2DF4 zD#qEvOho{Z(MGtC%(={zWKuJiedeo!rC%!`El%7<)7+IFJqOeWSLokABmjkhiG^#y zPynR@d<)4wXa)X+#&>{6f@O_2Ss`*vU=|_jK6UKQYa3>Wwkbl-nbqI#c%)i%o}g(0 zq2`1ECn%Ec=^-bOkg!i6sto0GJPn#_P%tEh%h4 z$Om|(C>Fa21jA%N*`5#;luIn}*7S%*_Ygo8Vuy_O1oHw8Z1=e$V9+=;dy6^l!hPH+ z-b7Fl!j0~^Sm|?RQY}H}4r1-0h}00@0wzed>2XX9B?A;N<^WirX-II42^1at9$7Za zS4cWLqPTp-XQyO;oi63wVIU>aPiTqM5|9Rj$AlakdsGOVIf4Kq-+fI9+`pc1^Ppwn zG>##X5eA9l2*f_YLCO&zX`El4Zz^KcomG$Q8c>_)Y3~v$t9M$mrR^@(S&||(I474j zI7{S8LG+O}yo+or?jG;&f?zr<@tf174v9pfmK4rz<@G?>`I-lN_hWRhr0&kIp#^8b zYlM_UwUp2I_dwr24Dpsg`fa?0+ zmm1gIb($sU=z*x0bpp@w`pbRx?$lnA1Y$(SyO<^6^#99nx;5W*D2{-O-7_T&)Ga6p zeU*{;8U@VNa!pSm)QUZwVr9k&otSV0yg%k-dWfVV(Bee`v7trKEP?JQB!rw|W-wA9 za3q{ye(ae@UFX(s}JH~{+{((E(DHekFb#wkvE+GUu7NVpRNo<38Z zGsm(69Mv_`Bw|J$4zDqFo>rXYI9cO_^Gs+MGocSlANYM*^BVLWYi`CsY;$YB_-(x- zwSv0W`S6}pF!QkK=iH_Pv~Oy`gwCSi=-_46dmrJXC}4Ji;tfXjEO{=esuPHCb}*)> z_Bs!9?TF9M01FU2~vB6lC-WwiBbxg=kFzWwS>Wj}i>K96nWzsy)$Su)AjpQG6hie;q4PlvIJD9D z;0YlRLWJNu5FLvU5+OQ3GRAmU=ICz03{XlfJ#aX6d%erN4)|qn=h7!fc%mql-@|sr zNmBrwl(P`#9l0v{5IlqwNkoKB(n`2hhzU|u5OP)q53?wbC}Zc*lE)OOG(oh)rbNpg zM2(Lg7d62vtb&=I6QZMuOKHTlu6I*}8t*Ft5+iezA0S+Yv>Gctq!m%R4m?~Qh`drb zAZUp*n$}u&<~M0iEa|GHl?!TjK%_;e8j)y{m?DH&p7%RB85uSB5h3Qwf=Gi_HK>+I z#5=cSZztV9%LJ843ZbRQCyaZVH{X7WUT?&a zJS6lzJ(Z%OLi+@y;n3eCNgcV@D6a@=$!PWg;SB>;IJZ&YiuFxNkW&`&dyTMS#Q+gU6=<9Rx}lbjUC=1s_NgLs^u(^6G1de!!}l zY17i$nvh6@iUjAe(W6p{$Ffu0Ch7MG(vY|uU-ig(lDauSm<4I7iNZ5q%rM3v6HntK zK_o_PB*GFlyIG z)085a;qjP8k&7M!xk7)u#!)**n=#|`3~3+gMM>jl$N-B#biXF)7~s;ew$`UN*g!aF znthtuBSOkJ?~|uvW{b}E`N8`y(K^TV>$eyUMhsVb>>M2tg=cNE&ulTr;TVs`jPfxD z2M4&OB_HJkDVVhd$ZkJ!&Y_e*WRfgNXazKjnzi+HVr-ED*4H-ZsWG?qcZhLLYBH+h zf;=(E#NmA;QwgKt1}#uc7BFwPZ#lnPO3L{jo`BGOyboMDf0mo&Hm&Njxp9fCZ8>Zs zK_#qjZm@mlErjwUL7<$Zkqa7U@!pfGyj!DDz@Xf<7BF7DAP0lk zBft6GXXu$8VFRr7+}gcEIcvE*ct5k9icPacuk9hG4r^)_gFR;PfFNE$xJXDnMY&*q zahs!JmpBk)YKRFDS2$KyMuecKbjupqt^FG1gP9h`H)3oSrk)xa)|d}r6Nd06D+Pcz(;{(KE}HLgFaq*Vlktx3rv>Kx(a7K%1B}iwALae+CP2z(>_palJ;$ zh&G&psHfH~r=w^<1Y|U5l@ddZ4<$`} zqqC)m2BUh|Xge#EQw>zHEGC~S-iQvu3cn5Xl?W+7dZKVkvWF*lhsSkFB?LkY1Z4@a z#n7N-f`|qYGh`Tm^msL;brvm$q{#|8q!1!idyIDt2?O4~^%CAif(-Nq3WtAB&L)4B zf0xHcKZM-a;Mw`N*=7W-=ka97UwiC_c;NVHzWnCTQ*(}V>xr!KV@krQ1 zhDezYnV$l`iH6280^SFF_QCV4tPl97&%VjtE>sLSu?w_>pMT+1Y9x5beL`&(7*U~H zI3qgw%^@{E`hidIp`k4$IM78`+^(o;gd_GHa|cBYlcQZ`7+g#_u$F)(+68#% z^~W?#!z`S1I8I-3JPW+-;QxB#8lIdPIXwcjmO<-S2R2DLpy3b@vaOVx_3F*kxgI01TOx(+N* ztk|OEKmOD|kM38zd3&GVy>pX8z?vDw#-F0nC5ye^L~(?nrbaSlz~R^r5ERsELL10q z#>N&ua{fg=cJ4g!xHGKpn2BeUrR1!p!ouzQJ)YPS-630A!{vyl$1CqMH zUXX0U`E}$_0D-aH;OG{Q>(2-T8C|Ew_neZW%)n@5Ub`~@e05`)K6 zpydnr;1J9aDcfoj+C0CeN8s=OH^BE>sz_M&nc$ehxW{!2z&w=r5SXIztl49rS6kE< zK1z4Ehj8~W4>$tf#qsSMP>$Kqz!<@mYdJ2qtlNP!W)nZ?m^Fb3S+6<(UCtqvevFfj z_t#`3gC=L@#t?~sMP@tbQx1C?6~QW!B(!6n6Q@?>#QXN;nur;%#Est`l7m>{g?mTPtzT|#sBf8cMz4}U0|U^ zCX{)F@`^}6q423Du#b$th=>WpJ19K$`2G$lUrQXvfIeoj&?`4f_IZMiV}`{)B=XzH zxkKnnq$D`<+2Nq%O=<*+nmcs-)vNCk$UKv5etaG0j)>(dI|GPnyn6@gHp9vPfaE+H zh2kD%xI_i4nGz^iPb~M=3oaLbz)h}lK*xd_Y>As&Xzp2Spn`(Ax6C58UO-Z@$97F!n_t4ZwAh z>uBhZDY5DfDYaxLCVa~C^}qR3|1z^{&+vtJ5)1h%s`@gM;kPiuZ47~$$a?qB^7iU^ zwoS(`-guoWZ|!lD3+NO)F-Ek^1y4z4sD>a>N+Q3*3nv~G{=aX>>Ha}|AFtt2`#);` zN5`Y~e{_7G`T*Y^^`A^82no))@BPK-0}^2b!W78WsF(=3psz$`?TR+<;9@f_);&_V ztn8ACtVnPOHDKa-Cj14eddi*Qe}vK^!daxUh+>XVJw6nOBypidsc}i2N|M_qsVb`> zbBcoAw^<*-YJD%;GRFxb zHQBzAI2QCGMHT4#79TZ6Cy*9DNP^v@(i;?_pj&xLwZoa63+PGWaQ-fxy+ffi(N@Sf zK`2ijt~0op+0ErmbkP!$WAF)7M45sn7-Xt&W`Z3&Wyr<9PH2QmXrVAt;gcl|6-|Gh z=g$5Re%)|uei?1v!lpyws-UQ6B;C@6jyuEa=t|)VpfcFuRfsEOxtEnHah7|f>N#cL zrc@JsO?gr6tj`?3V1FeT-q~h+YtqMT&@03LhjX2})fMg2Q@2AqtG`sdTpK>}`*b zpv#6xqO$`?@lzN+~ zKhLmmFnJGM3;G+Ho!K_au!j|%fMBzpp<0RZmg!DneeXJQLm*U%UnU9}*;DVZI(myH z9I#PoR(_yW4XACb-(+)Eusk^6!uC0+FA#=+qbIrpcEdJ5we|0^Ua$F`lb>h3J!e`f zj^{@dQqUATm~z5=ZgILs8%+!WTP=AWG#KSp=vPhiVU9 zYm5k(M&YfZ>Ko3<^R%m$wq7$Bho}_m-ZK;1y!`aXP;QI2FTF;r45qGG_m09$sLO5o z(6KTepB$B!Sij(Sv*+`Nd(7;NSOk15sG1G53AE}Szuo^bS{wReNjJ1eDJeD@L;w{e zB1tM$kz``ISg>(^lf(5rRLWzGF$NL94g-}g(MDoBfpH}tdiG_O?UHLZuQDm7OeYOT z_JE;xJh%NEt!ueiB-){+Tvq@Lswaq+7<*h;vFbEi+h+(NAw@}an%Ye1*HBDnq!x@) zSQ**BdxxnSaGeDqbM|LB#dd;ao7LO>u;j*j?-5;~5C)fe?(7|qgr}|~>){YpN~BaQ zj_1TxLlw&vLzB z5C!G#7G=G~(Di)$!VlB?HE*7L1yu!v7qIG?77Z7kc#K8Z;P}>pC;I2uuFr7W-{Ee1 zhs|k4SXm^34?Xu1Lnpa@{U&9VEibj%V(mIC3s4>t8QPPW;5?8Znnb?~Sy zO{I$OaxI%ifG*{n;8Z{?Nuoi99R!gi_OqHZmZP2TDU_?av;Y7g07*naRH*0hQV^Rd zT?bm#=xN0;w48)HRA!ET3{pyb;pB_VngV;)(OJ#v9 z^8`!Rk?2T4u`!*o_ItRPsD;X4VmYDnlHROoQ%mWgo=R+lEAuz8afL5hgccYj5Izyw zf^G8*A2|Cl)M|^X*REm96J%}CCgADtewmBCD%(l7wxua6RH1TCEQ-QRkT`npXjLT6 zGH^MhmZR0dgQu&rBVD0Obd0#cV^CD4CZ$Bzwk&1N#4EZQMU4;zQc0jk*##G5i|~=b zPZ-pSfb3+!aDMfTW0#Ldn4HII&O=YGC(GmPT&^M{d1nvxWl@Mhj zB#$Wzlu}r0vu;Xig7*k1zkR`7*a!K$Xr`9d+0_GqNhjW>yzC2-n=I#sv&B#FL0;qsc$YH=C;aO5f53U*6TpSl znsvB|-QDJYd+k+jkHz~x_54{5TFbFl{OUWuN#esCrbD7V;b%VaBYgTRe*>4x#(ee* zZ}1%F__-JVJYw}GTJ(JSonPVu^?yQV3Z{!={+&BZdiw53&j+PqjYyr4z?ux%%AxX>fVgY zufEDZdHaj}m5;s5yJpVMf9W>Y<3M0wi^P{-`8}Qo{(~R;asKl^_#8e}41GdVj;h$4 zg;`)Y5B%&$pXF@7BA6Zi`!_B#XF{kvgIi^psM$dKZCvsM1~3-F5|pQH;O&J4Gz!ml zJ*Def(um7wyUu{|bX4gLSvq>)1uG`N6VyazT;j|KLjT2&{wTIx^O-AO=Y%nKCf%aP z@E$cVWup?9{)F}FkgJ#9!aI*8K9JLf4w5H^?AQ>JM*_e4`@cs`1~C>RmxD55S4*s& zXW|IiJs?9z4naIM6M`ftF$}7J<-pfZ-r~+XuT!yyy^k*iLUK4VIX0zJ_bH7Rl6yl> z1-yCn8XXE3j!A5AbaV&IOHfY1Pr%PJ*u!W!Ge&}oQ#Ec(V@*lmW462%Vs_s~KY0*J z5r}>BFDe>sTZ)Ky!ix zP_X8wf8r|0!7@$?@Hb2qFa%KLWq``%iP7xSz~`d?0gAJ_FL~^j&`ldgkF< z5bwVq@$k$jPgxQ*cHyXjpZ&p)<5l9Xed#s2wPRyrll7|OG9?$99ccIXg@5=f$Z>8u z?h~ybzncjZ8kO=pA%w^z#BhY*HL}KjMHEoQ_a!AGVy0@P0H~6yi*~F)AA`6{nJf}d z6`+%Vd=;F)bBrh@!;tW5!UCI}19Zwoo&d?N9<*(kfEOs{2ppcbNL)gpF=Jm$z}+vJ@QjdID_X)%!f<-`n`@VB=i1Nir0HI7VlU5 z`fvTs(L8^0N-ZF3wXbm$?h$CwSazok?W$$SG7;7u{?Fg|Rc3scH80RbL2R#Zfv@nh zAAgA=Z1GF4f0h6H@+CAge)6ejnX_i4&vMl-(B9|lBx4MH-;Zo;MF;_FM@7z~!v7z8 z@aGZm^QiqFwg02`f7JeufZuOEymLtTy)Uq2r9rkoPWZgJ9rvb0owp6rlY~V`g$z4c zu^^VD6c93Jsb)($P4tG~CDsQR29zv`C=!vFEGbwb9U|7Gv>=&4ildU0l9cL9r4#{? zB3db8ki^jByhaouM1-TWmHL2!jI`kZ}X=BvEuE2DC{i-7{ZZBP2_#ElNj(Iwq1x zw1j9eGNCJjmx*Welr#pQ_g(ORewz(AIG(c!QQ2*C!E>dCIrjT z`YP5gFa~0hq#zL#NGVX#qv%LM6Ji5VAybFIk#r!%ga`!+h0!I}!S3z_Vta!$c(8)U z&R^uSj{-9 z2|kem6mmjLHP1Zv4DVd~5+Mn8cXx2TV?9q4y5ZWpSEwq3(*Yj?hx1E#pI8lt3>@P( zG|5UDw}Y?+)*m26VmDnx(XmvQp%k3sd7>9|{wh)>o}InO(l{Md}58m{4s_NTQ&3LuT%aNHME8vBzu`hSF5@2Ln}Aac<)rxBFYf zR6tDV#*nnY9W8k8?XNQtPf!u@WkV>yh>{SisjsKGK;rdP{Sz zcn&!W9QK#+)0UGGVvy(vS{Z^8v^b=QOih6@lCmk8O*fGXNf%etbwesVNd~<4Xa%B7 zbhIQ3N=j5Li9GZdU3=o*2EYJMU1!64L}76f-aEd=2`BWfy+4)oOuTN-owfq1p}Jdh>N!zo33> zgRNoY8q~CWXXgdqPnabn9b&_>-R?^@7EbVn{h^ zp;XWmCC#*^iygXFm_{+HCam5&;?CXcZ0t`0}Lbqi>?Pz5iNAfo`MOxvkg@8%nxtVY)M)- z=h#NPO6ZL#t&FU?NK;Q)Sw~EPR0gDhjnpvRsA-%g3?)rBp;j}B)DuXU7$N$s){d4m ziTD&q))8GUz8AtHR7WWTL1=m#vQ;lNh11x%V;bS?<`&2060=hhQ{eFE2ld7v&1l;dz3nl^P?iQ4y6ggwB32}XF~}sagGVbxT}_Zl(sx-+Ekw4F)>0s1LI#oD zTFeYtHbkG0!Xum@2tmRj#DGiz5e-@xgegILT(QQhKCcCnK$s;`B!rSAOjf{(l%qM4 zWKy1EYkC$X7o05S*|wSn86V3k5=jjq)`w01KiKpT5Jz84R3>#sMT|N-U7HlpD_Xt?>?6uVX&qB6XJpMe9*Dc1 zJ@42&j$Dx)k_^Od0O8ygZyy|U$dv1Q+i-Rl_Ftjp2E&eIMOJtT&J&7{aM#}E{PA5T z{cR3+AET#a*$vEk&xh%lUA=}Qa20s-Jg`>m8Hr?uCgBH-9zj44^tNOe%f_B^BwY+p zK=6UaJjQZ(7Q>2$J2|^HLbsM|8%2wy0pd#YjB0oiIAK6Ycq-<5lz?1Vb^+g=;Mqdc z5SgP$bWBj3WlH4P_6aVmzDz4So+fa@infak#rVZR#D2a60cz zRU-)N1q86YL8AfB;qg8im~NfrXgG!DP1in6Q zB^USvK4}KxedFW=s3Z|MG!XjyE?XjZ@F*owB@AsOh|w2WMo9CAGP{9^0hj0n+_KsF zUdv-lVR5d{0EF~~bTlX=1#vXcpOVrHAxGes6)7(9ennuJpLr6L zd;m)%r3LuCk?fohddBk#|;nG^B{=iraS)ie zF&eyUN(41C1_n-=OduZC*)gR9yaFFj9*_VMT zC^W0@+A3M&ek`AQz}ay);6NK32^=&F2Q)`MTQR6t?2IdsQ30ZK!!_BrTl;4Cm9 z5YRHwsDebzHB%r_{Mc52>jOhN1_D|sF=qM(w3b+F>HCn`+6lyWsO*bBGS1$k{bK8s z(Kct>e z5X;QCwgn=brPA5f(Yhrm975@`GI{hkNyyAH79y)jA7*#nU)ev{Ymf|*$*7=6q%`2e z8sY@$W{?z0dkUqIJON0CaF-C)1hXKDk{|>WJwDuK8Dds3i#0+9l5FY3mq{uii4eDm zX_9UDa0ooE*O;or#~$66oQuy8gJaKKqC)eGdKvE|x78)qqNT8gM1z%M@yMJocW)6z zi7)pE9HXU0H3DxPxC$vtWSS6#M~W38T4FLJ-H<|oOgaCSBp~c?YVC~QW_Rmj*dehN zH6b1{UwsuH*4W`B*AZp5r^eUW4%{S^cIem=5~MT%1R_O*v>-I70wGF@P@&cy-A5ij z_c2;q;!o}pyk-0R1rApWR3%95%>P8ccCV5Rn+Wn5i85{;zy7=@U}c6A*g*t)z!@8 z4mvH6x@9q}7%Ibw52%fvC^~k|O%O}P&?|Ol7de>UBz2Lq?s>|(;>Peg+v*}eTK(H3 zqxh}*7g*`9(wIo$8)VwWQ`4{4*x-nhfw@?4XYfq66`vn|gP~h-PhO{&0xh;7DAwx* zGbU`hnr%1Z?d$K+sEQA4eUR13k}eFGZNX4^y!80g)5%CMHKItAW0&?!(x*rHZptPWr9m*{cbVwQL>f&D7{8)K+h6idgj9M z!t~?(g~fk}NSe=z|BL-}hsV_m6b4S>EtIjyIKkSO3uR?RObYAPXyfTpOFsnTVvb{cWvl>S7ZWOA1q<)Icc^L*s!UYd< z#s{~4oW){EaCfx#4Ix4CZT+-=`wTW-;p3o5q> zdy%3!hHBuIgWn)&$s!z47J^Dj2GR44@H@P{{tCxwPI$cI^6{@zO$7Z14k#sHEwwGE zXs{~cM}?vZ5|sj0dWcg#yz@g`dG9JG%UguPQ*=}M&apO!YzU8WC30P(CpD=oP`yD6 zf-;qab>OvIuQ6qdcG7Zk_lUwcd=Zdmb0pR7)(#)p{t!PHU*grPud%*MbGhtP z#i`~b6of5^n}}!;($Sc}#8i}BO_*2giWhl)=VgdJm)h5H_L$ksF^GYK_7-u{qs=l~ z35x=UMidh2HA}a~4<3KG$1VR2Tuf}3kE4Bqa$A&1QH3=ktcjwh#L|UqPo0t=qyir+ zBmyZ6f`AfL&Y&(5!fAYez`?3z9t3lHh-+H3(5Pf^vIi6@Y@$O$vYKHpQWXu25qRMk z+&X8<1z&IOk027_3T zd{+KwVe#5g^3@%ufPf86bZ9ptCfilJWaV2^D9V^g@@jD;x=LV8Tnp_izF^m?iE-PFp zKqw>{l18L3k|G7jfuIiv(o%>PVpd=WA#(n!dj`G!X^isF{5(o6(C*2+zSBpf)cuj{ zl|Fs%tGIg^oLf>dUw;mVVa9^L`^J|z&kVyB0mn?zyOW=Qg;^eQloxMUUVXPvSU0lc;%|k`}{0 zQ{X@S@qdoL@wr#nXHLU}yKA7VAbx;2`AHh_GW1832n64t<(R+sx%ZedVakMytl2C} z#P!?!x1anWe(sB3#zpu`PwenSv&*ro`QP980^7hIp!6p&8(Yke|M3VpKgpTqDYn`j zTB|viYIN-RH#Q$bo!ns;c*8=wQQ)m6QE_qe$GGV)g6a^9dlcMaNcT|@0$`Z(=YQnK zctO3(xgOM=i~P#nuMmMl347h?p6m%`>c^SsA7)!!<&!V0`C$DvXZAIVlqi(pPrvXK zuUxv0&nG5y7A-TV;ew;As!VPj^7ig%zJPKhZ3LV3fv1>&jI4Bym+caGQ-ZE3qJ^Qw zaY#5-o62$5p2#ZV`}v`fNmH_F+cDo(W2B@Li9u$RMX1qzHhvSZbh;fK@_VGK2JhMo zir~?r&ErV8kvqRTLB)tC5k`QUQ5>5@{-e6D@vG3PA?YomKZ}t87vBW}&W~31GC}a@ zT9PbyG%;pFTY=9UsPz6_b2vqiBv|*LhIDGrn{&`5QW|1WP*5|ITXq)fjK>$g^cw4t zn6YFFW$@ag4;v2UmJ%}$N+TQKd2%h z9b$|`@dz?n?Qr8*;TSWQ$MRA|zT{SygdrdpNPWB?mh6W7F%w!kY;*+R?l>N`$&rv0 z7z%0<0?UvE2Eyeq@&v|rlo%2vLzECkCAsVJdlEESZ!z~C>;b5bx`A%J2CeD5ryCzf zQ5bCRkVZiCAQLI0^6w)H0O(RO43VW<=5bm>(LfuHfQHFV#f~~hzYo9gl~*Z%1vB>I zZPr0@W!T|$R$LA%O7jVHQ5551FTSr}d|F68Eh>Mz_fb3=8^14y0G7+;eGu0e^FH9l z81p`h&r<;4^v8RDAN)H7fQDgs9|#y@{EooSqvQJv{5$7HE7JHrVE*%wNi7h< zVkpNfJvrw1j+Fu#fULfKpumwtUn1NFr8>)`I-6+|QDDOfgkikYhu1ublunoX-}L-M z9CKYBSmu$;nD6VyZET4U8z`}xEu+N=S_`zS5EKMA!MSX4ydY%Xm}rS|4zbV0WC=n_ zg6I)dJ6@F}MuQJ|Pat(kk+vwpdCXAK+bfh}!ebjBz|%8#*GO@N(Q81Uq(g~>9*evx zDw2R+EpV~J=o+s(d~%~wI_rwnKvwX|gf1kF(6|&xF%Ydm#(K=M>4@UA(5XhlF3J4l zfRqG24EVUl`4gn*D78Y@C5z4@WrI!?DM?%$P%)u}M@EU4d3CQDGks)kmkiQpLm+81 z>pmg$gro#1296f{3`0w^Q4t9gOz_F$#DG>2B@3ce3Roy^jf?f?KF07*naRFJhEGwD(miUn{(W|!--K*s{# z1(x$QB18}dtzZ~>271ay;t}+VfrgS`6-qWJTKp(FszuhDga zqNv#1nqsSCj@uJ-U$bd;sn<0)!BBK01uE2tlxb;Ec#?<&8Cj(@PFakW6r!M%4ay{3 z?I~r++t=UbWYJPgnyg5WkKS3f-u3=~h-sH35)JY7fY5fHZHzvZ=b ziW)J(CsJj#vl0^oGX`7bjNvdq3J5i>|Hnv-7}7)bl&3og`M#QfKp~_WZF=(9FH@I= z$8z+XO!_{Q62t(?k+2v%DFvcf6Qm%T6;kYyx_VqP8+2%p_B>GGQ3Q4JN3vJ?+CurFk8p**d|{WDS2JGNe2K4}U-RF+^9@!&%UR$#3jGqvzsQYY;Kpka!JJ)X z(BXg&0Dt;JAH`)l1Gdo6mDFAnY3U2cLiJ!lNib$32V7c5ktEuKLDJLY7>qQ>C2%rZ zg5o5^mR?v8pi<1Sv~kSx)Gh<2qh+-h8C2Wv7g+^gL{ti-;V7r(M!+ak2$Tq9+Q3EV z;S4?&Mapvmgp5Yo5<%yV8~1Z+m+D|tvU6I4XTd*-nfd;t*T*xMw`wGrdf2=k(c6RlQa3_FtZri|7B=sdmO0#1PLI_5Y?y zZ&khTzn<;?JiqT&*KGQZd!Eq@cOOR}vgU{ky#2z9FQcl8|LNTi_&BaHM_=VYeU*n# z|A5Hq`vZRec)7tJd4`P|+L$iEsq7H;S()e3(=NYv$8+$zZv=#(2s@7aj*vByLE`wnVTYCmm_|*C+dSqqeA^p> zC<&&AZjCaM!DZKgK(*}=Zz>qb~dG8fOjhbju zTtkZ3VZg>ji633%;%>lSVzCiNm7#QcKW;1%7$s0aGx#MH&>Zfuih*uzDa8TST9WZF z*Mya49VFBJTWl^)sc=N;v1S~z7DT7fXgq-y2|7R}GSI#a*fmJ4D3pc8KVU(J!?Bz| z6APAIOCR0@Zt}O@eV=h&Umk$b3X236m9SHo49V(?p>kJ}jtr>>ldp;LF#eRNp&*a>< z*#b*Si4Y3cQctRkh$cxdZ{r{)7|0k1XT(d3SyUQ`KBlCPO;5LMK zxd!akeXR{zXBEZw0t`Rx{~vV!msk4Vf7kxsz5dVo3f>`P&S=f5mu!obq9oaUCg$^4 z+Y`e;RF4R9fl>*?7QqI@YP6B_2r);biYOyNuMn!wWK0Q4SR@)1oBZCQ&)aHMl9I`w ztn9}&$_gBr3?xNN29Zp*$`KKPN8%8pb~YE{vO+EADE)B^hxku0-n{n+NzRg$B_{1* z)NPEsjno4d?FLdy2nr=;2q7@0CWsc7I#TFSG9q*sb;koD2}lJoB@jIbMND-*7)X~h zGzApyfaldOqN7HLzn3#VMMDpC7@|4jZunJ_GF+sZ6a|$SD2S*iaXPUsHuz+6-XWUk zYJ_v3H9}Mzni~v*!-aE{2$V_@lEz0%5Eg_X2}wlfHQ`G9jZ_<2_YG3WdCoU-8GlyX2M3*MoEp%f*o_c(I5d13l0UIy-MAE3NocKAG&7H^*-s=!C< zJ0uZ^*DUApgh$)EnS5|KP|FM4dCRexp|%wV{>vQcDNnY)0pcmw$`?5~hidQh+&uUS zJ|-5+5815V;6mO(9TcpUXm2}lP zVI?_spQT@2!>fDL`*V)WPhz@{asEC-TrinTsnj9ecArj980thH&-wlE4cfbFZXOhz zpWWei(=QPboU8XKs|q6z=%Z!D1L`p2mFg!MeuCx}Vl)n&6;!hhV1Oma3`K? z`c;zlEclT7_wMuAiw5~{2QrU{nU;h$wf57>@CDVC>*pGbY$y>B(!!%9kQpc)WQN|Kc2=IdB z6>4wXt9t=KB1}Rcv&DLf^mK?Qkgh}`2~`?1)eS0@^zFd3sOg*o0?YFg2%gSav@DoV zQ|X5D#W{O>dzchiJ-uN6=m^r9R$I_HlCxWHvD+t9rNKGNv?}1-lPIt;qNPEF0%t9X z3P(%dTVym;rXk?jrVYXOIGG8iT7n_lvd0*4-eqgnPNTF%%E;h)gttW9WAzrT1xjm# zhPf$t`&+Lw%zLgMUdNvgtS?T`6H8Zacysf6h-g@{M1)96mW^7|H=eEC5TeF;ORobO zMbhA0wjrCShN^8)3AW}brie5_5PHvE8IZ{$t2K4B%mQd@v3gCI4%D{E`Nm;GQI$+f zgnys*BuZ2rhWSe^hbclCb2D`?t8ur5%aT8*#x(px^&pmg{-H+aYE==*b->s>i6nTvar{K9ZBT zW#EM4x+B;p#4#Z^NteMtQ{X}ZD%zy!Y3Nb3<&=RIA1o?nFntqqvgSE%8)2C`E+$CTXB*e7MfMQCNKFd@SMUJ9LR}0_;hyo=7 zG1yD9DHR1GrAw7uNOt_RPafox&hHb#md^Lg@E9a@QPB){};Js10uT>j5O}x1I~L2hWvMdOy3X&QbOr5 z&R1l4wg{sV&|l(c`0ukuB}Qy#XL)?-*8j{|n1)MnAv;_=F>uY$>!1Ua!o zKqMmOqVZ}w)x{cVx04r`L7Z}V1#b#F<08<0NXLA zSEfIbDZHE55{QA4{J-bcQ|R%IcH?|k2XSeaSG{Y~+^{K({T!c#>H3hZ)-OLe2}H6? z&}{H5BhVCifeI3h#QXfdWdXyG6|QOboZpeik|fcfsA*Y@4+jlSQ}~tw=m~fR3?jP% zs2y0XGWu;waDfmq3_7U{+lvl`K#cSgOGNDm|1pipUpeYxY8sqd5dasmmA|AwMT5lR zWn!EzxjhW|-iI>pd+?Vsj2I<&pX0$W6mrHu&Hyj8MTRtzhXO)s5`h?d6qVa||8Z3T%Y6wNwU_ zJ0q~qIfo4973^jL^$ZsyIn<5Tq?VrbC=_02V{Lu!0^-l|Do^yKPjtcr2|4J z1pAlvo=JF;>`AmFu^er73@H{w(Lu7=j7}7!SZC`fvWgDfBSg%ZV2t9J@x&!!21}B! z5n(@X$C^Ip>}F4yymb`;l{{JL8c4Fog)_E8hr|=YIYL^biumL%i7|P-eD;jZS;gN4 z{JnB2k+Qfv%%vml|YKDBEb{sabdtSpb%(LGK356pMO9vdR%ES6TxOUM<|0A3Ly%d&IN%evZ~IB z2qs~P6se+?w+X((#-4(PYtvgS!vzb!B*Y$-vhE{EjZiu>K!GH71x!B{7b8&)=%PnO zK_L$juEcIUQBEmLL!)}E6jY|77E{tNAYumRWGXY6LFR%00fI<4=?QeCm<#AZwnzob z#frMFk#fM45$je==Qrur0-T|!Cdl!?)2Nz>I>ys5F?$#cN^2&Q3Cs43_wRm(V0yMJ zNwO!1o@4?+dVKWQ;E_sEOUcxG8eK8Co@iTs{Ig%BswEFU{5v%B#H^{=6q1xQDGHR5 zNG-Ber7;XKk%VWZ&e2j43rBCZ+|!R3kd$W=8g-pmwY0ItqOO-BS(VA-B@?5SJGs$ktLIBgzt z-@J`(WIm9U0e^gok`=f0XIP&Nh(eP}Pco4{c!cjULFYqs6sV{PZN#k{(rBV_&}uM} zUOQq)$e{2xpru4fiA;j`-g%Ew)J)AD&i1%uvuZXNDxFXDL$p~{g+K>GAR<$C8xY>0 z>lr>RsT%0lTc%BeuOg*Zymsw1hHYZI?0MnVt5nYL{^DJ3&Yt7eJo3h)uVZROBT7Q& z34NeX9v=sg6<>Jm3!HB{RxWYt_H!Kc4fpT8$C^_l7HcE>)r?z5w{XtUuD2{hM-qvm zs0en05{l9^m|*DrfQ*Lebk41V8=w;pA3tE|B1Ki>rK4>(6h&fI?P1Tiym0$E?=9bD zvpVC8FMb*21>dAehdtQ5!>l?kM{y5Bht& zbNV*Lv1Xv9+&9#+;rZqUdq;DA{lOhB%qg4gIs0kGHF1Oa{)~^~$JqIbv-OI~Oz=Qa zl@v&64NM1Hc$pCnh^MC!VxBj%jjQeu6_(60$eP!st4}~af^*LQhB`Cf*!bje8{jqL#vACZ@)zA;Qa^RX1%^(w&$7ono`!d z6lpgeCmhl!l2mkI%igs)VX)u@Wn+jj@aVxql1+FUC@RCz(LO>Z9zEI;onrssm?Q$H z7f-WdRAzf*?;}!6l*u-ZK3Rh3K!Xk%nTl*vJ(8ni7?9!|MTdw3DMh?+M45=fWt;h7 z#>6!A{wcwA7?}?^AqJF)n5v`gHaMXu3XRYT=LeFwK#K~kXLQ{XyL|_w!HEk@nTadb zd&JK7bmvTSS=`^{J?|_Qcl)QY^c`!64U(E&%3g|sU`vuH2sT1;l+y}Hg-ePQAjO?y zjmUem%Z%aO_#2DvH?|%OCpy3golSd1dK+qq+;(wrM{uK`T zpFy(be)l(kw`u!xU_haGybaV;{HJfdg#o?*{Ds4suN)kp+Kyj&bk2KU{}vHgQv(iB ze3Rt5tOWC#`yc&ZV;>$91Qf6o>aAhfQyT?F+lrw-kB7SH`uvuaec!ms#COdxa03vdF zxoS8f8h9ZiE9yyB3dT82ah++S5h)=z9v3#GFd$V)?1szQVY)Q&B_m_3fH&ycJ>VAb zJUJcnihE;3$Ad3dt-J4G3gqrq4hvpo^N&cNn9vJ}^n}6%1<}Zvm|W zGqy+A$s(=9j0WOz)aZsCpoRoL1K)9kXFj%Z3!J0b5J8Q~aaTZ_fmuf+l`B9n^a)MQ z|K6URP&RWS6AouT%cJcvGnvTmtf#?WaW8A3@& z`TR{7oi&uCi+O*NlEsWsAxaGdThn>L{`4T9>mrw~2jFlf=k2N?W7b6lt|gBJ40bwY zy?vS)A0D*K*tiRkM7Ee$2z>0ofTHJO{fJUb7(#YQL4u*BL=wlm-)u$E5Tqo;KvNrZ z*K!^B_rLlR+V5vRyYKTJ&#@L?g4D9*0}@X!Wy$jZWylc}feG*rr3 zRaB_4a)VDTo&PpT3>11mhbe|@84yz*hh;0ws2tA!i0}mkWd=T&vaepn+KzL72U%*; zppd>KiH4vfN_M!A7(|0m4Z=s{jvgue7z&ejvqB7X!v!YIFmg^BCfIh(ta^?cv!6m$ ziFX&jMyeddND6Vx7p%|$e2U0I<4K65A*r0bA_74T6j4$1lBTcO)2|_8q-{@;Hc)X3 zxvn`ha}b8T>P3X?*@zRGs-{slST%tU&%e%t%^zaQ0zYwdWsk$5Yk_Vg%l0%EtQBbm#6Q6lijo#F(e$BZBThKm z-a*t7ku=@}^v#HkOJ>&Kp9*fe7l_-IMfrfanKM~_2Bies`U95bf}RZwnsU2G=_gQ6 z@zgx^Eupfg+A`P;3p-`Mn$vF<+^^=d_2Z7{PLcG5zrsC_{aEuh0zN*w%UOC%z>)gQFurwgn{$88*0e;C znAjOQR5rbbqyJ37&l>0y@+vhMC=G5 zps^?!DT^`NQ6+p2!Ffaw$fWQtUrx(0i8N8O~i#s~xfk#3)IH$}R~JE;cPu7&|@fFy26EgZ86Xgq z<04vuN)!RoQd9XCm=!aMB-peUsLFD(d5@$(Oa+_rV}vSM7afY4@0`5LU{~1kA!#V+ z*fN9xFMCw!QG-VjF)^SLR6%81y;MMwSXLx$>7^#JA%!)H0j=&+)bRM^8}wV)pI)N~ zH%LMibX$M##cK2nwy%|Xe@;vu1b zh!zcmC; zaM%6ytb#)zlFHhYfFM28fRrulc&MXm&=8d8BW11a^0WQjrG zhkarYkUq%HC+-G;fhcpliI5RN&TUUgJlho~#V2JoxwLDCD*9f*M_B`KA7q3KZ&6G>*s0bcGi`RlAz{(SnaD?&!QLX+&&L$NF z$tO}S@pBZj@?HbjIk3mx^hYQ+PdMp5rtd!F-~PFOl}h#ekH7i%Gk}Vt1pdvx@C*ER z|HrSRfu6_gwAqE|7}5v8g5~-l(1RE#8weJ5s_(N=K zdCHPwW|X{x)!!jS4=N&@8?8zAIblu`E1o8}v*@_B=r{)c{1;#5#l1s*>33d7Qf6T4 z(LcbGnONWQ*opI36eXFW!8Y>4-IK#-9gzb^$%7Xa5M|0OIVDAEN-B6bXmp z(FiA(Y=OV|tp#C>a9jcrK}lfXgeW$UPFZXLahB(+Kj!Yqz&R(ZFCOsoU;MNDrTyEq zFB`t;2mbpv9}$ok8YCrsT3w#+RD32}dp3XLA2|blx7TklY1cp!YjCjT+3W{urY8!}0xjofMwg|P7&N{r02pMsqyM$9?h*#EwIHsXqRXSz| zf}*I|FFp&YBotf#0dt}FmtOuUnu8gC_4U7(6{=T9 zq2Q8imd1O4xD(f2QUx@T3Gi?H%;yO4kiY%=Ut>W+nu1vQ5k$9_znhiMe*B1%fae?# z*N+%P#W|Ws>vQyt159*mdP^ET%w#HvA;8XxJd7dFSoVvW0}DMZcDzSXE0PO2Ms^@S zt0I&VWJn_os;9u?88TbndoUWi*<8lgS`rFPPsn_y%Z%R~M&*eR14%@50WJbkt zMlIp#)jEvHc%?`w6F9J0pHYExi7u=`g=Z5m zM3T%d04M=Ajp}omE$|IkyMm_1w~|7Z2-l%UmAWAzjKKRuZ8S0n)(%V!w$Goj-$>Sr zNI@W_9wQ5smROtULc$Y}!ce5Vj1?M+5@f7#9+sPPDlO)Cf8TpZ9#$W#jHbmkiEcu6J3r9%&O4lR0)9p_d>7 zve9hX)g{&DwUZNGJy}p++v7j}v44%f{;uUs`#k3Q9#5X$LCO-Gqmr-({Of=2=lJD+ z@D@F{K)ed-21P7LF`$>rCG+{5q9`tN9e3)#gM$OM+wG?X_8;PFm+vd3#9GTR3`i*{ z%aW#PMqof+X8P`OV0U0(RaF>c&{`8hpzFFzrJvUNdn&#^1%7_O{V&9&vU}IRJ0MUg zMccNYPyk-d`%Ec)+W-GQxMGZ#%Fmtpvn)%BqM+~p>FFldu3fuSeD7@Hua2SbW%d1O z|NrUk|Nk$q!8?S|$l&vlB8hQ>7>RNT;t5hskleboJ&fbQP^IiNkW~t5^nThPg&?^S zLX8py1dmKTf`CzyTJ2Mnx1rE1GX*2CAy2nKZ;OWotKhrx-$3Q%MyN+98!?FdySOg`}aVG%{M0 zghWNZmPoNT+V@-#Www_?CZZ5%A<;=tpb36J2un4sGJxGBqDq{uPq2OUQ?8~2ln0V*j zw|UxK5R^b*@ZRBl&PDXWQ5OZJuZgy!QZ-r#W_ku`!mvC+R8Tbqe$o)ifG8yIKY1J4 z66bri{fg!O1;ThHvP1@OeZWXVXIpe#aO*R-ASTXEpK^Tr8n&2WPaVP}rt^l2?UL@ z{hBB&)>;H5Lm%-)q@En0NOYTlZ5i!1EufEQ(^~}pTuRQ-bZth9`;qU%k!d}P5FR6+O8`cby3#z81?>g$P zMh^!$Z+mV@CSvu5Q@vrmdCbl0Hz?bEE>6!VuW9s;T7ge zDLV6Cx6F(p$QCnN+xK0IFphez@mNm!Qzkbg z%k~k`8cMT=FBFe19w52~84adxnC|aUOAs+|F>JD;Tttu}@1sN@KQ*(3u}l)BBFS8E z5g%hrLup<@#R~j@3j;~IOmsChvY0`riMBupP-EZfSdqHOq-a1+vArZlfs!Rq5#m5p z9%-N`I#78njVWc~r5r1d$kEL5nF*>)B_hhKRE{Mv?2o|7&W_oP=kyrcqKA1K^R;3WQZ-xZTB2-06rf7511UL3i4-%rAyCk8lgNg*Pfoa26wK6wgIFSY zM4|*H8QKyOl0%0`foC9$n#CX3DgO#l<5IHu>}R{i@CrCYavMQUP!Az40Z+nVqlFj| zgbY?aGsgX%S4t6~Y(AsYkK_AF$3_UL8(-LsYCRH7(iJDIkqi^YRHbLw*bk?;0?h^0 zh#*UF4izL78W&)nmfJWE78_)hm;<6$xYmuv|0~YN+1rIvgkr1>Ky+7;WjE3yc0!%- ztm}njXQ?H{ILA`t-1me~U-n`6W5Dnr^4!{y?!#``OD!6q9mqmw~mGNIIECy^=*G#-?7^t-oK z4akBtWQ$@Ko;hJOb%E(1F;MKxiB$&eWnrf-+^AiUQ(ln zoMe?Yc$M9+M=xQlDZmLZ1B5L^I4mKp;YJM=6CB{M_?Xy|(4%E{83Sq)$L{U3tJ)AL zb%F5N#Vr<^)~@qkB=LW<_h!MCUFUt@Zw-4q!<~CXqX7^AL4pKD0^%S_q%6}VB`V31 zl8PeQPJsZC4=!q-EqM)U!j%;Un4PAfk;YYWp5Xpv9Ar)6613F0fn# zw$aR6&t>JAB@p_CWFVgeJdK3b0iue^>_Pcnj7yG|HOMUPFB*d)A)z3{Vr&)f`O&cE zjCxEzLYcEi%oE%Ff;IM*xd!1&n0-4}k zi6g}#hVG+)EZ|MFSYO&D$Pgpzbd2lm9Uvur>nXAgnyvS0=P;8D`_T}ZKmb``B@&>QPplx4~O{yuNK zah>II$===`tJR9NwY47%{D>iD;HSrrAM^_`72w#m`PjC*EK7=_Kq&11k0Vvh6q^XJhTl0+he zjGHzeZCHhr81vKd|95%(V@AZANgzd0P?jZGmXYV*KSRmcz`_0z^ZERQJa7#5W?A+F zt)hQA{%4m}|F+qY%5YiHKi&Pyl_-MD>gR?6{NKrx4H5%y(%48CAja?nHp|cF9TH3zB1W0v? zbP6RbnFJpeTyHL6gvI6yRw7VmOVUY-rXPNfCl8X;cW4xymslyWBEiYnWYoc>nQS?V~4=TY_Zd z>H8ZT8c*H7#6lj@ZY-JWCT1JSgpR<`nL`%I0#A+cJ*gV8TqiHsqqUU%`UX4Wl)|l%1s-^2l}LE&H;8*MO)4`s=HjUNA>iY&{hT#ZOPuJrVEkB|bD z2AZZtj3qb395Y$*#e>h%9|ZF0m~MQF%dfnK-1dmQgww?Z>agIJIpWjT*tJ4Q^^N+EAMgty5O@in={ODHtUs z)?1vnh-t^4-TX2#Nc_|hl%;b$B9RC!xxDvEY^9}9H)KK`8~MWHLX9k9u3BSaS4K_+ z6&;}skP7PQikgZrGzgmPFtY!p#Yuxxf?y?8=#gs*7gj970#b_&2DOpm#fr4>wEh-0 zRfto8m2Gh%YFkvPIJCR5sg)Rp$Fdw@?0T`z`Q#oQ5tm2vkLSG z;jym65*^`=`~f5$Ar*7CBwe$t!W^ptUJPWTwdmTg40D1CpkVHg5V^$Q=|XIpliddP zP8#xwrw>bZ?MvL8dqNt}nc#`$-=MsvTU+2%Pe^*aw1n1>iIOal*i}^N6C7&dsr>@1 zVp5K1#T->Q!bsws#QDhh*5jPCC{R|js^+wP!`9|$n#Cda-1SaQ=j&X)@*0 zl}9vMAk7+OdI3`lCRvKNM=X{zl2X%5m)P`GKJ)GC}*la97)$+cqYw|FNX zVDsXbuOI%u)YkFX10Unkvo9ipXOs(AF6gN-XwtkOZA(fv33Y;0BZLZgwP3#WI&(Xx z%?(n<#H*kTH^Noyx}=>n{HufKn29~YC~&$zOWBO6^opvl33$fYl)`P1b(%Dkw8@Nr zUjIX8{Q-Wnr)Wnw-=hMI^c3Mzy0nURzw?d>Io?`O1C>jAf_C(MkG7goF~;^T0*PMX zg~uw3QwA$-+yjSbGn}~$Cml_`L^@4TkI8I8P?9!u2r?I9a_6VrJ*)grSJQ-eqqRwo20q0^*flu3@ap1#qTtjFhbdbPsaB}zYK8C)=R1^=2odliL?@h}@FWP43@Ug{(q<%XM4p^sV|@o9 z4ZF8)vRKU-k4u8^SQ?C6fNBZ4A}E8$5`sV#fp83@hy)+h0H_S!r}DO}?oP!Q(jWpz zA5g&|#1W1;CLGa)mOQK>S!aFx06mIEyoBj9RQmx^RTA=-u*n`h2B&0HFb9qEY5;f_ zNa-Q~E$V?kK_f&qzhJOF?FP;FZj*LbotUNdy6I~H9 zhCa?#;@toMAOJ~3K~(A<#0_dYgKz+$M~Q&*HsaNeXfGZ#Y5cBbV51d1F}lYJ zaJXpGPeRXx6h}uL^CE%XTVNAh5#giZv%rW8n;)h+46ILTK7Rkt@`q3VFHCW`TPKFa zL|8exAjJ&Rn5nB!2wHesf!{j;;A6Y?V|}MVD)1HvIWVD6=aIT$B}N24A6y^Z34kmR zNEL0Dy=PGQe!t=#OkZ=We?5|wS;Tu=+<`U*!3mY&Bx6=VP(!R~1b>}BRs#F)1Ngo< zM(J%m_ktnwbvRkxqX+Zkh>oQE+{IsDW|#Ek6bt;Lr(cS>+pO{N4?jj-F8JEBf5!EL z;nN&*IEV^HQy)(dmhe43aj4N$bmn8;%OwXMZuhxS#xWgS(kk4 z=5@RrLD(V@UsGm_{q&_uQCBug;80X7jhCb*a%>!4eKUxTWaVAg>W zL=8T$mR5u=mJgr!`N#OwA3h#?rTGT7?J4OQvBoYEB{i8};ArtEQdP1XxDsb@2pU#o z)I)s0vH07Okd4mMRqX&N!>|9fUnVmvuGKT1`NlK+o%ft)m5zD(8!sWt9oFgvSuA&` zh6|{xAszZ*fx-Pj2aqaWd)`6tr~&woNweD|z~*SiFFo)O?-CDiW47e)UH&X-<(L2& zDGfP2hDlzr>|i>Aei4=L!Gkl7EjBqcOC*LZV1l7!PDgZU=pFdwasSv+_yy|(1UW_W z0N2eG@@|Ijp}^5Q3+YxIAUd#7+4|r7hkt|FWy6=Af1HjP=3;|whmJTSq6f1P|FI>j|_#U~#61poAf&k-!Fk<#va zG-ptFrqqmBkO7tsZ3EpL3Y}BQDJ#7Rwjxy5aL&_{v7U}G<_Hm1th_MQ%`(}l3yX+ zeuU-x6+*a*vr8;9blbKpR!eT(+(oAeANj~f&_xc`ML0U#xl#Epk3VhtzrDx6OmV$I zYK2hI++coi!0zrY^Z6X_J)_a+j)g2PszL~gqF}LF;+$hVopABuMbc3j-3M$e#J}J8 zho6rB+j|@Xe?I0u9*=*!S}~u`>HGc!6gmNMh3D9(;HTsN@Ae^%^E8jg#aODUVm_a< zSS-Ff@ONx0Mzr`h&N7`&Id$eVSy9Gu?G55DF#rE_{NLUpP)PBX;^3|0U;fzMjrAr1 zqRPh{7H^}XG&q6_5qu5cy^V?t!igF{NRJH`IVcXKOi{8Vl}XIW3_03oU<1Ymg3TZl zG<}D4uhO*@Hd{r-x&S2tD#+;CETYOnoK%^|h5a4p5s5Pa$(T%)q&g$db{J)+kt#*W zloi);7_1+d=~g1Vh&IG{(kz0M3`!@Z1wscz5}%)l0^=plN_uY*A*ySNWP@qBh3ysu zDvaq^R&$iLIM*Rmv@;B}B)T98Q>+mPJlZSh6O8HTe1(!3MJdq|ToWKjM)?{W>t}Gi zVNnNav%q&9QU^3D+OCQeCoN8Tly~%4WN;J7scoV(Z zqJ6hQipZ8^XhH^3@_X!a`8!j672`^_*9( zzetiv=4nlpcVyWdV{4LLpbcbtLYYjdMgb!lf|aCsLb5K{I5VQ;4A-uAWHP1gDmqi4 zw2sX(nUcFHsnkf-VizsC=wKw-NY5~97p%7Sv6Dm6kwdN=ANjyX@HYhYtl^ROy_fxZ zkLO;0mRc`4d;clw-35*BNfSkq<5f=6tteAFVix;w`Q38`_^V%HlBXQD3uL0943Jo4?MQ7-?l;I( zM&B;EeC>Jqw8sgFmy(M9v#uGRkTGjIOVE%sNJDW(~VwxJjoZ!9WJD0GhMB|<4=qOcyi z-jD>vsp%<#gZa^dOlLzBPK0qpkZ7AAWQwTb$WAO=Ik!ta4P{0pEIcg_SjpJ7jGqrR^-jD%QtqT$r4uloMK6(yN+Q ztYX%pi||pG?V|!DZGj9Ln=87yC3Oac#%hUE4xiK{d5-Z8tVD?ff~KzrVZb3eo@W94Hh}2T84w;)3 z>+_3@-8q)wDt)?)F_$tR@Cec2k{Qx#>aL|6kI0Ljx|=ia7KGFzB^cL|C8IdsW04|3 zYlV=CpanKabQqyUi48F$+31*kt3!g4j^1CxCJry73yUKm3kszrNt)1C;JhOAk$^Nx z$DBKR7B5P!>|fz%aTS*+q!Kt8_vTVdgp>&3@gX36AP5@`Z4fa-6phvrttG;TsN%0Q zN@Ylwv0j{FYhw*d$9%PiHw{XAgzD&{e?D5PXiq5^_SSNEytC(X2OjWNkVSa31SKTF z$~cdkC8obZ8**}SK;MAZGlWV=^#r9aKuGDs>sZ?(5;HjLB=J58(TG#xhqdZhDi&47 zA|yY)7#h*j4gR4fgKGht8_~Lk>#u(m*ySciy!iYV7&GJS&>@NNl%fUXxTLFASPuya zf|#S2jtA>WTL2FZDA^SRH3|J~5a-wqK=>gOeRyiP?YwCbSW-eLqXJcJfm?vuC#Z&8 zXoQUxlxhHMR@@mA+u^*yGsxD2ie8=lT?3@NkD~^bXbfuzngDfw+!Bg_XF0spHku)D z#c9-_RZj)@uo`NIE@m|z6R6Z3s8zV#C)l@xD0Kjbg$fZ3)@#FZ8r$x;SUdS)eT}UK zk24W%v7N>1oZjj|!y17oqX4%C;XWcPGl#GjK^wNXdZ@W~^mELXm-rV?f01`H;cvg| zJ;?E#=lVUq@#i;*sk#jT9kWdVtiDYqc{_o}JMZ0ar$u`d@%R$~K#63X+NA_n#aAfs zzJn9vTOa>9&v!_6zt{bv6Krn@%!c`+0_{*5Tn8s%te9B;s^e=Qk`Dqzaw9|={K2^R z`=3|;6Vhj~WZKf%;dEsh-SjvrdL%O>|KRnnkmK3E8da+aQF*_h<4?c-W!7Xj0PGP+ z6-wYlz&kMQorDm1$IN5nw*s^h*nZeo+vt`PP2bIJQEni{Hr-(z9=#1-H-~4EMJqI`Krxgd%u%;x%B8Es}L~DRWLT#&AFIU!T2;u4?$y;(#ynN9-Lv zMNPvg#$5OJ02?$cS!c;6o{}t*=7Fz%=}Bh8dudamy|d2n{T4oK64)Z6=0c>uvClhz zn)^A#6NRH)Kf%(FrzwRCSR?2t5W{Fp&?G@(T*9&zII)cscY&WV;xhLWfy0EJO4Zh9fFeo`wzbrV{%ET+8j;JSyp5uTxUY#Q(7hnmS{QxQ%JUP zX30fv5a_tncVrrNEbL^G=R2q<=xPb&S@28d#`8aZ@pB|t@Xm<3}Y|yQ4ow5jDle}TuJ{1fB?{<~lKD8K)?ub_c-9^(>odR|}y_#Ym7 z4_ilbx_-s)T|MGiCe$d-hZ#FTa7bVTOjy#e8$7_T-F=-4=M-1lE&jz5FH`kn zph0fjB<*i80S=y-aXQ)Hw;uRK{*RYF%Opv7u`-}X6ykmKA@GM!{W&dxUY`P6vhv%U z;WWSVb6b4jtDnXIC1Wo0AdVdbhiG2oZY=A-Z@l|Fc9pU*`56EEbDt+=1IL_qaDflM z_ph@yc?Y*%`xblGKSe`z(jqs+oZW{n{1ShB*|2guK#ML)^01(9*P&nX4h}dE{LaN~ zWZg2_IKw~s_D$aR@P9>b&TyrJD^hEs>b9p=zd3(BJ8)vv$8Z~Vvq(Fqd`b?iOv@q)-g zzk_3R;w3NM-pRS|d-9^VV`V&^@dSO>ktE59{iRfKS7J?UP%C}AXt#s1O(zKqw#Yh3 zXzH4xC_sq#by?E2Em@vN>ztnuj|!D&yoeS^0Bajl);6Ym?sK2x;~)Qcv``ZwPU1f9 zG^LOj=TWI*_w}1R_Ms0V5m?)yRT_aGA5LsDhnKzS@dqu=QmJUSGW?H26i#eOl~U1u z^B9yIes-rF^$!J&_-IQB(TYAJ^70f< zJn;k%KKLL?$!Pnn6v4)#)Vc`F{Qo)rKk)4<6)jSauNA-zYGbYSk7RuQN<)9%4%y7a z#)4Lq;}N6v36FpEtL&WK{w_5{IGMMTEM@od9v}YDhw&k*WxRLDG>MOIneV@2{{JB_ z_2V%QZLE`izB?xBXBBmgsu=GV5}l&g;%p^8O_?j1}`BAH0^cz?j|y5oDh&o zyzn$!r;`<4^@L$QbRo{kQp7Dm2=1f^QsLN&D%{Qt3K=4-q1+ZDdk={pql1a8Q5t-3 z5kL+CFM7NZNJ|cHBp(!d5JZEJ?Ev0OoD!^5O;^lu z#?VMmc!KH)61>asF52;kpz*y&8qhLBvx5#1XbP$(2!*GQWu0`OEI}G%B0&mV5CpGd zb55j)kYEDT$&yrcjDw7O11(WTP%bnq17at|2G5q?D{md66+nHOfemE@dJ%*v`+eou23F z{0bEkEB5JJ#=c&$O8zm+-ou4J*QH!jmyyo15;Z|3_>sbldfK!iL9-oBQT8KdcEzds zA|J4yK&FP@@BcT%SwqMc2-%YNB`C>CE5xS2B`XqdDB1)gp-DS*@Z>fjvyw2)sBMoo z(e40+KzhGPhJ-#?d;+>mNKA?$+Gba}VpiP3$bG(&ewJ0Y;LyKLFDu&O2Blf&oH%|?ZpxIiq<%_kYET_Evjh~W+@MI$uvR3Prp9I!wH8#3WmXjgv7+y4vLeN& zib5#FP&-WXP0W#GeygKcJCDc=i`g!d@jCA~^D{jE>T@LNHIAy+nG_S+u4dNXMCW7d zsN+_9gGDzZQ#fzG|P5@?;YgPv7)2J8;43Y zNP!yinw)b{iK9G?t+C3|G(99y>Dky7*?JyrL!}tzvY1gA?dZV=k8_sZ3A6(}R`jBS zEbd*5=m-kZQej0;+g2EF5E_JzeNP`OK@RGN?~(2GSLL|(-g|lc%im4YD0w^ibQWJc@7=v-qwkHTrP=a1KOlUZ2_K-nS zi;6NAjJL)t7Bd75q3|>;2|nPGp32sEEHV?MA|dZed>>flb2hZ*qPmyO^)0@9`HQrs zWinqQEmNxTf~B7!on%K`pnv@wXUYe8!+o32{rNvd3eVcRM{L@4UU=pOinT5J%Cp&? zB3X@4Q`l2`%v6U@4WEDMU$cH{%4n2u<<=G2n@hGgcSuBuTPn^KXDOEnBd@t=&vEgt z50aOHZ@%y(XYV=97k59;d^w|+EnWp0J7j|up7o<`etYttgAsh%{-5lMU4(I*>dx`2 zTfYUR=BwG4s6s_p2>c=tHsXCqE17JMnVEemm0;I9@-)TS5^Ymbo6$Et$uyyEE3zzO zBj2Dq>Zy)eFI#^m^J&Q1TP z2$ivmrI!KiJ*kTs%0cu9wHTCE(QeZ^MHf6Nb#&j8j-VViT~Q_@GB?Jx8YQDb$QXkP zfzsuux!|l>C(~;XCRD~yiHg2#=w(eSTCB}U@)Fm=tZ(p2W7Zru^ozXVp6AB)Ew<84 zytof(B%Mns`+In-{hLhlF<-3y35V;i;Z%pTFl{#o(qNJWK~;>aj9eP}d`>G{w9$Bx zV3K(6BsPFEgis+xPa)@^HIR*)H+laGtjAT%oKJPY2ZInc<{yU^ z>nsw1PDZp@jn^^Xz7Yl5ZD6D(OGfxCL8%qK-9^}jT$d!Opt1_%mq_XF$g})jHM4wE z&Ge?KKv;}e5h#$HK~P2mNNH(#o?gC$OLUBY3OSl>yzU9qIJv@!8X*koj%XD`JLFjp zzMx`A!}V#b6MiHKoPV*SBibtlQ9^IH9!w;I>Mc%h-$z)E$urMh8dCLPOg(U?u0a9_9MMH9Xf4 zVoqAbXkH&;=J9R!@u&n9ULuJ?;9hGC3O5-+KgSxtS`y{)o)g>9aEu{};Y}T1X#!lD zMmGW7K^F*Gg2)(;wpkq>aco~5Ycg?i6-zj&nN${k+=~`x3#3vQ5v@Oi1@bMXqlfV> zBlycy^C2S}&1P{otIjgY*GbwjzkdI(^6BS)k0W6B4q!g`2=pD_96lyu{)9zZ`M2ED zan2w>qBADhCW${q)x*jc!^IhE-eaD)5AH7n_#R)Xu|KXO=psEnLa3gNHtakhjZkezJRfIzZk*0n9?2D|HHO46)^$MJB=lXXIcNW`d$DX!^ArDdFgY$8ZppidkPEDVJC+qv-I(7@lma6elIx5$Lx z@0`1fZ(VOIX?IJ?-PJk=qc9EGdnV91pn!WKgK&=H_X~Gzk76p z2k-h7UOOB!S-(hM&8SwF$T@@Mb>@TT!vsU11Tr4I_XGS!x=B?#p1=Ak>fF8PF0ed! z0m&75C((C*oat=FC$?^|wYJB9|I|}t8m1OLeE<7-^|?z_Y(cod`l&~m9lQqS4czz~ zuD(Uv^knSu$&daF%fnk-ef~O6^$Q8$GJ1fiNbz zQtSXLeAtT)aKMM&{|UZv;~r+taDDG3yy$o>tSH&y6c6*8@B2lpc%6U#%%Ae|3!A)D zz04l3qJY!D=Rfxq{?>cXpxe9o{g>AG)r-H*KYaavqUVr*_2eb~i=Bc;PH$p*czt(9 z&nBOI|8MgLPk)LLieG#GM>!X6QLA_HzdrR2GBM`qm;Z!szP!gSr*OQ7Q=1>B5i6Dl z{|t%bZ$9>$96j|iN8vIbe%FWi56=HQpT72GGN3mZr_X(i!&@EJHuNa4rJi;jbFlOA)&t75W_YsslFh0j8 zA2`kZ&1-!9g z5O02z!$&^O?mPxMg@`IaDa9QD-?v|PqTm}A5C21se?MdnpD0enZNAYl$mhK$IClc} z3L&C8Oo$Uu@P`3qtuZL2u-1|Y5er(SP9A?0;Bpw==kfbLzQ%qO;PnqP{@)3th1-wv zJ752!9{<1S7#(NJ9)GX3KDkzYdi;QWc?c&P>L3DcXg7U#(ERrJ2XPy4^&yfWq9u?& z$$~ysCB60f`cc_Cn_<2^zHg3g>;Ez!@V}pjjB7Q=0H-+l-n$>~`Aei5)>VlVk+JFr z>n9-~*nw!JqCKN9+n^l6S2$%6Dv8CuFnAn<7U45+f?y3!&I!&UgeFN#q{w3$jhv%& zPa=ox9OnrLq>xCVAb6Y?C?WAkq_EN2ZYT+2*CN{U;Un?LI)imfjBl~3X4xK~rXc0O zv9OMc;WbirVvdeKz=!z&7Ab6(6TC#o9;t22U2}%U9MD${tvbS`EkYTB zh=70?#?)KTBExnP=`Cr9If2p$ay=#~H!1Uqr9Gl+E0iEMt5Zd5Yi=FfM5%Nnz`g?FLa9CfaNHq719ziI@)&9#ge#Tg@MW(SZ zF?ZN2l=C2aoB$&YK1kMg))8F;%bvdKaApmcCD=)aR-P=&=;ww)?Qrhw1&VRS!Ihi% zz9rwxST2rOwM!@plw8L-Nl-nFxJIuWqMu;u1mUNQvK;Rc=8GeYH!#xlt|Lndw#)NO z-4t`{4U#S)6$xHCMCv(cZ{fNUV_-dOVr{@ULpqUI5rOkeMs=gW$MIpvu|px0Kv@M& z#5q-hQx+EtLZy_&l;uIqtXjZnXp1G!Egz@MC*&eyJvocPp?t!9Tkj+x<(X@Sc6rFg z#R*5v9MypIkW44lQ3OnM)(Hm5>OT1>r3n>Q z_1w7r2IH*}MVd$TL1P%DBi?<_!xWqN=aur2mzG}M3P`_j}H>*hJBeAh!EEu z?>xZ2ylJ>>k#Vp0SKx5Y zff_R0l|st!mW@&%$oOAMfwKXJM~Dy!kkVr@IPF=v8PY3^>TpSh8l`l~ktCLzGp&pO z03ZNKL_t(%UwImzIgATD^ZZlvqQ`lQ)(JAG6Jo8y?CDT%&4MIOPzXLJ3VOGejyu#eTq8Oqi&3veu$dWG-dt7IeDB=tSpTIeB7=zThR&0y38}b0 zDww&7=o+-mk-5iZNA$8M7m5~7!wQvHl4Qz3eFM>3%F!Bq((}f_YnWc(LeI2RH*Eyg&+#C(v0#rZp~vXag-g;@EY8+ZACsN2`j~Ef7i| zRf-T9niLx}wl@)9`OD7Dfb)SMB$^B%GeqVFpl5-Q4xOe1mtuU5H7$he2x)Ml1F4Wh zb|>LB3h0GJdWn}&`Rjv6hNw7XnEQS_=nVvuP`ZMGH6$G^Bb+@)eV9>fl#=sGi}5>$K!zj@NsPBt0vUSjv2Z&9qdZv93D{a9fa zz_<=sbd-ffB$Bq)SQjm~rEn*G9l@Rb*63jT{oh0Un@X+_(&D{6#{CA6KjB32OM6F) zF(c2WI49_=e-nf*#O)sGaqjO=;*k=Spl8Qxd~;P%;|YnU)4(`R;Y~4Sv1p=Qdkqf_ zXG6G(nS&d^0%%(hYybi+4aRjRHq7zVC>U1NsGdH?Wd<`Dts%s`X#*VIK?1oGui=hU zeGJux;dvG!Aw2k#Yu=3_MBI1K^@4PeY}=TE9#y33j>*Q_Asb%N2k0}Xiv%Mi*IY{n zytKGU;ZssF?lC*mX3Uecw2i_!!-aC4+42ChTyW1wlK>ST0<{C?TR>0aJxPF(QlzzD zdu6$R=IU-kf=6|p$@&zBB&A?POA%_`Ew_1=gd0dIDgqTNS&?l>G=_`7ocWO5t(jvu zT3qIyJmWwIj*c9ao#4a6+`68#v2{0nvZQi3BRQq>2DC(ajqyF;(Y0dKog?#OQd+8T zfzGVQv#xf*No?~D@-!vWUnA9Xk_46=Borj>9yGhaIp9%b^-Eyh0CxpeHz2~|Xui#r zo0_o++%;UABOHCVh0K1In`XirTqYq0E)qCm&KnRcf>TJ&;5Z8$V!6SJLsFniC(J9* zHsLNZMxo_394+g3ewKy#5Qp7_LwaoW5G&5n^Ev{>U4KH=4{;4aQ_>!#uEom1=p{Rl2qiq~!=Y)szE;{Rjs&0;Of?(@Fin)Yy} zJ5^P8RS#qj?14>@ltfEm97&NOIC0`g4{}>ukO+xkB8e3R zNFs%nV~dESP>@Mk3I}lz*=(|#?5^snuCBT6bf!J7DGzI(Teq4mtEFy|O@SM@sB>=J zyYJb1t-beJ>-Yb@Z+Q{H1tL$eI(`fxR-C=CWF4Nz4_DnxXwIlTZZk6#Hyz9lG+=N>*SZxEL+BLLff6;H9pF>#9ubcgT49Aoc1d9j^k% zU>e{6#FCv^j$aBKYcyZPNfPuGr;AxmsV~C-Urxa9DaiRJoAG~d7w1>YCDYlA-QC@j z@9mvQD!1ig!DKQyfpc$!O&hq-)HPb`0gQ?hSh!xVPk`lQI;Cq{`o2#JU_dGLu7wku z&(-(+8^Eu)4@RB_;ct9>AAI?9w!bmv^D ze!9>8VEfbC`E-8^Az3-UmA?1JwtmyL|4tVzocf&i73K`r*AKSuT>HPXYbz1&1u>{W z$sH4@RS_jL)~mG0ts8{Mk$#Gg5#k{sT7t-u`W2JZQrNU$B9fx17%QAli)BH1TsWo= zEr<>+1Ep(NYlrEi!+t1w)o?A=G&~9kB5L>kiT5ExK0Yc!&@p zl6^cEnLC5+?@*hH#k9wn88YPbKBH`N&bB+0#f-blhV`-HQGS%iFFejsagB@f=efIj zognI@8n8Kip{S!`>Q)4Q70H$Ya zM^OktyPWXMqd&&yzxi2+84o@5qlor4e%&w*+qAi);h0;uU!=Wy$ZWLD@%kn&y*{Vu zELm5wJARU`>kzufjRLPPuP_>okXrEId(N1XQyY#0^D8SMeQ1bf>3vOcyH{!Z1<&XY@UOLh134G`GyMr(F2BLr%sKM={GXS8g}fcnPg=@; zhT98>hXUU^{2HYibH<$GLl1p~oz*#BnSYD!cEbhr7(aXNZ!+p9+}1bv-29*OvUmY8 z5(x(RbS(-K=|szDG-9-x5*CUFvj_Rm(;vcwod55IKj3KZHdc42An3JaIj#^jtx;-dZmydM@xeUIlkBIPA_my zKgN7{2jZ)YwMFz>^s%P%D^RI__Q4}$j#r9CN1ReD!#=aDN0Za~nrJ%;=_wUU_}U1shvvd(cFzd~frSO=8wEKH3ynxZwRP~r*$`3PYHjlD^qA0f8_cYDt` z&WLDgWob=7XCs7EI8_p~Cd3SaMF)oxDNZLuiyiI((g?5`fVfi7&j!louHfSgQ|Un{<3q1p)%wDp1>yb|eC*G&z9*>}_l3Fp+a_i2E=_Hs0 zT-_q|lb9!lL&pi}6cI2PJ}8_|meJZf?81VCY$E8J6fH)KxE2Hkg+UF~2MI>Gd&@>L z9|{84xXglw)zLB)5zs^I27)bz2%}Tv%HQLhQbF*F&c=K0#kz#HW^wS1^kec6m?P+j zESc~BJ}~1pH4k${-Fp75ryt?c!(;x3Pkrmey)2c?E3#+_gapMmkpA5;HjAgpwC5xh zT57xnXgOHD%E77{`b~w<24Z*04*DK=eXE5RN^86e_^=#g@i~?6<{<1RY}pt_R!oh`}33 zDM1$_eRz|4(Nq2P^jYR^r|QfteZ;w-BGi++VLFmK`4KKW@TOtGx^nZNW=e(fu-12t>lw_m!(2Oiy}5(ThJ zy@>3LpQUTAbA0$E;1zNz2urq*v@Xy{z-X`)uiSZ&f5w~{?@I>M)s(UL0Oe%Ha{Wi? z+PM974#Wli$(`#6Zqc$!5A1V+7cN6PRN(APpP^ZHY>yO;)(A1#!!Ptuq}cKQkPRUjpqOA0c!rZe1VMAcWgWlr>| zRO6q1;gi&Skh4Vo%Mbnp|L+T*pab?PsCk0lerb)=o{4#mBReOb2C{62<)NWr#GIO6 z{qk)Bw`qyI{7tabke6KT8h+)4YkUOw+vleIoyR}SRi^y%AAX!iioec&|3iHK@-COz zqNc~1hU50jATtOP1Rc%MH)t?CJbs9+IH7WmU;WHK<~$>gxW%_>rkGS*Z5700;_)S3;VamipJPf21gM1WTeerW+pB09(aed%|3 zkdD9czMtg!#Vahh#ZNx>3w-s(19EYm=RWe&eC|uHvd@z&x?3E*c9A_^B1a?9c=kEE z2@5JFvjxgtN4R}(hmd!`lFQ8z|LY5PcnbKt5AGn=HJ!-#t?Ccx&Cjt4HF(8hJ%RFU zvUC>(mUS8zFbB5)Su-7Htd<=akPD5DhbTFyy-(c?^qT>I)0{`V%T;&N*^IhM_DtOX zk&2?Au4`snTlXnOH^+8bk(uRrI@sZR>(z=FBh%@W?VX)eVOG~Cmd_i7ao=_C`g5~^ zDsO~-Cv6-&_y&f5Ewz8h#71{nNy!A}f& zY<}BS{sZvcoWFNszwaa%I{kGTuAfXgzJu-mr)^ToR2(4Xkaxt%>mMjS-@@d5Xv@>> zyKyskE9dWxKl9x_=UVG~s^e1yAsZF2bM6O?{2grncXacLU_r!D%2g2-LZ2+irAGP^ zAw3F*Kn;0uf*4g=C=&N(EkZ;D5h49h8tn1HgSJ2*X@V_Y_DE$BB16pgjRzpQKm#Y=p7&pMij$-EL!Gd?4XRHX}V!@ zl&aoSpO)Y=Vhku{h|v;aNANwumq@A6rcGIS(xeHXS16IENCxkd^_qbYJG=-e6;XMH zloGEiDq9hoNK*%_03{0|EuFQ<=n{ECw z^Y#+7J=Qs7<|(wHvJ37mE<+Yz)-uXL#R@}9q$Wf)WB?js91)^L;UE}7KgCFm$sMIB z5tPW-VMUrm^=^eKw{fxI*5MUuuHwdPdZD=C7vx1mlm@9Yd_85?zmKWSn6-|xJ7?J5 zRlMFGp%#wldQ_>%^PGvz@zzr6FiuHk$W8 z^Z`_+_|)PxgpQOmMSrj&tVT@5m^d+9@z?pro#z?lf_Z&FxvRNzdmk%2dg5?yPFJm& z6eWA*qa1ffbiz}MfRK?O0>VM;1Ht)ZxsF1aJmr$w4Cw-*kMy!-tJq>I?sB+)OkWgC zrrYR3V4dU1bMGhLl6>yf-^B}12E4PWt&PCaZ-b`}YvKUyvavy0Nw%BOgodCz z$|zdfV1{QEA*SJLhy>^H9-<1!Odymeu+VL<>zY7A+!LK;{j`=M+Ja zd&rzXBk-cf;W1)_l4G(~qLrdAQ13&lSkMiF?|9RQ~ zL_P&@5aJgg9uo+xg72lc(gv^6&q*h z`xU>ZUV2DwRU%*}V{BDHgj_-?$9UJ_It%?0T#lz8V6h_2BR9piaijK+l2N+DvxRErn5!yZCvDqaGPFxh2}SD(gpUng)KkLKDcP!h>l@d_P}01ssf zd0f$&34uqs&C?v>I9NUp`gv?D((^>5u|X5&G^v@1YXIh&^xXGfCyy0RbWiYi zFP!DIy+`?PzFsqDj|2S(S$T`a>Qlh)!0Hg>9ndR|yx=${WqWe||1y310+RHxafqa?k_G2I~L8yV8$UY691-{AkN&rhVH48c% zEn^CPXyNl6~}W{eSY}AMzhQ{vlkR^UE*(cSP~`=+%$&n_p@$JV!MiA=S&=U4D^0Uc?U9 zuOv{>(aFGS{R)Inkr|D)S1>jZa4eCmC{Z-nU>Ii;t{KhURmTnc%fQc&tN$41FFOrrlJ1t^I7AmO`J@$0N5%QBSK z6emDSkYyRR?@v^&n`1k@Q0@jhlx6_N#pZx@Vc zt%-wrR4O&tWyBL(+qc#KoIA-W-W=0u%i`~qV)2bI_sz~r1+M#@CyB;GgyP-|YQ&`usOda{_x$tNnkF?fl(o|9AAB6EX+}$sU;+ z5!D(W10i^#&k&U9`Qv>8!_f~D#*BzZVTOB>LyDMSu22aKOF`#WNR^6ee1Ir5QVXQ^ z$X+wDXW5G9Kr7a6O%)qr1fK^a9~~!II@G5H*n{gh&($DRU4x zDke}TJAn?{jPq@xh_vAt%N&(kT3>@vI9YPsu8>jEXDv}KY26{tWoRQ&rYFV@=Q{)% zB|=jF>PQ&)k`ICyGNj0mah6n~A*qa8y+&pcNEw`smXL8S$z^ zQ(~!5rbYSyp~Qv}PGkf?#Wk7=?F`R8{#RHn8xE_lac6ZK=Z=wDljok9-l1w6q!CyS z(}ICG#>@okLf{)qe(cCpU_QG=#)N0gUt_13vLF6AVn^ajA)5&R03ZNKL_t(#kIVMC zWnST^$(c*f+O5cAL)Ju!ETaYbaEyxwWTO=#_jI!4j5&i|N*=79<)i-JMn}UJ{Qpj) z_9_2beFpaAw5Sqd(^Q@tW)I2BTfWROg7cXUpyIkeIN-5{*Rbg0tD9JYGIV z-i^3;<3*0f*D1yoYvHiglXVjap6mJ+b@N5+JY(K2@P0+PHoS*th&u8ubBRO0 zQ=et5AE4_aX0nCrYevNm5A8gQ%%QS>MD6dQn~tK;EUH7qSW{EcH4XkoPcWX&HG~)_ zMmgw!K#)m81gg~<7ae9SF`2|^ON`0RS#B)vT_k$Y#@vfT@D`~RQFuDnp>;-YJ0^NU zuN|YEf|XlgO^;F{*~bqMWm7XJ2TMyoEPC~>!{G?dB~=s94|dW@DSY%OL~?};5h(;( zY6NMFEdB!9Ja5MH)<$w6Fxt>{-F@@3@AvIw%p&4F=!-l#zF;@75RfS!(ucuvQ6-0o z7#u-FZ0M2FAyrNvB9VwLb8OXv3e+EZcCS!_rf-7(H>qq|pXB@Ytm*7mpTzQ&B#jRDr z?)X7^kue*UWV+%Yzs=Ef0j8wtJ-_$zO=9R!(;k@x4(4|-T2f{uSyp1?2wQn3VvC(v z()pUthEH=*zsxmrnWk8i$Bc0{;rj74l#z6*CyqT79v=kb(H4E*vVZml|IgizGdkX) z7?o5zbB@|$bX$;{jBm{UnB(jYt__%ZMn2I96|rTH$t9tQ^s(c3x=%41(Kc(Y-n~f3 z9s0Z`GyxR^U6xi*M(uQ{cT0A*<1R;_@Fpipi$@V-j_xPqwxl|+JnEk2XJ`KrZQbyR z8~+pY=`9}2_h@3kZRH&JyJV(goO>pHhh2KQOt4lCX*}Co1=~H03yEE4=r&_(QXo`M zs6l&;ietR$2yzXvK{5uZk=n7cH#x#n%Qd}dSj8SGYBHHIu@~5L578_gliIPnwM*+8 z4(7LzE;25l^A;;RgpMFJtrxhUal+uk0k*gFy&~7!ba~6lS?VakZn4$uCHD$-L>p>U z&>$i~3v#2-RhNWFGUcYKkl}=+GZv)+rIRSt5mC5cnELndsCkyih`M=!CVw7h4hU#u zFqj}gIJ$C)6M_U(z`Ie39{QBykYJ%JXh`s@#MFG zoed%oA|{X~ELutg8Io;?hR!aLM1*P(LK2;Us1c%q=!wD*qPk}XN5h;`rJ z8<>!)Jd(9*0(PDnIgI^P<#}e<`%8-!QBIK7kP~QpMZ}}=^c%HnHlpiGO1ANIINuO` zi$bDBF<5su=^UVmI0D^?iWU^P8Dniv@CiUEks=XdNVeZ$fSB>kU|>vrSe#hkYVIWf zn_*Dq2eoOPpy*J~k>+-GP+Kd|Q=F@5WI;3RVN5xET6NMC?mig(t{6QHSGT?gaRnr5 zXa>XxDJOaJrSF5SZ~q!P^>^PChQHbQ3Y=to-?v`)C%u37ZC)hB>v)v0UN#uE(M;&* zq4CIKgtSK>{7HR7r=g3GJB^7R7vjl%D7_3gXCbN+8|`mDZ!%>k$DtT1hI>)m+{>jt zX^Zgfr}f0~xyZn_3Hk=uDWGXUk4HooC{o2a?U0Eb1w`4U3n(qgq(37JM2R{Dr@d6% zh=Fm0U7!?C(8WiI@i~rb&4N29p2x}MP`8k?azjam4j=@z-QlWeS*$PPn>$Q-oP%JQ zn3lYo({YU`?{E~{aJaVs$#Q5P48wIV>4!&Rsi{FW;I27w9>rp~H+?tZ<+w z9M+yg6k41i#s=Dp?2O-wt6wGKYfQy5xtl~sx$JoY#l`3$XmDqt7;)U)CdS*~udw4D zVYmJ~f@507IJrZ|0dS2Q91Oai*Y zL(Vn31T1r);bFS68i47N-VPSOLJt3ilSf1r@1<{xKzgIsWG&2(UgKQ0&7?_1KMSTb za)MVmP=S0IEXU?yDzU}f z-)0=HA$XZmU7-mhKoUhY^!54Bu{ACR>KF#w^O_q3;`q$a=eL-z4aMXFL5=b89KxR= z(;ePjLlel6^ay(L6T9@l4Ll8ATTtol*>oupdAxX?<<=B9q|a{Cn~rjQ0c8ZP`y!0K z4BTa9S{gf?W$hq%R0JhEq&Q}*G}Z<@&{CntTey%Tnil6<+G<6c=S+YRN5CznMNi$# zadJTvR}kVda2J@9i4GA{bV%JdLl(E@c-5hXW)JRE;ZzsUrx)D+g#hVY3Vt`%%ZvG( z(P%`Bk@b4b_Vza2kT1JAj?-Yv4`4UXbGEj(v3*ZfRS6;wd9XqVCetbVcki;ZvqL!= zv6#<^A*773cd-@i8?A@m45Yl7()0A|cMAM&0O)DxzJWU%1vLYR-+=Ug(dYg%k`c7l zESF2NAbC$~`N~yP<(Y(2SHpePYf%NYsxcsyJ-S1TUztsgZDdoxa>rdr9{{Z~H zGf?om)sOzHn=$4-h3}^QopX5aF~&c2p%ON&i9Wr_|l-@?EkQV)8i;y;1nyQG99g#?I8O{lE0m5qvwZ&HPV7eBp!-fR} zhg24m8(i;M)C&}nq5wS#INOn%0)a%xh!6p(hQh1h>3yB3IZDc{=Y42eR%z{EFH3gi6=Rn%BFN^^XuEDk`KHGQ&kgXo1ja+^3X+!BQ_3 zwOO2tWJ+Q~M2TeYD?}ReD526=*v0#bF#jTM)>@o{2e!9Swc_C5fXUVbBMtloV85GZ z(`L*RLcm9VGT+H`KG-XYlb_wpZJ7@N=wx&I-D2og& zBz0X6h0hsH)nJ4qlNo4Jw_Lwsb$M!C&fa!b2RJRuF*EPpGcPJh(jFwxp%Z@J8^t!`^ z4iPhA6io6NvXh8PQTAgLipEy>#*!&RuR(<54j`jI295Rx<#U`21Q}5wM?0U?INYlR zcwp}w{gswbSjMvCe0G6n-}gA<$rhjb>SysP()t>0Doiv?mQ%DYnCF32xI@PZqsQF7 zbqkKZK_+*QIxIj7B(#TpP5{nM9cYPH;FG5jceQxBxOlLRfSA;0j%D=vvLzY=YVL^nFKI zJG>CsAP_#HL?jaip#r^baX2zxV1_Yh=Z`pMMI=%HSux?&+kcGABy;9W<&5#Ppzx82 z)!0_?)T2Md;n5L!e3@w($$d#51D)?tTB58X^vR-H84wyo^eG@f2x1TznZ~oid2*we zm=Q7Lba6z<1MFla!DMJRr}0Z%-yoDv1&i9#bQM8%n6X9}P3t^e-=LA0KNmdNK;g7T z6L3V~(jt10gdp+G6Fg*kmf#v4!39E38bfQ7ta(Eq4q3OUs8gO&2+9Ep3jB%6R}I#> z-;JuA%?kIy0LdhtE!No{m|e{7!}z`;^p}8RTG!E$^g%Z+Uc?UAZQ~jghp?C^)+f&{ zAq6>8L=g01hL1H)I+SqWHSz@4-UFSd^IK1HT%$V$fCtH|NYHl*JZMUO`d|JjS|9nn zFaHrY+lqmtCWsU^7=QE95wYZD+U29bfBo1q#9r{9-}ok%8;?dKbz~_Lbk2P;_34NA zF5e;UJxS3C*lLc-etS-B*VDvxdJn(02p8)xAQ7695}HQ3BHq2X0T)z$ZWdwk{s^ z?HRHs%YX4tfc2aLnvQ#xHi7#rjo;*h3Bx?sitwCPm4=TyAuypa5Tc)60zK)ekdTyqS z(xEqJKtY2;pBSER><*NdXacbVD-x4L4l&fCqqf%(oS{LGF(cN4g?`+H_%Ijtp2Db( zt9L&~U;QHvtKSEfnCu1zHXY+{{n1z0CGyDm=ZJT2Qai!O z;FRZ)I1D8X)zWijYs{0Q2N|ynk}*xJplb&hE)lvQ_BM?LxmP@p?j$9KoN);Bt)-=7 zP2f}e4)f>^M|K;5#GuH1AajZyoq%qTC=3FH#in);`h+s7068u%YcZvOP5cnJuZjjjsRHF+0NOw$zYCbm(-^%5 zt-ub~iGJe(|LL5~?}shVbGoi$YkNBlcAR5(Z;!gF7>&m%-}Mx1+$@MY=jghQ^XJd= zOTY9>{NgYE;)#;CZ5l!djK*V{y5{G9{^xn%fd}~5$3DjP&JJP7svS=z*uLlcZ97ra zzDYa3nKkg++1mDA?%n3RZ`8k9YgWr8#+duEfKRv6+ufSF##+ne%a_^N+2QQjvuLfk za^(tIYo2=QskgO%tu@Z2Mdi&gX{}F={AWzPIV4r|p)%n^xa3#*-qN)2;woYqG(f{Ri83 zuKnN1&C7r^8NnCSU9u()DrH#u;0Ufo3WE?OLOReZgs`bX9+^}FJ|M_YQKp5G=n)Ly zq%%YtiHRW(IlGZ4N-{aa#e!aFq!eIM#&E#mMT<6pr~)xcyc6Ixnv9HOc^HDD>E`5S z3*#RJp@`xp!5`t3BGVbZ)9mhSp@d_#SRph>xyHE{urdA* zgcq!XB%sJ*vSss>MDYkuJor~xEa%(~U%;zlLMWk|f#1O>MUXcTvZW|G$ThtUxZaZm zMJ98IhUhG0&{~h|XKZbq1-Z|no-;2EnKO*mn%K?xO!W^jBBIXTU|n?F)fO|Ez(O*q zraaCQ^wD!uzlPg_RaP@H8DnpF<~=`xG(9iB_6oi8tok0E_bj)*&i`fqTTGSFp1F$> zkyaJN@fqYoFfK}rZ;8i_52=rE;qeQ6>gI2eP2k5L`j-ehkr(&B&f2coRcGkiHv3YC*p1!dOr$*aFjJP*oyZr!+wci^@iMP`_mGm2(HJ?|N_$8#TihD)!#z|+}` zN6W`}_4p!3+(eH?XjfqCp673T4unHz7JL5~N4SK&CV<*pmV^iA03KE?$t*$it9L7eZ2|1pa^a-Xzwt{J!t| z{HHVA@l7>$x2mabHp%87lA>ZOHewlxWgD^Kh(LlM+GJs67bD6(KmftWCJ40gj<7c} zECUIw1d6Rl2?f%k5=u=ro6Vu;Zgy3@s(Rxc&-9>!X3&l>F{jPeG@>K3IXMN|YeuSMv7TY1 zB8!^VuIYA`SOVjwM6XLqV^Bdes3&x-!|Xt%m*65kKoAi#khF0LKrs@myBPw9Dm5qV z8d*w+9Vhk(vzxK<$Ap1lp<2#woZ_WpTu+jMW7^Qjio7dn>lR&VXa$32!j8NOE7%PO z>>pj>m;Qs#@rQ5xKGt;PVnBP`F>EFj-H=sxo!Q+}#%c%Gow3|)&^wa(Vap(!;I+q{ z1wQ}Gf5Dso_igs<6{hU+%u~-$PnZ1fhri45&ONj@L>aK!l3B^P-oXpa{qdSQteHB4 zX~%Tg3aKq}u*QWI^LBwg81lREw=r$W)Rc(Tg!9-?PRF!jNv0LXOT@Y1?|t~c=4*fU z4J_Yddetyf$K-=ZEUt0Bwv4YVX}WV3XXhO39Z)wNN-Lt(gy_iC2#-$%WN8t2ioB&= zA5-cHTI2+uk*Oi8rbSE}-tgbVO&nSmoIJP-tzvI{ji0~raVBDq*T4BXIXSnUxJ5B2 z`1VWRMj1F0=NwOusC0uWA}+KPHZoBqZRc=uf!(dB=1Z<*H;G+NQ!N>}DOVRC;ltNH zjmiQqy!>_chJsq1;_?SfCK<Z}Fh|64GdvJ2hRD2xZVR zk@mrafvv35jhz&NmnZ+0bJBYaE_@58)&sYD}0S z-4JaYf(~y35ldFKlUGnOi5&Y~Cv<5-gLZOg=$5AdZZD46@{`Hss01vEz z{qY`0)gs+(>!vL?m`wj!B|fHj8V88QnnDhdz_^^SsuwiQ5wadf4Ly|T)47gr#p%)Q z-dfp1=%5EjF_-#Xu$LM)eGY*jbR8nP9y|vhBf@uxxad{9s=twawJ=9~ z*NPO`3!ZR)DApQH2{M8h`&38l^727gY& z`r>i;%VRq|ErCQtNwjK9sfj&wp2ZZ;6*XWc;3w?gyu#_>3@G@}^-oeicz_F$xxRra zp5pLyiQ*K&obj;2t?v?m)^!GFslk$dq4iG}ulOod*$nRcLCjPN&Rz7bJ${_Fzz?fVGO-fE(^o zh<&b8a6&}Jhz@Z}PEbe`9>FHJI`nY{rq7{P^r0VU;2(VQlRR@AnbtL;u6Zz9@<*#T zal3y9!U)1C@Ezb=nBIdyT$=r41iu*p(r@RO2rQf<2Uaf8capODm{Bh1{D3A}@N3p# z<4Tbht&WH#J~YONIw_fZ#-_$`ZB!zw8mWf;YVi_;T?#%=VREqFCAe>)k$5x)-GBeU zkie6`fA-6h)o&OH- zC*a=zRv_!7VTn+8zIT~QL)WcVfWohmuqKNV<8rhVG@(Pkx6<#YLut2Bh0SL(KJ%H+ z&~+Vu_Gf>_!NI{ph4DvoBsZ$E)vBT>3bfW#>-846tLvJ!X;4aW|NechUAx9;G-9<} zqLgCTgTfn-?}L0j3gm1R-cr2JjE5f%7*#5%8WxKM4<0<=?CgxL2lNJm0n_P}{r!DL zqtQd^zaPbwWy$7jwOTPAk5NjI_ZiSX3bnTPp1Q6dvJ21iw8&X&f8zb)y+Gd&$~BwK zxPSjXXJ=<=L6H)zHT(Pf+`M`7XNu2%2jK7WSm%AV@n!Y>rm(%a=jP|X%^{Lc5G_6` zGIC_JL;*s0LbM1U5cmWPM1_bML`m?LfI!IJhx8Hj001BWNkl#H{c&TxXr9d(mjEQQD^Pb$)lzF7G0@q1ie*F!Eu-L(z zm@SYeyqG_6Ht5S2x%mSOa`T2e1Oa$uNbJJha5 zD%c%QP^F@>_gMQi1xp+Ola;toBQTW1U2f&iV1sAfEx2#*pocluN9y2t_3cBfTN8E0 zWPd;%Ry6UPu3XcZH__3M&q0KO&Lpb)PIi?~eCQ(xx!~}n+r%@C_km(p(#R#xzx-!R ziaqYPN371)OyVJHxuVP_%-bbaS>iNh%4#byYQSfn`6VXDL%uzGiIeaqopNLo#lYv- zss*8`i;Cy(K1beoR(63NNs7E+7S3_9Aw-SJB(*gtS+YBr@XUvP4!4)He8utL>^=uq zcELsNynUCp@hneUTsa`l9jkDT7zfV660ag7ms1!+kS!69%Swb9usgj@nMdlnrFIP~ z-{P7z<%2`!r^m#b0jC@ywh%p5Ne~@~)wb`Zyr~*Oj`FGGkV>2mc`-V+wv-}@hYDG# zmbeMLidYd)!KY$}e0Vb(#btX--toJKe+~#EP*Ng?l2BZlQ@!i&lg8=hQgJiy^&nqN zMF`pJg5*1_HRYwxBeuo)p6-}j0)BS=6kqb8lAMfvzu0J*wjhUmj{;*-Ly2vlNb5ut zfhZg{wkZeLdqfZjDG^a1gCt6U*q+rsF@5~agSL69Ef!FWOLFUC|v z_G4C&0V)b~ka!tTv^ZgVTSC1BF4U#>5!>v~R5bD%Nf;4CONK2S;Yl|uHfqU1|PZl4Aa4sYvU;|zV;%2 z{fWOpt!nm>2}hW{!-ySJX;G=nG## zV_XhW5==#wmF$Hbr0ZCB4OLT9wwlZe%v8}0YO4G`tQD&>Lwz>KtqiBj`*c%_%mbFk2?8YmIMzBBLLA8Re z=@`Wc*RMX#AD5l8!{9sYRark>6D#g ze|m#kkKbY)Pk8a(7pWgq9Jr?`LdGKd9!;~tHXd0@{C>rmIl~2q%5n;^3tr$|%Cna$ zN63H?1;l_8fkw8;dQT21<27`&Sne{5Gh~rKvgigx-O^58Mkz}c9KmV6b@DCByueCJ zo|lM1VPgj&V7mq-2Sl0TG>l4QceG9s7{Dag_|6i2MKI}n)dWkHNy_0B+Lh#FCGf1N z?V5a0G8pH0WWw4+hoU7!frz>X05P1N zmwT{t)`Jzv8Z{;HzDKUOoGl?12)Q zzNmv7MJaY!)=S7O>kRH(ze_R2K()~Ho9zw#UCMa$Y*};ebGIYSncE5Bn;xi;7ox{Z?GDqTb zUpx`<&Zng>!R?o?Jk!L+F-BA17y#FV;R?{w5-6xB5>YXB5L|NVA`x3#Ri~VBA1=o{ zCz5#tB@{8b{=2vM;wp_FQ)FkoIDZV?5OfPBW$LDGBf-lw?lYeX6kSIi7FeBzArh$4 zv}oCw->2H(fQk`d8PXz%dPPSBmy-boOXqgMeGC{eawQEXtQk_@ckFLeu`SOUq~gqOwF*z$>h}6Ev0~J1ACIEEUjZ*Xi^wF&iW# zny?j13*m?uWO$YkmLOgPd7R2Zx~8#p0`;?=V`Kw)rg2?zq<96mfAu=+TA~h581Qwf zZjENvk7}3B%Q2C8WR&UIXQ``ouBB@sgh+|(XU^1*Qgbxqh(s(CuFslpNJ+9J;zK{Q z)fV0#5J+(f4GZY|TPr4bSrcLhKEs9~M-;Sfz`;tPqh^Lf6A{_Yh@`z zo_Jv+t@{2xE?~7zw#}9nq@%6R(2N-j&!~6<;v1lsv@xR<8eGb8S0Oq1K-tey>$INs z>;6%9j;=vZKE!pV?6TxMcvNnwqyrm4wFI3U>4fBo0DO4GWo z(OPen%&epsP414b{{`LoK{}95~HhVZ6a&~rxF@_I)=tFq#SuU5X*K1BrPB=I? z;Hjsc+P2vSv~8M(EX$Bm;=O+;Pj{mf?z)aF%V^t{uIm_&$JBMbZLf`eu=i<6{NyJ; z$zU)b^tRo3o^Qzjd7f{Th?{58wk^ZqFxgmXP1S?`QcAKcG=hm%T92^{M-z&z5 z)|&ZzzWw~0Hn7$*nNI22_AkBt-wO=h{QfVq{r{p%DaC9yV`pavV+@nYg!A)r?%lh` z`T04Y`qZb$i-M+a%c`oF?(ERi^>)m*ZMy})j4|8Ky#bNe>-APiy6HQ%&j$CsdS59; zp64u=OQe*H#$%R?1tA26!{PQhZtTc6{be%;NGWOC79j*>Sz@hy=-FR>4{I&n`|Uk` z*yp$D`_8#-zuV-SzaL`2ds+SeI8?tW_s{b5(@zs)+|C8Bz4jWv`m4W+wH9Mi9$=p5 zsaVo9lx4Z?uU*$M7z~)rW(l@41GM+^}a6k6`0WI<39toOL+AOw&a zAtMBpj^)mxw8uz?G?82@1PT>WmU7*mp%kdl5ko;1pJbr-@iF3TO<@8%gHX5EsFH0={BUYftbG@FpQl3<5q`GmGuk_|_+=N{E)=J!3< zAG<-Lj`@?<{*Z`9>0^ti}EC@c( zsTr+Uv1UjY;C$hT7MAghd3Trl<0JgAMowy+nc-9*NK0MLAe5Nq1`>lUP6>JqevI%* zwH<)Qv;=8UA(aO&z}|E~eRv&`i0DBk;L3}1sC@+DdhfYO{>8FdrvMdtk{xQR61b?2^$hh#!Qh8-eZzYr)jzvF@Ye?1ydV~YOW-dL z0mA9^@^T05f7g=-V!&@-m{s(HC%gU|4JbD&bRMN(6L}WG*R*cb6Wo9NK4yC>hohTGP^IiQzt|$A~Cd z7s>vwY{#ewxBY9JRJS=B9uZ=PZ#^n1X5kbid+=+Pu{XR)Hd5@JU*pt8%Kagoo#WPl z;47Y6eg!cR46hqhki2~OUFvR4HCQJQS_D*3ZY2utH9Z_f87(LGC zuKyzY<0=2=xBd?*-BN}ep&cg&Z?P1&*^Sqj?g-|3MQ7kdX1H;~GW%oftuw9+1=53A zPT4#8F#plwzhu|l;EV2GGQ08`a%aVBr?23q8fyZQCiNXXP5KC*Z0WD`~nG*r^lTFKC47;0o(2c!LD(vyusOJMxo2C(Z0r_dJW!0SX^5dM(a)PPhQ6S09@<}}J(RqlGKtMP`LJv}z0UQ3 zSdpGTnr$#?-$tg?oGq6q=KRs~zt7))_EVf3JjOr$^1s;<`TRC7H4$<{Z;l$VKf#?v zcm&>y58Ey$Z;%UMx{of}+62EZ&{w_>F!mA%8!szBF9Xw$kQuhWm+uc$eorv^CkFrr zK#2?=$K1H~bKHB76n9$IXjXJ#jzJ@lXcQ8^b&5qSK%^Q}CU@D}y+Q~>syfhx6%bHL z6Z~e}c%bV?_akQk@z6~1t|IWw2x=brecL%ygbv5B$Nj$g#V_$B370)#hZ>#c9$zD( z-ROUbv7g*7jXBrzaW}`RPG@vBjX_bjlwvPARjHIBt2SBVL0kaYf<&H)0bHHDfun|) z@Hok(y>m#4en)aFNH!fn4>ku}noBpzO%FaMi{dfx?A2RTYt5@iuhKF`@DY}r^Phj@ z*SIoi`R01am%j5VOP0WjIxYx6A#=KrzCmsZj;lElO-s(Al3X2K<78Fg$CB#g4GJpi z1VQsR{_5YQunYd#*ZzRF_+@N80C5|11>TS;Ls2ROV?uomo!{iVdi|0ZAcE@2GQDtK zA}Lgc(=|50?Ev2x4Up4FI9%cQQz~}`tZ3T}Ye@If=gsBE#ql&N!@Grjk6@CHuZ?b)^>yF*M z39{0xmlgXd7>qziLqH5}&{WGrLBk@AVE-`+US^Qx z_;E&luFx?eO-IEHe+jGy9&Jn(7K_t1u3XM^j4IPz)j&u8-A-G|s|? zye2d1cpYKm9Z-nQ`ZIv8C@6ec!x_A zlQ^mAR%#hZulfzk0N&C5*SD4LLxafIYPdRf(Xnao{ zdk?_qrv>oFTn=W<^mj9*+UIe*HSj<&t~%?y+1hxqbUKH*ek~%QBj#0g`H0YmHQj zrfIeyj#7&CdW}+PBe}_3o=&H|$|(W8TWf16w_wOdVOSK!R+($Ej1U6LWwIz64u{lr z&1f{*W{z%Nm-Qro4S2Ir`BuHPbe3ggS+)h4HvMGtS+Xo+F`sY$?%&t;e?OOVj{W_8 z4h{}5#;~`y$8b30_19nL@bHkGogK0)qbN(t7zsUCIvS5zEteQ$D9e%<-kr|IuiK5Q6*n@3XVBliJ^yZQF11+DzZx z)>`U~ReTQsZoth=AKid{KME`G@28CaLHoeFw*Oz!wOlS4kH=iQc5VA?Zr;4f*T4RC zUU=aJo_+S&EttA_hDDKpBx4M1Pt=i0Z9)IGZMQ&e+qMt2*9Lsw5JEP@hewG$o3$m& zG6sVI-g{Q7)z*@HLk_uYQ9T$Aan^3F%Qt!Pu_wQ5h$5Hgq8~QH{72pXKhyz9+LR3= z*Zqg9kiD&%h%#lHVUxWx5M4>crTiw9tmpy)*=O)>&Il>LNz!&TwzshiM50iL{vQgg z?g*kG#Khu@GFcx>9}z+0I?puUM}{Ho+#(}f-@C%Nyh`jO)w;ojC05+St0PbqQU!uY z#c^dMLb4_MXcOszr?VO($3$0PJBbi`l=+Cn(E(-UVVXNa<6NDaLg05}HDeFnWL!88OrZ9|@lX;rKF(|j^%1b5KC-?&{<@mh`GUFFj~^q_Ypx; zgdrwQ5W!<>ODj8qu*lFdF0S$T_!CI4>5gAV;89t`J4>rOyiZv(qfDbrO%^j$wa2XSWn(%UkT&HG%FHl}3%)yhf!IV=>KwFTluhxg4&OvfXLv$? zgxERWuD{2%#~vei&&tlJ%^EEoc?nsJbjs1mmM&ZJ>d|+p>U(tg0=HXp6wj!2hcN~1 zs^f5dNGBb;qbbHl#yaC_zQ+}Fjn|hiv34tpoeVEMQE9&Y`b)HKg^M*=t0>wW=?Cl- z2TX%yQJt|K9#Rd?$)(2l5%$QV+kh1f`M}T_k3n&B|2kdWU}ruZYzl=gG;L8~apa7N zHZmPd`PfH3N>S~wv`4Ilnq|8JH3S{-J{6JL(6Xi`ct1{hIY)iFFmn za*Z5#gwsS3@zNt=Qf34o2#FUGWIEf2UO5}2CCY9)z7dZCp%;Lf=q;OLlz6dGP?A)I z8&{LK0g!uDUQ7zdzy?%H<2Z_t?zdGS24aNHHW;1bO~m5}8;2Y~360+vFmCpfF{vek z=syeU0=(V;c8^ABJZgm}-fz+EXV(Y*y3}{YMw#?J|87$#-;y4pP6ZC(`aau%5){LX z(2BmGrqlaGo0J#ZbvX5J6*N(R(@BAz`$RITvzjOZDww{c8nDviB&euSL83xZ>q|75 zQ^croGU7zQM4ie$$`OP|2Zab4ZA)a-X*`Nv?ca}=h=ypAo?w&x8Pgb%F#+TW=oXaS zAg#AS^@NHH?E_tGQ9+W~bY`mafR~;iUHTtb%+BFPKnsOkSr*-lZ_mF;IUBGpmej7{ zTd%!<$e`RQ8Ds<2XDiCQL2yR>NeZhFBBu+IZsvL8&Re`3JLDBjP%X}fqWU5w-UCb-?I@MdJIAZXs3Fp{}FLxee+F~kyks#y62 zl#W6xa&7Px6#0~=pZpZL(tPV1uQ6WiA(Z1~e;+yQxEgnes$nr+uoOp({eWV)!` zM1+V0B`#$vNth!b_r) z;4=zg$h5(^hD>Xs?P$An&!Q}e!cliM!a&S&q)1T#>o8}rK1pD4p0LK`?6LvIe3~yp zhL=g5|4vtd4e3HqRW(IEK#5cXY1SPxzd%Zbz)+Y0os{4!B0W$j1w>1X4V|lyG9r~m zs|=;ndYs7;X?7qRqrAns6_FMd9WrLbAPGJqWr2zoDLo=~gy<0A$5TH$%K)dz!T?3Y zvLqV7ln^6LT_yc)OuUthh>IFTj?fTYyNy@f0+}%+*hGX&4!aV_39%sh4$LC`o$K+s z_-N@Q71FmEs{K8Z^u}#MwfWE3H(fOXxloZs11QPpXbRDI= z0Fi#|4rPYizC>?gw`>gqr;B;Sxe3@MGY16J>1zs$pP!w+hluP}{`)uF)UG}!( z0|zI(CkSn00$ENTJeR(wu5fz6!Z!>?z%l`=k^v4uMF+{MHkSQa?23n@H2oPt)7|8sXm~^{DY#NV(lr=BXn&==YOD|*P+TlIupn05Q z{@eH+!tP`I_iNBs{|++zGG`}W=6`+pcd+kTz_LyN@~U@jP(iY`HHdt-5n zgPogD`DBf)M$kp@=V$`xB;3sz5Nn4Qfl~=*!0WF*Pt(?DU`UBZ;jp0c{^4jKx$I>L z-e=u|!rG}snJFUCBv-uQ8vgbKp6SkcZ8*geSSg9qB{A#(Lkc<~9nA(w?qk-Q){qg9 zoYKd;6M`{=#BJ#O5%!DKSoX76s9lipKT6-P%$IOllw*=I4vuwJjJ zPfj>HJ7YedBZQzR3O@F+(y<9S001BWNklCd1ZOdphVmh7j?8iS& z+cb1t$MNwo^ZA@RckUpB;Kq#`T)ldgEX$~>ikDx0nYvEXMOl`7^rIi8EXyBS@%hux z{@?E!4u>>NL)*4gRYi=E-Mu{?d+agp+_^*7b&N(MOqMa9&3NODH(0ONTQKm}ty}E$ z`QEeHjJMx@d#ko>+m?fa1KPIb`1qK*uD5^p(T{$V!C(YgxQe zWGbb$bH@)me>|GW{G+_jk7I7j^L(q8-8{EE&$mtsswaDF=7ZDI)2*UT_ejf>bhn&n{n^ny=3Lzwp_n{ovT-`a`oy}*6THg zhliY>pKn#+oB3qZPw(HqPY8hk`RMOs;d7iw$JG;km#g*5DFzi%DT0W_e8llU~yy#EK&+-a3i4SDBPoF#_7!kgI37HvKSU9rtHnW7d8N zCl^SjgisR01R-n4Qcefbq)cH~;hn@#5`svU(KZmHz`2Wnn+TWkxYOQVNQ=`eyjT&$ zoIsmY!omPK5s4r}1eK<8ACO*?F~X=F$TFHZr_(Ji2D}XEXX!EFj4GTFhLUr4jBhpN zC}(gmqVbyLBGR-SyMsO4%F{LzjGiEb#Mu>c*f5v~>eX>lE1N|cU*QCA&*<7S&eo^+ zF=$=l{eZd)bn+g#3*4}`Xqt}s(UM#Fll+qWhoE!*ZT?Sr+rLEY_Gr`rTD52uQL3bF zSDg6gh?zu{V~iM5EerOt>%^{MGTY&A?SG!&6<=QdKOCqj%Vx=a_dV|LDy>{I#3N&# z;&)t2H4(gS@8Z>rX;CuNW9roy6Q_)`5!dw>@1_L*L;2Wr&I*gK(IJp z@Iv?+t#TA%hskuzTPJUlJIT}b7trk#Url)8)>EjRj^~fQ#H**r40a0U)rx$uht?Uw zHMr#oRg_>sO?J53y@*~He8PX0u{)sc0#|l!AhO6yXD`soQ=+i!HT&$%2KWl{wji^+ zoOKO(A&8=(%`3E&Aco{I2jx&ABGj5dAoCefc*-IWJBtm;DM4wA@*2}kA!azeCWwFx zBXnm#wnWilRjNjq03v$4@X75fiUb^y)N|7|_VMWXeGn1U7~l1L!RIx+M!MLEfF=a8!mf+5l+`%wX+XRmMU zqBnhAJ9Ft11~O;fISxXO_Idg|-eN^VS5$qGIY$fC1KAqm3?dpj1zz?R(9xhmjtWV8 zoGd$KPrQIAlD)GO$?`gG!l^_`WedvEsU;$27-!I7qnvg))e%J`?@Ej}$bMcZx*=XV zWRPfYxS=2CX!(G!*HUK{PIYv{h8ZWUWyajj7~B}}?enj*?iPdt3zmGw#f8Q<|LJVn4Y7xj8|)WIrkb%W^?b7B3xMNUH8WqLw_~U18VkvZJz;ty~^a zF{8>VYGqm38iS-&vPnYlL?IsIm(vFvR9lFt;5(UWig}{k*F#{zTocayPUWc!@-2czs7p` z3eF4UNHB5=F&A9-w|Ms2r%`djH(q{`Sb~`bmf{FGc66?#sw>W1LuV}Y;G9THVaF&Z zsg+@wL9I1D?DHQ_|0_DN;v^hWcMmASKAl}7s8E@qI`0^c6*F}g5n7C#Ghe;QbL~Bb z*%+-4$wf(BcwByuq4ngoWDzZf9OZY=qC?6xB07XsxCmX=AfzX@9l3?fIf8zh!}1TY zszWsoC`bx=5hKEM2$3P(1nV<|T%%MX5qj5Pw8LnJlW9CT-_X@dlm;UeCJxYkh-e3x zFk)OBu#@kha>ZgXW3@h~5Ea6-cvs=6(OFI7X9T@Q$z7z*aJHihYjPtf$^mU9h|wT~ zPu7dlB4Z%L6fF{ZRpLe&DYm4^1Q+C4*@NH`BPGsxmdh0qg;phA8)E2)qV7o>$+}vo z1;SghxQh@auC1|lfsMb1QWLZsG0r|q6)JR`6YxYN$`wi78*GvobpxdA5GL&dRUDyz zT)FOg2tv`dqYGfr1G4O$H(NS9K9$*##FTd!hXm_E9Q7dY28iha$Cv~)Fih6JJD_l!a+ccp|@_ntac4R z#dJ_%{XJR^S?3vRV2)=U;za^!NcY}mEMHb9ejrM{{=G|Y+s}B3^bsHV?D5?IW!|wD zea|{y{C>c6e2?AG`z>bhefP&dv06Gw1GqCRS*}m|HmD&F&_d%b$GXG>qzT;<4|b8{g%5x>b6CDN5E&#p|s3)vGsH zpP!&cQ}iIBY`{0k>Q@ShjR8+uN3sp%{0;!WHwN~RAV-{r8LOg1a*vT1A?;lh6;N+g zm9ak(rI|0y2L&4&=XAa^dW5wtni5a!N%P^7oq+H6jtM^ZmtDcd#XsLapvh>7*E2i| zR`m(FIAJ>8=iV~as%bxxG~sqRHiAOmj^C=3zrB0InhDhdKkgq4T; z5*D_G0y;S$EM?jYv4gi4&^?qSKN^4*rWZI(iKXB;I&QN67m#-rGS+(Q!+hzU;3fGUPO=A(zm5@~IbBZ8W~Hq| z!Bw0t{VD>LK~V$|&4byLM0Al}v2|gDZs!bIF&`fv2jFo$Cd)GFx^9(vy)21)F=l9!e=rPEOkQy?XU3)>@8^j<|E@4%e?=|E9=@{(AQR zS2{MJ-ewF~Yq7?#SS%=tqE&sb^PJaSdyS$f*xTDf2*G;2=HTGqoI-OxpEDQ?7z_qj zYnjbvJZdc4FI>1lQ4~xj6K>zW%`?wDLzZPsCll`8y$isF3m2%Wip65VU;M>i@Lk{a zT_~jxLNJ@nxNzY@tKywbr^Ip0&dv^6Yo^mF#u$dfApnPmhpo!A+wHdC@7cC~yBWG~ zMcVOiO|OA-!IY zt*xzA@%_pxuMkBM`}_MuQADTHVLTo)8jVPjgqL4_8Lf4z=H6IIZ*6VS@Aq-easU2( zwAS3bd6UbRFSl!ql#*-Lu8|~3O9F7tF&d2!LU4S1%wRBJe}BKd=1u=^hzW1^{_#%s z|JyEnyCgU*h$;XeLLgj>as%)QF$V8KHjeZe$~_l$Tka)leS(h_R%oQG8j^5|a1qkS zAS{kGLRzFqn$VMA=jB8Z0B5I=G9p$A;T6sXo3)Ng=_Xy&wxn8DtaVAJlVRe5hs7;) zZSblhjZ3VUQ^reluX8M3<7XTqAvn zu?0%Rq*0Gri;({*3cP4Gy<@W#r9}SInRlZZ0}!W@4{uAPq=eZu zxL5x*$_pyLB9azk<|w^D zBMYYD1Yr%4@$BvF^3?b}ln0*G$swcufHaDEwTh{G5tXQ!>p6dO?|EdAQo1ElCS+>R zga|pTtne~MnH~u}q^%IrQR@QZ3eu#H(V9*iBYY2~vW84hfsatOgD1u)cWTckWTOH$ zO%Wp~{ScwRW<>ypoNE{)4VWAXD&h=KCU7o7;t*aTyliZ5!$Xh|k5@!aGYcOtAZ@I9 zm6v!Cq8GAW7t@KTsEC9>BJswCHdFyeeR+d0d^GXOVEsQx;leY@d$AH!iX@N8Ke=kk2XKxA_4$~<4ECPdzBD&o^H3qLDoD*0n zand4%#|ah0wvQ1XqDJYvxiaOVbD6&Y%7?so={NSyV3ZC;KN|}Ak>6B9Qml|v%Hjn9 zr1fB>#tVt`rcv_JD*3}SKAkHY(04PZt@Icba=Vlb^V&*-ZLIE;Q^YO+(@s^*&l)EY zVKAzqHYFnQA?3geR4T!FDqB#v92Xf@@to+=irnTb?ToJPGTz$56dElIl_`i-a1bfU z@!ru%yDZBECav+pHs=H<4Y~oP@vzg|4)F|;!uguIGFb1(GC`JRtc#NE?jF>AOjVP1 zH6qolMUxv^mt>J-Y!Z52kopKAd)(aqZnE7GFHde`x2GJ6FX4(3*-!9ELg@-brpWVx zejE`+5@!vyE|CVt{cWyXc#>PQ+f?}x{q7dEs~HU=YOzL(BeblUttt|_NS~3Zj3iEx zB1M`Wqt0cnJ$s#%Kjuq^Q?y-U;{q8QjMIpYq+*S!Yr1ttNA}3;6))U+fjH`;#1ImP z5T1TKLdBYa-NxpU$w|Ust4rcj+!R*T3S`dSmP2iM7WG3+XGOf8aqHlVOzSR{bo64V zw5MYok&wjn!Bx0A6k(;#5HiBc0!K;gCCY~}qg{>m_s~M4L`6sSSz8-aFf< zT66dCRm#GWc4Csaq;eIeE>W=xjxP-%q%xGeHAbF z&{zx_A@XomJ7^qvPLM99tG)wg3yjftzXr1pw*T%d(A6d|GC{ISw|50AB1*p`je88Z zM8XKG6AE*Li(jUn2x9RRN|ii#^jkqW+UA?Ob6}e%sBNsbc$N(uLCCNa?)?4!+>O2o z;%&?yH=u9Ih(ULoPC9_daqs9ws4S!dy1iYJXbYbu2;W7KA#L1dor9w*f`fvU4kILs zlVhxLz!J>^mV60GM9mZ6Zvaoi@CRVkgMLIT!LM{XjLJyy8%xVe%iA0Pa}*^KRtCHx zWzpoC2D@Z5omEhsO}B)R;O_43?ykYzT|;mW?(VSB;K5x(aCZn00>Rzg-S&CEQ}y44 zi%?V4hUw|`bT6iXQI#At!_E#!r)~iIA|BjqLrZGqr1cnq{2#S93e@cZl&hn_ovhUFHWjo1kR6WU!ou~&H`qtq|;YV~+> zDjS?6tC~e2wtkh0#2}5RZkyq*XQ9RE$3JS@z6Kr9K{b$k>*2ekSE|n4;rlcTXZ<&( zmd}s;$MW+a?XYfxb>{w$-=H%T{K5M;vJ$;T=9A3I2^yCq!=#HsJ#I^y;8(2=Wz~SnA#Eiw3fwN)C)!Y3uFHURju#K1R zBc}Uhl=hl^4P)^+4TrHIppH*upHi$rCS%pvNR{`;Fq=_I9GQEJ{N0@ASkpyZXqk0eZFbDY)ds@x$ z!!NlnT)utE0ZFF5&J$rb0-`}n#RvL7o9PAmql*$0lB|?iJ)qSN$#V`lky7BDHar`* z&4)tbw|P*9>)$_m?GrvTqj#tOeVpIEXJQW+;``>BuSEOy;0)&d4r>>Nr~yGi}AhoJLn)$M82L4fDteOveC zuIc&VE8#1+X6i=vybV%_chi} z#Q#w5_t(eofYIFM@(!SB%GIvbQrF z=Y8pOJ&e~5gde6;Ly8YJLT%m&j)`hBc?_etD?CfkScXw|ud?xUr`5b>` zbMtU(tB_BMVb zr=4XtPaQRg<7cg4bPuB%zB5Bs+z*zw(=(EDO`;5rwg7@#Lan_)# zEy&{83hhkig-B)A=hYV9pw4&jG$=*$%GFZlFxx^pe7+yEA#*tGp4h&O+D*>XADu=M zu|P9hKonQcX9Px@zl2+Pb}6?>SO#TaHxDIVOg*&OLnginRwh<@J0SEnRL_dKNRe)` z;)J1vwLxK5TA4;+Ojv(KCI_4DR|VxC^@t4IaG7V;7^H`Q#`8a|e)01-n9YN3Eq$N4 znw%06-L-gsxOnk1@C?jw*eO$EVhi<8%CV4VhsR?t!gQjDN^RkfKp9G$`I`ClD^z%g zCm_bp>!rhWDi>I2#o~or70D#JftE_-I_Q_JG<=ep6Vh{&qA5d48n=0PfEDk<*?(C= zYel%&QJJt+XtKV>U=e1DW20ovz*NS{OUpY@+j^$E{wvW&`V7a?W&h+NDp z80@5&Ci4CMB`u-y0KwXr^S0o#G}NZNnqB5Rtx@dAU4Sen0Xu(3-@X0ic1fzco)Wq~ zTI&A%V6@+b=h}{GVHf$PNXe%19}8s*l19ha8*w_aYbDpb^3?LINgmVeUTNp*N%C5O z9STj3!^c}NlE%z?HCsc5K!8&rVw(l5o^{q27!kh^u=jP6{2WKGbx=giU*Xw+*ui6r z=CQv7)K)rFl@$--9+n;QNln~GDiYdAAo&p!-w;dMGc>l_kf#78Qs#C|vSt(Ad3luL zY`iDtqEz@tJ(LL#lK&j`S*BG6f&!g`Cil#G^r{H#Q`O(ckaOM~Lir@@L&R7G@G+hQCBa8 zG~LpIvw==@D(47>An7|Gr?*(b8~oOu(`Grtf=iAI%eZ$HZ{c zR(YqxSdi1tWA5XmM28mRMK;yR?`C;+M}~yWYwpu*@V_hvx3I=&D|w~Cz|ZX8dA;yk zju#8qchaiQwtrLdRB*s7!5b>_5QfFb1x32CH}}`)T0{XSGWet zSTQCRQZ!?HgS5$(btt7&jOYZKfPc4z-y65;c~?^J%UU^madvGS^h?0#nbpX>A|LPw zFsP?!Bz{^H5d2Ot;b_ITdoyiaA#w^QU@Z{l6my28vk1uRHp%S*evwUa9 z;7RaA!Z9_8#g7zJ&dm@`3S5$(ke9DRRiAU$kXcd7N^0Cd+{1CKD>Pe{ur0$&#MOOe zP^Je%s4p#}?VuLsn5k&G#Y^kY56_eZ1BGoG-D1Lq-wx7d6|WnIzEP(uCSzi@hcz+T9bS!4Xvba|+u2v1Af`WQvYCda z#wBAGi5J;9?yL%}KNC&+8W*Y2GjOb!cRNwGVK3On>zQj~&^D-f+q?40KCz%ju3*cR zCRc@}F{H$D7--_vTb^QtpY0UGPzp+RVC#zz(O6_9zubrX<3%Loqyn-PTY`=%jAGC*ge&xR;X_n-2rioA4{{mh3VF!T8Wg4bth=(FMW7sym45%>P6p3Zn;yE#I#re z3u=No8+pNs@$4C=dXNZs%y=aVs8fFzFne>b%()fw8{8~-f7>R5SrhWbkeE2J8Yxz- z4Y4JE;O2?e?5^S$N$0=)7F7OVeHasIy57>+yMMW^izXMONQ?^h&ROAmUGR@cy4+|o ze$$0a&SATS0`CW2suTz?qTyiNa`E1-bJO$@VJwu+FHl|a_d=GwKR;sH$k)LBmP%zp z`5y~Fs2XMYBCcEl&erRVm$k_1cAd_Dmi|bib$23xcQojhF>Jd%zu4@W5^lh5aOfKx zVms1+gySbmo#dgHClt~ftY~kh?d$qcyhOiqwN)6x&38J(EDeeo-SH!ADt4ag90Y$n zseYt6TG(-a)8`@BOZ*HsTF4?<;_X&+HKZ6mqR}#w?ztN)#(=kWRO&ElSynaa-f4e< z4YK8qJkN=r(!MLkk?~C0-xHPnEv`pedjTgI`e%!Iv>676Mzw*qzrn?&DYz?BLmP(; zy7w(YY&STLc^QR8W7G1OjZ%$RH*&XFz-4XEbgqr2t?YO=lE7?*qpV0Y>Px@7su)6Q zC{rh&{-!8pOrqe1*U5oTn^%P|1;+5Pm~SN2!X~Tyhj+{ zqr5NQu}g}KNiubUGPgRG1;s#C1}i^{CuapBCI+&?z)k(tFZdHPn`=?3MJh^S-Da`_ zm1_}f_zpKI(ZxQgXiGJbPb3zZ=*wB*0^nh>C-~RKL(})|0&^QCK@@a{yKH}xAAYej zWFkAkNO~rN%-~NQ_7xHsKm0>eprn;Kqbu=X1|-+$t6-9cKn8GP_dn-GGbHv&a+OpT z^N$=LKZM~uNb#S(h?oRETjvLT_ym3&2KBVWzQ+_iAp|~p1r^K$T(|=gu%WwqitMeQ z>`G+wR;25(`x3w~+NP|PK+ymL(bU>Ib2}rJ@)6vxvlw$HL!;} zi^AU`&4!(!pnBG4+93r=XI|F*9RqtHt$BUAi8@Uzm5{QuwEwN_+ttn*q?Xwt9k3p_ z*R-5nUUGd`0u-B3m-qEu;J%SPPxo_8o=ViQ$ArJAv-_8pg_;b-cn%=&`9R2|XV2nk z-1@yoMjbe6!UEwTvB9ZMcZd296MB6D{AYMuasF65 zZTY@Qgx*+H#rx_xn+y-s1E7(KQqQ=*ynnPmti`{#BE9u$BAz#kgF6u@6&M&|Ljm2c zw#WlWUX%LKj}KAZdJ{)rGS`)kkOD^LN0r7ILLuhr`2a=Z4@K;-_#`*>vPPk8byja^ z@@{XGqN1MhhU>A*T1UNfY)Et`t?3s)D++6Xat>pOO%EO1M=lq>6HccWCj@4@tb<=A zs5!|gnu6!xKZU|mU~}|4QZ|9;PyU=bVXSh*`AiFom1XN_agNg9%r;1Jg?T5Yi5R)& z-D^;2plkKNjFpd_ATCjiQC3ig_bu?mxDBNgr7|4Y$GP&fu((j-C=^lR)I6cn zL&r=;`-f+W2*cWwj65GuKtNqIvJiqc})aC$T|abqmFQvp<&I`vTv4Ch+JAe(>iP!qG6^Gy9=kk#=cF%fRU) zrNuTh^)ba^!N$vem7zmyZ$XGmeGVvFv%W|?G9^;0!>y^x^`IX+&0Zq~o~ezK$-m<2 zXiDAr8RUF940M%}%A+YMMdedE1?ueS@dQW&J=R$7|4Nh`4;$WDH$V|p1mp)E1o+=9 z(CJU>BG;p~y+^E`ojv$Gy%;aJO2|)Hw3O^}t&J7?W;{DgO_v(y`|JpLZ^soB8>vbF z`+YbTw$Pbz?HOxRVuos6ZnEDMc1)s}71Zn_@(m(a4dXj4 zN#SGuCF*$*!^DkIJw=cpFTEH*2fkva-sa8r(cq0wady2 z^}WIj%_zN157RofrM8_fXvmkLJ=a(&4ME>V&PJH}q&`c93=?T)!7K_u?O?lEIs$`P zm<>WwaA@<${{k`oxXqoD7Nj<%)NhyzdtVPL9b}lfv=CyB)V_mObQ~(vB(gP5wyIK4 z?HC&eqy^>}59_>9)XR=M3*J9yCae?Z@*joYO{%6r;48kzib=#A`rJ?DLU%wicr2}M$W&xOcgEerbYRbW$_UH#A(hCdFiPI@Ol!@j|Md4*27zDp6Q(MgLRrVZh$ zP=elAv!q9=!Ax5m!QyZ5Pc#ALsnsQEXL0hywvsE{=gJ*q^3!Sm%MA-UH6GXuBCPq2 z5b~Sk>vF$8#Ug&dj4MEiRHF+nbk~oD4_j^y+x~*apnw2l<~-dXN_N zaED6xaVgN!WbBjlzw@1T9(

c4W$MCfnSJDz0!dN^Ny=7?-7e(-z3(%Xowea}G8L z8%*Z2*X+;9(&~-Nxtgn=7osGFiPYeaCc4=r?16r|EO>HyU_=Om1dmP@?9~TH(T=+G zhD>GzI~5M%U-EYDj6&E|xooCV!1h7WeI@R9q;4qGMVX){>T-lufvs?o+PM>FvAFOZ z{S5p-)@oXDG*2LSpx_#eIMS)u%WQ8E{l_E|i*Od|C{R8*Fiwerz|S{u?XwKtJb5>Y zLAQkU2RJ^Tke~%JVBCMYkY|!JuUMg%P6-fB-b#N;I>WtkTm3gHOp2w!vPWWoKtZx(*-AFHy zQ>9#W^TAPlc)K-26nLF}OuretyBK)Bn5=R011$iafyTgoxUHoM8B9;oDi zrx!8ND##bNddvwO--HS2cy=&4-UX4H^Dl z(*{ya1bq>+;?D(%N^@j+(4W&sL#D0fy$F=#F7=%S&vmGXoW-&PM70UC1g#93=Hs;g zEKY-3K+<@08i%9DkM1sf^DTzo(2H|+`&wNEe5;iHVW8N?xOFHaVci{DW)u4ztU{7! zhgT!5gAwKtUx_1t1Ujd&7qev1RHDTw`fO65RtHAm)L8l&gHJCUxs*3EfNdi|^kZ5i zB8oD`E|x5zTaUW&Z%Ath4PF0pZp(M7xoE^VtefB5%+OPKnwWl&NWf68j1!--$m#Ff8yBv_NR?&`jrD_w*M#NRQGU z(cHbf0@g7>)Lwso0PZP+zAh{k@1-P$3Vv=Z6h5=nYIZ5--gS6jtT9b}rg)$~kiG2QLsPxF;2oZhZ{pgn zSdo3o3ZGxU-+QXt=A}M z1~nygF|)P(4WE*Mqc>X?S4YrB)eV?=<-?B^}bu7>R2aD(WVy9 z?JE(KP82DFhoIT}tvyvh0yb1j>_~+ZlCy6dz#tm`MJRFnXMyT9(lRJqS%NVk%K#SH z1vlf1a%<`~3_d`#n5OC;MwEeI!-f>2nll2OmGncDFcoy6vzt&Sbi81HqC6{BUj>oP z--M8^LzvgDq-T(j;?KIgLGqY*J0!%v zz1QwYq%#|+y7-^QL)0kFk2}cy*Zgs#bchBbs1}IC04lf8A>M_9W9uNl4xf^c%c#DP zegAu0^4&jlQ|=*CGPr@*aQ=kZQdtUuhsd;3L>jHm3WtNkFD%POL2b~AH!ZR!klk;L zvL)Dq&>7blf(9IkzkW2m?dO4`jA~t8)pP`wefz$;en;zh^wYnndA0PiJiE1ZtKgsmv(}oUm z-F>@#Z#XNG?<;~Q$LFRZXElsZewH zZo#r4)afV8DPoP}38^3h!)sLAPuWTdtXVTx$>Ipf9l6>O#kf=`s={L75rZQ5nt##s z1Ehm<`X1NEth9^i9j)Gtg3LM3P(SVBva7ecFYz=Ri%y+Dg;-*m zv4uXyB&d@ynF+1wd^$J{Dk8zt|-=OT;m-F4#(N@YW#hkBB z4EHaM@@FZW!V_)o%d;0Kbuj&TQto%^Pp-+pBOw&)#?bL7n8WAeB7 zROK<>vvW5)hc!-kc?ye(-1&8r7Ty_RhRdG)<*q$FfzYrpC5`(6O9RGC2ce;-^2;+V zucYNFgf4-%J{Z` z9T9VYB#-zi@+K+u!5E8$nW^!Vd8MT0O>RGs8VdO>fy%A_Vs*UmlMd>qd=~E4;0fco zjYV-&a#KSM>^eOxkNxaDpZzRhh%i3`DPK-5>BhY~aSl zb&RTiXj9Ge53-k;6-6abgT#M;>ZiEj&}(l1T-*YJN424+z{K~O-$5;E&^(7nC{M+( z^vJD!NMNz*9+*@w7y#tx()v2hWRtT&^&uY&_6KfyDIWxasU_ICFO`qThKT&EhNarQ z4#t>Qr-tZ{74)B%5l*jS+>PKsq869+;0_|S%bE`F+wA7=IqOcXFg~~cs|Uaz9^b(TS;OaY`@WoOlQ0 zkd0+O5G9QQl8^Th*aAl?>OThP9|O-oVxW4(HLScKu%qS4q*e!T;?gv})*4#$A5^cN zgQyVzU+vmEUZaZU)4Zp0{^5}8TB2qxkG1}bdQ&t!n&RW|SpS^gH;i0eZ3R;& z9)Ig}NRVaeTO~tYB2AKjFDet^I~OXLah+~aFsk*mhcjK|QKd zf$z_SA+|A{;tFZQOu*om$MiK_(kHVeN8<&i=R$qe3`}3l!)aiaF7^6pH%Ixh9WK6= zF;_T{`x|IX*4E|M$d06|ydE+vo3KjAEg^*n186B>3G=n)grMvpeh+uClkbnkSog7U z>@v&2GeVV65icwqPt&eTW7Lv*mDx3(VMJee6oUNHT3iK#1oS{*IJG)~iPzX6)X)CK zM0$1eFcv6wB1EC2ppi0i)Tzj)-_QxE^p_2iTRhmx54fI6d%I@WN@IE`0@b4Q?b4~b zCmMRA@gto><4`=OP1+{=6IZbB7sz?8%MgeCv^$^Ja*8FIxw_5-rIU+Q4}HErULqGhCZ!N(wlT?U0;e%zuH zxqMcaZ)gGki6_Q1t%Pq_3`+A-5pl`Fc7)}A{|IjGsND=Z;qBdnm&PP9$K%>HmqKM_ zy3{hZwV$58t8kApiS0s_*{JcBq(4m8_MfiA1sH?q!kTH3sw?VgcYp8bIi94%B>hS} zehy77(?Y5#&ivH&a98dxY#U{4t>`KZEiG}I2!1%>qlT0I96vY(=;kat!kqAXC3lOf zU?h!;C3)OZ7ZE0g&X+2RQR3Q`Q@_*Af z>$v>}#=3eu?~)b#ml0!RIT-IkUruPahfnv(AVSIT)H3Z}j;J_%XlIijF6Z)GcPHfe zh#2+WpWlUe@w z=u^GOzaaoGq>JRsBHb9SRoDwGSj~%4vX-axqnPfG>hdVAItXM!hCw)@ zy2X2#IQ&nMpBT~)kfFO?){Ys3lsM+Kwp6~|X!cpHIl1?9?DJco+pJr)PN;lObPSZI z*DttrJp^GpQ{=!GPabScRA)FcxxSrw^j(+V#N6eYt)7Pm3i6QK$08<9K^pLYlo z2W6qo)^ZjIHrAzf^?4v%FvbK?ydfm+t4~K4pJne)*IRLVH${77BuqV>Od{XBXDi5! z)kFm!txs4FGr3N=9d@9T6Cyh7(yBMbhc7E#RqQv|zM?lwgkWc3n^bHaUV?G*U?D^x zR3PfDibFG;KYfF-xoEX{#4kVmC7y^ZEltVX?}LJ45y(5j#{spEvtUSEq~BV6;BVa! zD(_d=5t6$P6UPa078;Ac7){ovY3>=U1Owv#n>M}6M=V!enX;GJnzf(bRQ)`|c7DwV z{Fa= zo0C#GX!_Lzq!eN+t?`*CengH9{!$QV0!`5M;byX$&{eAHsftQTlfMuaZk{J2$!piC zw!;1p!yZ8TOFz7jAt$3eE9{gmpSvvDyV`a+;?%r)-egd_w7f}Y%KXRR_E z!pN-V$*zuOsi@WPX!J(Ko=3qX;2XXV=Z{Czm&3QSnGfbhEopg$@AVkdmZuPi@h{M^ z+6~VCrUS89_R7r+UN33mYkUmucN`WppK_#WLzEpQ4_HaN8Ywn^x3~TSYXDs?T%<`- z`PIq%j#ncVj%qfnhe)VoqC-TJrEz%UAhY6J8VTF(?EhT~@ zq!))9-^EjKQa4{*3v=hpYoPs#U%_)Ck1iT@j-7_GdWob!lewk@vb8@(D!L?ce>93v zD1-jOCpkT8$shI_dJRm1lut5J+)J49n%FeJZlW)#>;L}otUqsXo!Kh; zEDefi8!KyAG*(M2LcupUulqd+_|-N)Y=AexuRUF@vFB++fCdCYEveS}Xvv*xWxuJ3 z&&gcgC$xE6f9d_2(i*Az9}7^`ZIO;uW0_oHw6tN)PTZ6=Bant7M_5Jxw117e3?0vM z;QjK-QZ5GuwEp4dEA)y1j=-mfAk~_AX8LM{Jx|3C{#j)vXl|drXZIF76`6u)sPnV} z`sp{*GO7Dtl-|$lf|DSTu-Y^=`Fr?3|Ne9)U0-^~5({BMzHi+NDfG%!%FUuH{(VRO z#c7&^NuR^vMU(C3qz<3`r@Q?geffiK50nAt3;-zKrEXt0!GZs6sBqaGNf2fFmR$0C z=HSf1DdkXLpYiaxya2W|s~~qPcTg?@RAt&Zg3mc8KK?8HVim$4lEq4s-38ZH$kixNsM1c0JUtIh?6>H&bV<+K0F z2}5?(V$DC!t`UOv?t9z=7xOpzPmMqXxjG>YPFdcf7GELXzsThU-0J7t<$b0-pF|zP zJl+!%)71m~b%CVIv$r6+QT}#G{k^aC_<koWz+?(sa?>RbFH`wEStY(XzPG@jdF8 z^w*9TbW=UJD?F^E%%QEgb5Jq3gcwwm^cr~_Bo3e$44cnzW-PH3M-&>=ZCkDsY8mdK z5VfBqWy2jfO)Y9tPH*w&%Bsj?4?4?m(GAAfkTvZ6^;`}7znjstWEEpwXCVLS{VSME z%A{a{hyzNc6rWGy1a?YVEB9fPT%P(WJIV$pmpJ|Y*)ild564h!4L&2C7;xaE9(#04 z3yRS_BU1xzvT@82mziE^Y=JnBf(n>q%FyT2^e-OcwI|jrCnj&0 z>uvoMOvAw+=yh$l)^QD6`n4wIue!YcS|M+>vj?5zRS31>wP!*#G38g@ksNFj491Wf z0>&p^p@%mgS(uocY-!Z7ELZDO{j?awBn@ix1yj+iOxH&(&~ zsw1h_R>Jw}r=fhOnds0mjIz-o)QwWI?X=Zj9P0CdYRrN{R2oHHH@=O&kx(w5ByHiX zy)9DC@7oq;?tWpreyx4Bte2w0fh|@9#`ZoWD~26q{6x|YIjvT!W|V~ZMBFPV$x!jC z?9*2plVsGgGu$eb-!);vuwiGvh-1NcZd1_nmK&ldb1#D~p22rJY&Z(U!=d zk)yjV?O#GNV!td!jNBQz3aLeFo=AMctanFuvapm%=FutmQS_OHkVvsgct<7yL|U3N z;)20lcZbZDKrj~Xt;;>NSxK#lP+FV4v();E-Th^pjSRx$FHj5KHgGSjND!eh^{O}+ z9an6V;u>if{Eez8CM%0F!j?)dyUSZbdiX#h)}~6;_aiM=ZB}2JW?l zxMv{WYvl(n;^v&$e>MzwT!7+L}wJ{{E4T-kt2|ImmwS zeXQ%F!eDf$p3BzYMW-VQJB3yVGykt)P5!Wp6%cs zBVJtk1JPYAh1nLuK}!l(W?T#$CuWDQ*ICXMf<3+oUJ42k`FTc{`Rv8l+CGt__Aj&H z9?xa_Q&xzOBg3tf+v#Fqee_`rd`>fo$~5j8Vd=a!YR5?ZhV=HBp|J)wH}2A3HP|>O ziB6~b@|16G7FG(wG=$n0NO<`cTlrMhsSIRWL#hajG>DMq%LiaVf1$YU?UdwTiKRX@ z)XG7SI*7f7BnaGndHCIKh^T$Xt6HkZ{}Sb)9m4n1GRUg9EPsYV)=G{$qm(R%|I z1VwEWaNyS#uxn4v+#bE1D)v@DF%)b1942$g|exY7io1WL528=NLqd zuA+d77~pa#o3n*x+UcxL=*_8j7Ir=rWqt&o51JgVZa6P$c~7^S*!nFT6tWsd)Ve1g zd#qGf3pMZ-%m@ey?%ds_ZM!TPI+xp8UM}yKZ1eS{!yFD)&RPd4@FtuTl@K0E+l z9i0bNR{`Uwrta=_!~PMzjU&h4O<)>$AN&9qMDN*WHDN;9Hkmm7Kqeuc1K$#`gB-J= zYyRWHz{d7008Fnd+gUut-1~XB-~e!)amNDQsUUg91ZU)d|jK9%7qjfUfp1y)r&(6u^m9iwV(qXO{uh zJusI6&d|bnD(zmECiOQpRk76az`^?rCO0-nfySb*wXW0mxFhl)|Ih1?J@-Z%S1i37 zLL5MBK|h0MLXTp+DSqlWzIhib@d0fqOX+*!2$0eU0TcxA-@Pu@epE5irXmOl2`L|T zKX!Mt(#LLKnDOS^f4f?L^k^?TxzuXU+v%KyysX*GbAJ!=3Yuf^(yhkvH0B~kU0zu^ zc|{6mkCtD)L>>J- z5Ta+HM6_U+zMK`6kc){!v=#SJWX3M*8Bnv4^GW)x`&Y~B;l)0=Hy4>wk@j3r<(QK&Rfgh?0u>yz9CvjSrR5rZfmX~MjEPPODX*?2 zCS8R`h@wb@z?RZ#*(;Z#e6?eV^737d79Ek&??-aj(9R2Yt!9`&SkIn4yC2@FOBS2? zZd3vXoBmsqZy$T$AHNTk@|C|&@laXH4MP#RKa>+lwN6G1_6{DINprhjEa}2unwn`U zdh&suP`J6$R0$%|sC{dU&1h4!4N~yf5oR=^qF04WMGaj8?xlvh`yvu(X1c*5$a5I= zxq;tJUBSo&=_N!66a8cQxlQxMp*|dYH^(kA{VNzWGVpOJITJ$zyd(AsrGhrLa2*WQZ#Ip67WCt$=ZKj3;^dc?Mux+c6^ z0ZOq|tsLvE$(8m>>kMs^JRQL^d5FKC77({$Qh|oB5<#2e!1Tdp@fM!({`o^<8^0-A!SFsCX&ueIXXI5fR{cizJ; znMrKB`dOZpN&Oi#dz`Ew8(KwvTf=XO?WHygI>yQk7c?o+2r+xm%QnnC%Xf3R)Bfc@ zV0B9<#{Co({&T1LA9%Q@1I_^}U_?v4f|(ZoP0r;riMssgpM>Q8qDY#Uq_N_kA-iE5 zwmvDf-Do$^ssY5hejhhSs!uPaGYu>LBxjJC=5lycAdlZazL{w#2@L4wOG{4Y)Uf8c z>b(=>R3D0?iKEEBC!bp=)VM3S6MaXi)K%4tpt$eTjH4>*o$TY+C{I!9bJjeK-VgT^ zGTqADQ$>%U(892$n{u~e{*!C&KO+0VtwW&F8YKybZ16>Q4VOw6XGu7U?6g$*qQ3d9%?b!T0OQ3 z`a;^u3SV!zW_G(<5sK7h6qoO!`1saxt06DLp8Va9?g4GR$wSTmb7JGwyk0NNi^Ja% zf_c9^Ql{$mOEEp}hr?u^l{e4og2%pke9yX*rl^8{K8jab!*K^ols;p zR!DTNty;w@*1{5JBK-=b=hYmYFz6BbL)hM}z~0_m&?1^bOtdTmlaClZw#v0?j?f`Q zj_~vBtn6n|IT1yx@J~#_b)K8=7FBwFmMEeRHk0a|0tL+JtILQL*KIq_m z5h|kWdL*o4dKro}mxL=NHfJ@{$KAF~e@4I(ZC+b1Uwx5}g4G~P(9UvOs^GOI_q?o4 z{!bRvJ!TbV5rwrh&L@1xe;ip{MLC*7eb%2k&tKmxf(;7l>xwF}_3-Q@YreXjRnrEw z-FzjPDHs2;)oS~576G&uc=c-b>#!5@t?tlKrCbvbM;Z!F>m9@OA1C!U|Bamz5>O=J zyLa$_i}V^WZi?Sl>fZ^2KH6ulXOjZrH(zQucglla%Afa5KdgcGJ8=8{*CDtcfoF15 zn=5u-sd{}Y2EKh8V0(k=eFuM_>ed?_-0V-jU7>;50m;z{U0XFWae|2BT``C<>h_3g-NKraNwmH z8MCkNURZs;xVQiv3ILh~81H14IXF2z{A!m6-L-d;oF#BP{P{&6OWIdzyCStUJ>5F_ z6$U760W=`c2@cpT{bu6Ei+~u40CrVwY&bRb-xk63a>xP{I#8#AE*TV$`sS$&z5aZj z2>yCtD(ry8T!@hR0ooJd3n7) zwzstW3V2)t!b~;TsA`7&gnHoj^sJL;4;};D}I4U7U zVjOXJ3m0i54sT?JU5^3k9Q1Ulm)Pc}KBNk5as{+1fmTZCpFC|HUxe{f$`A>df1$SV zKB|-fG0+eWso&z9#Ee~@S~dcTIhrJSl$gruB*`?eOen0l=uF`dwKzWd922zo-**s` zm~D`!Xgrq0^eV5p$*ZeVt%PRIX}dSGF)9U{&p&m2 zG4YF}wG@`4moeK{_$i<4X^Emmv}iC+FPyDGK-|G{B=QtY`w}HUL^-&erkI0A5yz}b z%YP%QoGh=>g!OUuG{fKQj=PgAE#;ANL@hsGVjlSuWaf|xwi9V&UYZhKWIboczd%P- zd49R3X#c&ez?xb`5ywb3j=ZB(nEpeBL;%NHooYRLeVli2Ib5vw@w1W*^tZYMfpwwX z79l?V=N)6-IhGUVa#COwXCku(tY9%OdTOu|7d68scoxkvGx6jpZQo78r2cBeTqA}c zsol$e;7@$E0J()6VS1=S#SG)OeQgu(%cztY{tUM1=bf9mvG0;-M0nrjzlEfB;}k4| z`Qmrd!uD9_w$rMIU+FV=oZN?FH7(+m_-GTjBEp3po!q_sgB9kXVP<)9YU$7)G5R-O z&*?6s?0=p#mdV4fFTHwAd0VMYZ>C;fkWhGsx`@x!9H|N$5L!fse-jZSNV*m<^5};R zA(!l(@gsoeyc*8z9pfiyrpHr009GB*5*clFk7$NfclkV4qm@f`Pqex!3-F7YVbi_e zI%;cM*@gD-SY%tzhe`R5G1O3b%cy~}U_bUs#jGAz;@9%b<3J?}Dg2^udN`qwryWQf318Rn^L~wP>k3V=2A>vj&PZNLst`3HFiPa!v z+#a$LH4?)Jq3C;r7|m>Cgn-19*;iOSwq*F+YJ?^zD3y@((Aez4Y$GEQXu}*$e(f3+ z8tX1xj7os2wXX&l1zt2o+0dqXJ3t5x(zTY- zZMb85Zz4pa-;AOuiaP=#Sim7AAMq0={nYqub)PW<4Ra0ltru`Sf*$RAB3P4t?A6BP1jyqbfXaRnI@Md44j! zi}U8XvgktwZegnLLjk zNZFWdaa!#`z926H8gMZs`axsYCp@@Cc_7G_G5oD6HAp@&C!M3quKGNQUw`(*p$l6neB`FFEeBy_GfNM8y zV&^CP(*FO=i@d-Ij!3{HiX>H}e#nBWDDD9BRw=Jr6kP(h@icJ)j`l}}=4u%;6c>OI zvUrv0)e)z!-2qb&(M0R{2hZ=ICmH|a=WlV){`m;_?a%xH1p^@G?i*hKsY!yv{)vK`+IDx$-~LoQsnfYh4B*%`~_k{BaTzvn%?_S$Py zRn-^fyR6qvUH3CT^E3R?FZ~kEIqu%N#dFU+$FKhCulB_rAw-`O*{QpXG5q9D{v`j? zKmDgvc}`iDeO_!`*OX<+#>PeuY~C#yzw5cV@!Pf!jgRcJb?3H&JnMk8%iQhMvxC6^ z?|rY*Ow*JXUU;Dgzg_095Q52U#%i&kw2cbysi&So2!Ym`)oR7Xix;uh_Hbr*cbAQg zjXtY&Yio-%O)_3lXJ@C+{q5A7 zX`1%`e)Z~Ac6N69BFXOVE?R45vsn+}x~$)wogFG?`+pyg&+Rm|)@ZGJ*w+xCpFwpny=JURjd;fFKJ=ZIuyC#d# zc+B&kl`B^mjYgztinW#)BOm(EhbW4o2g2*% zesgn^)oRsea$9S;eED+k9?>biFJHdgua9nTx_I$oe+{YY8m;wP_7CqpTI>G5*UxXa z79Q32{!z~VUw52{yXcWc$_g7xtPB`EAUH==E=Y#s=Ehh$LTqeTKoUbF2Gdy1`-rd+ z<(dLav;%5CX5|KydISbaB34y|=m=3FgCO%MTkH^u94iiSGAB_P=!~Eu6*+O3G`Har z@^AubK|L&pHld85{EBD-E_sF^r`T{tAV+G0R03f&(ksL&Cp*cwsy@QgTh9}%;^xsU zmcuzt4jC{YwHam5#L)yVC)D+vaS&~>N#X>Q=^Pn7Xg>%Q4WQ7$K zWej9yfGQj7Jf|uuV^MBM5Cf_##RSN_MF@wNodTe>x)%^dq>4GI8RAXd*ayjoa3D%S zt}1R_y~CUF7Fmd7S~ZG;dC7)XY$rRYY6lwwc2FTE0%HQgN6;(ua7kG@26Dip-UO$~ zCL_vNaW~xLLVAUXdm0@ii_s}QtI5g@#$uaIy}?kYZ0Lm3)h+(QpAZEMcN2y)$&tRv zA})|xpy~k^<+F_RnAhZ2I1Y1ER163#eTlO*mYQh5=^CpmoNxr^nT;n5)dYLAB25x9 zk&!P8veAIlXAJI+NG@dDzW648vGEtY%vabNZ*Wt*%qlM!=u22#v%mc&i4Rm9@|^q# z|9ScM7>vgJtD~P|zI8~zGhZzTcW>jPW0@}qBA|GAqnyhY%8_BnQX$IIWJULX8|YO~gCPEBtpm|Acx~@%!Rm@oM-2 zDvZ$DQ0kmRv5y}(PD)7_lx!tqCe?)Ubj~Wf#VYLaZ1p~_C)ap!`gv}yZn8PpM%yVA z5}hTi2B*x&2UMeiR3*%k8FDVTR6Wf#dxeenY;f<@1H^%0Ud-8-uTV}4F2t*7E6FZs zg0WbaQz-{F66?S;8#6Ql!W<_9xiS=5<75f4AdMBq1?I>17|AQh;RSruEVI|CI7T3l zddi}z8S8DXCRcgk@`ngE@Y*XkU_WJ%p5d=b>S5U`vK7G(a3qwfz|Ky|voBB#Z(*Zi z9v4Vy8RRpjhnE<+0ZEcjOV5$HLsT`I6lzOdm#p#?YCM7@WjV<4p+d+pB1H1^fW*{9 z9VmTHE$(o|T;OB&@1g^Isrq%^EI*H)f}_NH5Fy3*jD!qW5wVESG^554abyI)i3lTv zND#8Q7uL}rd=to>2#wAL7_G6kY;&0fGHL>@&##sUJSmkJf&eW%Iu@8vH!(m_5>W&d zaRLGgr(~1eC;~!w6io!qgDxcRnjI+x+XT6S6pc+Wu2Ix#sOtjAnvCaAHC59-VmE2v zcMOdur??-YNDZNj#asXUZwHEF2VNQ#Z&Pb&&sGe07v2JlBLUY1G_Hf0w}Z>;peF{J zEZ;NW2s2dJs7aHIstCXak`Ixle-o<>b$ySFIok#ZO{Q<@fo#ZRI74$l+7{ufw#e_= zmE=2BRp**4djkAe>94KgL*NxeC#hVAtk6uB9u9v)o9o;E+QYu958c1y z{X2aO1b=_VZCyRy?|uiP>9-??jjaK_Y9AKct$oP3VRPNI3pHCqzmHXfXzq9MXGFqf zE?&6C-Tl{b1d_y3+cpch%LA58>>xnBYFJgZmLRYW%VUJNuB0s`c>qNq=R7pPuh;oP zV;3E|4C0Q#03tLH`#jgSq6`(2cE4UI8XIZ1;w%WhipNkB5LjNO=6`Jnb$uJy133o) z&H+&)Xq_OUJ%`l|^&uizQ8m^TE>f;eAy#M&PBu_Jbt!3)QsNN8QOSVFnp2)G;X3f& z|E-TfUhvCb_!3_ZbMi&tH;$M5TbiD2)k4uHZTd?903ZNKL_t*l=7mF4{A2!?m;R71 z*3VM9T_&4Xz$)+(q(Vkdy{706-lB*I1fB{7{N|@W&wq7sjF*9moRUM}DK1=`ER$kB@tJ zw^%F~kH@{b@aX7>@pz2Zn*IHKCX)#p8yhSZ3-<2ZAzct}z+f=wRXyEnbgJzR+IFC}Q)RBNpY9mln(P_~=JPq}WZJ99lO!R_visIV zr|y0`(EF&s@4Djiud392*xWxVF!{~KWHO%Kw5T1#0J7-LA&ChNN>ie53>DY@ZX zt<}BHZeRD__jcVKbnTSEQ2KizuiV1Bn3JZ%5yni#a! zZ&BbsN=5afnEyvLLYfmyr^HqG2(HaV_5i`6b#sRuV?~SsAtXW=AdnD|!V_gl6pF&1 zP+3pOf`zxp>3|>{QY&N(C@B%vVxk~*LuU0gVjU>d2yd47L6h!O#*&H}m1#mOS=B3i zQKLjnrcK+(6L7I0CYmT|tn8dYx`<+gDl{XLF>oouDPqV-%>WrSJ_I6;(w%W@FDHvb zgeftt(}gvPaWX?$kBAPhEJD^GJyF!)D-;s5g!jMqy{xEs{q~C#?Lpq%-(fvK;5wuwplk z$m|4lI$+mtF;faPAM(A=e4M@2A=b}1jyWiemyW};H?jE{AsCz$O!PHU>rugw&7eqN zP^NtB*&k$)pK?dMO0EjDA5+_c!=u}j`zyqz2N5ZfC9*PX2b<3*cjoo!&^s8JWe&yd5JpK_^H4Derhcvttn1HGRQbPIKiG+!Z>d%2$e#iFfL)W%sF*)3RN+dGjw7Q zS~Bn{Pmi8qfA2Qof*`SxY&Aj&`1+k!k+VQJ2`uf3xjLgvSL7nYgaqvkuB<3jPO`00 zTC&U+xXO`*0je5ucD&-nuYQ>e&7)HAR5IVkp+<`d$XM4U<(2g1NX5=lbZ z*q8@}3l&OLSP8XC2|^)b#5lpk8isXBINo74xlZmR%XmUa4hd$7lnF)Y8U-Ygd{I!% zEJ6#$>6GWTU!a~A{KoQsM;nmAAPYmX9O4mJeM+3wqHGNR3bDcp#XyaS5(-@tlNuEbE<`F-VpWY)V5~xU zNpKLA#zoukMI;7=^bx!w#2Q4CmFqFMpzuP1@OZgE3Wo|7BU5ltlqJ)_lxtV6gAcrM z^EIRr1SBFhQb!rV3yFx$@fwupK`e=~Xl;%a(hmqIg!f3LiQ1y1!s|A}QFwd=WlaN$ zd8_vI!F!%g75q-cRm5t0jX*YzHN+-=vbKP55OW$ij)5?3%E=*Vf7X=Rg{TlBC&W{r zI)}FRLDqE;!Z(134?vUtIZi%MJm;;Q#)2hD{`MnXxZ5`?aIvII(Bf61>N*L6h|i%vKWjE&^Zjya@kL zi|6y~(}%(0C*#TZ?i=A--&5XpW9l%Ye0yvAcg6RAZBJeU)P_z?+gkIs@GQPXEgjeP z4FjaqM5@x`Tg&Gd)cv&ifnzm|L``P9e86cSwkqNK4%dQ1j|1r&tA}oHifh-I_U~FZ z=f=@2K-T^|2b`b*!!h(%#6JF&Ca<@YQ2IdP<_Id_2t*BX`Bq~D)Hy+AJr7y6*Phr= zb!?MwTjX2<2DbT)Dl{L`Q?Nn6hmy?<4wrBOOf_scINtN&5<)_aqp-F~l$HiW0$!kt=3F(G!vXL#1t}RfNqLUD-2#1~QHh?No%L3# z^OKVv#&%$!19j^U$es0bnx<&2du!OmVu3LR?>$>vTPzj}27^Jb0=#$cUa#CbK0cQL+s;bZGghmP4!R79l9q@C`^~daBQc)Cr zesBkmJL}nX`{o!Ud7i%|FSq;L9gum{`MK}r`Tthm|7x|mPbJ;uC|hfL_|`QHbU*LZ zxZQf`3cGop_aJt$SP(*>sw%9teP+0|wrMKR=PK>>#)A$7ck9)Ak1?jVlNUlTnN04> z4DOE8y^jtCuFrq>w;hmtRI1O1*))Hv^Z$)r>pMOF^ZC3#hu!&DE|>j2-W}f<(>pYD z?`vI2+kGdy4DjxIR+i;?hOpNC8WKYEO&w{P_Taa(jPH)WKA-FRgteBUDEjDuZVh$& zOt*h@d(L_|xAUcOuf+UPk^Jmz~o+X(=uJ_n;FLGGCflDNE zkWsiCVFEJqNG~w)B3cX})D*tNWfOu0SuM$2ig80s+-ArnLhc!>n%QK87>qd)OWw4v z@LKsInKsDF5mztC>zv%Aq>}^{9n$6`-lD~b5TC26z-;Rq@a#Dqbu8P^)8 z7a$y!ObJ4g_$5X}ywK<%*~n9run2OzD6t~NN=1;qwbla_1w?}kO~J~`fF25LUQ$>4 zNG}nlCRG|@!bA=cs-|*=L7p-^n{m;8i03anPZn~%{>B?@UA#gS0>*=NbArxDhbh4a zj{O3c4k-5$K43pWR!u3Z71u9a;)Sf{&Z{@r89s&e0gqxSYkYcwC6Ja0OP6zIPlzK! z8ZsvNHs3S<7$GkV zl+W@b`oBfzDKA$4mP=<>*eRao;C9Z}E`FZn_>lNi&S7!JN#V(oF=MtE+X1QFU{nmS zuA~k*p{($!BBmSMGpGD!{FlfIP9}Hz`v;i{X5$$?HupNEEqevndhzqgcntT-?L%`A z5tABpX0X!rpykPUG9Les=g?1d_mc`ALerx!VgnkZ!-<3QzOz$?pSXN;O|vnLu?vXJfZ zFHZhvq=Ccn>kKoAvX;Cku)gGK`2ju|{t+(J{C~&4#=d%!WHBNe8eTtmlX6g!Z-0$f z`4Wfn9%?En^CeCvWaEt0YDJ1+cs3?31tZ}Q+mVuz!+MXUoHKc0#I60C9N#_0>>2#b z@!?A!WjDRT$;~si{bh2updx2w&dA&l=L0c;N;tF>L;)&-vYNyhMmA%!${4LK@zHDl zn7s6SrTBHUIb{_!rz?dXNpvERp(d3jXZ{W^p9Dhc5Q*TK=`M^Nb-qtviL4Vg>?Ti( zr*Y9z`91P_$s`!0)dZn&2{@fIA1zs#Q!+K+^^@1pZpdc1%JUb#mkm4NwY`^kwfIxc z#67mh>d+@8&NCPp;t%j)(YAxg7y%l zBbp^%Rum#bGD5~F%BSEebnqDOKwD~EV}+v<9uWlzra69Be-KUix&yr3`d+{9dFPto z{&rh7okQFMxzAwWQOe+aj`bDZ2M89zF2wI^bMf3-skI`8V?$a#n@3CG>qg*?I z4+HKUtZ0BGS2XXau%*lYWaU!&~;~E`hdF>xPFMr`uH`=a_zt$KOTcd+cc9yet z4WVgWvg<&)1JvzF%5W$gHLK<=^B`()ifB1br#4|WjR>f(4D@`Wo=@t%TptYhDA6T*@1a_{Fc)3Ku03*X9#M673NVES5kdY3~-^IG&?x!{6HZe)bOw z_9@xR411@mP z4*@?i`yNiGCBJ*~4gTfrC2!n*g_HKYyY>us&O+R(>KldecbT3 zuIpaqC#7UQpEDQ?dTZwKc-({7E|)P)Q_8YrI-RmyE_-F=a5%(T%XmEI}McQQ0aMVD&2&pzG1V!F}8Y2}7 z0Y2bb)pmE@I@s5N!*vK)mSz9%-S4kkJ9qGK9aI@(`qx`Ozw4^z@8C7sfmM4LXF+SLtw zMhH~f#E>KjsW$i7#&`4Ff#B}*tkt z5#eoL}HrTX;+{{B+-JQ$e5{JN@oexU6y%{cZOUC7U>xaaezuC z<0K&~CE9tssaQo%s4Yfi=s00H7s!DjiVB2BMvx&Rgox7xL4ZmXZ|r@YgX9h?bA}oX zo9}>+DA^Qz1(1XU6Ag+A-)6yh(cR=VN)8bK@(3xwcqXHa=cnI8x}5RK z!Iz0;WS|UjS@VULK1a2+pxy?R4v0P>loAsXrXhh!Bb6eQfmwcu7cTq&$;9wx^)+tP zuaN14+Lyd`@-nrp2$Pzj%&4n^5ClePs?gZMKyz1g}ue^ts?N zZB(WP4RFajiNX97^PwDG6d*{h`G9FLiEVQ|pJ@kE`-qbkB zczm#wuEb;szINDP(bDj)Q&{|aIy#uuWt>J4@X}MsqHz^Un%rL>9ZCi2K}j;!Mp>k6HUQYeG19cl>gdFDECFy-L&yN!Z)Y?-HbNVLJI#^*lBil7`ZIDA!8tD4>E z4&q+Mhd%OyP%3WRdXww!{VdA`r{*53P@<$^s0Qd@kO)jFF}Y+{?eP4???vSaHx6%b zJG_Y)$VL(D0(-}Y=%GSv1Xjfv^VKQ-O-B_hN~K(V>LRB?Ggc!Cnz{^?A`L@?7x>W} zr#w1nWRRpzqCF5&0tqrz*nCN%;Q9AHM?KE?%hz6_h&f6{oUMteMPEo+>N#c13BvRF z!#`zt=NNI(HqZS|Fj1Slcjp7Rm~&6OO5qPtWGE+zN+St)TN9#QWah{ z1QC%!qx6W>B$Skl#s+6C?|=9`GOdwX^hF5giQ%|S6eqwVgahF^7Pb&Xp$SqVRU{G- zLX#30JOodcS~3cX_za{BnW|1!aGN)dNaSO|-ye3|nEeX~RZ+L^v8XJ>2Uyo2T*Ujf z*Td`(OQ~m!9f@SI&j2tbIdp&bJYGm!oAMlzxhx2(v7Pe zUOV7FfA<}3(+Nf&0m}htpAr;RBDe8u_Ss?8%;9{1{;Pk@t6{^DmswF09t&8Cvgq(AJZpLXh>$UH=%s zbeNsHf74DoMZ`r5VnFugHZh6bqn8~JI6fr9y>pmi(71qzWH15KsXH6j-#WGw=iTlM z=K$drXiN{Ehrc*yik&Y{-A)9NW>u4GkOx!z(Td;r_V4iu@E^YLdH%KQFLUp6pW}c0 zy|42heC@9xAKc>e=eUAh*hu1k^k1t&L3a_m0kj0EscORP^#1@}c zs9b|vfPrKa(17}|OU!8lDL`^4X;HDGxmaov8|0`ZtWTh588z@XUwVyK^@IocnE#9S zxryOEIf1s@PhU(L9=Dbd1Dl(R>J}+ps3m&@`292z(Vup-ZOeE(X1QEa6a`nWUfs%q z4xXz;QEZvH1DIG81&hUk$z-yXbROhim&@fA5D-GJUaz@+{W@A}?%lfwz%$Q0!^z1B z^Z6X_{Z^8+s;aHuY>e@#0e&CXZ%;#CYOOCY;D){%KpJDrR)Ti`+&)PdFAG|l$<%CcHivdU;3O$DHhk0q}w*lncowJ7H-jxvFmHvLXZU4Lg z+9y%8HEuJ?m=nAPm!rf4C39jD__}5^R^-}~grNpn-*z(3QPW0&8;|fZ$KcT+lD9c2 zC{hXp>5wCf6BT3{VaJSl0o`8XneYYjLg8n3xMzQ#)76|RtOjB!h=!PNfDJLWkUc|fTb82})}h6^6-pZPD5K2xSeu%;b6jDJ z!H{&Mb!WtM#6-WuH2ow}NUC%fFFVgH87AoV20=z#d5>1ZVq9_LPC3qQ!6-2i`=lUA zxxxwydI?fdB`~q1^oE!;wV2=ph}58>MG+9uAVUdB5mZYQo;p@!MM9_z(ML26=^}&{ z?Z=2!hME|nimZzhj>9*(yZSC>w5GZqu+{U7W)so`3ie5@!LJ;&j&WwlRmH?l*q1AO z-cqZ#d3Uiv+Lp!m7~wQ}FGGz5r8+>YGqU*}d-d}a>oLz}f|p+VEVisUUL3P%SJ-^R zBF#yo?r~`DPnhdt3R!Z+>{Bi>+}bkTJAf?XXmdnxEkZ)AVpl+*9Jj`A^Ix6)#~kEW zk>iG>1dFRngi!1i2RxsD8QqS#S--``oY0gD7V?Bu=D=Jbg~YL+W5x|$pJDO%Fe3zo zR*}hmj;bYv$_b&nKQ*@Qu6qfiQTbG;!~FQfqlpNi6wWq?A|aH*hKj@eLp;6*TP}gK z%Xq@0wr4zENT2mdi8RRgEAZAa+n-WxHu&JsQeP&ipMn_Jj3Oq4P)H$q>F0v9s69nC}lGR+@T;m{{ac1vv&)sG< zU6M@-#=hW;d;HJ#zhvU~umoN9p%s@&6LAV+t(d;dS7V2@}EX7NiDDUf?f zlRRrzp)$c~yCRwvQjJEF%{2GLeWGZHT9PxPjfxOTVk`(Ll0*hsfp;386vj(*Qj{LX za)i=?Ha0jN(L%zg;#A*e#W82a36*fP8;?>2d+oFQ)$q45#_*5QuW~=$Vxsr38_CqQ z-~~>M&{;_~Dey(ZsFq@n%#W}dP&Ej ztqqYSjk|-DZ{pouphn3+NN+=`P{lr@@jK+kvAOq6A~p9=d?!;(CW1GC2XwgdX#zPi zc-OOiZM{t@@AABK|6ACm+@I9?>RdHJ^fIcV2V1)T?=TWCnZB2C3I2Wz==o9C7Mybt z&tc7{=bSEr&==(BI{_UsB-s}9>pXy4AS6km>_6Pk|6+Gu_K<3PS|LS7Op=r|LKNNS zV?0-Gi36CMI>u?=Zd=vlUZ7Xd9n)@WD*Vpzflrb)#SR1<>U??UfyDqu2q4cYsFm5R>%6{g6N}mfaI7pgvxKgm+@slJ8x~ z$)l!;%g#661)LMSb2?{pc$H&d$r!~A4$7b6EPaK*67)}iU$W)|#fFr6fW7EmTALv> z(Ayah^Ns`|Vt*e{2qc<_46Xxx`!=*up`&Jl<8=!MB692gDeKlEU3x9V3MA*wHC;zR5kSTqy{CiAAyzksxkU#Mhxc13H4_{m~gd&Uv5?xd*gleNQAv z?fE@ww;D6zJoC^8_@w)KVg zIv}k@N{EAeq!M^55YRLgLUipU#Q8CIEWdsl4{>`eyT`w~Zy_$8-=F>Z$R1(m4~)bC z3>(<*9f%cnShWVJJq)EJdZ}W!1(c03ob{6Up9CQE-jY(FEOSmzPq}vO8jHo^f{MZqqyNusyt}!2 zxZZ~AC#CK)DFwU_kM#L!wb;((=ldI^%;UE2loF53HN$?p>ponVV}@}tTna*TpB-`r zyK>IMH7*2?%mKrBe7XSd57z&m>f`mok!KT#CEgd5`4wiP1A+)F*QZp=BM1?xJkz`rr>}NB58u z(Xsf+x&&(6AcaGO&fiUooGdqpSmSN)$|4QkJET$s(b9@;jBNY@ukLcZTmYFzY5?-cim$b7Jf?lC~2}xq5#*3U*mP8~)=qfpNjL4*Vri|!V94aD} zz+!2`92panf{tMu97N02=@lBcrU^A-EHRVBGM?b%8DhUc?XNhqYkYl54vbUB5I)?S z^5TuF+e-&QYNtos1yD#2xaYdWA3F_!;(|pYVHc z{S%5(A)IEuI_9QwL}i()Gg1U?Gjz&ux@A`E^O^Ch%&QgaY|hIszf5f`_3aI-%HrEV z(vW32d!nQ^4a;%MTpV*4rl?G?n4D18Et6)<=gZG?P+a5Pw{Oyh7V?D41C?4L5M(Ap z3s9NDqq~PEDF{IjQ^F^R-XT+`UV#8@3?lZv;K6d4Rr+Bi`Qi=`b1`Y*g2l)TsRcd; z#`_~`Hb|{_I*jNp<1#)vloluYT1E!be?bo$3?apHYX9Jm%EY`>T@%yi1Q^Q6yl+!WwaYL46eCDMu z@KW{)=H4IjL3kI{6dbIdq45nz*Wc&ne8tba_*eMm+uz_MJYYXv!(@>xNN!}$^1|~s zxMknv!~5SO7aALDHuW5pNt|o=*3EA~qiC|4tNYj3go=rr@x|*ufoXHzpTEN&+d007 zv=56}Wu;SMryv5jXerz9^p-Yj{m zeis*4oD^qJWGFpCSdB>v6$E+kWZHCo%|0Shq#P9llURf!QUpJ;6vc?tN}THo@y62$ zd2R@&f>OkNQ{8fI;sJVemlBADG zvLQ(DGGa|43Qv+2Tp$UH#3Q68D+;D^50g*$VAZFalOTxxdJqwjM3*Fff{fq0tAE@l z?dSbZz$k@G1wPbB8S!z*O)XgR9dP%dT0rk2*uBnyQ#wCCcaGa`6R>6n%ykz)$BR6h z_!!{iqt`Uzae&On0yS|5%MQbcfOhd*CUplyacK}vk-c~2(_xY;`u339f72G67ehOVk7(D+xQrj$kXtD5 z;$-(x#VWh=U3yBc|BEdDNBnd9XT%Pslsn|vxZOG;`m=D4$~KEm%{PXG)}H7D5!n@q zC3jJddCTA(nfr5*TZ@4n5gv?w>3tt|3y`*6!>Vtk*aNlQ z@wCKquh_wxcqn2L@uNZCVJ$3Ncb~y@h^$Oxvy9cLr&{Lvd*=J5phAO6|zGN!|C zZ{Aw6V4x#A>a-**j$xLeZ#>W8=rzvX{yj3G5hl_EN3XO^hzi%o4@S^JDkR30OpcymuXvFd&-lt; z{yDO$s zwn{=S4uxpFr9;nzx%Bq^^NNQ(lplV#vtbw#-T_A&EUjp9$&th*Fn<|O@7PYMEA(uu zmQs}%Z92K&qQKR*PYYbmEl(mkKUIxL9kVe4I>=sHx08AfA|Q=KrY^ zb9(iN7$ej6Dw!ydYt1C?kxz2`Ch*zf72bRIJzoC&XSu(*McQ}{RgUqRW>Mn`k0=ED z;|W#MP_+#y>obK~Q8fuQ%Mfe`E~51zQW;!a;G$N%YaS>p#)7+H>7_%%k{BQQ}Vq1qgobvLupXHz`Ij(N8 z86C55XXJT}43_8vvx!3bir7>LnIYIi#%qM&L7q`_i(8xjmk$bKE14mk;q%}Ox7GNo>hktB>RL6w{Y&q=(^+xl0K!SLFbpQEk(_U((iVXyI!Qtyn2_2UiR(+h*1#Wu$UrW;i`%QN5?I$D8;JF}GH?W<=`+Uz z(9yGVE)dPsg}lon;EDK{x#h7E#SgE29uFc1YC6u>68Qc8bD9t*6s-Hi_PZo<7+DZ& z!e+^7zm-Q)2?==yO~-~#u9G4UV&}Aa$1M9WGwcZ$JnnK2#TML%7gvp<@3}{CD*b)i z_cAWyFHSs8u32#I<+>wX{Bf6d+EF@q%(K~(nFTm!`NmFJXE=NhcqQ?@4bb*h;X$R? z&*$l)!gcDhUZjW=uEPw4IBz4_0pwyR%1oW&fPDCQbudL|XW!eoswXSaks|CcM?K8! zj01ox`ag9B#tL`N2#%n9SD4eE4T{0*_o7Dd;NyM)eNGZmc|PH%w)?rT>F|Dk50nuZ zz>wk4plfVp>2&=PZ%I!|P$ZZFf&xoJpewU-Kt8T%t8a2zcSvfXuG8H9ZSKoA8L>j9 zh_WE0CP@vZgrLctVB{-eZ`mG1B18{KAjpx3Evq@Do#nU6!4<4ge8>_3oN-Lc1PEv% z3P(&2Na@$Gn=zm<&2vD7i8U#fAY}jCpbvXhW~pYhsLCzkZ#QlM}9AzrK|` z9b_^u1hSy#8?|3}E;4|D=)ry^QaM}Mq%5mk&mEIS(#W_b+Re0~Is_GM| zHLO-Ej4{mTbIP*Z77Fa`?V+`%s;bLI{tMjypJtfcFrJQ(%m}e%-7K+34wR*iYgE<{ zgeNIMQk`sNP_biL%NAQX%3Ppi2CGPFHG4eE;q)~o**?i{sG4I|;T|?PTzg6_9rfOd zIEvWJlB6Ir29p%R0ydJdPo}RT@L1b{n`lqU1W{`|il_kS^63p0W5uy_gv|qD8wr`}D*K8JNjaz`DtW9=h)giv z)5N4n8%ygFdLoDfGAR&35|luC2vww7dep4IiGWKrIxi8q!KM}&BO^H`3t$_;rr8jq z;NajISFRm$vHd=@kQcH{yZA=tl}2F5`!rFzvwKF14qU?0y%CAiF{ndVf_B zB`RuER78<*%8`UeB-sPUT_!4t^W>mRl7#5MJ6)rqCZ(Jtx^1HLe7N`k=Og?625VQL z^ASWv-Bx6|Ai2)(H)am61yNgwl0;23lDmsFi~CC^uAoU3$Eyc~++$3^sk}$Kx1kM= z)Ji7t0M+D#MzE?@+;8u2@AiGHY_Q&uQ8001UcK=u$L}BEqQjluR)3x73;YbM4qO^qI@S8{}r`(u5OIoklv~$cTAhHU)#0s#^fs)85$dV+iS|+04 zXJ7p)nH2oN@qJGGoTvpVNcPnpUJCBjcWB*`NfL~7N$?S)6?W~pcjrDqS=LRBpL9Td zdj_SSF-j%TI6_&maTUS~ay3Ck@TR4{@_;53TaPj5Nqx5n_XncStg#GfU$fw?6z3>Ip@$&zC;)3QE;{`|W>9Fg0n* z_=sBuW5=`wV{&v*_^s7YK+3N0JF}W*Sy8l!l8jk4LCP_W^=#SA1xdF5sbM{jE#O2E%oC7mI!hU*mHnE%)ocNGX;!P z%_hu2OQ<*Kyp!gvf&o#0^jp*K3YCHM@O-v zG$0;6%z=X|`a_ZD_oN-qRxtq3On_cd z>IlXXHg5p?9F$+=?%7?WZotOvEk_H9ivrpJuFG)^z^;T&l}&)ap=i)(BB^6EZ~MHb z>&l3V9WX3_5fNiH%w0<=40HlL2<{Uwc=iz#Xd)Ts^da$ZE7wztQZZsN^QsUWXpXI&x-s85IB&p!_@Dw5Wq#TJKf>YM z;33_4-4;bbS(cP#$!s?JzS|dN&W#&4I6FI|u4}yatX8XS(a$C0_b+z;f10ro8ToLLmP=n8EQR)MZq)r3%q>r&ykB4S*$AD z=$Lg{ah64_uJL#<0i_#)a7Z+v4fx=ZNK^~5oiWY7!u9EAXno7v-@=DK!HNZ57@X4B zpux6G<&qdY!3dHO$RNPXr9;<4Us%eEI ziW(sUQVK{pNieU6hbN2rQWzKj+6PE)_QCRC?zmTL&(X>=W z3SXIgkxHHLetQ!cYAQA7G`+$7`~M6%3W(1-?%X@#xx*LOU(WdK=u4zV@!9L2r=;Y~ z<2Tv(6*jlrj_)HMD9UC`tr~nDsYe@Zv7)GR4o_a;x$;?#)*mui9q?~I`yXMh8h&T< zf3gZ|l$uew6>qLSc0Bk5v9b7UI8LXbWmuYjYKn z7~2W^t7pjN7;$642h}_1rNA5*zQeb;uWu6oB0=50Gmp({n&hczu=)f`phy#BG6-K| zV@>fwi6|p?>JK=~51FkFxUqZzb2j6rU;7I4X36V|Z}4__gH%LxDzU-xe)bkgCDKGt zhXzSvmMe0FOLS z5{;iD3QshiW}diaUtm1iqb`m~<&3>F;p}vQpR|aXLIlC0J;6nfH39OB&`9>ubA0XP zpJ!ZWeD{NI<5^PN7_mt!s`U}$kWe1RHd1J?{uFClmT80^H;B9@1xsrU&)c8m7yQ44 zta5%o{sY$X4hLn;${o|D1=2*4P`Ie@BBD(qC`YCj1inpMmxy)`VV@(DGxG2(b-GOy zEnB0%?O5zwO|AEcUKTLM2vH(+L?*#X-{V{6R~YFG7apK=#?+0OI!TP4JnpfH2ehKX ziZha0qG-vZMA|*@hK6n(pGZjE6_d{H74(2Y0&M7PkXUuVLhE(_ zk5qTNZqB#&kCjV(=vW?+o_=zWPyCp_r;ly_KaC{!Wn9LO{8Q4$Tt$z$9@3B6IbCG> zU-)0xJ)gLp*W%;u3u$*wk9Z%q`M4px??Bgc2rc$^oSjzP-QN!IJIwjp`AKO=4kJ3- z*byU0fq&&+`UQUNH-DRkDK#$;`C@ux_)gtP{}!QDIG0Omy3(sB;6`e1wMW8dHM6N{a`_C0YuMNpx$46T76ba#+JBT(d- zp-D>=o-g;?{>wl8RsN@M{~>b~2;;VE&j130L_^ln+B2>Zu%zzna>=?4phmsVW5kKg z))zVW3J4^tzy>-Ejf$4ew>i1pHHh0TV=g`&)^z;s^S>mz_U!%>wxenHQq`?(Fvc*Q zP58pApQmkGwAR#h&B4LJ6ZiPNjE`H<2qu$R=OO1hY1RSI9e}@>!UdU~7%%#^uGedn zQtTh>k>!Tzbjq{OJ;UDK9#vIc@UMIt;|EQ2B=Mu&|3avq;X8PXUIczy+aRTUq#uVd z@uS}VKi1F~G(tF!GLk}P*q8{525n(to~2zshrytmV`L0yl~Xy#X?;vQo3jd$Ce87>MP~_P z0x?QbtMPzS4YAM!FAi_U+I7J@|P3MU&}3`E&YWL_kM zaA?(%geB^Rq%6s_w6VLFXluYJay7vRkIHJYa)gg9LUiq~lLXaZbxV|qkO_Y4_1|Lr z>%2zo>78>X`0YCI&rKV_7z@%**Val5{Q+%qIEkQ+_L2p>H8f#yMbhq0faX9i4Q zlo?)jFCvZ&SL}7Z^0}`v7dJS4Yeic-LKZl3_c;6Tm`q*ap1%uzP8hXVE6Afp)|zrW zW-U(f$|6N4e3ZMqs~Hu(_gjo093o}?LRt`oB*;LL=YDR3m)-8`Wjx`j5{M}hC4?Ao zA~KqcX<|jtk(dHP$Q{t_GA`rkT9}hv_nYNXf+{B$2ML zjiivNV`dK$^1J?~Dr!v7q`sr0NS!j^PHs_b*KTQ>gzIFZ+m6NH$DR6MpM(^u#k0l< zjmdM84m7UjUU)zz1tBH08{wlO2}zOdac%Z2pFjLESEdJi{nl@CV{)A^PlU#?2n&4S zN#lSj6e?zzm`F(wdUi_^4xdMysac6*QXZ+&g2TxH?XuHX+Y!x8$C&QypUKG$wa_p0c8~u#duU8wWdyZoed>12zPUkc3Qp1-B?VquQXY{gq)`Mdu_4k1 zPb|PW$J#BZ?FL;%Nu>Wfp=6J7v3@~7{^VEa?$2K*=3NBjW~KmI`T)5T-)+x>>!)=tK`jKlt#m5%lBT6S~uYgzS(Dd6R?gATv0FeTc3e~#}M+PzsI~7av!q~YuMBQWC z>yi8SL!k#L*Ue_bcs%ZW(aMtfd`_O{mr~D9d8}5e3zN#=^*S&-O{TX%0C3^=T}GcV zW-I+{t!1%T(6%i_Q9S(_y(hQ%6F>PFc&x|oz}PgIzK}TDWqk`Fe)RkQ$9nuEoO1{v zD2k%1s7?v*{SL$b`y?3qu~U}ic3fz!FN~+lczOr#C+Yt@&uQEC&wpuMN?P9#eM0H3 zkf3Ap)<8fC1wlh7(855BB;O!ZLW-Pr4x-p2E2ktCx$AE7VEH~WmV{AD5_6(CrpN?B zPYI17CP~r(Oh6`D001BWNkl zJ*<&h;VVVbHE9&_SwIpHK1a4!iAq4}*rbX!o^V)xh1U-LU4nzRPW~58&%VoOIwPhW z9S%t;;8jL61;mULJh^j>7a98aS@yX`5fr2P8ef|HBH6y-w@-hWYV<+DnXt4i6z&GIO~K*WHU7;P z{v9M4zkc^OX_eqj^<8c@Z&A7tUN}V56z!ClTN+UjMv^21);7G*zQSLNe}n6L&+?n= z-{LHtAV-o1<9qzQ<$sGF362lnr8PAn9TBew^0CLroMa6n#-tQzY=z8vKSc>L8nl}t zV-CV2Xi;JV(&G(SG)_spZgIMkR5CtCB)tWCcVE+`1oV@iEw=@bku1}gTvLfi(!Kw0 zFV}h*m+?f#=VOWpx6;3W)PfKLq(n}J(1OWq%zCo|CpsV4%klff`Yz&o;zT#s>xYtv zL55z=S)!ssMuqANE4yvfIruBi6F28dsgfi-Nws~R(j%hkl2{_pgf(bM5vByuQs)&q zPwcIy7^m2X4N-!ZboZ&K@WOC5T9X$A;#BgtzWT3{)id6|^B(UWe3#S1J3I(?nV&7# zEA}a4SB#e>LvBkfHOt}*m$#iYkkph{a_+2dab%8I=S%jUzslE}-{5R=#PQYp0Aw=5 zdDj&v`V8L&bRH48!lghJ9bN>)2rBVy&YJI`X*n*BX-tVIb40Ns+JNv^ndR4*#DeAG zl;XL78@JqA+yN~JBSS3%b(CC@Bk&{g&6pS57b&mgOp7b%#Rpumj?MCnd%T4mSL7xHd{%9q;>$qT`W+X|Ht%e1}`Amp1B)3fuR_< z;7%;WIa;04041yLH4OsELou4CW2QbS66ualb@V$d?qQMCDYfNvDmlY(8sPeJ&1);q zmAv3<*Pi9XB+lBJk)D$2f@WT$OGDa|2;m6F4~W;U@XZqb>p!}~sc$%9LTUazynG(d zw`kknh4eaPa|Djy>fWFEyh}P<-OxE7Lnqt)>9wEs-eZixT8j_@rPP+`w_Gl_AmL>^ zogswmeOlCozKSt!LBOGp2QYX5`$Gr_0p9y9OBA3e3WN|$r&GN5Pxtvh@f|$z0njHi z(}e`*@H#NS2heu_^L8b_f0XGAxO$0zCk^?Hpl=Fk0D+7yu5ptM4yfC~-D*C^%CN~6dL&Y+~T&D=e(WW^* z-b3MuS|hYXtD*y?V}tY!%8Y5eBiA#ebF_;!SMmv8c=1b!R`cG2Ii)g46M+n01dj8Y z%*BRcd==qxRISi55>>*dgmYa5h=O_aZ`CjOk~QEVUf75qB7}DhA&E_ zNCa&$vEW+!Dr%h}?2MoI+)q-Z$b)wpoX^NjL6nI_yCBI0UP??EJ2s;a6y%sV;#%=M z)~=Xuj=)BgYG_g*B@k(h3mam-Cgv@+X{g)-WNHygQu;%l5uan^b7p?VtD~PLlr5Xh z1J?dMNF{_sCIvbRoXISQEkOiY)q7OS zfJ||l)R*a8@cH2c=OqCABp&+u-=qX3a8fYapLS2QB!m{{ib$7n8Bgs}zq@~sQpczR z%5lM3tS_iIUB;7$*s(h4*t;T0qKMtSKtL4z``dh(L?(?$o#jQ853@}!R_cqv;}?2$ z2@oP~75PMhOlN3qNFl=phi$tZy4Dk|LroM(C4zJW8%eF;etn0U6Fy*sDhxU)4$J}j zuk112FZjbF2aB8+N3XFsUXe0SJ6#hsNV=lYs2xFAuJ2!EwOXSJMY4`7`8DiGgi^AI zb8fj?#Ifa&t0=3f(}qIlXd#GABKm~MGDH-#At7>*|37=fg#utlE6-E!?BVe zmg6Xj?bwzqieneMo9v;gyM{ZSd(PR@Z_L9!=hUrcx1^X&HYx4}6zWcO?y2wI`!{^o zZ>?2Aoi16&3+OLNrN(5{U|Za@C~r8dj(F|a&ok?%eEsh4vT~0Iro+)Qn;Z}d$?^IO zH7z(kJK=Xv{~3qA!H;sIbG_8Jl=e0fx1{j@T8OzV~+}w7%ef?M3G3bAW03%B2_@fCsLCn;#R0L zILry2K17^E9Nz1Q5hF&77%}4Gy0m}=JR$D1t3#~T2b&W-1GQ@HF+#pg6q1xI0(k%Tk3-KxZWXix ztGeIri{bwxvD;5PDhK7E1P)qD)%Bb>%d%~m%&v2w=Csx!#D?3h;Q+z%^b%P}&VdUX zXl1rn92d+<;#uHlaZYdRaRByxB9DM`U_+w6;*u@53B}@v(wNZRduFqNRkn7pi|o3N zs;d6jlRke;x&gzZxFvOgr-;2o+>?L1pV=wHQc7q&5I#Fg?;ZIQLippa_WWZ2rPP+- z4SO4JA;ey_Xt0V+Q5tA2R7?Sw`RYPZ5J< zS#Irv$MOGP~FczH<23~3zxV9nR+UnioLi0x~l z5o}@&Y?u`@R7hk#p_0Lo6Sbi=7f5LlX@&8i8XnirF)rwqxg@Y*1VN{6^fqLwcHcm=3e?b?c;_p>ySzy=L#Pqooxv*A_?TC zK*tGp=FgK{OR57+zanYSvO}QJZ9yI)p{S8EA;W?qXeQB-^;1mq8b4Qlg;ECEwxwDx zxX4aePu8@uA@4JkHyG{F+M%>Z7==lO8<)@WE3^NQ&?o-M<^Msu+EB}L?oM9k%sgf} zThdL=aki#ffY1`7BeARLoWe?rI+SEKN3Vw5c{kbcwttVmeg3z}&r6zXD=xcJj;3?8 z5yTMKG!3Q?O!W*@MN-g(HNknZB2bGZc2d*14Y^Q=kVBjzLXM6R#D+F+v3kf^))7j2 zMCuVjp%MsJprS;@Y}q>(2ydYoU&rg1Z$M2l6TrUwbgQ&nZEmf+pzQf9vSUQ5SpcAnMl(gGn`l1W4|8W)JMhs+~MTg7;e3=yr?AS~LjqDf)IkX9fG6F zvizZwCqgAYd?G;Xk99nGCye4-87I=qP2c18~D@0E^m5Q&y*5% zUGvQC+uVEiT@DToez5xe#NVBRYFkN(`cShu5%+|il-s631SvIA>is>vvwPk_DfNB- zZp4r4{gX&|goG?N`|BQJ+{QP^kC+6XMxN(`E&TSH?+yTsWB*S?%kdAr{{|lM2g78`jj}$F|&$jGn{QmB%H_) zOet4)D2-1}m2!1xYAUDu-Fos_k;LL92*Nn$jII zS$_tp74_mBTDQWaoU)kFcb4zG^E$$Ke0D*~&Z)bOqr)%ZdP58y)nvxnuEvqxl3pyC=UdvYH) zY2g0Z8@%=I2@^8e1z zprk^jh!O_;0@)eF<(!Hfovlf&L^P2_S&<#IJbHA@ z$WPJIAf3W?7OPvXAKai{*1UQDU2MK)eYoUQKO`;!&&WeI7Y&oLB6bc{DB5PohgL?i zUSCqk3Ks&AK-3bO^*rV=xikcNWEN;>XxkQ93Fi3>lEaYWTtF*LVJdpjqB6n7dWpz9 zB7?X+aE>YBBmkx@Tn&L6~Ew}>TAT0U?dbz=D6V!3|A>J zkS(6UKGcdHRY_XE!7Dq6yvHp2Po(x&?TST`s5CVCMHZkiT zd3p?Cn-6;>Wi1Z5qgpCN64+qL$Y@hfAqym*A zS(5aF;v(wpJRz^T;%>>_?HwS(R=$yK_Z?~Y+IFlfiz#ggAQQRHDSUzNYg%d1CZMzi z2{u_EqGF;?5;53}5ayD{?g1C#l1C3dAb7#t9`VfWTiCVZi=X`>Qgz(V@3QeHSkYsI zMkWP8qN3)7+jn@sy+?P}bNIqF?!59cr{&n8W55dp2FL(EfmQ=G+{xfq7oX>Plzd~l;eUAV9;-AZgauDX zTn~H7dH3=5d*VY4^6#gpJ_X4A+mT2jk#L13`;ciWJ9D18w{#)#U%vj3Hvvxx40U+S zF?wS;oGV_G@OV}8cQ4oc4kas&z+{Mc0U@JbewUul0AB!}NAoh+$Mo?5k&LI5(TOX< z0Z-(U*Zu09!f*J`KgkIFD6;dX`kDJsJ$ALad-pE$`Fx+NDy7^LD5GNT2glB)diU{8 zwY)q(=kDFReB~=&8H+Sx#E20egX81ly{pF$6>&)n1tJ^(hE6DKu#^$9EMe0l(o}Jt zI!@0XBjO<<8?tYca#T#PjiJ*OCMqhsB8C<_opK~U&%asyDl{v8Km9kf>4HT%AjF*e zXnGB*x2P;qEF|Y$OK_5+DzV`N6%0k3gPhS*(AWmq*1Viv;a`(~iM-1B2b;f)on9h0 zJsFy80&VKJ-~uvBUO18ugwRuECBY^9#!|*3reeV&O=-?0ETU>5&&SAV^kq#+3 zgYt?%!fJ;s9Z_2@r69-*F9O+dCZ6%P zDcyu->6ywyphZZDZ%cA%u*Olx6DT^gkW6*W-S_?l_r*InV>vVnvIKdS(eyPz^yE}z z%WM3?^S{WAgID;*>tE%)_S>j~h%X-TzrXv}sY;E%74SAA&LpbHkTGIqkIE!<8<^!4 zxstT&4w(e&$&%mbe~mI`oL{@dWgT9v@v=o{hIlDaw&GelV__FO|JogDyW;M}T~^&C z2R9DD3sQ`Pyd}tp^pRX>g!aQhhXfLZPad5aM2y5{Sd-c0h?yirH#nV$jJ|Iv^PFfE zNo1(4C8D4wNZ!OZ3L~L2e zAj3f1myxx<;MQku)9N)rT6Avc`W7SePv4R1C;5PY7&g*^NZMwVsyJkcs;E#=5oG`k zUU`Cudzw-vIpm?IpYR&|AmvLScY92c2;1zffi&F4vUtdpCV4@Oo}#L#R~z(!re3!! z#D@={jAPD^?)phoWIu-t#VoBE{ zQ$)Jy_5u&8fGFZXG^Y-n1Rs?K~HW3VONgH${YWq@$LzXi-7a z7d3z5^sl0W;^%(uPjIrikJ=>4eufeXq(C@B@|HSlu-$zy0%nol{O)gXL*C;0&1+;j zW6e47pyMpA$;*s-S#zWh>FSpWxIxq6)%&$^S5BQCfUq_Z7PzZsK9$CrL@-mD+Y?Jt9KsW*Dsqr6u9fD@Cs7#9Yz_ zhmR4ZGY}Knwx-B)kcnmAuvpCK>z2IC=wi*iM{9(S+_bOqCHZeLo6Y%0?SIFGzQD3# zS{BT+Yxqv!eZ?dfs_m>9^gcV z*ELCP(6k8bICzX0F=E7s5g!LPYy%Q%n+VclX%Pl&1at>cZP$1b;y?^5ED`95coaPh zYl@74uVpyw-fb8nWg`R+FQq9ry4 zE8igbkWX*%uMpCGda@raGSC5X2kGz{eM(%^=P=W()-ya4loa@Q&Uf&f+`i5c9m~Gt zUDiZ(n`_y#tlDEF;1EQv1BYa)LWc^Y5?Waj7Z6T|T5j3q!PjXJtH|y8>630w==a`x zkG5?IA?y{NA%uO- zr4&_F0dRhP&ey*7wXsMeMvNHoF*rIp`jHU7NfjhAWHcB#rxX=ZI1-NusYRJch#v1- zV$cYYNJ5ZQ4K!#UnPeHsOK1{hKOxT!Nxh*t4s@nP(?cF{qUEChfX*AvIU(tWSz+jX zi?y_?!pq59_=M5DYBVHddWo1kyf*6E=Wo+n;o&_5v^In zEMSXaZIi_rNQt+OiJl_bgeE6-mXJVYiriG>Sx(4X-nZ{lWEru|$yABNkoAI+8CsNF zFQ4J&om&Jv-~Glrthy!nwBT@}I6FBZpJxOKLG?qHUfjA^>~mUnIl9}$eth!zj!1ce zUG^@h^r1DH@Wa2^eVQcdDMCsB8dQu?45z`9_^9hO*8Yl7z*Z5xtJ6>{ zEi@^BVu*7I$)ig{c~IiKBX&>U^CN!L*H3a)wSINn7fGVSlkWxjMDh6H?|nbyeqI`; zx_m$9u+371Cv%+G%}4UXuQBADsr2;Rp%F&ViykKv3Pq5fWqC|zYfjETAhi)yCTbdN-r!@;RL;qcC%nMt=(?V|T(hZK zq6|0{kqShNsMM20#DxyK2^7qj=|iNAbhbeh0jWGfN}`MOeTOt2GXW(OrcG3-1`i{%NI?t-=4;I&0%iB??Vh^RT_QX#!TWhFw)*tiy3Co*sN)1UiAf(^X=z4xfP z=W$iT zz@}T#ZEc;?jzRu0r3wXuz4Mb5F5egH6y#7C5y5psUCw|v6(pU}0mt=_a-8W5>sPcg z=Qw))i{E?9fBMpO^4rgId3MbF`Vpdo%hr*IBpT+6jwtRS{F2y5LhNbcJ)HY};1P)C z%Dd6*Ot6L(QraE;{lsdbo2J<-Rd;G%@BLFbus`)1x+~=ORmCq18JRn)RBJ6E3|Xs6 zsnI6)6TlOT;<&dSH^v~PB+D|s{N*o?MH(?;#E6eU*L6RV-_y$Lq$rU(=P=HBu6_YS z$4PO)xd>Qt5*fxHqEm*DEm2y62qXd_)fBQMvpuvkuIrb%v-k|_sCZa@z+Lw@k+UVo z<{ovb@%s1hPSD2-@@dA>_e5jK3xSA|4UTRF*DgwKAHK{hWR5ae9Z< z^zUF*zoi=H+?p3e#A9S6-Jzj*uKBUr_^PyYpSlaQGu?z!$r#(r>xT@nas$u ze8|A_8Ch0P_$m6LU?vw(3dC{6zjNy^vgud+w)wlf!?%!KLRyLJN^~(JRfdgRU0yF| z001BWNkl1%A!GtXzFJ`!h=hL+Ge zthLN4MW%D|PO)ev{Oiwu1z|P!P9AX9KW5cFqLB?=N@~|IJCNAkVS9~AhH02H7c)My z_#%gQ7X0>Cf0GR>l8BtUQ=GC)%L+`S&;~C8Q4E_5nRbg}_N1&xBjGXPqcAAqB8h4` zK^l!s-LRhAx*H8Py5oBNlifHCCzuCC;@0wfuj(CZ{e63#v^&IdrG)9qK^CR(Hh|K^ z2)%Pm%!Fz>;r#UCiGB8n5&tUv#Vfh6PmP}26A9SEf7i!L}Z8{6G;!A?IC$Y z5QC-kv?F-WroY6xo}>b)O=KoVbc&9dA~| zB)|pS<^m-uCc30h8KQFp2^ZzCHkzbFDHNE9aXELo&vQdRL$Q#&^})ZS?%u-`mxBw= zJylHjc-b!YJ$W8ATnf57|yl=oI!)vUjwo)x>Y3JFpYV%&S< zz@TUTD{sF^0FL*sb58VYAmZqGBw&-^KY#a>`0go7pnm*K2D@!Q^dKIwy8Ly9?B!j$ zu!qnB4bZ~X-j(osw?9oFyhl5(=p&*qBgqf|Avc zeMgUQk-{!8p~9faoTBv&ZC}$W%St*r1g%+fDt?c=Xs|L6qhzBm2r3dqA{7SjBGCs# zjA(zzb^j`Pldis z5d+DfVjwRRc_DE~eBW?#e2SYcsr?Cvo?HzItzkWtaLLjeN5~vbCI}hIR7hbc&5WwZ zP`zf=o$yxw9h|kalNwbhqKPCC$wfh~OY&4AYQ>>E;Ip6k8T!id_W2_^C+LM@qkC#P z7I8`y3xqHn_L}v8nNu6(bWO$L%z zL|jbRWC_tDa&>pKPy6iFoDlV{U!@X7%Z9ZCp> zpf@1hR!J&|J(#En(NfnNj>L6-=H;IyO=`aR&2J(v7o@)DtPfBu>C0+pqGc_yNPP4D z*SO|dUOu`(EF!k6aj8X7kU}>Iq6PRANk}qn*u*uD^jqYGU@=8`F9n?aR zrIK6C3sgyS+V^--6XY3EI6#w>MxcjvinXYalZgzi23tlW2V4APGqP~Vp}tPS&^K#T zZppKRC*V^L+Tmg#h5{*ago+3OI!a1WLJHWW;#&4HMh5OR@37p|#6n|?!rOMp=T#n| zhpTLJ%ju#+*bTO|Wao)Kozpg++4P88w_c{l5RVI%_aCE6iAojIyaXfZWsT20jk9Pu z#YjmKo+v#+M3RuCl#_%8*&^|X*rO7ts1Pw5AG#4EMvNFS;t$;9`XSI43Fxg7*libX zyPs(XvT?Vb+h+TQZC0#g;E6?$TN~nGg(r7==oslFyvLOvP7EYvYOgF5KWg!~-^K9c zVDDaH{3-Tk;?sYNf$)_;hy&@15Fiw38;KH$tbomxcdjEyJQ2Sqje~$opiWOxdNpnk zvh06<1L7UPZwt*6o9W1KEm6a@-Ca-VpVagF;$MDnXy@GC(%E~zSN-mkzazQEzB#m0 zKno%EpGztC%HICZmi!AhN~9jMNuH7q;1x z4TUbq`#Bx25Yie!O_VK3ULsJ?7tGX*N$xRjgR8Go$(tORC0&0>3Kc0rk#fiov=x zi8y3G=X&s2PYGr8b|0un$&cmxr1nZz=N>WCJ}8fhdh1R*uGzo;&V5q1kDIMyjQhP% z+7fU<1R{yBRr`*%@*_U6b)y*4?B%{~7Km{mYC{?ha}0;y!3m4cEJ8`LKF8RM%-_oIanM}ni{Vf4oO+qxy7=cj z$lqk6TY6nnU?}5+NiV<(f=-ZS+_U$%?2l1$$*Md>7K(+xMYZ}YUwZx*kw)_FgWu(1 z^?SJTjG$U_qd5>zhlq`dP6&$VY2z91r*CoL9+ zCm)mPn|7}>Bm)nB0odHm=@T67STjFeodP zQpBwd+K7)Pes^`tvTR?ss|w$p<@1Oi;Bo!XJ*bo-&xb*1Bz;GW7%}3<1Cz8tqcEZ& z$d0u-C8fl)e}+O72qH1IIBI0dIgBrILw|0Ko;P$mNwNmwWgR! zuyM#SixQDEA|;H>$b=?YL9&J$`W8tSOxDknryQbZ)n4FNXV`j)ZPuhLAdMLo!6G7p z11HJU6hleb2JF%^6;ob)^;Jx{YRnf$=edu6wEk8O3!L_PQJ(pwnqp}MnT{Ay!XL< zE~h7`q9I93tYKp3q{dMdGY<3tGjqhX!`t-N6Q`GJTpdUbl+7vC6k`ml%O%PLv?>W+ zpsgTRCC?t*5}Agxt2>fU0x?QZVSETj@Zp@zv?YHd5hS#>BglX<3ZDW}h;g0%LqZY}r^4Pw zR`}h4jS(NY&)go;+MPS!lWt--1dB|Bln@LV>QN?=7EI?8QvZbb9W#?h{QrGUcQ)bj zO3!If?`Su|*=F)Ab4h>I47!wZk>0@sS`+>y_-yj)U? zHGSFfmi`w0wnqku4%vQQ7tx@SLir384SCFQu18K1YAU&GPWk=&zr&$DAnWINX_?Os z_}TIoS+qyIUEgKJCF}fvayd1CO80!ethkOWbpqDF;nzlMxRz^R_7A}WBI3MA2DLYCk|^ZWmytqr0@HE%;Tt|v$T01KXEv{)TZJl?%!8s0 zbGkSu69z8>E;V2xYJNmmD9+Wy9R3;im5>Kme3?7{T$I{ z9Q230dh2t{vz)ixn_TuwT<-ZmzQ?9tlZk@M;uKkRh?yWOE2>A=_@(;KQJ!U-r^meX z;tSlFyui6#@}_>B2M6!+_m+PHiDq3~keiY&^hlL4@y~FS-J%zP`g}!~YO2E=9Sc&Q zD0R-H$SF#R%)zP#Y=FMS`VLb_To^XG)ifuBz-qH1I!~UL6FC=y<|foP8k9mJlLOxu&!;|_C& zkG}!sHuFg-H8^xd5LyvQB$1dMEwHEU_mOw-gam$4_ov6okt`nZk$0nrd-4}RYKanx zB-7TDd@Be^36(UuF&GSlt+l=pD5=pp5JhBKPPkp(;S0r=dHtW=MVFeB@Q`1-9DoHO5D-@YYWQ8S{lF}Vu zLyN`Hsr#7fn78|ToG&XT;U&J3{|d^l_}%zxJmfn>U1G=(%HW7>N>F7+-sUK;&@yry zzs_&*4l!yJFYucDGSaQdR|||Q33^2}uc;@AE;}S;1*He!ESJ89*poCU9kA-0PCmkA ziK)uDd;C5{yiMLd$7|RB1WpUy>c2{i-=hf|@*zM4D-!{baYl*)ks>NdQdr=O0do(p zJSpXaANYt7BS!p$Vm_bKbsYfH>6DZbecvO5z!*c*GzcM>OeWNI4Y2>XX&Q_%IOp)* zljk`_QDCjbdrwgmIOoP9j~FrH6N3&RV2s%lmfm}`)>v!*NQ%mxJ@jlgW4&GjgXOVv zjy%uNT61=G#(X|!wOaAaGtaPGE|F4VjG=8?rqd~To^yVFz8@f)rU9PhhLqqU}OTPBkU)>@jTVX;`STrSD;oP&b{PESvn zPN#V9>HD79Y_@-IAp|ZiE;u+ipePC+KYq+&v7jgl&d<-8OeXBEbzRp?r&HRt-M{y$ zs&LMcQrf>4V+>Nt{X}Mrp)5<$iB#v{I#4$c zs3&ie9W^A?AtnWNcS$sfm$Q>op3g`R=3thi|?4RnlTX zGMWp2MwmH5rKtOk)&Ox<FM~19U~xLKb|ctk z^z0VzPwa1_jLa4jiiu&}41qjC4r@!X%laK}p-<={NaQyED9DIcmLLbKXA=zasvrA! zVB;eY2P=Dc%D!G~mFYfsLP%r^tdFE5n3r>UQSZmWNcC6$Q`kO3iTv}G_zFNdJs z+~^g-1=?4UfQVkTp`}-gvh2PhIH9=cYkQZ{*ItX|mF`A^12c_7f`ln^NF`O3s#9m$ zXHVbsPWO*}_D&@P5;`<}WmFtp(``a<9o*f6yF+k?puq{Q!QF!dcZb2<-QC@T1h?Ss z&h0$!{mxqaYi3QK>9c#+u3c41o2Kszr43UhbyGJP=bl}zT~p8eiZh#|DRR!{V6sG> zP74(r(JWG7d>K43SgDK|u}^~;Ka6K{|BN(y?zpgvc3-c`c4ll{U{D_gGxrJnvJZ%+ zthtfG+otc;h`uJGCNU3H`!4$Pma>9dl9Nz1WqKBZ4#WOO$uZhb;j)x3@QvZ}g zSXy7-yV&Zpwz0`=pqg?#YRwGqQXYLwd-jJyz~WClpniq|E(7M!BL<7AfBOcYkK1`@ z?!Otn%3%!+93rs0?vuds`pz~8bWI89*+eC*+_}Ud?bp!&-?pl&iKi7tNRTHeU%LhU z`Ob&VlU|s!a!OW^PXoVv%DL|8;_6z|Rlk5^G+c{l)z!MDSGTmC+Rd{wS_g61-UX&yE*Ssqoqv_$V67yPYqsrWPYh8AjhL|Ro%9^WF_i430pnPf zq_O(L_(HI~!?*)GsRfbPC_MgW5p?EQ0)-bD&Et#oj1n%B; zqem#yL#Wegnhw)MC7`A_$t=IgKGcMMnZ}S;O+s(C{^YZg6lk`V#Uq4$fn9h`^<%7Y z!a{5jT!Gcs&@2h!<*>%dVKEYxIR#LbCAdC9?q@u5341TyHpNFsh#-z6okm!{dn{^* z1_sT^ab>KGDDb)}}k z!T*wnP;l`PgP6d^j)dS>08#QHX=buoQ-cIN`4__WrnAON0O zV?14pc8SMeF7u&`l(j7^;v-)4nFPz))2};USeEG>?~>d(pcBue3ZE2{n=;951bdWj|!>Qfbh8XG+=mso3WG0Tm5~MW>uV3P}c)Rtavn zr~Mm7%MnYQcLX?%mREt)Kc|L6U41U9g_SajO@zM0E4!3KuQApVw*=AI_+kRteXsfX z1~~*a?qeX~tP`&g19VzuX9&B@A+{@OEnKPD68`;+ba*SxA?1(Nw+)TM0q4el=TSdF z*@>5Mo4c^|GeDoby)(F_x!*Pe2zVRK7KbdgDJqMP`9!f z)%tgsi{hvSPI+BUaA1%Lve#@J_r`INiTH;X7J#YcGd4}J%B(nudyEsQ;kS=dzJfw` zMnZ$~Tx;ynk}07FQ-c%J3B&0M4bD9#8eloeNZ`hqqRaToaJ? zuM!f7089-)lQo;06qgV75LC7X zc)Xw3*FBMm1z$pnLwmk6Z}jYf(}|l>MFDyYV7A?)QW7Qb9oE)#7Zw)}Z#`7i2JE=O z@8fJWo>Wf0ltUga*2Lbc*!2H^?i-3^^jfTm$>RsYoIm_^0TGn@6{a|RrmU6basyGs zq=^PgZxH=$yQJCkexpg|6|t-zDPd>7XHZq5%qqhamm3HO1=A&UhGujAN%KnkQ73&W z(Qhw-fg6EeQ_y5DLTW6N?_fAX1*?cE;r90;mP{%X4K2Sr-T%@J-%0qZQQ9PQyqjMf z3t6m`+FS_q{H2`S&zmsy)m$UAT;cIFt^JE-o)qJdWGH8ypS9fQ)s=(IerkA_;w0n0 zsnKb{@EDanXd$@~xt1}9^;CxJxDJbZrw^=lt3)ve7Kanv+N|>e)>lArMH{C$6Za3(e>ek zwGWO+w|n$G1U8f^UaX7Zs!y~D_c1t)6nlSCrS^14X8ZrV03S>v`Z$o>`6J8OT8&Q- zB7)@h>rK*^H7qUTKfy!vMdwSng+C|XSPZ*~2~pn)IFYz5?u~BmVN@*chtxx1{Yy)SRl~_} z?X4Y%(_iHmW#y)wMqKfhyC39zP7O>s=X;?pZbwjQDpKLtnIu}p2ZNOlFe zq|IT{>3D64vyVjqE>+*}*8cMxRO>zcXd+@DkZ~loY1)NfZ*tg@M13L!>!u_g9b_$? zR6e!Eett#ZWh$I2QCqyB^A{`zHdC>-hTb6AWDt|A6k^k2R*}9!{0=XfC|pn!zL;g^b>f6w_AKIoOXyXcg8(pC|z~tbeJBbgxcU(YT6t1N4z2_WHsm6s5P{Z zb^1rv*vyH{G)uq?ZsQsxAw40`w~jH@GH(uz*s`2pwwWbzwNE@#G3x=cCh}qg2i-ja zFHib_BX~MTJn#G0Xj-+O*5byR;mhtiM$D6O5}-J|JXd=gSekZoSf!v3?anu~CQ(j| zr0RIb(JaWos8FX|Y4k`$1~gt(XK{2Hsgvz(ZQukhGRV(ug8Q__j9F9h=js;#Miys+ zD;;Nd-f@2wVaET-4~EFikFK)WA2`sQTwMFQU7ntv*DcHR@{WyqodCQ+DMBe~J#^g6 z%JKjh=lid z@!J-$!)V6O*7qi@hkl3V=tZ73NsrK?i)aCz!Ko+TXsQH{Jfr= z8b^^sKlW%tMG85|(|+$5%QJQT_&%}SU~p8N8QNX96rTD;KszNpaYbk*YCUMU?cZ+b z_k{-w7CDeN_Qy18sV`5h!H!Xt5fwuIJIy2Qd~q2Tq{N=*P~ZmWktwjStSkqN|m2QY!6~9EW_z zyK;+&!jBs^Y?pipq^ZQM8437YfEdQh2FpR#OQJN4HCMpV`<6&(I4ci%!1wKOz_*YD=HeUHL1 zA{iF@DPHPN2UHAHx+7-Q%+o7G58CbNEm3+`52R!{9V>w#OyBpjCH;lA1 zyU4NeI;Doax~;jB5kV?{nQy8->1Q6{KHk3!x6NI7jqAS`b5H4Xvq@k(4D`tIWDxE6 zI7UPr*sl`q1mtz?2|IJmJVF!WL9&#Rqt^C&C|3W-l``-a1HlIm(kL<@DQH6cTB0y^ zRyZ+LnfPEH7qN14wb?11*S&_HfcEM;h9|mUKmz|%dLCM>jP>?e27AoJje!5 z_jBRprb<9HILjIgKo6*v<058kO0VPGDS>WP|YYXzq}RZ24|c@u&aU%TUrdeQ*iKGlBgKHehZ zMLZrRzqIV;5vsQt4sN&;#3|p+DtrmgmlzJ#4H0olf%BFn{n3Ueyt`gp8^U)Y{P?cC z#;7~epXWrP;i$STkcmcI{9@)=vURSY-;WV_Sf6Wu*Ys;k>%eM>C*M6lSjSk`pBF_z z@3Mkue@Y>v2AXb0qrwG!Q4;6rTi`r?V@|%a-K=g;VepP)N||zKZGl0T|8kboL5>hc zKi6F7zoY~oZ11y7P7f6edqC37TaV#46at+$h@+j81|D`U9)gz+9QNqvB{dI-NE;Au z`bW^TTi4FWXXVX~|H{xZHgEd7Q|@pq>WI$C4YgTSwm|O_0FZV$fIZdb?b)%;AF3)N zow@%`fj0oeo0*;b7F+kbBk=&k>pX7j4A*}d(BIA@ex+H|_Z2YFj4Py_?lZfR-Dm-2+Pd$_6Xf{zLryy8W3?lQ=`Mm)Y*A=T~xC*0;XWyia0Z0d;Ic!=ES z=7~XDKE+zp^JL&!wfn^6`Dg53z?s~g#cdB!!LhLHPTz0Golg_yzVW4PEfb;BBCWQz zmep1Eo7%v4=I`F#-s>Ov9VPozN%Xa~jet=0Y`LN|te~L4J>p(2L|@^a1_<4AMF#BUTzFq-wToa8BJwDc{XrTv8u@T%x|E4uZ3gFS!YV|b)H zh@%gcY1mqfL+*G$u89o$#gU|d9#hI&VnR}Sy|7S`%*#I*gc9U08{yU-6ZU}uWI|O* zNc)0tYzcZqFqFmOXTs3(D~pd<8qn*n7)5_2q|fa}#U9S}L(zmI{u~~vw?+^MJycNk zkd;+!HC?$$4TO`>7C|cxB=0e@l8njxl07UDqGRY3>6p|US1tk5d^M~_Q}uWY8@~O zC*vl935#4mN0R$Gud8x*#bKlU>| z{CyA{L8jkVP!VbnJNF^+`j>81ITZxL6I#+hKe609mB6FcLJX+O&pJNyCad0K0x7+* zMLazpCk-M}r;fAEYM;G6$!?;SKu5oCJ05+Ho`p^5=967IH_GUQ&RAFM--(DbYvaS_ ze@z+S6`FC}JlPLt_Ey!4=j0i+!qYWUtLqXLjxFOfKqTkuEl8TKY3^q&WpLJwcOh$U z`kf;pJ!}+O3;)fWs&KpKNmzYS*N}D9Fxx2q$o|+nOAJmH1AzjoWrL5P-zjg&slCZ> z2q!p>R;e7Mpv=Ls&ZF+Zf=$SuwZLpprnA#?g&4$Su7#C_kbo7j7GroSsDKhx$0I0e zMqR|b5(1La6|;j*6;^?=PK<9w3<-7ePk<}LqM0{j$FYCkol{kCGDPcu6k@8t{N~ypOu4rVkJs)rb?r?L)rA~MuLrnq~p$nj38=5b$=rt~!ff=8f z-;^io!!?79%jONu%z}a73!orcij+X)woiQQ(uN^^84@<0+EQwPm!K69i-1M%cH}nO zdv5JIIy;N@P1l)+Yr~7p)_qL-z=;5c?(Ok*q)9h2lF_G{r&s5<&*nD4?h9&<$7IXyJF?XSh zyy#?QOP_c!!wdh6QAdb}-oGfjNzrf?!Jcpr}f#*GaqrvC`DsKVW~imc+5RTqeth#4W@xJW*Yuf`^1y(6Tfd z)=I0fZx#rK3zN2#LLZQ6k#mh9Ly$I`%{k<@UIl?gf*^H0z%>u$!Non1kl5_D#36pDHcMufg&+vU=cL* z4}@CWAA1zAqXayJkY|k&H(XDjyt`I>x;D4fyEg4pibg(2Nyk8(BTe!VM3MA%?j*k= zeKKqF#^%?|Pk`jYTo1UO>k2{)#6c#|+P{l@mOkd}hamlOLj9q~iTuFnt7lqPpJA8m zt&-A|nUElF;mgUjZ&G(4hU5L-O`1mYA8h`gi%Y^j;)K(6`&QU_x^mX&v%Fc+4Q$wU zpr79bO3Y`_2-6A+@f4X0Nh2|335(@}ls=+sTid1ZX3L1{xg1c8oh<*Ls>$Z(HZ1xq zEgl(@){g+@{Oy5KMi2#i-X>Qhg+&Yz@(V;Dqe0>i+VVyKLv9Tt>D0RhT4`_e21rjZ ziFxC4|HyJC_feZG_x~xxWCEY5pS52 zl(ygc*FhkIBQ|pjY47Oq^0-n_*bLU<#-(+>D7}%M1u-ho>`Su2kYB8osOvMz0^p02 zk*RGb`L9T!av`OGOPPIa3!TXwm&irw_e#z3{_)fFVv&Fb@AbM3PH*!#Zk3?rP#i8V zwd~{+lpPK%v0){O{wE>1+7b-8o!d`N$Xhwu%(>KG#(a zV+>7pK+rWI-nnAim9aCVczyo1)|FFfl}oezbX>LX*}3oOwu8SRmAUVB{#YmU%(i}= zd4JI|5N08ZME)T(+tr_SHs&K&{F zySuw<-ui_PkfgsE=U&wDBY}$mJgquT2>}273xSb4dgHlcV<$J9QA8$`WiLyN|3#*A zZ#)BEe1^aE$pj!+{FaZAwqE4tZbN)-*XbMME9-ZhKF>|Q=`-eHW%JvcJpt_U0U&>y zCRyD@N0wC_Q2>u<;FFS*f$W4MjE$NaKn5Ll+po6X~J5VbugeT(q=6iKHwli zI|{dye&)?UR>G+1=$HT)*UR9ybKi_DyW!Y8N!;^uyEM3=x}Z=^l$!fDxO;4Rv31~A zpnq8Y`*H<;RXFrlb`eyTz!$Y4p)cTPoqQu2poT^LMJk}4rO^Tvn2btcgXVadV>X9D ziEq*~?1{%zoRBBQS$rGv)iZ?L7;mRTgfEB-4U=7oFXt;#tZF_M8u8YEla2CoTrY=P z;&)LISWIC*On5qWW$AWE)FF+z@46(AKgn_{948~EcBG!YMmzWAoa1D8HNr^PFeYN8 zM4OVgJ_XX`mRR{K4NHqC5^m$teVaKhcX&cDgB9MsbTjxUi%3(%Jc&Aln&Y1jrgGzk z6El2r)RbM7IYe=7d3~GuSY4o)mjw9sBtDA^i#Ag8G_?{0Y&AC{R8i-52I0^yJMc<2 z2drEu^?%6}4uaN25Q}Ffz}!7epou(u!V++h(`JENS#{hd9$^}7@%4;XHI9KAoPe$1 zC_Ch}hfBm1`z#DH%IJX#Rz<^wV8rPk*TQ|NSDZafcMAZA5zZPFhz6Em>_2RusWDMJ z_Y}_!kzm)Z`SYk;ej_Omllh6c>EGwkMtn~2pxpb1?Cf!bv>@LesTZ0cjzYTHVlXRk$v$4QQ5|Q=#Ks5ravX@v@&U5-#o9rWsFY0AX7@T zPc-WF%U?*qDbExj)^?~fX&DfYOiegC#px_v`Zd=fC_W(ZzSS;d>1?bi?ns=mm6tyVa}LQ+@F$2=K#ED& z0}`GRjd?TO55b>()c)hsU!wa2*BR@C;!n7YVJtbhVS|Ci!ify|@h4{yF{fC$=%5DC zdDPIa#Tte>Vt+8o^R0AhosedWBAz^NUa45q;C~y&k&=ZZ4XGY-Y7=~F-F<^%cNbAn z3=xkWTc{!-D8{j|Wn+ZNFO779Fc}X*_2EaLM-`qbN1p!tlxLu$5O;$cRdW4SCky5Ra98CS35@K(mZr;c*W>HChBkH zA~5YS*t#S5KE8ErZ@jJOOOQO)_}=CbXb25gWVHwJTh%l)h-Wr5pEjkVCH?80pH6IqHKWxGX4HLi45MTe|YXAB7ugO`*y&?}SIkgFF= zUr$KW`{2q$)%mL}fsnmF0#mbJ*5jYW>z(&!MZ4{Oxb-KiuF2=Om#(@+;+T9E$tk|9 zEVudS>(Os7Gyv~YXlvUT<8VGfh9TEF1;3xd_=ac;xg)%;2{5)FKaQ!UF?YY*7Y>s4iqR9Zk*>e?78~vyFN^8yvW;hy}DfS?<3i|eIkAwmTZ1Ldv4i{ zLvUL=)*C{3zd)&LZya2ooZN=j`N!qniS4{ERWJ+!HEK^rnZ9DUs+0z2$4`e~kOkNL z62r}xy_oo1VVx)^hl4>GdZY{|NiKn55Rnt4#v_BbP0=%iYI*{P-o1F>0x04W=1>M& z>@IgvR|G#GC$z?fIFD6orSO zMMV1+Br?7413hD5T`iS2T+p-pE1T-KGMO&EzO0CWhWz5l@W?S^%lJ%3_sD?_=W51H zAFj)C(d9Clw77DSF{Fg1!K`zXjmQiC`=uXIb-`bM9DS%!j?nr9JyOA~L>@pvN~!WA>54=Bl{e3HJW%(n zQgFhT<(wox$+K?7JTND*Zm9Gn z*;i9?g;Jx4-`~>^sXUx+(K;+~)u?|LkV*wCK*0*1v{B^9pJ~(23wWR~*souXxou&- zJ6O^zJxZPtZ;Ze_e=u2y`2~qf0vX*e#}xz>R4X9nM*|t?#9l}N8y-zp?r*Qc;(~JZ z+mCF69_2ph~f( zj?cZ$vU`geZqm10UM_r_WB2aA1ZLWRMPY?8yl)rH{+G=2uUdF@O@d}#VfMZQ?_NH2 zH7uA{NXG@{((IMA11SO^2ViY&4cIl3^*m_5>A6!9KTQX_&84ridw<*#AbvfNYbGqo0(J=1}$ni{v_pT4?$uCSV2hpAW?>AX*wtAOg-!5{o zJ5o@5ANp3^_tyvnJQ(lST!nTn*`c>8`Of$LO!**ZJq;<=)XnYl>D?HD5mxU?6t7=5 zd_PsajieWs{z`7&rKG`}VaHTTkaJCc-jjYeASxTW4|RFrlo!Pi=ic9oTKWT#ln}=* z|L4!2tpX-*TH@!Wp@(i5!ETh7ZWR6(?-=gm$LRM@T~DZ;&RMq98_g8|8~^ZxyBvhO2{jD_KTp!%ZPBMt;Q7_QCh%FQaEpUc^T~s zHWR!~Ew8A!yld*p077t~-ALP)MX>MNBe3WH3@u5E3rm8Iri?GXJe{if*U7wR0KEiW zl3B!CP!vg1;77=!*Zq;j!G5Lhbp#-1ZAg@aObuhPM)~YM%VXw_VFOo1hsDdblG_-i z`bY~X5i49`SDe@IPR%sg-Mhuv^HqRfx(@XJ|D(4<#5A zhohfVIYBmB^x+(g+MZPMx>uVuOmBPZl5hZrl_BwE_{ z;tEn3BV%o}&%(ST=8L*XntxXt!b^C6DhfT|^8a+xtvMymg-5s6iEq%(C+iW9Q^MJn z35dz$MxV=)ge1K85mVoB=!d|6%Hq{a+epY5n6q!7S8;MQw+6g<3 z?Fv*Bhj=cb(if3k`4=%<8{^s*WfXq=>Yzn;MQIo~UD zkKalK1BzjuJZi^+z8(p%QAJVOW6iN61oxq%dlM&mRKHu7eCS{rmbdb~lpB(#rR)io zHAf9d8SqM=vXqvQRc2fg64A9R#}eT(_1V z(+X$Vv(kIHU9YRJXRiuRr@WP?LI*Tl3p~JE0^~rsql&^uwN%tFCtHRv2g7r}zzWAv zIHKwSkvKG%ufMvyWTtm?`pbsD%;MsYsVOkjEn+2&%OQh-*0_^T)^kH zwzg}1b5GB7`myHy%xBS`{S6tLYe}g?jE?#KI9NTkpkYAD3wWpCRtdB3QUs6$E5Y?!)qHo zYqJ+&YG2;gW6q1UIKl9FJk=fY#!zzOpS{uR^*VWk52uxoTgRv`<#H(-Os1Ard`H2W zlWDI0S4pm*I<_DY-n>;KmPJ8xk2n%*zf@D8t>LH^$QbDnQ~?p$1W7qO%Q>l$TT4~8TrWW<<{lPFlwa&pV-S(R zVVpL5!px8#iHgf!n*-;aU>zba$1it?xgVECgf`&F_+oms#xZL@`e`I1!Z}NW?=y!X z!7WSg46+q$UUg(19MG(O%Q+IS-~qmtJ&&FaoKUQxwERP>f&iBnk?IqbLomHe=nyW$ z4AmUm4%??$7nzLtm&;9*8Kqu{GDUJyG|I&E>Vyo@8UvmweFf*)8ZE+2@oya=Q4>6W zgeEhtY>cscVM~`m?A)lsUN9_JINA^~!(YCT=9A$l?k@KWlYvPVRALz*gSkG2rYVSd ze_<_iUeX_j8(FQUiyf9M?>S|P%b*+=;B|38y=>nsr<4Kzn3nMax!D#~N}gX1D(v(H zh(Xr8KNL*WLA^TywxTa;oHV4<_WmUPA3E>EEW}jiArIjux4gyB%(xE=bI<2A+%ODy zp)+6KlHVbTV%;_eR8MLba@(oMpkZVrU}-M~6`zxW-gE6$-8;D5vB#$nP!yYYT<>1$ zY=<@1mW8S?^xQ^`S><2s;_`<>OAiebZ}14&IW6s$<#d5Qj$?;-Qr&0{!WnLyCvc5B zZ24;uuIu;2fVQvW)$^EO>A!?fFOOg;*_LROVPe(ZH|joi5_v~65JGPg`w-!A!i__? z6&7A)$ew0*U*l=dFx9;DGZ8C5niv=8Z#aPXT))HkxaG{Lcv4-Ca&bEKm|WZw=y}!^ zkK_oQEOVu0P;RsdX}`!?EF_tpk_6Gw*8B9}P|5d1-`=>YvN|fdQY5|LV3;~ftZ7_j zzyl++RJaySa{}kG3!1~96$9Z$V!;;)P<=`GyY%@hk8qU4BdUd}(aVQLS$7hg2*2rx z5V2oX6fIGg4pw+UKafSFzQE=qOL35*0qGdns$$V@@l4Z(Y&+^DSn5!^fv4(V4x_lg z7P+!)Kl@GV(@je8#%sHO!KF6Vlc!)Had2G9L@V)-SjhTArPByDc)}Y;p1)pO-&r)R z^xKaQ4nqIyP*qfUJfxeI&d@w5IOM6ARwze>UfvLGB?wD8j%{YfVJ#g8%#YWRd)1PV zk)C6}#%tB90_rG81G{?yU}(qC_6Y`Y+V9OP_N4(p6{@U01E()`V2TUF8k{k{d2kE< z2f*KZgrL~us~3-Jnwo+^{ypEnq!q%FGG9;3MmOLt#hWnj{*c#PFt(UnSYS7~m+so8 z3-ebfVr#|I#Et!zE|+JU!Ti*)- zkUqO!#?l{SiQRFVRmBF#N)S~KCd*jLXO1tY;yZ!alcBi82jnn7s-A$khXoUz+ zYYi;JNAd8&L!Tl7G9MbGpNgT&s>_^jq`Ip{UYRJ^|FSIGM)3G@_rq!%b=He z{f;cI&P#pAIe9MoTgS{k(IMhZKqdwAyMy(r`p(Wc#aXBzgF!zRyWX7Jw-evPJkLAQ zt*SbbMvVK-cS}nBCniWGqlutsd7Q5(_Q9@1r!JFqS>BkgYtArA`EDb!dcEiEJ5BBz z&+9|?KIiwfEiEJK>w(zqn^01;Er8nVc3Y-DWTpSC1?<4LOZkl(d0_srL4?8SrZ99{ zTXY+_9pK0T5cjmM$${92kIEQ%>yyA5DV(kZy0r4&VXA5>ULBuJ9`;EG#dl63es7dz z=VB*ubX(yzk_jjqLz?F{npAY^wDxrLK`c^4n(#X`1J?FS4K=ddv|(I3Gy_VR!u}G8 z;XqZ%hv6Eo)WL)xUXdtFivk{kDuSsDPM>Zg29DV=Y2vigG0yPV@CB@)~A_YDq!=a4%Es5J5p+y zowOk&d(5k4tJVzI*Zqr~V+)w$-;HwA$}*;h z4g`IbF$(N+4U_8tCd*VgrU5St>=vA=alb0pr_%tbKI^P#{wM50d@qu$dn$P#_&%Ox= ztBAiLfxUI`yZJt0+EVpC7Y<5eO{5Vw-Yll9(=jDleC_FE_3Ui(EJz$qo`X~dgN5a` z*bt2hBwVyerj+KO5wlMlzZJ-SO0vRG{v#V}snj&#R#TukaM|IZ1FhxQJkqm#@P}c8 zPdEnDOw|Je3;|we6jAt`_OuNu%>#V*+y5x-SS*& zse-%!t4qK*8x4C1UgSrX8Kzv8*mk8IKQy@zR3n0~O22V}V|Lj>XJoI15lJP2vP08o zV9}In@V^Gyq@7h(9^om>uyzzv+I{SNrzuRHb3@&;ChKrl-Jt z2lzgA9^!{loN>@$s=d~!3DBYruL>0Lj0i1I&;FavNKD#aN+;?jib|IKd0R8ACQt^} zdrg!E`_L1ID{r`Gf*`>j6huNU3`2_*!`U~_I7&mKqw{GHZ`Dg<(S*^MjGWFxV_vuz zEQ2$v8By}v%KGHtR63+dGuMis>8{!jc)O7%%C{Vs}y*Kgu z*x8?i1hFqGV*YxW{Xk2i0_1-^C6v|m{@k@cz~sa7UtmA4|EfksO)ZIw3w-q(kIUki zrB-J;>A0)ot~YwUmu+lEAe{Cm!NC;QZnQS=@yWcNy!b`^Lh_33S}fw;07=zkt@et4+TAmpp&@0c@m(f8qVuDsRWPonx@V!$VxRS^K|)HJhY;s7u^up>S{~1D%4C?+W=3pwyhCvM z>ytFk|NJ7zlh!G7A@*exQne25b2$FjoH20J!2pZ=*3L0pLJaI7+t*KVc7CDWfmU!~ zAE@gBwMZi=>v#sa>dVT+#7C{!$G9^5jja>GfpW6!csUdzaP)lu&+y`2=j5FsGN-7L6PyWVSBkJ@7KL2MXNIJ@wxvHE;l1f*%WK_^9gExd zMa@6{3N2*`^gFzf^xkXC!=>)$mKtf4glN(Bwl;T)nyL^8eb@EEnWBHghJC=k=iTcI z#!;nw{n;Z;XsNY@k)~yO;YdsgRgxzSju>{N$tO+lwzjmN`=BPJxS>R$+s9||5jww#$V7*#!DwZ{K}_vYQ$C!^M)Lh<9CKw#Lvhx z>?0bQ>y^kP5ZJ(9-f*jv_E)Sq0WH$=tOaJsUTW?JhA5c=P8bBxK=aXtdCQs~E1aeC zpI?36VTiht`nYfq?Q~t)10G`*iF=S6rzu@)IM{Ejk zwSNsz^Jv#(3Rr6c&s^H_EY{B@JM_$$aUwi=thSqvTmQkIm(RarAS3gpn6FngcYM3l zzUnk*hP=$~+H%p0ASpf##Oy!^>xk$@iMjHq9lK%DboYm?V9hQcfnZ{v zhhh>taE|dSGFp;$;9U0&ru{nOoI=52lJ}UNe~LVe zjPu8G|H})%4DI^snX4lpsX884G+p&#cgEDz)MSN44!a`6N1H(9CE!7En`ufA49QK7 zPit!CD3?szG>z0op!i$_1m*jDQ(JUPW;BNTn9fEVu=M#^QFmHMdo{rA zgDEM!^YObuikli%S|VIQSJYZ*1cKgWwn;39rv)V4?2i&*+3 z`ZS7tPGa%-1%kG>t5?)QLHjw*02_I{Csl-_um?{p8I`w#H`^T2K1e$R4rPbBKYO6M zpRko=5;qnmR)nMY*huq%r=Bh8*SHhv8FLvj&p1e7#A1LhtB!kRdlR^Km8>m{ydP$A91A(49w`fo3^ykY3HFU_jp&zUg?USA57bF%Ip z_D%#4YXdRcBCZg5Pjd2m<&T<|B|nGmz`}o$3LnUx(84>vKOIeC^82@Sz{-MEPYD=w zMk}Fc8DYW6hsoSmZnpA{PnfTlcl07On*tBPho3B|6!2*Xx6wwSH5AaX5dq@(XAK7D&>Z7j zhG+?fbM5M^vtg}el#63nvH180H7oSn(tZJXN=v)#!XMUn8{Oab)DN(r328t)>Ts;- zO8pQUWvJO9Ff36q%`IeXqS{`HEh(zm&ci8Oq33Eevp7GJm1eiO(Tvz7cBQ^4Z{~>$ z7dj;1e%)n^!sTr!?j1UgCQa=3faAny=GHJ6sp!FpL}vf7oc~#LUT528yfXM~D3(Z~ zXNQwG*x4{{@?(AcrW-A9^cOxz1hH+X*A+{}7hN;DSZ{VFgZ<+Xh+q)s| z{_ef)@`ud+)M&0Uw-R-1i z=<45#_{U1)Yj4*Zk=y1+!RJ3y4qHLkwH9+!3Cg?fQ6T?dB99RIv6R%*9vsoCMe;G$ z@&?t5`Iyv!7xVwe{}+?SmZ^9-%e<$FnE_GofkS$jJ$P zQKrY|0pSVOaHFH!r)oW(gSczLCh)n2z`nG|kMhY>v&@l9fi_%XVl#L5%OPwZn1CMh zBURdg-CYWFbaVpWml?0kPrgG+l7y2Z)LDqkwOqIguRxt^f_yqBP#4#-9Y)s-{J8@-i;BBQJy`%{qJ)CJc#(O2>Aklzw~eI+a@#xOAS`o#|stY6F#kcXGB(?=WzlO z9E=}NS{X40gb_|Ksi>&_OZ4mu`Oc@^Bvj@iwEhb@Tbft$tPWV|E^Dmxq zJbC?qBgFz9JyZ}b@|_HA4PudCC*QX#KFyB54f_AZ5z1FWCy6h96GnU4NKS=p5ggpT zq||*f;r8%aJ^b(WPalyJwRy^FBlB*Qz&t)wvH{|qCXJ3mo!X%&(ua>_8sEO!m#NO< zjF1%2u`1`3++YqhMsI(k%91QMv^jX;KzQXzuvDf19SW+TJ1-+X%x+_sq&Gs~@ zuGfyq{{Bl*vbXm%^yg4O3Jvji1dahH8WfSjFkZ#-PLuIL3HBHw5BCeT4vRX(KwOBv#h0^JG#imiOZ>;}PV1MV888R*oNw zpoyOTT(q|cvhU9(CKZ+aVF>PI3l4xd-2@zVdXXY+=91)**{E$K7#UhpM@LyDOVgxtsU9fy3qGkPhE-2;z5=a-o`v_(W#k&hv1rm@Zw>_^N+?V~Wg z>qhJ-g%EU={wl3@mUwN;LC<1yf*fUCzhA$s4Q6O+RPb*Kg1GD-~hX3gKacU!&td^ z90>+3cKZJC;6fCQV7Ynr2G03#Z3K{)`28D0Hhj$MWrypMPO-~xK5=VWs_u_55U^Uk zzc5uV7{ZTTIfNe`T5NMelgP8`EDogQOx!Mi5C5kCc8`xE^0}OB0tZ$=Gs%A4eZK|( zULfzX)Z$3(d4IAKF?T&v?~L;+-y&=wO{-!Ma2NsX2t%BuHkWgd83z&8|N9L=xe1b) z=CAW-@+~bZfwTuAe0+e9g$6IcUKA;%0Gq1UD6HG-6`D- z(jg_%E!`>I-Q7rsG}7G&2uMgb(o$0IHNXG!vKDL22WAFt<~sL2d+)OkES`SPTBou`2e|30rPJ0Y-{?K)Px?Xgi6nIXKAu>Pr%`=G; zN{xs>#Kpq{=o``~Kb(G#vk=@Sz&9z=V6a_jj?uGg3qfY>KwrNlP5FH>#M6aAPpu~J zx6Q+{cR9`qkoM6v|C1l-;=@JiM#5a#3)Zob&B@4-r>(7}z!RST1)gO!NU}Mu`5p^T z>J$HYWoipx=j$@`u`8cnUP9Vc5M(Qf&OO7B3Z3bmaRYx;eC&_U0qo1}Go_8KeF14_vHw9JA zf)25qoo-l)R+xd%BuJ3(L+spm&kmwe<~G5IsTc(kan`0ReAR%qSVfO3w%uzfYlJyM z6E26Uu*jiuC5Tm?5&U@F~Yib{AE*zsN zoJ6!hEcPCa-j+#KoYhw&MMPx7fXZJ{cOv)A8(1gZ|g^agHtzEwXfpH z`>+C~d56vLHSKSYV!4*h--htovwOIv0GVo@h>Rb>IHZ-#&|j4cu%Eb~rW41Aj{{ja zwBEySTi};CM!x!_IU+|F7(Jowu= zb6Wo+^Uo`moD?a3gHQ)5yMi8u;Jl<@p}mX}I;7^iEQC1*F;>%#^!%)nkqJXnv4CEr zfK(_eV*SH>CyQUsn3$e*8jQsS4k)^W&BUI>CrWuZ`>!HSjIVob&6%Lk`+6NeHsagi z{xub2J2iR=7W+2x1m6|8|5ID;1A9$x3^apRX3yshUHEbnCmhNuehbh8v-r4>V{W?c*JqXSEHF^js45JuX%p|4)%u~qt70SoJmMYN% z;8kQ3c%Jzxi)!@XURC}LGbze-imkUHHfI_~rvoj)e zksw~L24?1{A#C88LLBzVe-KOF4?9_H!128*w(MevAgvrGL#|AT>VC7HJuE%%b~I<1 zR)x>~)CvR^K3R2xN?qj5;#NIH==WG3@@f5+00r(9Wz;SkiYE{+CXo%!p@xQr4sIVb z7;t>nhjkS?4fcWBZaP=0nBE6Q`owehABXH8;qVMR$aD8&+)7^;ZO5>8Y~j>yBr34< z>MAtpQcpXBkw>W9tL%N1a*gzyoDzdtPGR9G2!I5nM$NJC5zXq^ZANCM*Mv_jX~-F_ zzrVKXtm|)8a&|sGx!SbzqYp0_x%*qZsQY>T!Vr5FtLLbK^!F!g_^-}yEwm@V2OyDZ zbDQ*q_dDs@@Xi1}xaRz4p2*U%^#9)rFztOn(x?Uq$vI_#3_!Dl`2+WU;gap;KM_x6 zNYgIcq-*Btn!;GykqC&5^Mp8`V8&0k{4Cv%PJ8?NZ5KmCIzWN)@gb(ChVT^ZLnyQn zDZs_#LkVGJJr){r2mf6k>*(l^qe$F<=11gtTLdI$po=@4w(VcmxOYY|jhDS6Y(&Lv z5t&#P{?^I@`@b%p3F@Pm1=1%w3VLHVY5zD{r+;?A>Ulky^isJ+bJ>D89szM*nZ%3f zjDC2EQm)Eo;&)6L5o0{FG?%t9dy*(3;f9GdTHuoX&VAyyxb9h!qJ%jTQf<#0$}O?1)IJ{FkY%p_dxIEmJ%Y4ENln_UqPqtN2|4EL+YXF@Ul z8ChE*5p0m*9w!;?Ma-GqX)FHkYlk*Qhz^y1j6g|HHUQl)YI8r9(GlH4D#c;UqQ+6g z+xymedP9jJ2TqS+_~K`^vW!jZ?dDsihw(=lY|?7HueVsB4&O#Ax}@ zK6FLYP;)V0!N7raLIkEBI!O@`R$7{QgKHcW`}t5|ac;uV39t`^zwhMLoPDzU2EPXE z-$i?3lq+SJ@l@yxI&zg(=x|>(-d3~yUK*oMvT$hkBSB+X@9*49lePX_%oN_2Jb1)m zg-$LNNGd0(B|~wD>ukI3E}-@I5H|{8u~!<&G~9wwVmPzU*ev!NVM<$Th@^GeD!ZhC zl99@Q;CwoyG#>f;>-&051)STg@_=+VGiX6r&lY^aIOci@#YKkH_ zf5tLDnF0X{jL$UH`ZBw(`|{-OI|8oHdC4rT-t)>_aC$pd;B*7b)>zotp;mJP353{r zf*tY=I77v%s;Ui7651RW%v#`8(FO#eBXNVxBFoy#^KFCkV!ubtPB50z1|$JtnAjNw z5?BN5gz(;~4sfdfeVYGhtaq1Ok-=tF!_-zvtq(PTzD3#Fys>Qn7wYKi zZi3mIt&XcH6E^%Ghc41{oi)ece7A!ARQKm$A`>+q(Xe1xEOK0NAzI7mPz({M1qJJ8 zS1tYzErNF&K}@W*YPBDDpZ?DAUH?>v+`oVsXqXM^d}6Nka*R<2Gzft6jE;+I@O^L- zzUxJEI_q2?aD-9zUY_$fRQMFB776mX0M5Pt`BiwZ^L9-Dgh1Xjw-h9ARonYAA|oTi zh=Cge)wJ)abK6EB@`2lT(2--FEY?K)kMSZ6DWsD|#T_;LlI-MRPk{2v?@VYF%s^=z zHzhO-es1|K{r$K3_P;lRr;c$%e1SghDJ2VCb?*|sr;g_*6D~gp!PyA>Scv^JUUlO3 z9o!Bs1&42+UQ(~w*xA{?!8!_s9Mk^`BALZFppcP8hxh;Z5H6QU6(ghGu9FM30Z-CC za(KhfH59tgn`7twx2+yljxdg-NbOC;*6Uf%KZREb;@g=yoYlkiIO=c3;RugMk(K6KtI>R<2iJhf~CW>^l>DaUaQ zYkC)Wo3M=VXHVS97mxctdg+Ll5UQ1j`aFvW!;1 z&qiJ5J~mT8deD`$g18X&A(h%i&=o+ORW035C+k-}TS3OpCKn^o>rKawpM6OgMgCWR zEF?l`o|uOJK^;p`nJ0*g*}_`EMJTdi|I`SHbP)@X6-6B?*ZS)4Hmtu?nd%g2nHh~< z&?Ox+f<>oEYWX0O& ziZ@(l9iswsz_qRCyk0o3Q~2E|r5Hb+>a{qpM=V7PVniN!N|2RRCa0pVXP&*V11Yjw zteqKwg}y4Cn4MEG{(^BIlHl$(Z~lAf1Pd~hSVAQ?Y&T2l;oeF2{;m2|2hIPZG8zVv zBr?$ku@_x0pxn7&@zK;O3dP@#1sKQfkz;9p9?{~sVHO!kFh<6j;*ZsH7krYBt7Tmq z+%nAF+uWv;shiaiLzLT&C;YzkFk&iSeY#CWBG)a$T;0IVhmz2SA_+X^QY&sha!a?~ zMKqavT4w~JFgx}2^^?kWD5dNL^dofgk6-^D*hKRCxTPTG?#SATYF*SH5F%Bv2_rrD z-Vwj|Z$x-K?sqS=_#6E|Y1ncv%bB7>FN6g4@b>61@~UIU9-l11C{=DT{NRJWEh?6p zDr0)t#MesHumz4WV!H7=Wci{A0_WGi-3yS$<$WA}QU{ty7?4!p1gU#l@Kt|| zQ|ilL{S=QZG&KCDZG%2kaDW$V4uym35gYcMUkp|hzcC5(0Ykb}q#IfOiwn{_yUd;F zIc4MRXm}5p{k;C?rz`Bzd_pf%$GD6L8ue`x1ZYnXD_Du``QB)t$W0iDTzYXQv*+PZ z**|kmNgyUki9f=tbL!WxUuCx$W(1Hj%j>Z53Q{v1Kc*=IYhcGsQ|&G&(6r+m<`x!9 zKnLo+vFQ#yZU+_q5{S?Vtp4}okF%^#n6cYzA|lh(Eo)<`%zCX5smIYBLb@vZ|C<9S z5|9+6`=B3Xg%~I^va@$8KRq$5xUUYwc3*PE3f*W!7+|~aAny<&;Y@Nb)|ri`8fmO} z>mIo($7Pd>-Du4Au%hl>-|2;?GJ88ad3|++4QL<>>qO z?|)b~-Thnao`M)X9Vgg_A)q)rdq8*m=*ZgY_CI>$Qp8v>%C~rpIvDH{1XG#dR>Q+H zY$5WXV|bveTDu4?FNhdYO|E#V(RkBDqa|EH;x+K|$lbqsC#;IzU#wJZ<>Vb;v5O|6 zygHSzrHa_khbdxB`q-!tBocW^A|B9${-S>Z8Akw~4&r<`|6?JNHK#0+LnSADqhRC4 z{_?fTOb&dF-qNf6djrK&f*!TQVks2cEL?68t|`B_FRPZ=5o7{Ofm3D~YVO1FjVHEZ zXyAmu24CXt;T}+I6ms!%d`}&rpLvrv`qWd{Nc2qFHWqo8Mn_*y15Ylu z9o?g@Z8dT!tQ4;rG0bPWUcg0^)vB;6r`>w zErTHqex={R$T2lnr2*_VdVD!TcAA>tG@{-z@OIxn#TYw;(p6DiZ`lzR!ZhL~f?l$;{L0gH{ zyZ0oQZM#v;Mxg7!F51W6s6|T0qQkmLvDXZ%O4nKKvgLmABq-0j;JNqKA ziI$dyXVkxBlHyIh$dCPOg?dIZ*iDDNfL&oDG`4@>D&_IUf`srYiW zf<3>a@$$Ms7ksE=xZU{qM)h0dS2Bk;o={3NJs58&>|fE4Q}S72&|#=i1P?R`r?e{d zS97dq(T;g**u2)o+p$s_L_5raB8LAI^aEW3iQ;>b-nCNTGrv-n2d?@v&9X76fZivQ zuB*=)*ZcYknK08KW!-&hHc;#CqlvHQdnEW@W0|~`D^!(zpQ=iwat&>3PVmfkZpqW$ zp`L{Gh_@BGHz|6!%=X!1jYoq6KE(3xkp+p-l9H$dBZ2aGHh5TFNXV_Dh{C?X3t z>iSW)Kihi~K@xHx?W9g>0u|!4=ajSMyDSKbgqYPkIwq*o^!q@&eRXx!aq3#T&G_ja z3Gbr|#N%I3nu7ROSi0;d3t7KyY0a&*BGhcV)MxcI=Uw(IVM{ZnlH%WXad7MqP@1gPvHkWef5|o$ z&JQjwT|?KIOy4=QN~;p``tl{>sb)n7qU123-XtjtXQ(R+;Z$>{$itGu@T{IIBaj1+ zWZ}GZ0WmMct`77h6qM?GdobF#2124Rr7(cf?E7$Y0V(2;sUqM}JZ(QdxHf_KI~@TQ zWd~9>U`<=r{RDz~zX+1}yGXRu2vq%eX^g!42@A-emZU1SzSAf*WNfvl{x6jriRSqe*Frl4r0w99 zi_x<68Rp=dKaht|cyCNGWY{;N4Foh9#A3&KEr-?m;X>1tkKUxl)ViYFTur(mcJ?GP1c9Pz2_!72a4`-&BiKo% z+1`J!>S;FCdQrQY9MIkc2!G!C$C1)Q9bVb0VdBTA7dEsN_E5F0EZcEN9aVn4U1Pd3!m~SBv!b?% zv?J#Z84(*2W%ojr(diV4?qQrbe+Ulvrt$xoO9GSlFF_{Mvw;|)15t9n!wn8LXoWwe zA8*|FxD;e$TRZJ6^y81P-2Ul6i=k3BZj@(>?QIe!(IjT9Tc-SbRLm$8>k=0h+b>=Z z@83rr3-4hkn>#E^jjm>hB6~va3{T0?VJ)gEN={XiAj_2zDLb!Qt{Jb%?;_M&GmrZ_ z1l94=_9)?SjYt$()zul=?-7jcujnm%b$$U@aDQE*%Pb#76RG%ORS*&al2mV@Xr376 zo@au$w|zXQ@bmI9)ExEUmR`}iqRSU{qL9C-(R)qq7(GZBG=rN&sI=z95R#hC zYoa_$J|{%1Nv77Hzdj6i+Pgg4zojB8af%}Qq=`gp(fq{5QDzbx_Gc0Ca}pV(O-?@B zglG9qvZh!k9zY=!Y5n5 zfL675{0Ipad;!xMqqM>oh~Sjh@*b5@dd^oGNTI_3ZD*Ft40JQH^by>`#ESVLDc~dN)@wS{rc|CN}KHf z1&%N<52>P_gLeQbJSqfHKqPBO2M=OnBrCK-11Md#NOm;1Zf%!fr z5KV&qe#S=EM4G6wYN5aC6Q9dA5ei(vogZpHF3E=RooBq8`)4w<{$o=PMY)1d@ z*`W&OeOzPkvy|@ll%T=Q4_%i)Ij3cp5^Gr*9KRaI_BBcm1DZMztE#zkf;=fe45Y$+ z_4+?%{lyZs+6G>cxU+|7#rN@V8xxuro(KMY;0|Ov<}Bw*KwiFJYnCQw zN?50SN3Y3z-Y6acRr$}<01!Qv42ICw89nm&(K=Om+a)BqhzV}QpWo=ZIGP5MqR0+X z=xin(cqaP1ma##gV0aTUr4|gEw1X{f7}7gNOdwkYUs)ATj{o!fALW~^VI0B~q`o&8 zg`#1IIZx22n;y-XSbUQLS&CRhItQnv-9HQF56E1htM>`+`1tAQprmq%e&nOHhJ-N* z8q(G2sXg|oXwzk5Q=)uRL4b}`eVNQ&l2;UyC#PB-t>Y+B!HDI)(}5lKFhnD{UPlwY zd)ZSxS(ttOU*QF%mv+sBPusmp@psW6cp)UAnN7x$bgT~18a7Jpoy{F?TXow_Q~#2*tu(eX>olrKPixHWY`kuKaZ zN=jVMEHtQ<&%EeLwQNfA=a=EeJt8720wW1|Gd zE<&}VQ~)=-r3BsEWJZEtui@|%WLfm98WD^f8{o8P1b^KLJ`_IiuIBa_5ycu8Wt(?3 zo$Y&l)}hqy-b7Ed?8)_YMo{079o(Bd2HdmJaI8H#9El#P2$YOYFjTcO@h}0mVac{& z1zPLPG=BfyWEN-(vi<%YW&?g3LhOJEh$o!?@(jS>az;)L^bfa`+j;3h`(gZ*eC?>h}>K?vbI16wxS>9rTW3FLiS0ps5G^89d! zhKVX-%h{xx(rfr-!OPNf>FtlRTbZRH-Q&%n?ZW)^vp8dTcvX22fs?GRB!FMtLFfQ!Sr;sXN?5U7Vi(AbFe!?I27F46iOoTnY{pSnr>aoJ$j z$Up$Gu%&jh-2VgeFIB?zsca}RS#8D18kPMI>%d9LZP&JotF>HdyVj8bis9-iF$70q z_7YfRvpbE}t#hXobme*6bTZ}p^QY%s%|8FFGWUDew}WQT9dRh98x;kBDclnaSUd6{ z+;s*pSXMCc{q*A^UEzrBgCMOQwdjfUqKeADJa5t_Y zbQdldLg;<6Ew-f$78{3x-eKrXROe+ebchKu5rR^e(g|V5I5AE5eewIwF*aQr>N`~V zz#Y_yH+IHg1AFXGvfd^np4x(t!FF~&xX(ht*s{ja6F-z9-B2=;c|)j2B!b<_JtI46 z*@dEN2|bKL?AB<%5f*Sj)s9QRpAK2W>swA}|9eNlDdaOf%#P_qY9>x7hDDj5QZanfku%ONJgr`T{6AU=>-4L31kRqfA2u#=B?c}RtTdIjj-g~Mj!HOG zIm~G~JZ2$X>0(6q&7Ov4juLK?hO;D#PD^_N73bdy*h)_#2H1>6GYj@8ON3x}P4(d! z%$+tZu`cVR>9dDHh8b^P?QhAD-7-uVehaHoWjY!5Ec9e!DvmyNe64Qyp zK&zvQ4NMW!8(j~l+gC3aQo-opAIi2+b_s}#T;AA>j0|!<%YBH)Zx$TRI1oiNV;SxA z7|l*sq9Pwd8>xq4Afj8!vZW6BW+^2 z$Q;_wdUEq(el}@hH$KJDy-s-JF=XFyyHHK={m-|kJ~tw^A*)qh=H$YavfY6QNh*qj z0fa&qOPNRt+S5?2gD+LF2$&KknBr7XrQ~++$Kv5ipy32U?V`sUd@J=`_a7!Lmgh1r zhlMTHy~l^%HE#zj$NfD-S?BZCwm9ir@XEXOT;rU|6PcdO;<=B=yF*MJr-sOmQ#Uv7 z#&;9*?lbZV{#yuOV-r>Rp_U^@iGAoV&nbzJ*WZJS57O9DznW%0*eD_dlv<&S*EKcG zPjcsaY#}x-{5Sp=H5hocKh2r(zI}R)dmp2a+Ar@VPM~4I%O?VBWFI4WozD7aQon?B zk!l)ZYtwgyHvPiJQ`5~)2n)K2RK4EH9~X0e`j|L#R^jG87VkH*AjeSyqYP{mESc&hBSMYh~#;UCA?-q%%_Yh`0FQ?c_Y8pKybYY!3sY`MF;#3Bx}@p1X* zH-uKqr4WUXC?`7_g)sy#7~97bQBwR9F3w^HOVrpjLL!Mr0)~V(4zZ%i6}8VKMaEE! zkP3Adn}V)UA>6l73q}vdB#?`1c`Ic9UBGw0$H3I-Y0`D?%NEGxf&8;HV;f+W=)au# z{q@iZbl{zzG6C5UR~~QZIxfPgHjDK)2&XN*$5vCbtK>(Z-S87~P}^P(a3rJBkFq!U z93yr&2xIimnI9g~moQ%Ru2I8b!Y=t((!=g=uj6KZWv*ksa4H|iIhVfelQE@|G*D+I z%A8FaKsCZlG)L+y>=-!8M8_1wq<3RuWP8T1<_H|)jUp1p@C}deQJ*|>^m9$oP9JqSOEsMk4?2T-&6!AHQ;pL`wK=G zRC=^yPXB)|fGs66d+FYvKhbkb1Q4s99Oi}I%O#H-<@s0ws(MFYKGh{^$yq2uOkp^B zU#4W!$B%1=F7gNgSv>X}BOnQ3uNR)Q*orVVF77_}?4G1?0b8oKC{B2JKC^Q_*PD)U zE@wE@=Xx!v)avWTysk;L6hbe^`IFJqTYKE&x%#+%{gHRy17e}If4Q-r<5H~rffLy7 z2vSQqvnJzhp!DQr=df*<0gxsef&+hw;@m3E^h&bh%0T3&%aNAzuG`Ky2nqhjw!FIO ztOA_qweKH?*J0_9C`A7C1Z|UWkW1+i=C%n`c|{ncDzLzL*$ZDqz`DgAk<+H ze=fyTdlGNQbFJ;OkLp$nX=_*T;0RCMd_!`g2Qv=OkSM}$7}`jRE#BwA^>ytg1acMm zgi?C`SjV9sTyMhQ;Q@+mO6@iLq0?x4cET>ecgVl?p(rNL{(AL)bw_MSERPHZomh-c ze58k#?od@Mu|2wMMzTp%Iv1V(y{XkKbwT|POAhY7ub3vt#g#L7HqFF5eTMqsAOOY&?PUFs(CfH7LMS@CPKUFJ< z*~c&}Kci}%TjDiQef|N1Z4lh_rePR)ePJJo>{pp7%vj5O{*U|(_3Ji5k#*Qjc#EvNkt4RudDJ3Rx zB6A+=!T|AP3Guf-klcf`}3gJju9i~*Q>Kw%#xSJ~yDwCZrg=fo* zR98hcpo(lN5`yp>BN4?6g9=b^9Gj^W)b#b$tL15CSmIW%oXRkTFDE|b|3+f%MMRrz z84WL_-c3oPQX=pCif!?83;!+I%*#dK8Jj%SJy93S|QdPFryw7$wHogF; zarr|6?P35+8U2fU*Hw-ncnA`o&wJ7Q&`tDgj(B7BzKYEZL63j?V;rQ`c(nHP-ho&Eq?B4+^Kr}lDPBge!`QK@0V!}lRn=Ey0z(uK?k8H02 zn~gHw-<_U4+YQaheZbvmbmfr>&pJFM=kfaj^<+`A`C zT*~#06VBgjd&|4y*#hpUCMbJ8Wn(Qw3X6z2lma5HYp5b< zy(B~f8gM-mLNFY);0=i(TAF$kEui)PHh!^mMuFb3~XF2jEz9{t0%dCP!< zuemuvOq&*NBsGzI;*r;Th^j=*RIe?c=rR&A`t)m-tqhuHlJimbLRn8rTEl6&I?TiI zMprOE!6)3@1FF4;nk~vYxJA}qe1}VHp7+o}jUot^F+7lLfwBtILx(Jwn&HC$Hw;#K zRORE<(sYn4pM0JKY=855Zzf?iloA)0Du@A{+p)|mD4|Szlk$d2AW+9M!ryy4*y`dH z+DTWq3>@0U&*7KoO%3M>as_7`MjH)TbT#sj0hu?9p7P~Piuzkb0nKk5p~dB-%b`95 z)|8t`78oO7;s~}?MpV%{5x4@UuY$0gRkD%JR2Pjeouc|t`{~w)u&}TRB_v=8`n9xV zWbYj%L*j#e#w5&zudc44U`jD^nOj`^E3Mvis%JIi$@4Yh7o#c2Dg61t24g9!KS0?>g5Xe5dl( zx540ce$8=>DPa##ktc<2S3xqJq^e}9neFG#M$wx`^Ocs>Ack1K%_+orf9fK&r6UA_ zQy|$)dmHD$n`FC>_g9iLCmi}|HMtR{W?zQ1|O_>Bt{ir zG}|XuoIB54>Nsv^66me ze%^l@2Ovt2&Gh##HtDj*wTGZx8Z-F@barm;H*Kb0%gX>vZTZ-Q_`0}ACQ?2AnSN#x zxpfv9epr9;i;ayXh?D8Kh_MIc7igJju(ItDpE^5*z*bvC^7Dn3u9Q#zNi8wUQMTGfO{S zYS!=leRtYnrsGyzE1us(6Ir+ru_f`c2W`Y@1PsPha`9@$pY=W|**pc>-NiK3t09p~ zE{+fpB|&;`NM#;yTvfDvce2-cHac31o|XA_p_v=lJ!r-`z#k3qZ$PrD{z)JGhYTnM z1O3ljU+4{B0xea9$r)P`oTPI6;l3hQjjEuih?|t`Gu4z+B8%ty%G(Y9Qehvj!9X6q zzeiO~QB&x(bQJNoxMgNiit}K2X0{9eiqN~MHfjr_C11!-@fmZLhSJ9Al3!xOVTPco zxoQW!1S{Bzj49qK;A)V6&R2X}+Jitf45wbxHq000P1wa7TipQr^f8!DwqlzUIZ9%? z;`9eTitBK?p;Y!@7@v*Dn1_3KJ^OwQ?lY!mdiYy|0u;CcoL)pp%3rvAL%LI@gPj)= zJ~CIj1|446VT0THXww%&&;DC;MPJLD;^sqtWocOwQ6$HW9K)P&k?EDNUStlufmuS= z2*67v6U@ILhvMR>^5;{ngw8*)y&-tRT1JB6$ek6I3WH6P6+ zr&3?YBEQ8%t!%7>`;}^rd{1Yb5wCWy@5spDxp47f^^zlPm~``SaQH{WUNN7<*;nG6 z)txO%sI~gKP{A>|@!-QpL4TY5vrVB6|L2F*_qheL!y4Ox+f{wYy)N7ooE141h;_z_ zw%%a~iIQ*Vvk0TeBT+IFsRG;W(ov=yoyH4_i1{?CDfI+tz9D_2E56jw3Bm~YVG6T9 z(;hgYiikXmRT0=h;<(loJ$&}$HZ&71^3ntEIoKjR^u{?Q?vmZk=?iQ)mD0P7Hxd}C znw%P_1bqK^X&bN#J$lBnDQ2-cUfHu678@rpi!qOU6tjl;h98d#r=dDI!Bnmx?g{vC&(zxD` zi_r0Ol@ApaRYe|bE-ab}@9&oY_>PaC-5&ztxB1#}JfeJw>fb9FPaN>F^6NqT^OWa~`9LXwczf3+{@0JIsQs zqNe7KrxI~XlMl~+H~CUS74tM_R+Ah|(kM)R)bNyf!<0FpVUsR9VGRHA(IlT`HU0Rv zhDDh6bvcBYlp1HqW<{$^kbx(q`h!dHt9bK*+9G$+OxcIW|CKOS)|&Qa^DY2PLGE1E zX{O15&KT$t?;U=`hzzB>k+54Q02nx6$^<_wUJViu+>>>}2U@o}?ylySaYz z6M_KOU;R)Fxa4c=9#J5~*Zd8$LJ0pIJ+4zGXE=_*(D zF|Sa2A#{Z?qemrpfA5V20f zz)7=}Gzbn* z9S))jJ8-WyF$~DR!*E3$$<|E5>??g2ia=<*v9d9~J01OTGX4AMU+k^d-#dO$L`z!< zSq1iJOanAfLT?Y9RPig24aegwZ_-E~8>zi872Z>$Kk z<}1u%XiCigz7S=K6d~0u4(C>o%$YqeW)-So}ADk1NmE_ox zwOleS%zC^Tv<5?KTl>IFuV!*|xSL7lUsYoP3VL{1E;n7{M6kXqLYe(4d^Ja6fg}ND zOm0-pHxd_dTP{`)#x2U*^XUf7$aLcqvtLkBFL7bG*=OFg*!l&v1FUdj%KD(1t6Cit zd#vv(1H8(y%J*URFAo!YaJxn}gcx#V40W%+y~fY4$FZ=W)&C_F2i5#lfR4iFRmoxm zr_G0s_L}ef-*s)ku?B6PQY6uZxTdD*F{UkGf0@P+3Yyr2g@w)i{kzrgY}eMcxs_>> zVmp4@w$LF#_Na0I6cV7d+d)nd!!8IMLphV*&;tjJ9n<9Jy{DUO76Csa2o{prCW}uC zKQMWFdjp25L7zond~~y}iLcA=i9e|KRSEWo8hs;<42R7=Si7~3rJR1_dQtlMgf613 zf1phT4cO^5Xi)$DZEUEuJ$|a;&pMj74q3=VU;fumlt`#+yyy+Met_Uu^jmu_F4%$L zU$+``UdM~I&ZnzwEQVe8D|BV~I8U}yLXi|;QCW>%%KTsyUYpadydGm_D%o0DagOub z`c-8A|JaM+G#vH$%w4C5+uS(+$8EvCKP2c%&exppFU^{po69OHu(GVHN57#!GW0+r zsHy3?ee5G_k2MWyDnX1i_!HMl?0)~OyffD7@jnTYJC=5vaz$F3G!?a(lo9!-T4T^T zwzg*Q0ok1s(e~J^wd>X|79+QE!yj#jvIz zFw%rW!zIRlp(KVDE4=a)-j1hiWI7t=I|oXI%*}J30C6G;nXj**n!nE z@9bV@Q$_#roND_>;=7@$lK8b&aFX=XKM5Z@`clT!%Vb@RFH}xYcz-h|K3AipEXuAg zTwUj69^V(J-g^c;xj(<$qkl>~uc!6$_6ZX8fcacll2q7q&_EJKNf*bN8{Z65i}xC5 znSYVNqbmI0&GE(L@27y>L(C=(7>O*{`Zl3)gTb}!+8MzsRynm+A&U$D!+kr()w9P~ zNssds%1Ni6U3&|MuEHMIzWOa6JgI!6I}b_LueTN*IXXsr=ZXHi7;#fh}=C z$F{oyD9!5Nr_q*>_dO;FVc4e-N=H#^ zTW|FU@cU_VADnYD(pm-kr1DLBwq|$(Kj2%`SE;DxqfkeghhQmGv9fnjXa~$?@=mMp zt7zebl&dUbBz}oD34EVGvH3LpjL0Y9vx7g(hY{Pyr7?wJ6z+sLA{z_(Y zf_q0tyo@4~GYC0V_QM9FI8MSn`yPr*jViR1q67jI^>*##ljFxJJFIoCp>x*tC)RZ4 z4+uEqIXwh24mH)4M8q-77YtueKwqWG^x@ZRT}xAxOCS}A$~(qjYgmpfkM+=K*!FfG zN8+NUQ{rPVh_kZ;Q_a1yvXY&Xv=olKF}`_gD^)b zIl4$FOX#1F{q`^oOVKly!3&xF{rz^IuI`EH&GsYdg7YgXYIar)*?RbfM@JFKVZh6` z={q?&1>WX@W@zjiAk)7w9dFfxS1T$iVj;YY-i2k_f-Gnp^j-^gsmli&GYB~G_KI5)aq(x=^~89 znvdHiqz~F3?7Nyvt5*~b_TH(DX_XxbE-c%v67NE@7<7OoKPPuw;C0920qujrX@at_ z?6;w-OvtljMjkv>0ke@HL$WzrqTqAWkhgnqP*%CJ*=fN`Jj{pj?nLCV8U=yvNcJa!4P9c(2iEHGL;S&lanH3NbJL$ zM$&q{w-3`4sbVK;iY>3fiv0H!z#XCYKG88 zg-@te!{9dFrvO&yTO3wnoZ#-MLz z*}s!^#$9+!d@3f*U;ae#4T-d0^8Gm@eiWiB23h@vO`&umiwTW&7#)dYVy>zMw=QAg z#t&f%983vl=wZ%D8SOzHF(y8uY@;je67`OX1k6Tkx|11lv7^vXSS|jJXg0Y?F_)ax zq3{xkl-N#&UTKvBSaRo9%g{y4`2iT{dIAaysAGuqZn9j}ayG^%l- z(}+_O>=U-iSUzUEt*}h~R3^oH?t5RJg+Zdgi;H2>uN6pcZefyY1%XuB;oHGX<8^EG z6-d%6CN=A=y{0zu>IAdAw77^3{RDa|>f-1y>r)*(J7;@-MB<`0zG-I8I;kI-4XeS9 zV4(Uc&asiy;><|(+P>Qc4TXlLR3cSQljFxlCfumlS8G52tPD_xpwpGK6ZR|4xfB;K zWR_Z$9TS?M0N4<@I9VSjU8EG#pp(j&K=2v`1(iUUq@nfO-+l=PE`ea;Rf;=yeL@Em)!fTt9{+}2@;-8W}L_==Hh7S~Kh+AltUnMhBA(Fc^5tDfCU<9Ls&tmR=l@?=W>ERz4FQ5Bf z!14m))W?-j^j61hX^Z;*uS#3G1SCOaz}mG14$uS-6l%m^<-$2|^c|<7q_~dN5!dSp zhif8EW2ccbs~TVy_l{yR!p6Kupo2jT5SJHY(j7Nmm%U`8iU=hmON`aIB<6ILU-E$= zV$$TIoWbZqvdkmfjVB{s!wFx;V#Trzryq*7EsNJx;oM&8{p5iCdn*ul{@?R4GtIC` zSr9S=WPg1>fqIKdYUX`LJXpN5J?)F4K2N8LB^AGmnQdae|L4q3H5F$|mfb*cDUKDB zo8H-fWOCc0jo_0xUuMD|Izr8FY|i?|3FU=1)Z*uS-0t0Vi9lb*L+!XFJJ5G8#wMc- zMnNdJ)9-V?TAr(1^!8~mNy_gyd?A{3PeO-~Kixaah?p@{TqGt$TU64q)UX!BwRT(k z0hM|8OaiBZwSF@#bFHCq*_QgItuBv_J0l7BliviT?2%V1b|j{syI~OD(MKF1zFbhg zAl57K>KW`4Jjt2Q)7Lmsl@IXa(@EvZRArh7JKgu&rm&|}hKHGG*`cyX%LgDE28l@_ zB88#7CKqDiTyOe9qm3ul%G<)AXhdU9^)p;Ho) zY{4nFu4!6(KbSV3%wAbaIK&3CYwm}buXFT3HUK0jO%k&Yo1|)V!yBX!rDf4WV|E$q zLBn`QCy#;WHIgA+tte^%JohrBxy1g3=ACk80q=dqXa_9PRc%!7GgbNeh6V{u%?a~{ zn&&gn-*aTRP)~p<m}Na% zROuxXKoHs4V|4E%okZz9df$ig!(w35K^Hu;Z`NZtINyB zm;qaO(rWhYx0)Odv=upy66c!6%{3EmyPlsb54wE?Q+HEFh5wV6U?;N?K?+l%H;({N zClHV!)Mzyym;X--Q0Nj6^#@AA0=*QQl_~Cyer(6Ip?PZUrj~?aMsdXXU)!J*xNw1Q z1O}?}1x%&kp><%mW-)h0)^(jX>eC@|LCc5^d*0tFfg&aLHAz4e`doDRwADP7Xk>am z*)aQRhv6pK=Ff|wB;q`_8OKbWBlmw_1i#^98LJd&hV=8$mO{7YkYx1ht|f}y28&Lu zJ#5~V&K+Zo+7HEDLRPu{{9-6yViveT@7qTt3o$$M_!Bbp(RI|flJs`xbCTpg+`KnJ zRZ6L`rM0kbP>~6sr5gZ6y9zg2tm7&N%qYEySnF>TjlkmwH>pn-f-(YNnXZ^!gRpf;C59#a6??v8?G)ob_gjL z*B7TE8@FmO6VgMHghpNP7+kxFmOUN?I#}Mox>VI4z_~A=%44uZrT>OBQ$@=Nw?Nr5 z5-ourfBmJzQBqDW)_6!KpP(6xCnbM|Q5aZ19sws&2gRworz&bpP%pQNiB%V4O8lKz zYxeKR28?@korgwN|~MbcUg2lsm(~-0{+tABmO|$#QyUy z3IXw(X4F*B$V)Rd$E$@L+PDiICSyM+ANJScXcGq7Vhrh6=%N~J=-T?anNn4}um~I` z{PIBvP`ujIRpYC`gcmtrIYNTQ=9@Kvh=c`!;mTdS4OgL~E$<20MQ#z>_vJjaLCx43 zu$*G-oeNl;p;aMwge=UM`KpiX`7Mq_AE9mms9zcq=&nKXS^%C{BYZ`UP#30RM?#z- zbk_yjg&jw~Z!vdlrXkTrd@dXAXU>XNTe-^xN$5Gns>38j*zE$_rkbcFIAG<`(P9J~Q7up~YjfRqHT=_42rqq+Y zd^-SViNvYezy-S7P;Gq>DrL@bDez#oio?&C$>tl5AzvzOava|cne-PW8z zFFwbd_{4hA}vZn@Olvhmp-wNkdz{gh%^(6V!O~jeIk@t47%xWY!pBQ z5IX7>P@)nYvI@tBS_9iQysH+1nd+t4l(EIK+g#@83`jvuBJ}|}fPtVu@PR9XEXKTB z2MH(4;@aAL&d&&DzjqUT;6w+6Vk7X%eZ|m6EYeV`!TE=|i{nt`>vgi79`12+`Cr)J zos;PB0KtXKxn4?W!10$uy~V!xYOAn57V|17^tr&S{YE;8uqvoBBGSmp=D>vtacHRv znPMf-V*}=_xXYo_%pQf1k%KtjFJbW@1fIGtO#NkJI)IEz!4&u123A`NE86xdO~_f_Du^J6Qd*@SY&^;lTIc|gIUwU zgy#%KA$D}n27j(?B#lG>CyB@ry_%ymn6&4B?tMB%Y`O^&bR=5Ie7jk*w;zX$&0UU*Q)Ra=7A-00h9? zrc9mpt_0T_N}*`B-uL)&nRB4OP+=})-d-`Z=6*0#r<{Yf!Bd}kIT6a7n#m_vFrO$p z7OI=H4JmGgrdXh~yyKB@^2F$7wj`m5Pl&h`<{o+S(cjhEjlRpIU`V}`#r541iD&G; zkR&H9a-t%N@IF2{L`3OtsBY0P0CIInSD5+T_cl3)KQ(WKkUAUILBa7&zU;C@gTYMa zuPhoUP(bkcDt+ib{_?$v7gHWvVeG*$jC`Y+L_VFDh#j3ACf|S-GMzBqPpN?vMA!2u zi-|St$CTaMkQ$GUO0I}3U>Ni|@G*Oj1PyrkW52b190?Fk4>a%okja#uu8 ziN#CN=SRXl@e5pFmC&+n77;A5buDkZ*3$+8$|#E64sXZVw)^jl%kKP3o3Trup7{qk zlnef9{vUBLJs%mfT*SnZd|>oseJO`ASG&DIQ?4V9ELM|SNQ#2x`fFcMrR*5j3(8^QZQd(h%yvu|2`y?3lmCNa3O zk|zt7np{kYDMJ=Cb}^pRovCgHZStKDh7my%OfW7Up8ft1c+jroe{bdQAw!5FNHq&d zhC4u%*UCm=>oFpNzz+CsR6VCfbf+?XC;{3v~6)~Ixf5e}HU_Bz1W)S4s{TyUK8kEMU zhR$*xN=_6bi42~78soEFe7XYMY^A^71#2TDu}zL0NF2I*L{#V`C;m+SaICc7M^m7g z3CJS?LZ~yfU_H0I^Llu^4WXMm=VpGPeyx;zB@I-wPP>`gl#!aGD3L)nS7MuqLaqI( zq^eNIkoG8~0y|zoJKu;hWxU9l2zECalrl(9&O7{Wm#>uP#>KBoI%hEx zaiNKbg+BC(lqHYym?q&aal$Z8Q1TYuBY@tZd|yy_kK3dr+|{{7@qgO>3O8&XVwrsY z_{miqBBOh!cQxP(-p9u==utr+4bw?Y;(!V-esG+pP#G%u}4yHnN ziX|ZdLTThHa)IeB(-%-!eb4-5H=~IiTrLC~Tn-!f$crcP@uGp2JT3zP_jl>yJ2A1y zGj&gjN03%vZcr7fQ!~Yqbuu5Zqy!9XE&^Yxl+gR@T~sPIV$)%?!Y@?9kp6u&aFL+V zTuysiSjYZfyR6q6^p@a6GJF$momFGXb1t5+gx#0$O(w`yQu(-DdT9K&ZaXlA^8AN4_lfP<{O* zId6u2j)diw64L`blxH7nK>KHY?|~kgK&$R$N9tSKAI|=c`#TYz`Whn{etgH+)G}?_(P!!w67M^@3YsN9KHG2r~{bER(Afg#DT@^970Nk{%>wH}bQp z7(7TY_yQiX*VsRuG}lBr6KghbLR@ht2Dn#l8L zaPNMmSQI62Pbr5)&w8O6D1^U+p6sTzUg>X%Be3v&bMM?{K`Qd4oEdRHH4HOqg{a$G zmTN&XFmt|skzx`OBOBW}mJVwGVX!@A?wQ)(JE=WFem%vrM)sS(-4al<(!?vxFmevz zL>okMZABedx@Z4#UoLK@qNd(^;n%8i{JNgDc=AE#%{+JxFV03%gmD)P`n z`jBQaFiI$1<zq-8w8{@B=YzM~k_HBeUV_}IOX|$17^~Taij6^2~ zOFW{FNWe*7cEZe%a*8wr)6M>q)(w(a zfdGSbMAuwyL>E9dh-oBzS2k+S8(W9smvF}x2$p}FPC$e36D>viIF<} z37o833xIp5t>tF{RI~>fp@~|#bgdizRm9HO$C<1`GHx<%KYOB{*ujK_56_JC7W3Hl zSQ?YSS`r^+d-aKpHN7Pf;bDtuW)HpG-HS2nUerY`J=wVIrt-Zpr8b$}$yd)_AcP^2 zi*v8T$8jh;Ns0Yk#^84RA~kKalrLY@2F>Q?eHy%}Z({lzh5?MG>q>0|xgGjw+FQ2p zPRWl@_&I6{vX70N7VNfGf)i%1$WNA8*Za*jaW(}Avsl*+!w3Yb!kLYt ziHEsVAMO3QkDnU_-&lK|hZq|`TABZx-vTdV3Qiz#VbAMQ?d`k_qmmj12m^=w4B}IO z{Q;$a4VMW#P=mZ3?%Yef=XC=+FtpraQK5BuN*I9=1h@p=q@taAN-RUeu+u+Gtofbu zmgz0ZWGaa!V<{I+r(T*4KKG-G21uh-?6!MnMrwVsxoREnB7J*jVg@L=>qCdM!b$f| zu75prm8@@=V<2AO4i`nDKxP31s&O(P#TwA(h&bwNt{StcIM29UjMo{M7;??@NiDf0 zDm%Hj3;A-DJAZpn(sf{n0~W^{ypl?FP$ywXrL%Yjm#T)Hxn#P^8E@i{KB-sI7!7fs zw@<9!T_0@y&hg zIaZEgacosnSvAY)T{w9BptJe>t}B9sA40SXEEr2ch+@~cs-lK@#|8w?Fu`&&?QJf@*(MXkbhO-OorDflI0tfr1VjM)$!%))AcZZK}5 zYgP0JBcj43zf4!k^W;LFp%dii0Ow~oTIb+T89w;+`0@$r)JQkOa=57Iy>#v1Icj@$ z{XPc7KF?fi&(wO5lYnwbu?6G<++QcjK9KuyN8ZCT2!|C!IZ5`YZr^!b-DW+x+|_fQ-l17#q&cmoXgYQ%86lRv}tPMFZQ>` zNQYO$Ms7vtEXNs#3o(_AMv5c=#^l5+MV}A!S**6o_>#k>a7_btl5FEaB49R?##5qr z_j)A>(@-ZQGr?huN3~Sug-H=^mDykGp1|*!On6SpcbVf4H681}b&8~bAojrPvF)FA zDD4lJ1PqR@=$OD&at?Af0U61cOk8%!rZtMDchuo*(uP0fV)KuwT~mY2Ct?ZqwfmUP za6{kaWB`O>;T5A0cA0@O<+_Q3$8R;5eMIvKgT}HOXd|(~_m~3&4oDOxt_`@d3MVvJ z7uLp6U7FTNT0(MZOWh46R9G_ew}FcU$-fh1tVFh2xMrm7gC39Twg?$trPmwsr#|5K zi3+C3dgPWwZ8f3))~s2X7oOg}*_*U}I8rp0H2q{n*UGC6P)__c>L65YycVw;QT% zugu`bK|?k+1m7-cxxlz{u`ng-OQfq@+q<&nZ&8q_i=-+92k@&)*@+IRH=l2$6&4Kr zJx~llNsKuU-yv{Y-J|4Wr~oCAlOfNWY93`v9>Wk{)Arude#_3zzLx2|mq9lj1Hs0Q z?()9g^I<&xru;nV(D`^7r>#XXF8XL{gn-QG=ooh*J~QFId8a4T zsb%n+RfX8JbMAENWs~p3d9N8W^;LUWf}faA>aFDz5ndcdTlAXE^kOs)c7ghM=DK}sa9b8+j@^4Q65L zBL}4h!1)Kr2g)a$RUvdDu@PYm*a0e0kps!8DN=OnkOekeT5nY3Ovfel0Zr2vXVOp9B-#f)BXer@`G_q+pJVoBqrOsvy-)KCe>dn({T$ zsk=*_Is2TmC>;O-5!|N1Z#I&2GP)uMvPD~4bzLWJ)8LIL(G+=XD$l&NT1vxuIMDKJ zLlQ*8v1KVl$pbHzY9&FT;Pm;NFV(MYJkVmm%qoHuGolZCZf(>grm=tu6sH<{6j5yt z5ue1xcand3qD!dML^y?~b#B4{6arh+Xg4DKYA*!aWozm2r*)wwTM9K5L?hJB{t_hE zFpb`@1q_E2Y`w`Y;TKXM+R!Ux9dg|zeHFh1nQ$hN7kOT3_sZ3UE_n$x%c1zPfwn_! z02|O&nAkGr75BkJEUVqIg>)O8s$42xciNMn zCI%t$U~_vOQjGlm-%1tT&$0VTrvy>nMXkym5>{{ay7jK%l=LN6G8-C(W~r1gshy}o z3tvfrcH(kI)h=z%b|Axf&7D$@a}YaPPlm@zl=GFEZ-bg-ha(1HOP%9Ma0fqeu*V-) zRYG%Y>&Hqwcn!nT%I6i7IZ4XI;nlL|<#ii_h>F7c8Sgp<@>ai$+&$&XOOVqtaE<4bW%ZVt|S z@4GPay`0Yvgyq_I2lX|R6HD9cwndY2)Jo`(VoLdyY;vNyDed|2g;rjom` z?mg&~;+(n<6SOZ9!-}CqQk#YL2-*uEaaCCzZ6U8-*`V_|k;vo7&h5ja2f*@_#76^1JzU?x4zDx#K@GNCCq zh11rHO|7>EV{?_$mX0w;1iVxh#K(5nppr~bH0Y&GcJNF8TzEms!19sRGfEV%%4&V? z@Qf1Ma-?vc-sHB{WsWhn(FQEe*7bLimpHH5CDTH%Gm?`(EbV<5@iW>ms(V^eUTqnM zRYPVLl5FfeW|6VjX-5u7gHkfB2?Pk4E0P{G!s# zzkb~=qprx;I`er2mP|)z84fB^#KlFdbHUxvRY5P8x8l3~e35-Or7#;_vH#M(T>Zhk z!d+l@QYvEvOPnmpmi?k4+a-~W+v9m9XZA{$=X)BJY#Ar`btZU3|Ae@{50=VqTFG2# z0Z7#1K`pEnMwGFxgJU2M4s^`2CGkDRQLyST;kL#Ld^l+u9A=&ZB_MM_&}*)2Au4s}ao@SmHR`9EhWuiv9`HMY6+HXm<m?%|rJ!D#JpRbJC82+wl?lPddN;z z9nba;R(A*O9jko-FHvIAoJ88zt}HRM1tBuiqk!uI9?wbMvG#q-WEIKE*^v z8STJNkOu@?Ky-Cg`RR}wv#5pgjFB$iIaTOWhaEOCvB@6`L-qBc2QyrYp|Jz`NsZyj zeXZJ@@VNPu_crx!klCe*g2v+vK7AOzJ-cR(pvkh`dCri2n^@ODyYcqHPOtvOY&?qP z>*}u#f5K{S=t!20y(D;!2G7ok5SnlE4`M%0>pN)vU!53SU2W$+mZY9@C79-}Y6eMN zK(@z`k&$H6F_5a4i=SUit=;he>iGD0(u@`4F9%hJ(dX*3%poI?d0O>C_C8ZL|K_8xfVXT@sxX?#iW7&jQdm@=lwI9v^t3U&C>--dZI^J>FLp(00$ReVouiG3S|hAfNA^9| z8Q(}+PH{f2_OS?mA^ys6>e+UNWByp4%V5s7jjk~#_T!fqTE4Gy_(?x?OFdrGc8#K8 zBVCa|#bMkHwWbn&OWU9`%t;J5YBzB!LlwXGeidUrYn+&E z#ae^V^a_=JEzDS=RLj5HtD$3AQ_cNvh~$M}*7~IDtp$AKO2!`}1>UIZY4IM5w4Qju zNYN7H@ixmLR+SN_RJ786(G#HX;QkQf);l6=`VpE$NRy>L{ow$zLuBe85h2w(&mST( z*#~uokwrSw&c6jM<$j<`kTzMeN~PNJXv?>qxi+YQ*6Z zGk>Rc7&c~0*hiOT)`%;jI3CTUSm3Cb&gh{)s-2UG?30_epC&b%m~XR}47VG-*``?| zTZBlCA~_03mh-J~@~6`doib5gIi%<=q4Sd{W!Gtlm%qZ4w94GnlMK>&&N+iTjqAG~ zTEQZ78uvr)&gp~{7fK)qhQYRU+6ySH+Las1FYF?+L=@fob^j_YrD@5%D*j{#r=^SX z?7x69Zueu?G1uT;4DEJyR9tZT@!+Nt6hYE0O@Lq1fF|^*31rtZ>CAFFnF%ruAp>&E z5W{D-sP1`L z`nj*}4e(J!5P>qEpw}Dd?znzSE1`Sjv0i>t|Gjkm29n-4r=ol})zl;L*tszOZ-jz$ z6$ajDV#8mmMXD}!&^hQTwP?egX4?o*BAfA#f%f45Di2sRDV*^2^~lw`y%*hlN$So# zuWx;&c{=t-M2rHjy+=Hz>!?|%t)lbxez-&<K^=irCB(jgb^D_XdhQr z(2xmQS923%@@}gs)`1oIMV-DB{Mr}gbF=WpzFqUY(CI(AW!-u@$xlJO?-Owr>!7S8 z2e;W4tTxgSSAFRaMk4v5@blxZw zEp(U@wE%DZTNY`ft-G($I_ST?0x!&~y~b&{ek%PxcDe2_bThTYT?rb;bdMJXBL%|}pGCYqo&)n>JVtR{`=oY9)$LJ}+%aQ5+f zN6wfotNIIO{l=jSV55-LA;p!FI#sQAjqwyYS?BhDSoh!kx0Sc&%=lqUcui7U(=&z~ zWnW)44eO$T?D~^6GQcF$&kv3R1Kki=Oan{vg2l;rT#@M?+;Gjo>ZGPinJTbm@=*$z zq|K(flYx)cC7tZFw&@C!Cth=o9$WXvPp6-g0YECQQ-t-xG6#(Rtd>*PUX0E(~R zOLJ5C&WQ?`1f27ixz@>Roei(o^OOnjJo~?rYN_Ve${xfie;`$Q!aB5#YQ3b zelP~baXo3mx0F_@?gqCXp?L%XT-dB!{+5fxU>>`fyzR~4>PY8jbpqFzZ(j?yaT3Xn zJ0g)Uzan9(e{GB`Up*au^pV-> z+vq&3G?PjJ>wN zjT%Inuw!My)BAXIrIhoz5)aLz^4r5j=%w%#^L+(pUZ!4Hfw~j{_3hBe{|=w(*0$6y zuCCMN872odxRAF7Ej(Thvn>AzQ| z+LJ9Sfis??I`O+^8`9f{_0|sgt8H+6W)AwF<3G1s+qtz7f)kkANeqkV@Z(0FCE`K) z$9fIAP=t9oLd)ocWI*Nk-X5`i*A0{c{{uQmJ6K4i!H}lY=@v6&bklS7!+4NeLQTy@ zmlH(`^d#v1LFcdoFQ!xna$j$37fij^)@2YvqRsP;LP6l= z(BRk)w1tno+A?RuO;Fz7b;tun6`fwa>mXh73oA+ZoNJs=*KT=ZT+!m{8py~jW@i** z2X@z40nmSATHN??H<*N~iL0bo*N-QGHz!~GK z!_(mG)k)q%v{s0l$w1$1-$fDEx~z6>K9mu-8Cb)cYs5dmU%!7{ol{Buxg7m(Ol24r zcgb2rd191ziY-T?5$8_843(_`r)|7cARIAN}D| zG9Zn{MjFCC!$9Hlb@bHM z?e~k9274`X6<7RRDbiFk0237t?Gk+a6P_?T1C;*6u95V_s^&~$As>8VtMev1pDv`L zE+BV?bKwKIkNs2P*-Z+Sz?ij!KZ`j-&BI@w8#9=q)`ksWG+<&MjT~{pUtUD@C!F+I z2rke7wNdP_VT`(a6sFtcg|8g%6eCo}{%rOr}$_j^E(I$kNOh$pK`L_JT0cayp1xh&YsL&ZJFQJ^;VpBqhSMeypM?=lDUSda zq7=ZdX>CXzi3A=Q!J`s~O779H@pLdKa!JT)T56zUf_k7X{}`J8GOQMZbO0U1VX&Oq#(8;^I%rN58ugaia2bCW%Bvk{|&6R(|LIrYG1W z!(8$0c%5#ekSfbsAnVCAw{(_%qtX+eaow_$kIy6s-W3{HQfdkEjYNx+uD5^^20<o%C2TEVOe2KIMagk?LKOumYK60dnXK5S&@lR*}fSr)(AnH zPb>|Hq8joR0g~bzmtK0k@ z(Vqj&HtXo76S~nlyr%ix^HTIln#*b^>s%yV$PVfOzmU*)ZF)7)q!ma2)khCoow7Nc z!6|d_{qCb*7q+G(SS_=l_D@M-JG`Tg&S$k{)}~{n#=r>l;8@)wg;$dJ`$i`r_3R|o zlwcrIYXP1pmN-DMvVmt^JE+oesQKy~P3^E9NbAAB-Je3f^4C+q{R88j@46eh)=7ZJ zP!sCtGWr{Srl>6X;h3|!IRW$;tl)xQsQ%*@_}SebPE7yF?rzSu?k6bScA;hI1Ozc< z9^Kp5lQ*`oo#W;?cgrcj4@@9loraDok9oL!I{uUc;W)=ULt}r2=6>5J>etBF*CbjI zxVmGXFy}tx6T)^=_ONlLlNcTU`mq~DMEM0w%K*g)m1?qX%-JKCj^GUZ#MyJmfeApf z6hj#A=-B$)D>69{UB(8rTv^mmF#n~J$Hlm@5@9VgK1CJ}AZeO~vR>|pI7cZNSWk`_ zl^%#rlgTbbu2}qIQdU-H4{-(| z)GvldLoV(**Z8vNU9AOL4Mp|(MQgXzF};~4{PsMXN}gl7-vC&cjr~K+I+Lk>(u&cg zd+2g3#l$=u34>4Sqwx+@sbm;57$@jz3VpZ(9h7bG;n49lqHS<6%Uk{F&c*L~>MssJD6S6LWE&&p2)Ne+zRsuDuyD>80FM9vFK^!-=p#5 zw@ez6j$$1lyV0zc&siGJgqL&rI;oC_O#VfjD62kTJ1ix&Mj?O`B!%_Q)%Qnp0&>FL#<6h&)WH#u}MyZnVhEY?;+8a39R6&(iwZz zNpTK-V`KVl^E?1k7HLB8oXuUAV3eell%X5~m>hXJGkPFK6tIMfGY@Ch1ch3$qlyq+ zLfU|=la+@uxNaC1c|9OmNBLD>Z|MBmqZa6iF6@OPXo>Meaa2A&V~>!|5l5NmbfaGB z71A@Yc4+ZKg6Uu5Z*VE2%b_?j|EZlh&v%#j;$FAH@WV({JnMMOdVBLM8&}_YIfjn4 zXi}OZBOT9ZxQU&t=5vYubdqiF8lCq3AZTv?-SHG_&;%O<4pIu7uQ@9}dz}w;%cZ4V z)&li$x+@9FMgn=p(Kw?=Amp@8E=u=6<=k z_xzmx@$n%{zvN0FresiEQezF`+VllMgP@Ju+k|ope7CF|cyD-xKF-lukprccp=b5& z;@fX~ZxV*0lV!=*+XvYL*aKUg?iuoBosOVEJm|J|+;sS-%fzv^S;43t$vn@72ts6B z@mu@f=xk^-amukqKV@axp%$F+gh%|Bv#BizXiP2BE+lI~cBCU+}spI5iz& zodYw0*2xA4QUG$Mh)|lN{>m%AC%ocE&l*ABm>K>X&mO;bxl4MyNAnDWC^eyMvmwI{ z$&dF=iMdWh(QrY$sObpN#ge#jmLig}qj|eDZ0r>smdo;B% ziL__#cS&vLy|RY)!^zJp&dCHvja9=4Kw_FHQsBpaq2tFlifHfVOMi9o3GfnvS`oRqSoJd#V?q-+ZvRg?9AREu)9 zS8{S1IR*ajAh?W4mgh+suXU1KL#wvNdg@GSn4 z=5C@cBC6=mge+}~s6WQ8zB%RL;14MNzCpXDiWqp0xf*L?JdH%Su3k$;W*X>~sPj)J`vVswrq5S87QW8CY2fm0}x>YK#Cf>Hl>a zv*7@hH5Z=04=eiq#p_sYz)ZU;#_DE}lh1CaX9|SUzWc=b!wq6^41fqjGlC#}LhL&J zu?L^Hnr5{+NOBIMx-bt5SG-fvnxXb-O?Y(^Cing^5Vox*F99yF4Pv9BQY67f4H*&T z>>z{M%Z?i8r7IH_!*0F1Wo`SL{V2vu^xpqX2ji$YViEDu!feD!v-9#A^=dsqk>(be zp&ZYK(K{gPElRp9h0jyxj%l-&VRS*w8GeR?*RZ+3UB({Hr?7$UR#|h| zpAH=(StENt$qYK;T;oAjT4WfrDV&i(D>-YeO1r6otp0hX%2F=gBb$p;3P{Sy3f(D{ zODM;J;w9LX;V|@837@?oe{pWF#H-C$j+o9k`I*!Hz*(`xS_e}pHflWg9Gu7f=#L|) zyv|R3M^eA+hnLKi0e4TMFY0ZpUMU)$$4!`=JZ5@29(~0jjIb8*8JWjU^Jk5RD3?~A zZ5R8-N^K)<5oU`r*>e~`ap{njglb%Ry7O=onKqv-T&Hx^J%|453F3G*JW$`Yi(POF zwU^h&q+Y52S4#X{n`}sB-vdWLpLpTLZNIuRlIEq1qx;MMri}uHic;XGv}8IgZK@9$ z@p!z8+n2M#PM-1vQssezKva5~1g_i3t?%~Qh5E)kd$oEWER0wFkzbEvU$I|rhyG<* zlM#M$mDpZC4HQr+S{-hH2^?E4tuNuwVx1dqs1 z78|3U>1f6isv#DDJ0meB>tQ3R60^h_p|n4nMfl#h$IQ%*gJ7m~Tn_{}s=-cqB{UNp zyGBDQkKC6%-3Bh@4sBsK?k6^)mH3puQ*RF8`tYp8i))0%-MMRbj;20T4*$VJ;3rMb zhQi(C-o0kKHV>xBpu}0j2X^H3clSI;`ab>}@LmwVn+ZwgoE}n456q946&vJ&`?(iQ zw5_tDGDsfnlDuw&cH)K12;0o$_LJDFp9RHOC|Vg4GHDF^AXu$&bhtCoDQlzVely;D zUE8(Ce0cwj9-nX=H@V652|msJ-;Y{XAb<%V39i|_WKM3Ttcq?S<-%W~Yx>}4Z(T+4 z8a+Rh+y0N(q?ih%*8O1dOh(tTv8bHj zH`7)+XL&$WIyZ?moNZ%BLk`N2Vm>e@p#J4UZsWI}HzYMGu>rfGhB9c%8F#m15duJs z(O{Jb&(KJ#s)SO+P;F6hWuGaFnc-Vvl2uBX?De<6Y~s?UER)sM zdH7~Hkgvx%f(~}>*OE=Ajfohsc{sO(3D_#1co|M4sq`H0H*}z*kUhEl_zH)2;zPGc zJ+8z2cY1Y9ATvL+&MuqsxUcvl;czao7-ECOpN7cLX?GXhkz6hca>?f42S5joI$db8 z?v73jGT{La9c?teahs?qvXVj`d{_7MX`W2b?Ter@-|AjjT;Ezib$|F2S6%xC&&l2w z#}nrSvdEWTJ3d)Oh)H8gS88~N9oIaQXS+6)~*Zl%$E37BF z50awr#zD5`Ku3|=tvA0vq0d{Zs$N%?nV}susHn?l5Ai>#Nd6xZ805M(o+Mq8#uHQB zXlb&QQBwoGe&^l$+eg=^{SDT-4*=x|*F~`MPC|Jx4=8_4wjV%q3YRsjQ zsFrBbLefF>1QdaCk0kEW1Qvy^3Dcf6gj>7kkJ-G)@*WL7nL)$K1PZJAx~5$`hc2EX zcrz9wh+7sRQjyejC5*(t#i|obf|>PWk9onccK##r54xl^F#peP!QJhcAI=;+1vM0_ zbJ(>3p6=4JBBt~uO@kbcyGWjU!y~J#-d$d2yqmYRbGo`{#(G>wUBzLXx-G{VmjxB- zxf-9xRzL2q#s*(sy_+bmH((? z{s3pD8P@8sG%!5g)bh!@8e>NqKwDhMoY{F6`+V=qb1Lf|@=#`V^QJqZH3GpD3DnRc z=2#dJln|=nC8eV`d?>1~m`n>BMX;Q6%_1XPA{|qK5R{wxJwtI<(QR%IngVb2`bS!G zHy3aEhWwg)Tio@st0vTP0a6JTq{?D}!2Y%aTkoWWq3roM%Wk9UqNG@+M;EskTp2mB z1Zkr?;VJ#r22t-!8fi>3vLuFfaJvTSi_}bplH{k$S62k;d@JVCe23VYi|{icc9!&} zFny2h=TGj5N3iio|M!VrAz514+w#NOL+$lxv?1ecu%tKz7h}|nSMDBRHXZdH>Dpz2 zBSzm?ByH>Or&zFw)jWu(^PxiU-Q)H46IyoNE6d(pY4gwE;^%4^STzz@!BTDxu%gn| z$xy}pRso7cO&_L>Kye@eT17-hSTT+y#g7=aHi&-w=CU;caeNX)<(wied_)GwY?a7l z+p-w>2q0ZT`7T?2HpwkVDx~_A$`DWrHq+Tl4xd=|^lvNB6$Z>?>GyYu0Uu1uzFhPE zMa*=jAO|6n&=W8c$ieRufHFd*xYZS@mVyN#=@pdfw!{dGTLyN>H107h7;pT+~7bKPwDm%%3M}#{6bRY zO3g5wvI|17g$Avf45_~DHsLd4CQ20W(is#id#aeaSVAnU)qV86TIvgG^3>6Eq#d-! zb*w-g^o}0Emrj*W0nB(g%m0t5w+xD_ZMwFDLxQ`z``{j2fPgolin)csM@PN;P&g1uV0}$yqHSJ(G;$t^8@_vOWOrn@ZT&(f9Bsh9 zl=w;A5%d$%?38rRrZ+zmWBiYRZ81oO;j4noFohN(a!3pmv8FAKDDKy`wV$D|Hm74!KQr0>>5;mSEHg=m9^~BVcS66p}aP&51^&iot zq@-d5{2sg%lraPTUIBf&i6#({S&ixm-FXL$6;Ic@WOWzc^)1x%{9gx4EN1=Dn>u0C;J01XkmnRb zO{YJI8iy3G?-sh|#A$0$9ym@9X+)d>6INa2^B@*4zm3PLjcs5K8{-xHTxh@A`K8wX zUm{zQxMxlxelddxUmvzrr||U0crgwZSgG$=b3EnWYRfhn>9t~o8?%coSwFts{G>tA zH~o_oIaw^w^a!2vGH7Noc!l%%k?rK>sng>c|L$(moH|a}U?oW>M_qc(ffe0|+eqN^ zu9=knZo=X#*ycHEqiPI zohhlebi3%D;nho<;f8Q`+uFJn&cpw7o&SkD@R5+Ch~->3pXl|K-7psZhQBquFjbF~ zJXF4sf98HIw550#y0wbsmD_vP0qB;?~Hj9 z&Tm$81@_G-xrY&|$l1#E3jeItIobIPGFw3n7oO2+g<#HB zjxp1~o4Xy9j7&!Jlv@T9GEfGg?5@KLX^-vMNmCnp>Y`o8>sr6n*j`FQpzD4>TgCZj z+R~4^0DUk`d3oJhuSy9kI!E^UV`i7$_r7Bz7ne@G`qXLX!0Px!(GNC>Q?01c zFs(t1>WB2ymhD&3mp*H=ep@rfFOxsItV{SCzZihEKNYrr7TM6gvR$`Z)npa;_VOht zbA}#geuSFEHNlRtEB{w)gC3S*Je4H*H%Fl&m3U_od8tBom?Gf_egmK>hg_|YtdeB4 zDgIqBAT72vDU8ImfXj({P@nLveDlrhOcz`=cIY^@;Ts8JIcmT2x$`+wlTd~kBEl*x z7lFn^!@>`X6KbZFk33ikyTG{YD?Ru&=Q?(fkjin$E0ri7D2b41sTG?`4zHyXh+h69 zKfJwr(R<^FYq2x(;tT~`eRE159w8+WT}k87u-Hs2Je}tPWd*-Iyug#0md~{?|y^)A+bh3dz+Tvm{uF=Z81Mm57!MiB&rqU?2tE z1F;3oWu3Po)r1kY94pb`?4UFE+MXICgJ6oU*0dtwA5|_|2681iCd&{16^puHWE}CO zqCLlGaB~1vx3sINE&2EAtp`FQ-Xw5bA6y~IToyS-mh2ltqpn2zNwHNUHf`8wTpTfL z5yk}ZyJ%QtezR2OFDlrzjxC=HcHb&6P}~x|VPbL!jx`eD2KDTY7T;uV%CRt5iSETq zn(3+30~H~pu=#}lx}d%jf%4En?f~Ue@lDF;Ecy<&ef;e7X3@kw))j8VzJ27g?v^&n z76?PG)f9|e_s<>V`dP2LqgeP-G4(0^pN^qq;4Zo)P z)G1pZCTcV3bqrBJPcqpX7Vr5O$E`+*eP!%+j~XK(vj03OjFDC4^2h<<4$`diImEnP zUxJ7?$-cVMF6Qt z17)fuM%ZBZ4W;07(J-q>%{>;reSk*8;Rn zJAX~COZQN|-{~r;rssPR0vrJX7h#Ie!42DQWvMy10j7mMNEe)1Q_8B_!T!px^^Ci+6|(P{mFS9B?@rnOkpYxu7JyUG9E>6mwCed8xAtW3of zU%I9$+?(5FaK_k>go2!+)9v8h<)48w5mzSlViXE7s9_aZKRbbhy-?Fl_u94;DP)!g zT^;`dM1Dp0{xF&XGFBq_gI&6G7v9v!pM?Q|nF?7Doa`7%s!|eJrlGD5LVon(Mr_LX zNR)cgqWxYRCH9<2X>2pRZYSRH5uQ{m#Ou8eRSnk}nQIz{!|0V16h$&jSDoTjhHO>R zHjrHCLRiEZ$*sd%rqK<5qm1JXt)%`Wx|>QrPIz#Een{h`=;K&wD*K~B&O}Yq%3f0L z1?fe6b8wvSp4J%J++o)Y4LpBc$2!zHxP!$_Ax}r=7@C5qLD=U~0HqPJ{V8iz8aH?D zuUrS$Zt*zzWW9bzDJ?iu&j3dZ&7N9~s+T&%R6J0ks&$TFr*aZDxK~rO;lf_n-LlfR zg;E;jGHE2`HxVQ^Gj+rKq~vs$(PFs$v8k=*nxRYR7%AD${UvVus^Ay=v52gL7Dpw< zvy4|O@`eshlEzDnUk8pc0S3nkObE0WoHYDwpLE!qp!J7CvM-RPzz23WYjCc|_}?2& zCGatnK{YCHB<>AvYzp)J(4;y)A1D6fewnqml&oAaDX8!xC&;&f7?Lv|P&W$TjrOF` zS>tmj@X;Y9QEK;4U8I%_YE5v?LN==*sRGH&Y2riB+1({RMt1o(rGUoCpmTdO5R8g@ zF=ft1mITjfl=TNkE=i@Ow{JNhWLCPJBL98lT9M7r90O%i&LVS8lbS-i(lke*On*(S zRl;e`!GJ)RNly-1`Q0MOetV~}q-10goTS`%+N=(`rI!wy8H46?KcO%ry3o$eK;;ry zoM9Di#F(l||JI31VN}UM8ChE&kb*`In*`f_a z5p9Zj!~8P^jeBVH!*Ali$mr3TaxyF`P8e+(fxnXym*eQeQmwVb;QSR(gzJVzsn~Cy zBs7$7UpDNp1cqldAudkr|L`d@4%;^pHLN^Hh8pL;Vsx*L_nnBivKT>{W^eK$b(1hH zCZH`TXQ=TeV?2qBk1w=2eR2ME-J)fu!N!~8_lh@8kdQOP`qdJ(2 znP1g+1L39GT3jrNl^=j~RTevsG40laVuE*yj(E$eu9kp4a8C8)LcUP3fLJZdndOlkQcK}V(7I0BEuHZ%ao zAS5E18BHh(w+_PkrePRlCs=6l%b8Di<$2!*VtR5CSzeR*4|zNzn2q=f0N|jZZ6#~l z8hV2RJbSLGPCL$o^se)9;`SfvNy}2@x=+`xr=m`bMNh4Qsf_ugCJ@0eoKUfe#qGkx zgh#iOshPS}w2i~}fxK7^ePoh(`iLMQ3QARRs4TubZC9QWGh9O3IE9*>W%EWUMdq@`GHF403*S&d4DJ}!bSoGhG^FALeFh$jP-qwant6CXH!^RJNT zmxa7qp@vx;-;k&I9#!>cW2PSD6>?1wr)B=CGU|ruE9BD1E-iDS;UjL-()N^NmA=p~ z$lE&NOqY&e-?cB!B9s~CaF4X;qh3*qBT`?Li9NBCz?#VyHC{V|z2Nl{Z2Oa2s`wH} zk@C{>VErl7#k~=;Xx4OgzO*YI%%YYhjCsP zgBv3qkW{+awA3o!q+v;@>L@6_OTQFiF_;@gre)|###0$=4q+7yZ;Ltd2?3r{AzJB) zb<<%_bX>H!-y%}ZK?~K`zeKEe*xJ%!r8TKpKRs29@s^yLGSnegjFB^yXzMH}9~LIDy;-MXFb>E`D$9M#6&eizpeLJP`!FRVm+&~c z1%-3A{(orOver;S*XLvwHiZynS_G$&!f;JYBDRt|st|Lj7X-bdq4VEx3v7~|!~T&8 zRc;Xk%=Bt)_$8NS7|jYMhLi=MTf+BEb3j-T=&%{FR@Oa%`7A_-n1^{f#TVy)h;WKE z;W(wf#MU;RBaei0LT-F9&an7{VTrxHE8*iIml$>12WyuurMpipAo=GRs~UF3lCY_Y z;z!KljtbK%-v>suk_#_`Uw>P%Vi)#24RdTzJfZ8j(Lv zH2ox%UolD?(jc^nE12*dCx{7xQJ%32Flbck%^)X6;l+Ps@=I;ZpwrO0Vj1pk?h5>% z(vr3;RK6hQTq@ltyo)-HHSgZJJZK*-sZfx<-2|nD@ncY~_7ruWcz6`%D}8JO2ODJ| z;crI0nos$BOBx^i`;?>>Kk_UTi!=BjLC^d{oW7mYU|bxulHCg(-^ncIGL3AJpn?bp zCo{K((=9Dr4dti+?XNO!qi{szfEF3I{J3%ivd<)Z(dZdnj;c3z?$;+Z{h)Qn>rOzp zo}rv~;0YL=^QCD&gWkl_Ws$Uk+gEqy!cf)5YgVHe2{!3*4wU7~?`jBDpQJL+0*X_o z!|yn3mBd^g>QApx} zF)x2ME=GIaJiCwhy8{FiOZQ>Qzr<5g%Jc&hjS__{fZ!2pf@h*BL|?P$ImN$zf!wL? z^N`}3wq^el5Zxwu0Rp2(b^;~By65`Cq}yfoU1vynIVzgoMY#I;4uE=f?$8AyyeIk3 zc4J=u#QOrX`+P4#>~jxUqWB-1uEgW@ zDrYJTgN8>yU{~5pBwczqV8nMCww>1w0o@oN_yHe0MtWD?8+R(=MtyTR zomVG7?aA19Ha%@WVrJHD4-7pY`20NZysP+134nYRy|ytrZ>sG6{z_s1e$b}n&+t3d z($&=!AQ9NMJYhWyj5PR57?)ALe#h&7Kj(jBcpfu|gE;E~K$qnzm@ol-2E5-wP*WAC z*Szokc>NP20iN)AxO%5QP$8v+F3|vXr-h;?KKGhE6p%OEXCPd%s$1^YV=-c6#)B!( z*J|*SssuT>T}BB;*(4RI&Enj6{%>TAE1o*Pu|h9Qcw;Ypp-W0-826?F#Kcx-5iU;W zdD+I$`KD>OMc=-g(1@#JTK$~8i)#>uhr+fhpHsw_+;Z8kn08EI8=K7~U5QQwG;D$^ zCQ~{l`)m8lM*{vffj(wgqh5hyeKdZXLDp_jhHXP_+ZKf$A#e$vc)y?IY-ASXEh-Dj zkQAKSVL#rCU~|4#@&8IW*0=i>l!iw5Xb=13m4)$o1QAHv%=(381OB#Nvpb;)c159( zqmacb=PPUK0<;ul;yi21_#4cKp{Mk4-fJvQ;t6~?@IQs8OoGfE^gA{Z`6W<_%mT(Q z^sh+6QjiVWPpJuXRF;;AvE!bZpAzBPM*}wr<`b6`f?4PrNA16vTjyR-Nvb;1v?|4+)-Dt@ z=Z}7A)b>`Ll>5-w#GX9O+#2$)pT^HsaGVh*6sPgfpXR1pl#wSRH*kTNPr|SKmT?JT z1A5TUDR(~9uRa~ZPvP`~lpx$#tlts)=X0;q9Z%@AxSK7DsaA+4c1Z9gG9jTYyT+OF zcUfgDL^vo?B{i&J;XhwPX(ySF^GFKj)jFo5n{^whRyc!lq4}dIaR?g-Zc8mFw!LOw zed?AN^>=PA(3p}tXsfC61eLRnwd3=3r;~q}%ia@?VI$Z7ocR4M%)=VgLsc^n&#I-d z!CWbs(E6i>F5geQdiywZTnJu;!Y9(=EttLu0hi3y$zrHnoNwqy)(2RdtJDF1#^iP^ z3lfSy*DH`+`yZ^F((A=aocu|V<_^%9(IQRnRqPjLNNiOSL+(xeWzfrkFUeK>G2KD# z1*n)qu^fVs(To^Ew_A!1M-6(SJ#N7P%A+gaVYlXXmt)g(s75<>HAnw`LYY&{k(fht zFakR?BbDB841*;=#45<6@%*ciQ$*A8xlg5Kz0nAcXup};YooEFyk)fdb<3p#(;yir z;04d0NNoZOmZkop{|qICwNsh5EnxB>8i!6|Ag#mgKcdFcp8xJI8FKRY6W0oPbVAJd z){xB!f*~X>5JG^rTo;{$2q*;7j2(jbf}}IT13&5yx1AGKzPYEN#iJiNina}RRv#2w z;V$;A2pdV^RvUC~dtpCWvbs-{Q7O@=;&;IL{J0PsWN6x;kU^F)4*pFP$xk}wdfunR zjW;)JkXd4!!Q%5E>&z}II`p`L#=$Q68zM=~(l6ZQ&_21mEv#5`Brwu|h7z_Cyec}?GyMbqk)mNE_s@!>V;l8_ zJgopC-TuP^ zl@6?YLlBDsYC74%U-v&0GFHWNg24eul_ac0zY*J^_9UVfF*EZNMoKX(ktn~xyYwb~ z(RXCyA8um-{}IyjoPXtTaSC6t+X6vzLv%>7a^92S!=lcn@~)ctX{V8zMkXO3_brIY z)lzC1IU{TND=2#e4!h6|;H&Y3*kwz@Qw<+eocgHTX}0hA@EOKz@<$q{v{_FFvVY~H zTq5TqRswTsYHdb@ovgsSqYGsH8^{Hj;qGWda*sfVln$xHr|V{R5vo0^p!a{c$++L+ z`?_f1pO+UvQ&Kmb3dtFM5iJfCc1Ni-w4*KtAFahG&!4~_C0_kS(uBcwwdQ9wT(4H`aeO#{2OIy=Twi)H_hC50|vg0FgOR z7~W4{3NYmrT0}cVUvR{?(FeEmyqshTd8Y>yhBr;FN`!mPVJs@R<-5VMg&IqJB@KLsq*1LOa_J?fh8zbkN&L)Kgt zb)QFbx-&TBAC_}oG@Aju>eFe*LqAS;Z_L|$Oanlc8Am}TV`TTaySp2`%4{&3x{Och z4190hVtlR(I-dmJSjhXQUe>1Sy1FK4gf0-eulTb^7Zv~~bKsVJ=pC^Y6Ap`>F%WX! z+&rwkeu=&Qa_Z)^6UBWAkQbxhG07X>=X^I^KEEV%?s3+TO*s*}Z$g~5?F;$5?!Vyx zzDN{-^A9S=Z7wdS2hJgCM8p!!5%A@Y zwEcGkb#Z$C6`?JCxCjsX+U{ZCwDKRkgTl7w#g#8>au)UxXdX?0KS4r?0*K{f`0{av z=|!jTMiOp<5==laX2lWD#(Ke1umGMx1#z+7KmsZxv?}=lVSy7O61@_&6SOS8iVoO3 zUKreq0tvSaA>rdUj4)>}Tt-pcozHJi%UN80@C_lJ&ou#r#2YZ<;!Kmlp^boYeY&T* z^Vw|uGpXQ~fr{frT>KTmqB13x1`5yRHpf0S_f_G6lgH$)Cny8Scg2(ajuHo+Pom0% znA#nkEoD%kWK*5U_5aE%&@#eH;!tXQ9dK90kPB-0Tkpfr0<4V28{eeYQ(&)AqjimvQ@hhE46m)X5U2H zIEyXoUF$e0?t+`xeq6}u$fre%;J4pkEB;moXVq8Xq&oU3SkhhpVEaQo5q#|xV%aR2 z_PzKINdC+TRV6!i{pZ}QSp!=3xZmmy=>r(~JAYuiWM+XaqflYt3RxKv^Vh)5+I02< z;)^$|9z|2fFAR~v6p{zb^Bb9-dkd(p4#h^3b@#xFalDKQE?p4PUf>SFGhC(zci z=CC?ngRT4R?MaW0-N=-psdj@V-IZO~sHp@3$AenwW;-(oadI{vs*g7Cuqc z8=*cgwpMReY<9M{uN@PL*%=m~;~g@;vR%DMof~hoj_n1AvFpk{a5|GP#7l zX$e-`s`7U~&07X=jXYRBtL=d}tKb1!&uEk42DD$jy7bMR#h%L?)xWguB} z;2ukxatl(^=-44C67LCZQqhb_I89}q$(1>63i~r45mvY?IKYa={t4bHPHE#hqzMtY z7^4rtrN21H`YfY29;wWx9L%tTNv>?n?M_qJ1c(;mQp<2n? zpN>!PT{hz1wBA&ooX9QcI<7VhB>&ZSRSc0c8IpktR}5T}ZwQrw>ks7;5|?UApRT0B z9W&U3p}IM!8V->ro>ZJkY2Mp%yH}T*zeT|6__CNvgjS^1&OD#L_)Ai$RK63l3xq0K z5m@w+nVT=I&FXlGBIkQqLG?TJ2XSf+U_>b3(E%ajOgAuhZ$S`bbD& zga+eip?zsk{vGh>weV#`=wAMTm?`{T4O6un2K^B3MJXkvIjsMXOYw0QYf<-*I8Itq zRwHd$3?dLFk7HNh;*1GqL^A%pCYC0qU=~~miBdA&Va4%;G^qzl2PL6R>O~ILe2(~y z91S@JeKCWsJE1m+c zD(W?cL;vRmU`1N_h>L^-u-$4E$>Bn^@bxJWl_*HF2N$7bwo93lh5b_`;uOP7A`=AB zhjG>XT`%}P{2~4MK@3MU{9?vqeMu}*Q26=#IBUxj^qfH$GSs?|IBQ30?3Rl#6^saD zs*II(P97q{q4LR~$FiKVC%n5T?(jC7rW9whUT;%ljYs6hFgc1hNIhNZC30GF4^~uF zM0ErWaKW=wMGR^B-x+I4rtf*3v%H2o>Rqvaergan(wq{leIC%w*+F?bNAWnzdBOYq z_>07H*{e@0;x1dEWWY-(CPiD8UR|y6v!>U^K#b0|3BVf7#qf$+TIjWbnDn0K+AF5Dl*YZK~uUhxI9OOIu5Z@~{p)l16ca|y3!L?D|!aJD~b zZ*hw5Gw6NC+BzLowLqQ&7*nX{S(X=clBcB+0IYitv#_v`I<*g6&NMBFKV#y(ncN*s zc;{7)8u!0%gL>X7DG;Hq|?gV1{U~?H|vo9h`F6&de5W$E*<n4r*Ocof^sP>OG`*ijEpQip3TW5 zW$N&{>{e8&KCyq8@A~=xag*(6X%AImyR=(NxW%*?l*y^EOmj~3Xa5TGPFKgS8vMCO zTvrYxrZ}r6Zbi$)><}6xBPg*}9&7pkD~1Rn+mFf0A(j$g21|9YH{}!TABci3F@@H^ zOYy#ueUf6|n}*Kg@ror!Gxy0+?PcHdA6*9k%hIi%B~DSXqlwNiGk<6cbjCK!ycFl80TY$H>a1Wug=%}dgxYa}Ef(QK zOInmC&ng*_YpU~zdAC?OUcx{m~2m~BHlhzyo3NTvn)Lr+L zJ5XF8ATGsgfiU6*G{UHlGo|`bT+KC>ExwjaY_xBmF*H6%;@~o;aXH~xH7io<$SCT` zkAvx8^{~9BzxzhNylQp7fhvG7+WSr2yZmKD2)>V*+{|v|DtctskCQoW$Ky3WB1b(DT$YA^8Olbtr& zgPwTO4Cv}2p7)dQL-&4C8Bsg1&kdL9`@zhME}yD_b}ApR%SviHz3YCQc(Onv{?FyZX9<_fijn|w{oJEtMrcJ z2J?bA!@~2F$lvC~MldSTfyt;XQGeJ z8{Z~3B?#K4xlSA>h|8I;98nHwyMTywPGSHu+5lQPrV*@@3ukN~cf^K@T2>&~wk#13 z2QnqWQ5lrCI7XJQ4YiGH3_mQskk({pxjV>#$83O-TPjZYD@VP$yKK?#B|N~#e3Fom zyP&*CB}!TwBhPG@z(RH)7P>0t9Eu<~NK8I~7azOj4VO+vHXo{QXLBzo9ff2NHew(j z=AvFpJ9{0w3I5E!)BF#9kkDv?Oo2gw-OCXRM2vwR`8`rx+c_y!kmZz~oCd7dcGd*L zY0;>}9g=$8om$02MRpzcok$GMdXDc4N2%7i%`gw0l40uL(HbTxj3jla;NT%Vi%BPQ zI%GOVpg}F)U@)c)o4=p9RVJa)p8$=vK#)2_giSR?AQPcCs!fYU-FN&k>|~_Kc8yRn zDkI6zWAgftyl9&WZ~toWwZOKWu^ZyI?6VkF)gPuqga+RpiZ_h-vM%a+o_IcNJY-F6P1wEazP{MK zoOPZ*Ozj*W$O9&^Ssy&|i!_sEl{idMVYRZO?;Z*Hq~zOGJ0GkHvIyS&_7VC;Bv#vGHKyFL@YwW&1GuH_)c{2lU>Mu;0Bw{gJiuw( z%A}D0Gi&-C$S62*T?R(90HCdN8>?n>zD!k?^JYx{)e&eLU)f0>eoD3eP1XiVp?Fx} z9av^#Xi7f{@&9YIG9pF@LU10s;W|2;;k*Ih6ITYnwO?Ld&Rack1RhH&iazGpLsdC_ zdA@l?XLlIwcjsARH6m%a5(5;wmx45P43q%qDZG_`k3@CrZyH{e2L*4<}-7& z4F9Sc|4Fdg%?$5eX!Wm90y`Ml({tW}mNp&A})Pe7$hvNZ~BF}<)^%FGl3r(n-$Q2rnKfxg(SSaHgUrK3~5Pu>CScazeHfE}{ zL7ugbS0F{Mq*|z}UC$=YJVTPCJ?lG5$6ChF>?)d6dC>p8{%CTiXI-!8W(7rQQj)2n z^=Vutgp*2tdq>^%K)&baRnEm1pW3I-7j;u_FbQ)g_J!&f2Z{dvZM@|27?VG z6=F$b=cXG{(-Hjj=+^cLWnaeVnIOIvwNn4iRHKf0+k(=^c@2j*SqT!dZr#69Ps60Z zk9J?bTML}yU7-1zWTwYO>5*$8Ks?koBIG8Zg-~I`RUQr(6^KP9BD#R?I0W)E#=+?> zvc=gQ1Fv$t-K$#&d&^Ri(7@mrpY_y!Fv&ai7Jz9Xq{+O|r!AM_aoQtHVbPT+ZM|a0 zDP`dCwaq$nzil|U`7T#1C2+K?C?OZ+g4A#T5nvcI^DmY|ey8ENzh9dvjt6wHq!n~B zxjyjh#^TOZhF9->Bf{uS-0nO0kCwIV3Sw3-T9#knBC$T1bG)1gHY-xL!~2xt>tn!ybM+I9(Z-=_n)I^rp082(0?|8L3tBS41pl zx}9B|!6t&rKnxCym|U=wg27r$K!l~0VF*Q z_>hICL#LuQ!pbY{AW(NJM%k(TcA6KhLeiVebM79dG9l*N&>#B-D+cpB5OpuKMi_EZ zQ`SBjwO4DTGxE2jiSEVvU3Ut}%M3|THNopk#w*mFp#A6aehk~rF#YEt{aue1!JND9 zyRObxm(O@fEox2U49=5=RTARB8X7J*S=_i}ZfkHj_PrOne)6tt0!V%)KGjaqfEws7 zuoumLy6NV#@AmKJJFxS?jIa?@@5Yu!T1#mM7Xaar&4Pmu)GC>HgQ~yYXPzW28$SF1 z=@#=U{c2x3AA)JtFfmjk-U5NO9S#yc0r5vsY$={~2o24q0 z0B2frj(l2rg)F`ycL87pg*8jz;O^<#^Fc*7tC%jp$1IJ&BlD|kA4GOc@gH);FMB1vxvQ@wktQ4ww zWF8xGlExEFMVSlG-rREq-U&^rCEWL}2i{k@?#xX&Eb6*lR9T3${PzqL#aPMEaV_n; zLy)RQtMN14D1`=glnXFN5p{b1Mi=HZuy+jx9f+-UzJA>simVv&)>&bwr54E&x%!|h zrmHre7F4f%whGj-1IZ06}kkKvLZ>!qK(ly^i*{UWM@&IU-jJILs_EE_L3jlI(Hx6 zvI8bOAO02HDc79k2^PuVrx)j4Qz;-?Ca!pv{{nLkao{bu#l;%^?AG-h2Z9oD9XUqoj8jf>NtkLJXbSCa)iK`I=-ODf}YUogexYS9giOg))iJy0`~nFtL%h zKSmJF=F`xfKz7!h?}-o56SIp>mq7nAF(90;xoYEB@tLz)SLSR3WMvIFi}Yc0Aqb>s zy*p?ZEL05h#y`GE?j%K@iZrc9+L_J02KJVjJ=INhx*U54?y$y@xp+Z5Bh!2H4e_I| ziHff`L>%zd1g)>n4Xv+@DvyE&(FnZM8rB~uMlff{Y{CZZPu7^=y%0vSJ#nC$g6ykM zwTAQI9(|x)!5FDWc~3DeU0>A&03$k4{>ovLNpRZtzfLR9l7EM^8MrU4#5N@ zPlU4ugN(k|n!8ma`3Xxn`Cs(3f;z*=478sfBuJ2|Jlvy9!Z{04xsRB^#&8vQlfp(Q z792%}B!ISt%u2nLOmm&~6hDUI1xw=UFiWb!N+>EiIXYo>ejb#5;jREu9Z&DWak^ZK z)3A3X{)FSTfQ{`uT`YD^7f8JlvpQz}xNMF^_~X%w5}tDaI)tn*v@e}mQgBkI*O@rH z`PT&9;K+t{lKp*qe9<`L+7CjO1~q*C`gtP=GK#p%3{G=Gzz%k z0DI5Up)hpG{?pM<^hnSaHr=wqs94tUOE3qPw{@;4ad^pmdlxFCx9FD0y*d!S(xrmi zpDK}+=s+N0Z}6CsOBo~&_8 zG!4#<1d92OqJE6zja;}dw*B;pP;?GEjqyKwEZ}A3O73_~{{mT7-qflvP3p$k+}=b}vYty=cTwXAC*R^NWSJaoRx!W!&2F-IMI^`tsQ$)3LR+o`;N{tv8>mvx{Hq&!{Z!eV>%n zgwFj?YCAe)=Qx1I#bMQ^<>Dg7H?!lcJL7%dIuw4A*R%oegL;kL-{K5gBcU3P-8iY% zhrJA7H}a^aCmY50en76+38+WFkLZ?XN(AcFNWuFtMsT;e=*|HyazxltdNSzX0o-r; zYFH+kMv;a#Hc`MHB02fH81-_qSkRlqp#DCAQ?J%B1cr7%Z$>@GOWyA;5M7h7t?Zf? zLxqjK`~I;E)Tg(0cY#@THE{RS9<`@u2jEAaIdOHEyf{?v0sdRZJJxTQ0e1|bYT<&H zfI@}+nJGNHTQhY$TKY1O^%LSqiO0mbODfyGotw~j-zK_=PtrX1S6EAic^=4V1}p2( zmNk>*Y3b3?QH$5CmmJ=Njlm%2n2Rt_ea=iyRxh~jBR$gkI53Zh8bM5KT84eOxDj|6 ztjg5uK|2cK;~%6JZQ%%|k%$BA~x!Dv!YpgYxvGAYA!>*<17?o9K+?Z`RS8oRO{aHWkZg@qrXKHcI zz87dayW@l(EmV?3GO85xyC!aBJfG0*PZ_*bko+wS%HO{U^hz2^gYf?i)MH+U^=lMn30 zCh>b#rehOJp2#x`zY39N-#d5$`^e|#O{MA-p^I5>9>Mgzu=?I^IY)P~C1lV6E79KZ zlPn>TS0F35fYp&^CcWa^@~L4wL#kdBTEHD=R0e81CP6#ThM{U-5VF?YQpN2<;R9*2 z!!!TuqVG=EfX>)z#{zf-uE%Q1ccRlsD1=d#wKxDaq!h?y0#C&eNcYo;B1EykN2&Zq zD$1EVaWU#Xj8_sgHLIl4dxAb`^xP5I3#IL2#QahvU-eao;_MZKQv3K@pEEv)9Bc77 zD~8SohyLG)MN1IhIRm5Nn}fR9(?g9B1M`;tapwr!BQy=sLa>#!ewTF3BAGnKZ~+|- z%Z6gj#t=29lvK*Wu6O#cnWIdD{a=ag%9qsKig?a$g0Nh?B=ECY<1uM48-RY zVA)8Db_pxy6J92J*sNAu$}H2eZ$3qJ;7PB|dsFh-)YZgp8LJ0TU074%OsbkIBY_qV zuO*uh%CS71HPHrY@aQDI`j2d%`6Hg5TwOPzC;vs+X1 zC|3$nw$eP2Cketk%{vb+}a92lI+;5G4>i>M7T(3#p*NiX z*XhSkLNR(|whE`5aFKk*SZjYyBL9JOY=SA_N>uVm!h}&m8sZW(xri09$OYW+ueIn* z!&3Q#e%S`w9917zHXEtukYywC`hNP;g0S*Y&-Y4c`f+gCPp+m_^;#Ng;j8nllf2@H!0NieSK1r^#MElP1>|^c zb z>$#8U`3a~_1Ox=nH~Md!z<5x?F5#iMr7NljSdiYOAbEf%dESI;+t2nyMFSj(z<6qr zv&Q?xif%0OKb`1)Ghh%mZ3@_p%6a1rpx>{u^JY*}tKzx<+CCs}1-MmXHV6X&VhmBz zDW}RNua_hJ{r5NTqTA5cHVSx6boYT*>vX!ujga_y6&-sIjgf5Tg%EFVg^=t4M`Hl< zAoO|>lVBE1@|Z`m{rqsnfbJoa&vKQbn1E z^Q^0LU+`=TK!RrSyG3`LwS@o>c-ytszU2lp^$X~A&&W&Nmc_(z(1H!uij(z5XNaF| zy*;Pm1#3i<_jICuL#IJlu^3Fg24nIs209S;tq0oQ6O)=-Pbu92kZ=u^wCzC|LSB`?lRI7Cv zE_%Rng~f4i_4cpXc!pKf8o4>7yNrll7=N5{3H|a*&WT7Fkt>pQ#^8~DhjT##9CgO| zetf8Bq!?q%r)zcadTBeAS_Hn&`T8*K3yG$+5>KtZ%)htGZ3Oz_4k8p_9iK@G4 z-a3U5amFgNw*AEI^JDBg$zqMZ8LaaFG83UDwnav?WkG+aNav3hbDO1cSNEZ!#mzr2 z0t-5S-CtYAGkAw;NsY5DJO>M{a80!5XXd_;RxrYigm^uzw0O9Hp2_8I`v}9HfffO-4zhFn=A@^hyCq-aMUlhf6RA0uOBSmML$Q>* zWH9%i|K7~73^r(4-*Bu?gW}MkOgTHX| z<{@B&qgSuFWlv;9SR)0F9!mmlYagf97I(F#ZNol znC0+nT+{n^)8$eKY8>7aOg2;o@1_V7ORylncCtfRn2MvnrPkCG*px(IV@QHWBvZBccb~U zZ~r{`SH5%7GlJrj()SP;h?DTeLyc63>mUm9Qtr~#cH_ghlD+Tfo*XU?aCb=mmJXv0 zJhNRD7oXUY^9>j?Ev%Db>Pr|&k?tUl3mU(l%(C zlRJZ>U+2c z@#uosxoA7tqP4hfY2WK03Ww-JztM$g5iRh4C0n6M_|te4Y6yn`T_LZ6J_5f&Ca3I1 zBhaL`cXkhQnWK2I&CKY>A-G8 zI20{nWD_*wH>yH58h&r1(5A8E%p7$_z)DHVBKanv8trrpAU4d3{MkKZ>pBei6n+S0CLkv=HxseeWG6v-n3AU-v3H zpZ=WfZM?mbkSbdo@=BcEpKLs$>OahiJumb;$P3-p#atw}bOybyjLw?qaPWAOcocX>z zy@%Ey`5dJ9guRbgk55l8XFfmk*uC|&T(&QEMUN1BMsC?lYx4M9ar-8q_?!nYc<%FK z^^8rV|5pGwU#|xLA5mWw)CSjfTPR-Ky|_cM;7)KT?(XjHTHM_VG`KqycXxLv?q1wZ z`p*B&xyeOlVi(!ZUh7%1KbF?w^@gvlt=)bsXAfeKi3AxuJiF>WjjB6+ygiVUfv*>+ z;I$!lvop+LXWL??ZE-^z-sQ?GZP^5AuHQ-i`g)7FpIgs*vr7y0a(E1~%qQC#tI`RW zpKAT$%K|M?57ApwvAk1BH*or_xrbxH-GBp_lY z)HE9csPe(GP^V+3#F9Zt+d7;>4s7eLu4{uQ+2W&K-;DtI)U66L-*|ldA|>aiMV79A z171)xeREcma@ORF3K>B?5s)a#NF<4|L{}~W$EGRkk!Lm?Ciew6>C{g?gmSCoi?x;3 z5jtjmxpT5I^f*3KY>_2_dzjM{O80d-a#o3)W`=!yl(ru9D;dpBO`*(?kS&y2bQM%E zQarC@JRo9@w-BE(ygjJwW1Z=op?-T4v*ftFN-$!sZrRIO^Mod_ksY{91G0T!8blEi6qz3J6@ z38ch5GvJlVVSoj;xb|1NGP|GYQtJr+uz%vF!nSDm<7_sECofPt*4*ja?NU3n=64iB z%jsHL(~cD&h51=4k4K~z6#&zNE*F+SrN}%(NoJC9R}Nz|V0+(7e>2ZFwtI^vQ`8JC zU|Z=^Jp0fBH-Gs2=1qoxUC z^t8;7jicEJu=m?V1AP;Q^lS<=_Zu_Q)GRfF0J71!hju-WZ(SX5u8Z1i+jl-v68miM zW=zGdZ1My%9iSo!fIB@|hHgcTmTn%Kb1AAP4aQ7xDl%=t(-t?IFU;k+H7mn6JG&S) zy)MQ{i<)iJfXZ&xN}iia2xF|&7>PXYDbyX=>S+a6iLZ!o5cIXw$&$Xh43TnA9ZoWU zGG9|+rH3CmKHnGT#hu|qjh2n9UntYLOx1X=IMLjN_MjXA==7ocnyl7WR&b5v78E<5 zNJ|FpP855LK%#ln@tHYW#|ja+Hs3-o&m#)e;iB$sHx2s@L1L&tgbFMp8;CAC5Hqks zR?(U5jUOT<)ZjtLdOkbPFL-L%Wnrn|rqld=F30UioJS{9A_Qx-T93lS~Gx9O5JRZ~8i9y=}( zv;pZ%7?r~%*fY#`CkODgbKGh!{8l%e9_ycR8x^P!U~>Etez|p+7(^7s@OJsalH->q z%8vSZ>v>ckeP^-08c=*)VXPCbM;lOS2vIxm!;gh4V-gQpx$5Hb{UQtxDU989qU+=B zBa2@BV!PS@bn9v+&JQ!-q2to`>_Tt<<5^HpM0*J_%-HY2U2wemZMB+(I4#6^nU@_q)=+DnfA8Jm!Gv}upQ;{P%2p=6&{7_VnU4pNBKR*U|AHiu5 z!(g#K4OsSva?~3!ktA3~chse%xU@%md0mH&Y^lC<73F7u3u!*WOpV?vf7XKve5 zZXO;(4dm;X;&Ev>g()ipb!OfS$NMu)WMpJDY5GfkmZCd#)lO@=d7SgERA;Y34Xr;ugP>c?K?g3uKet;?aSaRbuzk8Bco_?T&nvxB->2bzCQ9{) zuN&0!4`r;FUabAjEjC-4W|)q#2IBk7%`8T;<1Le^h7P`m4opgVQXyGTw0EmE{)bV& z9o;uMOG+lNJsD(8OiV0zHGpwz#q|^#s6fv0vn22(#^;!g8e(2N$ZM3Vo6hAI>F;n8 zk;*Uk&DFO*R?P9F2h18r++1U?!o{>@nlu#^|KK1j8dda}2<@*_R$o75`Nxc7ZowUn z$z;<`IXgI|6lJn5uk`=Mwk1!YAMq8R=B};C7-NZ(|0-;c?76^izZc?NQ_roQg=fY) zo0@=&SgG!0KEshn-tW;H=ot--7Zr?O#k=Y#hlsbhAE7b>35?K`8^*MD?iUFMFe*nQ zJo78kdP=|17N_LZom_of79f% zHNP^>2k473jROZY4`0MPM<;4AqK?cmnPii)}udOaGgBW1X1UmBcJjDALeQ=V* znE%*(*PX&c6mQrNAlPNJBW#wmu*~Yt_-Wg2pZ?uEIm@7u6iR*xfSZb@60&+-+a^39AB&I`yoKXMFI2l1clY9@K*=@s4(~JaBG*L$V80d#+ zh~yxjhSn5-<{dgkBh86lK_?|2#6BKUjqcD|!3`3pK!6Hk3Bm{-0O$M|kJ?`tN%qo5 zXn^Yz8YJe#914qc^pkA7Nc%LxLJ}uonUSRHoNyq;pWiU8BPhOD0FX8b4I0G8A&g)x zkWw7@&feoU~0I+FRD2C=+o zcq6e?O$}{yFNd20ySI1$EH0;DAH(wz^x*YK2iId{XKXWTu!22D`M*AEqc&2Fv8k9p zUa|j#{d$iZM@R}|^Yw=Br}vFd+qb@J8)T=}=lJ%DbfV^LJl@QEIHRZq^!(4=MLS;@ zYc-gW7Ipj5-!>Dr(@T)1@9(}M8+~#PcXZW%nKLk5Md?wAE~47EC}xe^jQp9-S|rz9 zO8Lp?z<1Co&?03K7BFHd&r{J6+KO!>`WHae6&?dq3=u(D(q{qoML8;=ueOmO!>Jg^ z*Q_L^pRqW#L>Q-T67U;ghjYLY8wFYOTHo+nWv=MghWWXPZ-q0;TbivVKpt+4d;<>~wxhwq1u zEI#D{l26Xi7ZZ`<266sLS=Xq*L-kpyE}W=Dl5Mo?)T*K_g1{?kY!-y=C#B-LvAb`N z+`=W-OjX1j+2;(=wyqQxRg1PbK&rP(WL*@zpAnob6sv#8`R62l-MoAwCWR_116kth zz2BtW{zG8k%(s|NK41g$p>pms=GNojmJ$|T)BvJ2a7SIRo)(SZ*U`GY zy*(&Z-Thl8+bq=-Ft-TqPW-PRWBpqdZ5UXCsDKI0X}`G#7RdjLvAgz=RaFJ|DS{>Q z;K2FwbK8^FB3o^+Mi4BLc=7=^U?78a9y+Zq5lyz-+}ws-ghv08=x_M+O|Ldf)9*Gh zMDl15z^(J@PrbHlPTRfEonR+4cnCv)H-Z0h?!W}%Zk*sGcsmAu!sBvfdD+0E* z!VC;FG%1Av6!uv&){|L-34*TcuN zMI0^x_izB9DKzE@?k=`f8fT)fNa#E{=^6uSjzwer$K7Wh0<{dge`ClUhl9$yRmJm* z#gCF6%b|*FgG~k2(xScEX8l<@+m1{V(KNc$rN~`V@!B3 zfwnNVxtGW7pAQbdxQ2{}{Ks%&1xJ+K{WFdSlUHmo`hT$wFz`%<5wQj~arLWwK5+;& zGo$4-B`4USFkYSDa)f>SMZHHf1A8O(-Bg;7NEmyV1U=?(?qjO>V`OUbekJN338J?l z>Uo*;vu@Z*@GKXZpLF2?BXzO)@52|TVkE2T?30gbv!3#=?LrM~h^zX$E+y9`E>bPl z7`5dcg?48tesqz8Xu7|{2P+$X`LCX6ii~3!taAhnZ|5ec zJ7{$aSVp^0H2sK&a|sSpT_N2ZS9F$*hd0uyh{9ybx5S5eiWkF(KXP~qc&Z?s8spvZ z+pYBbepWqT`|alJSzsymPT-P5bNx9*tfittkuA}-;an;k8F0Kc+UY5kXR)bG`w+Rm zz!CsI5-~3shCbrlm$xe3hdtpFUfpbIWzoyRk!vtUP{Iu~-K2kMVpf{Al*3s~#yLfZ zPKJV}r!rlhrHEQ&5(-aG|0NE`g!T5f9%9i9*SePD^Oq>M*)@X)pesX7ZFdM=g5f=l zF8vTukO^=OwO@FdWRQ`@gs__V=-AF=uQIWro9^qE~EYcbM{lM2j7DX~Ed34h7%ajutQxE%} zgynwG=_;~@nZWe>-Jbqv3%<>XInO9)4zu+1Vn5R&lFnuk7(i6=AyL!pi>2}}5eHzz zqfKlx(q>b?12V5a68e|AGecle9&}*zpfJuwVd<9m62DM1@1J|e{X@r>b_=5sMedEdnqb|-YtrKp^w)DN+FA0UZH#55jhiCMx&y#z6&Qh4%joTTRbTZT*BFkJ zIcs8hecenTS2@*mM`0+d{asG5o3rc5Hpl0$p}?)Venw{h07m(2%bOtHWR zOVG`x^ZBZ(z|%<9r+L>28GSFoYM*@>7GO3TxTHK)Gn;MRRp}evXWb>f%Mhg{=WOTF zXDab_dv&)FaOGZ=bx9ehx&VR8JbZ>NOAh>y>)w7Orv4k;Qmm~_0B$5$HK!c+1(YbXp9~bZDnGl$)5?RI#r1Ag%0~0)g}QPc9uw0_1$z_ z4X8flCWUfyuU1qQ`@j=f!$(HGcbu$@y#r&*`NmmSq+nsGwMDQra-n<)oHX(;LH4Q- zMLCtyGp8EvuZvH-X>3p4*{wHt1`m4h=`>oVYL2p+b7U2kftXyI=K3#rPTl{Tr$0oO z8v8ZS^UZlGU*sZE`P_Z3qjC?yl6Li+X=2Z z;${s~-d-78Qzj*F88wKQ{(Bc{V_ zOKpSf#$4GW792vzGiK%%8uf&w$NoEaTYU1Xz?)+y+arS3_;l5;KIIj(R0LJw!nVeY zU!jttvDYx51y#ilFjT7@d^qr0B;9lZqtMtQSa90;!;j+ACe434I8V{}0tS)pwd7_i z(TEb#w8U2JKZWG=*cCkna4fTfp`O`^mxvZ_RQ;zp&N%v0^cSAcg?QIP`cF_xQ~Hz# zIb`l6sbX^^EdzEuK@aQmSsHj~U*hN)NE@Kaqc`F;f)hgjXty%;?Q{PiVtxSB8>O+X z{c(=-%lz7T*|jI_5m26Vc{Tr6rr%JakTM-z-;+l_pNfKhc#$Q4JMTA4K17yR#8}pY z;vLkH*TG!QGzfAN^KZ_w@;rj@T zcgPuuW{0#_%zd09yV&b6QEuTuYS1Jx>N&j7=voSuZP`$rU_4KUeAsb^VSEl}$3P7> zU$K#c=j&8WP^Z|ZZ*jXB9s)ano49->_7ARV#g@Xwo%_q|LvCH1l2iO&11*VU--g{` zq9x3q&dfVSxGNM&Ew!gG;sj$@Lct5$s&(%OS&{~9>sfaJ_oZ;*!beniFIhdf!Js(Z zE`MtlDr2q+=GLB++iz6O1blzLek2kk`Er!W@ZHVNWeake8ULQR763Yi10j)&th0sI zxMT165=db^d-A{)$$tIqKOZu3BUCgPs6wg?(fD+!HKe?!Kxjx4R`O)D4R5vsNCu>8 z^h)>l*{5@w15_PuV(a%!6IS7Sr7*(JOJdGh`wfYoo2Y5jlN{w!DTjjch<}k=i4u_M z+Dto0YHJ&DLXM0`_q0kz6C)wB7)LiYR1T#tAMW3KGlNDpHGdrMQC#DGuQ9=u8{J}{ zubrGhQ@nnx5rTL5DZf=LcW$OTQ-0yitH(#Dsl*!9^Y@LZF^X)q@Haz-;Q$Fp3Vw_N zt8-PC0gJ^hf2QNg&ZL|u?orAWn}IUjZZf5`Uxe_N2Gw4mnSwS$uDZDwto8>^ESS;T|oLD=5Xa z8$f;B)2Yjz10b=9e$qCkSV5(BPa>QNX!H(8ieGL9TJIqTJVd6FkJG zNBhl(EpR#$IAj&9uYZM>=X=Kd_5S6%nQ}o_k;51?M@YAW#x*#SJLTt3#%M=bsv%6V zl;z8GxE+&9ROUfSqh?KJVw4CLCkKaa2QCwitjbu+jE)x_jWTc2(%j6V9<8=I+xyKV zQ#_Wzh09co%UOJ9clT!MxGzT0;9&&b7kNG(7lVDvWo7>vwBSj>$ruU?DZS07JlW1F zs*OBFMV4xG6_kpZrYk1^xw(q@p$NE1mca_l-(U%c~r{$O6R?fl_k%U{rT z?WX%P3aUun?YaAYo6qe)?yfeh{$at|5H_9`OpxXAYtZ#%zz?Q$07jYckE~`%-C9k1 z=CUax!n542!LNKbT|q97&Vg!LH$I;#sZnRh%y+C=kC)la9Z~dmZjJ`_5*=-yDf*nT z@YNlvQdirHc|n_)CNc(;+(3>ibW`;onrR zUq{)GsulvY@1tfp-~J(KcH7{ePh1-+2{bN9gfxcDCX};){Zhvufi-z*Ix5lRA@zn} zH&|?WOIv0DQj&roa_QK&WXfU~%@j<3)i$w9N4jU$9E=eBR9wI;C>$w7!i)l;6I$;u ztJkL&&UZ|_|1!brxzzE2wZ->}>9a_bqkBs`Ydv5cG4&50;sFQks9QK%Hb`4HS^wcN|Hk^6ML( zTvH-`0-vuh0eE`x+0lUmT*I8Vav%0NMg_aL;;fkjR|E8xN)%2Fa+Zd znZN^kG<{;h{%KJdMXZaE!XBb?tqUfsIlXg)BnM z7P9^$+`;$*M#@dhd5Tg6*>xTKgW*D$6m&E6P*)JGs2Q99O~VMF&UUxgC5NW<)D!5~q!rrMl1v3lJTbBQcsFHnKC?|CE4lOg@vHml)^< zZ2qwTv1p&Cg+|#oP0A{IMo2Gl>|9#QPD`uB7v&i|24zlnLWQNK+vx!$!dXMm6%%<$PH&0(2oQ&@n0^hg+#{f7Lomv=%7! zc=?%c%M?vAc^Suoz5G>ord@wYHZzW*!0p^TJ>1aRJ49Rt5po8d9I9GUc4Q;UEO-02 z$QyA+hT;J-&oq~aD(V`j2r75xha}FyGQ;j@2ae~=K2hiW594rhwWfnH%DwNxdlrom!2*Zf-CZn2-rOm5 z;PI_3c7tsjnO$1c(e*Wp?OK)OA47uwI0VT&PKaSYrB3Z68 zi*vm?aY=oEMB2nhl=L&Exs+91>?KMtxP&s&h_xqSmp%WM(fiJo%B=VOUKLpac03BG zvFverFt)bFDb#-Z2GFXNZqiEX{09yG!w2|VQAh9)Ew_i}T^xLG?SHvl`+S7*j9a<3 zuZO-K4g{+^r~2;5@$yND<_4V0x_8cHQ+8<+>E3&uzWed$emi zByauUrQZ58JNMwYv_f>@T5Xo6-m>E6p`1U65sf~8HmtxZ>tcDSnheHfN%DfB*T@Gs zG8e3_Yd1(6eK@+gipyxO;YcEzDd`$MD1W1PBSqA+PTUho+;@3KB z7-^LGv}|~3reS%1mf!uN313ursAel$^0N&+)Hnld}tAv1t^Owv6O_CjMuCL?e2Q6 z!d^J}WYyNzO05MgvwsJ;0Pjl7xaj6h!d1Yxo4*z)=Y*cns@z4V2n^7(ROk%nj1oaG zC(8w0VMADu9bQT?mxrA7JI}!0(jchY=-Py5;Sb)%w-*4`pd_%6e?dPDyQagb0Vl4A zH4_em8`H7M`9|0%ESBW8s0nnca3l#zU%o8%4k~&z5bL2t=PfaqFaQu&QUuXQ)Iox4 zt4X{lVMy7aCl9#NfW|%a!Q1H!I7N*T(LJzn8WPh?@R|dL;cyV=FFujKEHQ-5?e=%8 ztiDm81qb!)L^OCHX;{`A1eAyd*%%u?^wRlJQq^hM<#wfhDf|odGa(!uO^e}6Heo`B zFDrMqg0V%o8_q(ufl#C5z&BP1cO+4vGXZfk`sel82Ssuq0LmNbYZL0l_XNZlQnOe` zSPkSFLgR6?)Fx^W|1{aWhVl-D%$~M6i3V#{QX3?FI_?Or-5#tPdm9oU#Li%@TQO{8XY+X}1Z8>12!UJ~~j7(HxTM4$5 zFXNZ&6}dw|P?T7;2?sEvc#0W`4x&NQ$Nhsyl~4wqM^gjG*D)MIiizS)T8h~c5okn~ zsv2m7rE4%x{SeqGh#xp$lM^W-GAfAe$VEFWD{dyk0Sm3Vo$ejhCu|-5lbq8STP~*B zT9(*BGgeC;QMc|f6`EVrsJYuE-w#;|nxuGXlxFPOz^*d%jSoA*gbTDz2dT+#MVE5b zIeljMQBEen03aON)n*U-Oq7%x>xVX3syuAq|Db83A-8iyl*hlm3 zx^GrpXcwP2qF(V zz>x#2S;p+M3q+vU%4=k>t*CM+*;h?Lb|=(;V&m+tS+UZd8GYDRbQm(q4Pt0?IEJe> z3<_hB$mt)P_zzQn<+$2PDEPZSE7%~c?0EUc(u<7on8BgM6FANOrTR_(oMO$Eq zCz)k96ak!FXvn}rcSg*VDATIBzn7Hc{eAPMsQJc;-mrxdS(S>`RLMn5v+q5ty%s1B zmm;&_E7Jt6jGm$C3$1HzlEwFgxhZjj+;;}wNro+Ra^KvIgQwghJ=F=e5C7-ur(ylK zHu~bU?~!AY-6c77ghq0qC||Je;N`q~!S-dE8`3ZdZ;!2;L|7)UaN{U5pfLy+nuiP^ z9cBf+m?u0}+HXkVtA+>>!w5Wb>22TaYqe}WL_*7lek7g2@z^q~hdE`)s131zXN)*g zkkK@WF3+wAxmLJFC&e}6B+A$zi4sZR1y!Tr2;tx!M02v$S> zHfX92hTr?zmqHab+jg4rXAuTsJQ;qcMW48_FVUPSpj)LEPwES@(9tYy7WnH;T}z#s zVv$PsnjXHHZsTLDQZeGd6eIUF1r?)|Ui{@~2#84y;K$7elEZPUavK@9i>k(Y70Vr+ zgbL+t%4d|?a*9cX$VD>`M|I|!mOG}hO0}gt-=-dF$Rpp0U4sNnSuhl0fbbgJQfh7N zrB}N@LTQ?DND7@T=GT?XBob|_T{N&YG7QJj#Lbp1SWLo86_vp(O~jXZ*%wa+gFV~? zCe5f_ba?pRxC+?7m14Fq++$`IQ&R#>5^yq2n?_|VA*svqM{Wn_O9DgN<*Ptf{W@jS zdRbYymvNFD2W=$CM5>8BXkRX1`+6B=Q7FLlaRB9Ba69aY`qkiZ1Q$1yksp_tZxB(O zjeIJa#+o!VQJZ4GjI*unzHGc=d^r5~*vhMe9Z=j%-92doU8;2V3k4b5?qH1fl-ni$ z*6o`gMoULLt}0+sOeZ{9Npza8^#!$1IEXsJL7(aMiMdh9T44m!LABGbXV9H^f=}ud+)TK`l{Ez_YO?}38;FJZsm!U05CvH!cbyM zS&Pgd`2xPluF}LOjVzU^1R<9B=u8gC2^{uQ|Dcdif=^)}gQ$#^;vhRgq(r8dXDRKW z_(9Ctk|Z=wM3z%Cxks$^1JRcq`7Yq^(|hpm7Plh9qi~SI$X+KSqScP!YkUqx#-}v; zsCY7AA%f{dR7zaq(kT8DtHF}>zRbudF$oZ9i;v)96~0ml-qc|Bl=_j#t_bX}sVX=g zGM<@-SU=BbRTxUI@^3o(TXiDZ_KdN3l6F|3)}v;U8(bv)zqInZ_rQ&x1JDn|f_pR9 z%4SLM!rdy+z)t=hWd4AXOvx44K8cZunm%JN4(vJ1lhfj%mvl9lPN_ zcP~rlPs-9@#5@78CgT5O5WNCKlBG)eI@ZFc9Ot-LTcXCbhN>#Dkw(a9XYdxTVWsw$ zq<5@*>51`S%hBV31I1ooTZ7+dUGsTg;LtT}E;ixzs6;Xu6)AtPzF3?gjlY`jjqjuK z1NNvZ`$}-wf9m1F2Sq*mSEIrc8fot+100=F8`_-R;LJeO*^_U>H;ohL@5oiZwM zzQ5(Z#d&JLyyt=i5hqtnV;U_4d{hba!y0?&DM>#(* z{H|X)HC$u6aNSibdMySbB^uB(7C5hsEP{pABQZQjp~g(Ow@W&DejcQG0&r8`L%L|* zkx)?VrzgDV{3BzLM${^j-)&TCY-;b1MQt)*Mcg;WmQf=Bv@uPshJ>4|O6!Ba#i}YI z4s1{|%m-zR=oD2lM4~7aU*orVO9qv=X>MQRe`Pog8r5lYbgu0Rx4ynld{oCES$~tx zF~6nHx{b*)uReY1URpTGg*v_QyBKa(rS>tpv(L$uix$VInE9(4Ywq>D7t-AMLELq3 zt#449zS~Oq6Dc_bq!d}Emd)=CG`vTv4Oz}>$bX0;gkH8(fL_HlLJ!h6cM=DRMa~+O zqhpcX^&2v&MHd4|d6XE^W9>0SP+G}ng&J^KxIX}Jw3svu8&-j(+Clz7m!E|hEz}|& z-s?m~#JZfK%M&Lj6vc9F9m`YG1ezrPXkgp*cZ~YuE(A# zPhE0tIuA!r-o~bOKuJM@3CCVFD*UOEAk9xAgLsHv3FjHt(o zw5E;s@(zztYj0Lbm)=rNNWHV`MoMaLbe4*B<7Vye%;x8-#X!qCEj2z#D!L>AfP^qZip5bDU!Nea(FH1xnpRAiD(Qt{y7y!bc(1uxC&lGQ@? z2(fCg(wOYUAkX1T8An&~q3BwT=m*|ePMBNy95ZHlddh%xaXc=pNCWZnT4F)(;y&F6 z`kaNrIJUOte8yjBh0cJI#psm8cKXph79$)JO+ceC>9LXg|I*E+eq$)k*x*<;4*wmN(y*SHe6Wn`As>d7VPtvi#KTe!JKFRnpJ%~XPylSb)gOZ?c_SPr_1JE-^P z?AEG$1{rWtS)1AlebJCD|>9CwA3FhLDpj0rOx9UYr0?KSMFC7cTlYi?d%u)rhy_SPB9?u7o;)&H95 zc4y3;Mq)yM2QSpwl4KGtjizFRbx>fD-un5h%&2NgvnZ#F@10|-<$*dx8%fF)2&m{K z%0XGL>6Md5#2HI{d&hPa?333ft|FeEVwxVrND_X@uFs#*IExodtjvkHDqPwmnZ(%Y z{J<%|Rv?L>wl;CcKwe=rIY;T)tNSbq$vop7jHJ&!Qoj-1(;(LJOrImg zGSED9k2xR_69Is|x?B@)Y`5UVm9E8=6Fw^|_7tc~o9kYF{;Br9^ zV1c>hGJI8riVzZH>%Bkrqs*FM@>Fen4OL})u_>)VYkcopARr?hezUu#=@Yfg{1ub_3?(J4#&+U{}+iyXS;F!sj#_%m*G zSJe;@;4?Cqqs0V&1vV5}Etmx=pc*L<5}y6)zxuQ7-C#QwL%?~YJ+ZRFW+z*eJvDXQ z0V0k$%7m$`=eJR{pnx;goE3wXMl+hcR^w?dOs3p=q+&iRuSfDmc%jk%~# zON@WEp<~RobMhxeId{I!>1TqrbK5p&ws?o7h5b`M3>em{I^u6@-M3f=o}_c8FG#w? z^-k|rqkG>(ze;;L2C-sS$^_9U5jx3IqA3q&oc0Hv5$P-$i2#w_R20+yI=lv6EL1ntqS`P*3wsPF8)^&JU7K^QDmbO>vV*#1M~! zPF12oCKXR13S-?A-7)Uau_`#+>nk-a?-=Iju`2H_gpXq)xzHQn=-g; zJuwk~_)1u(s=I(mn>*_z#9#!$`sb7m$x$rsa|N{=Oay*^jgCvS#0x55((^=%Z5FHJ zi$?hsZ6Y|^nEmquSpkhG&=Q;;9X{#H37v>Q^K<&NDHA5^)}-mgjQ>6K*AyaxCvBMR zg7|fo1gO!v&!E1Oe!$?yJ zKa(%lw2a6CYGBTZ=2+{FC#?~{>BbIChb%XPhZM_*V=1axxjaZ;>Wi9igO&c$amt|? zJNb~sx|V#sdTVrQ|7P3(@qb71=c(N+YZ2K%P(uUQv`(zkv8kiSx%lzW!;%qu{G3|G z6hS-P=CJ<^R!ee5rN8rRyY!z5DIt*|?@Amg%z=Zd)FySP%1q6t*+T5T$H0ia41?dtIFPP}Wk*L~n`yztwd{C2?c@RC*y!f0)U z#<=P%EhN$rxl4&&w<@O>1W!JWbfXw z(wEi#`7qi!f6(!JqsR0V&*9A*e>g5?2k;FlUPE8NSvt-_%*DImP@h7~u>C`z)h9sy zRyOC!@m-Hch}4n&teOBW!y^SsC#?s&Nld(4Rj)!P)wF4hDBOZ*sjSa{EtA;^x zFD7)<0pxVFS*mJtZ>sSp9@xN;2U|B=%$QkY>@iuYXz|o2Q<hK4JJZ#MA-VN zTEWhV%_Bf-;ng6$V3aiZbKy3p|Eb`v{_E{lA9l_%JtB5~lrS33Ok(&fS_e7$ks47? zEKQVl!v>fj5@yk4(Fe$$+k(_JN`)!?F4DRn@5uRv*jawv!AXfA(jLMlRhBnSnv@rT z>>;bBfEl$3>5!xv$=D_uM?bTy)~#~AlFU1(cuh%?msq}M`TQw>*>O~uE0y~}zKHb3 zd^lVt>ury1Y+)*;xEnTZpt8v-hC1W1g@XP2vw8wL85Sx$sUA8r!NDjBaLttMQgq6q z!a~hlXy;<1Im{Ekaa(XvX)FevIfL=%SMD}|USgFLHwdBcCKB?SvB*00Gr7|5U$l(%6rXg3Dlo}_Il6OQ=i8bFJo9A<5){=&KKI1Dp zx^|Z_4&_+nh@>zG+H+p8bR>n-gMk5nX(Yl}M739eI^y5XSzpi+bZmR!C^Z2DAkqTU zNy9Dn#ZR-ycHLPk0%Z6g;^a9i4TpN-nzc;waQ9^+ zjdf@v5dt3OJl#{JcQu#JVU=kdby$H=FDRxkE+Nm$?^xYVd6ANd;c@e23z))xH0@ zkSe|@rdXk+I#T^eh}!}Soy1?;T((F#InC6D^F*M0vRqytGVfWXmd^p;DBr39y) z$IBV7kACO)w@vQ6DthtraA_;VR8_6*hJ01cR|RDy+Tg@~klsy=XYb0B^2K`RNaZ_V zb+b0nJOtE-13@XW%~-fRUZy#;@&tKq-RXLdGzd!`+Z*+IBJ)8i!)@A`Szm!K3m-(q z69+Ds@wy+(&$iUS`dhm@v%{!YdT~{Fv$cKq-I+bh;pWU2JKI!1LX8GKHzVh6<}uI6 z@s{p0E!l;#&sG>5U!v!`+lbyf<1|m$_fSR8tmKe*;u&}3LL#zbZm9ulQ}YLwLp~Zp z? zMVe+s$1kh+?PIBpw51gls{bks4)wi%0)$gEhZ|WH?I*WZ2^W?g_z%rj0-ZScLGFww zUj_EAj^M(``8dC1$>gWo?kwY-ay0L-4uS{;s%Tye(!!0R;qhD z`a|U^zItjSY>4Ba5<0Im_~{v!{xtssm^*d*+sZBfFDX=#bnu_AF4CJXl(@=D ztLTc*x?6Mi^h#TxhC&tN=&Dk4fV7xTJIPbXBIO{Bjs?vA(erPnHAAY)FQ|eVhk7}^ zMUzV*j5>5Nb9YVHOPI521o$?N%J|uVOPWg&n5J_mF{#_>O;~qnuIWwgZEE-a6}FH2 z?}<8`j=H&Nlc~+1&>wKui8MjN$63uNG)78L4E>HxcCaDHlu^Rh6Rn|79S6|1fN@`Lc zYOrqEQ?JT8Y2nnbTOghj*UTL9!HX3JN6c|np^4d6rG$J;tj~ z$cxU858CH5a2c4XROi;`>U^qx$JIV(;pf`hTftL1#8pZZw~kVyq@{b_6!8x!>csXY zQ6E~F@XSPs){oznpNKbQ5dCE;=BO8t0P?YT^U+xb_D)v{VUdqsLqxKWxR$?ubnP5rBvD0Yq5*!HJCi?_M*ZU{JHXN%1{^2 zA5gFeruc!43P~2xk6;`Xx27CHZc*K8f-RGD&~)0bCISkA|SKHGsOo=EqYlOpmNPw&JDP* z*4Txek7@F%nLOz|{I`Qn^pxhw7s$YftlDOt{=caTyk#IWj;!nA%a1O;4etQ&(xEEp zWcB%^$U)9C$^U(++}#`3pp8o)xI=J)y99T4cYl4) zxaW@dQ=j!$RlD|HYfa-VfxG+k`8e4nU@O=T_2+K~dQ0^sabEqk-LvKmbY%fQ!}t9a zI^zwSr+H7WnytbEuvFYMb)Iv{*dyhiYh{RLJUQs7wjeW=X1#yG|ps==har#i@h)IFS@1xK} zjghw-J_N6pzZk&rUHGM$Ll_G2bs0(dADtKMSw#8IY7}tc4e+6Cg2yZ#?`O}%ibe>q z7DaMXb6fD@<`wT-XFBcqk{f^1^J8G-mrJuA+PPdKgpWqhZ$oo zdIR{j7HU;PHINy`LNNvwK>lt2++wJomGxyX^Vvr@`!?wv1Ip6{hCdC{=TFDZOM_v} zWPnO4U3x|NU~1axNXr7FOQFT0qwaOuVQAPY2MnpudAZ;(a z@Qsdd(3~fy!ha;38hExy(+E89G&fH}CL-eD|;BK?bs4C-$S_VK#`*S4|6 zzql5;+_)sLm2nzF+cElDLdn>9pv(Z^e72wObP zU19EB97SF}nNDp5v-AH-4|j3podNL|uhm2iafFyyY8n((3C!?=?{a(u|2_2QP#J)U1$UG7P+M7FD&hyE#ghM!L=hD!YzObViz zsv`c$cB6WsXC;kl&$GT4dWUPAxGuWKwLiN|H9OfX2?!k4M>2DS8?L1)>N?q_ryaP@ zn>oo@*(-a~e(34eZkZR}`*DpH;~lAm>k^JEG~83ZQgDsv63UE-3&@#**GwMo>$OLZvoIG>t4UBzd4 zO8x{>(^)2+ij?U4VViBU7tu#ILoFGiEdQJdJi4NV<;<;D49gOZ?v;BIJ^rJmtDaMd zY$5(#cfWi8O`i8Pf5mm`w*w-7aj4r<2B$xz`HXL($%(IH0ROUM!ZTfOa(MDFY(QDr zN=aFT7-c^vKs4Dv+ZwQUBGLOSdo(n$1+oOuCVd9D8YTdF=Qn-B8==yoO6)LY>X9#H2C_P}SLg-SUGmZ&Fl_VR*4yk;hxq8m^iD{{`(XiC9YGGCa7 z0Yx`f#KLeuQhk1vh>1?0@TQLYePRvuHNR)OUV!g~2+6%=4&ZwkYspv~im$dX73K3) z_UHTaN8NBZ5QWeE^8J*flpT;?^2tKE6L{8kgVcVWR>dzlL3aw07fhN;)6~mvkd|vS zL<3>AZDhrd#hfCXafx`m>3=_PaTSw{#-t7cP{Ed8w@G1%8x`J^?r}>Dtcmq)W-Xtb zYC{Z(w+-S_5D}hvJh?>%^twZ#F}grsb3XgWvrOgBYbMiczic{7Lw989fdypPqnU7) zwk81q$S~)ro=oxJ8k+gKe|-A=|I1~cQIBIFnUD-Vf~!F5BNQdQ#IEL%MV9j? zc1h>%juw(->`)kMwKQ0_MIcWvudQ0i@P!>PnT+=@Zx4BO;zI3}ePB%DPMYI~1M;fX z5of=rvQ7n^T|;Z?;(t2-&_&pJum|kY$IU@$q;6o?p1MNs`_7O{juatDCg36z&(;n# zSn=5_Z_>0a_{6UBz9>gW^r~rOiUE{V^eNvWI$yy&6YtSgto}(k zo_F?aIlig?+=%fMrg_z5?a#3H8Qz>@B4++=%Gx=OYB{FKUj@b%6zN`-ysvn+ z32J4c#BUJ6(sBw{h^Zmi;VXT1wer){-FFi49rV-?=U!eN_JL+qeXsW+aB55>PY>NU zi}R&5&n$#Ct)w4u#&TW8&(EI9Vaqu~xU-+A#Q~tCu;QUnTC&1Ni|CsIcN?S(#e|i#neQGm%y@v?QcvA7dhKzPV#_ zoX8UU77{##y?a+(z@{8`?&xeEc}*hsip`|5^ut)27`Jj&#^-DNba0RN>sygxa}Rps z0$=fIZL}hdMtJC_B&V>e@Re+z1fE@bs;FZjJ$*@dBd>ZSOqaFkTSN<# zIMQtOR2(C?B7BWzT~A`l-Vbv|bq;I7LyV8Njy5kE!Ln5L*xMHVBkM`gsY+PGc~wmuJz5PY4?^q+S<5iy9BS?AEg_p-G}qrfv3lm~ zr;8>jm_;#_10>3Q6{H|xYml_YXqPMt%ICDw#0=^VhvfZe2!s6S`0u;?V%HltaptrFS#Bjjm^KRDA@XM#>v#jWu^J9&9c{1Ufc~0h3=*aPo-g zSu!}}8#W#uk_A}X<@c2wx2XdIjK)gDW8^+*Nn(- zCjv8UBo;6sKXt5g{eL})@W8Q!4t;|%33B~xKhax8ZQ(zEX+^d07^n~xzZ3kV1R&xO z@A?h(S#=W(M8Adz99g^wekIlX=hZ`X#+LmP!kVpim}pU#TZxny#?7@5Jop-ZFT2$u zH`MvkWw0lgS)v1Gjw~uuNI-pwrm7(>r`RYHse}mUT z+0>H$!`c2(XbbSgL{_9L3h0ou%5e0c!kGXnBKQl_hGx@y zh+kSqz0`*vRt3z{JSAlz=Z#(u!Oz-%{db4`Dn-nqP@=dXe}5#TPOleA79*xPJVNW+%af+DJ$M4ceItE|uI~)9l*LS}Ez^O|OdN1DPrJQX9ORQ!^6DjZ>pA`hjIpLJ~3ITF`71mHMpD z6Axi5?$f`s=2y4Ys;dg13u71ElmG!yQxGS>gSUI6Sm*Hb2x^4|VR*LgRbQkOx zycV<+2#;sN6bsd-BB3AkKJbW)!3oPq=0pt6m)QJVI#7s~L>R(XG9amnF+jysLX8Pn z2)ui9apq8!xQWDOh^KIdyuof6M*nWE5h)_{-m_FDNJlg*;7w~s`crhwUtf}wTOjuW zy2{V-Cu>^0s#<9H$lsrbxeHGsCw{iBy<`W22tl^`Ra)ljV^5Dib4wy6Bpz{bqHD_8 z63hZLB&(hkW~m3`-rdQxC_crTk*b~9>mAz`LX(xQ5uV?!`%CxD`DrB#f4cYvqoe8} z%Oldmn~uU={A#7uf=a*Z`qZ^XQaYNF`@c0Ir%tl}O~WkPm5ap&AZr{sfY?_#N-Aj# zeEvK`YAa>wHzc|q!>}nRzNu?d1knXY;wEE6xcq=0+I|AFl(m6-w5$r;d(Z#31^H5u zHKHJrJ@oV69)fJlIIdHJ$@wMoTjeXO=Tuwo;SG$x%N^^(`;ti5Yd0w)|L%2R)cKd`jMQ3gg)#yTO_H9J(z2x z0LuTjyVZ?O>0vRj>HGVtNr#HQFsQ%kGxP|2^K2BSmny(}7&a*?^sL@FfA4`>AUf__ zZ$c>{4bf@h7oX{Me#5tOTVbCWsHdpEJwCtlbk@GxM4t*H9HND`OdvYDEUGGhE7w!d zjnQ>uj8y8vY;?2@=Gj ze*9Oz!xx>*QCug_XGel8qT$_Pt9r<{{0^X6^SbQi=g_I72hVdK)oM{&UTJg0Z{ASB zkZ9uamZ?uZ7xE6jN{rP&)ZkP$!TNQ^#q251cNt@*TKL#h%3sA2vFbA@Y6~~; zsee)Zj4+%!$5QV)xSwPn2>IyZm5zVcy$HJP?u#xGcuMO%~V`hlJGa3-tZVs{XuY=QKb zzY&*OWW@FzpuW>Twi~(-~>{zNy~FY>sR%0iYyrQ`5CL@;-`d>PwCFo%=z^R zuj+5@$0NLVLzZzN^qjWPfJPE2&+$~hy-&YMu2=1agCA6R1THBD67kDylgJ3` zwUS-q=5Xg_o>)NEA^DOevW`J<%$UkTVP5MhI%9Qp)LF-f^#WV>1CA2!QwxgUNDZ)x7R`;PSgH>ip}W=XihP?Qwco{xKpAUj@!qg-TVh-J_>)t>9N*W6Hz`Ud;r< z+ruH*w6cCm9iLI_mzN(RqLrtp?*Ezo{?8(8W|dLiK@pf6F-|GJZ7S&xD9dcb?vi)g zIj0RRRG>U9-1aK`Bk}$Qp^z+WPOLK2Ey?wd7fF?#kZD`*cwpQJ9RIo3KSap+CGY9Ho z+^!^MTT&-4op3(`Zk~=*<^OyqXd7cTpbcudYbT@2!@pcpO-szLFBG1m7AX#wD9gs0SN2i)Rd=c#4 zIpNgu)eo1gzq->ufJ$nCzq0#d7umo0)SnkE* zkv8v`7{Qx|E^UfwefwqzUeCseMV@AcZGXaR?d{DhHYeNZdJd+l!)?$*O@aZj1EHdc z!I=*4vZX(1ac9b?D!5+CsA@f_H|%q}DVE?%HXik0yf);0-!Lv$g(CP#o7|cT@#=5= zF1ii4_9rc*alg>tgXm`Lj%fY6b44d=N)zk`PviWC3UF!&BZ*oXl@p+#_B$XTMLn9o zFN8FB&&nxkNkh={D*$AgR1}5COsbQwAzJ3cLV+qhK3OhH2ebtHefdHno%Pi;JVMS&MnYSN&xq#bi{(>ewS1r1qUsaGm233Y z+7f-K7VR;x&ZH2(N%v5et8N^Q_4+-C*ghNL|Iqn{)(Ebzw6s5u*KC#4S6pv$F_dHs zouhHTt;a1aDX&*P)LZYIQ|4}&ztkfew)5v-v=kPh#FYK}93d*ds3q(p&oIa^mb7hl z(i-UG0@g~=ZINjrtb^#I@EoQpSAUm2J~x|&2YLMVl8hWNVR{ZZ#rwHzZ_T&F*mB#G z{FlhgG+NMCaQ`p~e*YI^c{ZjLR&V?lbC<6km%E7JGS3DOZ+`#o7hCv%$D8Y{BU(T8 zt0ciU4A?bqXd<5Px>?2U$w~CzzY>2cpC7z)Kmoqt%3AJ@B_A=n^@71Y-ZF;C1NWij6Ia84Ox` z3T4$u%6=E1M-DT(X#6{cDU#Q)fC}Fo9DTa81vWZ)AF2+J21GL6Sb)o{S5KajrV%k9`NsqvTqAnnQcom+C00mgDUAukArx1zDr-_%YsaU z`>ZF1y1iEfo{*K6C2(ad1@#4Kh#LxJ0`r*;o@Y0hj@W7nfBZ@Vi1(&vzaJlp6v|@# zu^3qyN1O%b_c$dj0fY@U6eZMM4odL(f-k9Ec|KzA{wpZ>s)(5H;Hq3*X4vT5KS>7*OQ!K8M15Ikc~?Mc#`ld<)~6+_kxC4gZkL>fvw0EwOz~5$d56VpgrBzu$8K0 z)8BACUJ~FD$v^SSbDbmm-{}7SO0#3|^|fV4eD$1D4eu|e@AWm%%ZKy#!85Lkl|@8N zF!rQgn3FSxw_cOzaR|DQh3+W@)!q)8W;WIs_ixd(k zx&%!%G2ZB0B6mJ;m7GltEg_26Qi{!dPA9&+&3UFSU)wkK+s?V_ySk75H1=ODK)`IR ziN;EyzF=X!jL&J=J9pU~TOt$On6ck^tIwlNlb9)uheg(}%rQR>IpbWYCB#l%=(hrp zm!?}UQ`2F5$~`+7sKr>$JVig{j#^wzCkGju;QQm+>mxjIhAWThLqQ#Cr2rNO!$c%9 zTPLB^joBP9;}`8?X=rjKzD)wiSYcorfNAy zIU8SyE)?2Xk|6c@sv`8gZDO%ON;L`KQXzqYPx&CMmaI;t$exfxF{G8>zK_ z@Kxn9trFhGOA`4@4XpKN>4bmqB{asg=7F&Z*r@b;$->nAXq3!^G4hmDh`)KI zhwm|+18d`IuFygWOrAcJ7X9+q7TiQZorhw zRz)29u4EYPxjRP$#r3o|LFEDg&gvZ(M^zik0vKfwK2nnWH!u4i(QMF!1GYt2&l;U- zs9|KeQOD*YZ{V40!UWUBZIoy!fi3LYY@%9+He)1G5%$2qz>4>N^xg?z*HS}MYMrYP zn@%Cm9WSltvZ1O|dRpP`j&YnNTP2oDm_J!7q$6AdN?lwNxGToW&LXYj$(U>;(bB%j zlflcNBh|Og@Cz&vB&C0Sue<-&nUb}izJ8uLS07$Cq0`5Z2t-JzwN+(K$K{W4nOp?~ z!3}Bx$>&>!jN|>u{l!>((leDX%wb{SP^n<1#RMD&+?G;SnV0je)RJ|mqPVggm2Do1 z4SZ}W_%(?+lc_T1`~qWK$AvAc+QaPIkM+;5g(tAmG_hDFss?K*POFB!+P>VfPsA0? z=X`K~ewG1{Yr;BW2I8wV;;B)7w#u4vjb)k{z2mgB{6$wpUmFPx$eK`FiUOWv*A2mR z=M-ZW!6u~4cfJALh!XNQ9`&m(JKv+;Kh_HP?6=CmHFYB_KOgyNg|N}m6~#whE~T=| zebt}Gta+0Cp2e$CS$<~U8eGuKWe zPm1NbN-xh@Wr=>F$5EWg-TC41Ucc}oDLOeBXmbkC3Byq9d08oJh=MU7DV%~bVL~R| z1NbBJ$tSKczmSps2n!Fjj4=W73BUC6K2e{Hud?`MsYbxJFf9%%T**mW5&Fzsbi9Fn zAcsO`q@q~$g1#eGN*&#hZ!-g&LPolHc0jcLpG};NuC*RWmxuU9zq@>31tN=o3PmAg zf?N_ z*wOla?`ixR&vA=sazP&hB*1|SN5W(!v1>G$^%=cC)8)TF9U;Ek5L@|d)hpH%sf^IptHU>p3WnT;s-=~|B;x%wcg}8Z z(tyC<8DFEj585nmX{Nt}argC-D}^Z?MP6ULvM}$}V|N=S;1ZnPE-y{4o}*JRs4$}@ zBMS;BxwR)FQM0NNDnZ}ZgLi<*;-4bi17~-+YZ!;1oUW-vHv-I>F1nc9t^;~`q(-~H zeUBNm?cY5|!_ES8x|?*xSr3uMnm8d+`tXqpq?mYpi}!)|;!H zf<6P%Gc2U@r9Z597Jinkz*Gx5*Iml_O-Gt#jt(g96|!fH}zLnOhy@&6e9K7Arf!gF!JZ4;NzYLiy%Hm@CUYwgvI!T?qz zxqd{d52^ftSdIxXO%~t5EVa>i1nCKV&@M2Iz(D;PFBUXOt|#dtn~=d@7%e*mY>X1xF*+ec(by*g*y}w|m2m&<{gbK^f zD__LfHTrj}$eToy^UGYMe34)lqyF4U%lmZ8>|FX`p{vx{CdElsOPvg+2?ezd7~{&X*?36tO7-eYG`!uvA<8~2M8 z8{)*R(qT%76sE0;-%CnAQ-gXW;hyr(mYYdG@9kq@-*m1H94uY(X${%Z1? zQl88)09=#Z$lKc+mf5Xt%s!cj3mbcMl{@y^pBF>-nkb1&V7D9iRAN$pbSXCy;#Mn# z17smWf^BGY8J_Zz3o90 ziiwsh%WV(}@zVLSZ<|T|Zu=@S9T^s9Nwz^l!WrKJ8Qqg4u&PCF>_cJ|VwaC*b|dZl z-+RmOWQ&K!9F72GT25Y7We`?ZoW{A$f!97kJ|G?-PVp~dAhER7qY+<_Zsw9Wt+N9m zm}^PGd)AS_xmZ0b7> zup^$(W}T|A(c7J3r{uq&m`=|iCsEZ4iuTwAOy?^|?K2H4qf0AV``Ehrt*aJ$H)Du6He7UqtWr7e)ll9ppQqa(8UQf_k=y7L3uu+ zQtsr9Py-~>RsJpnqX-+Cdl4i^x5M>?KN61oQ-WYX>&Btv@1dJ^lnB+~>a`0*nOrL8 z6$K;_!+uN{92|M5HKxL@#xRkSc_dPBLUr1~(Xo4KN-<@Gi%qgEju+1>w0WV9&Rbr!W=E?1R*2h=i8576b(}y+p zm{`-OI_->7^?_xYJLP~<-ikfJ(V==`Y`JNHn~2m9;{0@hDb}?G^#+e9MCMbdXKZ|& zl2RcIq*(w17_xTgat!Xw3>g*G5!zA#PDd5AK-F3*j!&h6igkUuse;LJT*nx|K^rg8 zlbVT!emw;nA+?}krw{-gbAn!;rkJK;8m@XIg>R#c(D5yjow;eqz`r332^me^wr2AF zPef-xNOvD~R%dW6(YL2h>?a`czzaUm35@<%DGlZadUDL}Kr}#&{Pcp-FEcC@arnYN zAI>B!#HV&WcIb6=3 z+3t}w<*b(&BYmW`lz5j!iW%60X6e$W>?qbfZr29}xcqPDavaY$*C%cLqE&!IO|psS z*HwB)d?U39_3GI0b9%K*L}Dh?ipJN9uAU$&wW9=PKSxKgl%nGyJ%!~tC~Li`^IDNR zZm+HLPp*xid|@#RCN;$lpz0ym|IPAcj;FI{GX~GheNo!4R|p?K1ykxG(#c# zhI2lv3XNrl&c+UXR_n%N)!JS=S^GraZdm(a-8dT@n>jwmuR|yBClIq;^VZs7PW~>k zZROfNBdcEw50s(j+7x%43R$mun0bFTqxlwugp*?_qQ{e&5WthA1iik9iJ745Acez} zuV@ReX-msUR@_?uAFgA?oqIoJ=k3RRIvUno^FA+44k3fBp0K$b%w^OyH$iusz)?ND zWB0CeR!XR9rXTDK1!PU58Wy2NM@2>1sFmfUaAC*2e(wG8c+CgViU z3QQ3Z8lRYWj*w2op&OyX!V;IA{^&&O|KwS-`eR@y!}&+DRlq+B?wko3`n}5I{>n*E z7||;$VJTLm<0$&RL_~I@kX6uD zIL)#3@4Da=y?QAT=hG?ydnWBfLHU_3#x3A!I5)l(cJF_xxBnD!4>3qXoH-boqJW^r zRr2J*)9*A=5#zP42JFMP4vpd7)s)ypylu5i*`R5r0N zN|l8=Kh1T694dY9$<*F6MU-2(!sv74>LH{g^6rS630I<_n9UZb#Er-ouX3jA>H0NnO3j#Rw?f85Ag+6;h9R#}^N3h}r& ziGr?NL!~tEx-e_{DP>{T*T@??rLT$YRh1!hiP25q9JsQXZ>BEN+WL}|ynJm#L(V*G z?E6QiLswUkjce6{>l;gP33?7rPFU3J+=`0rjl^Vv1Kn?+>qV4v3XjhW3elUzl=FK- ztTD<*-;hBM-RN(Tk3MlpNm#;92b88aKDTA8l$yEL+K`-_TD=Oe7%-H^!wc6pyRbAk z?>B>zk`k1pVMfAQ%H}3Xkf6E+v)N~MSFNI95va2E%S>$Yc?A^B8v1UP5`-~P^F4higX!{06Sy(>)c2S~W zv_AE&^T|mHar=Sv!d`V@czP;WIfq1ic=t0O+12d)C|ojuEAb7VC~jb$M&kQ>-vk3Ur!Q!7u6%C)gGRAr2C6F6mBCLk;3=d>wA%U0iw|{J?U#Gya}vdwNlyLo zanhm}$~lejSnUqSBstxyt!vimrkt8p7FCLijcyWlAqlzgWHg&pz@e&|N-~GR97rK_ zDxp%zXwx4dV4W2=?dVS|l-(eL&hd8We~<9;FzzcX-1f}Fxz zm-O~VXlEadm6IZ;M$o$pwPvUDVd9PQ;la)*4f#mMoo^wtc8L=^NvN_BEy)s}I-4Wqa!vC+4=(%a-9}# z*W!6i!zK-7W!Oi5c#6jhBf4;CM>$uZmpMPQgr5sPg~E0*dKNrtKl->|9>;3l#wXoz zukVR$;24>3wC+qOy<s=hHun49-OY3+!Zl+6F{WVn$Pn1KLH-FY-ct-a`*V%C znsc3B?0L#NSbt2xr@f)pItpOEuCzSG@@`fPgTo@kG}#IW6wcDApuQ{}7y#1NIF6q>b=iJi2_ zF)16^ctJI6HUBVSS;^7*n?>BSkx>jZ17%5D1Li&jb}z;raMb@MPsUz^;0v+GJxp%- zBKO=+w`2CsL^s3SD3Vsi8DC-Xg(|~*$&r1bBKW?~U$1IQ6!p2Z5}QhrOt)(OD~CC$ z3R2sFuccgV4@IHkKhM|$f>3B?7Tqpr&NdUdag2bCZZ4DK&MD9xH^~|;Zco`R=Y*ia zdY$5_X65d~q{!Nhx%#9FHoF;{p@RWa+9Pr2Wtt{c6?I1fewp>Sjbt&e4qg3BT0FH@ z#Y|})^npI7KAGyp=&}xK{`B+aYG%GkS3ce6M^$IOEU-o#(^vW;3}0==8=P@qk@)8p z@dn)p=)2a5lz)GSLoKC6EuD)If{)0uWkxP7hLUJ!IMYCG8i<{^k(62=4>VO`aSCd3 zxg_4l?#2NmP>vCne!mhE7D&MWr6IR9hvhqTz`B@`bCG}tJo>x7;KhkxiN%qU88BV&w`OP2Zf*r zHaPlaQB<_xM|OcF>0fAe9$lz9a4cd=4kP4{3OH=BW~?PanBWpNwJAwt7oGW9$NdMD zfn80#KYY!JDQ70i1p(v$3E#@- z@0A7%C2?_&kwR1eg06MFp^Rve1n%d)gDze~CchSDuS$J=*vaghmZz@u=>yetDcH7D zJ9f6F=ov<*{*9J_FSxvCgyxR9l1zhu)Ow0wntW5a8#H}|=wx2nMCF%4$w8Ex*vn^y zGz>&2E$89a`-wN__;rkZNB8*|N&X0546>{pFdo~>_t}PA9Xsga-&Zo=%0%6bc-?nm z+GmcfVE2dD^>^R5U++hqJKqj@2Xhyh=zkN4L&1vy<0yve>h>wbr zDpFg;p7_{gF}=^Bz#IYhv(M>YJl-DnW#0Ani7j-u+WmuO`P;%G?k9Sx$FCuk$6lRL z1G!9}V{49$5awTPs@5@ns!;+29}dGXq~lhPQ5Il6kT!ZRtSc|C!K{!_{S7}S{xEk; zUe4vd^PX!2)Feg{W38LAyfel?LOaX${%|J(isSq7?GbN`%pp&^ z+z?eBSVTK$o>LekEyd^6>a_@iNrK%!;^^H5#|o#~Tl4Kwhrb~e8AqW1!oe2o8;JEY z;8zJiR&P;FNq)&SM(5;mW79C!_=(&8q_aEcWg`x;=1{kzkqn(sj9fM@HP(vQ@K~p! zav|sB+UJ#BlZ#d#&-Tk$IYPh2=UyvdCNSa#o}#O9Riy-ck&-{otK%C=aW<94oY_o0 zEQ--#8F*VRfr-%rgegGghwHIT|A}nGV7%$(ZP_tjcX|Zj1Uk>#4|qj6wMBk>u*r1>B|NEn#;sZ8LZwQPJG>U$^)y$ zT^|lq`DagTvB2XA))9%H@|@Ao<0hX#Y#x#9YKm}*GY$=20mG>Mbhro;ms?Ry&k)yD z0qxt6-Fo9Uj^cfw3QX~C@|s^f*fs{M`sv4Utc4$aC|!cO3e zwFJ&VWXB)ODywB2_rFf1D>9vinL zxTI=K;Umifl|Cy%`gicFka!u>?z)Lkjt4G}HED?WpqQI}uBJ3wIz{@$@CYmASvg-z z9wxtptTGt40N&0}y#!)R+#F{vrDuFYaDUG2GH0T>@z4(mFl!K&Nhcb;%XJPYX?ebU zww+)%CDOspVdXKzhR3*E+ky}og9C0;g4@lUS_YnKx6j(u&wMV>W?D?_RWFx2Uzf{M zQT2ELC=3ks8RUNm7&0-<{(8H=1y%XED$&$-GDfendZ-nmdMDBQUnhy|EZe`4HsF=B z%t8Dg0CB}7zu^cYc7n;P6iH#PE>U+cizHrJQiJ-XQY_IuTvz_7`jv}FXbma}i#KbDgO6vctpoP2bM}r-PCZ`jG$XaW zkQ67#S7QXTs^F^m?v;s16W`#FA=m!ni^b#UwawQ7cDze0e}AvnkFEFCU)?`ABOv}X zA*=jY^!M4?^fv9%+czi6nX>D9g#|Q08VdLBB!#i6xCIcRvtN|WLPwZT@c6xqZur=@ zk5`MN;8?Uf?+A1*c^7C2Y%EC(S>2H`+O@cJ^;x}Y5BKjm+!D5oc;Ih`rRns7cH{o6L(Wt6^59P5?I2jBuk)bVn-q`P&`QNZ zrfJQ|^oNNyOp+z%kKim_s+8Ix`U;TqCst1V3V_~psVFuk$wvl$^DnT)c?eF0fX>a0 z^AGXXlCpl0K>+{)$v_@ql$R7+=G2_N21;){A*6ofa(McPvHS-n z3x<<&d()no@P_9tSAB|$Wp*F(fI*0N0F}LE+E<6+{2DBjo|{^ONPfsyyWP_>64KU+QzJ?AINl zh4&w3xGmJeY8%>JC>GWmNbZ(&} zqN3{Pj7KEeIdhhcBRAJ9U^DUbCxRL08iMVe@tuaW(5 zXb8UP3uSD79|KsBDM-BQg2a0+P0{H&MOxe+zqEiRs1&yk2*-lGiG-gn?5=FP#|o-A zM38*m!{5=RrnU;C2*&Cm8<4-xG7tCuDE+Jw5lpITob zHB5DV`f4UV?IXOuyzWOLsT^{ZLd2sCW~=4b=TMC@a`P^UQ{bcy(}=6O(to*NJ$L@| zCpf*)TwR8Q#pCsuHPMnUoxb_~QmFU%6DH1DkXi;t;_6qFEkcD(GIUw0APhre9_8<; zApZK%=Tk6X%J{s%<+b6MsrVc2`LkxEd0<{)@u2)24egiTlt+KQwHP?vpM^OsscFdI z7hp(6=EFVPVkyv5H)8EPrOkL}pUzDWp&}r7yR3!<7a*!;*Q~5{hjS(UC3+brGTxS1 zH?D3ed9Y^R{rgBZD{CQX6N*8I1CNJJc9pt*4L~t$+UUO_6FuR5zYu<3|LgwX{x+2v zvOuM>D$vL{5Vx*J5tLh#+6>#P%>hTSKyvXsI>m{qCQk~f8nk>CY<7=iaxxe0HpgKY zaU7rGy|pQjvobK`(T{YwwJI7)B8gijJUN<-;9s!SY+7XG z%-C|LGpf-=XYi1DLtPAhZUv(YZ#1nx(8$w6@w|5PC!Y@Y zdmkV9pf3&_qXYmtPmK#WBi|GZXz zLx=v#`B|`SsgXo%>$rCEBeF+)B57fE&Znd*SPF2gn$;u>` znrXntgJ?rw8P&B<+<(0IqWuNk?}WFhzXw!WFMP9Esx8(;W$~)#u*&iImJg`!$COGs zD>})bfp*kc?WZ6%=rQyBH`^+lSjsqL-u?ERIeMdu|4~b@O7z+UNT|`Gf)6lsuyI2I z%X5XbN54(f*#EL6gKRbB=2SVf6jaP}*6jW+V=IRHSoaE~9=D!T(D=D|K`urhAswia zt%H<2USh2xB=9ra6Jo^X*&7)EhQXOJaIn&<{(Y{nUbOCVA9*NhE<7ZVK^_kp(p;LG zl2iDBt>D|QJib<>>pEofgHS!NrV1G~JG!Ikn+AJ<4Y7X1UhuB+L-E37g%Ir?t|j_; zPeQLkst*Sx+!RP$dWs+j$#$5qg2dqGmz3wWM1QQhjLWRQ{@`ma_a5}Xl*s~f`3KUW zDR8c;DyXdojFh!IXx*jUWPAY;Gtl?jBY0f?%#ghjt2{&Emv2MiGrn?g=!=x|-mXeJ zl4To-oLb(93fgOq&;C1HTXKy2Vk7DD^wM8w7#)%pqt&b<}R$W&kqkoW*2Dk|BtD!42q)*n@tGr3yZtE zyF0<%-Q6KL!QI^HjnvL&l_@Z|Ujoga6{tRbBmZ0 zDLF?4GE#6xf2-YVZR*`mITYsK#8iC_>Fe-O6ND4b7iP(2Nbr_yXouWVGRI7XyQv>g zB?~QHYou-vk(D?l^->OqhTJ(;lj-99_kCL>J}sA0_+q}<6DNTs;l*veS!XXq=Ijug z`Flc*0_(~&5C3NzC>7dDB(+6QD-jEW1vZDd*CI$Pdw(=kq;+##1g{gJQ9f1$kizS7 zEf+Ykli8+@GO9(Pz8H{SS`sDTz?NLanm0N8;iIORAk*=YsQoNzlq3+J2I6hye`6j? zMu*!ha!V4`RM|CsP4SsdXd&YbR$zy1fa+36120i=2y4gwxHNq^+drp!=1=2K`$FQG zqiCvaBjSLlu0E?BJuQG$fpTIt;#w$tz;Ny@U5@x&Ynh3?C9FBJ^+!hPiymXmPp%|R z(L9FQ?!6n6iP-FsvndB9N0+ptKw7>+gQk7faHaT%YO3G%&pGRMr^0>#=vWyf}Y6IlLwguDZ7T`qL!oDv1ArzV4Ki|vtO&0 z;&suVT-|Oz(3BMa*D02>-Z|FQ;gP&AtRDMm@{^~q2_|g`w}3zi{RAijF!WALOeiaG zhcH9XeqnChaQNyt_ZfB7j?+v#Oe5^TWo&bkFnbEx6cIQb4wvlLRMIF;?{H~=I!a(V z6!@6JBfk){)}_Y?RGOW*@qRzNC7q~u!w(U`U|ZVwGA_DTTwE9E-9;YK>#I}J=UZh- z|Lr$F&*vA307F>2wXp4Gw>CgKXlF-1?btM9-NO-Ks71bcH_(-%B%b#o+_!~sG_2wn z&Y+4r+9qq)V=Vvm7Y^vQ$Q}@a{#@1M_n;%Y@f&zas@-s~UQ7EmI#wTZ?j8-anPnB5 zE61=BB#(uJqY$~AE-_SBR|9NSdv*SmHN!*_aM4m$d$l$_rX45Vcs>5en|nveFWOE; zi(?rYLILkVpuA`E#TjwNqQM|P-#G^*>rz4)a9N1tm7Npz4(_xAgy`>Y0`72Lmm_uj z0lE2D$j%zzHc^ z(>;E$f@8lHx5gK+H{eV(J(AEeQD1D0ODO0Yv6Pi=_&pN_g|JqO{%X_p+qWT;I_!rQ z>L_P9?xPHaGP{;FXL?{$oZQ_xWmZw<_kgtD$=u-IQA=6zg3l3H2A+Wv6SAETK3q28z$YS#kA*SUjyvkdW;=}c*z&_NMdWf=$FA98 zLihZ*JHNbn-O=P`AiN5m@E<5?g+!{dK2Z~!gX>fyW-w@WTY(OtYEey@5h?b`BL86` z9Ih51+Q?1d)UL4D$1DO9{7?Q|Y(N58*vq!3*>K0pxcMrKVGI5l9JpPMZBj@0e`W@_|$U_w$7V>xNMqysi>e^=})aa0=BusHOH7 zSLHZH75u&l$^nu_?{L8HVy`@S&w~Wd7?hOHY6+eNu%f%6!xQ8y<==y6egKSGwU!y8 z6`vF*jM=EN+|Q1%CAV5EZF$1$KAVYGJCO_0yUvmY24z_BS=dZ9JMk3ieB}`Q6`B}! z`en@sDD3R(!>UUc@8{3n9fgc&o_i87Z-3wt_%*Ld+3=dP3i9V?8AA=I|6Xq>HDXBQ5M52_k0CttZy4_l-`1utWhSdXAY+(zr4% zb7z04zVChP3z=bZOf;K2-_Y6^x(Ka{DPlZ{i5z}WBM?Op9kp&r(}Q-QNfkH$3J;R!%$clD)hOq9T-J-*OtQp4YuyPj-c3*V6>gx&o>S$yZFbHqSz#G+tzbtYl zJQ^ee_T5{As<{c`eOF|Xu@92e9-(SfaS=j1qm0ml5hhZ$dq}RaI<&kqc zU9y^qEU;=OgWi#75FM2(*=KVcm^3bC%_Sg9VvhQs5&9E`9ALf`%T^|?REdFQ1SY$UKLlX{D?ufQ7K}!{a1sF zf*>jn-A*?*9`T~uBfNT>e%j?qF>)*()rt%UzIs&W&^?c>M*;_l z$&y14L;uK@_uZHM+b_t9d1Uz-{GLwnvkqDgxM_HOr8Fzq>%&zTBGwLD-&5~~bk*9$ zNoMa7XqT&);_G6 z{lg5p(*^6Z$MIgbMBkw<+5O*ZHZ6P(GBnX4v!+T*M?rnuhrH)(A+O|URTu^MPX!53GfmoriU#KiBTTN=iHfYc>f$i#@-AN zK*sJjLeE4?=$*)+uc&2AFb|_=!&X)?)DFo?uE44G$`g7O`arGXFJTY4XB_U9qeSqv zN}h2>QIEy=AdKOh|FLMAJvQrAywvz@%FbQN3XDz!nu;p=WtPojvxUYPCtY&<8-pd@ z_k&4j|M79lq=%anK6o!CL19*@$JI?Gx3~bSxF97Oz*z`-+ zH1INqsnE&5Oz+Mt0Lc) z24qHArk(#q6|fOWW?H10mm{drWVK70QOG>ZQv_V{rm$$O8Q1Ts3VaPWWeec=(#n=U zW1VFI>D}ELA%2t~>1V&8pr%>}{Uuo7dx02J-&FUJzgrI~j=F4o-iy} z_Mv;}cSCJZ1vm!xntnD}bZo@2PEH)SK<*#iK2fjncX9T; z1zmeJUP(t)(|^Na01Cg>(PjK^1pss>LlYPG?tj0@f85+q{qV{^fcx<8!h`$LYbL>! z6*Vb?*@jLpCIOk%v#G=mj2iBA@)s{ysZD1c)+7NNa&1COym-Q0m??O+nRNL=k{Z>@ z0UII;l{H~!fAX^SsB8HO@oi+))*0CVsu7;?;7L7q^(gngHq27s^yyu2>yno$j({v~ zuhgrUzCtee+2ho-Xwk-bcMxuAX(`LkW8>TMbftAJy&l49=<1S3g_Ljh z+Mri69Kno+(m6fkRU@)QS@#zLK)ZuM4P}EZU3z<+88h}(W0^o~wnKX)R?p**xUzUw z=_1EPM=@jKR&Y`hQ+dz9`;|jI^MI^~NSLaHH3(AUK*iWq*b2A zWcBV89kpZ!ef#L2cIX+f_GmHn;J}e%D6;9oE|XqlN=7(|0LPJ^;=7?G)HnXKX3F1U z4Mrb2m9YMb>i1h%!x(P)&-M=8>BOwYZbTv)oZB~19^I?Dc>k1O38Ep$mAlpg zWAz86wqjU>ZnUjfdyHaFojURCPqs*Hb=bymxs-4w5D+RjD#f3b3yrZ+vtW1VC2=bo zwbYe(YMzgD>GU%5zY;1t7jA(A!~l9H#UT45FXDJ7C5O3;Jj z4`uq94;^or5}Pqmm zyp=lNe*9L=aofMe$7zI9gISqBqa2Z1UXuP6Uv;H&ct}64K-c%hseTYHSQ(Rq9yhi& zPfAKpo0;PaAjm)4Z*)%;2~nkAb=u9j65&a|^Z6Q4LoAx}Ru2lOQfs_q(_;>){J8U^ z-)xh4#2}>Se&BduD!18L-s=*B4}GXc^C%yN6PK8MHgEoA%kNI1y)zmOCF0ahD(e@S zU`S>sn@koeG45pjrd^e4m0CZ)_KAq`a_H7VzoZ$--Qh&7x$zH1Vd3HQxtIGV1$q*7 zkGOZ6J# zHe>1=xXqA3<>)T6*AkB=^g$1lyH4CR+jgQki)=FfS?TN8#n zh$B}SRTVIW3Ux@tT)h~omgtt~c1Eo0{Uo8Kf^a=er1xUhk7U`AK$TkmZ^?8uo%jrz zk;#P97_f%BgDF8cP&|^*i#k=MqWTr}86-HWy`nvEchbyi zl~PJf>ZKB^WKrFt+hDORI}j1XWZ`qrAgfX$@k~vJh_h>jY(S_tIpM-Pp`xDgH+jA4rk*6i2$9q>^VG(eP%*JZPH9R~ z5C;j(#nklC*Qf=q{2-AZ+}{7FA1?j!gee={qDjB#rhz9>=h4F8L&##-8#YMJ+53i~ z`mBVx6yRVJNDC&B%y*otL(}c?K@!@#Rpr#KRhi~ESs~OKuy{X$A&I^n{|acjr$s?j znA1IJXq%%tX{Pn&F=Qr;%ZM8mx0dQ@8Mmu7N;`lgJ?JeMfW;sc3k65TetDU#tnWyk zJ=I7%G^fugn>;c>LEVWf&zh4W_A`aDsLDRHDS4S< zez6mjATIMazWr_q>#*XDh)b_YbMXsU!!DmuUo&M|o25J3; z(uYIjAjdYOe)Z+`Y^4Dy_hFPQ-sv1ge}w40@A7|+(;cVLz%M{aGcY-@q1D6;3Nudj zdsdu?L#sQ(KECtj#t58EDFI57)F2{NCZhkaW-eB_eIhAwvW23S~pIXph8ZZ>l4@+lRbtS|4DGZgHuK5 z;;`04(A(Yh%!qUoU|Sx)_P-W>XQo6GZ23=e-*376(J$Y; z*a1%-a3OClvZK%1TI<{W+SBhc!J+48?}o0K5|dzJtHE_0ZrOzt!0PPDFUaJ<6;uGY*xlGo%%AGlib@I8m{Y~Ef@J<9f zaRlFaceyl0a@1Yp$_BRSd(g9K{r>j+SY5vD?fc8Hh{kwCgtno9o- z$EoY3q3G*(Hq#c=Ak&e!>q$$&WJ{r!mCpCO8pkXQU`g%mV;86toF*7ruHGMd@)iA` z7YxZX(#d_~e<=VJuXzFpYK@O(tj6Z%q4o5c3S|JC4NnEWIm`;f<%-}!XKFK{jv~#Y z+;N*4y{nhdXm6HfC!i{p{|9A-w*LpY{8}QzQvJ$$;gKLn4Of_GFJa{o1OjDWp<$v! zEcIXgDk0;-_k+&_UQu(!@M7w53ilGnVuW>nlZr=$I3H%N=CJBVwGBbol5kPPaCrK;C?5|27X5XZ%bW<0s@zByO zga}PS%hztSt<%<Nvi$JI|M7G*IvzTMkozP3&e zjvZ=|IMSqhS}&uzzya#;f4|1#)Yv-zx$QF2BEY%z&t6>3echZf_TzD{naN;j$0N}X za8dsfR8+sn&?urEsIh2bLC+rA*jj63)zTwS2BSXh)Mao4@-!R^&oigo;Tha{N<@|A zo4Z6^Ben~o_E~qG!5XWlQKt8r+#`&of!`HZ%ED3qc;pFcTK?VqQ`C!Jg5qbSO(iNl z-b3in3+=spM2&=FU`>J_EsI7dgmlPKk`hgh2kefLjFEHdVi}hes8B4D18s-Dird)M zm4HNc*DR_IN9Q1f7lM3v#ELWo_Lr~nQxgZ4lczPv6Q2Yk9u1l1*QK;FgOQK1v&?pg z_NEXoIc^oX3^pWM#iugoV(hsBz)wJGq>O#TdeosW+x?u1&VTLyC^%m$k;gO7ZNj=ifoL+`Pi8Me{bF{IvttlvB$;*uR;dMs^ZqpK zH~7-rQ%~otSn#Gc?hyMvmYFGjLQHp|b@#bSelkJnmv$P$X913tnl} zpP*VIZR)h^%j5HfWGJOzNT25vQy*ccYubh}S{m%9d=I=)YKL;3C_-1nh8`srkqTuX z#Z(Q`zcZr~jvcX4$! zo!e>zVJ=w?7EICF8=DG|;~w|aAaL#92`#5L3DxFg4c&$y?zf4(MYcy2!2yBoQ%(y9 z)GMvnoWE*s^~C9(?~K#fJh1CCI9miDB8h{vyJh*xe`I=9Qp-!FIIt2P?JtRuUeoDA zN7EFfh#N=TL4{&Xrd?!eq*xh}>M2Nz9E!%k!s`yLYi~4DcUo`~BsFruPD0mV zVe=GWU^On{8%~lyt4?a!k7N`YS=Py_xE+V!g>aH*PtO_;%1{{QjbIz1hJYf^P|;^G*j#jt#^IK@iA7Gq6ksppjzVHNv85of5IUHM z7;-QuUC3LAIu;|2-s5qeOkJjCt8h&~m@{+k^pb2I>Y8-KTfU0fxL8(-#q6KLPMjTB z$&$o+6vRiUWffmq#hfz(qEgvI?jOblPavc{7Fc_iEEDxSDMPGul{;eO)IA<^B-D`7#4 za6RNETIutX`Da`>f7yn8q9w%=hG#jdbA%mCiq~hALZ*t}zwyY!-}j6gRz#v|j79Dz{pIPa!sjj>dMP8(GMx_is-YBckV?DqC3g}cMA>{% zb!LfPvuRpQbzTu1Novi?iDZje{4;49cOO@)n~lpn9d?D~_>3U|m7@uw0n`a~MX*Qv z{YGCTPQ)5H%oacc=QS>Kzbq1QR_S11b<&zcY>8aqy0m4=3|(UEDaECd9H;-bm1eG< za{@x#_eW!cr*X}jK9uhX^cD8%6{qIt1cH2*@_uv#gA*5Bz zVPho8Ht(uESP0{vR`TDpkqLMQow&__Lpq$$J3<&C4xdLf%^V;)hWDJs9+to^_5&~R ziN1!(`oG|!(&|CQmP0wU8)Pvml~s_8ugeFHIp|;}yq?RyFD^XGuNFktaT*mvzJehd zqexuqz45Q3@d>$Y`F`bxhv}PxAKrViv(DK={nvk&UwIvS_UtEzzkuU}5#UcFlT-d< zJhq;zwjj2bbR7@kKOW=fbZ*1AIs=acAKH*4o>!N<(^|Uks`#&ZzkHBiKb}|mN)zRK zm@t%2>ZH`k?l{zGT^;$qA9Y@|ymQ^(Q~rCgZ(P!I9>Q36Taf3!&72{hV6AM5HFsrr zlrK|t_wbNjNMV=HJ`C7#`lEGJYAvJuA6=-B!`*iFcQ%LjTU1Nexjp}hwBqjbX^l|4 zlpxShUo_WQCooeVlbVVVHef8a5kF$uxI`}9@5C)Gvobr_#NpAhX71yYy|}0j6vDSO zB8}{^pzvRP8rVsYW$H?CXz?+az61~xH$ErWvS-WE-28yw=gR+v@-PQ~_4z|Pt*)VA zV0s!k-urjav`;nt1a_<>uw$6f!h`2KNP=xUEJU)6vnn@#fwRZs~xl zX%5z(Lyk0%@DX%s}B%Q?G1N>zI!1CN)H{@Lg@x-v$$lK!%S(VD`d>5{ zSOU0J3i)ZT-){B`0@+i4R#$fcJa(2Nu*NRaxORT{tfI@VNQs`~dUk%ENDjBOTIyvC z(8{GWr>Cc}eoKHdFQHu9);4ysQ06>+ec$pysHy)ALmA8hAUBJc=cm7irQRyaT(iH) zT{oC#FCVhQLQmYrpS>^nU(POD{oY%&R>o8IR>X4ZQ4*WV8X;mE;q5U3)upiL8IEar zC3qsyjojjHxBX(SAkK-M(00HYf$9fIgr7pi|G@5;6f-3dLZI(J#U$xhy6oG0CJ2wC zSduQjhOJO4A=k2ag|A7+p))G!8%t72_cUgtCpG+E4()%?U56OE9&fsqvUUT!A(aCy z{SRO9Wr^4ARK*_^sv7;Ux$=K{x@F=q8%*S|Z82?R4u|(|c}QigZ54m6jZ%v+QzgM$ zihyx>qF3ObLtMj2EWz@l{ZJ6$MdLRZ6R&c!T973PRx~2CW}&_X_KT2AZ#_3}E#M1& zTr!AGCG3+ib?v#>dh$iI&Z1Goz<6n_Q~X1l#v1zWSXyP|&gFoiNLnr>?ocKH(v*~X zVp+@_e4@SGV;7wT^*G7&8*^8eCkr`>Snt48Sp?@Dke3t>0}1j~xhdKi>ZLz>wr#qT z`Ugwr!|%6N^ZW8E;#|F9M83*@MhMJd#3``&v;fimf-HOfjqsP13v~9#hrxJL!ab^B z2PE5u1TV}JWmL+iaA$NojqNKba?vnYtZm-_ak3N$Lk@vGNWxI@9momSMHBrZ|j8fI}ToMdPU6^qt&<7kM; zAttn#rpNxh0ospcZoI+Zvc~i0$ zUgBCvZ*y<>K5_`cRdpx`u0%dFJ*e=?Gns|xECH#VTm-U2Yz$08p8>_l_S2JScyNEu zuXTka#GSmc?v}^mBEdLmecIC_TmdZsw$G#yK}3cgxlnG{m$js4^Wb+R z!RkhYd&hvCN#uYZxJ?-Pa{@^TWh9~~wj2JBFCr&o<1Ww$iky*i#xm>h5!_O^QsVQ6 zjxCpDa0MNX7zZ7rDx}ef6f(ff?w{PG5QcFt86G-Nb$tFm>5cD=D6_W=l^2B#XnHXX z$d>#|-YU6!^}(^Gq3GQqt2sLmM8maN+9RVY4u!hZZEAXo#g4{^X`D2x#>b9fB z@;^EJ+CF#W{mA~2oUqfsJ&t73AbD~>T8|?^QcXAI$kALI4cSo|MVGBZI>_i4f0nwjV@$ci4&Af)}C76Hz-NT z#+UFvggFuiSz>*ld%{iA^FqI~i}U&dU20Ow4k(Dghp0`P`1OOwdC)I#CAk6Y(i^|Ij~J>NpA*f38_i){CJ-O=G{dP(+}mZ>E>mQClWvJ%OOSIMcn(XhmQ=l* zO@)IgEjb`>pr$7iMTC{Hb$(4`U9#}#qE_k$4mc@I9V2o^tbeCuERuR4Tcz0ah8{qr zSXOTT+P)gT;ml7?$nA4L|5oiwhhSCHLX3l8UqXzdCP-rt zj@>k`GhsAI6R4GW5P4OJLr8z4(Nz5Ta>Sokf*#f)RSuUjjD;a=ZWjh-(TdOu|KVom zrZf2(!K{|izsCw?jF*q~r?|M$RUGxZe&y*?hIHCdGvojMF`24q5c!Z-^fjInVfmZEi50sIEBQYpB)QX)Kv?R!uqp*}}Iy$vcSqC8I=r=;mUWDU^uhV<;zaki}r~j})!)>8fqbuIsYF1d84hgy2IR z$~6(t${3Nv$@KofL?TT-<9Ffeb;hCDkP#~#Ec562-_gacy+>!RZFL)TfY5W1&@RgR zHcIPW9G~Y^AB@-LZQjU2{<|B1{Q(mmSJ#RBy6^2&td$Ca*V5`OtFkRQu;LWXRxVk=C!C&60ke>BkTP(aVW3?9iYEPpd z?av|I)7%X3q(&Yd>A(_|f*z;eUYo3Zp8r|zayy9k7gFPbS}6;2T>&f!SlFe~%wwGl zEX8GMfLYhOyKlf$6(ImvXBvE}`EvgrJ%_QLxAkA%*pl1{WitJXb=3Pf`4zgV==WFk zQ;uNQz}nWkyF=HVM*D_C1IqWeWq-e?_wDzW%cGkKCdV5;Tb1VKn=}MQFbB z>TGElSzTS7UnOjAX}R89xO~8~J$c5iZt>bcRpR1Cf({-=0)hm?WH$f&*#^jCMChVn zm+#Ej>}y9ICEfMUJl*YY9+N`>O7J1q)J!L%;1lu!I3)$6(62nPw;(C8a@m|wRE@$a z$u^t0(HB%Yml!wh9audI(%@c%@VUhxwImN`h*FC%%`lbJ4AvSya7#N03cI1-h?2@Gg^EoPoEJ~|l1QBiGA4a(bGU5#5>H##mC%i%r!!f$b_QEW-cz+h@o`N2d>#w2?8UPS@Db!INR2 znScl-FNrmzmV?wzU{f|7KB={~gA8;-J7+I|gEbFe;^&2B?%!4s!>2mi;)yW;tuqLU z;+&Bbi@|Fv*Vhl0f#I%*7PAKce3xtQNoE!Mtr*SlvJH3S&N5zLHkAY1Sc zoiZjtM1KVZMD&V-OGMF0zQu?dzs^HsjYD^qnlezJA;5J{V&W%7ob=Z(5-nQ9GhXR)sFGReXS!?W5C)mb zQ4sx=P27@eXC7IGCS<412$sIy=5QA0FlFj!MQKVOqj_uWvRKIEl^`+QYHR1$%sY@5 zo^J>i2}G#U;&Wy)CX)+0LN)g)Wm?ioW=`eL^&VI3rB)aw{PSj7W-tQzwyZMr8LS}c1W2kts3jcAwx#flVRe;Jd{qlgG;Vsp-xa< zx6S3s_+WWP%!3N;63ss^4TmU4&mYi71!;8ln=-cLNpTOFOq%G}qo@Q6amq5TL`@w!+>WjJFJc{%gkE`l_%WfJ zNx8p%myDCAe_wFOoxRYfaprA=5^NDmer%FM)k5~nFqOrIzp_MCt2D%YLxR~UmOC5mvcYURI4n5D|NaeM) z#@o#OTTwdbw7+GOqc}Jp4+^^du}Gvo^paeoEA*Sga0|Mi@;uYhvLnZKw5Q#7k75D!1rjj>A9PrA%m#Q7VHDn{x3=Adu6S^L&;f< z(V)Z~Qr{g!xsw``IHONuq)}@}No;Im+#@u4tyxSjuv#1Jy{o`uF~rfCimZrG+s8Hc z8PjFt&QVTz=c;Abl1BQ{^kO=sBHUtXv?jcenWcMZjg8byD+2CGKis(Kt_j(3Gkth@ zKO0V+p3qDH7;<3s6sxQHC-5ZCjE#Cka)DIa%&aKYK99n z(K8d@;B1>f6%?V6Zt4!Fn4uyU8I)<6x!c%s&h?SQ1SBV^_is* zUKK}`M)ZF}#fMXl-N8gJbwsw*W5lr2=qi8!T#u`m%PWyYj%~_3oM4VqrBN})Ry9<` zD_dXs2rxF>?q}HlnS-Pz*(|4t(}Dt*vT}2C!T??`v)7F;{lwxIqaVNHNb2jx zEwz;!?MPnX!wX}C#hj;%dV3hp zaLE7tT+{W(!Q(;pJ65&VKl4riUG0QnefU)V=D&v1yloxPi*2EB)*|q$X?ttpzbjWf zu>5{#Ia(hx<9o>VdWG`A{2vs=D|ndZyWEHIzk+EyNYho4xsKB8-0fV~eauR|Xw&H4 znp0SHg`6dZ?Ol)fYcGG@mGNr0IApC-Ik7xIRI0eo+R$9^o67-K+q+>7U* z|D!|XzYhXn$jSyFjfeq4-BZ0aAT_f;6)v1Kf|dYvc3{WJn#W-7fTO@6rhs17-Q69? zAfJ=KN;KC_rqYSl>QBCJSP8UQGuyyOWFwJSv$t7mMP4g z-u>zE_ZRb%p~;p6lBYIdOPjul%1}2c;rs$Pu2^{=>@cuIph^^VlvGl&HSN!n zk?%b-TOV&*4FCi7{LBlW&8KCXrmV@;uCA_O?H|n!)wkbIj}QhD0C`oNKt`k&AhCoS z9BoMN0Ol)p>J89*h-2;Hd)4duVB=`j1LE&qiFfTAZ4FU8iq0O^ct+_-SUjE%_c z`;WTAa>k_UKsEmv-1A(~GhQb2=Ea+vQ6_j--gzSLxI0RbepPn)ovX(0-1cb~tEYce zCq4h;DgUU1$&V&GI~zcn-LD5suK(%HfMI~$ed#}jujhuYr@tZZjvm$-L&rJif3I0i+>qOfAO94e3INu-!DDmGzGY+hNa(|B zc#lQVXLaE}8NTh`yeyzs<8wO&v?~@h$5m%rb?g2OT-tKB@fOmUgbnFUqfmieEtJ;= z%i{IBVz$Emf-}M~GS4+{p3J?D5`~TVdA2KzmVs*jtGbDn%2UKjOeb3XDoWZDGn3Zs zM+OG8ExvNfkCZ_*IzrDA=9GyRr7bhYhW@VCxRtj5>#qA>-S>^{H%U&yQ6)Wh@dNh> zb<;ppP^21DW9gk^5eO(~t4mmO-IGU=v zhG?gN8O!3We1Py}{Ie(rLJn_AO24oYTmr1Lb&o!}gX+*kFRSTlz^v^2vftE*mo&X* z{E@}`cbItiWeXN$>!y}oMP-v|JGYp|j!@SxAv2MpfzA~Dp|F`oUBkF=jG}YU6?Ci< zQRdY(5Hz$w3b?!E;xdK@=&Oj10`r{l6NAYQnMyIh~NZ+p$k|W zlVB;VzOqQGaAY#w1g)&IY;jQIXex&#CqI&!bah2#4v(tTt;+n#9Hx zuWtjU@EBEiRyRT>2c;?!-9@NZ-4Z6jXquIxg6VK-Sxqlv1=a=atB@lw0%A= zxr|LtF`{@zJPMlE0B2Xa)QB|^z2Z90QXsPHlyE23@$pWJjdVvb9fr^z950zl2Qj3a z2TMnYMtUH~L2sJFW)|ov{4^0=8QO;d)rVi9?WGlWfu#ygq(pewBFxj;5|Am@=iwI$ z=to6KD}|+medLt3Lx!>7<_DIZd8K8QA~IALl0+3iR;w>9+MVnNN_S|5kFjC~A;;zmS?fN?(QeD@#_ zTB9&MKmBmqZ)-3JpTyO_c64 zT*@H6J@yrf5#YP(M@y;Ef7B<{!djPOgjlgKVIYTNfl82nz+P!fvIY*)%BXVmR}TA) zvySXjK%>Az;Gok=g9qs)*?2|bwMs(FL-b*Tm_?&Q28)T&_mAm$l`2m%r~~Rpl{9v9 z%5tP>L#Fm(Bz9pjAVs(NxyhUiP-&D2Y{C1K#R<@HCj1gIQ-y;r^AZ%C1e@}8@rI-iN!osFla8CRe zzfKlQYW9OgTlwJnSAcdNpei{iGjGwgJ^Xp|+{-+ZI~gMIwvHxcf=dc=3=){8%> zM5vaut_14%{4Ttha$1PWZXz`e-Rg>t%ih&@oa+;p5G5%bvRT*z*e|lE3fgPyKNfY3 zQ_h*Q5Mf;-(P*SQBrvfXV`y`?Pc6@mn15Jjsr-?FQ3<4sL??V`9l4HF^bO+A2K)%8 z_+Hw(F;t@rnVGDZUxxc);((zByll(H0m7_|@&+k&6>5netBt`Col?Kr{&3~E(T67M z2;(6_#}cbrUO|6GYSN9iuhKxUWdO3xn1F0EhKG#@R6yGc0j%)aox2z{Mu3s4&!`vh z`w4D7O?$Xpc0JU0@EwjRz6)+%$9Y`+{3;ODanT;l)$=sf3DA#aTZTJZui5?sOdmH) zu2US#%()8M+S+|zdhTs&4l!z8IX)Sa!Ap47rodTkA_3S zI4yq+KptL4d|Ur>OrI=t_!lh2L8wHO+mbKbzjy~8*Vu5FwCc_FXtpnS^f$W zy`0V#hrgWZ>-jKGo;a}zixWPL;sl;luelDz(8A8nPOY%Ay567v2Zt0v0E6etol-a3%ax^I0e`xapl3w_lrxH5dshPw9*fTx;wqCf2$5pe5}@KH~bYF zM$&Fe{pQNx|1{^bwU(MO_P1-I59iIBw3e$`F%)OunVo=Dx&hE`VF6|SzhbKE|72>h zaAf5)ins6iTtJd%=f~USQFX_A8nasGu>{kudW|n%%fGJE2Uzf<4!GJ$*2OSD*j01h@c(Yc7aOfEXOb+j^7~1hR6IN@krV*s^#E=5vw$L=93XTQF-{aY7Pv~vNSw?&+GtZwG|)at!QdKLkbE&r&2&2VF4b0 z%*@4r(m%5s>r{Uoz?)jO zPrWdL08$Rnb?izNdL8(Pag94aw+Fb_*4-#N&y@)S=w8FOMZ;^pp4%RD$j>dC-gM^L zHvoo=1Xg0!ob=s)Xq{>%E2=R?QV)P%u3>*hoE1BcrqSvRjivkJ7)Nq_4C%63uuHv!(rZH0QYJDqFOv)1uchG(39uxiH@9 z_FMNl%I(~SVlo0;6PjIrF#&%km15rh=v-0fCGhqn!Q>74?(&~7lhta_1ss?0o%bv>mIVf`%U`opAo_4IxMc?TgQ)c zHqZCl{P>5w3C4~XX2hp`DxtBjLeJ8G>k$vY-%>PfXY~`UA9+4N-v66&Wz)LnUM%p{ zn{O8$u5WkCfaAdz`bcl#hqC22D(U%{+%1N0M^`l<5^BS$hFY-Q0Ym~?1u({lnHe93gJcK0Z&IaEvjKQx_FcwKF@g&RAK8{4*RG;D0!PGj44W81cE+ilX=Npn{I zbIwI?@-*GqYp-<8Z;W@0S*~0}!k3rqM?|y<4lO%6lt;NT(($$W&dwf0$R55%n_;CQ zA9VZxRGvP1eCRPWRzg7`Dd;!=1{{W{Oqnd%Qr_3KqkXMY;CQ`5PE2T#D0&gMz;cDl zWqRAHhV4<)>7Bpl@=%7!B2ErP4aOga zlVdvC=|FD>lOva^%w9dp71Ii-UvDOxujEO9!zZjRF3F4y$2MB@SvyjE)wS6MQJuJ z7<=fiX~(;NJ_5}n3X8qG%PwdUxQ10CmJs0T2aI)umZDMAxkP1di0(VXT9VFz-))(* zXAJ3*ssmQ{E3aJJrdL5m1%3|ll}jzXU&Nj?Z7=fp5+aio=k8V1up@Q^7uVF8Lq zV>W|ubk2I0c#2Z5gbDrnXu)@~mKw8Bt;|@8mc-gXDv(?le7m0sajv-^f^i-TJfgEv z)Zx$T(4s^A7g9OttVPZl2<^GW zccD$ZohS&A5)_`>YgrJ*f)tp9!PUP7K*NZFPZI?T;sm0>o}mq^3!~=+-Bm{l1)&ey zbtnh<`zA@}Az>0JG-dju@w+K;2BT5Q4f<%A?AlZo36~=wla7`K=I!kSf?MDXYi3pX zjh~?Kh_tjwWlhGru0x|MD1#wk=iv&`O5KDJuW+j5)5y@kgoBBZL^#M582crnl(7cD z5+TH(Tu?VwQNoVgO|ll14ar3ZQO~Gr2>?J9F%pxIKD4lide0@LQtS9kFKZV03|PM@ zxNt+`deNkaHsKf)dY-Z|N%RsGGc=`akT^0#Kshcl1%`nWuwnpKx+|nWR4S4Q`-Bh{ zM>MY@)}L^O`lepq_J!05wuF_M8Cn`UoDhNZT}WIPUD-p(sT=|YvJ1gbg?XzHyw1d< zR(J`vR6!r2cphAi$l=sc6jz**O2LKPC0lWKEbNPgVb&jo@KqkyF=Tf2$7^|TP7cEG z+cmxVUChk@`?ZKqp6rN$`hW;-f>@>^LSP4 zclRpR>S_fUGfb~XeWtC>4U=L{*Q#rN1cgv#CYo4LvWQlImY6b@3rZ=VU<)sq#oFjz znb7@UH)fJgr`l*`&CAj)%FHT;hW!4O{S1EDA|2VnbhY4NzE1YILPi4%&&U|xxKuu| z$~23EC2$!;B8Gpk|AGC-LWjHi0osLXs0OhdU9RcIkSFJyz%(P35c=SJJhV)hNSfd1 zus$j=s$no0B3OHKere~819wC^GID`7(`<~c!7Q~P8U7O&yoUxeC5>@BiD=mO3`~q6=*(g9)P!*$!oq}q-fRoXoTbdlr_7TM z%0U%jh>7CKZ>H^q6;lYme`gOGBvWo9tfk7x<)EGxfx->*VWn>~& zdC?ldOhZfREOKO&ToGx#p#c|pP5>U*n0AM3&DT0f^P`NI@YyY7o^`x-ll}*l0qei5 z3e&ZUV(=*|=@-MR_Xw3Cl;1I};T6M)Q$p}=7g*V8T*EQak+M?huV%wVW~I_%L|%fA zuj&TQ+upoVVrW^m{{F%ac*bLqw3;o5lH-+K!ZUOnm|oM!g8ad`dCkAks9!3BZ6W%x zC$ZXO#W4*VW$H!HuA!zXg()6zj*Hg6G{L#Jh}rRQ~Q7;MtM1 z3QHzM0o6h~-|B)hvs9Fx|J4{HG)G~>{!1OIZLk^+ti9mi)H(x;OJY9VXecDfBGT~H z6`y*=JOuf9JAc4#8mG-UcR4mD4 zjNz@{_t%{He>sa9uOk|-GZ{U@jbcykm~sxm0Y23n8`i%0FGOXalfoV-@lu6h1YH?)3PUEFgZ0a`c?J3#PnPNI*i67?<=;>Shn@lpsdT6OWhuFV{G-cDz#v*-bQLg#Jv<>6i^ zfhi#578Q|IcRgt8KDMva)zrn&5#$9s7*a4R5acaIBMh3w3tW zGOmCRuF)iTmJ4_G7?%Z&H9o<|)YMe?kX^@Cj^Hs9FXBL)ZcS)YN?RLO0%AATlDOx!L9ozTxx)1fK22p!kfFdjK zx}RILWI1PB1iW6BX~B>^=i&2=Cy0s4tgVat^Mu}X6@xob?#p6{`$VR1xOjtqDIA-f z*FYxaIFOBg#W+4W@fhLpNd%Y{W`UO8yE|6J(}w+$5>rh0*TMK1Z~{ax62FG4mz5rT zGO+RT-4mY&vU34nf{)8wp9J66{BI8Dr%c@0NrE0tm&#_?R5Uxgj#q?0O8o72%|B|3 zj2kuId$k|~PQ?j^Z2qasx9Q7S%cdvbY7cL2;#yf*X*-UQbv{qoJvEMTZWWFm;fP0dnRzYRkd$7YYR4ZRu;OT(s$S)=gI z6w+J_dN0jt1e~>%S71Ezj2{{iM zD;g5IqRu=Fg1C7UOVT(>71Rh#Tq+4(QAuAB`h+Oc5#LAJfU$g#DijGQP}iuHwxHfe z3m_zCM5KeC#>!Hp6bA1*mvkZ z3Y#(26gj_g6n)DGxI3!|K$7@QA~zNiav#kGTM@obt~j5!7<05_TV<;pWRMwOMp++_ z7<*^$Pxu`tYCM4vdN%mWAG~+h3;wTvURW1Ak|NG*9uy3M5@M#BWHqNOrUgE}I4t%i z>8Aa_@V+q|Ty)O7*m(FUv(H@EVv&}nQybUxBvuX0mG zIuoZL_sO5;! zN$xEwSGyGBwYb|FuHKsjgXT=;cS*3ix>1#HyzymVF-%+OfizTFgN zpUh>@cAogT|duw$J|zTh6VBv1WLjE<+)?anhq}%!LHeD8J5*v z>4$b+ruYulPdc0t;HVI170HeO+~=@;Ty|6RNutoX$=KlC9wJM~f1gW*kvwjH?1k;e zxdIa>ysBjs%4xY^CM*%H6sG=FG$N;jibt>sDLTCZ-Q-8l0=a#lWVyuV<6 zSkj<$IC{b_)Wm4!d{zUe+DT`YqPQ5#Rk6`8G+?k@QfB02747g1$a2QUVlg&khYqn; zc3vod*0||I5-DP9bL?hqo5!HIOcaO{B1Q!64e_5I)HJlygk`0;5kL$>be9VR2?JHw z@5rSru}q1Wt6HyzOBg3P%po(1_E5fVJ7pP`i&lMIL!O#o1>s(9zA z?Q>;$C&FiJ>^{NJ84wzS+h;MbvwaPbKv?YiLMppdxR6!yht)qQ5;03&1~^_vRLUv?Z^WE*YAL0nWzIY;w)Z*XHewNnbmp9;n>ja#`FYYYB(mV}|9C zPp&(9UOPU=+uLy-s@A9d$j^C=LL*K|S}vP=Xy}{X;Kiuk9VdG;7413msdOuQt)5v^wlt6dp_~FR$j-g$o5{U-%}P|J$Ktq zK5ZS^QT#sK@fBZr0CMjU#Gi7WT-I)j?`uojyKg6y361V!d8)%7n-+g0Nswr91aCU8 z7a+=g+_iK3_^;+swq7AJfA=$a^b7zW6Tr4srs1nk)>OQp@A7^767Vg2-9f$m!<*`o z9Ot9ERbV>NL49*=1OHg|6qP&Mko+|$b^@hB7a|PLPqR*HaQ>Ozr$3k{@(2icZxFz) z!`!`>5%O+HTmi!inBQlN zDu2yd?uIX#3DXGBd4c7rz>x#!V2TpwTG4hw;MnnEkxF31MFezD+KDhDsRYu>>KEE& z096L8b=Mr=k~#ifq_XXPHqCjSH2W`;ruUqzS5`Gok^>~JuK@cVvk0xm=e}aC$%-Hs z`1}8au6Q7`j5^K$VH?1Fzt~mqHs|A;AqW7{IhvRd?g;Pv2xY*d30^Vajs;v}$D5jaQ(7 z_5dK|Cue5lE6?8lJ?2K|Q^qMd0s*ItDRMwm2WDfK!5vsvpuX`1QA5nA=z7QMmUd8s z!|fwTX;CO zf#bnKU0`LpG~Ul1VsI2#_WF1ff3-0@M*EAYuhD%y4>7!rO0= zc6&4Y?4e*6>p@8Ed)!W0$q{A_cmA(Zt5zvEye zs-c?rXUd)5_c~JVa9)PtC_j>(c*Y4b5Cr%}GT;wa?)$l!$Ay)iOu-x>^zL9dsxxqA zRoDB7S9%2 zWG91Z7rn_JnUAJDSymS(Te>#YhE7RCz|pq4`IW?7@@op<47z%_j(2h_ z5T!~w2~kQX;!A>SfFhYOEK7Y-b^c~0Bc`-T`~|Gh3uk1f@mqcaqi~ z1paOUj!iY~_Jq=f(1MNt%Y7NR7Vw zMXt+ks05X}@}gm2xg(udlEND!?ED~v+z7CQb%x3Bhm9-)wI`aVf~F4ID&2{z>44^u z_@x!LZaJQjHa<*gVDGP1`HF1?P7hwuD-FM!H54%pmtIJ&5HkK#DpsXiW9Ssq1ic6` zj`&*INQn_)vQ!wP88(g{GHE6#2|0{?z}An5EQQYA+c^cff?S0jMv_SkdK%1?3^c<4 zim#s35xYbr30l!$RNowWk#*SQwEPPd))_ywT)d`&r9Z1pqg)-z3z+O`7^Mz~s3h_C zqmzfCZ+r+aW*j^nEF&veLc5^OWDY8VgpUqq&pa@Ll_IT2B*y4!B2wm~>%MDiNvZ5+?V{qC2+-&nMHBF&Od3@|1-uy}C1{21U(s+tdG`@B=xi(>Zva)3fFCea+;yPjAO_J=uEx?R>}w zh>N#q9>o4T?fPzpK&*5=9@mseB5o>)()`rF(mh_fa$uHoEu7CjdPuEl z5d<$pL)n0<1*16z@61xJ7}&@sD}qsZuL_-*rcTN3sdH>v%o|js%7QIJV_o09X!6q( zk_ZeklSElj-!N2>#L-H@d|!FbS?r9uaZXaY5S}QG(g1m!2rRUW8rE_D0#8+5ASyA% zv?CbbMEyccDVVMlG&BW^mE`A7Nhi++P;x^OHy5kFYiLv0xNrCEcK`(~t~A z9=0|?If8*U0f|;1*kryoLJ8J?6Evc8s;0Soy(mLJTpr*laQE?apW>$jN*kh;b45x^ zG#zZet!ob=0xv>M5IPGv6jsX|q;Bi}`$sKw>m-jD^a)a^9JS@KF)tA;Ud!1m%;dXfY?G?FS@`+O;EYO+P&+9zS zNx%KwlxWwt7>%2i&Z2Xu?;QtSm^d9}cO~?gA6oHCKi>HGV{7~K_d-hj1l*y|P4{UdS!7x{{C^d%>2Whq~JRp8X(9V4j-|Sa(+?d$d#1zq3Gi3q8 z)**$Oeu5crXk!5zRsIMF&D1z4I_10_QaD}h3ISpCnd{G3x@tu*(l$NojMJC#`a#VJ zV7w8vSO+-LCO3w!1pMbhm4U!Ch4Ia9*VpSwL|J8su4S{|oYjyK6OaK1(ABj2KAr!| zDz{ql=jG>2>_4LKP@>s?X|e{0I?-7{?N{4hVJIwJ5?-rOuXy-CmD>$%ZDSJT}|usE+3ih{`HkE zpM!U@VIveKC7DR|>`=)5C{$+KgyVGY8~Sp-))i?qB5%LY<3awJM1vVfYwH z$u?2xl%_L0m%N2ZiQ1RpMTUG(<>mPs7eGM}xyQ~ygQtW@iuF1@VI=~w>3 z1ltM@h5!zh01-hMF+JX}%{}8wX`p?63&GC*7Cqnn(%=PbGQ9nyr_nsdfOy~(u;Z%h zri)fXSJwnUE1WyL`QOjvZ)pG)mX?l=Y22~6guBopacW97W9oQN+UpHVO?uYSWp=o} zvr`l7rO~!=tae%C2e25?#DYB&9+G5vnf(dC5!n8_d1nVCEDELgdbENJCbzph%Ni?A z@_nNYFm0%t?RKX59ybTfl^xbhQf2GwS~N*waBz>CZ4RF13Rp9z#_D(-4-NVm3m4K& zImc($mse;6N|F*>4#ZP0Hd+!%nShg%K5(BZvKxDNq<48fE>FRKcRU=Kf|rQF-3!67 z6||DoNI|u_1@!9ACAZ(PZSyIOeSC6$P{^Z%>}kN>62KG%L^IX*kHS*`UK# zmE-r*+f8AdgedOw7zSfKd%vcCFv4Deamc$tBKx;HK`?R4C>%euRRHMbN0o-F^Kly> zEu8CaO)#GBH4ahgeOIWqtw&iD3zoRoUSxFldUx(uD*FvZA^3lwfb(~36be{9|2RX( z?9VR|1at9*bZe2w{_7sib~+d_*X8``S(r#^)yD;E!qgwo@Dv0mrBBG7QroRpCn=1o zBqf4{hG~LKT+Z^dPcoQDTqYErCWxwb9EDC&&P=A%=eytTahLo-xv{_i9u`5*V4wVf99E60#yCb(mqPpa#s&`EP{e zWYkKdqzf9Mm6-9vFzGnL8yiAA@cr%?+UXI}#+sSH+=U8+7wNbs zmlTIBvftMPVdB6gJH-lnMd-P*+F4u*2@cnmA{OmZOD`d;D9E%sA(ZTF2vg16 zP`^OmmhNno8^(D3yIysfjgFnd9EH4h`boG?^RNuI*q$P_Wj(QaX7P5fanGq`7h1LR z_1_7y4^CFOufWZh)@iR~)YRfSl#WunvvY8I$wWh&hU%e+y5?frV#dU-eLSQ}JLS@o zU%oNFY&jon!HfUt{OAyZU>|N{igF_)?H6}3s^6NYr=59o(3Q0fM`C}F#ig&VifY0A zO3`91uY9RBeeU~BuKO};h|AvrG${04PQ9`WS|th%0TgKPCfbafPsY^B!{o7Fs!=-$ z^BtM_waQ(CHa^IYs--FzQbk1n4^ zirE@O?y3FZiSgwW)E_SfaMzh5sp;@2ELI_Ztf6%@8W&Ta2C*DE#+x5`WeD~6hhu!J z6lGloYs6vprWVHy9sG{!CStnCdkcvz7Lk%5j9poOm?vIB!s_j~Hv@rFJaQ+tkfqHd zE^n2u6Ny`rPy9=25EjJ(txxhtcv6`=gDMXsy-+NzKg;R^Xo+!*E7drilXcO|k7mA< zTI~|g7t(KRHTfOSHd)$vO)S3_CwRSf)K-~XAlAu5iSw}<$DAgVxkUc`GWGPqw^<^^ zw9OZh5rH}siRMSF`)*N;C%S8{y0O+=n>uxr5Zo%3{wD1j~2C*J{dj_yUxfJ z=h4?B5R4@N;|EdHLEUNNljG%N)*D0PMBQ;3kQp?FyFTZFrv^^;t|NICdP^($cw~* zVZD@5NofA!6Lo%H!1+l$-=68R1-W;U_E*^c1+hva{HmL;SX^KxWhGLV!N*F%MADMo zrS(sgj3+7!(>cx*G~P8DGxk?Re-9}RBVt4zAC$x)t`czjnWoj_yXR#j>-|qeGO1xu z6KvaIKvK`>w)*G49Z1H+lf5XKoU6Ga|Ak#z)hDOSRBBCa@0b?h92a_E@5aBj!oXEO z7MCtr^`zSsgz)M=4np4iuru1t;OZ72(c7z{4-%y4;HpR(QkFuP(QMdQe#t0iBzgj* z;5dsVR*{F3K6M|XBddbtB8B#i)V@1QqhuEN$ZE4l5YYw!R?wOnk|NFK)I%@&iQ;FN z)oy3srxwhY=OEf@Nw{-X8XOm4N&RIJ6!x7Q6w`mLu?H zb1*3skuf8QwQg^J049L%-OQT#qphP;RL;9d3p+9S zJu({M>l}U0+y14u1A9ofyA|jG0=)x9)a^G3J1wH-%CW&i{e$0|@)Y(TqY{3Eu%q=v zPLWQMRBLrcP$zorskuM@%35b;9s$!ydPPE2@~7{Ejs(RxgWfr>87>KRsEl) zh<>&$6M$d*1@NZ(xkdnh@@W@JU^JBfj_7aqtL-N-dlMh)6_iiuJ|?5vf0U{>O_r(+ z$~dNsM?>oy=UQY`bfNy9P6{(+idyv^?wNG-HWT|nWRa0T3iGMSDM`0)(F+lJ0C{;p zHpfwvX2gB43NACg+}`p6I6w*MG1QzZaQ>IM*qh~+?&K2QBkt?q1(vvSbs2fbRi5#AVHp0V3cDPdLGR ze0&_1Z(bjr_^hLa^ZJOsVA+(Gk&(Y;3v6fuh9*!osK7o^6<*bt*gQ4N5MZQZ;^Uh# zXWd_|GpekqX>hyTmcp-v0+gOtAW8-(a;_KaE-5m7Pi&rD_y(8>CToLKgt9+?G!&4Y z`>#wpb5+BwV{5EAx~i&xk~kv&vhwtuhzbo6GH{H&nx5_xEvV4Fr`EkMU(tv6Ivnur zJwIoim?#PVeLHHudh)O#F!b>-{}Gt`x|Vy~ykScsh4LRLd6MmxK)PLQVPJqr^=o5G z-^T}^2;3wcmGabCQ(48|3DSsKlkV#g2geEwsD_@va_epYSm*o2N4UVh1A#+2I}fM4c4G8tpKxkfPhPV_j@*TTMd7 zX*PNjzk zs#~E3oc_OetX%KD4j{2t+bzFMHI~~k%f=Zb^}&dd*eFC(XS7dk4kOZAX#1a8#o&4) zO($~xhNxMfgpvkxd6Acof)=(@LxVRu{0YZosqY+ar4qzVOqap7ctm?2hPoT{5V`)d zj@pK?&cpS@D`)1Dzr0Tyl;aGa<9}43ZZ4&q$p!-^tG~}Yw)&fvue|?yfWgY$mQ$*b z1lW@eC&%q*GB++kw%^;14T^&_tw=3XO_&HIO$#QasD%n{;EIVQ9oPjk*!`PU{fRKp zX_g>&TqT|giejBq9LOSBTgf|u2BUz3=b;r1{3@Z$i*htVPrq#2w`&bqIi_T+aV<~zj2g_Fh;xizjg<2Z;s=NF*%w?X+Ci|=Y|In z-KeYc$SO?Jn%bbm{)N(v({nVQxEefzsV{B`Mr&=p1Y2|Da;D}c4yHk~7{Ys*Hgu9O z!zs`jd&I$%taMxY@~uz?W(wjCi<<+C+rN@R;ALsd2`kkeUjoYe7K065y&YF!`th<_ z9;u`1pgYG`PPV8Un`7H&)?u-9-me1rdNkGiS2OK|na%+eJLFIe%2Z_vXGtu=x} zi{RCZhxbCHZ7Xur4?VjdYRQC&f zyeW!KJPyp72-JBIB374LW+P%gklCh*BJMz^qg2e{mK5yi!D74c^fE}A@-e;@RyZkhJ>CNE(Lti^IqzR!=Da&flDU5N(j;QsP`-HRW8hXaJ?}x@j2(7@Kjp`(F zx9dvkGdo?z7|26bOYHLnQCFo*!P>CO_H+kP25l7s3lAWb6i9Sz8Q2(Q$I~M_guy{5 z(hylRt8bhq)_6ufrK<*try)@!c%`wNrw&>~Qn%IRT6aH?B7?|hl7LU_dCml2i zqZdxPPuZUb7xgcIhZldjO^hvxQ!d9iZu?^3Eyv~29Lc+3MR+1*b*RW-HngS53Z4MYO| z$!eXBw9H$32UF7!0J;P828mdF6M!K+^x&`STG9lnRwytkjP4hK_>Szu<<3lh3?47g zVgnw*jpM@VZ+4LH)3HT9!)*8TxT7o%z8BsUq za%etEaT?a+NbYZkRdfppzlIXcYBO-^XOOi27?kKu=`H}s#QmteS@bG#94%9AV2#FG z$;aD{`{C-q`KC9%6p4^zD^S|Z+15B-_3^-7Y-Y*}jTfDkag(=VYxK%H^K-cYpe@q`d+Q9F%Bc}?IeWuVDI`&91eK+M@cF0F`*u51vU5oiv|F5M zyARYJ9RcPwanIXC&*W$7_;1&vE|4?d`U}*q$pY%p&8n<&70}aITPv7z0*qPZ<8qZo z4DF}HFYo`rpJHyEVhIGM0aYbDKWxulvI0Fy_9IYRDr%7$uGfAa{YgS%)ob1m+W+!0)EXLCb1Z54E& zdy+GT;)8>SXChA|^whNjn8svd7Fr!lDlDHv(ceN0B!T8jKuda9V#&FNFD~IxKWKee zx1uO7vDs(_>J^!W|F`R?=xx~UZCDh&3z*(u78xP}fV-^HD1nB5`(wR#eH~kx3NWRW zAP2H|E;|!H+dOSs{#Ba)|M&13KQrnoeWFD(V=m2G~l^~et{)$4q>3%Z0!f^Gih)7zz0ur?#1LK&v-b^6K4@I zyYvltVDiRc`J)yNj_L+Jytqcl_RZZ0#W)4o=MpbEboKH&=``O@RmN9$uW=*_180NZ zkDH%Dly7zcC9L(nk(w7vTBhhy7Ff^8a4hH(UQO39Lh`|D*mYN5+w}oA7cFA$RN2)- z5hxecZ~r0b@M<_sM46&q=x}CO6S8=xpkg_xexl!?<@N#UC9LCVYsM+Eb;6}+UFmGc z1RHryoMcvL@Hiyw^DY5HUzYrSK`3Ect0+aW(xnq?2RRWntL96Zg;)A!Yo=ZsA^OsZ zr*L}N7NhPK4uc>g&vR1i2oaW2T2!#dTJeSpQm14*CO$%;smSSKGlCYO$44?%8yeFD zxt3CsV!$|vF!vbYK)GE|jB}GBjIHa3FFlcR)9V`}<%=RIs0X@kA1@Fifht1_i_@m* zXs@}{p^32M+hdWa%|)Oc2J})Q`7`j#F!p=xVAH!m6i37}_hQeo3;sf4 z?pH;3rE&LUrQK38Lt)E$>E@S?jx*5-``Y|P*`t~J@v_R_`&%uKzn{x?iM>{epiwXG z;*fNQ7zFjqTlEjEW!Zg2r1cz-VfxCY{@>PVoi02hR*Ysd$MI%U@h@#U$^(%s(#Bk> zEVt%MNn)HAAYj7+Zd=ZT*MuuEeGDLoIz0?p97tM~tckgNU{x)p12YjY>*dAOc{i;M zCT}@I%QY8nevf83KcGL>xC&lUbSaf(qKGY^gZkQGt7wAYk^M>H0K+RtQ7Z$}5|cgT z@85IsFBE*cIexaFXb}2L{aW$dd3=S)3A4fqD%&O#FFOoL56k8Gy;M@@?x8Zl{o!?k zv&ia^qR77+aGIV!);w=1H>%sWA6YV&E{a{*PO`X@Q%KXkgz!6q6vqGhrVuwwI|IxqKo0b0_Mu?u0zc79_=!ALIsR zzECk1(Y3%r-FoH0G$XEQo`mk<(hr7akWA;93 zp?&7cYNYi9!ZBk1JGS(jLzf{v-zU`bITAo1V_Q4cxqJq|D@AT0kIbBv!I46f-Gm3sKRoC!Ovr+3AqQnXW&B1M1$v49mqvb{KvG2JXwr$yGF(na@n>-$vGLGSI zqfyG@mGpSW$6Gayr@OFUI}erkA3uBoy0#D!)Ez!vHzP+Xw_`V!d%|LWK=K8K8R35v zO5DzU^^VHt?gN|Y5$HJBz={D*@~M|cF!G%dU1MpVp-xJbzkEZfHuf{?v8G}dd=047XBJ(bh5~eFLnsN z4rjPG%P*P=TUNWOzs0bBOd@R$dX_1Ud(v)|eYLagRsr8sjx3&-gknOMyj_&UC4R9l z=I=@+g2ghyaV;ep50iuhZyZzs52q--DL-Zgkxv`2p{}zR5irC$q{@~*#VT-1F1TDu z+XpRi)GUZCy(TjKtEWO^nof~ncr57XXZqQ<;d5mk_y<-QhwsNq-|_OS103^h`r0$I zon=e3HBzkY?2M{RoSabofKI)&H3MJ)*y$`0&^V~2r6pL4f*&mo4;hGP+r*U)uskQc zCtLt}ZnyiXHGOsO1zX+NI2es50pRnGNnjAEz~yrc`ZUy7Wq}}YcRx_HJgeyhtc*kS z^9Jx8(gSth_u91+2%8NE)p?ezyr*okyRU3A1*)!r!1!mw%73A8APVBL+(!3(qW*kGaZbpw zm`YwnCA+?6YR+cw4ydIb9E+Z2zsUF8PF!=}H0cso9Q>5DfTG9`oZNqRC2emv6Uf5$ z2hkiiK$bV-?RoVZ_NA%+6YnXYZ~ntu?5Tgvw^mMyC~oIJNx z+vyCOb{oCFDx$dzRX#8YLpLs)R{@POKtIrDM-za0rSb&Zk4h~?jTiyzO3acs)>(lT zUMZBn0J|4=;sKT2($c~Oq?AvxoaCT<2p(!fUAP9T?r(uE%JKbuV!%zrJG52F_`sKd zE0xdT9Rqw@tY~rI)@tbNoZQ%cV1MZnO7+}e_W;7~we|J=K;~CqI5F#6_f_!Qq5MB% zDB6u;KfrYaTFRkTfL((fMqhS!`vQU70{+L-NJAs%;b%rdP0yPRcqy;nKXUukft`K8 z5QzUW8w#Y`JA(zD0tI#>XsSZiCa?rW!NALQDpm*z|e5=zJPt81|G`3_570 zjHqUO1whNp&%`({V16H*$@_9^TKxmwcF@vN;OAKbBx9NFtH&sq`=_P7kn_L_2&ED9 z6i=@vQ43fB`UjOZLCzY`+*jB~v<_HARpgGd3_p3*`LdeEp1o|&oW7^ZD^_4DU>?O) z3**eH9&`;;eii9sWzeYnYR}mf7piNIZgm6Nd`q(Fvu|1$x=LDtj@k*$9Q;tcQZ zRW+*#5nWPG_&vO?Wtcg0u6atO8Dj-@j@GQ0 zlRnIqSJ(BIP|}+_>Vh_T!xU$uv*cIvMN&7OwM}!?ddnr+@OY;89@EWg;G#0=Oywjee#tWBKO}%m$lqq-*x(jpkYHl$DIx zETR$)wtHhTXHjVuc`8i0{8*7OF?vv=9dX&5Fk!UBa=@U}PkwS{lnYSF6ngCz(pp}P z-Ov%ZsB(Uf`GE*r3)Fq;Vm*X8{(@2~ZQ{`c{a73cP+|$8F$^miEGf(c5Rzqz7#}aLg?VH%zH+Z`WWDjV zC#3O`lzdOr{dMDv-C+(Y1!>G18)T-zUFqbvSZp0pIz!+h3=EjbBp5>?3QJ)d;>a5L zeoXYLQ7%%x;0M$cN^J3GinjghSD}mxSYphE8hH91n?{a~p_HkMPzc{nPU_kC#TqH< zI${P2oEV8Eu*P04aH5t~sbr(aWGo#g_4{FL^Ky@s-+vTJ@7dE<(jq_B6EgltIG|W* z+YRtk&>R?>LcqZIwu*mwvt;KL-2^vNa`I|iz@O>ak(FVSZyl_NlIVA&I1>R*PB$Lv}(Gy$oLf^8~Y z;~=c~f*I5&d8Mw+I%F<&1nS2^Eao9*ZB4SOrcN9L=Ts`DUu5@Fs{dZtBaDu+L{c^= zIYvWSi5eA~@#>dlVX1w;q2`7ukwbl*?IRg}aPl7ZuWT`%$Qz8KK?_5OKXeMgQ8w5- zrVMfBopB&~a7&Ej9@w0=2eXyd`yyIjqUw-5m!b^|n z7j1IG6N0feOln+i*hUZxV#ku-pjdd5>^7=q&#^gqL;ayA6(5Gq z3+og#xGwK4rxKU%RSR23kpRU@F5Ui80Y0>-pvGsKnBXo%oGqpv*@PZ1*S|dum#d0z+HF_Q@uoMMC1CBMbGEOV%BP)308CK5V_^Ra+xw zkJldpFdD@~{a^Jo1_dvM+Y+D?4_NEba5_~V1!RI_@cA%$=gnu!G~8O6)4r1fn?v#` z_n)p0-sTzJQ7+v_cs}E^eZZ*c)%p0Dmpp#EU3Ldzj)3g()%#S$>+OKxgy^dWw3y-* zFakhSu>tNF{=!*ORaKQ-S$kVu-~aG*j?s0s(H3rF+iYw*jqS#^Z8mCb+qP{sW@Fop zoiw^T-yQe<$;gk4oO5<|#-8t5b3W6E;1+B1-(rg+plIVs1*Jv-BYOW-bKB%c7vRYP zGN7A%pF^|k`%1GqK$W;G=>V{2oKKknc%MimIUNiel!O8LOn*NJa09qmbhK<&P6}lM z3QzUXp7X5t2TjcZQxZdX84(;f;K!ElkLGVsv2vif1AN89$szFi#l$HG$Wbt z&un6HRIB(iCb@A>RCm7PL`lpg0+k4=?=pXu07qWjkK`PM$r3Ul-cJ_2fFNG06|NC;-oXOAAwfy!UzG-pQ6X(s@a z2($q2eFkhlBi$Zvr+P6>$v_a7;G>n$02pC?Mx#3}xB=3;o$t%q^WMh;_rESc!>ABk zhl<;uEi(aTEN!2c7T=7|e!EYm4A1lEkK(P%hK3H=^kVZW58!qi&e*&o{|`tM0=!+o zX9$2FC8B{Llt77 zWp$~(wRHqAu8ji8>9MIiL*T=G4vYZ?D0=6q&gE|XIK7dB!}XeD)>Aenp~{L$s|JxU zM~=NZGIuv>9I=z+A=)Ud2_09AV~MHL0ci*9+B~&$$oI5>Us9qvs;IwEVDz}GRg}(E zY0E+3_Q;CgP(#7jXzP14lww7HdaR!3pwcfJWC7Z0<=R`9bIUFWZnC~x121GytBr#U z-!zm|5IPFA&wtwJTD`kP(&q#DQCulE(@FpMP`hG=eFz|fv#H{s;q3U>Kl;63i09gb zuhuJ+(jZ$q$r?}%lX?4MyuSA$ASaSnkA|xV-XP;##!@l_(CI3*+C><}&Cu>+OKym# zM{-kRKeCtZrH_CwgyxEI4J#4evi{u*rfu*#v?4r+&>}nn&3XCac!boXYK^e85?dmH z@PK4uRAtA5jABAIX3?4QA}X?@AQzYuVdrx90lDR^n=tQSw5HBpo-2PBWh3v3qeYyb zIzmy{E-o2Ob1DzF@pU0(-XsbYC@waP`_|MS8ooZYJpMSc8|jBPE3K%#A1W#`l{jKi zNMFZZ!miXwCy-2uo!?GeaTRr{t3zXtpdsm1eXSDS>^

FNLa&j~1>uERhgUT4pWy zqfpjFh8-iuRgdXTCsoHPfujk65bwED$SQ`7z-l2&cne_&nx`K1yEjKqfbdDETnS4~ z&I_GR_&)wud)U}Z`AWAfXWKN$gqNU*?=-J3-zim*;YBbOuxkpAa?4U_A{#w=>2f9f zanu6edbNvaWUZI36;>B1S_@TIHifxx*dzT$BCW+D zx&?S5NkkQFVF~VZl!;&TP|=|``?wlJMP|f3Mafyq)Xew7s3ocl3q482khQ{^<3}V5 zQ7I8&8~8%pm?2z*lH4Qzd{aVW+SIb-7cTTqqaRsF4dWHehfAtT`el^Xl;{Jc ztlS2vDga$L>Cj#HP~WB%5w{ZSz(+n4VT|Hhz7|@*_wiKbdq_cW?+h%lRIINDqZl0I zGXtjR4IMZR|I8vf^oS0Yp^CTC#$l1qkNdm0#jk2T1bf0E;F)sj816|-wMkoTgLP1t zkt)`4wjz0rIqyO7dz{QIpJfS14!1pa{F-tFY0`E?>#0KjiGk{^o!%_7bJfu zXb9qU9WLMCQMWS-ahN*qhZhD0Vmw*6E^BUfv_ikagy~%afg*Jwrn=dvnWsB4nEBf# z5*h7cB2)=7NF?YUKJlXRsv>f_Vd8R&sNJn0Xf*swAL>pWfAk(6QBNJ%>*F-u5Y6=QtNy`fXciv={AD-rvZV>}tg z?VNq-n#9txcKoJA>JlQk!5pS;=*BIIKJdpr3KHw!3=5-E^z!o!tnA!}}UvUH~!7U}|$NV7Bpm?hFn#Sp!$P1Y4;F zRl~T+uCK=0%ARWwag5djvV`{B^QI*nRzeH&vkYeYbQ|XKU(Y**ug^=5y}3s(kkGWd zwgP~KNI;*XTsk=awGzb=S8eBnJF}?)qah$hfGNtqH=mN%u9M=7R=~sj1f)~H19Wb6 zUERY^7Iy0=7I{$bRdkp0@H0^e5EWM}80)}|x1^6@1qYXecmXMMs)Ys)*m34vCIL`1 z@C~q!>e;&7Hmp$mIPH12`Xr=$reD7hykCXfrZ06CD)8bdfXQL2Yh%kWV=K0T> zR<70+ep=H*U`6*IRr%wkXKNn~_fw;2pCy=J1K2=XT3UG(bihakjG25-_nPaPY`<0} z#&bpklcz|r0y(0!RcMyn)O04*~25 zh;L@!;#GS;kGGvKY5~h|Kt2IxsIt>onl~r@N2kxrLp*&urK&+SxOn)J!*|nl4WR18 z#q2WxrHa6`6_7zLsxwuZypkwBmybR*4N0~&bRO9afS>`2_&zD;0Fu9g``}?{2!aMO znak&u^C;Vs-Xr_Akb*ai@Z*}Wq?{V?#hGZh9&LgWTzz?ezx>E1l?29Vz;Q(`n`ebh ze;trvhXdDZT(#}M5cl zCXAL_+-<7AVn%^RLVe?(g~j4TFawl33F3T`KDyCX+AL^XVtuyd3aar~0j~be3?>rc zG{aCzjP=qYCc%1lGWpO+^i1V^=bh<2R7tviD(f1%uNoOg4SQ!#?*uQ+K2-}Ul-eqa z+w#UqyYh{JRMIfi&NxcxI7Hxz;d5xcX2WjH7~01S@`r3qRY+7L62VP7>r!))5%uYn ze+`OE($5u6;tST<-KIkF!FA8RmqW*(A`tZ%)J?@5!)4$a#?{7G*6QYPlTcip zJqh9nq7%!@83YbdmL~O$q?933SO{4@E6G zDJtJt`#UizptI9GUGe+;qF6uW&%2HE;x%%<@?y`&Hx02Zxk;8-EMylv)4)g&mC@K1 z^}mfyqmwAe#epGD&GR?#Qv|zu3GhNJmKCYN+YU0R=@G<+G|6@jFZ{a~WW%ZFo+)QHJX?H`Cg))g=q1iPfI3s;y6Oy%=gsmnO4Eu6~3G~+zIo)!L@7FzZf zK3`YJR>)6}HTSHeeOfeX7C@+|f(VAPE6x(5=RNu2AUTzk1$t4=`2MKO7Ti1U?01z5 zqrF&<|Hmp?2_;aVl$~wyu)GQ%(Ke(}^U&}!Xbmz`Xv)uQWu0a6>zZmG*+U;$HyGER z+<9r2<>olv1fLSyqCjM>GJ-8wHJ9yv=0cNw-!b35@ak3C0blI{A1ua<$d1d=!o(&! zS1ZPh`kxlpLOFLh1O~L$O23X@6Ud29_v-M~klhYhC?>ZH1JE0i(KTn`Z-P|oLnJ{q zEAf$E1hdRtgO;F#3Kfh&y`%;(cva@4DL8ZXiUgFg>!M;+f@2zxIIu3}+nuhWqd=W7 zwphn3DSo^5IzM+LgPpM0W6x6lWH;%9niX^9xJQ>0(7snsrM#$Xk-AhyRMRvp3k?#} z3acd|z3430op$ti-}G)Et7sSV}9GoZ4C(ZAI=llwBnO;r*~|K*2SLd=3A% z+sqKJOg&%9bl_(ee$Sv7dF&{NcaMx7Lh8_(yIR8jwuvCY4+TwqQNq42RXo&jcZM;? zkIxl7&uFJ!*uRnfq9EO2P8qbT$#aEZfE>W5;{_F7K~KRTQMnjX*&tAgq}w}sW#aN( zyOj0}IT6}3g{b1^&@4UAKAHOLW{M-L!CZs4R(3PI?RayU+8I3ND|u_U zFzUVCEV=Ka^G}5-iI2p@l)1T%xRDf}2Dhd-o$W7qTzL~t=oP=av=46nMx@ zL8>Yd8K?=?i_Imi`8}Rz0^WtXZZ$8n?-^_lB^IYb$kxV`cl8T>pM)fVMkcd4kpe=a z6~1x6A^K(96q^-f&=pg^=!hv_-R!Q3(H4QdgFFO>o1yB6DLrpj5k+Nzu$bNc4y#%4 zP=t5SQ1g~KFN1k~y+fgb;LcikQh;p3Ru4H_HAwf@iK_di6a=jlD80Q<;pFcqL>W;u z8O``J6MBEX_&|I~Z z_|6MKEF>Ai0zoDWDx|`lh@!q%JCvvFOaZS>_hr%eIuuIyuQV|Q_8P&Pqo1(nqkb!g zK4)p|9*$0pK-!Lui1uTs^_ZVv_$X0DL9Cvv^JCxT=b{DZ@ntS?AFExg@9LTq2dHHT zR|pWG;rZKb)86z9-Y3#&GUS{`PZ>SWpArDTKdgsReLmSGQ2=C+*XGj@#|{6xI3g8U z!%F2i34C)pc#5767a_150-kFt)~pmI6z|xm-Dgw)>3!3(D^vsuPtHn;E_m^psT5|CatPA39ww_N^La zDHG~t1>5bd19X=4cSN|+u$=vQ#(U_Gk2$l}vtPu6ahKM=;5JYt)8jF@B-5`y{q{b| z-=JP>4GeY~r&+V)+5ku}aCjg14JZ5D1^vsK{t0Pfcj;Pj@rQa@k2Pk<6W349W? zosU%4XaNklr~-iA_^i|TF0X?I4j7&~AG z<(_sS2>6B;7G*EKXrdcTYwy-JHdQYf800OMhrpK)TNcl?8jtalrluyj72PG5M~&_R zh>(sfySpmP$xY8@xhz9gU@apD%xHCjtvfzec`n&gTs^pY=K<#xp!r+8?klvNN69jI zd@@(8FYvXK08FCF%iE{f@o1gd&s=nz zwtK(YcHFB1vbOUAi)m;(^YpNZ9rWoqj>NdD(WwTQdTz9V^!e9K7H`=SBYdNradUNT zKMcIz8~$$f0JJ8v@dGdC2G6;LNaBb@X0VHED+#psUjGS2UuO4mPs?D!-7`z(9jAeDL{nB! z8MR5X*PacmSufL-8;h|ipUII|o}lk?gJWB=45>R8D>y`k^Cme9EG$>DOW{Db>Q5eD z?4}>`leSWv@ze0C{@eBe9iS(!mrNyD&^2nZw4ZXb#9cDR6qA&yL?uqzF75kHtzf7U zg__J6bq!(44q4{VUzcF#G&f~dTFiFQ8(D|I_G@;3zo~CLHTy3~WxodQJQekNjQ9YQ zrRyNX@VK3Qb~_jat=vK%_pC+YA4+P{V#%mvktlA-wl~AGp0|C=(sGa@9!;_h?x_|` z@+q+H+hN1nKd;$TK3!t}IKK!SG8+zJFUc_AW=wxCH#0Fq#z!l8A@63D(w^&$5DTL7 z7p=1s@YBC&TD9ImNFV#|_vZqx*6VO)3j5og+!WN-vPcfb&fz6g*_zdXMGX!C31d_| zoiRy-Sfp?R@Ar24axo^aA$Su`MgJmd0wUV-1r+Wu0l!F`AnW-Bqs!$~65M6lqtubi zF4m|Yh1S+p8RxV(>b53xjGO&whb)|zwL*J9O)>PU%{I{MB)EXxUu7s7sL-dWvm3XW z*9kpK($ll$Z%Dt6>!!LQL0lps8+?az@KUJwO%QTrQ9uvlC=8XYMM(}6M$ zOQATN_Tu*ta6+R95EIfei7Popt(jjoL9V%3);LN1)l4Xs(Dcj`B2mm-ViTp#vIN-8 z`;l}UCT8CKtl0|H6P(2yj2iu|rRwqs)2Rmal0+0weZM-#!n`8WrzitSWQx&n2!S^1c#ZULP3}ede#y+!WN5 zIoY)~vd4t#5jc`*c)l$vUm3U9LE1oI(Gzpc6Q}0iB_G!b#ty+L{*b)Kf_I)o zInMK!3QJ_Z_n03X5j5lSXkKT(2@9j~Kh|L1-O4paQ*7UvecUh&V5)!a?$tFHQp4~) zu4KfTU$|VpIO*Tx$yrz3Ce`?abzPGyz&Rw|9CavF#yR~OF5wlY(u%UGN~f5#q2K+J3Hl2_>o@@nXxX z+g9RuqD1XeSb_2bQd3;u<8w7JPS&-QrtT-9Q6g=Ltx^(yBbSEI#t}7^^54Hgh#Gv$5Dtx%x2d86ETLG^-IB#=+G>Q zgkYnl8Uw0i7rIg^Qw+1X&ff>PfA^b9C>%;GsEz@BrO42Hb&S$#OWhL*n{Mdt&8S(eu z_V;R#$a>napC=Zz9{hT$*~u1v9nehV&`vMh6*UdB1k3g3VhbIP<18){97O7dmfJzq z=_V|l^46v|Z5uGCn};1MFtYhWGzV?0ayI?{J}?2Ms^n9)91U3Kl|sP3v+v=PawE8Q zWQ9wunad8mmDmMp?*`h_`Chu^tVz?X@+GX_ySs*v-K$&%1clkEmFDcFiSeH`X8WxA zG=blu_vF&n_?m;97grGw$R%g{_B}ig7cJW-p|bf2G#NMiPcaOe*9tex&b{W!0|Pcx zyoYzCZ(AR@R+ldCf69<2*lwkl3sFF;!%A&b8Fe+G5+H=&$L55bo}1aKbf5cJ(q$pD zIvH>-7NN+Pp$5Z(X0~t|X=v&in|UUXMwR`ICyk=2@aGJ>;?c!~q*2&E9(J-LR250CUoV^pb)bZ7i$&WHwg-A7z z8x3?3J=@Af6-2@b2^gZFV9s%XR{lvfM=X#o*A=C69O4=oRft|)J1Ha5tLYZ#u8o=@ z0~S;cu9?7|>hX&%>tjJ&sBnUgllPM59vuGF3S`#BUH|caKi~%YKJ}sXGj*6m0gZ@E zx%k^w8e<};m~_M)IcW1KZ@hU{!HPq90Gko-U=;XU6(6EY3P}l7g6Pv}##RXKg+4uA z0)79(h2&pt=1@ZuCQk0ILWL2xTLqK z1#&eb(>gOo+`6nx!`{%W6NG2d5_@n}Eu?q}3M>U96Lp4+A@;>%EDEqGwdK+wE%9@* z&639CmZ?NR0TLs71S@!MgKFC((k7=va@zUYfj1!Mtg{0W z6ruJ+35dgPKlbTDRl?Dbs}ZP`qJ+Za18tUicdV-A*L#&`RyKVY(0ab|5#eMgYRr{c zXfet_2!%YJfXT62GHT>`jbx$GFXMF->z@aSg%-c-pUPcRn*^b<=`OxtoY6xw?jQ_W zOvy)$aUq>{iz3wW1k|s7_v?|p?)W;BKRTvztGzNFi%Io}{<}I16GhkWib!-egxI<^ z1v3kuhLc(^&nPUEbkQ@i37!$AoVfr@cix;_qFjs!YIcy5&_#%Vf(A@w`8^-u9=(RK zi3FvOc|~h$B8CY;*gz_@ceI}7uEn*wew3&>E!JH046Odf9doZJUp_h>TY>d=DO21U zF|qidbfU`Sgx`rMnueUhkI*c$T-I4lYbH_LA1E}Lr4H_u);8ug0%xy3&?RUaMYs)aZIH@;ns z4PAsbScA=kX06f@W7$TyziciuOOrOSV>w!C>?#V=OUtQzw+@BBX)KJCl2Q?(y>2eV z^fQ3WN>)~eLi<@PFCj6USS`@;bymx|F+!d#U)i|&hsif7FeNRLf5@mDWL&L6k-1j{ zRzt=ofE95|u2>As6$8OV4{{hDXQ4%HM>`3_5WMJHga7(`qO8jRh*Az?sOq0R8xdY3 zjtzka{WJ2+ah#K8BZn*D*YP;n;J@9KYS7%t=3iAhf0rd`t(>06mcoa_j|w)0r&}f` znEZ`W5nK3OO2J#XIVjV@MM@XxrXH1?CI?CCnuJPWd-QsXxt#v9xPL49t#KB|W!WflIKm;`MOBVUQ$5dY5FC*NRSzIxhioMn+#*!h=brS42 za__O#9mPpo6$LXCj=DR@@w0QT`m=AvuSa5C{3eIg#>G@p(hQPmat~M!Eag(f&f(?w zLtM0Mi{HcB^;vQ1o48CFL*o<~$4lw*grpv@Z3^cT7h+;z8mxcGV~ra_mZ7?XJ9YE|k5itQ zN0_2%ltX4ND7XIdXO_fkRA5kM2-P@0Ey?I#+3+gP`Q3UubR^OSuWkUv_v1BFP_3P7 ztVFkgexj}t6ddGXWz)#|Ql>K9on-T_uc3=q&RYbz+wC-?% zx{HUFcQSM+x*D-~MXAFScyEYBRX`0%*KQ~+XB6egM$Jbm$HKm>sQXY9Ci0n;wEQ-$ z_q+6zL3OrwU5}a(0^h-jKvLt#BJF;5bUzYcr?7N0D7h^}%+me{pLn77!sN8iK4CqY zg+;W7^>>=)N8I`%WB{|PTN6Os9ppH<#cfw=^#iXY3#OJU4QgW_Q zX}KxZup3&RK%%?@x~2Qz%8gc_srTT_@HQjnBGr7`95!ohlm~d=&Hx~Qy=$x@WsaHY z-{l^-`>JGIIXP<=2^bSoTGZ1Oa$2Qpe3za7+;tb$sNJ=oHv2a{f}VNgt-Cp*Tm(L}h+ayTAHm?~~tCTgf_exRK)9wMrr5B9Zd>vz-qha&-A(%!SA2waN)|4?)Deb2EPX_Adz_{&v+ z$Nw|`{M43t@e#IDuC?LM;~D4oci-PyRsFlsJr$=oRb-mdmEehBRLje&`^A$C*D6l_ zyv@tqOY94N>3#l(y|Xw!Bzz+UyZiYW@Ju>y1-oZnKsx?mdC!rcFj*Z?4}#?n5_Alv z&MFUBh!he>vJin@W^npEHz?lc?xG_UlPNl<{i5E%XB{PpPmG_sX z8

2p#aDE3ysJ!L8#2@`F=xf*~)~el~E7j^dW8gCmxJl^uF=%yngCHs3nt_-_UcRa{b+w z2?RxMoD_m5^oWW-naoDL)P}NpckH^{Ux8@mzsmrjv*_vbfh=|1Ia}BObc_Rkd6{kh zrdmXexUfY|xMt?8c2)C*1w_&Fjy4r_RLl16s&4j&;aN7ez0 zwf1uaS52C59(7f$!(3XHsk3r)EnYiI>Hr2Vk9cCZH-)*XWMZp~F=LFE5?|%n*y`Xi zMV{ek@Wd{Oy2z;^pfC-RjM>NgOd=t?P4}RuxFLS?wb&61n_czmy-jyMFl7I*rq{PP z5o&I6`-(20pFn11;-rHf^>3DSIG079?MTsJ#u6EuMuyKI1mBTCqLaKVps*v<$u%uL z9Y45%VEmcck(cOYEVQEfiAt`#MyZTMru*8%t4%PS>@40Wzd)T%K_hCJZJ(T&I%Oot z)Wj?GK=BVl0y!ERg8QU;ypX+omAoCMh(^wF;odbSUzjMm5}fH1*=Y4T87}Ah!yBRg z^pW)@Gm(<8&;E6cF*ELM*|b-52+xgz1f(9|iuAZEAo%e!hCmD^KYMrBcXxOsI{JBD z{KGHi^=(*Q8kyhgL%MAm^kVqWec2euk4R9NbN90tK7x!hg_m>+7NdZ}^*l=B7`l`u86lFBsre7C{MlK&2$LdoVguTc zzKy7{se49&ifknbah33tJ;)|kWvD&h6D8EwO-xR^KjcDrwNk>FhDJe+NNm+Zx+6og zoD;lX-=#V?)aoy`pl~|vIWKeBiH1255WuCx`V=?(>$6E=CRv(7{rfjLFdjDjZL}?e z>~w1cduNFS3+-Vjw;(wa+%*4k1?YB3b?2U`AL+h5 zAFF0*zI;_KC9l@#CFiacr`+rM`&^#{Y3>(;s{D?o4^;$OH#w+VsiVuHu74}npxj=; z^++$ZP-+B~NLbkIDJ(qWt^;FdUs5n0kFNHa$z5gihR;f=(b%+QlwpYr>H>Kv7_16I zD%Ay^u?%`wLK7AwiNDT$#B_1IG?DR6zxZ5oC@XnVy(sH z_hCeGj)=nT>y601`+X6tj>j5R`2{8h!X<_x?kBPmZzz>d8`cPsZd9>?+A-Z)!nSxN z+XmFvH~er*AYYlZRnoLG%K6*%xZ0$u;=T9MIepuTtzuxlN%_$fp>t-4+2Ov_kCi}n z8Bbz9{gUI!@B3cFUle+fQTWg>yeAxMgxRq?xV8pSkqtf@@ocR@MD0iAym^!+z(g4b zHf}n2y-!Z)dxrWd^2YJ}Z?~c|vwJ9DMd!8GApcOxJE~yNh&I5$t{E{Q6nAl+>Bjvh ze-HQDbnE-R(ksmy(CgZV$=SvEJ1ANp7aG2JM6@Q#$`$cMi!O_7w`omkv!b+~&{nZ) zIJ@s(d@fIwZT*`h=?m&Vp5{#p-M!|YNlv%FO7TVdETd5RLWxkQDC-pSy80J{!l6|p zeWFxIQNvQgLz~!3OIe_QSp4i0Za@B``lm>+vp+&OuVd+p9I=+Esm~<2%UXl1$!`&FyT@6DAl-JSFEgEj`O792b`ELx zG+hHFvjdx{oMoF%YS3})6gNsjKMyPVjj1kD$>LO4Mar`^GJeL7A)0T2#7})Q{oBPT zJbQc`m)K<-RbTiGAYu`xy`F&*geBMU3k>e&5!S#qkR%TLH^*~XBZ}Vh1U?ptKVslGd zJjB1Lj+9nKEnmWYgLqbWhLa@$&8!~LQZoxyP`EJuMBmC1#*u3&+tGy3fx({|z|*$qRPcX5bf6*o>I|F`fy ztt->$R18!+Zg3gO&`7Rs*QB+hM~`hxxM-T>`}lcRJi_xiG_suc=bmAsVc&qYlH}W4 zJ41+;D;M!$oI%FNSTrJA(hv{zOoeD72t~O0GQV8pob$7>Vp8fD>90Y#qJCKI$7via zQ_0{tobLP^qTAcI_zPLy)x~Br3v}rZ7#HS!6#;4*h?g^X)#_@P>naS$XW9c=V}z z!dyN#${Z8KXutFl>Ae>)?5U;4!kpRn-~E-9yUcM?gq?=7yZJjBX=Zz&RAcIO@yP#s zzuSx(ug;k!-Q)NBQ>#DnoMRYy8&pde8n!4DaaXOrRsfwNuZP zBx`y<)Q`90gveoGdJHGsp9kOs6H}p}f}Zd=7`L$9|IGA^G%xBpj~PwJ#QCm~8(lN$ zrm>H|7WBoM@(ve4tl*MJ8Jw#aRwAqHR^=~(%c`3_n~_z@>hCPB%c4W>2}^;{vsErV z#tH2}C?%>#o>CebqoIjNq7k8#rh40W_L=&F8HS4_`Etk$9pU7IWwvZXK$+O)jP7}ZnEYWTElmE#k|+{x zEGbveNKR}QOWKXbZKOfu!5EJ&mN<@ZOua36oOnf@ry>x!eVukvd0W2AY~R(_&z^~F z1ZOj$YD)ycifj_NNRw%+APi77!u^?1t7gC0u<@m@lWp--fP|68(Yuo3I~gedbrg(d zkJU81ap%!w%~w=qJ^2_9r#wNvFX!lr5a~2NxvcV@c5@=#RmB%O;Ob(6k9K+$)OXir zT4|~L`_iQ;^UXX&E&ERm#klQ&xliZ~`f;>p&%-4C)r;%i?ymogd0-Sgdox-Y*+A4p z*jRlrRjzO~vr-p=w+OG|TeZ7qubly%4e!zRqKmQ=*pXj+Uv6L`&Ahcroo)^GUF9a) zEwNhSpC&p{4dyfK?hKg7XRj$|I|g50N!u1m>GbwuTIpg>&oxo!v#)|DAAIgH?3cDI zYfmzEq@8ZpRlm7fz{QdjwMK8F3a`ERhOvI@GwOHgDyb}x(5}H(uoVrs^Z1C+ztwxa zKt!%fh})5-w%m#_v~(Iw*#3Iq0QvoU#~wDfTOr)TiMOr(EwAww0?uYFxlg~=@%8aXq~Z)WA-EfFq^OuK97joPuU2%E_LzRbwsUS zA8y(TY)^Wx4bpFJxT_0RD?X5;fQ0@Tik9Qi1;IQAU-eFaP1~`Kh_IQ)NY-8`CALVI zIId`@U@WpnZTE<%3R&0fj4nmsKf{WIWW9HEdvU7+9#gwrU$W_GI!I%dqE9($94__v z^c7_`2hQNBji*;h-mCvQ;*L6mWq31RXWDjwRKSTPi@gSYkZbIE3Fa?c z6UdBijtbp=*zA+V%4Gj%mR?PyCM`NTj^5#67n`BS2e*xljAxT#Fn+j{`0<=ltEt!y zQ^D0U>0Fo7QsD8XKdw|L`THG44V|2e1lTFe&?Er~+n_TU;*=cMrRn@2j$uDofC7#Q zs~DK`=34M_{^S=Gk@Wj;yG`$)Kb>QS?YZnn%W;1S(Yu}C!sDedTieIW;d!N@i=Z|4 zNd0B?r7Ce10^{o|Y6bTcNlT+i=>Q8ozEohWfZ|zSMn$b{=l^*D-0bvjs`}R8B?Wbu zmsRYJW$mt4-A*a7jVFTYr~`V`CAuN2QR6Ta(vs5ImylReC1%%XjSPRAKZKGNmayoV zQrL77sZ5(rQkp!P>TM9l)_xW9DX3j$$z$;I=Qek?l&mvz$L@QHPEM9v)zwr9SY3zx zp=_IB{>XdWVPJGhDFO!}D#iUm`a`P|VVlnKkEe%iC?^VwmW>t|1@?LjL_UNz1<|Si8<9#jVaAo%KAl#g@O_CSX5`R<~*a8 z0Avs%ER-Hzv`E9*$={iFUF2^)j&-)RgI`;In2J=} z+rI^5ZoP49#*{Ypxn+Ob_WWkPM`+_u9EP;YCgIm-h^5d#&Lw_sN{JIMIglDENm4%Y z%}Zi_mT@moZ6iWvK9M4LNxcV;bN)v|wOMLF#k#GY@Rp*zacYe2VI-N@VdOA@j^eLHI zw5`L@E*~T&>ShYxMAEYnUUGI#=MBt}Z+CHd^s>_r#=90qW<&Y)ffrBb4IC2)X&Ox(j;*oTtgOg%925KjO( zEFLn^JNOyQq+D9VDHT0_)q!RAk7p-k8IUAJp^VCn%CiE=ZF%94 zj47uV@ylmzFx`E73a|3@=TuPSuNnQ3TIqd}(3>-+kVC*6~uz)JZF08>Jrf zdq=q+N4NxKd7!N$cPMY}i|k;zu3>_hGQ@m~=bZHI&j-(og>T9ux~-#g9wEq}@%B?@ z+Z;coOa!U&^^P3)s2WuQ>89OST5d)>$^53kI&ZdaHFa?V%%gr}7oVE%MF#2qQDJ+T zgFXCBmgT@XXZjr}0hZg}QF$XU!*iPP>ZLM&FYsOue4C>i6t@48_u=8;YSYQccjVu@ z%|rQDA6+B5)>W1YGAxbvY$-mppcnj`**JQnLn%SL zxb1%A-H?XR8rr*dgYp@CtbFS{Vw6S9wB3(}4ESoZR^QVTI|z!`#FGTC1~U)78VE_xsR}y>e^vnLfwrw{7?9rrjWG zcjkbMop}c?`}NQzN0G=J>w3Ej?9saF!)yKU!r}XZcizC^PxkH0wXpogH7A|-2|HtI z-;bf`$4>AMfoVeDrurzlF#m5RTOoMdE@;S|imaN~0@JDZ6B?(%T|1Z-344a_!P0Hq zniR*8B&C}jlA@&8GPR69&dR6~+((9MKH#&P33q+oVD#{1JiI+}O5NZd|M$rBBiJ`i z+qs0+ux|#L%rFtc?ZgGQj4^CY>LhFZmfrOm;jZrv>25>f%+|0?n;8c&7Y{|1o?;xj z^WSR4>rli8A_teLvP$KB=4k>AY1giZ?xAn>2eK&MOs0qFZ}0)+dm8xP7WwU5JJ0tV zPyOc%0e@578qQkt1S5)L{UvfO(yN-L=r{kinQYC%{j(h!njm#J+}SSk#K?6eOE~x% za%+V*4zDP$&F>RwwE(|3hur7vEDNhM0d2AuOTAN6q!gzv=CvaUBd6wO(VpC%Jr{+e zoF+eutRpKEM#?^p98Ny)%BvZdIOri7jxiXUzg80OKZ{7&nI}y^K{qx3?Q4l9DYeXm zPk_Rp-FTvh*>550U-cs248xJN}%o$DQLGANSNB`LT3v%d7V zNC}Hv3R#MRQZPwyR3;EkfBSYxF%&~eD+>$BYGsuvk~I2xk7;Z6vHl$4r9h2$CKq4i&uC^{`|U~RKjr8R*a_hnjg$b3~veez-!Q#CEt z4`*cYXB5m=oW2PVs>fQJTcT%ag#;i3lk?E7A_wU6w z!uJ8UCm4r{?;$M4{%PQA1mscYzZ)IC_nn-frEHhIH2aC&egBR@E>K?6HtxMA^PGTT zYEw)%>?m~p=LY^U(Oa^7ytwky*9$_Qu%FHP3>$sQ;YaU>TVx`fjiBXu2CTYu+B%HM zC6r>~>)&l8M(sm)a~m@!r>L9-DN*Xob1k7QWHD7GC%1oHC>zh!2c@M~0s z@xH7{5F=~Q9yQLOHZrDOAUFLfmB2(T3O?p`4hNfYX961q$BKtzhoV0ONg*~}lSdVX z=n5m{A)8gIWiQ)JBmg49)lBwe7Hs9KrACX#23TWUwLaMQ)ygrSIGOJV2twPL>n5$+A%`sf$i-xNPW5sKLMtWc{7^^92Y zNyO9{DKLvRnJ=HRR2A7OxX$ z-r16~ge}G$)#b5*?iR2Ri6C7p>ZkE3)yTb5#KBbHBu>%C6H+|>jcT>tr>7RTR*y?_ zA`8%~9N4}4YLVZA!W(9;ca5K%P)Sj>R|gyueue81O?kE2@?l`H$|yEqPW#hLhlz<9 z!zf`CsnvX;cZ7uy;(mG39(~~0W;PZr!5l1Obyxt8c+{I zh!H4JTyaKLq{ca%5AI7dsve5M3v3i zCC00Lz0%P${Ijc=Qp>tXomo6`I4ybA1ujDPfwC{t$<9HjK+p7QAaRPW;W2&2xw`;X zBdW9(oZdMm8k09eg}^}n_1^T&cBoI*cKFn5ntgaYw^lNI7M@Zk=5sJGYVG@E?Wx)VLwUou0~8HB^0Oaju7Wrt_Dwx8;**wt=<>d9 zmp-bW0JD=MxP7TFUekOoxjdQ&rwQgnsc@WO;xj~=sC&QA=1e&S95kq8kv&I`;DB=& z!~OKwhro+HBDeHQkP^97XggWjSytqP;j=@*ACGa zbkFl71yHe?g4v~|M5h4=D<}`97Qql$b5O|Fsg&+}BdSOs13Xy-zS5!6=97i-XaD0*y3DN;E z?Gw)5*Q+-KZtMOgme;LgEV7^r= z2^st$0ah0G?m+{VWZf;N;aB~9c&>Ie7oEY+bCA&UsxZ-4QK(|fLoIn4I7@cwGAy9N zS#-^3NJGSG#flG}9+;m%s}%v}thld8A%29aGv?iD3yVf@02-d&-1eGSC86x4IlpDXLrBjQ7~-%Ui%uO=N*4?{pB(BV7Dxk2P*O`u;#7rR+(nn zv1^-zuyx3>)3{lkWRZnF@W|(t%jf0s13U@eX;Zg0o{axCB4-R-m})jK-HM}HUwhQf z`;cXw$0z)U*B!<4?v3 z3D;@7-)B`+jIUo~&y8r@nm_&OizpJ)#}7CxG^_Lb{P7=s0h()+gX^rN;%9&E6I8Lo zhla0x=`Z<}fAF6&7zwN9HeOCiDiYNgB|{3YX|?6N93as!yuYGb&cHjg5u(fUjYLC8 zEeCu1G}1w-IePLcsT6`qtV5e~%59td$uT5RB(ndv2?i51FMj!Xv?zk#%yR;L>x+`G z`-ZU|aOJtD>4u3~%_)bPcDAGtjTMED0X47$ujp2qX)#7Oo|Ezp@nW-A>u03xx-A3C z(}R7w)WJZw`uH_c83`JiP;Uu>UENXX5($db!ToREBesb`S=_RD=wJVasU`}H#$&`9 z_I~IXKS)HM7#Bm_#R{#VD;rwx(2OYB5vTP9l`~j80l_7INeSTLc~kGrethE!SD(BJ zWn$H=CBco#KyzAy3Yv(I9T;p)|^42MI4Yq!$7yZF{o z*EQB!Mxzm0Yo2`aN$%ad$5+1c71rxDP1DeIUDnJW3~c5xswzgK5eEkc zT)TGdO>)&;*D)H6woI7K{o4S(A%t8B_;yk{Z;-5xF>Yn6H;nCF?Bd;sRx2b$bZme~ zP!4B2bzkvU21ogz;6wFC`Q(jHq4g2J@s(fad~zFo+@ifFshBIPqor)87+;de5+>{6 z3?VWqhN$Rq^A+V(bK=iw_aZh%OxOVkyV%7pcJXe9_nxY%a*(w^FNl(qy7A$i7W%KqJJ99)6aYA9jV)a-SK zTseCm!(xwngWIIx5=W$FP1npR4l2AvP8O#Obry%s&K_CiDaJ_XJXROI%q(vLdv_ww zZ10QOc={$y64NtM0?=X1kc;^_2yj;P;@1s9Wkl*If^$pKYPH1YDq(nj}F&(lo(7|pq)XZi2*`Lh}ER% zS+5&PRWTS0ScMtx$_2C4f|)sGWolf4!tCK4bRG(8a2O4;LE0?8tQx?hQUSq&uTVkI;?TyS%@U&`F$M@Gvr9v7oh23# zLljL2nejai%3owh%JGGE5^W(D$*dSPd5Fn6`=v+m{+Qd(I<9k}i)ci$7iKFh3?p$8 znJ>?1$~CR6w_e|w=5;);I^JuA`cM2W$mQ9)2q7`6jO=M|It`y4L!IgVFwjiUCE z#XR6T&qSsa(IQ&)pCL0#qY->cB=eBap;N*{C_==<-1eH7GsRINor(nWP^l7$D4k(r zO+-7vielVp!kL1lXWV&KvBpWqx@c*|bGtg_HCeD6CK~OKB2o=Km4H#836#;{@wCB_ zQnnE^rNycOiP_RD^#G1aZ|v_68Hy?y0s?7-h{32OMjDiAAbIv~O{fP8UcC1ues=g2 zx)~8y+171Y&oIRhMMoK-jt_v6DrpjP26!^^tk4N!+7wL)1p`2lQb)y@X?csYcFB~2 zHl1;x5+Pnds(UYVO-h+forrjGpcSxBD#kb}PKTap*Kp)J#-}a%e!~X_`>gI7274ug zeM{G@nYAxb`xA=c5rg6yKGob+uhLfcSPmB?ZFv3Yt2E|>=`2u;KY}0r5XL=CCx(HZ zpo2lDgq9)Ibb@csp`38`;DY^PO1tW~e((hD_KahFg{BGk+bvHP*O|9#n$sE8q~hr4 zSw8au*eWp?!Tsfnd}H|{SKqhC{nH0j&I4JSq zfYVnNtk-aXXMbX-?3j_V7*R~*6=G1N)f~+d+t#dFkDcsue=fAL2kn~RN9eL3mP4Gm z&MFuPOFEW>qGe(OqgI$%kM|x;!l&%xty6&yiPgNO)eSL5_8DfW-paFf3;bwIQxqgj z_6<)S6C-5+;}lvHM%_WB64Z#026QqYQsSfp=?KjoV(FP0PiGQKy&#m9RZ%l42DHi3 z`4&?uqOrKHq_6?$)|}U8Ok}d{Pr09M6e)7wn=j`$?2%B`7L;O8LOJFmUP38kq&ew;F8B!MQc`6l_d;3F@lML)`r%#s5UEj zq>v@G2Q}l&bu^IXn}y5AU3{kzRP5yiW0sgvp4iK$B~gSFsHzIPEHJ5L6>6r}#^^#(`x-+* zlDx1AVh9S1cCm|H?BczRC=qAEBgs`o zPIhdZHbTz|Q%UWn+Fk789a)$6JKMJ?qA07pe{(o|2m}>SChr^Wtsd~y<4<#z28fMFN5GZ zs&rpI04+*A6-FPB7YXbmfqlIpc-VmpQQySaugU?Fc&LJjol*e{gVs>pTQu zzF0E06I5q;;@ZQRe#nzAz(Kh2D|wj`*``VDm1qU_xSetUn`%-#*TkBINTgv_GdFlBnVXX*RV zd&rBB6tmZB-?P(cviqEp1`nnKO6<^*Fpi033PL>~w-5ThcdlB6aC zMhHVZB|-JiL>x*SNt*udX?{?FUmXp@X3V6XQuqO#Yw@}z3fQ1Ap<>_$&?Y*)qGtIZ%L}7I4l@k zu^jK+qA6Axm^LjzyWCfRvKuit-N)UDwC5c$S;Q2i7;(N~-6ZzR9`>$cxVnb%holCk zm1a~WR;)2j=Qb2%Ykek4KnX@Ga@r_@Bvgv1m_0&CnY;wKa8FCfipDwv3MvBPakO9+ zT05eFhK`H%2`6`E+({2uh8eHleU(b7TzoLJ+>IBkCJ^^5UObWDSRGpw16m0 zHLx^Yo7->ai6R8@Ym`>oqN0am>Bh~s2Y;hQL=$_U#!zFZu`vTb_m?Xu!ImTT?REa~ zKl(rMCz?I?VfKy&%oF^*pZi<<#%I4ymxRQEU;6hyjdD*iQVtU{xaE6qWF(-YVEq7+ zqSh^rf)w`oXTSRy3MxuEKK-eWb1?c5Xda*?Q0Nk!$gI8ONGcH{G;2q)Lb0d$!kxdM zQ;!kj5g$0bN?dskPYkO+ToGSvdG2E$TF? z$}%6H64Mz<2bT5@&tH6=vti48X*nD{j?4y(nu-YqPFsp0|z66 zmJ!J%Dm%fs6-B9Nng+c}T(wsS4;ucHPyH9zZo%(<>0j`P{h#57ulyM9Xvu%~PybuK z;o#Gs`rG{Yr+WizsCHlnm z9OHxLQDwXCRMsHkNfvZraJIu)&)PR6m3`(LItuGEP%S!x zt6s9VeE4?jA}9w1p^B(N<5WYdItp#@Wke>z!Y%UWQ3Y0qtTq!BqBWvo|5@YKW@xjn z+8iAotRPh;3;H4x+*;qD3c+;{Qbdxb2`v_b#vn!>$+4?9jX_!MFqlABeDCU>$_SoB zQXa7iYb-*b4h{3w9A!;bIOy#Qa#2ABxm8kFDN(TiU*&f9S7XET9xm4V38!gm2E&RF zJt0D2HVd_MDH-xm7d;=-LzqE!$M5zCk?1@EgwAoaf580w0sx~eA-q|>`cY{i_3uO* zdM{%GTtfE1ZQB-WEk#jmWuQf5D{uUEJ!yZ?W8-7IVc06Ah%s*O+eYsBvgGn+V%RXJ zz5h;R$iKt!rypN7fbV4h_&a%48-L)cs`~YCThGG1tkFAhw5Fi#8mh8n zzL-&!142xUM?;pY1zLTZzkf#()DKzH#%Q!Q#26?|!F(}$#NT?m34g=w*hPOYRf9?v z9|zg9o*J7xM1>ci955d{{`}5gaQEy!XL3P1Ub8j}jFejmI2|=HX*%QJk~zZ2jPbGK zCG$Ls**S;xF)13FvSVLgL%D_>g0PES>|z)1;XELbr~*-CIcF6$I+!=DcQ$MB4H&#( z1n*)OyZBym5m`kn_p^sgsEu@v>l*&_;`999r~d@5M9z-RX*$no zml(Xh;AZ(G*W6>w_XFwtv%G%sHIgi8>e0VZm^ zZs{b_xQ2DRVp8oP5ypE%v}np{fi)G?Y#)>65Im`u=FZTG-da5gAjxASAR3JCP@N)} z3%;=U=g7WruX>esDO!Z@hlr<9(iv1td)*KLb+STK(!2F{&fD6{Dgf zbxR7Fb7e14Rx^~Ifv?d7Qh*c{MvsV$S=38TSB5t36PS>wvZu33eX<-<666QGZ}}q7 z>ISDfun|#$xJU}1qoAX~rUHV2bz)$K*uv1%Yuc{kX+0qlF$jeiBqmZ1PKq@+Jh2B- zQ;NjoNg?|~ilppE+xI2iGqR9~zw7bF(Me5b9A0;Lor|S6d14hUg&Sb}2<^v^iacJZ zj-=P<}pDtL1&Xd_x`p3F+q$1wP2|biKIl&E>0P2_nG6iNyuypXcQ16q7#@jqH_>N z7F!B&(SUELssm2f9dU1;b!;*2asJo;=64viAHjG_6wS(CAjzWZK#|VaV?dx~6wfKu z1;*Eym~&EoTR4${-@+Gp43&;xDxxID%uuWlYKry@T?Djps2CwQQp`TZNLKSyBnBFU z1@pLqL*W~%CCOi*kQKKMZ!lUHJac}?!G))O-eHG(L|Nm)9-=z5g5my%_4`N6uUqcy z&8cHS6%Ux|DNT8g=gn)p@Z+DMX#RvzbA|o&Ev{ZX$+gobQTJ|PSI4AaQPYZh%>r){ z)zvGUdB?;Qlu9F_aTroeBq=e<;+-a$V_4T5ofZ7Uo1ft1H|FT!J(|Z(_^{_|0Euf3U|-fAZt}-XDJ!DLQ`Z4}J$Z{x~zPk*+_- z>m7K#W`A#=#l?b=YT0AP*_U79&%XXVUz8Q4K(k!%3!nav=~j;9BPwX72m90y8bA@8 zL8_7zMl5G7#o-}UQ4w9@`oTV5d;aS@{`eEb2#fiO(ZN+#vz90&t8{|(mNHgMiZS)P z<#0M>xybFT8Yb>voUmUx=Ie6~_V!uMS6n+f;?C=@QWci{@f4p7^?JqLND=CLn4l#@7v zQ<7-9j-WkW0;v$zslg6l=H@sPa@+HsHn!N(phM1u>#RfbmgnBi_Er%j;({YtaLVC= zLk~4==&;6QHO)d1RRRsB(A0H}R{0&$x7iPO%H!1cCiSe6A@&vwDJ4P-_}~dD5KKU< z5XASI1AR?c5@Mvc9VjT;f`Spr7sz_Y`2GIJCBbq9Aa6Kc;wkNp-`(-w%FesI>wW7k z$<7n<4R<8Qt*`HLxkN-L%aYM(l%)^a_OEw$?vs}y@(2L@PWbh{SK+M2mdmy!qV;D8puiRp!D(Y%Y%^aeTI?2^(QKNzdF$C4o8BY?0 zjv%#Qq`*xgr|v$Do{_vIr3zaYpxo9*VHdmD#V&U7F0UUYGet7^n~Pg@G})h0CE}&^ z_(PdzA?`rmUF_m*#pNaXTP@c^2w8Dxpeb~LgseE!bshKHd)O(!2A-~KiFHk)CWWk8WRhTXW>oAz+_&@m5|Nm}4N+Tm%0}+F8ke-OCISWBw>una;Z`FKHW3_r8d;5R)eM z$xJ~&1Z_1*GRue*5FaVTl3I_f9frs^&;JrTC|OkJC_Th#gQCFrh!zbgk?3;LH-Z)j z@@|d$2BkD1W*N{FT?WD=7iOoJ-XOzwIol-t&)*w)J4N<_Bx!Uqq`t5Nm5>QeA0$Djh)nQ$!pM$@G0>$z3KM*)P)XUV8WX{W5*14lmY@uQT+on`qU(J>OJfi;DhX;^h^Hxy5M}cjLU#P^rIaINt3nmg z$rF^vncQ9?fv8*7X3g3(cvIs|VkS%GzM&mNx+=0(H8wa(4>soWB+0VbCdJ;rbaN{n z_19KOp`&_40YPupn(|OC{*80bL)8hzyy@6Ky3V>;u?!3LM}bmBmhF9tgDD{?w4Y+U zp$w5hTOtXXq6SfnOvFjUkqC>lqGN@>c$Mj(VQd4*B|ziJ0MeH68w-*^r4tLkVz!=9 za7IDNPzyuVFjgAp{MM6L$382a6j2F55?-|=9q4QZ=U1uV#3^2PhUB2&fN2;q^i${* zY9>THzKFzwz=^p_s%~@Em9%;c(*oMauq$wjIc8*-m2;M(mq_t-rt5vKT---@D+aT~ zW8`m^bJKXjstks&U?i%X$fP?ul3X8ttxwkx{s4X|AH_@%;^>4hwGsjQkV@t9N=v^5mQ(4~gaaKybupd0NIR_hL2WN$QPf3(L7&;KQd$46AtF@8N`wRVil$5HkM4;C|;)KU)MrI%mk zM?dsQE@lgyPn0s@{M0Z|dn6eU)j6gx45g&GSfW}-bN>!QYq3^XE?OSH^)&N~1xUix z9udXs-+Y-H*Y}yvF7RQE_gUUNM8~ku7++w`0MQCl*xuh<_j|U8^PV69tZYHlBt6Sj zd7Mr}LO-V_PzDn(*(pduz0qyqE!MU9D{j|GiOkg3DH8fZW06hKaeU~N{{OT0ropym zXMNvqP4BR$Gu^T8Rd-9>Ep?*-83o!zhzJZSStL}5U8YE!5R8+QU2%y0A;|}qKRL1U z!A0Q|F*ddn2!o8vBG@LPQXvL{0Et4(*3>QaaBug$_YC{&>7CY;59{6goO^GBBwF3A zuHH}8u6@S+PU~Iov!4I+|Nl3{%d`Jw4FsRJ9O10_E{K2>qQ8$*_l*p)XY!}dekoK* z^gDZw>Io$4gp|Ym$<#e#bg2G0aDM$P;(AV$sJ_`x^-2@#`7$*%WvI{-&0_LU-d47^ zv5jqP!dkoWuPw`RBVW8&Eb!jn$AEmJ#hSgl26|(Ro7b8l{dx)^1cSj~<3YS!R#@w4 z+xBix=T`{$UHc`65H{z}dyn_N2V|R9cD#p3Q52hNxR%H6I-8i=-fky_FF8RmsHo5( zprR)T`h}2zXvm%7pxWizMju2hGfoCGe(i-{VKsRct7b?aKnjf0co~SY#Y>Nqg3RUU zW`vF!M8w60PPYg=nJ)=Zh)jcsh>H3l(K^(yu(HWf5prf2Dz*}GoE$|zDH zL2T_;wy}*r+5OfliTyFDx(E?LKnh7f67j_7$#Ts#f1SzUKJU2rr+C}$yEv3b{OHsF z3yWsTFSI|$f+e5Yf0n04pGHp>3^I-INtRd$g+t(m$w$X3+Q!dpKQXs z^myr5wia(ag)Q(a!CT{7@dMBAEq@b#vBkQUC<1l9L_=aeU<} zryA)AD%D83g{3eVQU1;M-18_Wt$!4Jv4asEOuw@^+3%7t5lN(IdSBnS@>G!C*uJAJ;&G zhykKQN(WLCqsFdLRzS$e(psVtL?uCjlp1L=w2&wnSyZQJW%076HI}0SS|uqX1Y`Nb zJD;X99Z@Ni*4W^g#U-5$co%53rPUs*AoqdHC#Jdrq(3M59{Wa%-qBk1V_kc*>4yj# z@`dbulkfM6KmQ!^0!CL3c;VJ4t!C`zyS(q~pCD!fy0GBNK}M*K2+Jjq;Dt6p}?C>I@ ziyZyV5u@>tvA)cB58l7>JaY3-6N?3>JGZ(0&>jBf5B(sIT$u3o54@9SKKT@Hef$wl zk56c_6}tx$KKlRuJn#S3Z{h3S{vJMb?YpR3NBs<3eC*8#_R04=pStlmC?P6MZVvbt zANd&L$s^co7cD&xUAxNlONRMr%Wr-B6FhwV8jn8m2#b>?m6hajz~hg;huPDHSr~BK zg3lsBIBGk?x+&Jyv>v3qMkx1@rbfHZ@a}g%h>(K3gkSshUt@VXqs$BB)0(RDsNslP zi-uqR#OH~F3D)F@;RvYM)k_}E2Y8pUw|{{kG+l5=s|Yp_s&TSp6kr@YbmcPb;uIY$ zi`J3pJ*HE^=%8furUO>GLFE#(Vo@Daj5ShN+87ZkqiR5@5^D`rE6JUQ*pP`Fh=dRk zF(QyC1p$}tS#g$&uEAO_0?Nzud==*IvzS+rBP={MR;g-(@CK_iB(t(RZn%(d6jHaA9y6*9trtveD==!{kG(?+8&M zl>jVxfG8cU@^nPPU_e}C6o+F*YDnRigu-)d8rr-|orT-j#x}OGjjsYE;|$P9^8G&f zEN*Ii{kq4i#1J5C!QX9cuQ4F9{<#&M~m|g9St!?hQlFGjK78_PM_fF z>S6rNjQ#xs9`}#%mT$PuL)C-a$q)JEJO3Z6a>`IkYTuzcDD)5|N~~|T;#n_es*DnK zj?uQcY9ioNml(h0fZg#v_Ks(Kbiki^_(L?Z<})w;K4w%fKb_;H?PXw-hkBBWPAuRe zFEAp*tpw3a?98)w^?+Ah&7Qe2D}dh;fNxEIVLLb$yqQLBZ7yC+~>jJ z<6PE{vD7o3x1Z;vIwZ6$QLYHa(g~eF5$TCa;*`cq(aSx*8X>Wrho}i&pp8xq5FWbL z6F2;5dADj%l$-1DT4~!Qj4nW01@%>A4Y8LG7LvMJpu!Y}r)267%@LXiu0wi_^dl5H z$>>J#!hz^8!crP=!Xkx7N{CV*f+7ahPbM+hE4@zH{8e6YWB+NQzLj#3{#qxXz!Ox2 ztLc7;A~h+jYa%Ik(WsGPq=zUE?Xp8##aQi-Q-D>tD&iO5j%SF4q-+KZT}f_pl+(yq zAgn<)3fUU6HYfK5Su7w%G9eLBBcte*vRu^A)Tf&t#J~8v&rsM4$fyWHVs-j_<0U#c zl!7Q44ki<?Ix?eEur!e_R2)UiOv9X(%Z%8SBL<9;4VIIvnvPs*b|wcr z`qpn_5pKYp7jbvK!1Cy6RICst!#j-#1}!BabTq!Eik3DCieiLX<|@J#?Aa6Ssb$=bF~6zl zN=KU;u2gU1AO88jPqSEYA?)#1}g z_?_SSw>)t1I?umwg9q9-aSE973h#UWqs-@#s@f+6$;s_NH?a(hh{+3n_Fw%Rg&gsx zzu`$PT-;@Pe8gZ-;DOL8F6=%?tnZ+lXChW)xu%IHh|nT3i%=Pz8-vbhEy-!ljXI#2)K<7M%CkrlIeTaFN@f*MU8IBu83{<5U^IRcvuZ{d2d1Zo z?C(yfs~J_}5K_>EKyC)usPJ+JWi+Z75Pg!xcfqB(!3z`;sT4wKYz+52yY2>JqYMyw z^@4r|7X8{#B*BAp51(89od=NxcPp5jEfddyq36KkG;y4H_y!q>y=~mtHr9<@>6QLh z-o1E5ZuTX-#FQ+1b;ETIcfaCIxF^pON$KFrct1b?ujk40stD`cG5Pw64cmA9iqc_~ zMJUoUU2cKjmme<&5ZR2}wQ54j5O`hi))^XQ$6h*ON z{=SkinM|0^=L`nP<9IY0rOvscKx<8Bw_xIz{x}QBXb{mPpRu6Q_z;4C#y8M8SjLKw zLp7LU_Mx%?JCA5xrp1kL$S4^%IbH>7)6(P}w`jSdALAYM*Yp1U_p?)5ZmFmFY4cM& zr=DRf#%RAyX|}PAZEWLJpZ|NW-XMG`l#8<>+`a6-DDU>P+{QMx@iI#h+|M?+>-RCD zw8F&(5d&I4@Rkq)S0|UabbHKIG35F2ltv#hUP>MpO zGcYA62z1crZrk{Bb7zV1rU!a$FAo?A(qXkFNKaR{*xFJa@9=2zb{=~1aT-zan0q@< zKl2BagCVV1;id0cV@Xan^mar|)6m6^QNBkO45c68LZIs$-n1C)5MoIbEm2qyjwr!L zi3=Jb6j~H`l3c9_BUCNO#6DN#6TG#4l6g4ccl~b=WK9<Z~4jzKMGS{JzF_wh%x9YtxSmM2!j>O+j1VLB|&F zYNV)8u|jqbn}7%fkqLneB^rcik)cJP5Ne1rBTkNL7O`Q)2!}+(0-;uE(w_hofy8_8I&;OloY{``GP?=L>)=;X9MM}F$eWk zCX0RaqTtf-8mkX@$rHQbv4;)OcI~DAYreQ1IO1WBe!o z{oARp{x-|ilne1)7;!=wt`Y>aLeZ+^shzus2@z8WR<@?Gr!1X7We(xz>}4(y1iEw# z>DnZzeosKi01=GJ2+p%=Prw*xBLh`X#Ec>k;ELae8s1XwQQtnn4|jRMzX_fiQjCT)X35Rw z8K%V{i&5Zz{DB|h@BVLpo4Dus)a+?~?w5a-zw~{7nc-U|y#0Oe(gH=1=$A0wZ7>dit#hiV6fubCu#Q}bG${+mU=lIZfekaw*F~9j6ALCu`{$`9S zSk?1%Z;D+yu}ADq87a%YxJ`R_3nOl_l#*D!g(kbqso6ouf~BjG-HL~ICw%l5f06I} zjt{UnJtQh%Ah@j;4?K=4hupezlOQ~CwIWmj zsTY{~kerr(`%9l8mk|*J?|9d{k@*1}Tx2E;0ZZ_NLhEl+MeC5}S{ZOe zlq``!C4b^=%KcjAb6?DZb{k*x{B1$=uV|EId6%4V(=y6~nYPDiK9>1c; zzxEflR^7(fA8~!syBG7i-umh{u+kf^D&*nJkRNl zJ#Wn)<(n^kJA-F;P^IP@|I~ZA`OH&TXYn#a#db6A2AQM_iIO}kspl;^%ZMkE;%LmR z7mhh;YnGhg9<&5uah(MsT52SbAT4dIFuFh*iS9Jg8)8tzMv{je#`Q(~9fMFgL%GAw zV24H4;dF}+j!uB@z44sTNphI*D(2f$P^WkYtqUMm2$F1a6rR=x=;dASt}&^8{JwVU zg4lZwM`=N>`eL?0_!8wu7$2DwJD9LbX&hy?!q^qL2#KjH2h=gCTM0ZGh(ZyfB1Qut z$2#!B5XlfSLrRlWE<-@XNK~)i8#KsB<0_PD(Jn)`n!=7S7!ZLrc3c=ZLJUL)$|`i7 zku?RS9Z|X=p@p&=Vh%O(1;g;xguUe@c2@`Ft0B@4lE0%4c+=s^7VBzSvBdkxQ0$>y zj`kAaG+04!0qZ@Mj%=81yd%9x(xz!W>iao70sRr3m~{AFwmW%liYWTIb}dcrkbl=2r-02+Uo(8#9aQP zpA~Dyo$S~1fdnQ+5jdC>+?alb{Q7Og0}GCe1-Ss*<*XL;=hY>aq3jvA{do+kp|dpz zMV1*RgB)ob!C9iSbhg8Yj6ecvH=d($4MIt1BQjGAMFGv;WgrSer!v$;F;syv&RG^Y2dkVR1wI69vqaj4+zYhM`g!u4 z#IKCFzQHq#3T+kAOJv9rI~W0?OB8Sb03ZNKL_t(aV2GG;0VXmQ2HSXy8X@ZzS4#$7 zGVoXFp6lp}9VWXMSj8#Je9G?4A^W!<#?f%uK1x2{qq*fFMD##nRAhc~h<1@?*`nE{ zU_{M36t}a&JfN{{AT*IMlsIQOTHHYB6$;5- zZn-smf$P_D?sOehAy|Z#s+*DxCr~(wD6y4=OmkW-5gN=WXMQqccW=nfnFe3%iTWI#8UkgwJKOy$$-=i)0TZ0!YyV z(&BuB@fm|2arPX2>A6Fm1ArqE1-<={jDooK8o##=9>ra?#JEYq!ymbg%`tx&?;8t> zdus3^o~gsE6%f`9gRDJ{`?{u&kqm?A|9)H5ez{4-%kBge+mrY*PMzE?7{8)XRn-QF zTT4B!0l+l~{6-F?6j_#Gtwl=7Xf$HATD@+io^@6*$TFPw93LO^6F>12y>zvt>$-E- z`<1!wTI-F!uQ7&apM93gmoJm&IrI7a6>l`K))Hf6cXvWj6f{l4_k7RyurnGbcK6of z_e+jZQ(~28QOvL^BBQ{#0uyo|uxxKLxR&#~%U{Ir1S;7PjUX!qtm=wE9H6~n&>3{l z2$$ou#K}XV2;{+F<&>M(ev1!xPf<3Sc+$W@$9_BNeZ$T=2RDn#O+vJm5*0l-p^-r$ zqfQG&>0d&sWgFYr#x}O`#X?3w2(p(Hl$*7xmmaHZVzh|BI;BuvpLI)bV;kG}lP`ti z+Oje9fEs9j#!vtdTH<_!pwMD~Z6bP@vB;PF`Kg z83@8+l_RJ&$rd_8?liO|P6f2dD8+>AWI|ykh_T>MyvVP9_7`a;OO(%0K>-mj9j$56 z(rwsubb_(mrD%pc(7l;IclCQQi<0G|C;aSFA7)`{f-1-<5M62*=yc1XoMYvJ&{>3y zVVmI*uz!NGmXU$3K@ zjaQ7s9$A24wL^J2WLWJn4r5fvl2V&a6tLI|!l^*LsFBA7gV_k}GStwd^=zv#ts?6R zGG8Dmh?%DK7NI0j#`GREvMI=;#?i8n3xryc$(+m-WI9L3B$=*bMi)CkC;4N4zSfeY zJ9Xdu;biC~sgqxOQrVLI{|bVT@DhHK62NCm7!+^>lnnS7dr&2uW6zxdA1Uv=n_0L%;x)jO(PF2cV*m0jzWeWeGoL)k zXvYuXrX`oF3IFmR{ok1QW-uB-K*qq()gUb1v;-U`3IrKd*J5SBHVwlpqJ+d`CB8KT zGORGT-q%$2wkDYqWF{v>hxZlp*@{8b7?(4U147hk>=8DgJ|wIxkbItpRgR`W=90Rv ziOJZdYl$FAfzb|Y;8>h+(+w#70>ltq>~MH{ie$n=zcJ#{+b?3TPnnK(dEk)=Q~d&; z{K6-2W=3rqgwBxe5^lJ|e4=C2^TEstZb=(BLhJ8xoi@ED8L3>O;q_A+v}V9}g_$Y_kg8Ashs`QQiM z$G`c1KFX-jy!RWv4mHX-T1*MS@rh4-g5k~{Z+_$n_AUlwQS;2rXSnphLmZzz!-JQu zF`d7_-h~~evm;Q7E{l|-Jxmzzwy%AH-Av)?1xIbg?|<^wnJ-SbcI_I+FB~#f6I{&D zMM>xiKJn2{^Xbn%$KGHs-6I;vEuC3_nen0jKw{*KvGx?|glxP|tTmxYZ2n{$pwL1P zq$Uu1*=BjB(cDA2YdK_j4)k5KeK+ji&;zUS%&G)<2|wMQX-h;!iHZKjaA5BNqwuf7%TJAcG2@Vkv|Y~x%E1_Kt01>SqK)(9bxQj%pE zWm&%A&yV;1981(P7z|$5ez0xZqLiYpYxei|DT;!3zVn@w<=`%l=T{2&4I!YEqN*x( zc6RusU-~89^Pcx?B%fdD^D2bE7(-pJsH%#OfBfT2CKE)2x~{j3-!JD{3W<{*FCzj+ z<_#)@jdxN}8dkFkxf-xP-sj>_a(nhd>djRG7c4;pRM0pPsB%H8LHQwhXNXIM7f@fC zA{$F7AEchObX7!-4PMH-6CBQ5JUnYpBR0t%o1|?0e_L7aZERy3+ju!~=0B9aUN_yW zJ$+wF;(6O}vyE-M%v|;?6TAC9yw9ghZ}J}}BQ9%b@`{u3;awiwYqqcoQ$$dxzE}_R ztfqifsVF6T7FYVcCL&V-Owu!bePVNo0K)eL_Va-C8$6;+pbb5a3>I9olCYuQA^A>D0hZD_~z@pW$_rLDe$`D_Ud^S-3&QUL?vm0 zBLs<-2JJLnBuK{I!|HjZ!|cHIw+z_X-6w%$lCHCTle0i6)fbEJ-lO;u_gH+D-vbIO z3q9399Or3^+0@BtA!A}w9a zs6~y91|K~pN|XplvqHp(Cr6?;;CDEu;;}hTiGp+=m1VQOif2B->F>jRXZZ}w6Zfnw z)8Cy}WjfE`5>cT-@)Q+OVZ82(@&eh7xj4-+ZiqV0;6+V1Hgrv5A;wOjg+fb183yF- zfWdOepxR;F?P5ehGh5tLsT|U!6s)8NBgs;nOv!ab7w#G1KM775Yr(c+IGF$zCILMD6Lc#~H_IH|4fJ z;^^p4KZ>wk%(>3ZOf8GNlGA18vac)F;Bv$nvyCbM{ z$1~4$iAWkJ;J9?7##)5x$_Y$|CdY;7#$8a&@mc2<+&bYdI6Lp;P!T0?cybff8F{d-j z|NbLCNUjy%_g{X9AO0sl%zyn?{$r-A1*kd8cFy2J&as~|eq_w^t7o~S9$-41aj={5 z45_}w;&dZsYtA2b9%_b7k9bx@SmfU z@H0R0Q~amj{oRyW^OHaQaDgP6ZkjDaHf3YJrNL90$#coC^$8+_HeAn9vITeX9B-?{1 z$-G8;wP6Ua^A{0&7OYJ3sq3E~UI-$hmuOe1DY2K)kNrMNVv?Lcmt%*1AEoGzFrGc% z5-^?aebwi=YnkZK-w$`cp95&mt&PtBbBP!JC9{(A#K#~w2SN)75+!v1oK8Tw{8E8m zDJ9*SD-!Q?}K8$xIN-=K0f-i*yxBgpW%%;%qoMSi~vREu|&at<*hqadZe9nan z7nslI8*j+_rAS}pVs{7(2FVxlQ=j@2i^YQZd`^tFFsizW5@u*^H)Xn9XKbYd7O2%d$80`dn+hk-Zi|aP{g{lu`_b z!_7I2F=C8)T>!%CdDj?&bB?O2Da*m;eu+`s{jhln&w-a!B)(TA8)>-&Oh}Z=(dVT4Y6X>sAkVxDC8iRyDqG=;8%TeN%L#Z}{W{lj+#DZQDtAY}B?Nwl%T0 zf4lqNvp0Rw=k)3Cd>3!MPgOlt3RJBtH-xPfSxrAcStXioFrbJVSdJ-}_FQs2m??nH6x5z6p4|@H*T=IxNp-rqVUh7%P#Xl*sN$@|Yn|#6DIQkyzm8 zJC!MqH}FzOh0~ea>^cwv8jbghUr9%WhI13D&>$a9i@FmiZmMjdQRgvn48@e7Q=fd0 zGKMVjEVX_>t8QZy@sn|C@O6#=jH463_GQmW#JNGzlC{}b-9;~Y>Xg)(MEr!AH6J;4 zvdLXk++ZTxk4OQZ-(P1S)Dkz&vNtBavE>GK;h#+3Kc5}N(LjklO}@~x!}$b|#FIMI zNZvsZdxHWP+#{D~(5?YFK0iyaXKbSJ*rLVRbQ5c#hpZ!&*z&h+b9=&^8I9@cq>PplVdfTxfPbEBJt-CA2*$#5!!6vTm>G9 z_>WM)q2886q6?A?Ifmx|uHLLH_m(>UX&)h>=qtOhf+(cB#008mv=xdQimVBTR>q+e zsg9YO8L53qQltVNT{VEsQaz6?0{Oc1q;+Nz%CW6&_fBCjrSI!C8mbEV0B&6o$ssWB zG)FAx*2qc1kaZTVN-`n%rzfmLI0^)zc>5GSKkc=k3k5^;efqJa%0d((TapC0IVQeF zFAN;-KTAsD)D)UeNyV(#V|^g=G4XEj4HE@Q9+Oa=UlJ>Fr%p1l-V%vN(7=gui*!oR zyE3ZtlTy$w;P<=_dJU485dK8PlS+FBS$ zV7laC+uSfkRfyL7b^-jGog~hW*`r1S@&2$6xW2C-)QBC;hCL5fgk zGoKx#Z~B{kKXirIQfTg@A1WevE1HJ zHC3+GGKWNU{a4isE33pAyumN=9uBmfZICz-X%;YloD-s6ASKUX&HJ`WRW!l8n@q-! z<8(BHje`s?L+e}_>9C-39<2qEKEPwUq7BDwU56FAMNl(puE2>wDobO;jkgXyBM{Po zs~+K4HWwctDej{mtY}1dpqjvPjb@dgJ+8`E5-+_7;;H*B=ERoAN*jJ`MB@Wm+>iDh zO@N0!qa7o)*Ea=y|j6jRpnlNS5Dy(eaquZoqf&|QfaK>f2vKDZs zC6eU?N#<_Vk%^7jsR_5M}gD2T*UxdM3C|B<=Z*_|fI6+>yMaipg)7bRu zmfAxuZR>SMk%i!UjEj$toHE9~SFEc8IXAwT2;fE?VyxtynMXii-^1_7$|J)#7o0-vycJ@5>9O}^wOeo7-dEV`s?B*1Murv%32Efk$JI9!#Z3Dl z6YAX%v0liqaskd1p>iQo(f?&$;AQ|FpG2SbzCFc%bBODMV%BB}I}&4+-eqeJHe8)C zCpE-;KjDq<3UzBN^boG{Wj;FXHDoq2C1)-&Ge7gMD76ZA_9;i(WP;GISWHP?s%f%a zw_YUV{8)|X-(fqne-)&YFMMG!vg-|BO7HxXGnQ!}JTzI|{ts*TzcrwHV$0CGzx#_l zwYZ*Llu{--0JrJom@;_<42fQP|1`r#o$rca(7T6Rf&4iSS{HR=dv4$Q$*#?W>II_H zem1WgBzJX|bXpp2c@_kH;aJT=M8Yr&NZ)_OnuIfxR9{rHP$*!V$t|rC`KEV-=81{H zYSroXlV)a9B$=UuH^yP6q*S|#2XCv;6>*x_H#bFRTP-RLi`krcaN||>JEe>}N6eq0 zu&NLf|A1qR(oq&x>Ewj04{L|W>3SN4>)XCTYni z&hig-wKS4LPX?m67{XK}Y{I~qrGkO5(9HB!%YUi1!u`#5<`}R~(OvK2Yb`X;d~{7S zI0?oxKnzhy4Tp%okTIgt!7g|khv{6@t&~M9RJO8rbmUX{wgekvVo+4j=Z-%xU>0cI z^b?z*!ki^`WX#fp94|_`j7K5^($4Bv*;{{HEe~LwH5Z2f^;&+TzMaFLpXftJxKRa0 zSklk=>BGVH@^fF^uSKXh9B%Fy{Z+jp*Pj;y+Fi=gm~3)SNyrlF>Rk^Q7?T1OsR34G(HbYMrS(*Hz;WO9_E*RmdT)=_LE>%q?Pq>_8g}L~ii7<2 zEW|)D8+__+u|(pd^@Q_H`>T7d5o`fDI9x$QzLkF_2I=cyq@Hd)9RKB zrLp0f``epa#h%~mln;_g)^n0fV}Rs$RZT*lLhyx2vl1n+-$6u{(K<01)^bS&Z-6UTJZTAL>P?$zEX{HA#N}ajpf5V5^!7%!v%i^j45(t5R!tH|EKoJ$+pEZQ z+Sw%+@Vfvh2!985tZlES*ZTg0C3Fu=Z&5Pva1lGF1 zkK8U<@8!iEKFRpVQhq98Ih3Sc;n(Bva%9c7R{vW^Cw}3+qudJngx=86^p!WHL7JH= z3j}F?pDV)`rjL`jci#!mUJw5*L$j4^lbhs>UU&MYQ5+OqCG#Y^D+j8|RgFw#E%x)C_!H3Q zG0-xYo;|NFE0kR)jC)JC^>Tq>z&gsrGCC}$N$+yf_HgaK?ly*<>zn#-mXL3ORk(Zb zASx}LlaQ(ZW0UB@O;U(}?U9pe+&a}&Dwwq9cAttmEFb}5o7vChbhF&)<{Ue%7P>ndc2qmt`d_YQsYR3_+fHsc zId997DFvodi;^&W;s=3po)X7OctM8KgmhgJ;AA@lq`%{MzI_1-A#{{;(Wl<@eI)&D zK2Ls<47dlfYhxd%lR37u$MOy*R?LGB)Uq2KC`qBCs-x&Js7H#nwlX^cC0}HAiCrZNGL{XVEDuPm`Qae zsjP$qLqJG;dqMp4MdxhN&(}J-UXv?hU6|)F;5Yo27&rZ4&xWkX2m5hP784c%#{h3q zXfeQ8AK-{U+n}N2*DTf1zm#tVuPG|fg_bNtP=TXn{a5dsR|UC%!7xN5jP^ z{{`u*z}Yg|ug$ewz})#(i`oa&oLOat&00z5FJ-ZE;~;dC#e6;UcAxxGTM;=-?4Lbq z7S#NG&$2^{0YwblUB0!vt+7T{V&?Ck7aRkLW0_$rKE+2IAv~nNCGgcnCgzQY}!>8qyd@$qq<>}NG(Ue=b$5y(y z`C>iNDlRKb^aXLK5g8Hk^yDB=JV9OF^B zAwaN`5fs)&lRUc{OPQK!1>5a`_tmDyF#CDA@VTo)w;Bj&pF&ru<|t{_`Fz;+c-b|* z`FU?>+s2#0Fk|*}3_UWD{oVdU_ZIWXVvzhfkM*opCrWHlqevgZR$m99eyx_@v$`=@ z0kh{9&mgUWbEInaE^c^P%UN~dir z2!hnQ8hP(Y*`Po_3=moP>xNFLJ#nu{9F5HZ}_%|W~E0r!{Kc?ck-`U10Ro8z4BiQhkSkm1PBc@5tC^I4Qd{BY7=*6loraI-`X+) z*P_=F%(eP9DZ);fb`Ac7VTKaJuUJ7S5%G@s4rcXcg+#T!Qt=UH+qpzgxK}DTEG?qL zWO*vAlBIVm{*Mu)>Bqs@P~rCYcITmlOo{aGn|8)&Lp^)79Xu# zSv3ANppNJSPk<;&5(BP?!Tr#>p_h$S?jjMyYickJ3m?3cI+ikV0hgv@RzVV;O@Lle z<^Z2N&`5R0f76z50^9W49R!tEH3BC!Q|K5R+R9biEkKo3HHjk z2k-|kKB@5@kJGqM(n7H6clJSstG!}scGx!12`6knwN}cuJB&8oGXy(XmVHClIw^UH zNpw+o60htxdcrdMm=$6dLB_}-d_#U^ zLBh!W!?j{LWeog1^lW*P4?{t|=1UB0Vxh}(Zjct_gr&i_dFvMp^#V@g~)jW!HQ zFEzjQhtI*1FQ?_h_mPqTHO`1JR8b{njdhm?fyte0!`Bl3Ns~^IlCSE_=IWXuH$i=y z0crkc;4?b1f4>fnXYbhFZU%a|&n9pZ6T5r=tKKr-w8>|>5O3Vuy*S50c6Nw-3fXw1 z!Jd+eOExf7=X$wBdRgAX$}S=S(MynpK96{jtQiJ%__Wz}$+HjMKqRyD>}EBlF^RaN{)dxO9hE=7c@yg)%-T&B zY&9o8e?r&QX6@xmMa4^%s|SC7>o^}_-0<1s=hIWV!1U7C>r~L=O0+?3E7f+#A$B#V zw6ye@+&W4>qUn{jt`$#pa?UPDq9>xwp}9pZg8Ckf8qFtu7KZkgU?J{yWOv%@V-eoD zgMPiAHI*J~3|)zWDFT;}Npy{XIbR{wb7wSID(j1@__Zw2#V2Jef&-j#qxfWK2e@* zgiBX*C)pZA1GE#XU7^V0RDRzlly}hLk`0N(8dK5gJO*&bAW&6o@}=S97N#7d+3k7e zKif8e(ka5zi$#CP?>78)q&mEboO?4WmY6ltCvE z4lq~4e#5832Z%~A7DUdq!LW$B7-pWUWm=C<{8@GVf`cniFkzHIJ_adv8n2b%` zU@3VwdjBJ5!!zf+Q(--MJW{RHj4f*M5GG{Fj7^#nuNAsA$hfWVyI0uT=}#w6!qwvn zgU87N6x&i1;v?J4F-#iA)4)z}5fX3Tw`5ILt`X~y6lmFG&C?`AcE*!6^F;Jp)tuj# zIL$)Tk!RWm`jH1OXO|v9FdRgKpvO=JN`?@_j-TkO=Rls>uX_ntP0180q-e09vwjjN z1uq%x204Vvze-rKC0x;y*}nW1HnF4VC?Jxb0R<5)z2&5Ua71^#M)5R7+$`7j+q$G1 zPG{~)dTCEHD<>6G&cO*wvgq(fTM_MG5bNwRIYTDW-zGtOCv?a7yvec%##xhjk~q^zu={a&$Us&`e$ zUyuv=sLfZVf^tH$?Rir=V_He#NvwA|$}gY)hvt2q$`qVM9Luh z;Gp3!xoBJ_zc&OEr6Gt<^%MRZc@kwh7f#y@?hx>B{h}LqIu?0RVycVy`@%EsWWf{; zzb*Suku8BD^?p&ZdGqdDXrmmpYKxS(oN9eK6DylmBwPJuEzwVHZ3e9+&i*+?PMR(+APPZ+YE7 znv5hImpbH~)ykqfwQ`AAjvZzj{%!ro4wv4+OmIli39EMLwODMn6^RDqd%l*AXeSMHFuPB1T2HQet~Uu{E;w8cvYLM?sE+x8mWh z2_y6bm1;7+GEFEa{WT&Ruvn2bDzkmj${yGxQAV)CAY+q!Y%D*aMGfpU6J#>&47Fqx zJQU-JijOox&>4JJtRpI*Aiai`tnJw$y58TNN9)N+VV5W&t(*FQ#zBAyL0L>~lPPy6 zI<{$kX{s2d0BKcgcoJh~ZF&#wvFhsTnrRRD2!U0pD%f3xh*jD+$Cd^r5E>*)j>1xL zD~idxj_=Fa>$-uz^hEB2#RZVI1mpHOd&kKWs(kstm+y!s(nOwszC=l;9t;Oiu>MI~ z0S}-yPHiu?xK(fy>(8utr$3Vojde`pF4bgL?IpQLxO0RFJQ;Gp`KHMyz}aKLIK@XT z6PDX|wu`WWwccq9_LkPxC1L*Z$jisqv*%yU21iX{C^I@>ozAgt;<7=fqit5ug8LBy z95y^WJbd@+Yte`ct^w<+`L7`4@NN=3Zk^r#!e`DA>r{ObCS=(BJo~0+nT4L4cz=SC zC%jC9Uh!ASf|LFNwICp#tV=}Mbb$5NColZpXOdgdz%g#6@u+gU2`xQL0g1bH6X2GX zjKWjBk%0<2Uzo6-wgrcR94pIJNb3V<(^KjmN#3Sx{$MoFXJe`kf7CXs1Sf1?XO7z~ z=WWNWGw=W6hjZjKGW5-;dhaf@GD8;yJ1kv*I!q;Al^c(>Zq(#dw|X_B^4{LFRTLeR z`R12`Nh)*<4Kgw5OFBrraI&B1r)}FE93z&^don1q20SkE4U{@$q{aGT2FN4K_H{?x zxDVeZ-Vn0VD0Fs<3#zd5b>Od3MKqWW7j-aKI~9QTqCaLVkEIF1D*yfs=`Kk~9l)YV z8$7du&C~LW_O{Ld%5CI_T9CZ%zkW5Q!byjCUO|M!EbS>qi!EiP&<^~Ey9vY5PB|;K z_8nFq=~y)oS6c3Xv=0fjKpNod6g0#|b3kJrqYhJamfo}44Wo=(Jkuh=$^8qf$-OT8 zjT;K)q>U$z-}}2d`d?Nle7lPB$noSg&V$nYb9o*GI=U+qB)GKrm$ETU9<{P~gM_T0 z*+K!bMz+xemcKx}v_K4XC^6o4dnUV#yz$NVX1w8B#UO0ar#8Zr#$B(`oe-+@Kn@_lAjg|Cftub$C?jFZQarDn)ev6?Za zK`o+Sj6qhPy+sx2jP~}2WD;KV!(VOr9FD(pg=o0r`~y0Ig_y3qvK2|`qWC80O494n z3kNas65LPb4?YqHe}odV~%Bqg$Ja#q|v+kYIt^fR>hYjssKn zk)r=4M+}YyC<(PNM026w6<-(Ekip~O5?BMa={p7OhIOaxewlsj!iMv+A3lfdO@1At z9O>>=$74@T_Y&8ji;j8>&^hA4z4(#xc+6$1+Y*xguOWux0chB1L!p5N6Y@(H3PBd);F*HgyE-D z$5-M42u<#hz@6Z$Ps&T5cYK_jjY1Gx&4nTk(#zXo&kLi$L#96ONyZ-Yc49DY(lZm)#uv=!6em$Zzw|If0nWd z-^q)PBam(1VB^}k;SZb?ouFZyynF-8c&HpQ zU**bZ$G?J`EI$+!f)4R}o{1bb+ItTwP4BFt^144QdDvHrkB{EKr7tnt%6ix7(;0}dinepA3I`{$bU z^(`(ap-yK4oFwkXUSzOv7b(;o2~8J4rv5e94Qd5&xBz)TKD(CEsJ|AlPl2;qIw)7y z#M!}jSp4m3G@gQs#8=#ZIi4;M0gm#8RcI;b5mttZ)iU>ZwJ?|xAP&Il{PR`X(Dua| ziEX=D5({kEU^Ni8_;`g{L*Fi1-DdK3tEd>e<;7c=QKYn;HWNi$nF zxkMfU{b_8~IZ-42w;W8*d5$xSSQN-$(WZAWfW5yv#Ckl;NGh+hTy`wgjSpR9a`W+D z#7bN)Moo$4S5(~Zeb3lcJp1D?_%wtR{=ZqpIr7&#QWd|mzHpKc-kfIGnRXJL zn@uyYe{AMpT&h9AZ8Usm=wE2OQRwgp4sH=)u|c8k0+Q$+=(?DP)Txl1#?;S(!sne@ zOI3Jn=5PcqTwO>9x+1+feF@)g^3ihz{)&R$HTEK1*z1m5FPA`tI#roZgeL-1y~*7E zcDHzGBwvS(DgGrokg%SYcYMkyjednZ*+xNV%*kASR|Vsy3p(!X+(-9_;EI4x7GxHb z1OM_p{K&EAXVm>|n~GpG4F>7$atbMrXu>_Jg7Imlnr(>V>Jjc}$uAXAoSy^kL@NKN zilh}1i=lCk!sm=sqn5C0Q1h0(I4On2Gnq&^*;qPngt1jplQ$ zXSPL=hzkD_NEu**8mW0K;~Cdk*Fth@*C!buJ9%Ahu2nTc_W-t`@7pZh4aVHrqRm=x zG$NA$FM_!b9NVV<9L2Ajn|Fnz=mrMVe%582?ekq+|HtFgwH%Uz;^l(MNkmkP0E@rba2t=al*dpXazmcU|2zPm*$Iwg~=?b zon#+8Cys6gd9gtqoN(g);I|~A3yYwf#}rQ(rlKsd7PD(oGHAiw*_E)9?9d3Q$z_;T zkq$NU_D3T_>6F%r!ho!%FzUqzz%JNg#&IyAJ`ScoA#2;u9De+P zxUVQKr*HX&zb|H#W7))BXhUali|dWQMsP_icJXwR=Y_0UOK`*ZdCvd)Xww_z)zxn& z%`dQH%MW>_Y+G~l@wRj4vg4YLB_kFWNqQgDckVe<`@ZU^l*%ddi(`lsJ!S+g(#YKNna>vWoC8 zpM(OSwl9a~rH?~JHf@okD~;#J#&r!79zhM8m-;l>fItfEuHUFr4NMH_GYW8xeSd#% z#%m?F;4{x_{w`1Uo`XGuCL=$;ovlm%{=jT_c);w>yLGR>HHhsyi(L&$QIK3lt>nf} z8V&KY#atImib8@1T(4Et$-=swdxTfpiXZ!mPut(XITRdXw30pGAP+4i^##l1qIVCX zpR0&s+_llH+ybR4HX8_aI@MYXShnhJtvkm6Ya?Iz9K4ps@k_qhc3#pFy`;-c@6&bz z^x+M6_erq(w3)uwlIxcP68O8?wC)QApY}CD;S9-ARe=uHX_I=O7YK{Q84VY5ER8im z(m{FBWxsIR|1tCv;8m{pd*NSFr3dRYy-g0vOtJm1QWU&S3g$=R=uW?u`CfH{Q+ z@eSp)a~Q-3@}?t6(6}5Cax5AoArjv}@v~CgXsB4!f*Mlz$Cl(00czIK+zc1d@joQU zVAzUP9OIFvQdC4dj~7N1+r>i{+z3Tw+F@SP*v%lkSUPgAOVcA*+fagsdieE2nzKgwwZnOX?Lvix$C&00ipb*v(3$@iX*& zO`b2NB6Wl_i^n-&ZRn&mCBMmK000mbvVa=l2oVw;K&=N=M4`UlBKo>jTvlfZWa5Ar zd-l%e@%V!9Sx&47%&&n6_Npq>K;Nnh&arL4&v*&)hs80KC=5)3j7R7zSovN?!Kn;I zmHgCdmvz&H7~Ih%#=W9l?iAcH+a}p~1xZN~78Lm=YY3B_eT!=9nkSw0B)=u zK?59(?+SSGWxN%meapsi|^ zW{*vBni+Lo?~)YA=cqgrzgKuha|2FDBe)P#;FjwOondByEw4xUkYkwfiIIXp4xr)% z{ajT(7bcnK%L&#l&dY-9j7GrqT?H#X@*A$@^v2Z6iv3+HmsWMDUdAPR=gcoPEM3DQ z{}v-3`~E>)2Xg@;SI_64A2j0kP@@jpJ1dw~v)SHLl2l1xZAQPi`DaQY1L82UBJMNd zUA@_Mc)IEIAtQct+#{@da3ZdZb%Sx9?KmyJ<@XFG?EPS(y@PDGzkC07)VVykcq=Rf zo{pjH9HZ+r3Fn_#v6@H zWr~>x6JwOYv+;KEEbQ{?gDUY=Ws{8JDng zr``A0e^L7Jo7Abk+S}Rv=fL(mwDb#mz3R!k@r-<|Yv$ah@7|^Nys$MK*YsV`tZ!}} z1Rw9wSXHqj7u_{ynHwAW*{*usJ{e#!V+!m0R5k3Dg0VMydEBhk&-fqqZMN0=x|IGe zwy*2NE@6L!hIss5Tm7>#_UwM`=*dF%Jr);uIi{S--PjxNc^mh-&DxsK^uO1v#V2r}YFd0t`}~Iu zo-`8%P5OL8n%^U-jJ#|hls34)Dp@#EJnSWH z&Nok>EkNoZQTT~^(3df}TsGHoo8#8Gh{6&Px zk(f*|z!z4JSZN-t2#JU&a#=~TF?^cQ>VeL4o5{p zHSx1T!J;nYtiqn&>~crR^%xj8`W%q`~+t%BB9Y09d>V>ITqB#p}54xuOY zHM6<*YN-ecv_A?GiKFtU8Nnz{LN)m1b0koG@NPeg)V_wM!r}#L;DwOE(C}q*lR$|L z_4mLN(c9UHL>Mnp$9~LWwex>^9Nu-`?;sS8r*w69hoLVXblYZIDW&)wWgQ8A!H$z-|;<piH8A1?FigvLnnpHe8vlKd6L)u}=Np3tzS;|Ec0x(H9 zbV{MAodMBm6b<13xSW8r#FQ%9B$zAFR~#sdRl9A6&2p5Z*l*bgfOEcEot9g+DQ3c> zd`$|my^vwAsFQ|~W-+rMig}K4-Uu0h7`b~GE2N{Kb*^OM3SRNZj8!%wL#gc4rBK?l zi72OG9WR~dUfRYt{@ihYAK1o98m7w|PUasF$O3oVZ`-#1>0a!A3|-a}qtk`hexX45 zU1<72Rmxuao^|PM_Q*N12R9A7)E5$Ss5|Y$u6tbRmi0#>e^eSCbT4fM(?g9*juK*D zZr6h&a;X!mt4SxTO4(#LAJMN4s<&P=xYXi4_lEtlp-1sI-=r$QrSh|;225a8Z(60( zex?f|sbRnh1XLZ0;_VVBiicx{to8nb|I|wSqEF;`$GZ8TxEZ?`X)Kga&Eej-fBwK5 zJI-s(yeBB^B^)}}c~Y}&;o;8I7hXDd&RuvEG<()y$Gtw!^DoY+&?qx)bI zKnlLcQ^>HcuI+$b7L0#7rByZdL6O%G!~~nVn~&Xjd#xWAwJbSANslkkmB7fLn;V=; zLTzU8l1xp%4f!v|qgd_W+{&=3& z6^cwCu*?=TqS86x+_!zQLjx%MCbO&8`%GmM<|}V{NRbicZU(_twwNN)9BJ4$_1sui zKs^$m7F1EbMB!|X2>Q|WK%=0MxhCJ6)OF`4g|G>--9B&u zL3)>UHbLQe;C$_x77#pr-@T+WJ}mU`#be7CoB79V)YB~SyRp#Q4zlY}j^S|L=X2ie zpyAu#m(ELfkK4Jl?qu)Fw(!@>jyU4idi(B2@18V)X|Kl)f9NBG&$m2({>p_@c8caa z85r5&Nv&%hld_gnlP+3$G)eUZust3v@xTQfYO%Xe>&NMTE$!bsZusGH+4X2ZQtWaG}vfiE1xRKpTI=T zJI;m`HHet;d&9VM>8!dZmCaylXb5KfAhCgAWfji}?4D>*yUJwc8{eO{fv{39CtO+M zG;$012hKd=%3=lUbG5S4Hs8lSz)uG5Eud|tij0ekTUuP(xIO*bv0>{4c7ddtgB=^q zsbGQ=Y%pA^Rn$%eTPHOt7r;&7C($*cC9c$-?YgQS+-WF~D$ruKztG6-R)clI9~V^_u0tK>ulVQ%QvMN6_unbhk2#%H19uFBHwDB)@Be88~wo2 zw>(xekqm~N9UF`az^?9ki`XsH@^JAdiaGfII8FTTXZ6}z;lLLddO!^&$6T)(<4pv0 zt@pl$((e!njBWhPI+8n#%DP^9X?YNx_uuib+}VBgsf>5jj(0&Kdg2ly*nQkdx+*2X z!qEEi*=k=V3CetBh@xFy+WL?7u}f_jYC?GpG#5n+?+`w5jzlx{fj6_RU6oswVFG86 zZ?x?x+pS5^rFGEBZl-{YRfx@X%&&T^pR)$#lgrw9Y`>7~Cbf<=dM0*eqj{eEPMY7Q_;<1%NZPO;EP%v3K*^hwAlNE?3K{nL^J|KBK zn`rY5OHRW*?JEvNAO<-CCZ#A`mF)FYk$$iYC8B)vD2QDm)p*rTu9{L^bthS}GMj{A zDyXkeJxGa+?+Z*Y0@lj+IH2RMHZ61rwwah@r73nw_l>{->KwWRiPDbwS>ay`lso}O zdgL+p`~4^GoG$OGRge$bs2a9eF@?CAG%0~tCJzx*F%T|Intr;Oj=NhcA+4IVqICAw zeW>mqh$1P3db@~^<7OrovExk7a_zfz@5NrFnvq}){Sb&N$B{t?9S^-5w zGJy030*#rLF5(V?p1^?D?i8@Pt0rE8XXl_@*H48g^jM`gy7LzA)mGdR%U8d=z8B>b zMDPH8g3=#^Ok-@CBQ?|#7*J@c-Ae+Hlj^UoVEDUukz;L z8Z;QD83TSfl&TxS{<$zmQ8M}Zq8qN47Tk67y zNyN5cSfFHN3to^!q?356qvj9ze)Qr&nP6C$E5?kec#3qoCIzyueK6Tki}Na2W(6X9 z&O>N;;n$-G_ym)WS zW@2OO0V}9}#30assVpm#<>$lj{S9i-4wI|yp0w|n9J`~y=)+HNwQ33N%hy%P&VMx> z857u@kCy&{ehI3KhdygvTM~76=A6Qhsy#o|Q(Hgh{m0%sWgP4JX8XW2V6YUP8s4j& zMxg`(279WR_-I!54q_+R=s(C6>-e$gSj3guuC0W@n{p>78H|=|lFrJXJ3Fpw@Y>=i z!6Tb$Q$s|ca()h0+jv^L#%=f{y`S!peF6-h%MH!a50}T-C%zrWo6yCP9prLv3|~qT zZs;Bj>v>LH5Xk-dJ5=A=_J`Q-=@CapK2=7}bb0xL)E2}{sBA46|Fzk${`xEZ2DO%` z0ZmiT^9{t)uWJ8?0KQ@{(SApL-yH*dOI-upd@}>9tLOWJ`-O4-b32FiS+;nk@sW~ zKLrvSf&J~oF9pQAIafYMnZ@T0H0IiyZuI-qXsp~s1Uc*>+lwKUtYHGv8AQ|1d%_>4 z2A}QR*SUFbuoV?1^;-GKCg417^#z@_b}a^+7^(A%3uo|6!H5N1KmGD9bo)$DegA_X zm)|4y*@x&hbZtqBcF>Jak~WkzY{hN}yc7;j1p&VcBxK}S9oNGNT<{v1&YJxnBNT30 z{oLiPwclXWX7ZgIMjqm?{}{eixF4W&1{@sGI*|KGU)v28Vg<>Fk>_3 zz^jJcR~1;fw&$+Y^JtdBEPjjrc*sypcbD0^1}()=Z#r~57_1P{4IXW#?Pahf7RPAF z7!-64$U5(GV$hU;Z@snxQ___^+q`ScrE0Fp@nur^y1G?XS9?wsq6G>419nI<5{W2c z;z>Mar0E7Z@n=FYw#%m%+v6}>T1`_{5{P6v6+FfXVuQgye%~n31|KE&3jdFt9%K5L z-T&7^SAi#z3T+5B&sl;3DU?-%77OO=gLYX+zBxngibw^eibXM6Q!)>AeKnz74GhnL z^1hk-P~}J8QbUQ<+ve7rw@|L0MM}-Gp?0zxj$y)C*>;pUb%gQ^jbe&Kzvhpb>AANU z5I-TKW?!TkwJ#h_iN9{9E79F28=`l{;mNSkfu<0p%hOOc&|i zX*@a7^%x0yj0-H8mD;NxSy2TW5Z~TQ+=t*qo#Hf??9d~TV9!u1F`0HwSB~?WA*z@F zG2p9jN>T=7EOb=(@Ny+3Rq|b!uSWY&MHUB7a1aXncX<`kX0az|V}f#SW%)E9=G5_8G78xfnIIg>IQGeJNyATZe^!blXmSAW@Q4v zy?-w`iuX^yIE&R0ssXx=di5{Wjj*#{ALzk1#V#vR$1*2Q%F48&KY{ymTx?|&)_W7H zIK1$rJbGWMM9YXozXic*;j)Y=k7lx!m(68@(p{Db*bE5glM!R=w8ALeEyzf7EqG?T zYzRRpCc#p#?n~KQ?;1XQ`a;eWt?iFg+lp%P@9iO^JSW}an+I&a=RXtHo3CyZxr`F@6{E3)ru{u{BbQ%DjuO$KGYZ3a zGL=qlbG7y}C7J*iXc*K?p4?8UHalNmK=?rG?d8k*oqbCqkTNC08AD9F>Vc*tq2B~w zx|CgwUK1NB2ukm-dm%*$JjYZ3vK55NfKEFWZ6F7iPj=ZgB~c-EwlohiSxxX5y~K>w zuSIz>1)Zsr#JQ?;A_AvmMI1*4R?7m9HL5O-5;{$vrL0eEv6lTC8)7bS9)s_XKhcIh zThlIEOFejoUf?QIG|hM_!5~aKM6RbmkFKbw4#Caq%ns08@}E)GBA<~?y?DDAtslWC zxug4R*jygz1hENT3WaD)=h+1UIwb2bL-16$m?iK4W?Tn*(;;{ys^NXo65#8)^OMn>f8rVDYAYlj?`bg`r;IzbWp+TWp}PQ44OcrE*~q%fV~ zPTifapYv-yF@w#xSFh!Hhbgt*jKz3GU&kvf9@m+gTL~19aP5(4|AmasLX^_sMvz)M z@K0B9AxH@_u)_bYg*SL;&~&n}4YyFAn|7&?lngRqrF~8kewlu|Q{0S014TmsDTeM#HsTv_XrzySux)Ymwqwpt!rcyF-EE?heJ>wK&Dy9p3Fd-!t>guf8I#bsl(+RlO;5nGreAYBSSpBwOzxSv zA_gC8?X=OTr~bnK4#J$wf?%Zb2q0p^&D3E_&ZpD-8*EgURkPHdEzLc&j02LYRFd&S zvzLE2F-yGUjvRQ53fr7CdMdQ_dU#_Pa%|PDtFP~a(|;5paN7c7(C-4+?hL+{pM87Y z9yX_P-;Z)x(&eZk0ybYKHvgWk)OXw#G45@L5&&Ri&O^t+)ud}zqVMfT?ZduuO7dOj z!vXfa-C&uj`ZsVE11iA1;hD9%AsGDIrqpuafm zJ7erP(fd^$v@jRA-)J!hWKocyGR~{ctFFe)FU&nY-0r!*Mek=c8u>}REgEJ2I-bYA z_qngnJ$T5@xuesdC34MZY^$y9U0cJ`)N?1#eHu4^d_54HdOFBe1cIsdDsA`w0mFk> zlY$>!8!sCV4jb+V%vkUWwQ)WrDM<+@)!jLfj9qDad#0Zd3HXNVfujn%U&TU(iE7M2 zLcyZ>PepZg;xB5~4R=bQbn~|ErRZ>ZI3+6-k0`$OD_*uOb;cC)pIKV}_%ZvV88GX5 z=)CaOb(~wqCRqIKi%xk1#ULK*Xu5!xs_F9{UlE$ZFNTi zCI68$9X&n3CLP)C3w^o_6&yDgxWU%Y)a16?`XmAZI6hKyP7*SuKj57D3WHLQ}CM4En3|95c5gnzhM82w%)l)6ezlKT8f#gt~5HpQ_*sw zK&D#jCk_&k0)e7}RAgkZGpo`cF}0`PN^&R(K?Gu@(+s3jR&L0Lqw>&(_~r-`9U&7G zQV8KoSi97Jv5MH;)8*EocXI^nL8~#;e&Cc}gMKRxn@LC$h=r&A z!1%Kh{5cm%1O@lwVK>8*KN!`KmhHe1cBU^@Rt)5}r&L-fNT8ya@wW+4W>><$|A3AI zvy_rP#3L&COH^PgDhh348k|%(Vnl!8;qUl%6nZl0$_WZd>}JVF4}&@M+YpFZK1$mu zW-5sABq>H3O-6C;@35rUG2kIMMHX>S(6iJiw$nes(TWDj0*JZofM5qlxV z(e{~LgZHJ@Wmxy!?)>o{_F$gD%<@U@RET-?RHcpCQk3)~Hlvkr{jK|cx*|$Zy@;j) zHx@M{K13K%k^*RVFpnOC)QW@<_Mm2IoQ9bkqEO>N!Kq*cd>XB3$;bE#D^ew?1b-pR zL(z`>3=n#0QBw208WI-?k`&_vDznJ>Xyl}^e%4`CgRI4>(vbag8r-x{68t6*NH8Js zsV0ENY*tuBreVf}qDUdSttvj8B0YP^JrEsA1v?IE5jTraT#2tRERRM6M#>hM3ymBc zp$g+0MA-d-9#4f`J-lN!ITcERbl|TeqHIX)VN)3a73-)aBskO<&huZL)qS-MQ%W`o zWjy5t#4Pe4QSnG}?fgJqxP4dW%is02Z3-&3)6)nzTA60rl;{}>o$^2&H4~k*?39+LqGW1-q3`d-TIc>{ zht(Z|QN7rvVWz&r>(+Vg{mYqxlD0wFF*Dm9%k~Erye~+A!wwiOorHFj1C}W=WYGQV z+)R7=*dM39Ag``o13r=RpgoPy)5mA!E$wS5{SRKfepEo1%=o`=TiEU3 z#3~X4e);t!8U3FlvEBC%_AUP6*ZCKBa}<7qJzwPsnpAPQ$T6SBt#4c@R<@e6urT3} zbajL%B`d<7F5^6m4xQO)t%v*(CC4`D>68#>rkW5(j->vq9r3aI{1%Gv{vNrsQoLUn zl5TqP{LG^wqmaebi@>?oqyKTYc?r}}<6jxC&r98tz=9Ip=L&OkxHs@Kx5HnM=l!Xn zk53L9LyI4#z6Z7lsH*c`o1ybo#PcbKg*Gzn83N;Ov}?Yugcz*|8P;I-u{B9?8%aHe=BbP{?erfRoA^WBlNr zu){C8H?uJ7*5vI8%gcD zCBHvi5iOqE*7O1T?aR>W?NUW=a7OnLSuUSfF3xqQIXQ0Lx7Rt{)6(mQ(7L0FskzVZe3`ZYE-s?ueT)n$P-y!qrtM@OeW`<5we}vH{c~b|&vu(Ev3nrhq_RC6O~WD10D6THc1$@M8@O`U!gTs+pBV z)G0;nlhdgnmn{rQdMQ?aR4{?rL}+N)#Mb{;C||11HrO9*a(1B-r26NG$+`TS5jn5E znwOe#EAV=qBc=B&$;xSwj7DYH6ucl{oQxUp5%-KP5{nGgQgbdR#9WE^<73_GN&h4l zV3Y=5cKF?mL4PhD5{P2CM;`)X3trRK}}U8(~tzqFKE#4HXa9skULWu#TgUrU*i z~lrW!B*N)zP8y=*&0CCzq!$Sy+U9 zOMGSq*iXb|+x9Fp)qDiS5n5~!;6d`zkvMlVB<5tX1{a5hE%pdUw!zvWapW3<5-spT zmynirWj!=H?91g%#!^b#K9DNxNtV4_S6{i!eoDA0?<9*CCQQS?d&kcIoyVoumc3z< z%y2>j`Gk$j6gqqfTc}4uNtSZ@v`sep8RbOUo9OE5YpR)u{Co-h*#HO1X-fg&gV_W-akOF;luQ zBC~GH{9`x`eG#cR)jWqx5!W(7en36+F`k<>1CE5|qtov3B4>|s8NJe?FdV_uQQ56- z+7e-N!C3BVtBDwS{L$?SjxJRy463MB^Xt`={wk25Bl3w(05XWtjN`eluyD=%&>U(| z>p4*Xw-2Ey#Cyj~(27$eBaPqbp} z6hQ;!%;Iy7!)x*!*!D!5l7EVW{D)GowQ^7|U|}Ri)4-y$_ktw-G(_#F7^OQTKL;Y3 zCKEA~ozUb3QeJhDII7Y78QqrOxgrUtSx2hYQob{7%j9o!kt&s;@DS6qRxTvxpv8Vc z)|LeK-C;|YE_vahpZQ6jIX{mlGf9dnt&mp*=^jU>w}Tv(SChP%pM1rW$c2WnjZY(m zQf*i0W@)Z*=kRMZ2`vz%2<^-%#zVUpk5L7Wk!lGpis6v$z7_|u{$i~jyOsI;klDrg zKF-SRW$KNuNrx#13+D!g@M&67Iz}sn2VbI-Sn$TT)2|K1y7GQ`K{wAF4zap|>7INt z+L9yF+NP?2k1ZkUq5HzPXD~|ClFthfkXK=Z6F*^w3!RU;Kix$zbe_ zxtOYk)q&vu;{xzLb5Y`wf8~4mw7Zd(+Oe(fb(v9aIe$`7`Qx%ovm;>L(MHC6<_^A; zEO3^^DTGbY!gXI+W%k>;f#DC#gDgixSMLYCeO_5N#$H-E!{yG7)IS$3+1;?DC~bUa}&PmD9tn=#dIY0 zZTX1}hkDmOT;;N5h(AS^q16Nk)HPdwAGCdi2L8U0z#SbOf%RTh+c6DFw!`D4Aw%0C zNzP5yf!)mn=gpkp+Z@+Hnj8g|am&%K%*V6McN?FxC7)9h>0y$q_r)~fR2!{Y*l5MwQnrc6Qu36L4GMv5n&H)DphXrBleWK&Owo5Q% zz_j&`(yQpTgX(^wvpG7!xjFuCQk*Xq7?9PwCi!>yKefE%0T$cBTEq>^O%WSc_FJ8_xaHKo?dtN!p~>Xl>AZV=mi`r@JWW|G&E z4F}l!7R(qtoUa2PyXG_JBbYkP3GLfHwe5UhHE=B(&FRvtUdr6t=Q$v_CX2~lE&c4M zWh#{=(h6^b+Q8PbMcojYIan8kVM^0$F_zu;A+Op9vzSl8y_@k%4TIddv9=imNkRrn zCF&$g=60+SjSIM&u|F-`Iv3qEHGE(>vc#@aBa;rmv?MEmicIaQ-ksQ?ts+S#^SxlS0 zLAPK}!2w|;gX(C*-)hdTQ8Mfr>R6^9S^}N=g}SMa=w*i z>sXh@2h_uzdzlcGe(1^PhRi!L2cE+&|G{PfOrsg{w`FHW#rf)%z8wNdv~0GZshF(D6bLTai-| zje)v!9Abdj=iqzxpe3pJ!4tv5h#D5a8?>&tDiG!|yiYn5Q25Ho7%~}&#O25}q~mgM zZRiyBwKljM;H|br@7+Au?fh2P{^II&v!U}eqVK`+#nto4*4Fonw$%IUuWA)|PwR@x z8-SXrv2W!(m_IbD@|hJ6nS%W0j(fDOkc$4}j&pMof$)*aOwC~gJ(akEs6K(ek>e%9 zM#G~#FF(b+!OA&}>-})oci4`Jcq|hDIW_Ip*$F98FX5`a5eQ#~L$Sa2M(V#fJg*}Z zUaz$~garq4xRVww${j_^{_6UqijrH#GLQ{gtMy50UF4hP%JF@gs#CIJ$!&h@@!S~G zB{iaWyAvpa|2IqfLVO7x463Q{O&6)YUbKSot85 z7O+3v5xy87t1xl9Bu(jgvxnnPkF$a!@Nw%MU|C{4((Bppq2I32lrdmGQIIBrw`0NM zyl(2hdloXd^^#*wr$B9Rjc#M1^EFB+Bv{Cl)--ioI6!GpZy*bLeINY-=~GNJT_N8l ze}^lwb(7nTe1JzwON+C@}Z-pyob` z{b)bq7_Bq0vnLX_lDDcL0$8zsre21zfJ9JvET&vK~`Vq!$zcv-QQv4 zwsnS^n;SCe-~U>H_s7_eG+;Q^z}Sb#dA}{*?L3&|y&wzf`B&T5T{q=B^$s$ufN1Bj z0Ze_s>(iw@x-kWgu_I126cJfuD@Esru#DR_oW4}`QY5F1Q}2e_ zXZc}k8S`!%zc>PQTl*yatYI;uv5`GV<@8VU7vu3$oNv0iChqR;5<60JNmp)otV%RX zeq_>Sn*~%6D^tY>-=F!5o2GahReA5WD&_&}UL*26Z&UQoqo$BxTC;g{1vXKmXg^d~ zau-T%*z7e_j-6%Ld!_CEsN|tgA`1{}a(~6QIpA;cA%b(Jh$`i@TFxn&Ibr&GEKH(A z(Tf`?w*Alwdl#6YTjrueg{9$A#9-+_C?pZ~@Q3Av{FOa6HM!qj`jf*NS0@MX=->!O zFsT|e^2Ri$%kA}VouiJy?rQh=?9D;dhlI|LK`KQDyEuj#6q27ar7Vl0dlUzqMU^&B zZ`J6`=dVpF>gLZ3jgB^nouEW&53_1k@1-EzLrXP}M2bL676j7j@1N2NWY0?I#ZE3j zehmLk5ez@$!@`#rkAL+wQfuGxHA{8DI?X#*rl?uInJR$dCc=PRgUjn!>KFwd5}s`F zD|8~Uyt?EVTKLZ%gG$kiD7s2y5osih21$!hgb-_z6<&d!m6a#5UxN|c{muO!MhhDG&A{vwY1bcTQjv6x8!qMxEoefTrMfZHNUBM&AXz)xVO2^Ar z@}gkB6SzQyUy+NV6ap}qzo@u5e`MjnRb66P3MD5cQ6bmUWIK}4i0-4LQ-a_`Sxt6A z4#n~d`$JzCV;?;;8W{4cbP6@{Dk!+Zov6Y3`laQtFE!%QIplNW(PHKsh8Gwl-q4!C z+Yz$|jconn(YOGw0*v(8lIfvUl-&7(qU zKoQZe@8?7?ZfbUa&h7sU@k1(?h7Cx6nk81O8u?Va|2rU8XgE7+1aRTX2tAtQVGWHi8UA7w*q4Re>qITE@Z)&fQ9sBBKhs= zq_yy%jE>apZBrzIEj*0XJ6efX^` z811y7={QeX^5uB%HCsLrl5#rlV`SX6Ny3!nHBOt@*hG8GmJDzB{6RGQ<8dSDenz(A zjBJx=%KlkWl05(lJ~%heik;)tuRSF6s08OTFZb{Lv>B{37L&N;IHbZ@;|db&u$4z- zDMHqrg(N=zeyLz`nwwxM+N~w!vSUXW%<8l6a?ea~yCTnr!-LZa`AAwakvx@k!Kf)2 zRq-c0yW3dRB4n0s{!HN8;Db6HEQRS}q|!kWu+d4>kioD(lPw092t($TF7+`6(!fuUY!S;k@C9x#4#^V;Qf^1bGqsbHf zowsRDCs{%GhX~D|AMW#^?X6UlaYN(4VmSNp8GJQAkFwk|>314KCW4tPE9DlU+41~e zHIvLgO$;R24luEzpH13v#_4khvmZ8k&0G`BDhF3rX|xK0h4Q?{4K?-Dw`|FJ=QG$v zNRU8vX3-;s1~yC-(kKx>x0Ywn3GCn9*W53@;qiJT4ZL~6?1J@e11mv(JZ_huV2#iE z9{c+`kI^WWgEKWO4T3w;wVF2CAAwhBL@~@fF8OHXo zHDe}bU#`mhJ3Q%GGd3*aNP@e#xOgT8`dPR-iAcZV%`@W;(#oQR)%$sZ!ESZcozLLi zs!C?C;PU=hML+BIcOn@jtR_rY^6MM=fBy!z^_XM40%lGB+}DxZ!p)1h?|Xm?OjA=+ zT5c{d-%oBY>e%kBU-)q9zm4j%U@4^KTB+bn0m!rTT+)+5=vDu}dAPm-3#|F>?k+vy zv8w%C1eWXL^`@4iE~OCi!qC(-xQ@z&McCi0p1b~h9dWC=x*Fo&fH&^bIrKtd+CA;1-T+(5tbglP&W>$_*Y}GL0bAdfKdr}Q5X-t3Lx!M!|!egoZv7b^v*%U%F=K#>d0ARXwg54zdfq@*P zQFBw15-dQl=5!oDuP&Sklc}E>wmWY%ukGp*P|fK+HLZp=Fw7qql*pw^1WIPCOZx;c z5ZfdEgNK{{m|9xGT<}vWWR+})DwhM&41FtpRjZG3TcpLR5 zZ?gU^c0t5uCNV$(j=|&p4ID^%&dE$3Uqnbox>K)Mqa5%d59~F#f0j-dPwJk_FhiWe z82zvI=2f)5|HyKXn;|Pcm`m9mgKWlfodu$$~h6E6aH@ssi4GfR4iyW zXq3T9-GVa@ zT>D`%M9dj?FG6{!7Q=n7lu-t>6~(Fc>X1h(Vs9R*@C@PX_r-#Nf}rRcuvHaWbQiUs ztoUHCr1^kG9#*1Ea*kb@V&EB)kWUXPsG-CFw2=^pqQr$F^fOD0SG;qWd z)LHp^t3>#_g^|fIZS#+HVu`|KNA)2x!YMiHhUr7U6wMw6u}ea>`VE4G+a^oa3bWZt zPjGb1!ldz4G*&85AXCQO?J_DVNWDkJ+#y;A7^~9qCg{iSTt^h4REu z)lfN;=0`CoFkAY!D*{=BVS`~2$)QM@2S@x+FwpT!No>^cVWNs}ovWLBaEUUHFxR+;a~zb%Qgvx}=R#gTje zF)lxxV}+2j#A;{$#^3+AoS35hlO;T1q@tPwM;w#SvS68J3nY?PWFitEuPQWE=Wcpg z*aW`y>uESk?dJJ-1{C+z$qr<$SQbRf5`k*;izYB})P`1ZA1t>H+WpgLS%C5xq{|ZQ zl;erW)3CdxJMT4-*CYw;Cpp$iocNyW5fc;2Ie7#Kx;ptD@qwWy+;!;{$lj(B!31A zkA?k)Uv1r>X^*7dv{eAYqEQ`OCvR zsdzSB301T4BOVE@IPgI7LoP-tP z($c7$;C@-@e3B!v7Zl-fmK<$t&z&sNj-OPaRAe&W;{u2vG`>c0eg#j2X*h94u_2Y% zg085laMXU;&e~`E`Jp*v$oJWkeeB(k4RwfAgJ4SQ#QbJ#>O))uR|oz(YJx_LBdJOC z(8u#h_ugf#C>3?ft9WX{NKpO3gGv;=tvHZyEIaJi86A%44 zp9iJ~-IMS84&#dMw*&R+4@Nc}$6E^H^Yh9}M_V`S-(MF)NH<UDZK4hMMRLXmWz)=(Z+mDb33E1uQVsS^a5V%k|T3Hkv{iN zc={JJdKL*tN;bWYdau^|YLPKnqR?LnE9cUz63yvD`U0ljj^v{#$OG%f8i9B>lt@-+ zRW6(rzCh=xE`IYlE%t_e)HA3 zpW(TSZmzt$F6?Y=s|2!qI$4TDm`3erW62o1s{u^aYRWa2KQ{kXz{N8b(-(?|PCP&AG8DOsywmyltKU(}5eV@hv!tamnHy6Or;XMf0?t(7(ffgn6pSc5gfFeyN>vFaV)$`4DeE>D*GDyqkNAX;G=YyJQrYW|HOaviItKs)jK6Ny!O2v`; z9KG&8z7$0!fPA;6=HI7*hRT}b$cYCy10Y{fuX>6lrTAuWUIHg=4~qA|Oy>4Tm-S6o zwdm&GPL`jGww^kK`OP{?-PGhY9cOhw;%|TS<*FzRu#Rold3mf|^xgXTS{t<<gZ*{=fjeW3RRMyj)+UH@XaAn^~i72eaF{e zBIkd-2d^G9q2Yk^abm6p1!Wn7s6Iplo0SdhpfBs?v84%Wn%-VVPn-HKdZo&7q41=^gR2xa;9O-|Dog3e*CUU?z1U9HO|t zFMksh@??vZ*$NX3lEpW~t8UirM1H6cAVHBpXHMj>@Unxfp7|-k%rGJ?Wg4PHt%1Ww zE|3Hgyd$Z!&Zk8hcDEbNa;L`>yxo()FLHc;GWc$DyX!M$I>+|jk*j&Y7f{o3b;a*E9gPbNjZv(b^LCb zJ&m}gyfNvT`60xqQ#5a^1WlVCCR~RcRE}qdG=necF218uI5tg%xHwg~o=b^qzE;o` zsY8doL>U!!A3O>tgRP#f=SGHdrqUsG37ch?N4Z6=T?k5ESG=(r#}(7SXq_asA)AJz zEgj+Mg$aP7MoU+Kk=dzz+(J@OUmSe+W}M}O9-g-%eGqJ6cxoob%2gVNzEGP?tSu`e z`1X?M8E?60?YU-j`+-pUMFw==ePG`mP}ouozkmL=F8iK*!ov8M`T)nvS#S4C66TDG>#-Aw7yA%4#S_l@z3b!3 zlAyox^S7vMrrfN)A%RQreNN6p_(>DJMy5o8vG#o|4AT9BgRg|KTAQbdROqpz59_;v zY*M-PRuyfUM@V)eYP&LdK(;hIqJLFiXVuu%`B|1BM{Axt5;4oMIL3pLp7>`!rFgHh zD~zBpXyQ@hqOh$aYt8*#&lku7gUU{Yg2QQS)4xSo+=AnS#76tzOlM%8#xrDv+H*7~ zkl4vZMeM_5Rng=ED3l!#`mN&6NxCi|(>x?nubrB*e&|5-95tGx2lZFK9C?`hI&RnB zq(P!J2)C70oRVmG$9%#ehwxzebsi5?)JQ6cf4R+A@>Qp>qoF~_hja{n7KZ1iGv67m zOP)ziT<@_*z@Buspbo|zZ{b`ECQG(;NK>Ztjfg(aJBU}NTt-FaMySUuilFMG=(1C(EN#0HU-oiFKM{j3uOx7$E5$;Bjuakru>n|BPe+G(VGmr2zK(IpSe+Zld9T zTmWEHu55lM?S723{afsFT#O_#UXg9ph@+LloGxdUdH2xu&0#kzfQ~@XU%<*16aubKblqj@HTB@3H-HJTlHta zgU`K1RQ^ImeQV=nA=PrXuOQG{kVymL=)(0MOazhut0vlSH))Lt3;yxcTyV_yeM(R` z<5w2Ium0;ki0``Ad!qNymQLg1QLiFn|NeAP!0rVsymykTy~v3n0j(2Ypgm$D0$}gJ z4f?q<-tv50?mnBCBc_$|*Ihvwjn&T;wqK#Th;VT^2fTGtaj$(n#r^wP7Fm3<78+E+ z43z>IPg!wu_oPek53Q6WQ|bDZEcW$ZjsU|A5J-7+61+TIT*5A4365xm3R}*^(tCoVl{16GIE`P8dU@Dpppvo$6)vMB zY>*|ik3!17%hYe0_XkxMEYYcl^Y=$&JgGw3ALL&`9DIX3+WFCq&K>qw^-4cGB-^E} zyV4K0?fX(>7$Fnlc!5aMQI)S-L3VAPJqBryY;U5^=WHUeTzz2(rn??fa_?#tV zAss;>TTj)vTpDUIupd*=Lu!WcD|w>+vd~>*njlj<d236JoCc3Y5{o%F}-vL&B8qF~w6X&c7UE*MF`xww1bl)47zgGM9$rsbVb9)c9W zS!kAIzHOm#Rgyj;qdipH_LN3DpZVu8)ybFQYdi>JfS}13h}j*fH2753Dq7lD0?-NZo2^D6XMxVNlQ_w)mw>&6vS4LJLF~XckH^+jtOXe(FBr zAU7m`eVRIrrn#K#gV#kZ9+!P^{~lL=AdAdOv`hT3Ng3M6gK4C*%cEwX%7xwp2UZcs zMIHYeVg`q&OqVwA7l|y_o?>Ge2T>8l7_OWIX~QH{1hOUn&|?BJKM)^{Iwcf^Z3>mR zR)gGDkyqK;8ij7mOz`-TjeB`M2Zk5(c8g~H!X z){zwThQ!8NR0Ya_6WdUPYOvrr}nbsrJ~a-3}b=vb3ztHNC6(C z`EZbt?$^SK-Qa#B7$3M=5Y)^Ft2#LO2~!Q-Fhs*01N6gf38T}DjkLSnFtcx3PTI7^ z_%`a4-Mn%6vWTk#v=u7PO=Qq4a)7v*KVNEt?x2M=S6i2Y<0gp_ibY&JJInJfvt`Ck zL!T5?C~iYt6cPNcL7EjOcC<{z65<>GSQ$Soxf#-VZpx%{n^EM(rRZvz6>0@^V>G~JB5kJp)es9iNEkMne2mo7nxa2UnG`F}vgEv~YHz`lkyYPp0ydT>5pR{Ql1|!T^>&?wi}M;+}#%!FK-TgrE_w{b18=tby3@PQd%j6mJ%7i+%8%l zHauG|x?bGoGB^5j-&S(3c7P2%ruP^>U?w8i1LW0wx%`dU6(^g@Pz&U#v~S!o06T$* zpD97@IrbNw57&~uw~}4}V!&DLxqk8=(=KI<{2zmDM%%cOJjOVR+3R^OcmDz4r9Jiu zzKQ}aDnJru7LRj;{$sHIR79) zZ`|+qn@_xJcF$-kGXF?(mm`Yr-5poag7XP=;@j>+yc@lg0#`7AuAA_6>ocHA238Zc zc~r3fcmjHNWtvxA4{uf&kx-04YD?H|+LZ76%|Ba8A`rMjHqSup>oD$9&u4-E6mw&M zjT(y78H<9=J5Y1^L=>}01{1$&=yzAucI=%H}ge9&8fr?S*mYR zL9uY}*3^p9scwzy)g1NGL%xJ4<`emS_>5 zc4bFbn^x|6?89oQDIBw~emJadgk8sstv~^}(v;ya)YdUKM8RN&Q~_vSeon~#sYz`e zgV^@?JWhwx+tk#43(;ZnqJ{-^V8`G#MTl)pfANQ4pEU`K)YQ-Q)JF$6o zS|bZeP&Ftbtx(s#gb`&qZetJOIT68yYvebfN(KHvjmi8)fvM8or76sSVfd*mh6i*l zd6>xSDytpDZ$63$juEd>?P_M>a98j>NMUXvonYeXQ~XY0DxE*uT6Ij~+|o+-wBV20 zd+&Hwd@daTZnUPFj4HsYn|tuVL$F4Wc9~NL>~zn;6%nvTW^g-+a@8;YLwm92t~bAgiI= z4T~Ut6eoZPwjS~FnrP!^J{GOUc+cmED2nwH^Rt}@9*EaZC z`isU>S4YcSCQuc+p|`C=#T6&^UeU22I(2we<`yH4!{tvyl%18S%s~TCp1eY>( zZ(+eS)D~5=SUyZ3);5#|j*OO45L7;hD?L|uO2i8~J{qfq*_)G$&M1Iy=kCDm=l$mq^8zDl6^_gYHs zpjcNIDnUu^MU1TwN18~Z?9uIIv})xIf{AzfHq=pA2HUbmim$_89Xj5y3!bS*99FNT zHsvbu-LKpYmw#mYCPgd>R@oj_3!Vm*Ur1_JtFAE*G^s3PVGR+pgtajFesV!&$e6kb z@$8O$E4W$X_rf;w{r&mlX(%o-4EI-Yi`P?}PXio@7zorM$`e_#wG0@I?MHd#A}|}3G>85C)KR9EBtj$_o=i@3+-P}bu?3Z1 z+4bdu9LIkewO`H9BnHcEJ{A4Fq|V&6ktVH;yRg=wdfzPkkp|P!lixepe(zJ^TSV(+ znHfxsBI-M1Zh|%?^i#`$&~|l(ciykntA*DSwI}pkaUGZ-3z45jVqaqnu;Z&y>lo>& zNrkzVO=@tFZJ-MK*o&K0n%=jiE9hawhn-pm99p+_PDx0hTbr!qDC7WNjmwT>!VcJ6 zoLeR`ylB9F2{N7no_!Ea9aW+7hu)smv#?l3s@H{;-k5FIMJHtZ?%n21Ea+Nb(hUTq zFdxnNvyL)uW1;CfS!&!;QeQS`S_&K-Igdq}ie16|ytN6D$=m~Ow1!2d}0-FWpcMovq$tepV%I_VJzU{QQ zw))Q*HlF|u^}#uXpz8(WrRv9RZd@w3A$oz^xQ~4p9Dg+Ql6u`;oBzS+H)$I2985R* zv>ys?M}l6|nTZG@_=a#}CN;g^8-M>*Pud$2c)m!RiskZsC%O30>=sYQgoh?=m`4*A zCW2TzVF%I%)VuaWKSpqCXXg==m1aIWt3GC_eK|h z23#@H6^fHh6{{r^$SRhs0N8r&D9Q7pGqvv4+8VwU5JtJ(Wcp_Pn~)97%|oYr&mFOh zsbt3h|Hj*+Ij^foeG^yL)Gt1lfgLy57k_PRJ#j@qKdE-yr#cgPFFF!`QY~+8n)9q1 zaN*Upw~y_Or2-aQn-f-gH#k1ml)edoZcP86kMNyI@Z;R|sy5a;YV$Gr!EsK$*lp4= zXU?pZgKYCI3h<=le^~2#+5GU?c$##*zHjc%&d$dF4}S+-zKYcyep!wJ(>?x$+vm-D zo6W&Uy<3tUF6b>+0LFKJJJFv4h~g-Ew?8o(`=9ImU(X(1xDJ3k8kNjYW@R+{m$T*@ zfbpIs_@wv|&iHzN0Mi%u@8n&(U$S2hW8bNSks4@j|NLl={+9&-cyQ*Z7Asu+bJ6U0 zUZ^(f)ML$^dRowbQ~$RV5V)_6{ZHn_YOdh08_nt9<~D4{MFs)~4AdT&(&ZixB?U)4 zHvla@8 z*L=3g_lh3K+iA&;1*eDsem>osG;zr)^iN)W2%Jor6TokP@3IGist73YI<}q30CQi% zaE6WnsI0uayh)~7@*#srL(KnxmQKAd)TXkx9I!Vs-s{l^i1<0R!Or$YV_!X17+lNO zh!s^#mZwP?#e#6E>7lqOXpnY6$h07G32xmfrMO)r3&NcW(MZ3Vc`UqHis6<~DTmR# z`nZGDgR9?LwkXNOV~25Hs(mu=E* zX$?t&im@4+?73(E?-50U z0=_1!yc&0ZG|pV0Yuo?Pbd^z2c3oR3hwhS) z?nYoprMnrrLt^NXM!Gwt8>B-@>F#cjF6of2@8) z!uuIdMI(9(x29th;-r7MtD$lvkc~Xto@1_fG5)gWD}H*0;NP2=&^>Jm9iB4`$&0Ok zcqdIAXmieN1$UFQ4Nc|hzvHR#h+58P4^Gl@7}KL_q)zXY_6HYb>mX_I#FV@#hbNC- zoK=0BtJ3X=7@-D;1x!Th@udGk2) z5;}}@&piFFu@5Gk;Xf@#Y~O#KU- zaL*v;@A7%c$0L59Km*U0cXS+`6aU=0V_N()B@<-~TbmEEI&0+Y-}NY~^_uc^b7(mj z-%vSd_G%Ug?OaTf0z)8<<<9nf_^CTQz(#YQ|#Bg zZyYYRrN=V)`%O7E@O{tmUrX7a=cm?I!Jl&#JC}9h-|y9oIKIC*BLSS8y$&0F7^naK zq_&C3BSYyn+rvqC2Y2wK+X7bED5_nnK6Ws8H6hj$Wwif;pE3D-B1X@K$V5@FeVUsQ$ z$qwFI>Xj6wu(Pvk9D@aJe>WP12BXmn36Px?f2~#6MxZF&Sv_sm88yp*)JUY@C7TxC z?sG_+Sf1<*xTlQau!IdhPcGCMT?>H@Kc}2LC&YEV@Qr2MlIjwSp4f`%Da|03!k(`J zy-*C2V33^E)Vy&)0S2aof93Jppi_di{|b&rP~t@?IAOOLK}PL{L8}ZkYn4*tBE4;B zk|^RbCrE7njbHz5j!GR}m;<$*nsA6K?;Or=Z^$iL00DHKjQWSPw7kqZOgu;DZt}u) z%}_#3Ur@BMNg$$*VO%BcV##=K0>#n@}IAl;_Ru9N!mn8NxjseTu4sN-ac z?}qHoT398S!QOZ_MWo-kzhN_F*n9U#Y*|BrK`z7^C%l7TQX&R(AeEmfffzObzlv;% zql6@zG+nuD>|-Xs(k&BkHm^`|Dz@|UBv8B=i`h9TLAEgZm$9e~6gQ`T5Qf&tv9)M| zcPQp=bHkih^N17a-L`PJ7+HqJ{6v(a!t8ZIWkUGhVhW46K&&ldz>;m^>JZ= z*-)+^)ih%ZM`*3&y7B!YfgQDj&}UEaso%zXIy)lxnr3JE@$b?g)!Wl`?dvK&9m@7n ze0nAxgn9pPprUGfIqJOeNM41vS9vPm;;3j=uH&}3$2;I-USceU>u=pvSLvXV&4gwk|BvRc}P(z>(6-> zNoo-wOVST%=Pqwld9B@OsChsTO5i3Jh%`z?0)8Ov<{BBLV01*n;u#O}y2n8b*&NIy zbyU_9MFXkzH6zCzre=HWX4!J1-mlA%{TYQH;0?C6{C8Oc`;+{Bi|BGy6C@9v%!}TBqr1!!fTjyt8?0h^k=Lc z{IXI#wIO!Ma3V1Ll)e>YnhxJ;5z0o2t=?Rzz|iu0ll#I#yc`=1Ch9!7ON%M1L)}z+ z>*ra0WxAD!bBqo>pziUd7pnwCnu^+B{~*vsVH~(NhYJuATsCpTsLjsmPlkUO9+o;> z`08nms=&4{>u=PP(nhA2SJgJYOsnrFOs$PT!R{0wdR zdaLVQQ z(nOm8^ddSW7QGfJ47eVLk&O*EMV4`gX zP3T;ad(58%{wCOz1HSKGSQFB`GIj#EDkx;LrS zN5ZGuev>A&05bY0^4$u1SEQxn!o|6OZjg;z(&OzA+xXbIAs)tY%p{AUx!Zf0{tZ4+ zl(N#sZi@Ohl=kXmHlIrv(gjQ$Gh9rcaI;5+;AMMz)_SNGH-b998jeYi$UCtN))jDc zONCU!iqOVZhBT1rP2i63zv6C(UaT{vo`+m+qK`~~35#rV&bLh9`D28W@Sn&#)A z#ImW8mak1Fnb&$RQ!XAh^M9UdS(<*B?5F~&z?!}-)O}42hlpItP%b2K;+wDpA-o7K zgte~&VfoIyVOrP~4^2+-$DQ;N5%k7Pp$S5gPlTHVTVB^}McMhH@`^X5Oxj79=Atv* z-dWQRGzzS?=0@muCYQd|0KeGv0S2-_bP+^7EF` z`S!mv$oI$wT*NDL^vc8}@am^R9iJJ?{*vm06Jg7c9Nm?ohL$M6ABh6h^IKt2%wpq% zlj|o4Dym`or$#h~;I-*Zx0T(+l;G$HV?!*Hk{HXrV6qYyj%mH4ACi!}vMd_5IU#II zRUKab+})cmE5%Gu0@4V~ffNoge9X5-Hv4F_n6HKq0Sq611r**#>Tki*;m3RS`zW%R zkK*^HoQn?Yo@mTn(ugj=d|05_$Ng)XiRsmQKV8m2K{7G?F7i*R&gOEHi}O6EkF}O1 zd!CpZNIuXJ$p%-MS0w$Lj}Xl<0+I#xm@zh~cElU@{zX z?y~aAe72$y`OJ2$wE!!Tp4ozsnM~vJu$+1=35pV?Rz3N9f6?Bw$iO7M^TJ*&taST= zXnWCN>spF9G?Azjh(xKAOJJOn8x-X7CQrp$4mIn4TmbNp`V}1%-n6c3(VH+fffcP>)kzv!XU6aN^>fsxM>@4=CWf^W5 zm+1NrdU6s(saj+05BMK?rCfGmJkIoUt<4snf45)fnzU_ejC)!dV$eRI=-;hz?AvH8 z&c+-TY3=#YNc%fQ`?SZXltNTbj*fo1XBZI}SD1Nv{-!R*XQwH-}KP**vDFNo&Qr zy!u{yYvwji&rEmiQut7{efGE>w}>l*pdzvL0!g~h!hex6cr2JPdFV)6&fu>l4El=b ze@~-6>W8HSyVOX0w6)AD;WT0JqzEh^>U`avoL#lzTg`3uN9aP%@kCsxWyEIU%&NsE?+Ef3+ z#}vn8^z7ltaFP}fDZ;K55P$fVOAJ}`RWOnZLtGC&qw;0ERkxk^t=o{&#QNlf*5f^r zN=YegL0vjV=F+u+7}pSDkA;mhF9#{kDB8245dEU5Wem}e(&Hy%!|Xy+QpePe$jLFM z3UKa9B%n01!4DKwf|cIHDu7AXN<77eXaAwORnUnXW1nLaijBr7puT5HL;jV1>zO8E zST@|J&wMxgOFge7gI~k@n5qG9@=!Us^^ZVmpk=I(7-4K4oRJc#0O?-_Y9~^&+guuY zM`wfTF)Re3&q`QVIMFby){qi>v{Rz8eVHG`Zu09C&WNRIQmSSSLL{kzZW~MUXwfm# z9tw>e;s0t*bSI9LvIhEa2HJ+)D|q5RXR~|vWvmCEBnq0?TAcaQvjwHRD2|UbYT}6N z$l4j7rM`{PgN^B(3^p0gT4H+sIO#iTcn%qR=R{cg9gFRhnOga^!Wg3<^W*jiRm zHFZ^v3MS8x9yOO`8pr!6K;3QQV@VLqtejj#FRtw3)#otMH;1=J>J6zYZ>{oyNYaHHY;76z7M5)%plaJ?RoQmT{7d)^+h3^2yZ2*P%Ol=Ue z)ikPQGt-4i_+qW}$bF!{M-1#Ssd3)DdzTnQUCK!j(oO#4)9%s6#Or_yquuv& zL$t;J0sh(#4-cA9LLkT8C^Ru1xZK|qO7>$^k3QFlA0 z>L83i?tdq2s>EjtwY2m|6d&x}v|JpmDr)K(x>c$_BEyi>ayBPnOY#_F4d(uq8^U~; z?56S#xqt`{S|Gbc)@o|4i-kp?a9o(O_~~M2YM$F&zi80-gnAOp*rXxrezrwUM5L>w z?vZu=fRt_&MPZ*VRkj?t`8s?9mq8=`y_Kgf75HT&>%}P{pu9Ge8KSQ06yY*f-&{;m zIe(R6H*cgMWom=0yEtWKZMz>K#9b90>NgR(6psUcN7dcrKOrV&R^`piDC?+U@BAg( z_imypCs5+pQ~e447wAlOT)_eMX%PWs!|6ix7E$gfk%Li7$UNKN`x7TO!ZME5nDOPe zyb-WW49GLBK(}sknIhG$x}LB1czK+fPesl)^~~4j~#5uY}CB2m9v1ReT-$5tD=HT?dugr9VJ#0;)c|o&=duX+& z?$unqsD4B~K5)Z+z_A&aSI7%ZYc#9%tAJ$^FfVnnnF5h@_VyE4v{4LhLfMpsRM941 z>Hx^8Wb|c5yH1m-Nv(`}`lF3aPP)7|aX-KZ0K}Z3c_o>#*$ishfZl=mfSK+){@bm+hSgYl$eQLn;L}6g_s^qMy~fABX&iXVVH*PDi)(9k zNn1*o>wN?g`ItZ<{i6p^gIWO>pT>Fj{O8Q^Jvo|$hEDQvC!i<`V*qOwZRDLk3clAo z7kCj+Lt`Va@3R0fO}d?GRj5~(-8<~G)?b%K*3!a`64-|BNZkEd(B}DLInS6!XZ3+c zo&}(D{n;$~6XQ;eV7;?K^;C-1yFBe^pCUS-I?<>6A(wSDmA6-N!GRxHR`>ik)-pgbH zc^c^;y}c`PhG7X>)QH<}^?We&iw8E{l>YpidzefV&%57K>?xY!h7Yjz@>y#z-u&t_k<%r6;_0V-BfB* zolF;ZeuH|dj8DC~r~W!?9-%AX0-$bkVv(!apwh9Ib|hew5cpBZ-OKe_dhCSmcOh=? zggz^nK{WSUXioGV^xo@{Wfb6}oM|FKFa}fEj&ebz7P#b~kofK$YM~@Af7T{M&nL+R z)jj$=YNK*GWP6uNw_K8;op1Rdbvk^qdCb28(7-nFJ9J4A)>bAZB%RrCh(10pn}r0M?HU_UrKC7H(ADvD@}&k6X4AuE3D06~;8I zSv7C4kxB?BtivzlunC9HqHE~ng#8+E_sXvUVimNZ_fI~Drb|s~yY4=JBq6VVIM{E( z@il6xac~cAX=T!Nk`YcD8lGp76lO%wU@Ar2e+;)MXBrh%Q9~`_UqcO=5Vm2pmi2fd zFp-- zc`^+mm|4cO3d#k>=OvMC1-xOEbC%P;n6)c644ro2kagb6)Gx+1$!~p2jHe54>w@`R zV`8gcch~qiU4GfwN_ZB2x7DtH==^bAzbd4@p;bTTYlv_Xy#O)V^1RimXMXLxcB9M* zZHp0Zp3Ux?g~i1m+%7Wpr!~sUI?&}BuT~0qM&$TD?$(;lPfoii;>y78QW>X4zX||6 zj=$c@_2Lo{E^-5I@72NA+GRx*!ML6u`LBBxYQN-q>V99-jfpb5SJkP>)hkEV!Y%A# z>q!M0rN3bW*6-+?1UcNb?bA8E0!!4F;oMSR0 zr=}&dy53shC^#`YyGuP~NtHt!*uY@zQE?8PSPV@#)VcLMzhOh-xs5m*zk8WdtgBAi z$>e&!rQ$VNw(`SM={B+>s9vQRutou36o8(Y!a#eq=mN(FbITWUmPB1%4n9mGGc9G9*ek2SXhAYW-%?FwERMNt9n*l30!PdGXMo<5a|l7e{NBq} z=~IbzPg)D@*U=z};ft&GRf5~o-9S$ea{mHbFN;mh;>SMUN~ z|6Q->wz8j~(mt6f8=;|d_&+o=F6G5;N@>`Dq~MN0=v>QQP)=0YqJ8u(Nz+s zOI*H5QE3NbAlI^WhSxe8Q+@^y$9uOCJi}}EZU+R)mB-b>702o4XZEFm@@1yjdLyuk zRYXkoW2km&3yR;Npz*jb{<{K`kucp(KYiMWdyLRbQg7bmVrOolU_t;9t5+Qem{fNe zCwA@=m#HQu{OiIT3MR0u_LjsNmFjx3UH|XNjG#eaM-i=M%BMqeb#(>hhlT*{-E^@c z(AF)bSzYqiEtXRUDrO6zszs;E&?5v0L(CiXo_+w|mLiMuSEMWuRjY9JtVbAo^tjJ1 zr@*QExTu)u#Cwfo5Q)-hzg7GUrB?+C9;(e!EUV(>WB_i30^u;OckNBR)$sB!=z@RA zpfPKjm!;TcXJxMhzCm1Dm&rv2GX8jD@=$-$capX~TqZN<^s1)E2V&xNZ*hNl8f@SK zkUl!}CZ94*^*jXdRN%s~quD z{C5w0P`Pq$Jg&r|EF$8GtQgj z+_N=L8=VWzwv`mS(zc0{i(F&piTlvC6Bnw#Q~GFt?q*4MknfmQvX8Af8oWxORsNmW zX1%@K{fXy^&AcfLz%v`9+{s>G%-SvGgYho^QkR8={m(*P%FX#I=T~aYs19f z#h5G|`3!qJcBM{7BnjsjdZ6ebc=Hr=<34gfEP;vknAX*R?ap7WB-K*rOV^nC3GaBN zM9UFCto!f*rFXyg26U08uqD~evepBQTG>U#*(u;Gi79THrZAdh2#FUkSg9lm!CIpv zL){$TG4C;z`M!Xcjd|JwjM#T|T|Yfb<(dRtpzSewW>`HFVx;!rt!x(jV3i6;pjJo( zolYoVS9-$je4`kY^6D)8DkgAp^cVPW&yK{EaWtXqeL&My29hnD(5`E2lmxbL;S{fV zJ+C1=ZvYbIFksd+3QPw;nvc!gDUj?HX11(<)JI6zn8qhdu-&|Qp`Md{*)!()XDCSa_Tcl+Ie2}Zs`I3MzK2AwKt z27VprLqiI~#{y8sgDK_bC2c0NLtG;q``4Xc?HM)rhmc!9hIIfCG05gL%cxj@{VbBCv5`<{l6>^C3};p2VvAI8F1u;7kylaXhilw2MyCeOpd#u;OUWK$NGv4z+8zw2 zkr`1t@>_cIJQ{hU6owMFnb8ZEdLj|O;yj5#T&7^cg4)5M5P9q>O_Aw2wJnPGCptU& zxaz+cHX&GA#H%+@Q!^618#zmSjKuH~kg|TP8N#1aWjW%T!;ssY7cy6U6$Huh?;G!; z)sj+`HiABfhJKcYL9SJkn#CRa?G66m&bxm z<5oA`OD6o%>Oe%VUusN2ubxtdqgU5%u@^HNq03~`vYGU?=xF?Nbu9M>E#-)mmStr? zK&zIN^|lKCg;P=o87&yU8Akv{MF|1nR5pX@{JnY|moOf$Q_km{}5z5p7cH7N`mDSHlX-)ge2gEk8d9@*D@AFag z!D?iHFc6Q*2bGi~eZxV_vZIK|C}W3BJ1#aaA#}p(o`njJd~SINw?kw5C+H0$qSv-f$TN4_V7Yg{cwT@nA%FzJx0Jl)x+G(9G%kP90fMraJN^<@Hw;r@^k*UPc zI~JxF=@KbPY1_Po_Hzz|qw=m_3i8!@8luInB_dE7UV2`et-MhOq((#6oo!ZN03Lm%f8wOa0fpkcn^iv5gqJ9Tx_LH1M!eV*7-E5;a)L1$0 zF>3Srhsq;&Pg7#j?9aJhQD_!8Gm6xJI?W3C3MCMF{Cl_-;DGz*q<O)BPA~w(#U5$L-oT?_)U$-6D+FE^bN%;oJ*0@{Twyn z!BI&F#njDo1NVpquGz51iyYVu?`W$X28D$v*{MZ_8M?-FT9P2@+9~JDzy}CK_oSU@ zr5-PvJ-S-VZ45~VYG|6(05gtwJ}AYF6>~Ej_g_+dq9|`v!`m+Y3;QT#_}a06tE*E< zvzXwvSSY1&scx$2@57f=)~c(~hw zriXRtA9&k2+dJ;ghEtil?b#5BHs3H)IHqI#!>ySC8E_%;k+Wm9aBIG8tsP5hO|B=S zQkTm3rUF5N3c#sjrDB-D;#me~(e=zIHHmU$8()FqLK3y2Y4WnA;|WUo8}N&)B+hH2 zbQqldq;Sk1D+WYrPMD?ZcxzDT1Bi14^|ieIVj?6aNbS^g=~|Bci|-Hvkt6E)ImZiV zFrjm7KZpOVNGEVqf9A+ueW60XX^SM}KSR=Z=LcbDN$RanLSihtT!&8K8%?4aW3$Qh zTQe)3w{)(Ny|=R$_VS|=lugq;2)2Da-1V9j>NYrEL~pt4+dBTu2dG#A=NU8%60;L%JJzFW8W5&E>ytS4{5_x4-9AZz(X(WreR*H z5spR6tWMyF0|d7t!7@=t6aW3}9_0Ks4+A%>oTPA!eTbs9Q?t6%N`js;<_f0$W5y9G z<`O5NwbSrp^Gf-t;g_2`l?(UlNB75^g2Z4fSp6Kc&&5p#K!#4pA-;U%=gZr_f*148 z-fM*Cy7RH51*#Rsf1n}o8P#seW|c^+RxqiI(EH$mfVAx^O|7R8r^H`|LMz2Hyqvz@ zKcPP-KKEhpfAqRQeo6YMqxz3yH-OhHHa|!t9~1O*@>XRXhD~`)WOP8TOQLy{@GIjQ z_yKS3klN_ET{Y5iJD3tVxf~ycp2Aw6BB)qH=ANR1FeWaRF+`bA-3{iHtx#k++^zKs z)Zk-qHH{~7fgMvLR~TLnN$dGHDm|=n0ZME#wa<2JIRsjAX;b4xAOl`fGb8PtCl6^0 z4+|m;I86O7aB;h09+YdD&t&}9I6ynN-M0PmW&F?hq=YaXu0CTI9oau}hMPn)g+)fT zDI*6EK4#jRJtZe_5n$ljd<=rXskXnMm z`%{gsw;#yUxZ3UMPAAl-$8i&8X?QB__WBl`LL=lUD!}P0J;IaX<*(b{MP#T=*}>=~ zaUqTfsJz}(YmUJmfL(PI53f9cOCEqc%T7?ct8t?N(ov#H1zY~>l$FKg+;fU8mQ^6N zF)5S(4i=E&e1Eecn1B9_V)RW2c8*t}PpMknw|9Su57Od_(X`E~dLv5rHx3>@XiRrY zd=y8R-*1dWMY2rJU633kqHJVj-0aCwSqjMFCdJ&|Mq%1Rb6Jmw1 z3lI;sTm-#CiIzAchgKPGN$nmy0xdHF-2p^y7b%a7Lj5fzNsX^F;haC@*OwN-oj~5G zRA}I3`S+R=5+gAfiqCXmhi?Dzpqf}5ba_2(1`KWjrM99Uk0)XqlQP4$WXf)mvWFS* z-P5s|1G{A-$~gU#u<42&x)R>e>$^$(&RT1K$+x~mWs1JrB?a<*MIurRkwR!hH2qYB z55uW4N{odN;su7a9L3&OY5x1d^cX2(`Y*&AZxwQ+~ItXm_oWXlJ;3 z>{OS!_7s-5I3q+XmI_;XWQ2bwbBy=l$RX-<;=`Q&VV10L-gog;u{mr9x8mXMBx@1BUVbXw<#v;$XoO=ex;?25%I*asef=TNmSk$2r;FZ%L< z|FVQRDgjN^&DxAz0UIe~0;yznS)Gsgiw$xcDcBRyVkl{AZuw;Wc8nb@S;NixMHww# zR#(vbEq01hiHr4ji6)nTNV=L*(s9{htHuvjLA8z;Zju(1Kcm3j2P|0aQS@BeR|E%` zywW#?$H3*T!E_*1UFyA}-Z$4vX@X)zpigUjYdp?X1q~$l54<&aOq(U~H&>xMlhVnH z64n$YfCHWudpv5AJICl`m<{MKHET!iS=(O)y)tXN1+?lhB3tcm^9=grHHWI*2KgTI zsw^QF4G<*$s*S#5U@HnJvdpwLTkV*$UN<0|CuhAiH8p-WZ4hr#k|yWd5c2T6xynM` zJh8+6CaEt;-3;}0K@e^E&v)m zPEu&B1Qs{|FIYxBRD^>MJa*Pav*ta2Qs zVYi$9^!NQKLE2iMOt?Ak}A8w;O2AZcOHUVM`*GPBr{^~Ow?ypunJi46uNx&tgB z-IKRO`yLt3v9C9Mtj<86oCm=se(qZ5R=Y>()FQOf`AML1RT1A$i7vYW9tJbWwVaze zMSe&i^K9WcKsR!1ohLiY-Zuct%ef8J4$?MSJoeY6->G;4!Q;9@plXKv_>jFmI@bB^4)Sm0k z=KIcENe0PVS|pC@PYoEMQTLmpGwQnS3aq-n<-25mR%DNNM+%IjMpo+b#9%1oRT7bt zE;f!YfAJ0oTV-`)s!Au)t2406zLC7y)0Qu+N#Plyc&rypVzG`1z|YEK2z3!Df#s-M zPbiDQ++*kdD))!nUCFTE_lf3wHnh&i+mw52E?e;_9jjVuFXQ(;fuh2=Qj@=cj00@M zMR+L_c}f35?Vs^Jo6nRju*&{l-6~^vYJq7R{x4l`8e*A!jLeurUY^=r-Nhmh;*h8k z*>3{Kquz$XL{;w&v^DWDAoyL5wrDo=C?uI5S=-fVj)XaPFpPuzF|p z$9N;zBPA$-wwF;mR%Pn&3J|!y0Rj?%IN?cc%EBIAKxd^11+o&^P=N0ic%fF43844U zg=;e59fs!l=h5w7c>rw=pAN1#(B^IfJoV#ao83!yBFP=yV>etlVW$s`134qyWdROzK zX=-AvO|2c1Yd0J4yp)z&4c1Gz|EMpb3%}NMjrv0ZlfIWUryzAf6~^3E<@!^o>o^9w!lSn42dd$l=r`EWMij18$2Be_EI1Fw%$_%;y?r?}KS5JsggQ9n@;H zA&_GICr^N7uYSH9w>@sZ*-mlntX($2}r1mMJvV!Pdy%SEQ0ma_)~clgGJ z(ZfSs9Q_|Tv3xoaDL_S4Rq^|9_xWKH>e`kZun{{RmM{_-SQ_HW-lg4w0ivJB3xwVv zZ(usw$kTmB45|`98Vxg{B`a*pCaqt8^oP1S7udW){43xLu!BFR`4}7NtoZEd!-uvI zz*b%_BcAq9`o}R+#eX$9d!AiaPtsBhrim!PYO;ZX{YhX!LKt~4{4j}XI z3A- z0^@Ni@l=R_sEpY`4F?_|R1ly5I5Qgxplb(?!1XmZAZXih9JB`mr!2#1+kF+Q3pF>x zOiM@CHgx(+dg~4FkO9}_4X{=HIR`v4Qy<0Ydja^vGA+Ky@-VBg-d6fF7=vHC3@W8_ zD(Ie-u;>1Jd~_{Qg&E*8(4eECf&9PGg)7Mz&7&>@+cK)^`UaaGyU@ljzU?c~#;>0; z&>T$*Lm)sbN@9FzX{A$bMS6?GvG=bqN$Zp1QO#FLq9&76eBdhx34=^iRu^c z_G7TZ^w$8UOoABuGOZo8p4?%yf`FU7h%)B7HsemI&xa28tl7f1Xy&|whUrgtfti^J za(kQ?&b@8|MIUaowh$866np!J zf-TOPo*63qx=sCZ`bF;{x~?(j9es+J=Hy#<%o+Dbj3rFO2%d?Jr%sR)6Kj9Rw|5kU zAFkqTLEru%up)=&bT9_sr`6Gt?n+)X=E9Yi5^m_ltKgd^k>jOnG6I6tL~wcfI)mhP zj7d;YA|p&Lftj~RzS62HT(G4Y{((d@mA&B(*R1U8LHFV!|IfK;ZZ3HY;IIg=F4riT zXHDjIJ7KH8N3xL~66!}+ByTnK-IBgwqpl8DeK)>!od3bp>6a`o!(Ei5Zn^SPqxVjOWzJ zHY?l}D7m|Pf-i-H)AuO&5jFV3}>T^N-p2zT|&r6UFl*Ys)E#+ zJvEvtkXF*Ucr&XgV5bQFL{(PU2+9XJhLh!kINszj2rmGCkLgI0QvsSxO;9EPY zmC*?F1cFLEa9VMAD>b(@*lY3^2x8N)%8<&n<0L}dv@juWyU-kbBJJPia#|Q*$_ite z>TY9opU19JZ6?>T?mqOiQw(r}o%%%|S9jJnkz%HoAxt}@%~ks$loa@s*595idbF#LvwkZk&}FxfYz5s8U;B z58q)`pSMO7Yeu+_!3a0Z^zJW+Qd~5y1x-c-RJFtN>yo5IImz0SH%)Tmbw|{~ZBgP6(_Q2FEA|-gmKK%vB<7oueS!I8aUr)=x?V#^CE`k5hmbLc1SzV4aemfMcK|Dk@L$ zKvWX$wAwKB_0*dmY|Tf`&vE%<^7Lj>yYYKzrp*1{{J|94_h@OCwW1+a;lfB52eGS$ zk&cKCGn7j3l+AuOSdeWoiCm!lFiPq~3YjKU=aoys28owbz~HZY%Y9nfIN4&|+kHmX zDqwuxU9Y+wIbd)~npTuR@q}eyDEO&X^hV5E5$i%qHD1&h(~mNd-ES#RHwiQ;YD%5{ zq{o1Q-27Q9pw^_t#Vxl+pWFtWni>?4609;~OBgp?r zgE#D_HlMh9e-x`bl=^jS<2EZeYKod9)8lCnr&2)T%8vrdHxRG6l*g{+P-*0hnUKa)u)Mjt_!VTG?6x8&xdNyjo4hNh45~@|IoF z*uG(x>+*8MBevoh_@vUMyma$di-T{ewP0!Oq^b)?t-6KV&=~{(ji9gOLg`xd1C}FK-%z{a1mw-8UMmO5Z%>tVdM$s@do=6 z7fKCh4vpl)zET6*HG$LJbY+>1b}^m=m2f~c2T*i}cjEKt*!qBsFier3fwm?#UNdOg zQ2DIA3Xw)~=X^RV8{&5XZ_8%GI}N|F2QOOBVWmY~xNxUq_OkCR(d#Gzz{rNXp_D$HhuuDN zv++Nkf&e~nssSw^(8iqQ;kSmqIs$B1sKt0{Fm68QM14|{Y)UT;OT+QsG4A}&FK0hL z#__PCv9_jW60?0APG3stJ>kt~^zXz)R9m6M1Dm8~h)>mH(~!d>yqGQ|HW&fmjK*tf`y$0UD##cQ{JVSp97!XWl+;tA&hOr0vBR%VD{ou-ElnY+SDQBvo z%y(^$Iz!7U40tSh&vlBkxB5~Upt+lJ7;>gU=D3~Mk_D=aDDdQ`D6RJm5pNY)#`B~7 zn4Pfd{BWWLM(9WkV{(6Xm(tRAqflZ6$`jzQcX@^bSwu1g5pAYL`mY7_zYfKzIJstQ z8$w;kqKuYNO-8H_iey;4)Bt@~9mL{inDh=(Lt-W2i%YDfxoioV5bKE`Y9>7#=|^Ogl7+p@!yeuzW+bIuFrq-rMskFmnlnc3ibRW= zuz^e9{||=t(Z#g~n8*_5dxL(CFTeTwF*mGwssZjS>YF3hrz<*2`c0H$N{>4E;5!nO zKQ_eKt${jMnHkvGJLKnDMd#Rw-Vsg+$M^d~*y@4@BZg6u8$oY305JGGG%D2sqdHC& z%VQlzm-uXd-{>c(sbq{J2A%#N5~c=0f{AsI$X07<3~x@k$UVje$&#??$E7lYeggPpAI9KL#rSGK^&K#$lN1}m<<{5JP8S>+g&DM#8#v+5@l*wt;d5!{ZYxWqo~MJgM|_Y|t9q;BY$A^96yLj)S7)du z;0Kt~0MjVq{*k@QWV(hqj_-1@Dh-oreW?v-GXjmeEWlv=3TC1E-gbL!Q+}`z!LRKK07h5DWS!@+p^c~EWf%ky@UQ@EmlC^67oS@9MHWc_a`hQhoxExf z5>csiI!u2s=L{|>4X75n6obT#!VuPgtEWBHo2l4%)|jk*`FwO1=}CUVzOID zdILn21o6a$38=t-mC!I;Tb<_}om#DMn-uYvG)k-`43La54Iv#LQP{M}D?0cCoNx=P z&T`4rF+G$qBfgb<%FD>wGkD~wGF$(0YaBGpY0KN(-I+A3X|j(lF_J>xeNN-9ziB3T z#xR6Cwdi3OyxI37lekzhqh~4n)x6`lpuDuSZs`eYVRf~V_8FQdAg}uB|D-?%NRM3- z{PV9DkPKBV7Mwz!cO*7EM9Ik6 z?}|J(sKbIP8YUzK@0U>i|84>eVgY?knatdkEBDI6%G(GhUkR`*$Q9h zqD0r_N7cyd{v8u5Kd|U0e746$l~xktk;0%6cc*j&+D8hUeE~zSrl<;H<0CrfPO=kh zf?n!NDo%bAQh5xM5albcQW|d;*_rox#%i-)Rv3z*TvdpZ++>>AE&6U5fN4Y}bfRnx zJ>ypmESRJ(($hP<153@@7U^UiSEp*PXTv5krFg+We(_XM+7oX&Wuc^FDV%}F5QiL5 z;dAccxH4~qW=udu>^4g`Gu*RM9pRc-(~?+vXnWctZL*I<6E4S<=e9=}MuSjMTQuFY z%52`-v?jK&3oav)g>N!&B~)Et0yuI^!4pCsLBZyrzsyqT_{8CLZd!S|-|Vr`+i6A=igRRr=3c0cS{>?$fB>ltfU3+|&1#E(ASJ!hp1ugYT1;VS}lbaXPe^)HWX+^MTRLEM+ELk*V?^r}PxGTg|cw}8DdO|=M{fKNPf z2>t0@he0gSaD=`i`i+fsegbB*gA~aOEZ95_+=IC}gzWbqQ2XyM-B-+HBSn+{Fy3iKw7#Rr5kA}>FzG+?(XjIIq$vq`*9e zTyxE-F1uOTf!IzKO6$`m0}bU!LF*};RahF&>JX6Cv1X2Qo1pKB`m%%i!lrjM(Ky%G z6yyZ^^j*IPq$hFe$6f~Yk(k(@_&on^C8GFjgJNC${se|A_BQR9I6D6dXY)41*fz-6 zn0RuHmWt}YE`}x)7$Wh@&_Y&ZV^bqCJT4|p`q@MGd;AJW&3zC0mI7~WM<1@la@@+^ z&vKnCeL}%=sv%7g%5ZH#xAeC@xV&LF6gS+u(96QB{b~KHw+@WXU;qByT}43QRQMO8y^)|s*R}KAmj~lg@L?I0=?(>NwCG3M<{E}><>0yw9(}=)G7ttSh?8ny08;s(gMRb}2 zuumRh%1BD`hN|6k=^H+EyBoP#Nc;TywjEb>OuyBd^~!FBjr=OrZl+Pu0a=p`I%{y zK2%X@q)HRZO8Q%ZhV+kTKoNW69b@^t>uYMRV>3FGyWh8{hhZ1HbXoEA;dJP;F2|Aj zqwNvaqgWc+w&ib{F=ThK>paAF-`(E@A3gu1STxcfk{+a0XL59pEc@t=jPh9Z@8=4Q zIG7!Py&gcYf>f}?#LHTFW?q-K;OTyL7_wn8=S>6r?U+n<#i4#n7x7C$>!$Z}J2Ba= zJ=#t05XyBhIp8vxj0sXUkXzR9^?GeMH%jfFTmX^(n)vpW(4F_w%H!f_bJ)X4t9NN= z#N6zxfxSJdwLs3eYct_%6jXCDCBOLO?sW&-qr;!WRMvyruC`dnO7WSwKtkc(46HlQ z#RJDJJ|$208Vc$=0qYU7s=4G(3Dz|>X&d-3=*u$|mZ2r?B^TaI`Yi(n%pKo- z(LnPemYo0J{NkALi7=fiojz?jtq$mCy~BUgg`vfIc}t<)^d-uQSxUi?W1QT@MLi=- zYe9T2vun23f{4v(v>*| z_gZZKod83!>ylD|e`dbhQp`eNm-n)`c1h6GOSCB^>08Q{qFJz0OhQ`a*MUezzGvCr zzAUK6m#C$9i=~RVL-HPO(ea!@xK+Q{6*-l^BCKa^0Qx=QAk4h0M|OO;lUad_AiKRNtrHT;$RkZkksr+wJB<*Fqg>LEP*VeRA>;zI zFs2mji5-=s^Lf;)u02!l9tbw84MonI#oLpl8fY=}eG$jP##J+zxwG*_7^5O%hLUgl z_X#21jPE@ff;0h~f5k`plHH7AL_m2sw^E^HNz4Zhi#$3cQ$xCR_M&7BR z!-u&XJmmf+$0p;+UYWU6l`D?zh3T)-T*Ob;wY4%byKqD_wkV+=bT? zHL{`^$=DH(_C?67Ybu?J_@Mr4T0ptccZ>$hpYaVJ!@f?I7Vlh1ynl3*O)#(Xl3#Nw zVfSbK$SaNZW+;r3wWyzr9$A)!n!rETDc}}K=B+In+WCW=_gepiRzCM6@fX$JbTaDaEfC|M`M=1bNIsZQiNnh( zy6faAss+cgNVp!(i_5#e)@bu#mP*Rp@%!*CHKj6zCvByDcF|vfWKcbKJk~eb-|!V( zR~-SR$SKK?))u{$IexJdkomlNr${SqKo))H;+329pXr`e`;txEu zIA|K0t#?&EYYxFRiQPuRX#b4DE7<|#-Etj?bGH6nujA<3(g+~QGu(F#i5|mRbLl>q z>S0KD%C9_nj0idg>goUa#AX&o`(%i!jjd3>ED_S6!w5>qtJTGN=cebY@*NP*j{CB5 z;uQ?)OU9Y&kWs}dFs4TW9ZzeUD5?NV8<+P5*G1aOT^b<3(fr;JdqnHsCFrjK25|3- z3_)+xHb?myU+V>5JqU+~$jXM-lDzJgnjV%;dfaaFXIdkPpT>!ScP)|Et)bUCwU=Lz z;1lyk1p3PPhn0?6kHK090|9u$dL0a4Ok_R5z7_Ry8^tmWLS~zhA>*(rFq8!hWl_=e z+>z(WcVchg8~YJrx9bL?ar>TbRz`uu*HrTy;`#@15Cj458ExN3!Bv4|$wM@ezHf+D zK^`pu2)nm`?6KcWJMl2rHUf?yiSN-M3GX~$-G;J2K<@vv0RK4vLVS{{rwIrM zfEym_=|k(w!{NzEPR%wxsMWV1vCr#2%m)(aWp(Ntpz<*FA8Pam7gnBKfOI-?TBZRE zKO@YoX6`=CEP>9c-^Pp9HU%BbHL?NtJ!V7VDHN)0vm-L1*26=P#hDq5XH$?XP@qvrB~w z{G(FZm^<0Vi|?S06p9RdCsc)##@nh66`o%nbXIy9Bs@YG zpl+RHH_)LV|1KI6v;$-fOt8qwB7B-f`_0U;+kWUS9$z1|gM~kWNh808)r*#XjHYA!K z?$k$-@xpd;23GOY76<|jWrMk{XQX5Q0NzQwS1w_aGEBjMOi6r_-ulO=o5k}dtnX;CL zUK#GpCr|sITQVjI|FUZ?B3RP4FyibhYLzRkxt>7IMjI0$T@@}Rq1vDo zbx^70X!Ba+T~?|HPXJDf+9~vhxrJGgw@hPyNAT6;OQrkViLCOP4d1uQ^CnJ_HdpqN zymfoNHRC*2$t5@yzO%z##|UavP)6pL<$DeLL`N}zA%bHZK=Rh9=}Y(oGA1194mWVT zbE$-LPF#L@@ep8o{=P7GDsThtCi(~xnV z1Xd|jbv&48Oi`C>d31C1ykyp@pvRCGWSv$D)cnJGfpEk#mvCoeKRS{M*m)toE_=;? z(>;#yCDz(Rr5rJSN(v4KAZc;f_UoaV`vX;!08ynD-tLtm*(>8hr!biKSER_MYMIla zyG(&Jh|Kw7G7ckuG)lmRmxxS1z5d;m$EJed05$PF1@PWxlA-n5^}Zto#-T?q8w)&O z)r%OoXp_;iLF_)2>q8}pzsE}oKG4{IU+@N74jUDcLcP60&n$w^XHjQtLKkd+nReQn zpe(s)dj49zHC67#p=BLOEHv_kR~SAj9(cDgZL~b-^?*m>*4yi9Mp5Q;Y2|5&+gvJk zo~n|D)xFstRp9iy$8eZl+fl7htE~r9s7-0&S6mfs`qow0Zy15ez;E=wO8D?iFgX4+ z@>|nuQW*0Q{*m72{f);9?`xr$9Uk-1^sUb;H`e}!Z6L~n7r>Sz$E$rcuY+%beS6vp z7Z58pR(iL`!;Qy5;+L7l?itp!?e}e>rLlc1M5NjIcK{Htu6;eGq86wALR2 zQDFKNTBUWsiuF~m1^X)GW7K*-XhT*`Ax__SAsM%h5N}b%L|qlHpcm-6H5i*DmMJit zmtaV8zJG#o*mRR=T`Ax?WSd(swm(6%YyfelM6Rpflw=%TUE7Y28H0k}EV>^I`;f~f zA;Af#7sG1JR3PfdCRp(2rwj!a6@gJJ5GLF_?hnTPr&$3BtiZfN7Mnv8{YQId z%`A}J0~c_#-+wzx`fHeh$*803;GbnqNex`ahJ_H(2SPcKie#h9pTkPxfPC45u#jBZ;7%Gp64 z5Iw!O_>>-pMO%p7CyZ*3r5Tg;Wr!}LQb$dLdR9i{o|kG=rO&|WYZSvEvl+ahZC>^? zC(U1m3O%$gba6ujvVd5>JEtDz!j}RnX#319|Kg}(G{5X3wIp$+=p9-x!eXGe$}`ij zw-+@);R*yNNcF&HQW)USL`fAD8zJ{*6P#LLwhi_fSprGmr+1vd7|ts13KY`%55q6) zQTPi+#z^3w>FgBkV76H?XT}AtuRzrSEPDT3e?|4n^eiLQ$crzvl}j|ee0bvg*GLMu z-RJb79cM7y_MJPq(I%_vmqQm(R8wnQHX~eqIEXKilwJztwv(DSbGzi0p)DV57Lb7_ zu5o_$=ss0?*xm7)x)^uPMo=ETXj;0aN+}@sIzM z+w>q%#x7!OP$~(E%m=qghdcSSht*7wz$=MFKM;_O>Qw}xvBceyxqpde&@)UG{SXL4 z8lTWf9|VuJEPZ+Y;`8CybR%g1`J^Kgyo;i{q{{#u=r?qV5V0h`58}X+RC7SWEYkh=avB4Zyrk;cU?G`j&kzS#~DcD`q0&s zN5^Yp2}9|qi6lS@4nbEu+Yc9EfmUVH#?pa8tt)M+%PK7;%e?mAp{z8_MO`wJ4MXe? zbDJ<+QOyn-hsgZbW7H%uP}592C5&sTK6AtM|GtN_^>+s2s$wdcQC2AI)}xsV$S1@D z8#!^UZswD$w7g(8nIngyk4ESZ>BgP!kYYbvR|-7euZ|X8rdl>A{Dcp$2v%H;=ye~n zez0EqNb|?3^fm#Gi9sDc9=3^!5zb?>|0UT=aMjNvRdQIAzhi|N^+ri4kN{SLydAc5 zmh?|--}3L|7%|sq8W+xQ8uF;W7|p_iURQ3BR$#;A5d9>|`ot`5ORkf|L7=SB=J#2F zXE$o&=iFiP{0xs|qA9qKApVQ~K0vz#gmOZ6aYFr0zs@Fwo+b|u51EOgzysKH)BKWt z^3Zak9rl3)i4xdVuK32sdZnJmM0xmo-<3aefSAFDJ73~kC{8XeDA%>O`hCTES3oXA zhSb@x%t7F^llJYr6gX#sv9ROaxhY6(L>0UxS$RHMiJWe*-Jj7?Nu+$z>)M+v0PGow zG)6WJStuD;mzSXhD*`Jg7aaN*98H&bOq8KydQbbGoq>r4k^3%bs&i?c6M^M_$&CO$ zdI;_~M+r$NVM3w`Af{`OffNMTJ|3++gFw!U6d->BUG@_}?TQz@(CrVQzO--4AuNGG z#LtXgPcz#3r&0n^D4Z{*t6r=z25D(Mc0uk=WU(5Nea z%i2}$|1#`vBb6f;!)m6%@VunP#@7BKkgEv_3+{3G8gGe^&47NKFmU;$i7@Q*s z`2tzsb_jxkg1~=_BBr=3KUk1d!u)XeWxWdlti=sYPoscuf;cK*O%zHt!T#ho(DibD zN^_#PY!E=f6*(X+wpF3L?oYMf3z}2x$vv&Jg-<0WwpSki^rV7o0;=xcd`L@@+HrJ~ z*2G2gqnX}?*GX1ZWxH=ClJP$bhl?-vs{<*#;vkwUJ6eT05}1lgiD)|ihCU^lHfg{N z&HfGF=`+Av9UBfuUPLBd9C+HOYP1yejP{;rt$Jrt;Z)Hk9NiK?jj|X{-HcWRWgu=X1gdN&%m#4^SP@& zy`4GtPLWms_IUXY7cWdV3cV+s>k)#*wU zzmonwX!%dB3GQ5vJj|cdVl*A?$*0zs6(Zavm%)lgYTW~7FnZ{>{zht9%_6+QyFs`A zSX7Nux$4FYu_Fncq1EURomgu+E@joTv)N&P0Er2$cbbz@78Rnv7&8u12YT^TDhUcr zajX>O3w!o;!O!@~@+Yk>)qb_QMpB4Q(Vjx%kgtbnqqHu>7Q zmbT=+rV70eSqSgtjn`!=q!=%<`X7|081K|Nzo@Qm2u`*W$;XFxA;7s2nH4Ggt8Tm5pBNh>DnGpjxk}yuFBjEnByZoeupUE zZEKeR;X{)LR4IU;1FpwR-{%JFb|{(F$0dnPIa3TvDaZWoJmd*_KkV_P$pd4u&C^pf zpGt=Mt7+}}jYz)R;g!cy^*>`JqSnJUoW=>*peg}d3Gw87RW)&fUR&LgLP=z}*M1~z zT7v+d)GoQ;6F;8@Daq7)&1(8B&htt-_7oCn6XkW814O6FYFOZH8iT6TOY|LRZh+?y z|MM-+^PZ3=eSt#8HsBb5Lnfq!UIw`bf3H?a;O9->wNGv0a9!;K@g(H)=>5y+zP@(( zw)Vf`9BKCPpK5AQ)%>EG|86$Tkj5S}Sn``+IM(X}`Rb27TmOZoMEv>)#GS!5{37D`N{->8vQ;VUHmUSHlT5^Xe8k`Jd_&kRZ$Wnp|I=q}3k9rua zsU`*;>}}2ZXCE9_rI+L6(XO|-`jZ_mK9tKWxm{|BW8a}EHBH`C&c$Z^JG8mv(K)Q3 zV|Bp@9*8$dte889!{V94>Yt)!0#L5*YBso%-9M%)o>Cd!1a~IBrWg&ny6D3P^9$OA z9Hr(L5r>UUd1!Q))lUnWvtY7PQbVKm?X9-)!f^<=+~Jd4E1xif2nhaR+yQAusXE{v ze0Ky++&;W7iSN)Fv|u*^vX6*}2$yI#;K@wtzY1(gZPhLC$U?IXjE!HP2mmPhWW?!j ziw5H{^UV{dcG2mr(3Of1xEY$RYs$BtA5L~4c|@SN0*^YDH2K1!P>}CeQUh*1Pzy($ z!HK?bMNAmawP~eGp9bWa)=G=fJ;Pm_zujx=QP{gq#&_26Smv7~ z)zpp@F485X_o&`-L;Mu16Gj~gYU4t7M2KYBNUegO@(ow#8b$!F(-FrMHFaX##*sGn zo7FX>H9xf15l4aLjZvMBc|a;4-S4JhVlMe}5sGdc|BbsMdkoG*4QF3bbwKe_1&Qac z26OD|j>SwdF(1(fg3s#QS&mr+UnnQuR>w+FJ4~;t`eGT3bK5I5keP-cY{R2Yf7Cxb zEgHvv-zP}yw*Gpk_FCh3`|wxs?4LI4H;fiXY5Q;`^C;tCBfKU5GY$iyr`Kzm+C*=y zIC7g3qrT_zG?%K8D3v|OShK3tTMw6G8GJoD#ZX6|hog9cA*4$j5AWEiQ;Wn&?`~5O z$J%(tO@Zwi6vPNgz&@Y@qQMU$%eRmARGb3XJ#mv1EW* z*+|^SfmC=(G6kNRuB4>21SLlD1^OkovBbkr%v}n_sXGhc_>g zbm>2^eoo~0p)s}nMx@r!)po+8hV7W)Alf6vgn~kMvogRM(?;T9v@;|~&o7}+;mbMv z?B7fzz8bAJcJNR`pQ0U=kTr%vZGV`m*H7eFC%uUOCzXgbLzgtzDDvd8?TyFj+6py- zk)5DpC=HsbcmM_pB||-}60gVps2aRP4k^gsBtSV^c0OAdfA+p!=3kC25`1_ntFfBD z_;sHuSnwv()Xt=ubR-zzcW^KXw7Xgtem3z28uCn&TX}S_=;gK=JNkyJuyOQEroq3= z&#x&+&}^Bc-%)g$GY>EJF-x{ z_!F=i^?Y!7g^i8vbmg>-l5`c?@^oZ>QEKlQmey$Ii0L*;^N!v%JqXhh)wKRXr*9PXqWgSCTt0eZowXWEu{jd=YRN9iy*WKBI<%WC zh0}H&KulKczc#|~!dZ%a`1=Y$yMIUnagBmW16}zoN^k0kaKglOW=tI&V;WCdQtZ8N z`0j3i7JuQ$>FH_)@+L=k4@&fdM~6;xyX;+jb+ojy)r&!6&~j4s^+3I>VV@2Jw7G*1 z@>`XzM87p1^a(;+eZXC7qxFRk67uD?!?)5uH1tW!gtkVZ&7oACJW@1ym?}XA*2i|? z@0uGCxbS@;Tk32zvWy8b>?y;k8iRd#Ag`P*0WnWGM1*ws)S^b~j_gv&+c0-IKMMP1hr zOgRM+YZvPS+>H^&t(>|pW#onK;6pbQU#EXt{Z5M=c1b4Mt$;sAeB1V>?!Ks)CXvqL zHivlQ&{4++ys=<$_EA-cJYiakf990Pp=A zey^pOVxcOTbnIfFWiYANXLQ4gvQ81{iN7Dj{!vwas19kn{pl5+C}30|o9&@ma{A>X z%S2yGw#9&${HH1%>MusBWJ>eBEGTe6eLaOAs^c#`L`A~kvlj7$FA1_mL>Sny<;X-F z7%(Y#rzv_!92}zySptHCb(oc-XI0O#Ka}8W_U|wA_V7&}?jM`5EVnmbQ_oiTOXWq- z2|=6Q*!s_Bbzh)~BC&LVFK6LD#F8(^L#v4f<}uWBUl8aW-)!dQq(LdsU0<_=6I_ZZ zA8hs^uyjOoqjw6-LQD&k= z+~->rq=Hm@_}(qvs5sW_MjeBoz=ztCE={TD3R5nb`vWTZ$3#N@UeR~P7(cKu$loDZ z=G&XS{ZP^s^+WZlNeItlVhqUMVz?!;V81M(WZ~zi1y?KDDy;3kqNYWo66N3A%$3PquxHzT|qQWMTE%WKdgk2 z*bV-FV}o|@iN`IgT~D7g-f`j^aKNsJ zM-s!C%6ZTv@W^xfl_AlbbsYGI{0;opY|F38J?(_pf+Iy{@aAYiAF665q8c zXl(@=O4Vo$BXC%M0LC~qFVHj z43in(!eZk0<7&OIS`z zsW^9rxRv0?0C^EglQek816uxyY2{M&3mr{sTY295meGz5kus^_bDzc~My&&W`-O`p z{(^@JF{^x?VJbP2n$v!pLMXflxQmO6_(4+%35lO+XhV@P6&s1VVog(VOzIqZ~TFe&CKs$+>LtqY|> zPVRq>k)j8dk%#F1uz&Z_D7Oc?f>R2!qsD?dyIfS}3A#90(x4%+Y{4vQS>EJc10y%7 zh&Mb@YR{lQo-ngSVh)C$GK*O%Wm_LCSE4_g6LVdzD+H@=(3+3}9dfZkM3*&4Z0QFX!p5awBo-x~Ql^*egkCzV-ed zmRFe|HTWWCv(q)UXRj?8D-8QouB z@Ky3IyzEY;MQMcb!iuL1h_xu-j!qlEAK)HWr5B$+a*;1HLkZPnqIFJx3rTs)XskDF&f$)vO^^Yd zIfRP!0#Wp*Ab&SPma(1!XVIi+O}?O${Pnk9U~k0rtrK9uhq|Y0zVqPnlC#vSKGqva z5*+F;jk@4bP{IUG$tEWLdwW;t=qhNfAgQV9BzAr{^w?zL`mO47gsv=0i}QCM1=vH2aMX?+TZH6o%Irr z&d%ZrqdBYv;IM)ZcX|26OJEqrb?_`VJoTXA3ojwCF)l*^Gz0aF-hI~>X%&=*#{Lkh20)KoN6G)wLr~gk2AmeuJkfmtg=!i}`xorz}SVOZt`-)cvA}|Ua zBihKA4LEQkFc8DUHPXEG4bU`lmt-&SC^V{U^iF50nk&c*J*p+j@r}+b890AlVwUq9 zX>i(GIo;mV(TA>*XeR4#&LWTI!+1O`)K*&3ZjPA~wngwI)ot;utnH-KRz9!3t_Qp` z_tifYw>`^(vx!N)5v+`7ZHPOY-fahtbAN`epK|ES_47;M)ZV3mx~nPOgbl`8A(>}} z!-|G%`HZM_3cY3yO}26&vw(nHy$)66h7J_ixs(N;$;pXTNE7r30V2K*tHmwgJV{JU zJYVNgDT)ja-`t;dX^c<~#iCaqvtS1%Q$j+cx3{i>C1ZPE&M&C&{{S!w32Q3RstI*z zl&jDfdb_!mYg{}v(BC^mB|x5CH3N=Z$iOo{KOao~>UFQqxuOqmF1TQN`}@xszVV4l zY=iT#Lc`?Cmw2lh84#4h!0@NKx@&fJR;J8A?7Ui+42VT9yhdXDE=!m=P#R7#OLh)Ods zNRwurXx&GKRR)qI(uj!E{z!zQzI1>e>xs>@;6u;Ze-#-fZyxZ=MEeBlIPy6`xBcm- z(c1w3uI!FiGswFWT>~&H6s|p;Q3Ta!)qd6Wf6ZMYhf5!JKhP{HC2{2aIDJdh96*_T zBryBY@2lgxfMQZdq!4zEPeqLFB!{Qm|Fv3>FX_U#n-6A)%UvNidr~wTB-MO>cw~c? zs@XN@(Wg=1JLCWSQ#OVRop;HS-@Qf?2sy?TGdYukn!3hSP-k7%m9AaM>V{5R9^F&8 z9%nWDC;x|4Z;*aq=a1DARJC{*--h>=7iVS7HA&?wI8mvL?sEox?@KzrKT>=aWAuOb z68OaQh}Yl|?V#Ql`-V;tnmo!tUzY}kFd3R?G8W2oX%;dH{QeF9K5T2z4wX_|_eE*e@B4sov_2N(z zE?V(vol7JB!opBlt>&zPto?AuuU?CO9b3ZUEB53X97D4mzNFv5gX(~|`v)9a_Gt<+ zL;oDimJK#VyT^&0&oV4rtz9)UdV`>9Ec~_I_`6_d3})gst|N|+)V6`rDE)`|8AwFg zSw2^Dh>C(h!fO<6pWzfP=f|_&3lPnXMhhxIP(T1&lD-#DFM%^s%ZAfY%}jRu`WBNn z4`}ND9ehRMUVY_t+exfUgXy4~B$L+xDWkdZZeJ3WL*)zD`rtkp@3UrgI#slXP^b5S zw%e)YuGGHDc7b>YaVsDI_PFUne)+2G8w(qoXgTo(AQl2dQFuTVwFDTCNG8wd*euEP zfj2TvvIxqJn4v0{5j)H^T{369?Sg;#Eb`l_FRIRe$)EDPdlUd^gFYVuyU9`c_&=kW z?^{SA+<=BIRRi*S0QlT;`UPN#aX26jw&sHWuRr=C))QhfQ#XW8E{&1?^0>3}7|9a& z1BEvj&>Dcg04S$kd%ryO?BKyGJtg|-j5|_^u7)N?S-E`X%rgUg=!uDmkKKHJHHG4m zxOn`K7;&#yNbsn?VINRbI0DSd!~%-Ne2w)T2<97t1bzc1Qi%2>9&9>bEhqJ~}O5|E&cg_TY`%!n9phJX1NVCnJuD zE_m{22{JiovNTMSUoD?C!m#Ex5A7W~4H>HVw#PyY#Z5V;+XCNZh}I*$e0ex3;ki|H znQ7-0tO-dd5pYcvJRO@RR8=P&m@o>H6M9C0fdVr>K1m`ElJuRd#mm!Rxc9>VLEg6X z0%ga_*{@NLK#ktIsGPRN@8P*zXqqwgLeZKCZ?l}ff^$GJ^L%emuUrz~`Kg-sXTZGK zS#}32E^g6dQtlB%xnixnJh!63gaTcc(0{SA*3%_f3rFWah#!4ko>yK#J0tKBjYghl z3sdlZJZd{G<^bFZjo$Yvko?yQ#|??=!?{jy5N6Oj?QCxYu)F%xIC2dnyAUSny1Xwt zI1f?q@B^)v@7$cG%Zc8q&ug>WrF6ZymoHanS8F6ECT?5Qfrl7F3{F#rAjvniz2~Z=I`5vs8EfQjm z#Ywk1_^Oy;0tY5N$kFKD5Ot47!_u+(he%E^dKZZ(Ol&s114d98!en4fC1xrj+m`fn zchH*UuEbZJtT}Q5_iFewTzcaYsR^?T7l&#wV4$f{@fqm4o#N+~_)e)MW;vPz0;W;i zogyb>lK!f4YmtV>ZO=mu{Pa~bu)1ToTF&45KURRHi!HmI0to|+it@ht6Wm<|bRHr9 z(YAV@gaid$J52<~FA)y4P+nfO{ClO3n}HPa`(zwi$v$>P6UbsQO7`JDnnk$<-324R z&SEU0I*-u|Rbet_W8h3V7rJxs_ZkOz_`kWNA`11EpVT#BPi|u&YQRKSbKf0jyiyMn z)D16gXTh~*KFhS^RJ_+Rymu012`>_ur&(R$2+9LtUMI+)!`)<99+xQ0T)5KglN z3@A4(gvls_(M-urCflPBR~w?G$UYlK^k}`IC(uza_#}c6B$aozL^k1WLC@?NvGLtt ztF0Z*|4dPWOu5{?gQDlFiqa2sMY{N3cqxXT6vn?MT11YbmmjV_V43t9Rf}l*atb6X zy%UIS*yy5buR)x7^`K(=A#*ByXEQFnQ`wWK5UHn!LOMP!-jK`0>e3<9x3gJjL8^SR zTLq;Bf6TJRp;@2EQN4Hyw=m)E5vK*IZJvV-0tVPdxPMH_^F?$ed%6>U)^nqTFo1V} zJd-M)G42k<0_5riWRg^>U0VtGfJe8NyNs7#d3U_ML=QI0&)2mZ4}w5J4~pV{NzHo- z-pSTwcf9Z3Z4fy1k*2!LTh>cahcUz{gC36M2NGCO{XJzRMSB6?0w5;@1OupCcfVg; zf480DTu=o}VpIG3r6YN^aRFq8#1=z>GoP3ZhxaWbg`Qmrdb6gi@aY+KYD>R$mY3PCW$QT+L6Yq^ zF>-A4uY7p8jJP0r?Y8VUTm*Z_u~>N4;#!y56Cn%wuctePHrY$Nsq_d~tDI7C_v3 zu_*xb%%^@hO+J9!7AVoE@T+aw5($q`5*gcbp~0f(X{Yz^v-LH6!Dt2bI$nlS=X0LS ziZbPg+jZ5DWMno7E(M<%wCZD8lNRi_`1pe#?4O@T_#jE%pb-b+U*e7SH^iIv&)X2p zdpp}J*mHZ!tt^xNu()&Ha?>0I$?7imx+-qk`e45X8VZCmR<-~m#s36MO(GW~K~ zOI-mtdVNDfNT5RVY1Y~i>Vr7eyCHMI(G2h`fIi5XkGS-!m&%!j^&tZj_xI*RZ3c6m zMkUNGmBc6EGN;6+6t{l!L6a_fGwHO#T+bD1X^al$p&%Iu!Gpm!Sk(`|a>zfwqCN^a z^EYyAIeIF(0^kp%tN;AeFqTUa=_TEzr)r*(s!uFKu)Nm}2@ShU!)-!a(empe9mk-D zmAL++{DXFtQap4GQ~7PUE=k)udi<_ksX)2IIM=TZJ)$| zx@?XX^Q#t&B*JL@UvL7-G;HBKhb#jJSuJFJFh_XCp4dgKrt$* zja4c^Vbu;<4>Ic9ldlsVt9_FGvHt#%c9Xf%!U;Sj&III6;S*x83uvn{iX_mot^W+m z8sg0CLoAxYcJX>7scDj-^IQ_V77I3}Ehjg9m%Tv?q~RNiRd(i(8&uqMxtw64nP1+g z*4lCWk~~}im(b<&kxFm^Poy=Ws8|l&#s{A^p2Jnb7{+2soR5V&43j)5rd~;+IpGT> zL-l^O2E}Q60&MvB?>0Znjait0AK`-(Qtl%ptaP-iDbO*-a7}feY@4CP{DtG9eaPE! zD0s8R?aBD$8ibRU8f4knVb(BNU0CE}G&KE<9dcz?65$N#11cYS3lY$f+II<-&O> zlxTTDG)MT$r-9Uu^|5sJ+wSQ>J8n%cPbZ_^$8JR6X~H%B`Rmsjz|W$zw^c$9RbNQ- zUyMe9T`L4z`UrQT9U0enkuYf5uw>VAk`ep`v{hRgUL}}e z-HRWbcTc&yPIxPS4}$KVHw^{!wV)u+9DoABnN_`2(PYo47{XV=m1&+(|9yQ2RkK0jWJj)ttWYm*Is=6*cwym;GH zrrUT6jDC;MJ4?GY&cb-H1{1$AA*Iw)?c>29%tb66d zQ9N@FS*AW{{rbAxZP?l&?Thju;9ouzq&gu^Yw?c`hLixFCQi0huCKjDZlPH`a#-5H zXMe^>`#BZEI6nlUqF&Dge zUv|H*hHI>(3>Bzc5l?LKON3n|#0+-x+3)0mJ5sc2jsg(%%+;JvngrA(x(_AQ@ShDn z-LsJzbcc?o{(hWDY7uMJ1GBz66d+Tuk%#ww+{oBGA7m;Rw{RGsE%?s}0*F8M3NqwN z)i=N$f@o%L{wq0o9avYJP3Aw;uZO<0ALzfh=f*=O2&wM-gAQ6su&{=oa6p*Osm7T55V^&y8<7G=^|7wTMaH5v76vbdj89WZEcUFl5)oEi75cgp->G^bOltFf1uUJ|(nA`$#FPb$@guD{X^sUMYct ze2D+X7Upz`jUm$Uj&BB*{yDkXkCIVd#>e0qN~t3KC|PKpYyQ5}U&8$QVH?I$ISG?o zB}I?ihhgEH!2*40R}^%pA*>~3%p|!If)<5_<(UVLHB!Z1Y%u(q@G7h;B`O6CW~9TI zauxk@Pb-&wUUP964(;D+;#}r^(wZL#AC#q_3#2R_E={8{w>LC1a&s!q3|{e|U*-_W zN84#9>!x0t`E&3FwbRA6kYZyi`TOl;C1do`RAcX!R8S&yP)QZj z@-o89fz7^7ow^{o3;eTfA`04G?n#shS_4rWO6c%|u`1884;U;Y{^8IEq$MKnBZ@PU z-D|Zx z)8VuFj5cjIuxqfaU2r=QJ7|7=SEkxo+e~_mUzu){DEcczq*AIOOVK!(n$N3p=!7QJ zfgp$`^!)h-%mNt6H}n^dIE7yBMtSacbI$ltdmTYBgUQoB=2m9F22TJ#fT3baU5kqZ zWe0*hXDM!y=Hh*~n-me<;$~)MvvrQ-E4Mvd{|%%~lb&Gz`@_Ei!EWdD3xZe*Qs<>U zjf0pN^s<(FE0FS0HNs0jEM6K>X+6Uz&%Fi%CRZ5%3HJiLB38KTykA%_VZ+JNxccppdSKLdS92uPN*7;Ao+X#7l+#nuH`U#63*mUXlgqHzDCC|^2M7r zPY-LG(9aq0y@b~~GCtum&UeJEzW`TA>fosO=>2leWV6)tYrYRR=Uv=m2F?pQgtswI zb%aaObEgHvI`R1{N?@SDL5&w9*MWA8GA4c^t4bN)qZ0y;(Got6)s26x2z`L$CFh&X9(}+ZyZ<*oDhf8_#W7NzX zjN5STUAb2;*aA|;_g`p%BF(Cso>!S^;_F|b8vMRT->#o*<~hlKRBa`h-}{g&7Nc65h~6i0O%V8y<#X=!{N|EKIU{r9C^Awfh-< z5wBStb;e!QnlWNq6jK6=5Gy-C;@2x*kp&p)K#+Wppb$(FgGWkM5d(F~Wu?@hmS^bb4Iz$jK>{VZKAhbE=7;_K_KCfJj(wU>EYBNdJeN6+pM%Lcn? zz&$1-#~@NIN4VXVsZz+H{F(W-+V7`(MTDbmGOP_p2O^B2)tgcn4e``h@FfM4Pe0*5 z5s>Cl{tXmE3@<>NAo=1SXTcwH{t%KVg%zzKt6_H$+>q2!g}L-cj*LMs8=a1{0)0C1 zV^5}g<~>bJ<|jimxBRgp1)2=J{*#UlXmGDqRIq@X3fx^D>)ww-{+v|k-);S{pwn_q z62*X>6D=$yXrXJY5(=^2xe9+YViHfZ-nwG$;lV$uo2bmn$_g1zKV$*Th8Q@qXTH9F|K8Bc z3+#q%Y-|9jtA<9Ot#uIY`nRj68uj9}21dw!z<)1+OU2{qqPs1eHn1A>^Jk_ajl-;A z&{pnQTnjL!DpaMz3=?-bUX(7F%=%A+1>Q@l_w!w<=k**!fYY>wY`@L)Oh)N5`RE^C zr>Ube#3rE9h*h_n9k%OoBNIoz1q~W_$lC``@AzIIf!n6L$4bsZ7!8&u?-KK<=+)D| zG8Xc~%Kn`2_yPF7f_yuc@6!4VaA8F8JJUXYp+n@tY#VDQDnyVlKSmFD!*n1Xmf!x) zYbP#^?PHWAWED0a`Lof|_!C|RW|`)4?c)sduj<)x_+P(xe-baczj<-A|Mf!xqsSdy zZ3S7m((B3Hz#!t??aL7ciTH1mwb=XRCHC@r(^-W5=A0y9 zC%Rkd7_ZX4`U4{1IDdpgSWjBV9g|Gj6d-?FG0W(CEJ+__pZimR@$y zP@+>GYcpe>IDO~%z>TOYMQvQgpto{^;P;Aj!m}WLAfbQGL0sao$1$}y^oDlm4VS9s zv9pW3nTv?!b7kL+Xd++S+*{LLc?oP(FqKwN(ZI>mUF;Hnk1zrCK1c1-u0Li0T~}n* z${wp$>gvz4xLqRlPUWVE2ORIv&oqYOMJxW-hzo@`DgO?kR67#lb>HA4Za)!H`1WW8cfzkA63{y2X5-`QU~1vTALcC> zVQTUE%cJ(6m(Qk%Zr4&@i#n?;w@>)bR!Ok`2KV+7dAq&Lw{`RoQE0zrYNxn zA6F!2GQTV9y!eWuvwrt~6(zXqpBbC|v&z3`wsnfepltL=#8D*I5pTc}MUu0;R*T4i zO~zGlbLIRvAHP}CfwCyo)rRPHvI5W_*&BIE3{zFD$ya3?Yf?CS{_r2pOxmPaJ52cH zdZ$UC_DVaH5<3 zmU>Ji5kFl0vg)@O=@j0?-kg!X;UN9q&wRkRa8rm?i``n6%8c>DNa0)hF|Y~ETCg`J zK&Gm(b@5;}!5*QbzED{c*;h1%!Id=7iHLzq(Xg2zdmtL9gD?Jwuox<$*_77I4}U6mzM`7nnexwhe>m_ z7)b#6NDvPIUx=dZ)40UE_e-l_l(p`P3yw5Eh31mK{*%Ia{GbyC>JJH>*ZJi_ldZlL zBGw1W@oNWcG97L4rpJq6j_2F0kUW2ZoL}H%2Arfh4OqXY?`HCzZzw~w?9$(`k)D7W#R^JIdMW= zLuMw2?Z|!?K$p+T^r}e6@JW)R!OpXHUrvVf-E_V@J+6w8*;QtF6*4I0o}Y01jELjWd&z1CuxOblpP?$R83u706M{FkQCrN&=0m= zl18(A$4*>inx!+85)u-x_@w)dRo!g5$HnE{CEv^Ca%Qe3?UYp`$3cEv)64UN>ygIV zkX{f@-|OBOBj^utoR_=$fr8@sH*Rkai<*{}k%dJlZ(_cGwHf?H6J~je=N}f4TkJ0# z@r-;g`SJdGE!O>geQ%nM8Peim)drAD@(uRFpkN)<5EI_1kX~Ld^ zLE>@BBx^0&J3EcYaP(RA)40>LEG)my&j-^@v&BoX~@3-PBh2H6`2`a z_J7N-(01GSnA;G+=xiTV@p~&tc{6)&7q&}xb?j-*%suH$UuN1-9>m6dCOi_%_MrMLTJcbVGixMnYM_mM#6X_61}BA8Tr%Hys%*syH`x; zNRfCjS#uOlkO4dw{>ig$D|-d~==g1^P3*fEMh95WM?pDL31wF03(cF~>`#PjjvuP^ zZOj74y5A{j<(P%m`H?W2N+(Z9mpn^R3oZ4t!Nk~!hWimoibsbbWuc}-z5zO#vH0vf6{K~Z#vhi)FT&FE$S-GM9^pXBe*J`PfjAum|fX2 zd1c9=Q+j1h1m}|Tv4V}All47z_}6MbLENw@F3?4Q8}xjNr87R?EZk@Y+;+g_JboF- zWg5JuMqaS*)XG6e;;-xAz}z@Pr##f@02V<&+4j);@4n+@ySI`d5FA?o8Y_}i*HBm|&Zy!1U6#e8wgYdkP!DdjTbkR4EE#UBn9|acoX3d+g(tYK~CSIa; z!2k^90V@PfASiG<$i?rz&9WP!0AI>YcKBB3Q={+SeTl^Y+A)n~3hmPHjq$>{x&Bze zW*7oJze@CzaKGwD`2zn^eVTdbf*bXJ+dB=>sx??tacCR6Djq19-SmaZ73a-IjoIC_ zplGb0RRW!!EkYFcC%*P0tGY7^iV*Qb^r^h{57@T*Zjl@wq0SwbD<3LAW>xZs1Ik$K zBoSPv6dc`y2@=}a!q;y3b|IkJ zQUshnG`~a5UWx!>W_Wn`Sxr)VI8|j^EMWO(E40$wD~)jv0YLz&mdg|8&a~IOh46@o z3A1|WZ#@8L8s|6{9OHZOc;3M4=t@x025_k6yL|a)yJiqU2#%XgSM5x;DGS!OudHF! zZ!jr5AHG&o+BTn+aaANxG#=*^Fs6*GoG(VA|f zBu-F}uS)&O+kk^D@Dzw*Z7IZJ=r}l|Wc7@j;1~l60gz_^UkffgzoQn5r3N@rvJS9u zFk>c1n`B>KgW&7c31kiqf=5O2+t;~|&Sz=)E(S=Ieo=g3B(7Ld{(QGvCauF0>D?z= zrvzL=Q-RVIf?!I}el5k}^h$@LzIXK1{o^kQWB^grkLsBJ);)Rav6+bp37n7@dHj}Y zM~HnXSVlu#Xs)UTZXcPU!ts1h_(Z8c#q8^6Amk7aeF0rhq90`Lrzz-wF4;t8-pMA# zAr@f+2m&I>wTPZXNxoP7ezx2m8_4@eg+(w9Z{t)^-Vy%` z5ml@Umy~iR?>-qGGbmXIM;SY;>NxR{7TXlPo>y>*kGOZDTtReeryUGM$p3|&ot6D9 z%mG_nE-mwfQCr=I?wwo1x8*1~A3r-l#>L(!mw(Dx1@P=%nLDAam~1K8J}JT!O< z#8U$VKNw_(=@$I5C5g28Di$vG3tCxPnvtzDh#e+m(~Hs{A<(K(WC_(zlH@vGo+zJIbMa-!}47^tp-{0?f0nd+H`wfnen$YNyCD2 zf?z>q#mfHITPPb~Vsi;Bd?H?<<}$Tf;BoLem2JA3U20nQy#(!9nMPwIdFbsr6yHEz z6fdw6;(k~d-~If&{`s{9yPYno$k(p4ADQTvr%Y(t%XD`+bzhSJ6JxL&Lp7&q4~M4Z zfN1Ugu%uRRreu}izF?U2w#sUSQTJ zXv?KUy3-JaXdcITlUSybueIkXS^8Z`Z7?(W?;pg|?EJsLek1SeyiA(!$$|O|h+g_$Q3B;PSk(y&3ww1rbKOt@+`q-^6$GSGVNmM+`S!WsKO9pu zZ$k7k8B)-i)iZYIR-6Lt-akZ-EVw=@rVqbLfYx@OX@7~wBa#zC3z?wc!(;?oPQa52 zBRl9!t}GZO)JDFaE%P1gT4uXpTCOI{nId&yR=%be&@bRug;eXrSZGZ`mv)au5^0TB zg4iiE)BmZbeOibRMNg!1*|s@Y#!MCM7*)QBXi*Rq_0=D;^eaVH$06YldBv~l&>0AZ z9(}1y?2CG|YWPlGePhq?B@qef>Yg}pACHnXimTl9e0ZoDnKazuNh*bONXWPJ%d@E- zZsqyc@I^(_lU052TA`_87$K?tbVCKEi2grC)4LhjCzh5~4uPvlSZhg+*<_g}u5N4C4H>-VVc|8nByQ7A>PUNio__eS1z-CTW?Z6`{o7 zQ<76)r02l~XYG?)p-UvSDX3~L*WDEd@tEJ+#1v5ct#%Hdwl^97IiXQ=*q|!&aV)k| z89mh&IsM<|0H%M#y6;zARnovJB+-PW?xBC?Z@aOWbHjb-zuzM+QX?LS>~m--LWDQs zl%iELc0;2XDjZqL_=$b!6OTWS&abaf4ulR86#ovPZc=Aa7(?3!@i0BzYMkkL;{CHR z<_an7H{psE+W2K~?!H(OoGro^IhB(ZM?jz!gaN@MHE`j)qEvR|6pEK%}%Y} z-OjdH1JAIxH%C`&`JR5(OH%m@@>N_SU;h@5^>w>sUG3vhKkxVjbSHb{E6i|cQaT;}}>{MP|Y#HBiDp8`Um(S9*NiR4_P~0F2 z8t`;Tx^jh!U~T>snB5!4=1syY?Ks`@Ev$34e3sZdeq9^t#FJ5XG)(DO5Nceps&%_E zi{!o#eFf>jO<$3tTw3!AO#lq!QRi>Fd70sX*6xiv-BHcl>O;C`g_2`SYl|l93M<^a z9;p#zAH7d-S12=qfbZF0uU{2P-r3s-{7?ZS$Zq^-76DD-Wa0t4uNZJlg1*qC@W`Uu zFxT@|pY*X>SDc(3RWcOzS}M&ehusH*>ept#2CJh|>;7TbjegduQqi?xxpU?4!*kZl zCHJdp3+z|JL5$}sS?9G5<@ICjHeyZJ`z0EPmuTm!ms@<#TfkrA926Z(j}v&$SfRO_ zuK5174qIXK?y(xcZc6p8=5F2uB|`h3*A ziH1RA#jtawt=lf(5^(Os|2GsuYDu=|%LJttMAxkHo65fvA7xnRQqWk$P2_RdLbsaw zLW6tSQgmb_!lGeXqqxVMy&t~xz`|SiWIYX{-SxhlKX^>ZJkAq(SNTv#@IDR7oCm$^ z<~=U)-62cM$Slk+?{+@s;BD7tJyG*r>+=a?ntNU2y%1%3TnyUBMbYcI(}=Cn+nSNa z*3`>Xl!WGzH`(pL0x1`GW;8T3APCeUxs|i@_xEcy+d=GMt5j%i07{4bKhvY;tOt%w zb|c^j^6Fv&;w&`mF&*| z)KN9RtJis8@!B=^0^NGE+ZAP>M{~W5w(^O#Cc-jZIKwdqT0`F45d-?C)Md+4Iq``D zhv2QIrw3hnlk)2FdcfZUCtvV8B!x+6;QN-uETw|%hpO!2m#s`9@T2iZoG4jHnV=ek z`lh}J3C-`mWK)kH$5!~x4f}>ipB`!TlitTNrpgIHXe&d17Rx|LL$}02S{Nw2HBtNq z{jn(6V&v9AfJ`i=W!vbE`^D<9ND~L|EHmO%*IYl&)Gj6B?hD;e8hgPX_;8wPRawlP zT+*-+*6L5F}( z>oZ_AJQ3a}e?Qk1hECS!vP?K7wecuHGK;FLsu%FzkB1<^S;QJ;=pr$La62TfQiSHO z?xURMWg$`(`~9vrSErk1&&txdMAFlUaVHcF4$yS6UTT9!8ow)%;r%rX{`w}=kf=v6 z?z4Auy;at0&lwVzl*eb~2{~Ff`z);+PXfuhP3o<`wPG=jm!nQ~+rH-=w4fWlA6zJF zAwj9aA}6GdKXP{`XX6etv|VX^m6d15A{YDPY`U=8C9+OE+7MNoC8euo)GBcut(szT zV+4hU8dfZqSzP?kY^cgDadNeH8Zx@<{RE#B|5gKYJq%T7xK@|ov z0ugac0s-=vD&KxR*Zyvz(#-P&bsF)oW%pudxYu^MC81r@LKB||%8y?|AqChL0OuWS zc(9V+LgtDc+_ICpV25)_xZw;ID5~n~ffcBcr)PTvBo=&-D8<6+YF{(y?uh&N{XHkx zG;?wiPBf(BvdRgxXS=wwa_r!WX+!I$;npq_(hC20bo0=5yBP+I5>8I6G_w5qX6T^3 zPTZWRMHdXaDG=m_^`G$j=R9~pgl_#QnwfzuHgI{FUtHYW9Zf4IWS!pW+hP!lrAPn7 z&cy|uTttvEJ>J~Wu{yg7%mO0yd4YflcCJ9se0}{)%e_>Qf^eRk#@?s3V{wk=?o!T& z=$eTAkF;fPjE#*oTb&}#T_lU9fXQSwPnOU1UFnv604gr-iP)pMImRbQZm`|=_xQLz z^BM1MKx8qpK=%|Ocn);1nR^~RY##6F+RomQk&zjw1F*iTElKn%4jAd7{$ulZLWG{O-MS)I?o&*(Y)4 zBk-bwNBOhB5$PjyIJgea#aA#R*#Z73y^sv7l91#KcpVwy=;4%cEyMR#I z{rt?!cb~^M^jax{Ai7d{c;tscgGuQ>-;%N!c2SWpyNrsLj%zwPz?_6wOr259d=yxa zs3q3-f5Q&~OL;zC^Q#_Fz{;sQZtO}fZPx`AEn`TlLT+l>vxP(+< z=5V5#%Uxq##i@i?7an&M9godL)sCSG@3JV)LIHmj3sX-U5<$w4I!``XA|d-(W$_(k zoAAg7NHdW_)PBHKxWyP8ftb}twH28KE8&S1)BR8%IWuS7WdWDbQDYV&}lv517 z6Z{rBQ(>iPuy}0NFi7K-|8j4YdigGwS)e%J$5)sSCDl$1U-rI!Y{vIwd5vQiEke}J z^%OHGlFASLn%l6=auagi-^||Epz_ArDRr>Vk=?Y5PiiK{cVzK#-K_3~E z<%g6voanyGQ_OVe6lVnl-iDQoaZ%{U5d-@cuqUvXs?xb;4U@bsi1A z0OOP70@s-NcG2y?due>o^TUi&l)m%$ zChlhaGXgNVvNI$uKGC|85Z!Tw42DYh1#dR6CjV~dXEga^9cKKM(}sio$zL2Wir_Mb z@C%$;m!b=j>C3(hj(UtFy}oa>4W@6CCcSkoygOb*eiCjn7gACdPQA-=<1`KDzbM$V zj&V|`lm2Pr0Oh%Rm+ocl2QoW%P(^`d4{PnaSp`)*i#Jk1)=EHZCUEp;kU}$+Q#KHj zESqT_yt?Qmm1I3^@rn>wT#>J^Y)?J|3&=*?7_6c469{q6>ck)9nU;&Yecxaru^OoQ zFKg(3GEIFKaTUc72r^8z+NTacuuMyZ29gs0sXQLnhALuzyj)R8%=z|} z_4f95xXc$kg^Eaw zr(Eu^bXbZ1_{jfTPRB`<-yg|}cnht2Zg>Kcp^yGkVH{51?#0(e#Oe_pdcVxhqEL4C zg{rH1C~i1Nl~dQm;d@FQ6Du90-YZihPD>t9&@R5A3y})9gCsFvO1fUJ61ARKjb@iH zV3~C2BKvHpc@lKHxU^(W^J9v6=j<#Rcou;S(XI1gp;gj}b8p}>{WZ1@7@L5q{p!jQxXPjT0B=**O#9=-dRD62*>Vlb zm4ni;auTqsh8#4mRdMIPc(T%9-E39+*ji$Tv%CKgCH&u6d{mY`nn{R zfh-A%ec-VF`g9A)W!D?o+t;FoeL(75J7vO*Z~=OoPoPVjJd)6aICFJ(X{77}-7pdb z2{?HoV1}h=hMo4se=5gxa0;uaZftB^A(NwV>u4WrnZs0mbt*1G?N;-57FA*EIegme z-^h4RftiMb>8o{C)7?WEep3Ba|hEaBO zUmDz{a_Zh>gUkq-Qt0wBBM8>ST_>}$FM4m0 z6u0!wYb75$G7(8n!Aydnmt*qTQG;Hd!ci$lFm6yT6*E4ccDL6y{No&ncca2-SMcqw zJ46AoE3eSeF09%d$%<8@Wrd5Q(<-7^#1*7Z_P|HZ5K?&%0=j5*%!QhY;KbtI1Y%l$ z=_-n$s-|~0!j%#&9Z}qeXOVZUDN@6LnfDc6P`YF|>X4rsBo z{4l%`YmphIP}`XemA3^=rM1-MKaGw2Gzf?!`l}fuNU>TO`SbtP9jMek0eQ?M_Av^E zOp=KRzcG12#boZe3px`-Iv!bDCf<5aK9Rp{?tAAjt@OF`w`;}jV#JuFrYoT8eH6iT zPTsTURD)cMOT$n;w8sE`hVfJ6SQ|!v*7nc4|8n3;;O@~poUXUhdVj7SL2yr8Yrabx z*^ZCF_6_vRaiLdr4GTt{>Hf!(wB5 zG@{NTiqijK?vSVx-?j{%D+x9Y5%};sq>R}v&f5-olG+K+(4@>lgajkd3aEvkty@OK zLzbrsJTLb(vFoS)s6&{85yL^;IPa#Pij*HG&qGwFGBW-K=@d5nYpUBxUmHz44mR>fA?y)9Sxj41#(Repijx z@*xSWczyTme=I4%9A8z#YosuJ&|K(zNZC}} z5OSN1G+=}|#S@4$;Rp#*`}gI#w=S?`6=1sM57OBsQi=(bvD#3eKMYZ{fgoh)_c6gC zl9Cok;bySV!f5g5!Sk@Ou0axZVb*KU(iYq3)*ZjHG9K3?EyPmYMwaQ(;MLU9*=_|l z!+TXiUDa|GLcm6P`c`~T7&?*pSdBtiG`8S)Eh#HSD>72$pOl_2sD;zP0z~&D0yBaF zgo5Em(*px~=0WyI1j?Za|Nl4`EAWg6C64XWg4r2hbq`*)-<4@*EKa#cyjzUcIKTXB zB)j+JnCL=pOfd3Kj3D$G19?s`QUq!QQ(Tmm`NMLtuVE?f46A?$MPZF##s?*{4vvR3 z&9pWgHFGOG?x+$Z!k-7k7~NuhR~X;8a(0ZUN`8rLP7?2vd5Hg}p{cLdQU$?H!)N&=) zx38?%l=Xrv*gZI)0QLwdLK78G1N-T!=lFci03Uz>QA>!-NfwC_tYft--jczGQ@khlkgAZajQ$vEg|-Yl1hsrJ?g@v)!|0fn@# zt@yyF)%kgo75JkTVRJwL0gq+))eARDxC zZsCtVQvdnkt)^Z;P%!HG13sHO@zkV%4nniqnvNq4Y{ViLmD8@!}Mr9HuBN;<9gN zeGuTzzo!e8La&Y7VRh3+lJ6o<5*Ic$z>oPVHf8_$^kuj&8<+9zZhH~v2#^cem_l>c z!N41c;h!LN>Q8S{|3nHCff7$iX=QHPc_Fi?q{KdS^()HQ-lY>`y9HbAvT1YKBiywj zIMbA#C=2NO(rfwd)oToJNiVqhl3eX4kY28W|Ab(-oCpMIR~fg=`Tyk)Sv%v<>(T&b z$}N!c_cNvO?1TpH07P8I?E!BMhbYxD-u>MhK^VKpBogdg5DHPc=BQBB%)_)TZP=GK0p6e=X z;Vw!!RNR+q`%W<-RvD)zkGFja&IvMVy-g3Fh}ZMtRF1c=a$HU;U^3e-%!Xlzylk$R znRFH>eAL!V8bc~YJnRf{k(jvfy;=7uym!jH$bPf#07F4a%owW5hz9WIs=asZvkI)7 zBQGPK!zB^Q%RfV^PK_x4U!zc247pA}`6t4yY{y*D(I-SAbS!=RpoqhU?e=NnG`3%% zg=IC=|OA!(qlIV-yu!u5A2HI`e_-LTK}#SS~sh+7&F_1gn6H4>B$l zjksFjl|Q+{?a%GQ-L3pBT2fke1~PQxU!t*`T@*ec=7$mx4}Mr+<|epM_SS$JA?BAZ z{c7FOhtD({*vcf`T*@#QQV=k7h}yJ)`pucdST)M9ZRVPt@sSA1dX}~DI>S!Q-#cR# zETntAf4LMJ`h?htC#<)*4AQ0+`b@z_T*BPqj?IYjiEu_aA?*<6AL%CK%QJ-zY{bDE zqE1|DByW)14?05rCi-mXaAIKC77ntlKz6*NR^#1I{^l>Kv2-P>Jy|&f+Kmkj$pYb?7=yHjRV$K105LRV%>o;@>}%0!1v0L}C~a@{~)i zzHsTlgpfMj9yvkT-*e zXMcCGGke0$9I*xm9ypeYXgEcd$uPg+f)S)rcc3BQ;cc_{h(x{6C~}8yHe|`@BnkOY&;BpOdzTJg4<=>+~#lRNXAiqzlkNJXl(vOW?K&bsMBViB>j32=j?0cJYL z2gyd3baL_?_wXw>>@Z1}D&5IoK6L1{j}rCE-KHb-=}sB zS9Zqss&yTUy_HqC1O}z*pTp+=6tvc4H+vI1`o_T{k5(ghEsT*jC zKoH2&j7a)Y4k0eeIOoR{L5?g*AV*4~eMA_ap9sH4J&P7mpP?d36D=;E!ZF11yK+Df zp9S`hV^-N=RmO4lUTo#G&W8=r48!sz;~uM+6gX*ZZX&HXblbovGs>+LH2d$Uh!P(w zdP{xPlcr&9LZ`)MOFrz-=Dlp)YAhA*GsNR_YnXQ5!BhFEcuP|ykjcIVAErkBDxfQF+p+XcC z(>sPwun5Pis^nQpO8S1qufq?~-|R3_mjP+Op=;UCmSza>R5Sr}vbdBgcH8h2N2v^C z9@Wp(4GMX((0Mimdc0J!gt;SFAE&6r&Q;s4*{!QjNSuH6DPNyl=0$TnUVWPQ;>X<` zv^XlU1)TRw3iquv;l?&>Mx?sP`8IT2{3g+Ny?leQ84;m#&N>KgVx3&6(Wv;Kx_=bM zOq-krxAhFiiu-jjL}3>=xiDK52Nz=fon0GIZWb|eD#n%9d2SD$W0nF2$6)Z>O*75o z>%MG9YiZ)}`4lVOV%7aM32$No5q#e);r?nL&F^?D?X1!8bxY(AUaQ^fp8w5{YFOe8+&V;sfyr+a}?QI!o_8zAVbOOP%B*&ZP z-`W|AO+SDBJfUvCGlY7L08nEC`BtN`E`OPZNl7D{o*T24=rB2>O+pJ7W zc7)E=DbTRrJh{uw!{*oEAdI|t-`08a;NLV1*UZKeH3|~&0jQcU4eqwv*@BrbV+y{% z$+0hZu@&Z$m1<|0_?X4Z8%v1>9d?2nJ55V=CK)TM=uU1)3#1rsed z+utoPvx-4l?;NDo1Qa8`!d;C=E;^!u!Uq`m*pPD|jt%`~~jN2_#`rh<^-{_`Jaeo_jC8ij% zPp$p?l2f%u4o2o>&2ZPbrQ2-cv7Ect+X%CJ*t2XQAe8U};l3b7g^i%0fB_OAvi`>? zl`mN?g2Zpbl%y0YbO^o7&D!3@{9wrB9=elolKGO}d2>j2bSei0bELV4 z4W6v+?D_^r>Q+%BND^z=jzDj!VSsHf#o}z-YC8Q<*U{;BAGcw*D3|R~=PvWkA-E9u zJF&Q^UTRg}P_47Jx@uLP9+u0F)`_ZFCg7kfhjP4@B$gazaG6n-Pe*B+gxY~7wrStL z4)Jgp_VOjW-l~zJDLl6XaZgfV{vS0?>1STP?cKG|d*<47LlB zYy9$>$#3Sb-88z**fm#gL_q&p2DQda;9Q_>igb}BGJi1|M5|?XIl~7+_UUC`1#R?N zS#M~mGth^C#G$J8_LY-iUHUheHyzPf%g0VJ@(mwecq&oR%G!He{MVo!4$sgPQ_=d5 zt)L&g&z*;>wKtMKpW^h9hCfjK41wf2J=@E^&|Y0ls%7fLqCGkNee)6SjWcIO_bIK_ zR?Q|$uw{2A&8fSKCwo*uyd-Iy`>qDxC(XKCoyfh?lEdX{`=YtBvwLB7?{9w6wp*dm>)9rOvWhi(eK6!jjiK?pST7I= zw)96GBn?U|iUF*mKFXDeNELS62t;<6wf-zAX{r2Zr=$c;Fu$+@0mRm1EH;MR(g;l{|ntU8B(o1b?X?J=EB^{W)@G7#5opKF75y5XnOni!CE9taPx; zw@Y_eXK890Tt~$X;IF&M-__n(vWqwWyQSG{W&M>W<#I1h=Hh%QOE-QgDpUZ zoG#xfU)PkT&j$U?TF(BJ%gPgTW+3LzMv{IBAL-42u6L6~Ca7ETVR0}O z(g;TkI~IY-j<@bA-oY?Me~X}s52ofra{lOt8ib#ig;uNK2>w4+!tSy-sDHJM1$MXwxKkR zQuw+{q4|Peg^!Nhx7`SOW`xMDcy!3Zj1wJuDq(8LP==k%-^Qr zHuqz$c}hAasldmhsVLbi%5;m+FnKoON~Q>8IpWv?!&DQu(RPc!nJVm!UY5{zm!TF4 zSY^!6bJ30B=8Dumhg0M3e^fU~rRGb{APUd993do-T_M6SEV5h?qnW98`xeW6$#DofGyS|p<*%@_v zC#SxxD84bEwgWoo>guY&3pm%lPUqAeHL?2vxFwfpC;^$7nF+LU>C8PK2ZS^HM=8vK zK(x`hPL$Sq$pLL*8y(Zy-isqz%DB_L`kTvDw3oKBfz zKw#X%9$5HeXJl`}1jPGV;?T1%y#>Wf4RtFS16HOEiV#=euzsUvn0V}Ks<1A7ll7$Y zo#v+p?zB-=4Gr^t&lGeWQoYkXrnVb&{Y6Xo{@)i(f#X?{q?S{^g)X?$hkfQD)F;^x z1PS2j*kJ<;SF8)=XnY5zV%;2gKZ6B zXJ*EZ!}kzaWDGhRlXTg6VJ3-wm%7GZH7w&juFOc2J_hU!|Bwf__rIvHzI+MY6?SoB z6(CX5UkG`_{mw5}xLWqzJ^G`$P&9MK4=X*P?RIM#cVD-w(a7w7qcvq2lKugr`=TBT z`YsbOE-nvFttL&NO*=X|+Kca@TE@sJ1tD;`OF!tSmE`Z5c>G{I zB4#wg=OR9Vjr#mT#CXjvM<<_be0IcCMj_^j=iwiNM1`$A>!QXuxGP9X`jgS4fc;Mp zwqwvTI?kDZV_MgONVDC=7q8nz@1ETQrILxHX68(J(ZMFpo!|c;x5k2rrLd0L{x`JL z3wWT|W|vZDf!LZhkm})}U}D&6a!<=YxyT>`c_{Mogh`@wxdVlv#)!sMAtDjbC-8}UcsSh|7N&E~#*34d4`K{=&O`!;6!@TPP zxm)q1A1YG2m0_acR)nf3(0%a}=y+MN?Ls~Kq+}N#*?BhSJ$>%_!mNX)zKXA<}p^!l{H_X^sdxu?E}WX&a}029Q^<$R1)#)`mtaU$WTa< zD!^03gL|T2>CX4y8S_tTwNv&R?D$82`&%`ylZ@$JJ;~FCcITQH?S{ofc{>}MKhWq- zP5_NqC^MB6n~ELSw4_8mmm_kE)#zB;H&oZK9WZ39Q2y0G zzNlZ&ifsI7t9AoyF-m8;8Bj#~3~QJ@WPFMvw{ANQi4E0q>#eZvA{Z<)$SgGQ<6bGF z@9CDY{v2IT5wVCmO!~ zfIf2Lvga8?fALsrb`2>V%<#j3^Q4j$Y@&i`@2TgKEaKP#o2R9{t#sfe z?Xtc=B-~k~CpTUby+C zJC7OvqwstHgwfx$NU@D2m&BlJlRuw6!yP^0&N%dKxhHYBoV&KD!3rRf;4Dw(!)?f| z5`AH=I(z3mc5;{F{XSl4f>N#rf_ynYj@Wf-iRb3Q6QsLyn6G9FXGoIXq|-wv6)_an z3&MN>f#d&_lr%dqq7BvDkpZMfBo^C%b$R8|)fr4~#;H{_Wm<~#dGy`z#|AFx23MO4 zHc*!cO#tP)XCoTyp5*Q;@p?mK7JjT*&i5H?yYyM zHSb%ShJDdEvvw64bBf_pri-MUnxha{1;nD1;Pa>`wZ7*U=*JZnlj2Oc3DUw!v+G(B zwJiLgTcWEisQk00x|P<@nLxI~W}ldT=J0HrIm#zP(~r($ZvU^$LG*Js+Z3}mn!M^Q zDPuQ{B5nlEcY779+S4`*E&j(`c2O)YL|hfEp4W0_&W%k=GptQr(^}Kr^Ib@SV{PV{ z6mdj?QO<1KF^f59xo$DnNeXT9DfwGJKn1HRl=up4FOOMovYO=zo~!;NZzR?6soU&3 zLn**9#l6gG-|5WuZVEX4Wjy{IOSK8hf~wE=-7T4@0b)_uVTjju1u$&`!v8MccAFcS zNfPXBuV8R6Ih3R%BE#;El=?P_lPkgS1amRS(FL-M|G~3G!r>?VBj=0C(l_H`jkX;r zARf?oB4B2j-0JT-X?_PG8n02jU8TBVGpQ$3D;$d(uQN6P(W=Tt;azm6V$TyVQDR0n z!tt#TE@2;73KhD1KgYF8WePfsDbVRFX+QHX|r@Y2fxEZ7=^XER!(Jg52)uZBL$K5BlxCNSB_y7Ax%5?p+ zHfRd_Df_5t$MGzq#@VmjzN$-6JcEe5v?P}t7SiwS7za>PWw_5j0Ln_U-7TS{M06@1 zaEK9DY~UAGjl%#i1p7%8B>$10eE@|uHZD@a#?)8e=n>-D{W`s3iQ`@L)UtGW@^85+ zif#_yt7yDa^o$m{-$zy3OG|6cxo#1@z5*0Hb+e$zs-XsSD6j@zSXkItFwWWmMt_zN z1mH5J+4yMlbnghJtYe6?jaDn0U?Kxe0JaZ6GWgW7Q?u6-ClFX=fU!ErwgoZS=1^XC zc9ZIk?=7W{Z*P!wEJ^#rK)fn(*F=a@fn$ER?6Y=@ktJQjGX~}YA zX{J;~>O0J9ManDF9l?wW-aSii5Ssj+Xy6wF9 zi*%$jE9k@`APkGoX4k-fS>1T*X&@7`qpiGuK2(!CLLu`vX{52RW|!$^K#k0L=(^wy zB(E{txd3*^LWzd2MiM4Ucj6Qm+}4A)hOP59&(w3O?Ki|?0~pU@OFkB1=kN1lL|+8E`G9|w3klQjZz?9 zfpdrf3#WGWls2>nX^&^adz6j_H_T+x*Yx?+^qrp$mcK`EbX+y}+grDRTdfm;_lsfy z_9q>rl3k(14w(VrI=Vvl9lluKwdO4QSD$vNI(aK}tZbi&fAlP3mZJs0Xsj(29=zr2 zq}~e_;&w^x3-A9n$=sKGNZ{#xvizN9JI22nX0LykCcMXybRJ)8MCJaTU)YkTTjozm zpJ_7K~=zZi1hAxiq1|q`%c!UN5&6KI?8I>q2$U7QV&TB(Eo&36|ko6}JX`XUyR z_K*LumyRRg6jMq>2@mS)iyTuHqv2erXGiY~t!n+Gf%a>Noe#{#inzMYJs24(Tt^o* z@Zr}@8rwm=YX!tvo4n|m6mHSYkEpX;NdBd0g@fJ9RSJbVWb~Q&09dk^lZY&&8gPRy zaBKgF$gv5WCv!O%`2B$lJ1KNHpLRzF`*HksD9$>HBN56$RE{$@5n_l$bF4CY+kE-( z#GW#8UGVxJ;e z(8c^*BU3!7*j8|pQ}#zy=+cVDi0GE-VQnlnLKsM}hAs%q40|nlC11f_HlETK{7K za(qZ@N=Tf`%P0y=`vhV0RZLKjAiflnn1BB@@i*Akc!W9Q&r!J?PLk&Lv}v;7HbH_A zq3}jT^pIH!-jb9%1_AS-T+$q<`d%z3b%rF84uviMw|X(!+2y2+h}Ci?rRTwPf`~I75uzer!;j4(w=~l4-&1OB8eRo*&7IU$eBPGCccbH7Q-6isx6aYa zS=173ZESvd@LC@+*De5=OSE&1FX;tqHnU6HEoBhQZKET*Efp&81ylK>A z|LxtxL>hw`g`!vxGdLE)o2*z*WdsPXv(I*bSjMMXs*a&lFLhMYV;j+mq9FC1|7 zmZB%ue*e~vPgR*0N}iiMFzGUGi`}ZRomwK@{)V{HxK>T0A7<^FOV-!$z*DxiIjX_W z@clZOAV=Izx*glhYtk?NLH8@LEojJCIVn}0SV_>@h*#9}`1HjGeZFS1*TBU0d68etymo;AKY$71dzeIEH3r)**u zk~RaETi~XwlnRuWJR;Qze~6~6nZ)1zV`Yx7PYr*RyQ7V(ryW=(=CZi#z~phS#$(CaTb%01 zC=wdVb`8_E4!_p$*eEr}|0%=s>Ec!}_fTHyBb)?R>(s9yCEUo&e-jBrJGnhf`3*xT zWb|iYBl^*CD=k7PMyPFHz9NkMrj?G_Xwbt{C z22g79{lQ{Pj3$TFJhXU>yR4cEMT@Q#q;oC-n5^ zjhF%EBiUQ-=rBGx3Z0uk{xVUQ+2+8Xz4bSgyS|_=Tu;dOj+U3o<7W?+P!g&x>ysaU zmxO9-k1O49=bq3W_(jSEhvDSF*-@`ItQ4&=;@J?hE%WWH5qX8jP2xXQCzIPr;=U)X zBTx&8LcnYDEM*C=G5Ie+&qn=fH_a95e<0z)Tu25Cx$YLS-Q z4BuJ4dMY~cYu)tUGz&k|b($^R=8tuMG=Aq!QlR>5aad_#6Z=z#!f{YeN##oYkTH0@ zjzz~S8cZAPrr*slNo7W$o9xf*GIJ~Ur;or?f2H-NR43fu0dF%#jnp&X9825P%`A#1 zgDjW8Ui1f?Dz%;x1pzgo8vOj*4m`!RnV$h>I~8h76^qDB6mOK$C zHAN6XlUFrY)7Us~(gqJR$vv-yTUlNXfQ`@q*zt`G*4f!vduc-tAH`Yi&a3?OKWDNk zCasSh=@AzztU)K2+|FN$bO#u(R+Z*t)@~2v8wb57_(NDH{EuE8l#sG| zMkE5s=IrDZ5PDKfGxfne6s0YIj97kb*~No1sG>mzp0Ggo&v^FsJP;PYsj;!&mMfn@ z2F!SwrZ~qTbKEQ*pM*mQEq}&QfZf>~F*l*}Sd)8f$1t2lRTI3+)9vo<)5)_}rq|ux z$9qn8&Q`2?o5m$8q>b#YS1$7{tFt>>PrbSiuY?W)@MhMoRjIYuap6RGG@9TyKBmWI z0oDT8y_?@>1VWlh=qkS6KQFpZQx8T$mQRvWOpBG>E2nGGng8nPNC1elKU7 z+sxgmM~Z~;lQTE3xus+*mRde@#TQQ~Q`ypfA-eXMY8uGR>g7DlqXMBYyrFM1}t zB*e<8Gr2!a24tI*OC}>9cPPl;RtJkeOa{f}+oPy)HaViy@Vb>gRC9I`&80)ac9$5( zB8M$TWpq6;Y%<1`EFX4AEo+UImp4gTdw(`WStbsM8CVIYnCihY$s7vl8H)ylFuRIr zU+p4GiamQoxhQr#@#%`@I$*gg1Z`dzm@J&me1?o0woSuj>hv0d&MRC)| zR*6ibR<>Jpx$qCCvYQ<_(|~&K73mx_|8tfi&o;|>N_*j_SSc!NulXDmA0j3z$!mwZ zOXw~UehaL((89E|suB$`to4-p3TO5wt~%084lM4`Oz*woF3)&I3!KJ^lKw5g2JJ_G zt$$Tb!pP>B9iuExV*rywoN92^on_2=+QsPw89?!T(onZyPmvp{y}A-Hy! zkx;0BIODHXo-fbJBc7Rr4jYep$+!r+uDh!E?@c*jbBrt>RHIy#Le=YUy$ONLP9g z90)7okOrK3wI+S|dal&*M`ae4q^f(Qx!qa!O| zSC1DVvAR^fcJdxNcg3!vqN1jzrpuzT4PK>lYrf;j$$I&haOrIBpH}BxfJz8w2?G3^MQ>|nyqk|V zB=hH75FhO~-xzLH_8FyGKDu{pjvTVnl zwQ=IH%lq)}lOW9MCDs#((o&d4Pk#vTiqq9CQY$?JWH9hj1TnCmYq213*{(sg%Fc(5 zJna)EPwjw#s&lqJjf3*{dQVZR-SXXe6RaeCQo7Nl>h5K-iPooQt?0}fMNS}DNGr%GKe7LPd; zM5F8)V@6)pr$iSP!O^yX5!WHws9n`qCrnUq0r^U0oJFGI7>jFO<2xqEGf+`L`UM$3 z7*-lhF~me>MX!~St2pU)|JKHVgQr){F=N!fgZlNSpHTTYV#Z=TsbpHhmmYPb8oR$u zCd{Srw+K^-ha~XGED%&T#?2tH^@-STu(@E zbsAAVvxasnC@d6YfhHqI?e@shVx)*8m;0#p%i`iyrj}QtT9b5#UD)&Eskfd60;3EJ zHuhVjDXnu!gA!qEdg*Y}TjGqcS5!UmY%6baFqA|{sx-ps=#c(N4M==v`mQkbZDw)U z&4?&@fYz0S#vdymK1JUsXbLMQP4XRPLUXJ`CS%xg)C@FMAUl@65FJfHj)DSRL?1>1 z^dvJy3`^h$tyoYmS%P1-7E=P%r&K6z`kP{vvnQ?%xv~s!{}`zMZ!rb|0Rgb7fUV)$ zNo{j;=-i)S0bXx;glI;v?aq(`7JIoMQkBl~EzPogNgLh4Y&i44Ja7FPqut{5&-9)} z&xP2i9sA}!Q|835^Omp5{lPOy&v}0R#&n0WI>W;jAn#DYP{i2PH3jVQFyM$MB65Mi zsdY33V)C8Dx@ej-luWnhXdz{6b83*0S7EN&z93%bZV@_0u6fDVNz3A7u z@cHE*_$Q>>@6o2rbla=3Mj1s3=Tj(m}1g*n*@W?{}BA0DOP?N5q@tO zwdDdvHs}K*y7%ZXI+Rjf^%nD7PWw2TiPcR_QiT1PgNJwVaW|Ps1kOT=zzUU}0N8F# zep3Js3hLO$svk}+wr4n~r5&cKrR89pblf2T17*S)(>vOBoRa$fFw}b4^FcGxb=F0J_3p@qt9cnwo4KGedX z&D;>nFx4e>cZ%SZ@F}18C`NZgc4yJ8ud=kO9%ecIvGKtAxpS~kocha4Iu8)0+$|f1 zVcX4N>sWAoHaanF@jUK1&oGr4zrXh)_SJQ#&#~OzauU@_jMqo1ri_FUA!YvKW7H>` zQY@npQjfbyjzQ}i9dG>F5Kb#_LBRmaAMNhqBDs~2R7p6qD0~Q3sQ{_aDO4oS{P!o5 zNKJhjvETXWe#!Ratz*xL&y@_6rV9&S*VEo+ZI?aKmG8B+vbGIbKTyRPiQw<%UnUnb zVoWA?!aGU~OTP1?8Stky<0DZIqWMPxNoK`CrRJ9v+*lhKcV+X;xVj=(D|yB*3S&cs zz#htVg0*qT5!>2@HDCLRB_uXbC@3v;<}<9wqb;ejGV$ zOkP5URE>m&NLA!)2h{%+L}#^H=O@+-%V;Rlmmnkk zzA6FX;aHa`@l-@HU(DLWLDY+Ks&HuBPnyJo{9H&zx((KXgJbm6H7uTTE-n z4b3jan9sr8ub%syy1)=8=J$Nv_uQ*?uPQP4Mm!&5PKo|?&KQP0qLNYxUIBJj?jA%< zLMW%?eGcjn!3={lu2xu0g3^~rQWTQ0#3o+%VC$w4io;rEYu0e|fmt}^@#IvbfH%TH zQJ0mMXcyOQgXdDg3B&jA-!-(f&IM|ZA^qc<-z`>LPp`T1oQb0|o)25YZ4_~U z&7dALkSX3Zq$KshM-CXRj(xKCS{sv}bggcFPaVO_6n7v10X|Z$g^9`^>4&k(IYv#U z?}zCMXhQt}z6gBSL&?z4(ZR4>!$MP2^Gqlk6654^0OS?N4$z|}alq_wfvqdOzm&Ie z)6=${u^=AUx!7_Uu@e9{t~Mh(U=__E6H9SsKlcH_4zdF}{81aA4oG6sg{On+_e~g! zJAb-AxvuF4Mzk+;e7ILzF zjQebTw+Cjw5vx9^-5$B{HPr_IE?Ep5w1fC6cpE3U4va;f2)`^r5kqC#_`8~1cy#FW z-2Z5igOKdl2|2XO^I}Z2jWu4nL+7B)AVm83_E$~=X9z&+c(Ek$%7Tbv9|Lc=n@zjN z?g(;-eb0wwJAQy5XgwdI@3>64-AsGG#QE_fpmB8+5dIyTylitVb}|eXEOMpwm=|2( z-$oY6kIy%A3vk)8FBS>Dwp6}exxKgaT6TU~KW?}4DWmVQAJ4r#;)ZWmj<$WpjyB=6 z$qEk%&1(3CJ=Mg zRIm-y?Luix;aCs0M@LW*E2z$9do)J~mEhQ(MSr*a-G6_oIu^MC{aa^8Q^iu(jQ->; zOIoxhw36gSE8zu<8;BK8-weHCTs?m85dU27(!9k!f;gnm3cyVhrV?*=KqI+l_GTI0ycL>+GN%Gb#Ow3Dd@wx#1g z1$Ulyy3+;RLm8bSc1NB+Q7Ka)7}nMN)04K$wkqBKCmS)4j5Rcby+~rp7T%N+$}FkB zqrz)4^gc1~JOpKM_P^2%^FeQ{#o6l+T7jw)F)T5Gu>6ZpD=2wSOftN0;t)jZ zX2guYNL}V4ItCEFD(gGwF%~ICu}>=FE*p)#@<g;J$sn zsYCraxuXy5!C9#1{G8QvEPcHz5Ct5PU9+7OxY!8a&GKHY zwd%O(WpeZ3kiu#QUnt?cVrsjH?Z`y?TQlbt{ijW&w`UxZZkp-Z#}?ZG?C*giYqSz8 zL4=2UIp~1FEDt#AM)6-Io4T~{B^w^`D)d47qP2pf98hphS~tFU2SG;IbS_7aY;0`C zVNZP!Li|Yn0-hfgSh<3wZ+^VT{nFYFAedI09yVJzU#~d3ci!qgZR@(6{zl+m@-{OI zsRU<0-^!ajZqG5H25@P(CXQ;4Tkd#Azm7uxl(SwQ{N3`j`-c+|1`x8fEOhHYE!oQ1 z0`aPtH7CaVE{<4XtN+x-70Iu>jEfH9;MT8n3eVKS)lJt-*Mo(^<6mEe`}m*^pk}Na z5Bk}u-@os#z9x3gTmap7zt+L_Q7r?+YabHGRblnzegw7-qE}!z)Lgw-Uun2E4x5iI z_`s|r4TyERM9_m@C&Lbw#1*3pihMH^X-3&ve;9s+)TNZgP3*hyyj@ zmEMmB;QtWl&zah9a^I_iUYt!I?{3raabNWMx|i{JQq%zRW2uMCPOE)+9Ugs^Bs;X) zw;9=wMJ4GBF>0`}N^~bF_dl{C#*+KlZuiJT$DW)aA4HpYxZw0vJufj zmRKSNL(3!yIq}L_P|EORj7W7op-@(@x+GzYG0a7*sd30e#1fa|ztFKXg_`Im~39TVSk?1NJ2Ogi6c)UYq`+z{Ef&b4J3&-ICOdO z@BtD^WTs`Wjb}!7IpN+_x%e>|V20hetV1Ph`XZTBWN&@7mDUobrSC=LH?tWt1W|~?Oh*@nBi0Ecz$*u_Qv*xw2se#xL>aZnL2(JpEjTg?IxI5fPg+ug z$?Vd!ez`mnBok*N`*cDmQnawrw5CEu7pIj~_KE&3Zx3;E#X?iqtJ!PGVo$MU%%t8; zs98DYRI}=7<$nqB>OOXf;`v-SO`5lp9n19*S^}@I9$JB=E+_R``W===2rj8>bdIs6 zZ%>zk#_QVp9|5CH*&c`SaS#pI+P)R>&aQ7lseH2b3nETiXF9|yoFZK~iTho_Pe8Ak(-}+b3 zYq%I|GABPq(SUH~njsd|S6MzKDkK6-hEEysd6C}7zfjNlf;aJGq>IT}Yx_L|ce|m} z@9*z{#MT9482a7Gs|R8xL_xH>)xmcQy}y6^CLyRv10%myhMlwebGxc*f42c*!OUAL z5N=N5c)%|toq!$~e7>)VJ0ZK=<9ygJ$HV+G^VQ3QVU|xV$GonYKp(>I!2MYny`uRc zw8i>FRnPk&b+y8_^Ju)^J7Cl*Pc&6&+3-Dc30E5Ozd{QJ?y}&l2z10?en5N(l(nBILN~dtu=?!?*-~U5 zP9Vfn{=Yll7r_n_-W-f|v-lE0B^J{5;i1!U3ps;RNI+W!8kyo*^K?GfDSvLWRJXx> zU~z&Yo*8o}R74>Kq&W!*xOa~Nz<_R}2g!P+*$Hk$dV0p6|G1t(27I4dEx@bY zs}c?1lcId`A}4vg<(n2(S9f|su%DLG=Ud#zGyGf7ceCix(k<(?0LvPviyk~rC`MM; zI(;XsQIY*R-%fGuxpRK(wR_OshX-5igoFfgA=fsYYYI-ISO2dCP`b3%hQ#h4yYBXd zaYcHjH6P@~8`#*K1b0-t>;6(55~tui|2yJ081;fYc>CP}>hZzh=I-(!o!@=#ewZ`u zb7<~qAQc!ZpKnQlh9(N?>3AXIr13uUfF2}iwbH=3Ki9u+tN%nqy_|KHm%Exhpl6(X zSw4Sn$jaIO7Z4Nw@E<%Ak}II6OEp=uC?%{Jwi}%rr}} zg1CEq;6vQ6_Ov3leN9%?<@IlVG3jk(*nIE7!vO;7b@q(N*;`Ub zc?eXlmrQ@*NUBeK!CV=lg2{FBQP&X!{=vGUy-Ot$Z}w{P5~rAf3L#^(IUn`+{$i~R zISU-%Dyu0WGB+3q!AX;pQ7}S5|+lC zG#Bw1=Wj$OMSl=jp`a#y!LJ)=d(NoC&|q`_hM)tA+(j8g!6cf}-CMt-mjAL+86})a z-%ja6AIt17gMu?3x#BlgAYVOL`+f>xN9Hg@#N#&H&=k%V-5~Sz?3KQTqqZ=O{wP!! z$~P#LM@vSBWYW7gnhJx>VhxYlFN%S0rJ1Knm24L*MHvt}WnNa7uNM6VI~X+}^cSEs ziE%{=%gDkF1yH#93;jrVZe&obx!4R!2vSlrXa2yS%b=l+o28A~^=AlH15b#YCgxj- z-@P9EgO|vW4FwJ^Ik#B@=nAI$d>$v!>@@P&Us25@WJH$3ck&U!;zBgFLRdqEe!%gR zsBD!{ptDM=<|dfX6~YNilEB7CFNi46r=~|!H&MF;xXXEGoC#;CUp;5;O?_Ch#Hv6% z?7@dw^hbXf^z6vQrk z;GPqd(_5}%V6%hHcM8>qcM`IEaLLyRWY5RYm3-s3eVpyS7=9hMX&ulYPJ$Yi|DT(! ztxtR`0HVgv&d!p{{sjT{>Gs~=p>vbhY7aO9wn%c{i0*K>a`-RcZqM0~(^c~o; z7>-~z-0{UZf}<7?B73*~!3G@2L<(zz#-gfi1rHKoiV?TaEotETbOc?MLX7ZXVrCk z@w$O0!He=0_?mWM_9Ck@Z2fV3!r$M40R}_FT+X|f2=HE`MNdKB>#j%;TW$QOp`$i? z)()+^m~}@_y%Jc*=8;Klczx?@UoEzD7WW`A5)?m}CbwPZ=z1gMKwt_=giT`$aLg24 zad7Y>@^$QzP5W(3zEx)2+NCVIzeo5JEj-fE{!mjX=}_$kU6rNxvvy{cMkgDiuo@<8J%7e~mA$=z@>&7RU_16bFpJ z-e>o3R$qSr*F(89k&+Ls@BePosrZoN7Rp_9eKvR(0S`V3{2NrG$2nVdS1VAv$DEul z%@zlBM_*qRS%{X`S5AG=(Ydl`7*i%6chLO`JeqgO4a4<$GHRNerNNRGyH4;*nrr^~ z3uQ@KXW0iQuz&p0>JsxGA!YV*vLLBmQQG(CpX19$9pEcsJI;T73I>ZYBgBcfWvu(t zCUVa|(5TU|M(-{iSh4F7VX}))L$S=B;p9G6@S4KCm}}^DN|H6V1gmih<>B}4F(fq35yo4sVr7TDPQ%s zq853f1dW4Z4(61eY)Bo)xe~c*sJTdCajTV}1Qu-sGJHL47o8f!cwby7(Ud(^#whNi zorQw;9VB8(|9GMF)K}F&t`u9}N*Qeg=L2eP&rJ~Zmeh0DAs+I*-30@qYSjxhBP>P z!g9*+>>48Q%mzNP7U`>PNe#!W#n;^7*R(SN;_0LXITLTNwNO)O5b-WQ)$PA_)QJwj z++(Li#<5q^fT?I#&34>|evk^Pi=F7{QB#OSF~X~Qe;8e9f@g;4D8y(nw$(`KC%wNo zg!L2IARYLlL*xo32ppf?4H)G|cpX&ogpeZNT;bss?*}CI`MuSk2Ig z%cUC2iVsSAgl?#HIUhgLt2KQ19lLE~^E7_(XP!pYS7)rmF!7a1{$6NL972GT(tM$T zr8nBfck#|fSf!}@9b(h2JJX}|ts0qMYaiyfo*Ka=E5JiIJI~iv18bbp($c4s&CW{R z!ds7}BR=o1V;47GyHR_f?9D`K0-Gvf)wb9cdT8X7eg$+T@xW($eA?36wF|b zOCV6SCn+s>Xm_Zur6BCCJjGJv%pZXB`|`$B12B%Zn6HSTKzbSYL@S*i){fWI)^0)< zfzim%Ixxu@8bSuQNt~-L-Mg3t@nvOYRn5&qpd1HQHlQh3UAQF8cdHh&$2Xv^6zdTXi#U0SGpa;O(Hi zM@;|fDsj15*ooJ5%fsmp!HcqCAdCZywatE?=_2{s`g-xo`OO#Od9eA+{JdWg1FKau zO*<}d&j6kws1L?t-=qEbq_Kpyb@09All?W?Lm42V8xPL6UvbpU0UJv4sga7GV88id zbpcMsJguEqPa1%yMCCllU<~VE90|0$I-ZxRx~&R0uOcM6Vavdq;{t2{rypq?5!*$itPHX(ti!l`_v|hlXXJNWqNgWTA;)*Xp z_jc3csD2*mVGXSmoK^!dUo1$kO%A)@S*G(ig`&Lua0xKEJtiHVW1 zx~**#tX(v~n&)~SG`yw)SzLC0FFFwL)A*p%Isi(l7t>6pjtADb!JfBXpqqPn36OEY zla!GP8=mmN%O8RLCstjb%?qcC=liWcrnPT21+=sEe2+MG?BAsyTqUas0C`j?)8;}*B)9Xn`> zN@R(?l6k3p-eq6%XUBvorzg;& zP}L$0ov`gtsw~5FzTQB~A2NX|Mur(d^@-THfhEdHOAo5`OkQlm=|78cU_4)jZ5SHl z9{D3M4lzIH3p;jup*@bCnuu|_U-)k zZPc4AmlFPaMoOxhNOt{CkWW>)Wfjw95nq?k(XL*k+u(D$fueiU)e@F7MGPtJRfnts z)^Sfg!S-S5yK>L>H9L?|ct@dM2mbnaSOKH}!~VA8VVlXE5ZLKEr1zfTrCM!_ixT} za?lB+;xhb+)aKN_^;_M!!yY0g&L`sQoJ^~HMz>W7?Ftpg{s6=>EaA*}#gjEd z>XML(0Jmb~8rz}vh4uQU$|hHr4BtJwi9gi;;AT`r6!RCP1_M}PkeQpaac2k7l?|{l z-}v3t{eCMiApSYac;OH-kD!h(j_;ZX#0`^XQdpGiy;y|O=G|2ApLctZ>vMZM1n+gH z=vuzSRGyU%q7dfa|LY`q^)1b?uDlNp6GI|fgjr2g4@m*f%4E16nX5O5ZI&ZU*dy2B zt$v1XdCvj{eP}2i$?$%&h9*(t>*xe_ziWm*>Evpkf(%+p5>wZ_l()^1ArKyEb)>%} z>OVCU<5-08Ss2iSI=b~;;uKj)q8N=yIth?b`?SK5>AHMz0}93d<tS{xQP2O{VxsZa*mPn7Z>9j{cnNa`g3|M`O23#-NC=-&^K|l82r~SRwFe z3R;-|I(H-Mri64Rn*|Zq^_Ar9Q?hEv5}}KbH_d{^7XF$c)#%9 zCFr9@*xek1fYI6$LYj3UN$MYm0tfjy*Vorlu|2h`gmG2VdoIjf(5awLtfU_QRt`M; zz%U-9Mo}E`)v$}x(+T(Y?+jbL%>b>6ouIn9`uFPUD(0Isj4l~o8!Icj^{!XrUz}p6 zhKGk=RxHM#?yhQW9RYsbAXWo*6K@$SckUz=&=)kjueDtAi+V$ z+IBsLW-Gt}P07<8cTjtaga{&-_ieYOuZ*{Hmbd7>Xbsc6pdY+WZ8NJBFf$30|5f;R zlYv zgk%AyBO27?hdwHwhU{Oxl3V;;tx9zN2)vy?*~fRUPr%k6Yp&y+%1te<8y|bDES%T| zfQ$)N{d~mtR!v<<^L-zdn?SB*Wm;0(? z8NB^VHXTQm+e1U49c$1wle>{iL`e|lwLgDy0iW#Y!4;Garm!vFiO_z4XXVWR9v_)* zn;UL92Y3?g8i1_knzaSaqt(>Z`2HOu=k8xNQ`>_%Xc$OrE|h5VYlMFfH3lG?&p-AL zvM$pWQ}lTqJ)VGr6VeQ3YW=|gq{BP0doTeU6N36_=?GXZRL=pi=SD=Ow~dc6tv_>Uq>qDjE(aJF<3ZZ@elC)13-D$@7g)#M*pZL3=5k&2TbRam+#)Be znU27wX{G{Ftq3q?-qG{U0!N8XckH*8BsL9Nh~+F=>T7M?EJ2E5nmD+U#6gk;-`LY; zuc)wN-H5&>1}JV-s&c1U&Y9Pj#4f8=jeQPX5o=1Mc)}a15gY5&Ru?BvAj?qQZVCxc zBl*C{L~d%i$s8IjO|;l(k;d>j#8e0MSXd#k03qZ#IWK(>ZQOkVrv2A8V2M2GJGBHR zq)5HCvbKJ)Ub}N=KokX|3SF^)EZ>H^U)N16g(WlTpRfFwDIyJDob2wqGzEq2=QqBe zYcy(4v;@kx>AW~Vr1LsQlBnqT4O@+C{WfAf!+tW4Ij2qKvf#`t(PWj$eubkSg!zgr zyim3bSKAS6u1l z;8)c@us$z8duwQaE#fq6e-+bXgfAVx@U3emQC2!kHC7=ozF7!fmFNcpt{R?%VixD& zuq@sr7Ez785^iM(Vj6y|U5m8X0$iNb{v&1C#7u#hnM@f4SqzQEq;ZHiiKV0hyhgDJ znj2+sO8C9s<$qI3a+vqxS}HoKZk@kfq6&7fs{QmksjQ)U3Z<=i*a8EnX9j^a9I5o(KiZYBUo8$wQQK6(?0GWIUthl5!IVv7l z7BOaPmUc%Z$Gy9*Dm%$jClsm-IYPw{4YRZ;G!7N6ElUmVj-I|<`PVg3!IbCBc+jh< zRWmAQkHVG^-$il&tw>1D5dYop0~;WPBFmCW*3vdhR!d;K!o*M!`k8>J?VH;rozGm` zv`)=N+F-Dw3}&EV%%K!kSZ`UnQjt$*k)~+!Ul~JT8;BJI7{2&?Gy+}oO}ZF4 zznCv|9>Me*4xD=E*whx@@w8`7fTmbNjSj!b!fvT#g|xHGG< zd*9M9`0J5i&n3!!XYJ6(HYZ~!qbHP`1k)cg;dXJCRNx=a>CLW9e>*=K22bbN&DDBSTkN>?GtdGQ6i|+*hUNyZJ?wC< zzMXa@A3NFX)}R~(dtaXbSj!*Xq%RYo)0aue(asecy7@1P4su*By+syZU>sye=&t0y z6nWnc`vqv41j^8Cons4*TjUbX{Vy^$?N^Wa5stYEfe3{-pcN3a03jZ9So`}W2pBJS z$pD=Nid$eba{{|!UhjdnP#u_*lmuL-z!e^dK}dc+pzETFGym*%(sq593uD0uw)&E^ zAQ=G8R&OmPIvN_6>p6vbrOsu|nrr6$N5HFH2IV6kfLa4n8=wdP8gby(*y&$kmJ0fe z+pvxs6m)~pVN%}2>sCH{3^;(w1|27#g*|JEOCbma0(&SF;07FkDH|FgE zE15q4ugD&}2)DVfIO3o9^f);=f%t13c>lkw>Oq#SLv|@%95;sn=;l~s-n&gE&`sS!cK5!w04;#S-Gy2E-E5^>l+iU|YSQ9&RLiKG z5oArUrixLzs|NT<;=h;ky4QL)po5>&0za_LvjzI%h9#@Sq$K>Peq!dx++ZLP^ws+z z+I-Le3Yfe z_1xA}Za+&a?V2scSL8E_YvDjPa0H#BOWg^!J8+#YF&=g;@{<-AaS;;7gxJTSsxRKRqyJrmnO41KWMWds zEivYZaR~dxj0*1N2E)sV#V2JA{!PbmAvuQE!Ibp`4{c;e2Z`XLVrfbb;6&6!W+e9H zjC_OZ_Fva#^8_ifn|SsaboZR;*z2ga@H~`D!!{~Ni_H*;W;??5_r-nQ&B~-c$m9LN2KrkV!~{Q;@N(3 z`k$(eI+vs{=`tBk)aa{Tp@RDBE-gtOIV3UJZ#ce@%v~nV zOV4uu{YNVzem-y{cvpaIge9yuu&*kj5R@oa+O4iFublO9!FqY?a+DJz#u(>1nf(q9 ztJyWFRd%vZuO_xYBCX44p-Tz79{IH@3^^(pqRHj&+9nEvkLoIH7z;i#9``(9irR#w2P;AW1pZxqWTiMO z@nYl1v=Pw?ILS2_51N%as3!siUc(?GU(m>(<+0Z*ljr`71{J;2{B5 zr5Oz~jpC!uBFTSVJKNd2ka#fDVd;ZyK_da-92M04c{-KP zYLO@3Ej*L3lM$qC`k4hXot-*(g}Nx8z;!AA03bbCr}f{Hs98e}zEQXBjrG?L^WpKN z$O0Kdd=m8csT81P$glNSXx%D?y&@FuD?jMp1f#zGth6}z?|)0W30@JgV{g)GA)Z$56EXZ91rsH|JMR!@N8QRycGXJ8-GTj zo4}?7xR!tp$^{UTk-DS7+Qh9bb8Q#!qm-n9`U(Ktt_4btzAwp`^Zs4SNUG(s4Y%p% zV;YWq3CUn|XkMS%SmH3U3{nre*C{L*v>~Zj_WiH#^TOKNHN(Jfy}uBk7(pNnK5A#lz|gJD&c2&xNm$K_=5}pEf`Kg{%jfm?`#c zAVxqW<@?v7_qfVU2${y)^sN(ooE9_&>pajafeh+-?5^{tkp?-_^GZ`Nk_%&jWkb6> z@jWN7v6L5lWS5bVAo6exxwVa5T{Se8 zzYGBRy637l%Zq7w!|?SN zB%Oylw_fvqM=$%7;VX~-?y~8XSo%(ryl;~Lbg)$SF;ph$gWcJNIIzD5`b6;VDs1nQKo3)yc$&-h8=)F8Da#*iwi4NvZa2OjH3`%l3JTPa1xy0@z&;yE@Z<8 zzCrJx*le_qs5f<{HrYD&8|Uu44m+jFIksj0ELShBY)yVe-<8=oj@sTf4v5EbJuXdM zzJEU___r2Mu4aJ$a7C0ey*?xElRfTFYgW6WhT$5(z3l;`;+MtyQu!OABDpN%gPqSR zB%Ulvs+4nQVdLiaS;SP|HQ1p;*s;i8yG9#|`>GM-7<@GQQ|q?uV^n|B8Ptn$D(zcJ7K^D-n6c4!$Zig#w($Bh{4A5^*hkWh3W zyiB{sBUrSB-3%ObI>t_FndQ90?rQ)yB;p|V|`2G6JA_Nt|MS;vE8UIf{7tUS`-8?+zCkqB9N2&+M zu|(b=w-`k(43@)&A4&+dG&@-~>IkaCb;108#pUgz;w28pJTG%FT=+G2k=*#jQALH@ z)m^LL$+b4DsyvRiO?g>@?saaD=xU>hQ2}uY(!bKF?$>vy<K}x$*DY301kK zR({t?jAhRWrW?EadY?Td+Ga$&Lq(GDL-5P0UHFq#HPe-x6MSYO8eqi|?B-HHTE33u zUlRsXq8|~_ZMEPJbM209+YS5NDPolxc*h=tuY{g9v%#bDTQnK1&#x;K89eGY6gl_` zHL@_|V)!tEs3i4w!7+%K*eEGbrRO1^wZp_^zrl;ac(9%A)|34Z(K7((m>fi8ftc`M zqwt*0;QAx=DK%+$8cZ_7Gz}jcDxWgkH+BzXqk8F+diOOHs&`q54y01L(pBPCWc01vgwxT_&v0$&|WW*8yuVo-EOM1 z#=BxvSB8j zWNQ>n4=yaG{w@_}9u1y7DoGgy@|$rFaDcbywC6tU6PFe1!k(t(?tXRuC|h0uEYJ(+ zEI=+?YN$=t&#WqV&gdnWPA)p;)mm*)pkZcX^T+Ue|9sPr-*N?Vim8!N0Lad(ZSHIe zx86^?-U|&@@1%>vV~RC9-B8WDlHv2~d$Zvu*ike)c3pKOdM2{-B0YDPw6yE@yv&w9 z7Ny%GJFmJ@>*E0$0q{5+sW7C3y%^Lv@61m80M9Csm)YVt8QTcThY!65F)#nX*j<~k zCLf^V?lvr0YbRh9dt2214^3Ac6;=CnDQW4H?(UG121&sIDd`63k`C#R?gk0z4r%F> zP^7yXr2Bj3{nl?S{YxBX?mYLNefHUVpO&G{Vv}#4PeWxemXsGSINT-vMgviHTpYH| zg1M)s5d29#qp_nSR}U2dAt6sS)*ucZ?`f$|u50Un&=96&$ZZ%ciY^j8ccxcYJDqB4-nRd(iuN zh5*sy)@~`8A=6b+ z{zQdBeC~AS1H8MHP`Iea7Q&HQ?$Xx3#GscwT*_Hue*Gi z)K)bj;+Cr$yx2Cfvx~kY;U|qx+|PdFMMO+IMDUVLh5LssNuWC7W=*30{#Gu7!IA-b zPp&E}j@XyC7ba{KTV}GaUV^}&juW+tX)Rr?u14F^1|39~l;JJfz_*{~iqp(u{&XUh zxI|>P{Tsp(NWfwQXGEK8dayk23ZaUytO%_UdnaG}`Fgo^&yT*=8f7sk6I=VK| z)043f$HR(=XKp+A*2B6%XInFK{J5T#`kaKmmSY!)E3_Xjl6+(VH zQ?omy&mjQuG8~wM#ia72svQk|u)i>0;vMTf5mCI8>rbyVY0rC7X7`jzl+P&62wO9Z zr5mvvqCOg`jaTmca}h^Q#HO_qMZG}oIN7}dS+iKC?xRLurz%BmU&E2*&DAZNWRusC zN`aV~NUO%u_ZU%+;ej20mrVI#s#Y4Es63qS866}8?{a_1+LNf1iQrnL^#)V@oUj;v zwNB!5I4Jp@cDGPk&XhJlR4O%<3VF-0pEBtMHqn%lXfb5GX#gknJy(3HTx>1>RH(hu zsDN}YP8A_Y#G<|KUMIyh$Nx-Zh-Y#8^k*h@e|aqRb%0q4F^j!eSzm%7c@}pmZ z?J>2`i^6-cjJ#5*WrI-B!jaLmYQ<^s97(auh{9nI0;_<|EULO`%Inj|W0?CWGxjw|hkPgD6z(yY9{0c!m2$YX-OY&tY zI(Vt&@bQmggz=aKXQq@oz7ehEtAjIP*x-l&Uebu#Xl(=qu6%+zvH7pulDczJQHTf! ztrtf!aBIf$XnQh2zP+6LMsHtO+a;t=)8YYXboJ^OHa-p9q+&LYa#%1NHsyz~ZUk!e zEA;E$Ut|hFy*Siq^-`?rsDmST-kRYBPRvLZ1y|b0!|m9On&eLQ@{_Pko&4w7olvx<-)`G!WJ^5|lL$Hs?4Ih_b{Ju~ zc?9e{X=zrU#4sEt8#*p(nz>KRJm;MHETPpM-zX(Aj&q+JV1)vMq-O;iaiqU|x%(}4h=&A`eNosI8>zQim5A&Y9xkNsk;XA! z5dB`wL^S0M7tgV$yUE>PyK5m=>8lUq`ljhAc`&|>d8C(7Wk5zT<(lwZS^3sSOs7%< z9_#kTP!vTx&^CsCxiNjSsRQxx6`8U32SvAo<{U&zK4G1vZ*~WLeSJ!e8Uq9k6wb@^ zsx#jZ-OtZtd^*dtYqsut^LnZHh`&u*ni9$W(ETOO%SKbVpcI%Tl(z=Tgvp0MkfC8d zgzxdU5wRb(e_$XjEo~@XuHJTQcXt;yw+d12vJ5dgfb|ym{M9NnK*BuWh`}QXZ0aVq z%s3gpy@fP^TJF8WMP+A2valp95z3p8$SD?yhn(JFPH;NPQLSi*>9+xPu z`3t*@4##S{mOc_>zp*Fy9J{sJ%vJ{g{_wSzN(^7caPAK0*M_L*Xmi8PtA#gz8nwr| z*VZEF?=}}q3y*q+UD+@nwiD!ou%532RwVOc%|y&P@|pY_s;m7W5um`>lK+cm7RuOr zb^<&zXa;28z6J7qP;bnH*?x_S9ovXeAs|bX=*sqS0Yzb)>;@J5nY#0e0+Mg*wDDue zOKGFjG#@ct!Q*RZd{rJV(a_Kq9eQ4tf9w=Zcz866G$;S0Z4GLN zfo{`^U+;lexmm#^<>{j|q?>o|+A|aA+etk(UMW zGr&8hWG#r=!z#?1W3*nN#z>67646%CX7!h?OHK z44GX(3p%#BX_{P9@)|FOw&wf*k|{}Lq*Rgptkb z%F9Uy3BadwtBFI9jv_;0){ir9{Yn2ho@N?F8eZZpE7iPMe}z zBCCy^R2_!=GeSYmEPpgrHE6a&nUPwZ^;9{goukY@QS?jkj|cZ5(N%ROlDI-miBTySdUzRP0pfL^|wtX5ucXL)RJ4GQ#S;+p*2$ zMtDjQQ(cYJcT4;b9RyTwE>oftS^PJNyj@M--QE)A1(00r%0@nXy790n6E{V2Il=&a z(6Aa&jRY$Vfg+D;q-s&u{+!ZmXx%qQky5NFf|2h(ayV7r;NdVKqJN+;MV3aXWD-}9 zAXQYQM-6093Q+FNjlWe!k*Aalag#HZJ7kRGyBd=|Cc?+X-pDY5LnLt=MtIkyAXBWF-(hrViDT4PB$@z2*T~dm88n-A;Dw{yskL>q}VK z9%gX7E>H0t_j{~FUhod9sk0aDH(E!vfH0hJKN|W=v%i(BpVC5vh%){3_}*PH{yIl< z{PHKp?RSwfP_RYx8PnUB|Ev&kb}|!xbD~oA=m>^dbrvfF!qM?5XcZb|2okY+3Fa$S zAsSUP!u}Jv8y&B5nFu10U{YfcZ>G!3+n7zsb4Qz`Qu`S%8$`%gPpo0at$k$Rvpo#V z3-LNmET+bV8dEeUese{M%vMOSFKwqgmj0x86dVirZKLthyP~{!`tC%5@(o98sh>*D z=Z5hrR+az@Jm7qh(5H~Pjwg}GcP6N}qRAFZTL)frmILxWk%Wr_tz&oK!h?9<_R9#3Wbto)9bt6Vz$A| zXz(H7Q^P9-rfA{g=BT-k%t`K7bveo<>c->QZ)}!YlI)rk!H3diw}{#lc~>(}WFT01 zexBViK#6QwFgxWSun8tc8^IjjRN(mz#(C!E=HRX8f}bCv0Kdw*AtIrFs)y5b=U0}< zk(CNGL}13X?%ut5%DSOe=vP%u==^cAnc2z+Lua{?_~1CtEkfFgz^dlwTu6!ZYcmTC zX8aByZFBC!*E~%d_YMI{!g!#QwD{g)=g!7+=J$h@mDS;HulPJZr7Z}E#natdm8)h< zjE$*zIQ&Euf9RSE5SjKvFRzO*+49}rrhh*%pU5EH3XuJa3*XXd>ur{Mhd$R(;+_T0 zvC#~prMt@uul9jMBT__(fr?A%`~bh%Lr4cYJz1V(cUB8(m*6?VohA_)_?_L5;mCbycV1fk_#%aSO zWJ(BL>Di4a1TR9So3g8(H8~|2Xi(BL>wd-8*$Cg0?8&awv##?7YS`Z??k(ocHHTQO zd+Bo%OdWP5X?M<_6st3@wb)&$+UWd+l}Gf<8Wcl6FhzRADy4XJ85ow_jU#EQU4L8q zGrKF};JtH%%OCD@w~T9_gQbUNcd?}-?6XuEurf`jT=ht(ZM|P{ZrgT4x$}M}RVrNg za6^m!g>c;I8M(>SaMc5q`du%oF&(yaxSy5{HC}j(ZbguZjusz$VHZS3A@Kd*%jjIy z%3SG~K_XE+R0txD12yLcQEd2*-PAXKqC9vX1)NB%G}z8tm{n`T>QV1goDe5;+Dogq z^xXViu|Xl!yf`QPCDi$A{(t|)p2fM=hsHx{l*Tjq*_n(#4K6O?iDf>jNY6+TkvB+Y z^+aTRC;k@HXguGZLo7+{Jvt$KiyG*nws*-@*o8%hj#7gqJ=I-JNq}vH083tk&RI@P zjgw0~DvqrXbMnhCaM(ET%#bC|!a@B(oz$vscZ@Ujnv-4$D`El}RL!n13F0uKpxXD` zvVACJ^gj>Tg1EWXdo$PxsA{56q8O99qq(SYc@$`A@Noc)4`s~5sWM-}phmzBP-wrM zx)QGT`Rg6_cUb4v6+@qe#k}RUV%{33%}Xs!{m@qtO4DzLVzp2yWlK%TRN)fC{xUmM zJj@4H&1qqs!B!!$I3AyP*y~d&N5BwgggR6Tn5CqL&GxHOZkURxT@2&3a~q>DH->*F z33BsCrKKX5WFAGW?=kCGc;devJ1#PObumn~uKHe;K5oZ^01XcnpP&aeF43i(E`5x< zhf=y1PA!$Fn;wVXKYr^8@*x#FZVgJERX)K~VFXO|D<@V??{S*P0sC4xP(pQ4l zG(4})7=TR@c0n$Ux}Nbq2!}j?&oGZuhQW>KyQsPpYO?ZJ3C>+a{(D;H7dO^nY^>-; z{&BQ8vIxC--QkMiqqV2F^bSt%2dm@d)Q~WuVOWs4r~?9MV?`s+c;Bp;IQoW9UgFPx z^XeisBxGF-2<1hkd=W4y6%l&))3k+yuqJL;goH8fctUNvPDk-d@Wwk{an_eNYGqoX zUB7tRnu~|W8D>KnSpxWGy-_sJkMJc|1u(z@^f|9!Nh)|L&0!@m{jOMF#F_EgSGj{M z=@M|m``3J&nMk|^iD@f#E@5u=I^t6OQ9Qo{0--So#5ZLU z271g%sFKJ)%_G|1-(M@pzG88{p^Yo)B1}<^xgYf64TF`9%=5FROu6=4lZMGy)z$68 zj>d9mws1q}kK==Mk&E9sPl>>weJOTS2<5+6|CS~&1Ytq@s*(~W&k`EUlwV zA2Z(`$+c%ZQOpZG@I3q5a^NX3{QJ`Nn@*8(=ZpE=2jaSLq? zwi&Gk`KTHv&zIPH3-Jym>&*wf(BA>G}qGd3^IF`R7s`@jw53*`u_{Oo5;GsPgm1gDo+ zKPodk5~bfK2IPZTXq1W)r-NQZA#f%6MdhL^HrTVUGE6OMCH=)V!6PI8^ zU&&u=Dkwuhwm^prI;w(RGH#scWHaP<9 zXCZs-`TO%hMH9{d7l->#G+>$!ufG^XR*Z~{ii$GzeAKbi;%G^aD-RHCpJPfI(e>C$ zYCE#EAK5ROIWk^wqo&G&M?(viWZtkfTHps)AUmg6rvmy9&)L4Ot0Joshxc!XAQ$j4 z$HksefRB(@vQ$ZLlMGl+-Kh&u`b~?P@U^_sFUWiLWsvXm6GQYywbi*f`(i`nxZe}n zY-9L|SmM_Y%=rIBj5-dGrEtcOg$5jOlVX6d0oH=K&+T?8vUT!_zgQ{{AZ0VSlnd8Z zycriQOEz)Y85t%UManlFIUZUZ9Bl8IlQ`KT8PWHO&cE$=sDI)E?KI$gZ@Q2~yGWK# z5$PEi5-#&JMrfy~;yxuqrsNZ-6}GsKG|;TTF>P0Z^V_1g+R85{G-@Z$`3Iu>Dl;_t5_O-`yTd;!v(Ri4>|YFPe?W>U;d{B zxSGP8P<6dS%X&^iKQJgt9hPAZNc&PMYl<@vKB{Mkc=-9);@8L3pUb|bPegCkbGqxI z1-=g6vpsz}AroodvLg@k?cTLa=+f(AVh$pKSj(tK@aYiT$SN`V1jVPuB?LY9`fJJh z(@Ij}v(QFv;5GlTM>WmlG!5d8?#a1>&P5 zhMkrZji2rclgF(YeUHsIDA?7k2JwCprY+L7GPK6VTUaJ^xzSM)7+4C_-%zRfAt44~ zl*3<&KdqjC=DahTjsRQWOK$mYDZ80=!K`DL63I9au54vE=A_O6QAkUyp5 zmh>E@>JKHVk=B8md(AZR3R$MyxJ930lrxTyU40J|-_S^lz-P<2mpmX!6&o2H9lc

pNvE6^VXXUtRtlGbF&z`_jJi-Sz(0Q+AssAy?sFU~(g z+IR)fKSbweCHiki`XX(+%NSPq~d5AyfVsPJ1Q{<&_ej-T)Q_Gkk3VE0aTmzb>C$P5(o*Wu@ znD>z1-RaOKU>rU@Lf?N2Uj+i?XWwI&cNF}g&6IU+k*!H)V)4B@G$GJqjHkaA7|qta z1`pS`lpK*KgZLZOFdd#Q9Ry;SR8xLO`lttxj}ftCkx4TRgaLT?Xps8-M>h5x@M03E z4-+^FwM&L}q8c!xvfy<{!HGl&8R!DiO<+3$D0+~XI^!{zKv#ZL7^;)p_ZAKWqJu^% zbJ*VmGZc{>jkPQF8UK-~Izx(sEi5?j%4Oi4z@oSUokB#)U=I4KFEyK5vn0sFf<1Rp zCY5b~9g*on(7a!UvyMyzMP!!)eE3L|fSL<}7hNbl9EhveDFPt!B6$vI3;p^%0^h@i zS=lmu8CpW5(?#%!uJUh;=P(CqaB%Pvj8p}Wg()0rh!~>eQb->!k#;>w0TX6z0e#k{ z=6|AvV1Um$phJ(SuNMKY0;ow517=fG)8vM9wJtPP=Av;*NWbI>H9VppLF6RBpCE`R z^td<=YV0p2`u*O5y2KQI2K_phJLFG)_55go&jDfVywpS3j{xj)MsYEeB>0G`1Bp8@ zePwaO{A@Sh&gqiL6#(*oSex%#D)|F-?ZtA0XK_-`NHq?Dz}3Jcm` zS91XyC^BS-^c%hTUFwKsE^#Gdl4|2WY-+vgJ#8B(9_j3^?fVEetJ zue4*G1$TN=6Ac*txB&S9J}D5Q=&wU48$srL8G1-iCM+z+`-eCQAyNq^(X#K~Ro!pl zV`8M-W03EGdkDpYgfhM4ZpsC~?NJF7v;WgWQa@K9-hv^#}D7lseC0QT=Z4Zz&;sY=>&A^+zv z5@i9ZAT*2u3kNVP1HN>(1u;}1o12>{ix-8CmYLLdA9;jaSBy>|f{}N!0E!7DzZu(* zef*e`WM{SBw1{a2o|ZcI7O;!h6YlM6o_pv{{8h~9HF=7`Ri74)Z?`i-zH9_`i@G%L)WClh@ z-$Lj-2=k~jESf9O-XMxfgDGu4UlSkc{P;1Tbf>bivcBi-1}QP@QQqdYYA)&>&&ufq@y~XJb%u6=$*SG-JzAQtyH6@$Y@%vP=uKcJE4=`D;gFUW{wSb8|!EV zj{dTOPp_=5c1bg3<9WywW5l5p(gGVH0;U~;IC{k*)W2TtND?G$nU@Z#6_=rp3gGDd z9Zrk=YUcL%N?_8~&kqko^U=(F(=-P^E*k$;mQjF0H#J=mWZev4hH&AZm`v(KkoIrb((Gg=&K(uSHpq++2ye*9>NCoe8(^GAV^7>M5A zsZ#%_ysw{p3@`ob|1&VZAk|6w6b_1F1mIsTZ|1~<)8IWc^$H|f&J=7#i!Jb#*H;4 zDx;+u^72@457Dqhc0&^n)~p{2=14SVu$0HSiqXhRq^&f1LigA<|9~@I8g3To%Ovh6 zD!+Z4Px_Z_mM6zA*8E`ld?UiaI+3|AV;a(zpq>~&X><4zSqOye{a zCX&bPFjBMWYsPMrGLzRk7y%y?@{Sk7y!kfJZt*ZZJ}u*{jg)Wv-#0Laf!*~ zJ`->bSfyi=mK=jk!f{G#A9fS*EDV0>XS^Ul&F~JSpi)*FjD+Rb&C6Wg4NXbDC{v>u zD=7Fol~G_D-xxEva#(0k*bwHQi7x%0Q55?Xt&?$@ADJvs^TpW~x8=_}LW5Sn?A0+U ziD|7p%~w>Rhdhn#PxsY@rvMXjz@2P>g3cqIEOhGU`!3BM4JdV&T!fqMeP7w_T6Xb- zK@!M7o{eY9g>5M@49?Q|S-8TM23F^)TW*CbHhDjafZBA|1*F^jmT(@CnjAsiu`dmn zW_MpRe#`h03x37#jM_%;J^6aJfMmd}CzYK?E6U&m9A5#V2%gg2sxFGjHCLDO*PdiO zWiO1+-_~OH1Vz%muMMh@tto{eY$&JDh4|<$(5s{r!J3bw-E?Vyb0AkO(|DU!m7o`& zT;sn}5zLh%DcMa$@49;|CMck*6GtK*t9+-|>JG)54zv08NO;v?bd^YhI1As7Bqr-9 zTPCN^DsXbs%4fw>?7Mpm)PGS5uXQ})8pB!X3~WeLLeu^fjdmSG6Z0SYrdsZITSSxW z$z%*2W=fdAH-8vmu0$bBML-iv`XyE-H?=9tGo3blNg}E}?gmY4LP_N~e2F_Ndkt{) za%`TKeB#~~l(f8Wpy|H6>jf=H(A`vO0xWROLmm7Q^3LlF1iGanXfvud*VVa^t(kA1 z#>rhKwId%I^Xr!tz^Sex_%M{{mpK}c7z{v>gWA#$cf-*8*K)+Z5=SYwKZApuW7B29 z6Ui77^AFm3CZK!Jt=Do?u*C_=jkH_Ph!aB;a4dk8}2R)^{h-)W1Qw~#rC+hbz z%O2Kufj6-zCrkECsGW65=C11EOVYq{j_34gzsQpMt)CEKzGRR4IXUSyLpPMv86bIb z{ybnIRY8Z|%KBY(WhHH*a_iP%+q}~!0284SgqAiagT>HQRz``BVtFCN_{GWU8GDa; zkv<1hOt8IAAsRCR-A2iv7!6$QrBzG?I|z_%_*Vk~?))OW0Wn&lIqT>yDGsy^MMs;f zs}BT{Eq!jVDR)EjY5iN}tzU3`H5#2kCv~ojZ0z$G$n27Lh@2^B-J`x8b(+BfVjNdi z&HSmS+R+7j_iqFOpya0<&B#d%+Y^hlbNCC2i{Fn?iO^8U$N4bO|6KFMebut1wZ<9U zZBaY-*=1414tqbS1hY88WcfX{PKsvAz)zWftn?Q72?035d6rTz&GL;voqZ%lY6;z@ zhgLo*1tld>1iJ2KXecoR4l@o-?_qt~UV0c%wj_4LR-+7ys1$MtcxrY2amI&HyRIe# zex)VJay@^Ttr_o33Uf3*mvB^OErcmEWs;ZawAaJS-7f->q2dhm5;Hy^rAZks9J^(7 zyFMxlL;jJTjWL~B5}V_i=wRdZj=ND!e9Qy-Imd~Au&kS9eX@I6F@Ng$h|x5eWOxOW zZtsb95WId}W@RmaQ-T#1@HxvGBk*z`wjlol zuWOwlygc==lNTISOc|{%J!)fdMo(cmO`=owKWjL%7t+P4P!3>9n$nbN?o3WhOvvs$ ze9acZqBwUW0u5t8ikqL>vGXM2K`98c`!iU6%dI*I2{Eg!oAq2#AN0!Cegzd1L;#jh zj@Rivem!Nb@y%do&T|yJg>82#&uNJe9^2Ky?;*#+o%!B70S}WBL1LREC z{{XbXqbR+k3Bi<>FkozBxxEtZj2I1Ec&K!X80pGmuwlBPuz_5NjwS(#vm}np`m$W8 zxKd;2V~Bn8C*N6uSHo2SZrj_ACS zeIg@moFepSZqM$5tqBTp=3Q2YKph>0Y)#M>ffjY4hb;7-X39{z4Ns!Fo*tT{aCl9I zkysLLny3dohvKG8yM>RB=smJn7EV$e_&e}7VX6(p7{eQ+IBx*)z1%z-;VSYTQl#z- z?B!Hv!BmVM7#RH8vNdwgv$k$JCw7%FZN|^t! zof)O;2K!Q>GnyIU7Z7l{GYd_M*JXM0H$~q<#3X!I3AJ^WZTZV1OA7Mmoed^TzzE8F zOP;JV4ihUs@S`d-6#<%6+^;+1jrXap2qq)(HITG8R#C?S{AZqX)w$$^9z^RS*B& zS-+)fCstRgPJ|^MM5U336BDdguUc7C$boSgC984dqrOA4$)M`)2Tv0_sO`&f&T;B5 z8W*bc4HdL}vR4w;n(t6T#tV9bD_WP*a%_|dhn#gf+v0kozo>rWYKaOo9oOdfeX zmy)Gis(v7QiO-Q_Uh#P)@H&vHpVH9B*?bvI^Wg*&Wpp>=){eq6)gQ$jW@Wwl8T-kj zG(VeTloG?kI9z7t1j)kE)mgT87k7kgZS6ouP&%oN>AbW(&r5%*C~IQyE$?uedp9BXjQ>X5png$` z;3_wpbsmRpaZyQ*d4`>&EFLK@pSz7}-c*IwJ6*Q7YgWT8dT)l&&HuCh!AqGI?=<$o`$vaFnpF=fZipngMNjHwOPkN z+W|ZR$qcEGaNLOOps8UhP>XL)|6;~L76^tA7E&odqgML9lTG(j12Jh53FWl-U>AXK ze6J*_?4L4O#U%hgo&zLagZhA4YN<;I8jlt zd*1YS6_(dwez0&>9-UN3!Peu)kBJC^yigVu1`wdC$+IvE;e+Ahb8N7$2HNvlgEV<` zwDa1}erfuW7F+(yTnrzTTK+gah?dEFgQ3)c!C^%bKx_eQ4bzngE6^(bTEPftdm_!5 z{MLY&4%?gOE7N0C?3~j$p%$spC0ON56w$Wq4*$m2KTa+4pD!g{wU!Oe2+-y+*2Rzg z6cxGig;(HhuX92!XHYjvlNIUWRELF|7b^F$38h z47fI=_HH!*FpvQSB+0H*7F)(P{Dn3Yk2Qvl;dv=LsrSo=nm;1Uvk~7X$ns*1>2BFN ztiV~bU%Vf$lBvz1J)ZD^R`I0PY1|Tf8LiYo|670^ZKlyD{Xwmq`A28~Ep41~>%1$* z04)gJ9$gDykz~(j$-9$qm&{_QyF7IKTQVw%e3e%jmNt*-zAh}-yY)$5hR!5l!t7<8 znBc7=TZmME+PJ#AgS#4P!bKS00#pnr3IRZZhz=&pE~^UUo4)%oI$B=LlW%*;$;7zu zM*+Eq#W2JLs-QYUf<6@$FpyB`Wr;CJMf~=IbuFd2BQ=4caSEG`Rgb)kKdp zjj*|B9>&D<*_Y{$^9Py579~O%4Ae{S6_mv!ha&N#aGGTy^&c3e1_cG~6C_&cS0;#} zcnqT%nOO4C&*7@U#J(%_!)r@Yd~7p9Fop?Dy~)r=CJO(Gm!q2CYgg&q*u&Up#&oCy zeOzw?tv&Bl8#Xk%b;wIJ2|Oi0728d8WMRPfx+dPklnl_-ZfIQVTXu;owt8`$vzO%t z?gL?mMq@#^tum5uIRhWD)Tj{2wv%3=DTR@7i3%+SGq;CtD&ARi68cCL_{NuvDH;D2 zDoaaooSGm(X4@}yf!*lI#J$A66Yd1%NM#JhZq1oea?=msP(5chD8&D-B!;DPC~4lSVSaK++i zn8~d1*qT952bd`@MD=!f@oQPX1k_n@Y^SaY+{AO4DX*>uz49yE`R=oL%$tMO+8*=l zyH`RpXbG_&kjg@47sfiFtWpLb1e#DN8N9>vr#L0cq1=TX7k`a1Dd(&YaVSk;R<-_(zY|Pa@rPQtR}`#xM|c!- z3fPLueS4k`ZF!ZyXJ?lGQGUPPnrFx7(u1ZH3v!tNB={K^JkrSq&jhnh3csT>?9-eN|^wQ3SHm*q|`o^O3rW6KiG zM?cNaE99A-I7}YyWb2^n(9G8#iF-vLA3wG&!ipV0>l!kvIZ>T3`pmn($L-%zZI)*? zKjlEThc^dBNXyD$n#2Ta^#7uLv#Xabx&WCq~J8!-UkOE=`t%4r0ETzXj z6;~rIPDxk+&#dd;oxxq4<)*t#iVL;rTe@B)HV#E%An&(JC4PL-bjU|Hidg9Hw}&g8==yV&`u zlY2>rT*0&VgiX|+G|0VB?IznANQ*%HgV>mXxskOgGF;pD#DpZC4&^XL)5eknos@p0 zrWSHtCFG>=PX7~QaxgAv+TMJL;T%7u<7yt|f;`WfxF`Yj`AD!1gYLz;zWBu#KfVFB zi^7|Zo%#F=vjP9_x8w@o+!V_1Agkht<`})VH)AV-=5&Y7HiO08CespZOi7XNw6>RD zk&2CoCRof`OpifJ4{R&SD3UPL6ezWQ0QhzhCFieL8H6LdX1K)+#kIBlfSnFWZ92h1&wr)U;#T`WDhmEnlvR}}kurVtzW@v{nn3^n literal 277185 zcmbrmc{tYF7e4%GlnRwn#-s>E%9ODrMUo^WLrLZ_MCOVHLWLw#g(M*%^Uxqk$dt?? znTKQ^-+SwPJDvBs-uL&%?{m(jC-OXdSbME|-RoZari${R)ig{r6bfav!eKd8{1Hi^ zEc!*g2;Vs(N0)&=mgyfkBuAMi|2@o&4WLjqQxxR(t2u`CHJP}aI6pT(&!=M?Dq^9P zwXNIF>)y*1AC%7<$T2kqgvWa-6D8n?kjeduQ%s28#r&bOKS9?X;ac+sPd(VRO)_OzX0y|#&aq@PH+c4irfgdW8>{(c$-wZnA& z{svwb%x`X@{_pn&c0@B%{pVW+;a+x}|M?CjBPC;R_TS&~$d)~M^5m(7=hCIj*JnQW zj&^i($VVkdM@Q!@JQ*2Z4O4;w0}mGk2M24YsU7ZbYtxTAjz?FQKkbO3qPa*z8tdfb zWM;-p{-z{@-65)Rc9I39rAHsBP;)dkHMzRDFbSJ}@9*#b_KhRBL`q63Hz()&g-m~c zf7wSWyg}aaE-o&XW49?36}~$A`D3(y573@(=gyrMRJ67GzG7%GF)PN_K=LXkB_ab?XO?IY%g4hz9yB~bzeVKD`D(}!R}K9CskX^Yin!E%gY-Y z8cIq^@Vcm|sHEh`gC!N@>!#zTVn3C8H=k!Ya^%RUlk2HdA+OKu+PJE)u&}Z-&7|z{ z<1Iy1{enfGKYwm*ZGHG~bDCCyYTTQ*Z%^``Jagt@%D_sBir#I@C4a4w!lhjuUc7kG(C~?JY*n`%Y)Q4UOuF-NcDA#Mipt@`hmDQ9(pH$96WzJEW=vB67r&8AJ8>`xjP7$_-yk{WMp@9pjF8>XV9ukV)sYlbTGYU=7gzJE73 zf8Hcb%UO+|lao_I;&gn?z2M*@*NZ!bZ`_~`Qe3}b1J}_FT^r9DJSdR3UT3a+Y~eX_ zBt^8cveHgGJWzf$Ev=s~d2)*`W5rTdE~hl|{^#TrgvVpi@&0@EoKVa;kI7+h1_oba zrvi!%9zA-bdO=W9QaeUfArcG4Oq*d=eXb#6~{OVs}XNIayg*>^kR` zE%+Ms_;GaR#(9LoD_GT&1@Y5PoFM28}s)W<&mUS=B$KxZ?EyHi$ zZiV;g)2E`i-}>)o6+e6SZ1*=+0b#*h^yB3v^ zF;N>|79r(4H*+bV_wotA`E#-dp4$BWets8M?N;pf@St$l`eysrnC4#S@D8+_=}&Jd3)>qI z62jwo!`s`m)8hpvrIF*XD2WIEJRUNJaA%1xi#DB5RmEBGq-SGe^ZRztnNv*cYq9;} zG@NgV{(UqO@`nzko7E;BxK0}`Zf{zf7_QCla502p9lYf~o@0(ZzUEntY0^=_A3uI5 zF8924?Y;JTR@R-uLQK9&T(*`S1uX`25)tC|Jrh6M_wL+0$XZ@INrKtRBVk+zYxySw|4Kbw@> z%tZ3JBDcv7#*{jijT^TYvS2mqlg}M`V!y=W^nXobwKk#x4)i(C;Y`6|5 zMM&sB$IDoZhK5G<#EGiPN|qD1aQHX)9Hf4vvOV#rAQsWt(NQeh`k{33$B*K6U7x?b zy-vq2?E;GnQMz~g_U-%kw|lV)Gx?^hT;g%f5*_wD9{kwPXTAt2NFMD~u1gkyzt6b*Dy7k)eCt{Uv-n@Av zm_MPPX0?@)C0$D0%s}?wKy&W&yPNB<_+|Xd$#^}S-kXcSF(0WCe4-l!9}^iVz)H`= z#I%0>de@+8zZ*BK9UL4?zZEonFc!i-j1*j6EHgLJUL3$3A0NMN?OLZ%j6)-7dN5xv zPE9;}ALZ$>-xj{_z#jLx8O}p~eNEZpgL)s$MVy_Sn$O%F$Q?p_4 z4Yt7F*Ed|o-K~jn((K&bpdkB(yck!B>8$-21e5QRr%!J%{yvJ;PqMPK;%n;P`ozV> z@$m4Nn3#x%mzk!~a0DvGNab{Wz;UTdTb$vCkb|Q#JJIe>2Ah;W#~V;w|H`5PBZcia z3^q4aRaMn3T~rY6_j{9tglueV_8671>@oawH1mNHSN7|zEv5bA8*cjh=R5vvYnjoR z5V)nFrB(m*coZ$G_=v+)?*8B;2xh>N@HPd7L61G2X#l{-J=S+`uSH&KS#OPk?N>a2Lf5#x*@FiU!t(v91Qnwhq7Ww?9WyYryPrR+;Ka6W`1tW-eKuAh*V%pI+x5qf9}f); z&CO1a_tqvIiI7K>eroqWq!#bAN$Owk(lE$`O?m7yv05LpwEWNvvB$1ZZjFOkG{S*d$rE| z-o<)zkzCz;L+BXZBYUc~XPKFy5# z=z~$sI0^WF0mW2SKU8q%$-(zF}~8Z(W`BdV*buP&$iBIqPs zU2(@%2?56*Q6ffluT9&#G_%^dx?xoln+G)v}P6mv?eBJ?VFcD8;BAJank&-MdET!Q3&1bDEm> zar#n9mRo0gd3pJ=V)9>;Yieq^k3|ID^{D73bpxT@64vt>decfr=JTQj4U;T zG3gyXd_y-Wz0RE7W$1EzyxG~ak4g({56h=e8}ikehC!A=G#7nhWn;hRcI zN(u@JP2Y`8@ktMur&2yRf~su&=ScI!@27#>|viyXjK0 zY44+7`I+9j+0NtMv!+_a*xpVjDoI?(qF!k8=6$Bb3n1LV=EsJI*UIKhwE0}8Wv$P$ zkC%N!FUzv`LbM-SQg%Kt#JM6rGK184*r9{1ZTrCm9Q;t1kC%695T-m@tLHxSdO6&L zW7|#cEW7T<6~=ulw$jo0I}c>W!i=I0`A5K!a7VffH#xNEV6u-NzadVkin!Ftj$pjK zInE>fmaSXAhZsfFW!f46-lZH_Oo=^v-jtYvu^26zq?mPUK~9dOfIt#PGT#xbmuJ_l zTJ_|p7dAMva=&)-1Bhe04>CwM!NdyQW$q?1%`)P=-HW+ z+}jx?@9WeNq;YS@Db=D`tsVEsM307w=(&yt(YKX~wy=oXk({;X>3%JiI@7d|2D>@r z&YU@ebk9|J|H9_@U9YLQ(|-Sk*@l$7pX3?_Y>nyFvt&2!?3;(<@>4qr@} zVa=bL>V;>zIN0nuGhrhtn*Q$HyUUB0)3S)|;^KN=7eiHGQTVZ%?9XRwbNIs#w>eb9 z1`rQrZy@FAj?~uCDY~_ZGYt{lREVke`Kc3XYDl+tZtzLfbDA93Xz~2ft97i?Qt*~I zPj1uw>1M|U8`1}1P`R)hjsw>mot$Vm5Ky;yie31AgI@Llr^;O*63>ar&dA<8JqL$z zgx&J{f}8-Ml9DsnV~hIKxa?&`66^z8wB&(CK<<}GaPbiYJskF zeBETelmU9ogPZ$Md<~ZM)~!{}-p6CBkhvgEcJIp6W?Qr7k$U{wH*eq!1qwG2a1Ugk zFSfWK;WIu9o-}u?-fZd8rSOma15Md2F271K6J)JN1dHHoUM5O;WK;bU_crg?Py!b! zV%5CE0w9)#10zEYpws>VqnE}xHv97Y(%fXH%>2wR=E1fs?k`>GSpRL?3JrGe&Fe_l zO5o?`hvOO^9%h1Hyu*12Z_rsDDP#6!hmG(EAP#`uW>)sKYqxj~{rWZi_U?OMW>Lfd z4Ag$0@e-nqyXM=~%_gi-oljr+J&TWLE&8q{I!A5FoSN_MFMHz<+okVF7hExh@qs3C zoB%Q$N4hG6{f@`i$PyE)cY1D-uO1)NQ*A6Hs=Ib!4Mlx)lK|m>CAAVnfDn-V#n&hX z>_*c0HQ#jO#*I(0gm2%TJ9o}`q-zZu8-L*@0MXQIiz#Bq&zx!ffQk6Am?UeuO?Agg zIgh!F)@Tgo{8Cm?`Fwy*O32{DZE4r3!+PG!JeJ-32hz|xj}NSu9qDh-s5fuQ8vWT` zgkwEY$f$RC&m!c3dKuQ=E-z=>C~O*7s6SaGGsofiLMuVExzPUD^9n0%?XY44t(OMH zIhTG#OTi_>3C$i6$W_zPaYej@D=B>cUR+m1Q1E9FyL)4bk-t>aeUj>QRmGOG-}~O% zD`DA~v6@)~sjYcS-YlJ2#%qa$b0aKt@d=zJmp4w|Cz$`#$&*2@zuvR&x45caB=w~$ zp4Rrqrw~!AX7{;Yk^K$n1f0Xu*FIrhxpJi!z3bG-3L2U$OaHW!YZ)0GrbfE461Ui8 z=H$H>0$Xc2FF*g6Zo9g=y0LP?B0Z`x1qsrBXli;I(etU=vkh1QEJ%X-k7r?B!B6tF08T~7xTWioGEqYWr+(PXT9#$ zMnO^)w9Grf!Un@lEi5l;y(=6Z?7#+BW2f@J( za4~6GO)#F+RH3V{Tl@QW>VOZ^<_|t}@LksMO^yzBNwjEUGu7ZR7JO)Q?Bk*m6ujRSy|aV%ephW zwlmOxAgVF#-6&Ng7?%*WVjY*5^hypnzypvns;a7vj*b?bmzoybx{bf^)U&JU>FMh6 zK)gsZE?>S3U=2*PI#9`1AR z8~gdQ!dM8&5@;qN@~FkAE?vIdOy~hpJaAqzXYZ5u(DFsWF8sN z?92@ENox#wJ)io-^z?XtgTu!_p31?S?M411dLu$BDtf!VeA`hH4DLj4T#iG|*9}Q3 zn^V^#4-XHpaX6sJBacky&(ArV6q{r}eE2Y2!lB;$6|xx(-Agfg`EH2+&IrXn$|J2r zLak=TVwFNvkwrPIR*xSIcWAyd6~6nt_vu0G~P6m9^rdc?BNj}GMK=IUr`XI<>ia+w@P#5by4 zN^xhj{mrvj2Ee<6Vfb`k@BsDMG%b7aCS*Fuw<1DAd;2N}wA0-`M`to$`ptk(tQ>K2 zg|ov0v&C0XaBgmHAUs~5RBbr3>+3O->Zixs-}^3Jy!h&sD_5>wU7U2Gan*_yHmf8S zQA|(h>dpc5^*3hz>P^b$=i}?Gj46qN_xQl+Z!E-Q6ugY$zVvsTE9ie=P<%IJkI{w= z8rj6g6Tb`$Ng#n?Wihd&9o>3;0o6vRtyj*oMV-w?(>+onkd=>e!T>FJkOB_lCmc zE8kt!&@f#dv9Pxpi|fo^-Mzaus=|182vRceB1n5flwdNd2a;-ogMvboxS}dFRaNzO zhbSiAbyG;SwYP_7K#HjtqiXuJrU$N|!9jd3KsC<1`stmN0Vc}81#ni|u4u>3PrabUc z9TzgS`Nu~`Pi|+pklEPKa5_#6E@XOgQiu7Z8gEcuUS7Jr7=!Eu*50o;rB2P_)G*h1iAj7&XVTRU3Edzq>)Tco}f2 zc(xGb=>pIYJ_(qM$IuYzBaXz(%nZspSK_gXI7{cxccgKX&l9*S2@0>Vk%7jmJwGce zYdAsu_s}WEyZZJYID|c~UA7#hoW$^JV3Ix>yp;E4Le&KYh8R^78P%*CuCWXTIRimd zl!+3>BS+>(liV%91~S3~<^~_pjXmtEq_oZ-0)uHC{46oCthiX=$dMA5 z=O^+g9XnQzKk(O*k^sM-BO|MRKPy(O$a#iB1de;2hC+$$;YaeF&3`e#GpB$m^jv-x z!n~Bj#2%@}vANIu#Ga*EwKUh+Q&DiP3v?cW6b4JYckg6dp-*vfaj<}19@t>z*!XA9 z*2-e}rX%ssTHudHTKpOSFY$q(e?aX^BPYY>5C>Abv~}Ph zCieNWX2O@iz(C@wLEct&2Jva^*x*BQ%B|RI5%Q>e?~#|2d#c6@mujT3`rl7*@B|5B zj$9iw6f78^YLl>OHHe%~S{EsnGL^ny1(UL}rrvn11fd`ao+Iu=Y+0m?)$R}=Haj~z zqtdK)FFr7FGslo_QG@= zRxW%>H#|GxEY|wM?FlmZUdYTrVhP-5RkM&c0R6xs!gRR)_tq3jwN++jCZg0dd=@ZU z11K1RjG2Ua#l`Ef4aO7X-1J;Wr34ri8Lc9X@CHW4?Ck7x) z-}kk=gXnLGMd|&L0E`ZcXF>LW=z?<+uEXfD%m=8twJazy(!CWq-*Vc%mV6noe1(NE zr&0{zWFr}j%&VTPmf60*<}AE%LBHC`lcOjDxWP7&^!Um?a_otVeecKGkY#U%&3s5j z==+QmhV|=Nkwn9mr^g3n90tO`m4FV$zE@yW{5n|xVMdI96=dmQi=<4P?>38_N7^L= zunjVMdTL5Mo1e0JIgHWc7u*uofGlTAo@@ThFzkb$KM}TtEeGf5k2)lX?tj-ny9M8s znd*uH)02~x<@EXCexR4ZrtEZ3*B5mtJyO^;N^GWGcO@y6AW{DQ;SSClzyUxyMj8Rm zc`MW3mH?7=a^_b#sG#{0fqW1}gseg=1}-d1T)9t5o}ALt0E(>AE{;g2Fl$9+W!hD% zTv{(LUq;LFHC{u&Eph3eF?vi5VCbNhTCjp}P%qBDM8IS zcWJezwl>SUb$h_1?7zCK2?@-=zyP5(|2)=v;Jx}l6c&1~C+XFf=XF)!_xe)G5tGHR zlA|lgvECW@;6avcr?N@E3Ao31@8o!@3CM<@`S(e0L`qwWa+T}!#SkSCmx-ay2=kU||=9{(b9$esxt< zV4Zt##iRs>H(kf2MEIwi++1Ru5=>;2M?pBGf=dHg%PQ%p@<>H;X6WrP$)9o{df|D) zbpA5;f=NPR1F9jH0~KxyOB2W$k_EmD*J1FGU?A_;a(>swys4ge7!W}bU@Hk5BJDD< zm`)O9yzc)@-ysZ+AJ_rr#lLfB03HI?KX|ufa)JzI?d^_V3TLZ#Ez-EC-+fXzXcD&P>H2_Hb!eCy*0iIt-LfPI3;9 z%SZhL4>bXn+K)|&37-gF6@JTX!SnukE6P)XrJo!P1;_2$T^R%RR0+H{(gu{%VAUQ~ zqlW~&{8^?nISNygxv`!4%7J!y%yf`;r`@0^A^|fCQLMM@&{P2UpO)T z>@w1uHy6O8SuY~KQfoaUqdO=E(2B)4YVf~=wz%;91OE8$L>C9&z55cMgQe9tdD0is zh~e+Wr4NK{FCM2@@{#xI6@zDaAZ&)&ee3C&`g+cvY#fS3Fx7u&Y3;zn$Jc-{!%3ew zaf02k^)lkX7$}drgH#zuwTWn?l~zAl^A!RhegZeOb=$U`dU@KhRTf`gTsHno8`3&< zVmpIC?nouFAKgrzr!M`M&wrb3%Fc*ih9S1a4R%fD5DBo4x(dcpq{=e&Ljx zmzt`URNFf`g`6C4ar()~F@#@mc{m47xy?j5a_!?sMd0P}pdiHcE`xx9;yguLuqjmhTbjkGR&DOIRgDlDS^JdGA}dSY+I0Y|EvL z=4m(lnS@7u;Jtf4Iy#_%AP)n>VPAstu3UkhgePVD(oG5KX1=x%Szkr(sGrf&B}-6) zf2PKpwiqi@VGQgqw0PTQ9C$$0OP%2k@WR!I2AlR6N+S7NVsQD|WwIX!0ZvKH!lC&R zw~UNCJS3cnWz`ek6rX?91D5Pj6;Br^5bz%_Q&K>FKrDmY5WI}Cva+sjgj6P>R-iU9 z@qP{7qy7mq(0*BN)HR%#>JJj2SAp3f%SccU1zQywYUZD@WZAN7*RLOvlaoU=0bk|h zJn>g~c`!)z8olpzx*!|??^rfJ+cFO`&qYp#fGIS8Y0)SvSzSIDF+7iePFCuR7uEmfgBlE%k_Bd*>IKiI_aE20q;o!;fsvN1|r;t6!QU4zC+&z$GpcZ%v@87xe zsHz)vI(7AXLTjSzZiR-Ph6D-Aq?Pc+SV;B4aqm4?t7XfVXJ=;a9p|?`p}Av2f;!(e z);+s-S5{R)=Ya=G6(j_n^st+;=yQmaK+?dTCqUu#y|GydTT9Z-C8c$!nf#^3zM>!k zDui5nujOu`Ew;|{!eaTL%Nk4cAyS;Mqj@TxgIjMfj)0aHBstRI~%54>aS0;${oE|sDBBR zBiFGA6o3C-DJC%p#BgFBJm4*TbN|7E2X_`8)Btu4_YMrO5v^RFairhz`jMd_>x+{G zk@q4Z=D>@AY)<;kxA(!2baiz4+uN(4A_E*i+B-$0SWQ`J&>E)j6|zr*1N>1IK27#) zUU@7SNg%@|cHgPv3h(+747Q##RlSdt3bOzRewYwfH}~TSOhbqo8N0lb+`j!oo!8q)TlFT0Yg2eI&n%-k0ycyBuiMH z&(BZoG1B;x_IXT2qpZGd+d)+HjErKn?Yk?tU46aT6S^NdIy#LwHPbZl_xsh<7;FU> zi9&!Gp4S6J2H%VIL9+gjY7U~Ti{O}tTdG+fKYM11JOZN@+_(x!p<8!MFwy5?OUQtn zI>3zJ=hI;HrpEfGznr#8BMi!Vk~S7t+(m5!Nc#Kt?{LX`v+sq~Uf4@&w zFe4M`9V@qfsyoO?4o_sta2Kvy}^u=E<6g&imkv z)~;Izcc#^_o~iQw%(qe!%_k1P;~<71rNU!EtEi~BAo@s9uRSa%4~FpibpR-dOuN=Z zgJew{YBM?s-8`2%!xUlEz}9W1+q4sb9L zCA??0qUPAZuPt`5Pcx5~h`=7^-IsBn1B(J|KRqsRUL+I_$ZA)y!@B9*gHW@{NAc{~ z@w~skap)TrEFXt{U6yPc1`QNd;azECK%RF)c|fEO=bK%>Bux&7vi z8=DKMg(v{;#F-%z!#2<0yhA^XNY7vx4Y5#VqIaSMyguo=Tx23CE-4 zA){eK?G>(UKpd{Dl@`7fvGzHUpTNo>fH-#eu=T}*WEMl6@NiGCGB|fIWYLZ*qW8aN zch5F&N#E0?srNpbRx9C^`}`cT7}2#IKvZXocRvv zgTw=3k&il?EYQk-CnAD>8!IWb4m9rNkV9gC^zhDo@@!;a_};gOIS&#sL|aHjpF!z~ zF@h)wAp_rnlo7J}0LYFJ+04!RZm#1774&O%yk(sQ8HNh`|D2OU>YQGva!WKA=#8`hhj3Rc@^5vA2`NP;DJBz{TBoaktS z-^3YANYZsGmA;Jx7bH2#%4M+n7&FLvpW%=IO*;K56-DOdD}S!Ze+72I`Z0_FbTQ%< z*7^{_flFU<5q$QSXoYoFR)c^m%h?>ypkN6oc@T~r%5V^?$RQ`NlbH1&m=U;bRO)6i zAt>yKy+c@cP)?5CV#xp-PBj4bclbZJr_&&-V8D3CR&aHYchb?)T2@9EBcn`*6+u5@ zq)~qcsnK)IWPNa+m^a|h;N5LUP<8=Yv#xzXMH$$r9&Zo-2`3+?M&J=n$NwDfmj7@0 z+AA;_G#tp-&!^NOD2ED}Y+;R3<2{{fd{!hB{D~3jGM<{?j9@ijPKFdLR_vE$ENl)yf{t5P1F%%~d%VW?a3<7io2f}&4y?d{W%Go&NKv?z1 zHdwv#tB4omO0!oxrxd-<2>7nlkWWB>ZpDgA;ESW(u`Y^AO3$4=;c0eyin-6_Y1NtXi!i`dpoD6W~%XVC#NY0A-O!ez9zS) ziJGO<5&E8 zAnhPE1U~iW6Tow@h|}ny>8q!zmI0#yEEyqqP9DJ){7Q7o18(K83{cTmt}HUrsNHo^ zU7cSy=WA6}3P?aq$^PQr0-ei2aa66!Ho(+S7!XMrYUvn;0gVj?MH#JseRVn5$NRy- zogE#cut=P*5=079D4^&cV3bttf3yf_9h)4TB--0;(^T4!@@oxxJFsgi1F(~?JPSJ z&{9SI?C$+(wYu)JqbTz2&EE2m!`Aj9qVCybO*n$wOxsQovoC#!`L%O<7Z}N&aDO}|ZhXr?!`s<7$o3Onwjp(YCiOacJnaDUG_<(VL@8}Q)n1}6c<>rRO&;85u zQ*EZw0zjS|9Q(zkK_8J`rSa?A5Ed*^>cCQ=+2t1!p}7~=m~*Pc<;#y-u%6V=knp={ zP#LX&xj>)!9g%^6&@->EK-!mqg+eppSXHm1kN~_6=x|hZ0T=uox<0?IsTs}MhBfAp zgQizEiP7C&t#=4=52Dm2a{%~*Gn|7+&Yw+cYEYXV(|7P^nk;0BMBIZ+O1!eX{FwJn zC>F}XB~WSbmFM(g>YWhZKoPs68b{7l>+7ptq~J#&3d#r={532z^aSHw6$d`*g3(Yi_5%3x zd3H6VC#BW_6yS{nv{JiJ3At_fS-tJR4?C(AU3VQz6H{Xnbo5EAR zK0bRwl;8oO+KWi#=HcmvYj#J<2jOHn;v&5G*RPsIC0txwWXV8#CU*|O8W+TTlW*_3 zxVjekGN)rsw{G1+rD^``YEj2noT~P-Y4!{#vWaosz0T&eT~ZS0G!upjDn4@8Sy`-R z1mZcO&{zMs_6jspI<~#L2`efoEp-L_F^kV3ooW@xn{ih2C7=2Iqc*ffUj@46rXhYO zWvFj&uOoJag7ctI`joh!;L!zlie@z5?~Le$6J|P!6fbwD>&x3h9!^k9`EC@12x5)w z4Kyqe3WXGIn89&Y9uWW?3Y3|T(ihIjTxg3-4l0xf`_cXa*$pB1{>jN8d6CH8{_xQq zbch<&!W^QAS$Q$)THD$>Ll%6|ELSsEOy>||=L4N=-{^{(C30M!_Ag5e6q%dfm0JbbeI~sa2 zv=Y!r=_@RjY2@ylG=^zf(Y95Ku-zp%|nl_P~oCx!qpK z5a9V68|NmR-ym6oQmGs+mBbL4=ldZFvlGwN6`0-nP(2=kz?jn_8&}bIfhaUftH&X? zQ8Mi{e&e~qul$W=#p8q6ulGp$xwg@^x3?pu16%`J+7QDbSCXW^--K5~QTY$B-QaavSMNF$d zpv#y|$?iK=YGA;!B}atn6tIA+u(tOR#r?(NH0u9IoElnM^!S61+&SbW%TdT~);BUb zI{NDu><9TOs7-g9TVOhvVNurBLlE^1fI^-wL;O1$DLsqy4?bH;Gyq=E5?4 z^w=@tjYxe9SOZ%31ITZ&4-B$>(B8+zM%>-tdJp1x!aZVvmR&syvz(tDbVrK?(Gs<{ z{{o@cJW(kN^LK6c6dxzhvLl|N!5-I&OIx7n(GDt_;iDOddWezHe@?((536Uv*lts6pl zW)~$ABLdcoZ|CLB8gQ2MDcr)^*VeX{Vc}t6VF4NzMqw-Ugz0U)B_8z*8#WAJuN1{m zTS6d3Q<)W7$L1%BWTG{;XY2=G0_H>a#hLw}o$>P+E5k(-(}c$9KbNezK|pr~DKV4`1QS)VJrfT4JWU^_i9}JG6s(UQza#Yuzty_&teujO_}t;{j*jzmJj<3Y^}2RVaqy=s ze4VUpba+n1B9G8Ekhmn>hO8FM3{uY~P?pfdT4OCyDnh(3OH6blO=y70sQi6N(vvax zKyMVhSZE1hlSK9+)PfJ^*UQTRjtSOv>Xug*T1;uonD@_}zGc=k*CONgm3cqaiW3Pm ziRv~Q2^neLiw}iAwLiUnecC`pJ+ES~F6##FFDIA38t^?`{p?1)w@)s|*=<|rnLBG| zCLgygqHXQHbhSu9tX(|W-ji<-mn~#~f`Wtz!nSw5IDi@wg2%Z6fYP%vGLWl^qw8Vs zUK5!to%e=a-U&rur}`h%x5)$jROui2e z$^gya4CJiafV9JDtZx$&)6}yl8b@{+Ny*02(uCV5?wNxe6W+c10iZ!Mw+WO46c-hQ z$1zs!I}`5%x1)*#Sso9MLWBONapl0Yv@~DeqsTS+W)5XroI4lgT8Ys-V_xDxr;aok zDw8=R0f29NpelR)`rE?mU*+(%MGuZA1>L#xt+#g?i3F%55vVkPaC+qSb<1b3p?HU( zwGhQG)GQiMRE9t=0d+i8?nNG|0^Ho4P_iHm13R)BT~EPYL8<}g zk5&Uti>M0J;d(x73sjA(R%a`82tx=>9W7!^*JGhGv9ydxr{dxFwSbpKoIiW^=dd& z1@wPSj#3U6S1qDKb1F~&r&eCT7)*Vi{SHN{`ipO}r1(=F>{bicq4=REDq3%6nydF4 z<3<+}1B?+hNnyJ#mAH0F%=&(L3LJWnDP-O#1D-M9q~wI6b?F!Aec%WD`uJc=d1-0d z%a_CW_R!E%jid5Bo&%YAQpEPOAgUgXFka!4Gb#Tj$9p-2OgtjsQ)e{gd znz~e!W>3W!8q9yi3jCHibOA^nLPAcVVSq4^UpB?7#ci>dXAu2))a7UA5(F~jfRISG z=_}~Z9&g+~qp&ZJ)l+hC)F*qzm4~w?mp4-4zGql@ zcWWzR({lRCrS0-Jof_cj1L#iU(a2HXcokXhohwT?lnr z=(X}l@-N}=DlIKYTx-RJuFo8(r$E|>j?k3HqC>BYQTyURCbb%6a#1T?=&V6pfl-c8 zUP9USKr0~+1_mzzAYqGgp_lAgGqVPuHFQ^@5$O{|%}ci&4|_+oLN)gH;A5^~J22g9 zfZp4hYHHPB^XOQ_tcSlV#HiK*FhN6ya;(NPHH9AIZEwIOzyq+dvE>1?04yr9F5iBX zjOi>59Uc2_gAYJ!sARTwb{2h*r#J=yutPu3w)et!WWUg$;`ESz!R!nFa9f=9_ZaZC z`GGdS447*KDezw~7%A}T5CG)nPIezd{TL95aNelh3TS8C=BFCEMn3dW9a3&kL1s12 z)^FUXnPPYp2Wa2T09;fs)^{qo+7Sk{Ze0K-PnxblA>eX`yMKKu&2`l{qM}Cr16e8~ zGxO;v`PIokx^P>Oy%3KD2r>MRw6+Cs58gS(Z*kzFRMfWV(cgLt3j>ZADLEZA^_ev% zDIfUI4Gp|ZRB8F{?znUaZjW4Tfd3JVv@|sjhtvL<@WF!#>ZDN{6ar+3&=EaC-asfh zbQViV0inkzb6*AvGX^H%*fAm#hTFI&PODN`ftuks2F(M*U}X(Q%^}siPPIpjqN2K$ zi)#RP4zc*m*TKvTp~zs2Jf91M?a_B4sRs9vrE&AVa6%c$1pa4-1(na?Zssju+vIFpHJCS>n z;I{?AZ-^fhfe>y{F|B!K(URAM3$C!-n>Ph1lDrNZjEM@M0ttVG?wB4#&gA6ezn5Fw z)60u=17IbPjN%Ls1rd%C5(CuxqW#oUk=1tg_v^%|#sH;Bh>0D>xw3(Y7c`(lf*E-! zLK^lo-=KIc?k9>{N97@usF$CIIuUesz;KATtKmtoUthj_QSJOAMcZd$4v&LJ-b5fqEL;;qP~1E+LO3GUsS zi4lOOYkp;M8Vf=W)n**3)}sjsoaku4uEXyHBqSu@GaqI^R(%$~jv4IUy_={`v0>2k zZn6JYPZf9`X(rlF>(Q`}=4ix1gpB-&ww2u6+;O(+(WWwqYU3=5A-J}PBx5*6s-Iy{ zwV-d9A)CheXWXH=%l3y7D=RA&ci&HiW5?)dXmGJn6OKQ85dwA%4mGa+`fH}G2hdy% zfAj)A8`}UJ3=+>9WOiMh0&Bu9)X`8-E-f#&LL?VjN4ZSS&KI~EEXaCx_Iwl?)uWaT z?azcO#rhy#fxySGeQ;((O{)+0sQhn9DHGPXGz$W6vF+Qtu;_|0FF}yu|9*@-B&0MM zFX7(Cx~q&3&~Wl#xmyY5r6JmM!E^7?2@1OJE%GqpCs?5B!_l9{9W1)&N5tGvU}uta ze1S?{b>^QB^_b@jE&*yd*lzi=JC^-EHQD5LEpcYmGay9eD zjAYcVum&Dm;M22F4aG2c7`)-$KH=(?rY4=gmbM_&3EVauG$|z$bH!1@9sX$qOZj?kbQ7Cl(6*3;Ve* zP8~Hc(zL1FqtNdK+Z?Xt+=y$Emb9E-?=fEFVK=Bd~6eK;y2xO$$Dm1j= z#v0CLbZqA5&T-l&iUx&;OQFdEhy%5lQk3C)#P%gW#%^BOObs!5H=H=;i;b6*l#KRU zOgY#A6ao1X`dn1;nGgpxpw@6Wd_ncIFwgC@Fl^|-st_rlip#d|6#=S%`wsNx*bLgE zw$=gB0XhjZRs|xUwY|l~5t~sYVJFo=GAm znf|Mrmu3NgLABZj*&6a602XARosjJg4k9cI*r(QhuBp)h+<=f7cTc3~7t+8s3a?+} z^q_kHQgwWM5J8V1TUH6eNZN0qY&T%?HNdxabH*1-pYnYpXr~pHsPS(fjxB zVW86BDsh$oFs7jdKmtz(5gz)TRS!A)q74C(Q_}i?D6MKl<-Gzq1v`JHb~A7$eu&mL z7w}TZTS)pVOJFB_(r8!3+nO3-At5`U4U8gK{9mQx=3JB?&{`zI%WDd({q5T~(!KyX z1r7O7Pe=QWDMCA<3x7$fX)q}J4G+cOVuvnIfm;V+2RBfMcmQXhOI*+gs1b;O5VaDG z1g%jJ?|_v+hKbdW{>;?lZsDg-=Fr9=azOT;aryFV*dO@}V4m&ZkD_uLA)*Gq0zIE9 zjo$=4`9KbFxN-20fKW*~**|cpojnU>yAqres0tI@0}v8Y2ksI*QnT3gBdq`SRcx<7 z)!Y_J6%dZ3XAvu8Yhx249??X%u!Udd2 z&?x}L6q-_0GT~K6@xzvE2P>R8oCCAZ4=?{cL)CT|H_^)i%RpFzdzLN$eBpXLkPLCQ z9kpPu3JMC~!;d}?irXp>vpR>Hb#8ju&^MJhH6ot}nU#eLjzAvbv{Gn}g1AHAM(y}G zO3hI2kX&9Pm@fIxno1#|$y29KA7Sm8mq5OY0uS)m1pa{_W$Af3@=>1P$pOK(pz7gTE0va4b z5d+++F;fLnp>hf5i_d{_Edz@Sminp4zY(IaptAD9+{`2(E6xpc%x(xrXkbRkIJ#^b z@|m;n6`)lS@XuAVeq3va8I`C%*AzsR6hJmXCtDqtqT;L#>7uBIjyC)*M6!61uC-Gn5wI*L;1g%8q!i>;nBkI!lqO@oTQyQb_@@kIeYfbcu^75 zx@c6!Kg3sDLCN(-^9i4#<~*xtQRQoSR-T<#4{1Y`zMXn27MD}*oI&H`)@ zcoa?Izx^=m4HL^lIB9hyya>=Av}A}qVL~Q%k(XBA{NE@k%{R0XFg{$cfi6U4;5G$? zua1jtOn&tt0>L@{zWO90Rl!4cfA*Sv zn*t*u$UR#aD6ShK^$CJC#xGzipf8Ak>9Xx2EMX%U9 znyACsvu&OS(a427X5~sBkYFH5@SvK5$GZWGTvb!EzG%DFsZ-ruUH3ynah1poodd}Z z+anIKWZxhBe#rrRB0>OCgF(`yJUM{+8g3=QId~EibF=Ux=ol1#%5Hul1+=maR$D>2 z?%a8_5fZscehaJ(N^Lj*c<{n(;lXP&Gd^je1k2lhcRO>UZmu{)t*8*tZrpVSh<0pj zZ0)rbt5&fds;ZUX6M&yd^d98jw(UH006;mUj|?J1 zCK2=P|61bEqYuT!H_?@d26g0Setv#8Z>~9g3%Qj39YLrDAb1`pD$nF(9>gysfC=-z z+FpS$($owb`ankg(TLCL&sObw1ZL@>5;7NEcyUl?VE#Wj z?xDog!>{0mk!n->eftXFuS(v_;0oK{&%R<53)gMhGzkm_;|h2lKpN6l z5VxB$=npLNlC%&)(~G=Q(c1b2mWrH3Rw>>V&uRxxG#RmBPNRPJ`q!jDA!|hm*yzqEWUF`$#bTwg3|^^?Ew7}bS&bS zBzJ3qy+toSC;)P!2=4gkX{Cn94LzqPlgoPE1Y`u?Jafxs}R9-fPkytErk4+8nHmGb{q|MoFdz5%w#P`=Ad z^41g?WNVTgb96s^S*V9vmYoc}UNBe#9?cFdx-&R4||@ zz@2+2WpcQ)E>~efi5+zVWGxAxG4TOuxDWAPC+HCfx5qByw&T^t!lbrFX?P{-D=6o| zl=1KIyn3^pRzLd9#O0C?9~_4wL2r}Bd&i;8a98w8;P*k#q4Dy^4|Tv}@G*jtPaTnX zBhj|N_+ZMXa2atxzzG{&odk6dnM2_HV5Gz&+vqYmx)blD&*b|9B_djCYH}S9`XPzY zC&bnCAbuf1BnJ~35;ULxHSm2u;hCz`H~zxF4_*hchVm-!tN_p&?hFD28pM$G84Gem-o1M-LHB?JoVTo_ z6|IQ4X&n&@1T~Te@BXac)}8vXxEL(=2W%m7nd)>aJz$lB)3}eU0%9QHYru0=avchZR^uh3-mu{!5-51+ z>t0@v5aVVGq_9|KQt<~y(eDMW^v3W{08`-BbX;4ehJC=g2_cXB${!vPF@Wmtg9l7& z*S-3e_^Bdi=)SQ0JM(bSj?@CdzBR(3YxK{C>GWF!Bxa<9$MB@J$t z?-zRyf4H9>W?Q&E29~P^M`uG%yk1yX*!@CklbGmeP-{RE67KV}=^1yz!gf$!iHbT0 zX8~fd6RFC#Z^x0F-;;KCN6CZ+>Bgp!U==i>rr zq@fQ-6qJ3>=P2O@aIImaP4LI#m@`cD9eTgS?p zuv6fNj+!{`_+IcAprn#B?*}7cgyN^V?y~4Gq65l0^g*OiH^Ao%{nqBPz68w`dBt@BuztYnFH8U5T{?jih()&bxtvmhM4$ncw;O8YBh*g z@#qd9CcYCj6?V6Yvq(6A@5zOkNQ8O*a)-B3_HntovGDq(|A(pbfXli6`uJs&orDre zrOaexCL>BlMYI$Nh0IiF*(xQK$Z8uUBMp(Vq9H1gj3gN)T2@xi`u9LE4QwckUAvE)gFV zP_p(F0iA(DZy<)~6wz9iEu(!G$3@diryV`Z_z3?%Iq`Skk;7>(W@VJ!qD^*k7xcy3 zvP;u+qhTQIhnL+73Jl~-C|s;?0hRG^n29LYtJfnQFfGTTcICv;yTeB;)HfJMXFtN| z+z?Ir`BXGCF7PuM>+*53xYF2m9CFx-Y;e7C}1{a?S-53)3E~)MUg{>8Xoy51yaS@khQ{{Z^u>ZbgBLgN{ zgTMUz+&}lNU4kR^$pMYgqn*~RJ6+coFNXHn`Ddi7%Ue{>jW&Lf?$HQuNtY_hB*H6G zt_Uea37*|rq8{&l_N-Y^erEA|r}hRU4K#_7L8XC*ibyNNslOukh@gmhlRds9dOE{b z>Zq^d(89$D4hv-jZ>fkCS`qUH@>f(>S2J7W1J-u|SN<0(!m9MJ5{c%PcMm|o8NPt6 zi5w0n9NZ{n+RPIezc-)nxcBY%G_|4$IJlJVKsMe0hJ@O&PTBB=U(m4%bIQf&wql&< z(MR_;UNKnx5A2F?0rG}L89+Ou(Oh2u3Ue)PadyqI???4$Ueb%&Rpo_QqS()4>~JFI!Q(10;1RYS|Z*?^yI=INfZBq1-PRbp?&ZI{Ay#MvPzz3LR@7(VNgVbe;Q^zJTX3 z+<-JJ^bXK1x&O!YNynOnC6G3ILQ8TP=!_7o5Ty10ig(3p;8rdj&=p_E#ni*jN=u!b zk}g|t4(bo~Q0U$JwsHSe`Yo27m>x+Yr^!RK>q4Yrc(9&0@fw{XQ4Jo9Q7i1_L#M=J z_=IcZMnDeVKPu${UB_@DD1ma}8RIuN-hR1uQ|TxUMj>Zf%uR!fgo?(!CMY7SYS>JU z$K#@+m#LdK3Lc#M`S+z$OLc3rc{s>eRdxC=IgSDC0rK)k{r$sUJfwEP-AJKVTx@1x zB~x^8^r%q>Yh)!sYW%iM?r@k|zEl)!Y#m0ImgnAXb#_(Z>3*B8+iUB^pQ6A`B$eyNMnFYHDia^vOgNngh-NCPkPND?`YeqJb7HvW8(I zAs_#F%buF5+&+k95;w#~HG}mXEiIpODRH`9KK0jz04&|HV=70M4^;1lEhyltl_Y2! zbvw3h=^Q_9Beq4Vg{JoS&#NEB9K=<_S5$P*F!@^jvijr4 zYsg}ZoQN1Rsb-Bp)a#w-ms@<@6E#mbfnh*Bi)aw~zyMU<4&3~R#n&YusDEBHPSkG{ zCA=We3F+aX;58F^bl=3JelLij(L|2MBRW;`$7DJrd}ZPu1!fZ zaaP*HKS$>fnF;UN4NwX&9UtQw51$3YFsiV+!VjBoTlOUh_ zosf005bp{t1~=T$L!vj9f(3v+^s@((y8gbRln&**biK*(ytnl%gB6>p=&nzV2nKP_ z|JGKLX%Lw&0Il$5b?)1#T{}k7Lj6!I9AZ8$sjIM}Wc&0;GhhJ)J0slEVV*e;J<75m z21nEU!vk~YbL?_4Z#rg*(Lh|`LZVF*wjp?2dx=arM-*QjEzZyv{A;Wm|Gc>{MI30e zW4vKH*IJm~y9;9;v$dr}#v4N)u&xoo04acRFmV1Aq+P%aJvAsSCu!2HVMsJ{goPc0 zw6n`)IekGG3(52dlZjpCwoe^P$)$XW{0R^Y*e|Qtek*UBA?Wq8#Q-HSBds44nNhTnEXY8rJ;bSO@(~( zyb+UgmS&Z9=NV#w{iKmuz5vWrtW#Z}<5Mrp`THKD)}ypg^ZC-@ z1;Z&~^mgdhXLs+Of-FvN{Bsp%@4x#Q)=%fYB>E*c$>J1h-GB8F=R5nkK!j!^c3P0NsJ`Lx^Lh5;!6S%wU0g9 z$Tv!YcIA@tT|LUrR}b3Qe61gfeY<1K=OSbjeR_@6}6R;p0KB;&8A(Zw)#EH^w=``@N*43pl-^$VgDYF*7NM!*`93JFkVmx#yE(1}${(a5#=ed+OPD5nY)m2HKMXoLpZ!+VAchkTv~doEAzZbU0fARW%DWr?@|Sfxdq=E=v`Dkv41my9>-PSIKB(0 zNeoQ1+Yy=PX*OQxeJ&tnlP1Y>@+0jG)!tb`38Am>XqeAstTv!!Nf)wSMkT0;YqAEa zflnW@y>-}a8f$qfD_}!l)&c?MfSj&K5n5qrWnzit*4hs zg5;x1y*b7pFVUXOsHOQFv?*iz)u;+sqK$NkX1a-ZOUznjXQw7O$`rm?1`_C=na^mV z`h^?+c|yx{xSW4M2??|0O?bUYPc)j6NVwSguQK&(0J3)J1bo#;Zq1Cv6kdMVk4-Lr zPLY_1z3#VEt@~Le@8#;jXadU8VtfkFN@bjzA59lN&ff4r+twkw!Xgn>_P+Y`YGO=`g7W@1mKeKkt>Gv57Z z6h$T2sK3W@@#bO`mPdFUT5ZFo(p(iWvwTdvQ32_2}LE zIphSNm@DVoXY@axEK7wA4P3Lv0ld$bxA>ahm6zLn(;`bYy{NAJvuqzXX8p`7DLK(S zV%xW_*y!PU_|k$2?S^x{@1C7DC4Eg-_4`h*<ElXAl{mjw!sVS`HY>#XVbV{Q!c{z!RHdW|KOT{iR_Gt9yTX(e z0k8)dFU0W2hPq`)Y4{^BSNP1Og)<=`0r&l!g$uQSm_!(02g_jQq{Y6wM8M||(14wb zCjp?*z2y=vsi2LZD)6gFWh%Cv0_P4A=E*W7626{TMnBuPs^X0pOBoxC6ev?u`DWhr zU3F=y=dTHvvjSTYkNP}Y+(34iIv=h4g6oO@rW-xW)Z5L^eJMDNpAI`5UT!%^bi!rJ z$(MOLU@V4g8=`X29u2|C{)TH69;Rw<=DiM~X1}WDJyaz~5K>ZVA7*?-#$eh<8C5j;$(rTMgPrHR@@Z3&<~IK2rdE@CGT#FhpF&ZwExiqwiB}*y zG;2=6L}WaI3h+&+Kxh@PdAIq zouNko-8A5R#(oCm9K)K-$>JFuL-?jnY-OEu`*yjBQGM=V$Bi4idDQo48IIyi0U4i| zI3%F4i&5Dkz8oGXI1)ZgxT(iGoh9{*4zL``LoX%m3Q!GYdF{cO!j+8YD&p1{2;;z% z#678wXWqN!OvfmE#7D<|J%|7jiAWuC_^>E$IqX;k>9W6~*cN=n?+EwSnEJV@fq2Ij zM&{3tUGP!RwMuo!H~i?_nKR>)k{+KJv3BYwlQwU!eS(yS5IQ!@l;xS+P-+ zm!p;+IH%{mkDPyDw_*h-HysrOfR9L$a{2P!g}2)bVzZNQ)gV$56v^{E>*utaw5zup zd8Ac)SywVHY5yl(CxpqD4f8?&Oj`m#j{&p&Jl4i#$bv;J4d+uXgH|AVwxaxsAgszZ z3mhGs6u~iZtpCTtW#NHZ@9-W``Fqn#koP&$8L_kK8$EUpu4*LEECXz{?tQ~<@nXeS zvzw_oa)@BpdlZF0kR~X$g+44xhHBZ}p_kH{xkpCovoZyf7a}?)Vi8 zc|Em=E3s09*ATykgjGdiyAq8pl|19i^WDHkttPi^*RE^Jerq4ju{^S%_Zd?Oq8Oz& zggaBxGihW6@rkD}W@^d!?k%bMN3$p?LqW>rOWnZIDVwbWwNfU3bjGy(iB&1AK-*m; zGGK{vjAC2X{yo5;x=LDF&ahyJ>0{k~&?0rP zDXAmkkDz=IgT<-3fT;f!P=-4pYN;19p4!k-b9u326Sr~pGBZP>UKGPJLTqsMK<%Il zMv&zs&q+9bd{MJE%93RVjn80%{{|V9u?L64cEt%yWC)zAot6BKnoqcZ$xsBJ1(tUk zI$ryH-L(iV-4z?IsC~@Qf*wD5q`-CY^2&mUCJuvozcbMg{c>KHmKSG;_ysfJ_0#9I zy_8k3`AGhFm`rg&sb+bYTO4+4r9NzKbuHCuQ#jt%)bm*uFT%bLAz*8zK9--}y=6FD z1$4M@pVLtS(OoN=$NEgTTspO;pN6L951OZh^d&S0dKvj?uJ8%XW!Ye|+p-&mQ+Jv2 zC2r-JQ;+X$#eJmkD)snT5( zRO2KGGR2vRD-=8%Tfi0EU{>oPoVA)v@wV38>rkJ= z)mI2xWFop)Y0BynDopH9DvUVyXX`TYiV~4aI;7fu($A_(LY^PzsAutq4y6#qwj5D6 z2W6C0Vzsco5C{2EUH*FlSFcr0LD|guc_j5wNAH)FlpSgBtT)9qkEmo#?)-rtdvQ*Z zX%^-FSJPfVVk8Kje6cr`I*YJ!6aXZGF!T*??(j(a0=_n%#$kP^sM1_&BLLj|6l=L2 zka$v`Z6>Wd^JGXF5J9){^DnNO+FVJ2`4*d6OP1xL=LZwpK^ADGddFKyti(!$oSYAQ zPui?M+p}lSe|5QxG7KFBH^3IEnqO2WU8Z1U8FlQ7mrtLXs|MosgOp6YEH=bY@x1yd zQM-m9f|=~1`|mA6Vw%SDl9AHomh)|?%bsOa`ziEWfL?I06C?q_4eg7XU=gGBZrlh5 z5`pQNnLvS5rVkkkI|oT9)3s~Awl@tri|J$}*o2~7E}q$?w`5GQp9Ex2K~fF7$Ul=V zT=-7^EHGIW2MG>VJ(p8eTH1xBz9sRNLvbpR$oB5rH@Ngs4iC0+3UB28&s9b> z9r@4dsfS4cWlvrR4*=yQmfNz6e2XGEetNO>Q6dg8tL}+hVJLlmXQPu7is8L`gPB#! zC~A7Mo;;zVwT7BE{PS#Takm~l*l6_><{WDW9fyvcHsNZ5D$N90X_IN7qi`?_y3}CrqdUNF+#14y{U3o<6OKmcZsI^E z$5>i2MvXGLdg3NUR8q1*rQye9S}x%iFmRy1 zpFV8>LsdMP&F95PAozY@RY_i+=*Zw^AIH$7*cNOo!13jPcmlG}REf#(k;1!$WR?$JPUDlNAtpI)rU6 ziW2>4ljo~|RHa+Kg2kj;<2zx%%Jqwt>ukuf`bC+Ag`YF5eVVVS;RNwX*mokrG0`7y z5*Ien!_@AXZ>!V`=YQ&D36o1>{*oE+@d-zq7wy1LU5 zNe52Xci+CKYyBl^S?-J~*txUiMQe8FVO^s{83k{e>NcZ1nuS=OKUWr=_uy2Xxm0?K zp6yzZNDyk!UBq-?K0Ddc=VRr6KApojBsd#<2+}x15#FOs)D0QhIdu|jr&KP17}-@5 z2SRNNEs0?PBJi|3G8+i#-Mx@`7*%Yp{s3}|@tA*|u-BgTtRnU@mQeH#WTf97ojqE7j=LPX zzq4$G*SYzh)*U3q$bgud7z#C>M*{x(j|2;94upNG8&MzE3oY$8ZQ{|!XI>OPeLC)? zQvT*-Bql=LfLGTfIw8zu>)yNfFZN#%7iU)a?Ag7WwR;baYMrOo#rV{q^| zwP~}5dh`SOobD9YCZ}~v-1pR1jco70cOQ5D{4iLb%wb5Xl%t{(o4UA3p!|mm3Y(Uh zoh>||DC4Nfetxot{Bb2n&(OeV%|0XVt*F`Fk+MRuwf8}yqpE~sLZ$l^obau=L~rKI zBUnX*fE5uz??`V21p=A)T*9dpd2kv&eZfPfq%?39aq;o3{_0FuBLI~v4z1+KY$r-! z?wRp$OVQ2`T_Awx~e$FN ziLD7;JNH%Ogq9c}lA%+h$kX)FIlaG&J@a0r!yov#let7ycet(xSiJahb0?&h=KAKJDms!V0&-*h7=SW zUfJ2w}MyO6v00;jLO;G406FqdvD3Gt8qw_D0K9-Oll=x6s$A0z`;3=~s)%tAA9*~xJ1H<+tT|t}(zP-e zF`5+o4;)y}bxvN?!y+;tX61{pX>G1oZA_0e6b&bz*l^xt+I!E@iCGXQjHj8y#*cpn zV&ZxOi=)L1I9{H{1F)uFUF}GxZIh3Is7L#cx%mYvWxH#j1(6 zyELX5J#V2q#3U$xT>ii@=HGNI_r}^Ol(tSB`uxc_^W?UAAYe${lQ`G<~$vaAn-Zg{a#LH(+p73SiALvP-^ z3EN59UUg4%0sgm&w-PZIa_s?!oobuH5bgEua~@* zDF_^8UZ1xsZ#LS}Y}qP{ZUI%MR#x|4*Iu?Ty;zK zt_SZ>#eajk($OFH?|(4E;VN_tr9Ul@j9-sdx7m@@qL_|wbr#JHhlLfG{;1a6Vmhoc zg*6txGFDfm7V`goIY;~q)s&09qw17GCLPJJSwE(CK#p3-k9pJ_TTa*or0ZFkH(j4q zIM$PgNhGtqZ@tn8xkpi(HR*79-?^RkuscfG9z)!CF8a9RVjTAJ<>G%*c!f-x9u%`{ zzi#EU;GiJ?pc#GkFT|y8WHdQIQNKX>P!9f&A?oS}ewEj{6pS}wHG;lJP`P&Y?7ge6 zcyEzRLmmV>GNY5`Vi`HPag35YImX*`FeA(XoZl%{Ck>nwm6YT}GGtZ@y=%{vPh z&Xb8|@NU7?H-C0`&0lM`VCAY+`bQ#_UmB_YHd-ECexUXCS)N0We^EOgHRyPf&%-|2 zGicg^K|~KJd-duf)dBUFR)!I+D;H3kaZ+$kM!CkKs_-wEv1o_%FuQB_gsz!uT6*pW zTWd1y5f%ho&fIrhariTz!ry?gh-B0-kyWPuKJu_ur_Y>GA2=|e&^o9gBs6rGjFi3s zPlAWXoBuXo#| z@hlIDzqeS!@J4&{L7H8Yp0CctF#(_j;qYSAJCUivQh`4pW!X%XOgZJr+nZx)WD2kg zwp_S;^eg)nD~jIlc|s#QwFR7vc1(xIU}ri2*YSCQOQW~wJ>mlzCjz^&3+Y4F|Le)3&*IxO~jacjMo(aW`E#YTg#I zHQxmq+w7P9z4lY|6GO^R5gMd_w#p_h(NRI$?#fPkE@4E1H5>h7MG<-oOxQ-8G`PPz zHqLOTodv*37ig|>J>7e}Z*?Q6B;|+{C2369%-L09eI9Opvww zaA~{o{&ZD$RO-@}mQ?nFux@#=gF{@^I*G&jgVS7Vr-Tc2y=bci=FEAU3pB8bRZOr@Isyn*MXN>HXq=K-3`o*mck zsAanQ3s&O7@-eQ;?zY}P4?PnN0q(d64=BAG%kDOpD2mZ7EC<=(n{Wg_-UJ#nx9jmzp;mdYvn%H_9+=oQxRy1s#ALT>@X z5nYf+5VUqp3CECyIv~2CFRhpxP-w@_nJT?zVe4gj^ava&W(?4nKrZaGr@vVy-^B#A zDMmrGmFRC&?!3qUt}fs!6H}L;^!Vm|-%u_B#(zR?3%3_r5TUT{Jl%-Bjv61H)v2~j zmyLhBS8H-U;3tuxwQPF+bHP_5sZzpoEE#|l(3ImzpXHU6F{e&3H6d1v>gRa;eT7+l z$?YqkI`lQ&yGKYuq|=<^6P_~rsh~jmOOIv}ZP~yqNaiI?o`suKfOPY~S;O_^(Z3y# zBQ|^7Ietw>V%~*ml+t}wdievBAdz}^+B3m{qp4>=bw=+Yv7;_<&MAX*5HDde>>LUQ zgPDmB1Zn;gZjM&=8is&Qf~8xyu!x@8$bLV`anvD+moCvhXl!I;AJp@oG^Im}KHmq{ zW;q#|C=sS@xlSawbz_cUy(mj@{r6Kw^T>b|P$v{DtTW1Gx$x?`M=nlIqYve%mB^LB^T*;G2P4kw^*kA#F! z^{-;Crf>W+d>SNWj{Q%3_Z`(ML;U?~@Fbz}LPM$eN=usZl|+}hSDz{?$1$-6ZeDFX ztK!U*4rCS;;W!vQbm)E7?*0$GC3Hvm-t=KuKq%OqCfbprY_)Jb!0g0l&m#XQNp$9+ zWYF5gtAV4&uxg&fv6u4LuQ?F$En0dm(5ri;0m6M-zvORT&&5eZZJv2*a+@}7vNW}O zx%c85rBMJX&UxcTq3IJ5v^_!z$@R=AqEiQY0AXy>6DC93awg$QDrmfU*H__bTU$nL zTw|v;o#J-OmUZveZHH8WB(FoO)~(Sz#=wU%(Bpq$I$u04yw3u3CRDH$1mMOSfm@G{Y~eXN?#h)T^Eb28h2zQ3 zb0X>6Aqh{K6qMWucjVQ5p%@^TqIQ5ScXVA-|s2V zhnvExm@#A6-sXOxp(Pn?Fs-Xxg;f?3as*jKn~(h8pC-^CgI<)E(EZxpC#%JXFE)_o}K& zIQ$WY+~2MbZ^Dh4{bYSG$+&Z@ku4nAJluq)t}q{jv3{neJ+;65+Xbd(XkwzGepPLR zkz!z$Oxu=Gz0_~0h4eQ3af-%>m>9;D_vJl9kc<9T=EC5%#1n*#^b=X1NJf2C^ZF9wihz1xuGSY=~@iCuEn^H$X}CLThk->9#^(lRSy!NY_65 z2OO_f%i41G+_{r#GZ{01K}vZ%P_{TL>kJM^E+D#7cBfP`iUl4zEFf`J%;kYx9Z)S+ zt)i%)!}6|CPNmEP8qV-l@?HGS+OuPHb5YBAOdwE__QkY72>l?1_7cy*+M(4I6ynqYEt1G7LhgNm_QfUGJ(lx>wil+qA!bT`qy)*$E z`J)di#1~vJJxjvpPOV4g!?To_knk(vH@9m!oq!!$zvgJtNwP3+1JonZ>-ArSHIqg4 z(rAqjnPktO+M5x*^m{hJzJ{Ma#R4*#$1)E=C3YS8$h63@qx%;MyT;}k{B z2B6O}FyJj8H&lztx8uYEkE^~|3452h+g;w+_n$u@sl~uO@>uBC&-0Nr(2nqTARchL zDp#pWdjXDICRk0G()?sqi&g^9Hg*nuK;SNIij^1~n_}ex+9#=QaI;r@{22GYs;rVN zge3H30X?#WXNl@lWGR&_p8~Ue^mOpO&-{on+SPtacnwuCUm~Znpr|MmK^sLB7!y`? zSt5DbQad!1UY6kCui#2@wCFU$Z$o}%k_6{U`K2&BL8BL8gmStt8`wOMd3AhN+(wg_ z+;pn@0@p8>2VSkdWdS z27$j3{3&J|Ojd%MbZy4^SKI**i$K=dxI*;xUu{SkDHlhn0-4P_cV54~f)6$5&$}P| zmzb!CN`fcA_B!D6XMT%mIUwAZz;Kya4Zm>;(7^bW^MQKNkm?`)XbQ}dp^Prdq#X;3 zFtL5Etu<;2nxL0=Wo4T9U{Fqy66>n}{an)kW5BQs8&;QHDyCZQOCe9&G1iZg|~B;`tUc`BuIz00pt|bX6FXRi^`b%!Uw+ z5(Mi%v^aonP?#xXxee>qukV-T#~TmNx6AfR7~XEzP2d5cgujmYVjb85v-Dd{c~&=i z#OV1aRXqB(?vS4H5By@fN=BBJmV@MV>;`lBB+&c!X`sVT$d|LQ>Ep6MwoOMl^5#Zx zTasbbze6z7l*0`(U#(-4#?f3L8n1pS`_DX$pqoN z_!^f~K7+7L@Bn#G)|gt@5Vh``yd-QHsdx5YgFllv1SF4%;Wn|{?*m^r%hyGJ9~r)Q z_~=fIgC^<&^^n&Ya=2*W!f%nI(+T-hg=ml-2zoyPdQjd1J;kI$5cwTWsyrt(VG|Y$ zev)Qd_7$}m7|~2;V}Ds6CfnEWA4f$gx84!{Uo8=)OQ;tpVnD!h&5-8XJevULz1~A6 z9&qH+9k|JP4Bdb06((L{coZuOsh!Yks*28s#_wn@@qD1tr7fZQ#Noqw0Sf3O%s9n~ zWcl&~Fxg=4oy)YQ(JF|>$Z-b;)EYfQDc(v$4vjEBSW`FO#N)*~Gr?MzWP^h%KYU=S7diS1=}Byu4F9qP`#G};>60CWPRXuV#yIa@`;!w4 ziPDIM3S2mJ^nKR5dLquMB}=+?>(>88SbV(kj2Wl8M(hdhK*n=8WIFf{s+&;Wn4N%I zKy5tAn;A+pse(I#l{VzR_~N-dJSizSY6!_dbJxhgEMLJb~){B3%4!=@>AVIK@zF%HJgBnfpFzWw)Lrk>|u=b|X0PhCl*>-_ViWbE|@tDn33rWQpPegT#MS?(264 z!j|4s8gfl>#DN3=ji_GYfttoWn@Mz1rYYrvW2qy7;SZPG+RZ|BS8VZ@i#kg3?qC`z z;kKB?r(6B&1$gPv2t)V@J{Z=72Rexe#|L$1_1zGahwQNRAP|z}>%M#;=$yWIaeWId z;j};~?%kzJ4I$KE0oi)aVGSy$8+mye8X5$hK~b z)N`~jlOR{|7cYvp_4-@aTUdN}_38i|Mo^IL;>BVAyNmilQOdQx$F;{SgCOQ$Yur<% zJ*Y~pl&q2KZ>WZTa}ycsVL^dtsYNiRTo^cB4Z6$e$!f7!kgNcb#gY_9H-A$cH>7`p zy8P`Vg?fS}-h>RBTDVi@`O05@M8u`>ySub>JoX>&h&~fsG#IQ#cH%Oy;(9~MbBY}c zQ&T|M;Rv;DI$`WUA-3S59Jyp}Sn*V+{yG-Id5eA5x7Ucbd?8KG)K8eiFr-m65p3uE zhi7WcxYLzyhXoWz3*0ULmz6|{Amc5g>6aB%oYGYv4AEx6h+f3z==iT{4aX1p=} zGI1qw5p%a5+9lBML~kdrD=8^wVq*u5*J)rXm2jQYtV1D$_a4S#q;0G?kep_^+{Erd zl;&2=w;8G>Bqq9%$*Ju*xbsX+)zqJyKY3ELl@Z6amQ4yv5ufqsyhV%PsH{N|#G(rg z?|!z>k$0q`#72WE>qJoeA6F;G=E5Vn%X7+y0e;aYPo6!yFCo96Am(Vg-l>P!1BP$n zh$q;ABw>o$wr|fq2Ml2r3`{2E9#mk?UxME1(E^WQ!JwWZiIQ))FT?|0guaDNjvHw5 z5sWGTiLlO1Ta~HGG3(gA{U9~9E-arous1>tClnDBYvV%XhO-AQBqw`t5(9U38q!ik zSmE^lMK=H(DoCIScE;n&9u7?chNxyc#ebFj^+qEqSza`{9zRafhjinG7-l+nfxdn_ zdt`EkR^45!0Uepue8-IoXcQMO<_l8h7ZAdCj$)T%^bGPrdv{s^j)FG?dS-WG;-9$} z&V2Yb%BVV*R01H|w|S`)Ox;Dy}tM2$ziI2h0B_=M@=-Khuz79mx=x$!quq$A%-ORD!3lyTVD3HK0 zVVg*%P{RA51iidAe}3Op*N7TcOl_iZfj9+xj;NBTdq*%W_)~TD`Iwk3Ww+Z=_oq1A zwpkB&!#t?H@&OW9&rvJqFTLG%h_rZ2{zP#e<5^~Yv8k&`-5QQWD7LS_%-oo$$cON3 zo&DfJI-v)wE{K3CQ}b~6(UcL>KqGqR(Ek;+lyXNqT6YhwuvOa9*oAdjn{Q?Zbv^(5fehE2a z(tsqoQpDq$;F6b>RY7$ZdMS4Ko4~uN7u)W-Nil#sv%j`>T2j)2w~JD4og4F(-&;ge z3PszdZ(rNVefVWRu5VR!8;^{>Ti0kc4!3_1(K6XbWp)Xk=7@6vg4|G3GI31sq!k4a40gtHs$o`y$Qq|Xcf5U{)s*5x?qwn z|9tOw1$kc7A`-i&y&}oe~68U z?~sHvF45exhI`Ba;RejAAFSl42?#|CjEuVaWFYK4Npri(e$Cf+0z*Q^@>3XPp;6H| zjRRIf=JulX5pfexdS!nG4;t!x5mUODMD&9X{?Xf8DyVklC2{6ex#(MfNwj4+J2@?A zDpQbDq30~wh;jI^+PqNkp+sjW(Oov^K@njPX{%zq1`rQ;gDAQ@vMPNU2IA~{_lUVa zc$Y`)8aH{YFVJ>+(!Kg)Df9ZxH9K!2M6y|v6nBqkRVBN-Myx1E(9Ps@Q1VMZyk*c73wj_e2;Me z-0|&VE;Valv%DYNPY3=3T=DIV*%PqYoRiFL=sR)C&O)(m$gaI`B;t$WKB$lP5BANl z@$ED5N}Abf^Wn!PZF0MRc;pMO!sT=Ge=OF~CdqltlIp)X>(x5Fk_%vHTUi9$6??uR z0?Az~XJ(I%#q^o8Fqh|Ezg`Noq$)F+kUt<{45U$gP0jaTGE-@!0^>H&`EC9E^6V9` zD-eIpw}qvN;rt7KCEo8LA2_UU<$%6=V&5;iIFt>Z3dDz@5Wx4Qw$Ky9`C$&lnl40U zxEfS7*s4dOBzu}TNPi;$al7&7o~FPOz9B zNX9G3LM1Vkj~fa`G7-#ZyAdJxsMfJkIzS97FT_a#)Z%xPu3pT&xnh{-f}s-y)lxxd z$C&rmZ9o_QDi|2bKY&5gZ%Oiu!P0ibV7P>m3rlve+-U#ZNVOR52@i&E=p*y1X_4Zo z=qlxd>}ctKOnt~|b>`7B3YO@1l!2(HPoL!gRec2MjFcOqq%=iY8bZJx$QBUadqSVJ z!UYF{BE#^-qe9MjTr@FwyPX)twxL`Pn@_9p*sQ*N`Lc*3z)_}j#O9`?^}V3LIOKTI z3&YwxrUlI)*I8RP66}Ty8YC(uzBAf6kbl(0NFdn6NmOHQTeTUkOLgt-JrjOh-+bKG zuV+u5d<(OPpB3)A7);LI2m&n(X`hK(@LBKboy_kr!i7#-LWOXbDHi{7poMKY${)p3f;CPN3#vB81t9^>xuBW7=M8%9WsOHU=^5ojqN3>Dx|a^jy6Te5oEF5wqg!8xM9k@VOzf^!9kT209g3ZZCGg z)ScLVU|}ir*_TEAy_fnwd%4?sfu>Avy)Cn3J}>&zN6uZz=!>=WhO36o4>q((-*zZz zn#JYi&w?Ol@Mi$6!O3)9<%UjrnUfPsX-?@#_5yR&fBi}z+caxd2VEn+E{GYXli%dC zff!9p9-%vd8DY2- zZ67=f(X89OyMBp{Mo$ru{`^W|Rt5IhBS++PjYi5ja1A)8BS(Jbfr4smf72==uccw9 ze_N8brPd{tQ$aGEzi{Cop&pGL)7y`6ci8F; z%H5c_I6(e;9{e<=1Ezzu*O#@_HNxw1XzN*kqP|PHdZ+lo(q26~++os7_v$HgvqM?4U;xip_P)&wK09%u zkFF61DmOd(2cJRR8~xVv`9qzd83*=e*k}&$i@NsNpw6c~%Od^!z&qF-hWbv2%Qkxv zX>fP&xpzC2x3=%p>HfWY(DJIfMkv5a4s!12W`<7Mprt&(iiG7moibF~Cxf$iN^K>s zd8Cut%t2wLa%YCMZuQ%t6xlBGi-O+rS(P8IZl5@^e40|ZRV%40ir3!#XgvuFWtzcN z?YN&u9O7_BlUGEmF9)1ebqzm$jH7Fh88iiFfV{Xw=s9NW8mb*)s~jHjuOBV6L(f+| zp|XE^n$m}@q6Ui=xiNmSy#K_6nM}C~C91S(R9$(wwflRA&#y;!t&o=st;*S#b*Mw4 z5yR7xiqrS&R4`?Fa$TzrICP0^TYi3ZnAclt+&ET_nwpzqFuwHZDzOB5rM<3E`PfHf zj{{%0bcsnxC)Kj)-%*d)F58T1DXth&77l)dre+YQ(6jfH@H{RwN1%MwSPrGNG^xh&no;=Nu??qe4c1nH{X*bX0wTwQ||GmmYfQ$~ghk zOpN{4(w@9w|Ipv@pW3Mx%jt zBCj;F=v3OOX_GsA`Lb~NWf{v>1-bvm(iKC69-5(!=f?gZI5p;9hO4clp0Um45t6{rI!-FKt~<1d1;Uu& zz#vfaxF)f#?waz7_`^E!ew$Nc(((g)b!&C};6DBO&L%@cS_lq?JkX(aWK@(b&nIAP z$J;iw7-Ufs)V&d486(4s5ExoBzSVbI%DJGBE7N$uNBsQmi)MmG9a0_@K2;3HsA4WF zoy*MOnq-%!$TtXoM>1p2q-fY@<{B>zjl2gBs*kQs>(|+Wr@y6%o9HAz`Ycze+$@`j z_E)0^b`*v8!Fs^EOLPADx#G3uUC;;?Kwh{gc~MAjC29~i!0Z7}XpxmBJIKk24I&^N z#JgI=E*KvQY^n?1Ba4J@jd~VUzT$Orok8n(!{RWfY=|b<|0UYEb-V*DgbhKE3wxYS zjuRF`L@AucpXq`o+k2*^xg$If#^2n}nYE@wm~S6b_Aw*Gk=`CSTHZFWvJ$ZHqGQ(C z+YsfcXoL9nqSR*IxL7%k+{zRLy=@6Uob-$e*<<4}p@c_C)Dy-lCY-gmn(ih)FfZDm z2lfrVRrp~=Y8y3~x`toiJW7CSA@9sNZk)P;C19)t5O`HtdFPx{Jc+Hmi}E3w%jDH( z&M*o}PIjhEYRi^!dv1lRc|Sj+j1)b^sE`h-%H0DtUV8N8$rx52?>HV{WUbt>c!Bgg z-Wp9*Go^E6Vz*A2SrXuQ_ujpI_nLh+dKUxWSv(b50x-=ojE#H>Jh?KuxIgB}bnnq) z#weHa=ts`Jt~KT7pIP^kI@jD@s+00WRjD6;jEd~t2=*PTwwK*#ER7x#H^lN%Zit?8 z*}5^5b4}Kaqgl2ygHc#w5Qe1H{lL5Za$)=J6XUn4Hv^rYRBze6HA3vr6)sD*p zBM5s`^W}?))3m$<&aTk;S{O9nwwNQpLqPwcpd3r*AJLd>t-;Y?9ER64G4!Zi%jWFn zqqzUW|2@ph6GOHcZp7D0n8j4K8P870@1hs}zx0*dEWINbtRs>`pKd?En;b$KMHrRI z80IcLdmauAU5odB)vBwI$n+`lG<y4S2)Ca|1tNVzLSFPx+`kc9+!jxvKkq zh%YyHLgA0;rf+r7GAI42X>lkAu%8EX!+TC~a)s3e)Xw}N^hZ_FTtKZw<#AH2@}c`F zNvJBR7(KKWB{%J72DshXIT4QGrek{2jPJJcGo z832u1`LZ9#kyZc(EyHS`jEJzYwVh@ZMB33`!tjUJ>&8&D_Q4hu94u?EDDB1QQET`} zSg`nRB%mveH3L<#@()+Y(vfH{5t-?0VoIU$ETZw3IB`TZ} zQdhYPH5Xn&v4QDOV8WDuVv^t&*3Lf0+L;uO& zk98CSPjF~pe&eyCUoS=bU_>YY9}YiYj{1{&N(rcobaZ$AdnPi_agj13{9%QRE{veR z{4P4>NCo}Znwgp!%6!RKQ*5Bra5_%UpF7icwb{3w$C#4p<~yn3m(hh+m_wm*=-i{D z_RxtFY1F7pZS>j_diAS)|6$+c8lJR|8`^3iajBECj8yd9oe`&h{P@!lZv4fPn|t$J z2lqt|ACH)LGif#;MNha5Af2(rG_0A5i5ccCY6ukq2Eyq98Beavpo$Mmyn>iPgd+vA z3?~sUbKU6<32O+RgBajw?|`obmW*hrwEqKx&V3_J)0uH3;xuIeOFE5YbR+ZWZ?e9& zB^tJatWx)$HNf?xaBA;LO0(UY_8&cbm{vw!{klD2XAT)C!)CbtDS3v@Fl{e$>O5!x z!I(_)(6(nw#&oGY3_F2koi*75raYZ^N<9JNdMx5JvRqwM;P#%G8`u~?1p-5V=8XM@ z4Vq@^zqJy#=LeoF)hSq7aBu3tNtZWuvZbtXaG<4PP@Pr<%*h3sBnUa#FKPlkxLc+0 zy-El4K3Uk#w2MdV#!L?;=K}$9Y|YU>bCf@V(EayK40v=3K{YyB*NWf$zz&6#D{1PW z_sd`APG^3)tkwl69B5@`X*p}<)qx87uC&m+s&4?5u`jpb7uS)TjM@#33wUEja$>bB zpohNgtTrmiW>MHmDg1dQtttY+-}~GcaCUWRUgAu_OztB403w0V_5ILElc*Z$DEy5aN;evIZkRn~2SEiYC@6I4qUhY2YsgnC zFh9EuJ^qJO{Yc91naXW3h%aaB9UrHYWT6WVZ6(cG61+$HKK6TSVqw>OVxboWW6(`@`YufT< zBlI1BCpae;E==BbXG&hhvo6`@BjdzFpL{BW;Od5kkoJ8dX0VndynpMQqB9G_s!R}*#4rOrMq+y3uYl@ z^;X3CZ=RmnA`wClLg^lekQ2oOi|en};c4e~-+Nd8VSMmDj%364?|OfXW7qDH(Z#47 zeCQBe8a-rWsFaOm4&uBx_3%UMxqVIq&-!Bga<_MSXk@+}Tm~ZW#FX{bKn{jIFmfiO z^39H|R`f-|frQLj4o_$6G*m_^>r@)yh|w&Z_&~Xxgf~8EGAfN)B}6509qul;*T#x- zU2T8#Y*K(9gZ!|6;Q(sAV98necDlk`K;n2#)Z`B0qB5E{Z>rIJ`o9hx>XBk(VQf6* z(|o4RuOMHPuj(AKw!s#D5=nAucAd$Bm?J}Bae^d zU1=#xFWi6C&S=%Yaq_0~U0V$=EV5=S>~6~inma6CZUg;C-<>x3W%r#=Yr5%wGSQ%c z><2~qii{oBFVhXa*!M45Ju6ba=wC0uYn%m3E)`P`_A<_tD_}4AlO_>HOb`PhVyom; zzG}y?nnYX_617&L4_G>TmoUIl#3wYK-esgPYd>gk9g{!1=f7E-6h7MMt>J6gpL<51 zrg5&picx@pS+qi{rtAyY(}6=*;dq78g9d7jAx(iCyYtqo3&mB!|BDJnjL55StjJPnTQ_%Rj%sVq$8Si) zgk5e&cBhsSoiw^M4^59eK4$%t;%%ZPXg}SE8T^5tbKoYqYJae%0Mgwt0h$gbyng=r zb@cGz7ZVab*ViK-m)5#Ke=2>O3Mq49!e*sQ&)9oLM^lzTpZ&?pbL9&74`0wx$Ydfq zb>o^O(oH~iR1SNyZ>9xTH*MGuQSxpG+ec=mo4o7(fJc{YCbClEnfH$eqy<`;J}e1 z8O$1x%y-A(xVtv3VYwK;j)Vx9q%5iQ+sup;vy%8_26PrtCS~Oi&ym98%r4!@&aM>u zzZO@^Osga9HEYotM#Y`MPy+RVUE#?{8rJjX5q>5vzjv534_^+hMIVG-f2`mn>!Y&q zMCLJn$|s0;<&F%Zqu3?_X668>!NDWTEe~$}Q|MgAzK@*ei7eLc-@@c&rk4M`QA%2^ z59mdOrNe`COgUS5;@O57XFeTPd%xA~)}xwkXVPNB(%PFXhj4A&(Kz(csZG|GLL)C< z{*ILx`~|JC*3i(O##O>GT_fc|VkrRqgI~U|h?>>!!eE8(g(FSG;>i$;F?A2XhroJ&i;@uM8U;_N{kJUH}8BA7C?Cds0r- zf*T22K8UBU97MD<2K?j+my@^=NJyZ-8#a4@Xw###liON+pp~Ei5%}T0rnG;T`-CdD>@nT_oHOWn<{qWnVMgu!;i^~v|a6E$SA`t z0N)66L8W{8x|63_-raU{1K$8dbB)UcXJ_Y%h$^lLH3rufNfq@G%_Qf+1KOc*#8Fxk z1?ccExHJeh`N^|qSPA?h)KcWnv8{yCGvM{(!a~?h3Z|v75CzNLQb|&qh#7?d@+_dw z6-_r7b4D1@j$~{seI~9?&z|3DW~Q;LB1^3jRaB_(a5dO@zU~-qYGHwkl$y-=VCbAv zDB}S`H>OxZlHeS*xhS*m#OK3>&WhyLikG?@JDF^$dw(UW^E9LR*kUkjt9UFK-m`+ zPW!h1oT409QBUh;QKtkaKQgMHTx*7i);wa=Q$$tmAw@d zM5c?4bA++g>qcMh>7f45EDL-Vv~L z@VbZT1#d{7XIBBxW!wzBoh&rsr%yvuzS1xt2nw3aAan4Ciftgsn9aB86xUA4QI(M* zvEL_G+;vrg8=aDObFuok7Nuh!)H~!u&QNEe^em>N679)}Cgl}EwBFrQ> zPag=ArZ(T)+3v5y%6znD+;l{l<8wqK2Jkk%e?Whzb#4<@6A_4=mjo#oy*AL(tEsPt zSY|K>Cz6W0pqdAckZ(|Q(J=UJx2zr-gmsDlv7sCz70+KrccS~RF<{3rV=hA&W&548 zPkfW6Wq9e@a=f}x?T5$Hfkup+rz~wGLo!!cv^O8%keZO3Ojh}QGaq!Q)1DDJuim|L zM)sxN#&PygFmqj-scp~xEQ#yh5IBKZR$w8VgT$Dqd#4zTfe1)3Q;hWYwZ zV*rE6CA>?|9onJjrrl%q}Hzsj@zG`h; z?^W)jK6EH^*;5cvj^=*CstLDGEFOW1pR`UZb;!4C+c3Jo-s%k)HWLe@zaTaWvV5fZ zf3v%G=I=}B3c*E0#O%Ty61LxCVwOYK>up%Y9>>(B)2B1p*%@C4|44JF%dhY2-7F5Q znEYm@fq|Gj+kZy!*Tp+u1zs$!YAgXk4N_MJVM0(79AhtC+Q|1H+)9v-6Vlt{N*&F0 zr`MAF4+@$g8xtD~FNSO2<1Z_IFil5Ul#m@yu)GVO8;vwro0>|gkAu_rMpv5*iKmX!d$L;qZ0=LP91AP80qYfgt`CLm^%x5QO5b;I}CF{_y&&Pm6(V-ccR&1jh1g_O9&xNN)yS`BT6MgRH8wH zp_DX8#rHdJJ^%muzO}x4y{lI}xbN$_&U2r8ANx3teG8C;oSs*3u>3{C!Cfi*EI#G8 zq-EK%d9y5)GenRxXMQjB3h6_VS)3t6$9(j7PxNCDw$${{B`!d z#2N3`YAq^xevjV<7FMCTdD=C2H@zr1U%t$JGP{L_1;{#wmT-Ha z@t^%_Jf&w<{xhe)nc2T)!SjsF^NkvM8BbGr zx++*kRmCK^nep_HRZ8)-gTkEmy!OcMfM!|q!;tv;!+G%`c?Z=8RD|YT4-Q^5GwU2d zj_nxjA1xDWGe5XCuutOJ#iy3Pd9KncA^7&Riu_>JMbm=^W-WX(UUgm8@sDqkG&D45 z&TJmGTx&9>Cr8PS0aHloEG(i1-y^Si@!~~#dX)0h@R9sn8`(9L@IV=BDoc6dS&lRrUo767}Hdg@Hj z@9P*JKW0(s~EK^oE8kQEcW z7`t0uRVDthqQdwpdwANx*7hA$rw$mfH&``1*k)mH!Q#s88&$JTA5dLB{czU->x{)+ zvCs@PExKqDiSjo%N5PZd9C+#7}6ni;{9jfa|PO*Q;P>c^&> zGH`$rH@?p8Cbxv9CvB6JYu7Gz7SmUSf!R&BageohbH%7upmnN?w);*rPg+3b&x#fk za;ZHLv2pTkcXJzPa;$(-Jm6U;v7CqQm_%z9xQ#<}%Jf++BpTWP0Hh@f(5G-V{_ilF z6sn@_J6cW6zw2)^Ft5bKAX*jRzRdcXxklK*=bFp5+zG|Z1&IX*gcv6WKZTQ4qd9Ig z)MVk|OBMxC$zN2mFb+~xncg#X+G4Dz3J#x*JHw})!h$om4UV3{2MKfyiGHHWcZ~}I z_N2LiZR;ANfo%uH3^vvq@HAkj%JjCAwWe3vP=rv8KJb3$9etn-!V9)##!-*F4PKFM zlQ3?9oo8$w6&pL~XrDfku3cnX3hPsrrTD+sua`r?1bIR)6SDfFm*78|3vXr8A!8$> zay)*eqKS2wJaQYcvtZDlloH9+O3of~>aJqE48a5|t6O~Pj^WZX`J3RdQ`?DLBrp)0 zg2d#>Ds#n}ro^ZdIvkYt!_x$el#oQ<59i(+^B-;`Vw<{QUIvbWR*r zfssSYIt}O!G;i=9_(NX}Q!yHHHI0eR;TvWz>d@n#k*V`5Qm0?_j+@e9blWH0ruq*! zWO?Cs&*94Z1`dtele+BI;GtUmGxzO&qN%!Xc~p-D`z~|^xL)?_X1{lv`!zS8V>2nI zu|*okkloT&y&jh8a?#yeJ55gM9AS}6RuZA_#pc$=m?Zgf zO2W-^KXe~^R;pC<^r-y+u6B5s5EVgD%(4dbF6*@2PWQ~<1qV}ZB?lsT- z#skzr8hA7_B}lG6hjDk`Hp;Lz*^?ijTT!auR7+esUL+ftWr(#FUAm}^a ztgZg|^YJ==QYUhF2o&ZF6u_~711I~2ZmW-mo)2RwoB8-+BnUjT5=_-g{jzNZPuJB| zkUy*cDs96aC@l0NKPouB#2e38#ZW`40IPA4B76PkP9*NJG}!292}&tYYUv|=UzQJ% z6<-{XSmBn+iiR2h3_5)1(AOKU7iamd+i@6nfx{d!)orQ*NWosR+W#?d3Op+H{<<7I_XO7v3#68C;%w zLxzTkXi_Y>c|0&sscYMbxeN3(QNv$HemAl4w~Cx>>9rl00mR0>2O2x3WAMxE+Y5af zeE(zJ0^W*i(3i|?O!UfaFoS^{2iM?)-gffm8P0tqp4y=lSL{?ohkSr?W@Cw0uKsMb z%=&Jbn1^j*n98*=|>jX2CAp;&sfq3tSe4VyDcHzTF2W-Ctv7{p}z^g$-a zY}T#o*Qd|(-}=v9B{Z%jAPs!Bgw&> zw@5s%@@_EtNKVWK&oMXu!ZaL?T8R6Q>u_klf(;Xfsrx@K{0X^*6~*gz@UevBy5FAby6gfzl}wot&r`Lt&1RrzL)a8j5fu#LLo+m9c1 z>PN-L@#-K}%uK$Y#+x7uu$=QSu6>zZ=hi^&CJsB(<3`R+E*YL%@V$$En^7OPtsZ=z z-N4cMK3TLEVe0~Xf%2UQrnGWPf+4Aa>A*#s&^nf zb%3Y+y~gaWRtlTDY}qUBT3q<*+#oKrRqNLDBViC1WoFtkO6*%WllCI=fyQAhZgzHF zlDNE;h$qLA(EQ7IZ9q(r>?J-q5p_~QbY6!y_{lWN!>Pic@pW~zp8M~ul_PJ_Sm;U`bjGhkO-OHa%9=i4sdc6H-x)S6e6w2 zu=JCB-T+_tFyF`Ca3aV21K@(7@3H=AfA2s(C~tt+-&gM6SL?wPP6P!-CM5hqx8_r}E!wJMnD$&(b!50C}O+O&JEh6EX1TU5>voE*lgt zngEC+f)5<%Dkry|2{C8^(du1GNkM2#B|LTELU^@5$xc`6wmGu}EYt)U`mg~}G3_Fu}%URF5kuwk}Eo=ycyE#Y4#2#($9Z1?v>;j|mP5y`W z>Z0M@kqfZ!4&7SHBK6VuqqFKyMxH$sH&Rt>qkEHic~nOlOCmxn8QI2xF>hY?5`CUG zX=}{MlMuJ2I}3o1oqvVgy9SU2;`nyT5%JSNQz`_A({G5Z{U*3V zax6C$t)=`Q1&Pd|Ihec~$u59fjvQspn&HZCd`I34tR9h?X}fq(2fc14VSBdFNT#xbH*_w| z+^~O8(&X#%lG1!Y9Qe|10FT@h5v3xG3C%e zFXbR3Y6kWd@IYbeHfLIXyvP}oLz+vRrm&U$u^?ldrS9Fv6cRS#4+#$#2b=XKfty{; z#*sH55v7@mQ?q8}3EbTUfmVJm0HC|OUU<$R@3A^MpeFQN!F-JZhG3soUVh}zAw$_! z4tH#CY&eWo67D0Z!t4&?4fde1Cn@pWm2|2(GMsu6mqjDy>+35I7?44

@qVHX-+> z4eaGbUE>0supnc4jy-Qd68(0g!lI31j*Z)D;UY%6uq6kE3{jlL!~qAAblOoQsM*J7 zD9Hhje1q2rdB{5uVaaAvVxa~Z=oJ!T0iKxRp{9Qbfh;(_`mb5kIxFjM1 z%d#=QUl8tYoZ4MQv%kvaHOrRicR!b1DuICnB9YLN*R43B?$?3Ce(jK$HOj$JD zs)m8Ssyqk>Z0yyfeAHlqk&6!PkIVdK2+nf=Kwal4~Fz^{aD`MY+M|t2Hpx*v#h87aahs9_G4KeZ~gLefj)qGTLp(R+&Byp9kbK3314fRVFg=wjE37oT#hY zYOsfF(rE?~QiHoBdilSvckS9$G(&012qMDs=i^mWI6V7i+eH|SMBOrxbFoGy`-Z8N zOQNDa=et*t+S;sUPR*fl!Ek1GMC-~*CWQcP2$2y2;jdLi0sp1R-g5sgPu$oWUqJY7 z-g4B1&@)yA1zDBTrvH3#OLXxDOst?^aDlEBJipYxL%|CFxXyUQB@E3(ZNdVIHSK77$Nv#C>8GUtKQjN{|h zEz_#7W&d#jZoz^s7(%iJq!4d>b;$C>YbLgj?ccpLc^mnV3;=Hq1IKmt_C~TuxE*So zz{VFNc>+GZ$ygYGkjqCR56*w|pep)ckK%h>whI|b*29Mo2hIK*WX_4j}FG z@Ex{B$J0o4x~VBFgPR1QKOZTWz+uw={TI`m8E1`W%n;5wC#U)z8|O;|GaI~S^vp4> z*9{Gz`~VZ+;E(y3xpQZ8gFQHP`^M%M6dWgllFI`pbH@D9>tVTM%=wUci`NXB^>qhM zOOTl{Ilc|3)!=%xd+fN@lHQ|x61!Y+Dq2^1sMy>ey7(owR? zCLaff6Q*AByr1S(87T` zX@#1YjDvUluZ?>A$h9bZ3155n8gpdu!0VU%u{AAN{-KjkmJO^--ugF-f||F{#k9FZ z@!%vScHGEC*46-n;sNL4(L?^>j3VT3>iy3&10}gPZ{9%SDWg0?YIkJphUFN!RK6(W zApZLKGk0}ovD24Ra@Z(*IRk$op zgMI0ULa(L$QNCYB^4WOn&o42Ah{#AGS*W;2AqIv7aBc0e5{Dl?z-Bg%iAjs*%>`2Y z4V;@Ej-U`g0i)5!f92-#U*i@ICOu?V2N|g%{K^aZ$)wp^%M*Kl8Vko7puu*h=H>fT zq`$sZ#bPM6V#Ot9g9Du5D1<6~vZ{P)`XjEVaOsDcIM5KHrmF^%b-rDQh;dl>!D z52JX>GdfZf2d0$G5R*JGAK|bbJZu=qDd3GOZZ-ui4~yd$x(3pZq=<;6#54ZlXnXTr zfbp0g%dk6uB%t^85zRY_b&8U6@c6B>mX6}Y1`Yc?&n|ZKtYY`x6X(qwD8_xVVA-F@ zOTX9Fu6CHg7yzA<6b(6gzZe2hi81@Ny`3bAPw8EaSaS0?#btcF@!vwfT#lZEsR|@E zTukLoo;gDmoEMQ%{^pJMEBt#T61@df89XbTG8Qni9S$|^!WqsdJB=7KMSOdLt| z_4SPJ?K#1fmYH_L{PvRENDyx7IsoDLq$DTWu9Wqk=uwtL>TRTc6i6I&E}HMfw1W-q zB3P?fWuKbK;ICSvR{ z8;=J~yZm#(F(Zu<9C(Ig^bad)z zwBypo!aXr+*-mhHWG^_qi$EeV!8b$<$p*0CYS;=wk_kv0vH@0s zxcNkxJ9q3zPeHNo=0Bx&Jg)0Jf`x%I5wrb}(I3ZZr8d>DEn`9yh4?1*#tnY<)Xbv> zJRi@2V7t&^NaJ8n_3#MA)I%V?sp;$e&}6_9`n#(-ek6GpY|yJ$C!%=5Q64@HmquVsa>TclyKzWR2+s^-5?~+AAbW7%OoK zkcI%z(zPpxDZ%-4r9oC?OvBe`rLcV{7RGusjF*BeVz4XU1E9vpny|m=Xs%Z2*gh*D zzRjK6O&ROUQr0zdxHcRP`kOLkArAo(aHKAwAf=DRG=pf}*~K*OgsCPji5$t`G&sO% z@J+DmJP!0|C;43Qa^rQ}OUc?On6Z=W+qW-J5`xBRW*-`QHwzTW4>62S1aS;ZS`fhT zCnvTLl5T#C6p)xDk4#J{fKUTfTcGV4d$Vnc1T&9}TE_bPFA_M{WWMT&lOVjXRm;s+ z0q^;ZkQSn!&a-Q9mn3UtBML2+uBigmQVQ%oG(SYA>9W0`;NUOE7OCmzalf^F7g#AG z0ljyRrBV6Pn2!T3?b*0)|LB5yl7ss0-Fw~b=SJ%Fn>QQajfqP~q;R8iS3MK5Kn^$_ zRVFJ2ng!<*#B?zkkV7vmr_V_7aFl=$`;OaaLp~TD-cR~)E}__=^7Qj-4^Z{DtuSd5 z@E^-WAxV(go~+SQo}#ahdHM~~+QP!_jgO^ayOR(Ezi_Md$9fk^Ov&@-<@@swf$xdF z5vHx(ec#ghMQ%a^l38$%!rJM?05jvGK-6r}!t2L4Q@Ali)_>E}IbpEHdiL?gx`W<# z${d+{KxGTP58xtWG6vIIU0oRt8?X7kgp>hd_~ti)yGq*pX=^iy3AGQYXH0Kvn5{^E zI9y=GfOCI%oNyQ=CU08OtC^nc-YH@@4uuR2Q{Wr~dj|Lp5$@;Y|G1Q+2X|y!<0Wwn z%qHs7W~i^L>odXifLO5E!0i>BKy->g=%)USlXc-Br!+7~T1NG3zbYv4!iB)(W^u8x z(+>6!3X7?RG;Ou6X9>tqlG_{ThlnMnnc--pcdYX>9x!B-&1?@&uyGtS2uN7&M`AjZ zS^(~Iax7Z({8ztycgltg8+P?#$&=mhw=BT$4-pB?0on>jU3|t{7*$x1r-lvKQAVY z>{7Wb(URyuQ8ykinGv5NMe9)n3v=G1owP zCaxGO8c>q*DfrKTxx=aH+Oy}iW$C*E%D!(TYG8E?l8sIjZ5VcDtYB5_uAN8J^#lju zAabMs!>iC8ee{|DqnX9Xp`$obBBvhG+epTFxGwGzjvnh4}yoypd(z{k=_nR*8$LPXqZ`Ay7<}CkF+UI zo_y_d-;?adN3@FgfOj%8v9fA<^oViq0f*AbDx+E5^yobUAWdZZ7Lk$1?ZRZ<;oJz8 z@agMR2E(jJ;jZtvL3$g^XbjM2aHCj*N+){mPIp}J0;rk`8*EI^_TbS7 z&Ody3&VawuAL@9##OLCtPdO&?!+Pk=re(sL&EggcczXJDW8-)%7rhZZ(K;}0-QO{1 zNAc%?W}dWpHj$kGC`=Z;lChCywDZf~zxQdH{Wd8Szq4`vX3oi3RsEy<{j;%RtLk*m z$k{<$u4i`}JG+41nyl+e-agFL)H2c1jo(Eo#L6e%f%h?b{P-K}Ij8qK19AcK2vUY~ z+mGw>5D*5^Awmm*?LzLOwHPGFhNX9CvwHPHAhgg>g}#09#oNgK<)|f(qF3)u7J+3i zOQD0zmvuLyFoX4~Eyc~`ZlE&Dnfj%o@N6+hA?LRq1t7&Lg&S%Y8;~&ukJZo&x%3o7 zkR1DM?N17DU{!h}zNb#vt`3I31Wb1N)TvC8YE}6SV~=;AI0g+lj|=7%?@J{>0AL@b zf_Ko}pe4w@LogQ5XB>?Kn9bXO#~D4dXpu00Hn>Yy2SBha=}5WcnLls<$1~Z{w+p9E zu|Rj74q}Z8-%++_fdxqc)hHr&9vk(nFh%7YJQoo$X~~wlv3wZHVlXJ;n}ae)5j}pn zlh|>y1kmw9!d?&MgMG@!&sQA#$2f7pW5NdpHBf_surHqR^K zQWF|yl06Lg%N`Zc(#5M#t&sC2dr42X8<#Up814E;BHtSODUNOrl4YdjIoa8N zFc9QdPhcPrM{M$@TX&2xuCTNe9UL6^@h9N@o>~*eY(T?#Rhj_(RuJ( z;apL+&_YCE`|%^Ax2MW>-aCau;Rd4}C|pxg#EeT=nI^JC)+&5#aA)*rbSE9DHRkca zHwHWG-np~BEDHj-My~BHH7!eyWjf1oUVu~tLRfGZ+cb#bmxLXzycjheiIaswQQGHI zdGw6x(*5VQ`87Vy+25^=nqk>DrN+WLE* zJ9UHrh0}u7GQ|JJNVG1`Q zxL`ZHyjqk*zElzH*v=}3K>aYN){qM0g+v6Vu{FSZ&yA*GK4^M@@zyMGXr zZERw&Dl^!Fw;LpE8sdM(O|Clp``EL@2A4L7*yN`wLE*yQ9CeF8n@-3JfWn0UoByfw26 zsupV6CiHvVQ@3Z%4X(|S&I08y!*x&chJqs`Kgv_;cOI5veLQV3DTU07*H#k(02Y(zY#K?Aofxo1q{C^-I^FY0Bx#iHCGpbZQ%^S1O!)0muC$g8BQtmOGo>?3MkkER z2{sfTA}pn)dHmVk{U4uAl?6k%&8L@dg;j2_=jhR1-?~1&7;}hd^x)Ncp~;y&n-2}y z@bZcJ_k|DcUyfI-3O_9O`pp{+EQHt#50F)k963u>zUJp|x{cXK$GqohlZg!Q#>Kvi z0hmj4Yfw2=Z@4}a)dv0q*p*eLC!VLt!dzFg%JuB6t39ZlNrD)1=4R#D@m~RcIjFdl ztVXZ|%DiOzx5xZWARj_86iGs3OcyUX1KMyn9uYOGJPIB?itNr;x+MX&5ro@B%i#k< zjJKC4xY0PrE6iJtgOEz4a>l3XYSR*b4e6+eYQJ@3^@(Vv^w@F>3t>1%3go*TYn5!0 z1{(%rCV#UuozxABE5O7co_%@Y5<@jL>O79}w0d_^Eg{-lPqTvfLIIbj`2HjH+41o% z8@cI}u$%w#g|@ZIx$wm`)og#mssoDjWFG&6Zx>n^+np~ccC6l@5_q%cT1J26AS zdCmI8_c(T-aQz~Cz!sL}N`JEt6A=*iaU181+g+)`c@Cx6ECptqyn)r2M`JV<9mwyI z0avA`1^h5>_c;JUgBfcypDxuJka>{r4LU$8NmxP@RrQ`!uRy_vRMgL)~#gc=*L20WLv!c>&0-RUJ3 z(0!+Nb80PJ;`S5sTw>yT#nApQlRgHNf1{h8ghW|&*f7SH&ZdXO!)su{RqU_rj-3%j zPRG9E5p{~^RR47qZ<{>%)}TQnM(me+O^H4MZ}MNHRz!w=ii#$ej{&$*f}oGoVInm> zRGYhU274@rul+Nm^x6uqT62sEp#I%N2nW#^;Up+rhn}N^GnDWt&|-9nm;(S|BWa|i znb{=SnlE1*M(-wO@#Ohew%^|elY2!vKf;tdMDoSaTxDh4W!h$WP=q= zqlI*hZa7s0Gb2`TFB!%oSV@EHrkEU6pUNypwqL)fQsyT|6^my+4onJ|ui>*fpd`l+$QkfUT*miR_RhBTozj2r z6mtkjTZPfnh{FpZPnFehOUCx0(zGMz*9%X7g+p5H&)>Y~h{L}!a{`jOS)~mXe6$Wn z<7tK~>RC`y|2bbB#q4a!geDO4_<;l7J7^JmG2;%}-!9xczTKQ47MG`~3H9aMx2Plg z>*_A7uOZqns8R|}0=x2Bu|ma~7RagUL@Bv#(ikwF%e3LC=CIVD_Q+R^U5WoHYD);V z!k-f!P?G&462aLUoA-WPSO}N)Hk_vL^;+Y`xd1PMKM+5Kw@=EJv*hQ>HWVJTWS{}j zBXdQUK)tTl_@*-+lCmAnJla3Dmgz@iU9vpAt?|g$#ByyrzP74<= zzDZ4tw}E*lQ7F85Q-Er$LWb2$aSE0}`3f9iF@Js|51(q8O(f>5y$gX{bJjBPHFOxz zRr(IpHygHW5%@2=^jPn}Gt8Kz83upTI}kw-M>}V37XyC&M|!7;n4!wFY$;~|fLx8r z3E%-VmN8Up?`IeUfZMH`>AU1-q$4XTCN|cN=^nAM7VU^jc&jlh2mJVYUn+rBKd#KdfiHGCeeuiXLF;i45VJqfb740#LwN4V|v}X>+WBv&I-ba z$6yb6G|`k1Y=3m3kaGP^!gTs2S`w)8xURKNF6?mVy?H$-1K2NU5j^Fd=w`t*umUOX zNTC$go*{b#K~jqc526ii_>;jQ-g0VcY5+34xKR$bN=t7ZjH+Q7d`S6pGlZD9cZ%>d zhDpWr_trNLI1iHFOArv;6DX~4PZ&Rr$MdjZ3FxZIY9Mn0PLO9*T|KFQNnZE1yS(MP z`@-C)7ox`TE_v9WSb5N5S#ou)qSvjS4C~++BsSZ;`CH~D zyZc#Lvkz{lFbm4drYAvS9IYVn=Lol7M-H%Y!-ksL+G3zzGBMW@{G0!m6Ino`^V!(;-M+Vvt~K3UvHl?O47BmFy!m0E&~8*hIj8`KyrvP z2voe|*rT*UGGMzH;t^%PU3l<=ShxSU0NdYHRtnxU8N-!|%}GZoB?O_4O$<_i41{Bq z#pM5f`Jteoaj-V&{p258!L%!NYC1wBU~S$(K!UznYb?pY%m$C&UZ2Ds;I?o;i{D01 z@X8I<@_$BM(3-SO_G!LlgXX>YZX2w0NF04CFE^iK^PuBHykcQ840 z4Z;;|OKAb^hF@7Xc-Er2+_1s_ebPrWNDrJzsdhPiM;z7#n80uNXlQ7@Vp~b6WU^DU zRNyu=AUG~xtm4Kid*98$MIDscg{7sXOjJAQrGAC!S^0pB!Y;Oc)#2js zD_6c#B*y*d)z%J(DR$yb;W|AdtmW3v;PV_dj3NCCvRB_ zLv=Q-Q!Kp_8WnTk+Y|aWTz`(+x6_->a;yg7I7GN~arp_;N!S~Ztw!o%rJw7Uv78$< z`sjmt?J&-%xcHbCTdTNfdyn1dDXUDy=eK7M%HGJ@38q*ka!k2T0A-8tz2*#dN>(Ue; z{|ByHz~r1%Te2czGeD5@?~XVhyK7uJzucAPNY0$mq_iP77|Yhtxa zRs$LteaeC5LpmV*9QBzrZg1W)eU!9V$qhkkZ*ragqH>i;tK<`BUZqGYEW$*Hv zW;=?OlcyG*O>jOG{4$Q5IPp-BrpbX}E07sdHP!z35xdXt|H2qN8~6J9DnPD;9!BxU zfm*VmREcOwZ=ds#G>9-OdSRvgTEVRhp4U@IJ=(Ra8i|{LMTc>mLhvAoY~)U_(tT$5 zieJy&cUqz!%M73{^70qyWyqvg4jDX{ath1(c+JO|L`f=Jq?}W%92pk%7~C1uTJ@}! zyn)Til`OuPL4b^pnZ}$lW5@oE=nl5PS9~n2`mU{yT+y(M(CwC}wY`q5)VH^yt~MWX(&D#WG=Z0)>c%D2ps&`(iTLV*hHi zoWj4HT82&tFc#esF8z>L1D|hl&>cCCu!`2QOgBU51Y9vS0{jcMFBFv{u!YeOV_n>< z*Q=6Cjz;~1rc9fL1@2{f#pJW}Ypu|>(6wC8MHIG=*u*1;fdjYhEPP$7T4=#SW_<9V zaVMk5-D?g62L8IWB2fLa2{sHUYtst-A7iZOFgaI-)2b)X*C;V>RO>!m|URBJ&=< z@?O`jgbkf`xY2UT1D}ErQo+*u!Q0v4XuVOY^&z>F*hS(`!Vfz*)YJQ)d3-F2QSoA2 zYPZbqHEc9g>|hoFETGr7_tL3PX#7BmB*t2eze`L(v6V!LhgjIb1XFn|*XrEdy&P6> zG`3u!?QSm4zfNR!B+tT4RzL{}5SKFZ@-}k+n(9~2jy{afO8bscg+pX?w71Z_tmZ?J zdQwK>Q*UQCO|5Lg80lm0*Gw;*uImGqg+N-4j`67;+sN3MtAsv|M0h8VBy)~ww)@Ck z?zk)c6^IC(VEzQ>-8WQS_*8)Fg6L-1u*#?FI+BU9xta=bz6WajftuC)m6G%8;`^}> z!IvUzrIp)n)Y3`Rs$j2el!XNxz28YnO5QZWi;9a=GRhXAg5f5C_>?5BXnon1yTz4z z2g=kgO6&a0KfE`{qTV$K{18tel|iSJa&1>qi;-{XZ255H#`uPCah0EqMKfTXf$VHE zGkln04VU$S{jI5iu3u%JU({l0csLjw6CGGB+$tWvf@8n=S64avUT0kDh57SvrNHkvee0soMN=n3(~)~TNj z$)1VRZQ8Yi>=XcML#X*04~`hF>kJLCWy_Wi!gQ}@OlC?m@_AcK2{_^yT^2d7BZBVi zY_)OYjwYRaIaq#g?%Lnccau(iZ7ccYm-8MjIC8~BY3|nb+j~hOR0v^iG%le(5J3L2 z3O+_}2pSE3pJfy5I@NFpCKTji-dg{HV3ji`{1xIDl*ezd3_tA9l!b!K}WozxtCmBA5 z@wJ2MUE4+1)-MBs`LupqZZD3)&&yCz;HNslqv5$=%n39AQojoei~sRCW;EezbxLM7 zQVxP=A(aFQmf3UX`uqAqr;XC>sO-&$IJ59-HMtXuHDTV_V;JN@A1sNKH2B;pqw0eA z2F*`w)rI%VYA~z6ytsc5rx%8!YBl?pN8q4~-3YqTZCHG~68Y z;lb$iIYw##k@qs+GUCttQ$T6(r{>2Ei}FQC%BzK99)1Ae9P%qq{HnfS0jK*i*%C+JX=Yhn2p1t@do z%*^{4|F+)9X-D|MsKf)yY^vt`q9TtnTT0-Z_gBZ3+cK6KlYB;_Z-%mW%6$v7qkf@w z-d@i&&eK`ovI3VAAtG4lp`084s#N2j)~w0Sy?ZA^&YnXpd`T8E07H-Hl>9w?93xn4 zFqPRPzpvhHr!>&O!6qWO*d` zIL5jA1XnIGzt5b+oc9*@DF_%gUw<4FX7(_chfcXSrO3dH#q+gZ4E0QEO`!m#xoBpm zFN#-Gy$25&^0?oS3;GG>G~nG80_um}nA_lNmX>a1ZEf=HYNdzX(=}I62c4f7J}2?u zvq|;ePA*=>LgzhBXJP@m;rb$;mF*>-l9zI~n7EwKcOGJ5&Eh7EOn_xkQC{*t2bIIM zfYnYus6YiqO0&$)uIND~S%X@`6!)*?L1-LEN1U9T#+;91N9%bsh?W#hDzf3D;O|DN zBygaT07H24l(7yoFL z4en+Ixko6Kc-K7BL7Ib4!6AbgH1{4cNGwd&@6-#9im(Hrgg6SLZgXfU1D2+wO z@~_=Ja{TyA|1i(~D$-4nw3pb6c!j-pTyOia(p827Y z$EEHUC|ZXB$_*LfQnu5{$iQF^j0>mzCG{a6D=R8ykNH?QQvGE2!Uaa#0^g*0nFSY( z@uZ8}us?e7v`f9_RD3@B+E`&lU5#v6#A&H-g`mPE>Ge z3$Mpbj&2yAm1c+~zJb!({Vi!f!4cCGocASvtFy+(Bh^nKNT9cEXQw?v-CWI(4qewK z2FJ@kzzG}SUo;uV2J+bbjTv?&o-#UcX~@>h39e*pmX>#I)XCLp z@IV^k5TI0z=_bo(;&>u#(wdfO2V6DBceYhTGfCY6I@c_8Buk{bL{uk+_o+S9D4CAu zBJd~TqMuOAj-A)a%*cQ`{)W7p#`S@7Z)$&%3lX@^yhz24lvR4IU46wQ_M#UgL#L)Q zxqQ2}f@D(Fw~xj1(f2?B7m^5cz=KW`G?4@yTi#}>l%gWB7xIHYFf?(Eyhi!idr+PU zbDr^71Tv#bq_wW}IZ$45utW`{zo{bQF(lo!oHGY6k{Lodvt}0RJGKVc56eq1q;}1o zKmTxP0u-1!{C}9<4HZMkoza}4;Kt%4>G3Ue7pV}l$B(x$E;-4 zA{#N_Gc9f6WBVlNjVRu9|DFrK;n)ccJB_?^3oh+G*Pa$W%!fui)PON-;flHgGCB>| zvE`rlwQzA3%$akWVR4mNIXQ<-<<8Iq;YI$;SwgspuM6_5|j@y(Nwd=wlU}+YWe)2pIVk!l~u!8i+onMH~k4? z-_9f_KLgUZe}5Pw!=!urF}@Zw8L4j`N%!{46^NLFse?Ghd111;{muHZ-g0DrDTeD4 zq;znJJ>o5)p9K%1Em!~RSAOu0jOAx(QPZyGmNV74=NQ}e{$A4zisjqx;y&=Elv^(6 z@#sX1cRCSUX@wbN6bRC#OTw;RR5HrcZ^ulnrcLuXt)^A3PH20i z*auCE9A=LWk55w#34Ssu4&lYoeIMWj!!a<>|3Jk~b)LPBsUzH&L5w&e`f4A!De`Jg z0E#@v6LLB|e#gp1s9~Xmf#`d3K+z8$bdeO8BJ|`lu`zR98JG;1kLosW+$m;&|K%ED z>zv7b#G;OOK4K*W79~3BeFL;{>Jc?1y;aJIRgDs8kCu$`X8TjzLiZb8w0;mRKs@V) zsHvMd@wydgq{^|t@6-A=mJg_-b5BTsnl3kD zE>$=5&>&6&1qB9=K6+@!M7BjxuAzPKA4HRZOWM*=vTj$#a$^tOQ{5pa;76?tDsboN z)1$6l{bG1#8iWSiZWhTtH>EXkM{AulrhIA#hwcvPp+xV^O?RBJMM8 z(%070fPiy4{m$~}hNbxr!X3bHQAjrFXQ?3fbK1iIL(8%KPyJ?0eZP;_^vwYDDFz@v zd-fxSGxoj4$RA^(@0i5^AvDeCp<$k+>`gSx0J+26j|(i=Nv(JqNq{23!JIY(CwsWw zc6ttai_QnhZ3HbQ6a4k-*C*J1nkqYuRdF*F>`mwnnswt)Si?4;WI`1A?ba8A*d53g zpUH$|Euz#0jSw-{^bIE}yB!8r-=>)REYxf;!29`$=bd;?^!>e24x%6+<}Y4&$J?}x0C@dbPl6^nU;wNrK?aMse6zlC7;Qvu@!#m1 z&Y69B;(3j^b~sMH*&Gy9scv4TzWfVm7_YkWM9VV}jv*ktxV9mk=10lHZU0js0mM%n zI~K$efOAtIgwu~IoUedM5A7ftaR>)`k4I?B@E#1+E`o|)F>MePQ3!d}mt5W`m zq^qMqM8Ob?vO%&@aD}|4(cnDS-;d37fJg$(1tI#82xPusj=5#QCa^d)lLiVF->dVZa~Fv6{U%i`RW+)k9`N798FO_MQZ|^ieAe8iqf~MB z)XaM8Ox70|fWaQhXn+3>n%!0KhRJyHq62PPA)FJ-29Jl>4|@g^ ztyL+}x!0wa%#q)n3p{klcInbd;*tyL((dr_5zeI$3!029JP%iEr52+!M&a}Q)LqO^;Ki}7DUdW8k3rZerQel3`L4U=qrOgUj zk9O$VZeQj;)kBuSmQjXt%s%XqaSQZRj2avfF?eV5?xXte9IiC?(9jv@7nXLa&AIt2 zLTUTp_cga(TzK&Ohi1C@^9k>h&*H)aZHW@-S%)#qpCS;%L%gI4g*kCs{Z82aY}?pV zr-C;a3MYAeIl?&~e4x~8&}NAtC)a7;R%qXQbm_7Q_9HMSQ(DNdA27RdTkjf1&>_zU z56^n>!ULkq*@+h@zK}8U^^!$f>p9g}K70NB6}8tcdf%;GszM&hli(vq#yS)XMyMu) z{nl^`72E(gr~w!^7?CWXEzeVY5{`wz*OHtFy9nC# z2_zlhheMT>JNNBd+9CBL15Jo{P7t=)?P#EBPo6uG7#;_#0+*ra2)1X9oI3n6?hdS# ztX8L>vx?biJgn2hxZZQ$=#_G2;2(on4*SE@ZH18onNP+CtRo1qSdTM~B6Ppd7^CP$ zt}qDO!=HAnnFSzhy?Q-0K4`GSb8)`p3$g~$x9e3SHxvw?9F5hDjmCQalB zoNQn~aD(i%YT2?497O>8o9&u$JJ2+fPY6Z=(DpN@4^$d!(T{=qjWkr?L?oinxY3O_ zFIUMWRUv=<&Dq}>+vRNS7fsKWNDJ}l9miYwMo~hSKs#%*#YVM@KVxNYh5D2?LT7vB`!ir zvTAB);g7aw2FCCC3m1k~sw2)%!5fU;8&J!^TT2P0B#g1Y(uZS5to*d<_FZlfD}q&kh}Iws5+V)@btgPy5b0|w_ z`>|8boM>yZbftsm7WBD2eA36Qe<^vqi|osvw!-e+nIy*XBg7-D-$T(&;&AJfA0d|e z)>0p(FxXf{c{xS<88ozhV>l%`^&I6{d0NWRlhp6R%N68f%$Q3gI>-bzKN=1ZknCx0^Z z{7zceN7JEzZ-T*Mx>=2~4E!eI>{%>af4m5r`yUs;n1uB7YOct$)Q8E^{0`^e~@bdTn^R*%*I{FR8z#!yd(7t)*?R%+vSN3LIxBf|cifkRsoj3+f zF^zJU-)b@U0gWIbspqt#%(}Wl@dQhN9Z%|`2#dp47j(tm!Jz>rJ;%U@^@+JfN+RuE zG{Tww4R94b+o^XtOUkXulDBZvA(sitlJvSy?Einaue*1UpO|Oa5pRmh;HIbjvJoiA zlq;S#ZIFgWlJ7}>_M1qoKpbIi(rGZBJ1qXhnQPa^!oVSers+a6bJdzPebBBEYwk`d zV+IZnIQ|??TCT_GKQUKsC`lf?KJq?JQlR$83w=@0v-@crU~rkH_(>hRaF`tA=aAjB zov%@AP!W=U*lSq%RPDMcGmIAW(SU#)0Hw0mujRlkOSel+p(Gcx6@9g8iK-(I?CN3EdWweC}K|6djh8 z%1QsvQ_Fd#S`a*)bOeu{Dn25a#O2C38b;6uDCas)<6_HmX#F5GY#FLfh7QKkrKPg; z{4b0i5_RQ@R`myIV_H%^6`?R_9j%bQ^k}=Cmx+yu0cok`kcYdm#o0ObO6Z(ULE+(z zBxvkk#v5=IRz^nl%*Un-Wp^iCxnejEnu^stOUteJ4Uz&-qVnDAAjLsQpVMRN`mx6m z7jAWNLB3YWj1`9$O6_G<0AP#CoGSQO@p~?jWu0^PuG!qVj&^5rW0l2)l1w9UBplHU zjTINFg~X$%u#iLTC$~BNoWR4A+rX>>MugPJcm642RkhhE$K{Y5lQt9;Y2!!87rf}( zzbLuN&+y8fjQohqc>#VnVo@QLlbxW`|rE5;ieN?#GX5Nu4FG ziu?jDjQeS3Ef5i>gS66Ru)7^~w<`bv2^|<}3w=2{sW7k!=^ThkW#TL**P3&<2?mmc z(O$8m%;ibZTL19Xeg)VgwIC=dgW=K$xmctm?Q!$`dtytR)YP919yF*&-@bbGxe=y)egeA*5&VxI;eZ?jVppSC@oUpxt!KM; zp@it$w*la_zTTA%8krm~j{Br3J4}P9BJAx!wmFz|)RE2YqmEz`R5;axk)$}5^6LmV zsct`mvu%-V=`UH5mZgHpz@?<5@l1x&m1%r!Ox;nP&>}e{rFE-T8Mki>@xuEvl4Mf$ zL^@Bf%Md;@>GLWlKT^)w)&-45GiKoB&ERk#!=j?1bw9>Z-3de<(bCynwIZXt%<+Q%mx#Di=ouEZY1@{wyN#@DQ=)F)sk?7RC-qST5coct5?WCrbjo(?UvX~-sX zZK828gqnh#0F@fejEo81xfO6pu{?QvYmc(NoRiKUoFIF+DzO!)w-spH+NcW)IRCYXh_}wjjHi1F6mQojXZmA#j=)p^7uiWM=6;BTZWFxnpFI-^!%X9;S z*EHf3*Zt1y!90o&ABF=S6GwSu4|`t`89N>CwjDbT>~TU%UHuq5OA=5HNCsU!eysoE z2fKjVLA%Uca~+^tSeW8plT>$hK>TZvQveMD-P& z95)gzJsbE1f@rD~)M<}yJ>DUzB{C>d-YasBsB}dixt*S;1L4aN(G|3MZqY&Q3OHmP5^*|my_On1WW9#0xrdHKDT9lryGGvG`A?oSVpJWS5 z`dqnot*&+hspn2FFBlN?{J?YD>^uSq8^ha|+~7X=2y!@NF-67CZ_TSd3-{iCE6TB* zEr|WEUWuLq$racu5%-I}`~6JLI-nsKk!+47OI~m&VTSZ&)=!KbTk11@0Rabn`bVq? zw&MuInn%xmiyum|D6Q~ z20}Np^x?yEZzoWTF#FDK&6?-8dPU}>-z$(T(WdW6bm0MP9u?kElKTf%Hn0P}sC48F zq*-r_>XY6Jq5_05en5{?C$-4n93%A3}t9yNcC;0pI*xQE-{nmal!UT%(raz6^ zy?^p$mwX?K^^qP%I7(0GN;gAhu(^^|+)Ytj>95CB3$DmWlnbxr6J%X&$h5 z@6Q`X6wlmPuBUU$L>QW!n@Cc&yzbGvzC}l$E}c8SLebK*r@*u+>_}@!nS&~mZ|=;p zd3a)iE{-zn#_GEB?ovH3p-K#w8ZzYRzb9Z9f_xya1qJ%_GCKEtq_fID^C5bTcdHvU zbZFbgm}Z`(chl2XAatM`7bQR|&zl%|P!WE%@UuBNn)c+x7Z-=@ zHH4i@=ryx$>YGZwx)On)I#c@NEEFd1_?wyzP9rcU8CD^C6E=sl+k?J4(_f(=!E=e+ z5+Nr&{z@VEsFw(B*#Z|$ykKH}YO$F;``|J9p@m(Tkx||2Bg4Dnmi3i`m~-~YCA$D`?{cA^_{9-ZJI)x zo$JYGE?t_O)Y+;8LbQSmzyRwf=^`u@TG(msTGqr8GO2cYXnYMGp%Nyap+@8G4T$RxM zVPXkkxf)jyd3kjV+tp`jVcvgBu})io2m#^3Z9^cPXc*|racM@iL)K}zx|J24;h*S5 z;8Vkc$t@^YBvx~`VdygA&m~-@OG;XeSu{zx|3KeoS7+e{0)+{koEE3Tp&#w>a^uhf z3e(XW^0jqcN{5I61WA$4ic*TxIbs6wfvW~|nYvk-GdOh?Sv21RT1#=!%Ym-f0NLf3 zEK^ocTyR%yPR>SFY-+myzw{P zD;E|QW3})$Y_9Ux(QH>@0}Og}P?T2O){V~2Ol_&0>id2D_2+EZez2O+NfBkM54>nV zQ-|>{TB3UbVEA$ZsywGZKh_&P{GIo^8X}4sUE1bu=1ABt^;+L~>Z>GIp=Rq1N@zY< z$KD!yDy_J`t~v}Byq2VK-I|dWaxMK0v9wUv)C`-j?Fx|t6*mMH;Q7Y`q$&`}B#+x= zH5~jboo&2fN89FG$Dd%55q%6{gfY>hbg!|>bQ@b+{=2r4k`m(+SObKQ;^JS(iK-6R z&XHKF4j=BPBumxuC7s8fMqeMi8CYe|3UktZV9v&$IUfARLPoCxOzl*!@YZBY{TOu5(ZPo287ov6+6%i8 z@u}86XHf6Ejn~nE@}A-2Hk|@2dK`1vghnNuQ&dRcOV?S#4|^A~_fDU_S5)*PVMq?` zI>1tX#JR8__r1Ud&d}aM>RibEvfwU$pbGmYOBpQV$>19IAhAdG2W5^6Nxbn*A@y~ zCNFmENZ=rIKSDqtZQ_^W{uDQ&!^GxE_pqSkvHM-=eb%wIPiaZtoEJDdFtd0h9ev8G?2Rla?D8G{?a%tpWV z;>AQ|WpSA>777cu5bFS&0ne?|+#yM&a@V*)yLTI&Px;hjLocbnK-O^_FGy}M^te?& zlx*&2lHdZ!?(!CX%E7%N7JG9P-@c7+l#Z@0${h9(QJhctgR7--=A7u>rAt(@q38L8 z_;~E7zp-{Gh3`(Y*LX%nju%Ade*GGM|J;PRH8gnUnaH(Nrcfad7XIA}F2b;Q&vt+s z3rtF!X{k?>Lx{EG;&?Me{X+eF=8T_V)T0Wg0Rv)kI-yk>yX8YqkHtHcNM}paJSHx` zEepm)8buA(uH&za=Abp@PW2RpG)htB;0-$|>JbSJ?TJ?Xh#&$LB;-&&lksECPmR-< zv1yHINJw68uJo5rqV-4a0?Yp+T1AeQ`cEE>+epVafWZAhPd`ycx6~JtJh3AJsO+DU zaPy|H(P2Zq8Nz8H-!c(a7AqM7KB61A0FWjlYFAH$rLD+(LXHbsf>0yo8XK=-MSx|k z-?BxEG1CVQL?{3A{ThTP2$k#%3ghQ{CxpVe5*>QjSBOx)B<>3P&Z#*eUp+j{tK~^q(U|c!-304yJ@Ly=@c9mCcXeu5V$DbFU}kXwPzU{@2$+!!O;vr-v$aFN3|fq-gdI3Q$oVR4rfcGxu&)BNgvG= zNML`shq?)p@=h1jHUH^x9E&3+2Hn6>GD2GiJtFNLvPo%sCnDj3<#6}Fpa<$W)pqom zEawgM!3o0)ZXu;eVPWPksW6||xy{AZm5$n-{QOHQk1{6D@l6n~#!WE+AjU100iYN0c<{Xxhgq_+|R87`kWx4iIcD5rimHM&&L>SLdtwP6c z=zr+YZY`{FMd>apyT{)j<;GPeuWa5dny>SV7F2hmJf~FIz>l(@P=c-t)4hgE2!v*a z)2+7BUvhop08Pzqv-{W&i&kiM48^f1)30ra5~>e6cS+M$u8aY@;MCbx;@Y3ncF9*4 z3o+pnToUmA%^S{4fCsGmzG2GKOF<#OLQMGkuk4nTYp^sx1Q>DflDz$ycJn5J51c#N zlx{5RLp^qUREE3Y#E0Y?Y1j~2v5Kd@5!U*acjY5yIs7;oMIS>&mh!0$5U9f>C{Qk8@UQ>&hW5G0p&w@!ooANwvOdyQK3WZ6%NlL+FtkC z=IXjQWy}9z?M=YB-1oNctCCbgYKan}G%O(vR1^&~NVTffq>ND-D2gI;B!o0aXwt0G zK$B>|(m_XQ+$~i$^vKQ2>-lrA@lqQYzY}8b#oXkv|icpZ`kCln(y0 zl(NGiBDMF;Y<{~tD((8HgL?cAe2n9MHhi-~GX`$p>EUtNIS_CZOZA{}V(7IqQ291|zaPyw#QBpK%3zBLSO}bGP7ut9j+5Y$!!1+fx}WVJ7@JX|QI`Q3 zGEq&%e(=66=aez!MZ9HJU?`8h)c>b+ojO^C&_Z4lmtN5U-LTz3Dus;^orVZw=U%sw zA11anj|@o9#jJ40mUw6J&9`|nvcU#ZZY*VAdwPiFKhWI)ind3^UsuqL78F>vK7FdB zq{I;&K5Uq})FkdHA>L)Bfk1oXdn+neeANto=y0hSFV0d%A4CO%pH{7V|V5YPz}?Sf2t2!4J$U z!@K;1NEUq9ibfM+HfxF(32CKnq2XjnayM}1WQeAR#x=sMy z8cO+$332O%<9RD3Oo-=9Wk`9m(a4lzK4S(3v*P#)6hXn)hoS9pH#U)DgS9944Ur5q z@7zS7n$4b`fEce)cmldq-YjJY3Et*35*R1UTd-hiP+v-`lShtBqJtK4SJ!ylq=li$ zMo+zKy?Dy~)tFo|Z5NuX6wLu#YrUIxm`$Ia4g5)M{jQ?o<;H9JG$}|>_+8_8n|qc? z;{XmNicpb#-+dNz-l~G!OTt7>OJSy!mCyYhe}Lj9h}7&Rkyo2HZ#-ZFM7DU_eoIQ~ z>fF+`%1CR>HAwl#=dDB%1?xHGri!rTlsGu#1LhghrsETE-&TCsAzaA^Ps}0#0YR9p zjQ5fC<>mQrAgH|nPnnA*;*=yx$Tl}eRd9gyM~(7ooyPFUtXZr@;(861I&$-7OwRjm z-aEX?Ydd5g!|QNVxM{ypDf85f>m9_lR8&k= zd;td|s~g#T!xylhlG0|}eIaN-g=S;v3mL=#H*z_?hO_MlOirl-y9(sbwSy`kDo>RQ z+`IQBYKJU?GD^3%Z^~0<6W>2VeNi|Q5*eC)F;#3*mn>e)d^Cjir5{6|LOg-gTG1o4 zjPdB!fAFM@9R#BcL#NzX9Hd z4E7&R1>T0~e=&>PV)zNz+{)7OAtN~LA7}zHPnK*pcA-w`E%XVJJ^J2zQV+h5V#Y~cBt{rdSfI}5R>z3Ur7ZWs4@?ZGz1K2RC5ottsnA3S_->rf_#0nt z(Po8a9P!}Fb?e}k($EH5p~3oeotqu}&cy)eg2>5-1j2`M3JOTVgvmh$;DP(Ssn358 zM57v+|LSc3dzVNH^j-O{UoX4qF&B%S&lSIzgcYY@Nw3!?B<@FMP8mlfqV`6rzh6E(=b;*iF-Aw8j-OBjlbZ?a7n#7ndA>vc5Q>QI)b9a~R){XhuEq}_MViOqI1x-n^ z+sD7qgh3c-pS!TaTyvxtwbk$}XOwa)aRj!M#Zwa729cg+cgMxWaY5NG)S6?h3p53v z(bZp(YeZ$tBj!T_1dj#ZfAOQ{^Mv5V( zoRcMpj|0Rm?a}fjOAdPNF>bRWi7#@v{)1h)94qn~4#I!%JGEo~95BF!0h!+f_u6O3 zR>QAv`Qdb^W0Vj_f%EGIpnI6=#8!X`_y)0>&-ErSah5oZ$3^}kUXeY$D7`E!SnS52 z4OphMWPoMHWc-Z5)cEA)Mi%70dWEz+5tXKI611S^(uX`vhz&hMQFeV>M%*2cKVGiC z<4_QPot$ozmOSa-A`|1|L}~J}xZRVCe(rVL|Hxnu zA69|I>@GNkQQz+jMtykSAsJ81sxMzet6s>RuR8F+Ll_pFtbH`y^Q#w zCOx5uH69BdCaryaYayCJowQ~w{%+CFAxd)l;amg~K)bqf)ha5sE2mcEQ&DpWFjevE zrxG6!xh}9(w0|I0ft0k9)!zI@ur;#iqN{6^#3s`C8Y6fRqGdn_78Y>4Mz5~}(R_P5 zVpl(sH$}hr!`A%4P!eq!^&_KJe7rE(#5)V63dzdPufxO~it_j~XF~6XY}tpnh#F+W z`=NT(EbiLN;gbvGd~uCJLb5>>vVSDfoSr=2hm#k7=qB$Q4cc!gfSQlwK}Sc?F78mn zuZ3dv#`O$MqAKkLIgp@E*hHPe`iGj#v4U~&-)LsJ$Wc-0_IgD7Y@cjdnAofjQGtQ? z@a1-EeFfEvH06|bTD6F&?;13dC<7Bn)A0JmGlr*u#3&=~XJ%ge=x&r+Q$nZ~t%5eb zH<{??rct-rr>*50%YkTl@OKuQiTD<%5J*$XN0)h8e24nRj?cJGXg+C@k;KK>j>4>X zf>#Pp;>C}Spe|I*ycrP$B_C@dfqVX3s%uvus7MoiieKP1x(l@f+_@ikuEpK~m=1vvP831kZ zn7$T=13(FMIw)azY=FcsV`1`)U*T}hO(L7pfAA~VEB}>{N&SwDoQPbo77%~{NtRP0 zvw^noJh4vXLtu`wt@=w@CKD`x{+}B58{58^7YLfpR_%?H$iya&=jGNR7&y`Cf&DTL zDaJ$}TDF!xhaQa?ITG~r9(k`l)wBTi6L;x|5$CnHY~y-GXZK$7&wkD?zASQq(CxfR zn3}ZFG>rq>AFR0di@kXh^KeR0$G6JK2~UoEB1sR`2?hE2imR@Aqu#Bh+@ZD{5U0Wq z%9Z3I+qJD&xpMm;Q92p#Odb{8>hU7pzCCj9-gTQD#~k{CwKhLLY->?YPN?b8jkCq& z(c&Z{B}I5R8GkW?WlBpijXQ241Zt78_;7^zmAl5{8kTIu5K3 z<*>iMW=AnJX2b}pzl7_{v1~z2!^|Z3Hv|4V!^5%m9I30jpRKd>R(u7qkmx)~2d@UP z3`4_!Q(*&t0oRF_UOv)^%l<({gdlE71>Zd|(WjM8ktoOjPww}}^ejs**@wVlAf%)B zxqf}jhR&ZvT!3BOcnZ=><>k$#jXhIIb8;IM)!(0)5IU8RU{bS)u8k|mi+#Fs6z@J| zR(nkagZ<)^$sr1gbI>|^i1%Nfqm?0BRv+Gcz`Q~XJGQp+%F0^m>Q7JD@eSBmw_GwH z;r#icsqamE0*H_E0N20Q)tS$ptvYI@Tst;t1=Nd0RGd$%xS>NtseN@sJ<)Cjn?os(5-fAv)!U`)gT$9^RdW439Q7Hgbbjf=&#tdSDg)COy3r6vb-Ut?L>b zQlaqR7_SS)A@&CpE95P`4R#aMBfjHAO!I%Y4Ol|OBGlyQV zqlezo=7BF#VVl0af7|bO=EqEgRk1WcqOkVrsnx4jvy&O4ZJ^h;FPE}PZsw1=Iw~MM zu%7emCI<5C%m`nQ%_4700oI;dChr7oW?_hCbjX5cI8-Sn>+^T>T*L_V@9B*6(I-B- zjeEJFqwj>EocByz*C62G;16v_Y7SE$Gk-i0sO0p_fC(aiX<*R6Ux4h2qN10kc>_%b z#Z~i*KiW^*ko9b|v_eEfv=gO`-EV9Kg$CkBo4f2*-;G=#Tw91aef#yJilOiu!(VoF zj8jM9Lv2G#Z_$FLxb74)fE-Bg zqJ9qoqUpttAHp~S?<@o_&>!fycx#o2b+83T_}Q!=$%xrp3T`+I678w;$DaXUGB|Oy zspjiV&08m*pEqqxWk1T#2S57`OqsRA@W9X_-Bjg5Dmp7V}@!dcTZ>34s1 zX+;jJNk{_uf4FuK=J>BUh+D!U;>psbOTlGeBKWV%m*XNwJ(u6^X58NW^F3$rAIL(~ z;{0}g7M!16uf2HW2vQrb3Adr#_@E_V%q3Oa!p?zRhXVzlU2h@NXmQGAM)f_X;iEXY z*!1cecDbIRYh*t*n6SQz5zW<&s%NK+R+muyksom4Zl$q{{u zH-CD%pNKb)D~G~m1d6WcDlNAmMq!A!vZF98yEZOh_D@BRph#CH_ zU4NN9px^mcQ)2+a8fyX1w)NVhw;Kxz3*p(pD>$raDR((l=sEyfpB6|JZklyH?fK!b z3|CBdCvK`*gc|?_8CaLQMdA9bAIAzU1<2eP#O*VDi5vO0qWz!_i3i`*^%l#aW4n<=FjCF$Bd;al?iBAwQWc=@uu&{`T%qR1N4_^@Ci_1aq{}x3qTjiJw`7cEjBo}a( z^*qymVZWa#XN_r0fFH5tXJn_Oy!^6tdPi|~CbZ+qPcV(l3UGcgI_1$oqt{Yvp3?62 zrULcJc1T7%2^;1RR?xqk3p3sL?&h*%FsM-TaAHnhr?!G+ggEmL*4?9(2vjy28v zqC(=M^;wUO{ma*&a+_~X@kMAt_t3js0)G~*#Z@#9~5z;Ssjhd9+_-Ru2`3JsWb?>As&H7V-oVr?c1lhcAZL`<(2WW$dPDv+2f`%#AD51 zt0}%R*2%9C$cXYy>K&9sW*}TGqcPfBx@5_?v19vVu+~4AwcM*Q6`)|H1X-K-O0q@S zd->!xXd`i)L`7xiN)4fI6ZIjbE}dW^O|0+oh;|KL^@cP0ZdfOCW~XE z4KwA15?Wj6vs>sa=t6)q^;SI{c>2$dEB69rA+Tc;xldb@73?{Ykujc)P)CKuZNeLo z_~s9--ktEKZe#Vm%{R8AG=a$BXF2$`l!JCo>DZ5vSDOyH`J5_L<8*TuIi_C>_GY+7 zMMmP9G;H|ruOyCXVsThb`J3=^S#$*D&3fR_o_<6<}nw~ zHGDMIGecgW^yfgSN&N5xTq;gBnxM@gGB8>lNsyxk05pw`E>pGm+TLIq`l#xKG&D{S zwk}$;=4^7ZD^gelD&lyJ_w0=$A?6@$#HI7w4*wd?l#OWf!Zf_x+Q9R^Tp|rxT&OK{ zdx(#Zh-<3UkO<>NMRWWH;rnzAiIrzK>kMN* z!lp0o;oIoagHk+Yz8^ci#DeseWboa^m+YrA$by1{s$^oZUs~TEw6~%td-do~>{Qm# zNg}+t8pJRg+uvx*b4F8nim`eI!h#9adRf&{LljFir2OyOe!JGW&(Ml4tq0dc&+3xB zHa%Z8Rc1r<>qBdzyQ@dPEw}xr|HOIT%Oe}~^`@=EGdW7%T4Yk%G`3Y)PFpA2chrZ_ zF1rRyI&y!F`ovjTvz59%&QQgHS{xgIv!H?aUF6 z=QcYt~CPjznusbl>TtWv>4VPcU@>WC2V2MKBwuzjwpnmF58w-R*z!ccJ+%in)9 zFauBv{WkcJ9*xpVCb^m2iv95zh|dZ`oE8=kl8m5iy2po;}ak>fxmtb{Ia(&K6fmLV#mG0J z`R23{dU}_(oq08-d#`Uv)1T;E8T%-_py1VK@HaRf{?wV~=A!>T#dG#0+Fptg7*=u@ z2FZMhru&tL2pCJ_B+s2qMG(jJ<6i?c6Y-I*){=u!-Or6#H9%9bpSp%g`N70llEw6#OlHxB(n3s(JIEcO4IIB>^e1Y3>I~6* zizEkKMS$R*g!}tX$~2Rdo8r*au(eC}kO4{(1N-&*o*Y!}-m6jVHvuDY`+h^JaqAqW zhuR)x%^uRtRQ9cj%OKnIYRmMs-p?Z%+&kNEVCBqQW&;Wo%$2*Xi$0?g{nr1BWar7j z)U$+vIOp~d*v0quaHcJ}2!L&rr~u6Krv|@XQ%~4o+7Z#CMXOHAIglnGCy0 z-*=Fc7~$&^&=K@&;X<(>Mx+63BQ{zePC~ySnQDbQMmy9#KB*FzZU6o42>Gh%Uld!x2D_Lz5_}m#?nV0J%0Q}?7TK!9*35!*k2Xb(dGP9 z7Ku!Z+%638YHpaz+NpD9z{HDY&#tB>_^>YSv-ADvlh`7bP^>!LmfOT_y{aqVaZ^@ zx$a_Liu)y79O02ToG@R+prq5MIf}Th=QC4lA_t5E(29pW63lgt;p+T*%vBYn`NUO) zFXj=a2fxjDp&>P?=HMv(xzVei zM$cUP_4^oo1ZL5Pnzm5I=Y6aL3*t`GB2eEYV(lgR;}g?6hpu7_p}DbwOS@{->x^f{ zHI{Fd)I!E^PvLhVvoLH&zpxg(`uOo5&t^}=(`$@|hB$hPnsMj$?P^kV1_%xih(zgx zIojJJAcq>-TilOw?p)lF)any7y9(OzOyL4iHms2H&M)}s@Mls#!9W1qIQ zI9#$h+aa6_FR!2g7JBjM(K5Vi#=j4XcUJ48C(fm^2;MMp)r>iP2{ z*H31Hf_Fq@u@8%$1;G(ABg`eTJa4S} zPxpDzx|?8Z2Iv8ev7F5}OyzAWnbs%azmB!ZoKPnc(NimM!iV0!>|B2SOhVzfMe+;g z?h%P4oE1dLpnLV#ic<-DDAL*gOBP`F1;YJ{D{>ToV<=7JP|dNvkGW2n*OzB6Sg?_W zTZSrBEIK%Mn4e@yl8x$1KFm@{{kIli$&A}uE#$p!j~3CmFNtbU|3_ZT0;K^ z-9LA39$+gvN>t1DA3Q*u&3IY>XfY^yIm)0`6faG1y5QkU42s#mK>3581*s=kZM*28 z4V|fqO1Asx$S4yeSgon!QJeuzc{@&M&A#gLL&ANvje7d(r+0tfj7v9ecy_na`M&s` zPe0HDmZXMRuDq1}v+V`*;bEbYIRqxT`%@s^BY zEe20qZEYP11aTAZ{I@H z8{8HC>-_lx6&CS>CVn>+yx7zK^c9idjZcaz#^4R(1OnJ-Cf9w9a zn10QPP`2+edrB%b`7jN&;LTp4l0+lpeR@ z%a_>QyX~<$p|D06bJ^!}ZC2pB$_WwmyJlx7Y*F1c!i3%tM20@{dp6--l-U3``@|I6 zMw<87b>o{xi2d2fhg#jnXkvIF;(zRi0#IPc0Ui&`aOayXq`FFgZFH(|SLoe98jz$B z0IzsT_$Foi^E_AQ!lJX{;1eS&+wrGUWni6oB#*iebK6U?3H)f#_x`KR*|W)N4g^&6 zTX66;HiXGfaS?Od6L z`?4NiUUr)4bex^lL~3+_v-rQJibKvPwY%IF{iz741IpYOW*;Es-}dhCg$ue9#l=+Y zxNu?|pBfqrjg$9%z24Npifh*#N$u3Ra_f&zd#It(oMY6O2G~$q$PXMD5>0B9m*`1z zEEiZJ%Z9v}^zIY34aa}5kgNyEh6g<8Cc>JmKl&{>X;Nd})gPZ)JZl@hf)&mmj#to> zzo}_-^LfQ6{S7%*Nt*7{^HyGlWz*SNT;BNdYof_&r&h~ot6cEG<{WX7(_c-ZNxSy# z;w#g;&y%xi8dJWyv|~4?b)!DSA^9R=fZjz?K=G;7(X*w5JjQuJ)JIleYcd-0ijItV ziMZ1gyXbAlJbNQ=)qFw(;9oyr?m$+?1}QolJO2e(m-B&0NTrLp^dM~%m*n#04{q1d zYS0#fcy{cBUyU-DLI!!pCOxhQGbMz|43UYy_UNyiL1jb4SZ`(>M*8V6bVR zNtnw;TJ>~+uTxzID}-{5w>^7F22~5FDbMc3KyK3Vubj`1{mN)6#svESWdJWE4+9$7u*6w(h(cA77&8uPj+qR0N16 zq7p3oOS3cCawKmh{{YHjo2-rLd<4qdwoQ!~4Pi#s@7t#j!k!+3%~awi=vU=AqopFU zz%exEXWQ$+l|fX}gy0Di$0j0Ra}a(-MXA<(2v3P13BhGfmPh{X;axN#a?XDQsc!7P@QI^4$MZQ?lgd<19}C^ z@$NFggMz&sTK$J_({k?F^XC%1#=UNg1<{^nVZlPBZNrfykijsv!xKnLA@m=wFqct% zdpP{bc4h{CH&xhf-D+g+xQ1~{Cnwt^Sy_2%E9xxn0cX!3ZF5}1_dPvKfI_x&lIeMj zu(SuA0bI_@%`I`CQUWH;_mY;85v%-@H<*)5}^VpGbbNgdNL z&5$VV0mkg^?(S{IY+*(}6chACgmaqjCD1s#htA8dw1HZK8*j{1^?`{f=kG93-bn*7 zemMg>Bc`ISVj`1kzyLG79dPoK7dLO+q9hL&}7bqqKOi%?q}!M?5Iu_}@f zs8Mlkq}xDvoU)U;lieSCW^DcTuCw`Oj4|#YF~GnPGs@8W9R+a8JN2H<4KE@M^x2`t zQDX>%htG4IlmKsvaZ@6@CaqjK z#B16>dB9Di&a#fvs%HBHWFNmm$#dsG555m_7(^Me0z{otMC32!M#`SACNf^d!5Q2q zXlv^I#y^CoadZ$+5nsQqYsk&X=`NIf{rb4oe0ydYMCK#gi@;PsW2Mn99j#KND@(uR zX;prESs7&X3s($1!J4yGrND_nuJzdVB0(8b;+WEX^Z0gx+OT0eS{}l@br5K@I=%kJ z^cO3Qs46eEX}N|ZWKO8}$SPXQAx~Z6)BlHJbd>V2eSTk(R(!4Qv+qJ@2?;Rqrng6v zR3tk!KGVOGSE5o0V$neWWUtbhuPvG1dG(#Npcq*ggbu>|VS6w|Jz(y!b)V;IE$_A* zV~_KYY`iRfJ44=AE?%_hvz;X{`}Lg2?pl`HFp zJUdQLnof(b2AG?3!Oa4W-o%&=g$Z&wao0y$(kdcx*2=l_=9RsF5B@z03lJjBxA8G; zPw-RWa4|vCXtZw`(dq?ir>>)RLDmB3gP^9N2`bd~OkW`i#tfm%8Q(0{+ zCt)JlX|GKR{uD$2{(!Nds+&&zK|-Pg^YLjDhr+P-U>3JHU0upQY%5aMnh0hrbp?!E zY@rC~A2Eciuv`o5%gw8t83?V5@I{mLMGBv3Dg`H+$LF@$V@<{Wj!joMKW+T40jCiz@S4)F|$5Zs>A7#wI`MK`9^zFvlQf zl%cpE-&(3-ElsuFL14z^lGV2RFAzYaAK%t08SS~+#qhOGyYeRF$5<^R)7CR4-}M)~ z=b{O|;8)-N6pl^&Z6MOA$%bfrb~M{tP`dY1R=#O-SJFet6jsLAxP)heYKTg(vw*XN zcWbkf#r^Ih4-GI#O+0*9#Vfxuh=IqLmQ5QsvW%mX0MqEslc9y@AvUaLPdQTtE|?e7 z#N1{g6DV7EYoNL2p#uk2tzMlh>xrij(+V99$K5M+;pL0-Cex$|*MgAp(DtIWw_?G2 zI!hcDPiX$kD^rec9rx+maxu(Hukjh~>XTM7_ue{*y%PgHzlf5`duznj-K25 z)10!V+b(H;%9n;Pw?)Z9L! zYKBbN!ByS9-FM`-^ucLMuAWQlk@_Jv7-LeFgQweGq^Ur}h`S8Jhr6~H@n~Q8c;#4q z3Uo-94#J|POYt+Pd-dJec0UzTMEP(-6(aixJIQ?tzxtVfJ-7Z;+6#>amDS#(r?ooh zEA;LS$G)$4a>JSAs;IBx3-bRO&_U58YS;*{$rn%Xd$ z{PSn9&ubzUZbKvhDt36G(r7{g!vBx1lLg}lZ*eR-Iay@BuV2Stw`qcCX?Q0!=rt8R zc=ZF@i%37XvZW;@7nmIKDpQx-Whvav!SLGU)Y`-glc`YHw*911M;quI`^B;QH>({pY}geB(C5WVFa} z(tDqp?-X~A81Gb478EvQiuyOc6~~2_n~cScV9adM{rlp4GRpJwr%si+``RgOo3xoj z#~1p^6p+QiQC(ZrQO{{Dy;=n|MkRT2h-M-NjpTPa8kC%aaa=D>D}M6C8T}t~?6^!I z-i~RjgLy@fP2QpLr-or{25`~2Amtk+IzvvoE7M*1vTQ8J-LCENCis_9iL;%WJ7%2m z4t`AKxq?lyT3Q9g-S90cWbNNRg`lN&MYs;F z>G0wG<>e8u(#>x+v7lLy*VkKML?XY$s& z3oT4WCoKih^_xe+>uKJJM(~*Uqf%DT@Nxd=h4~NsinxZ(kb)Hm6-g}lMlp;PD=}~6 z#WFC710)V=TO|H$9A^0Fk-Z*m{m|Ysz+dc+L0MD zIf#jUhS%xuFIf6{#FQ9WPl;l?M@f=nYqqL(1QyE0&p z4gzkg#%f5NsHD%`zJ0hj0W_gTDb_+~*sv}53Zd};&_!9mc@GbN#LO-SgA(36a%#|G zTzN?D2um^UrME^}K*XefLw2K2nBO$|(ZwAWiM_6?3=doB&(fw%s5VWFI&@HO17!L`ut%F zX3p%c`Mf?g0|6-`KKbspb+58?!?J6F#~CtO(Xo1O^WR=9#6FSTv_Jc}7cU#X^I31izc(;TyTClwi47l?HR_zKG z`);2RiqhilAbFO}MonwR9~73z=XJQWWG4Y}KGwg(h74gpO%+xiF?kuGgD&jsE8NM* zPzS!!(-ZgK)ok#99fM626#!=!Pd=K*ZWlqY);rLt+E%U~GKo6H5hMsUW3Y*b7D`$& znPkit=K3H*xSnQ8S;4UYy*xyTNxG#t*_;fq3~E=&(u$yVD88(_ebz6_$fzj47keUmVs7GuJd{vb zgDXKiOGY_DCHHQ$lWWI~ds5`E*q0VSC=N zerV~^nQC$+PgoXRe;57a#fg_VNqoeO)Lr{Yg1iPF#(Py`}gRyD< z`PAn*-mQ&}yk2Un@8hW(}FyN1twyo3%!)kGu3z)q744y56XNF zTGi9AMOxx|q~dSt8vUcDd3`UR&JkeuTbfl;3XlA0#WtF`$xMGd)X=3XtOt6LWXA%%sR z(@%SCzgzn7(IZGI@Oadh+@|eQY*EVj`ug6y>4hYbm`2TZb>$CUr&o}QI;k{|QtO-n{US|EMxU0m=I8u74bB>%3S9@kjG zv$K52K+J(~X_z;!lfV=iF(eAY<=IDa0J>(%ldV^qUnmagO|3GIF;mLR(vVdY6BPUa z2>WNQv-Amg{o=*_<5#G4;8g2Vr{M5JHQ6qCDbVmp(ex}&?ee;8mXZba0njl$w#eUk zdX5)-O^q#pc$twwU1U_=3c{wT)9b|*l+B6M;L?s``}FMTcjY2*N$G{qkdXB8=J`s| zx{dOJ+R&k0b&i3XhwRwVQG^h1=oHNUh88#rM)R{rjp9#sa**WBOifu+-N9l31Gb6) zDf06E>DCSX`_nXDIDPIMa+No9oe-*oNF3g*shLVj;u8}yt8*heu%TYG@uN%@hYkPw z>j-=pP~+FH6FNRqhJJ=^+&<+UCz)3ayxM$;W#ndRay;JGs|n-01CUFCIm4}}8=(F8 z+>sAk`Bzll@e3DfC{rM}Di_55=%5f$xjAjJy>G9cF8YRcdNB#@p@lhFMv_gs+|Art zn(gW5GK^;;u6CVy$Z+#_x-S$XIn~>@*y6 zCMlEM1r0k&`fJD|Fp|yw9lZn0HLY%K8BH}-4D_Q{5BllySbN#ue+NMjYV8GXp*2zn zUB>T;v3tYrqGk21>)CNe+>@6IoN#7o578`xY)U$13Pf^OcBWVamEH|zSXG2WdoA9A zlI0-!edc9;t+r{%EI%`V4vFz7;2Ck1T>I?9?K_`0*X&Y>nihCqfgp(Sbk#w!C07$Q z1*1=1Qc0DV0U$DLg>}Al1EX6$%i-lIf5FjdeE4&S>06l1ynEr0ySOP$xP+c;z>$f+kWqT%mPN39akMWA3=^X76k+f#$@ zQhZAbzL{lo@L$<4<9U}()%8@Wl;Gm-J{ywv$&<>5CMb&STwO=r&@BZT8(aN&aCA0* zK^H+zighO|A>8y17$Q4D|8*`U#e+spR5SYw_ZcmT2Ad;fI%SH7hX*sL-Me-LEoJe- z2A!r?#nu~E4cFF|*$GKo&QAoVYIDMY0Dy16c(}gfa58m@o2k>i=UGoE*5!aL!o*!B z7+Vg;O_dK@BosA987^iX$gjKQOZ&mL-o2LpaZGti`pix06;f_|4`Lp5D)-0y;3(wC zIVf;3ZP1ksQhCMBlvKtUh?(%%yj zskVrE;vRD*VuMDmCnvcmSd}*unx5gev3wrBwBE1TF?kTVnq|;L-f-z~<*a-crcEg- z)7`Gqn$nc=t{8BlE`oU_({(`Xc7(}gRzOE&W`wQ)TY4DVx)pU>N}l%gG&l7=+43>zJ)IZLG3(^T5qV}XarH4W>L0Xr#R{s%|6u#n z{SzYeL2R9kq$L$c9x%U+0-6twjYz?0NWdL+EK}l-9JxdkCV^r_PXH_W=bvt4XdkF? zS?0~12}t+7Ry)9uQB-+q$X&Z^vEQcCp+VU*GsMlCK_9eNmB0=R0;P?-(o-m@u7(xv zqpbWeI$zFSZO#`{`!&QC+ISv2PourD2-JTZH!+Q{NgoB^`fa=d;2D+=3Xi9-3iv7X zqTmZ&hm`7UmekCV1d5%Pm)1v>_HM6Zdko&uVnN|*Y3b#AO|$kw@qkIk|03w{+kQ29 zgNSY*i`CS)d<~agXHE&5aXib?M^gT2$r4kKZIcq1Tj*M$gSzFemTAhJ+lL3UCE?7O zoW;I@BYoDZWhW7CIXhLslywX_QaTW%Q3_z;;JQLHIu-1MK9o&ov~Q}*E}NQO0ovr& zVZp&zU-;#aBSD#RD;8~7{Gp{;U+I(dOzrMf2lt7^>QYh=r6MI&mi?vB&>Y0t)SAAn zOLmT+GQWWem8z2E6uK;>r?;W0|2}X<HX8ZFCPjq|AY==X{fudBuESI-|17 zA?~o_C%=m-8anBi&b3>d7vX?*)JpILrX}Rlms7n~KB1$5J7jYzBdllw2FsH?cZj7U zB?-TczrkER>a2WmS^dAY0B6sND=_5cI|>9A5iOxD($Xql{zF$&(}8-JfVTL8H8+z# z9ijj+d&hl>);;k&i3B1Ci=gtyy0?YO&jpjHWhu#)rn1e&>i#VopWB(6ZaCS}!`Wvz zBC#83KSQUeAK1S?a@sKpUiOQKr3K17LenD#tff!DNd5eF)wy^ARE2hMy0MdfeV=4H zKN>~)rkI!l{tghBh;(Z_7T5$j8yaEHd)9=CF$ZZn=>~GcU7b1qVvPiZzVos_DY13K7IP8U*%uM4cb2t?YoVBr90Z1hd$}&yk*ZLkl zL4ztM!Fpb6Evv8#8YCDmU#_y%z)a45AOjF@t~pzw_hB}i(2uk6c-u2o8itHu(lRPy zXv;3YW5*!WPl!auKmTkf-Z3fRPT+k)2?K=baYV789D6;b^Hi*$3<)&tr%rX9shbg8 zv-h0MpC7}+TwwdxZ`hzNA3`7odj%8XN-(-22)c@4ghLko-Z`?B(2V{B{+6&wQQ$wa z9}gO2ZIr$~JfnY8SEn zr!GKY15Zj_Rr-svYbhNM&>6`orAh|}Ll#3YU$MDXvz^ePo#*UZ+WI;k-*2wjoN|&; zw1heNAsJP%@AbCCoLT>IyQ{gW$M4fGcGEdcog>uiUv(kGzkK<3!<8eMuWzbkzFjCA z;1?sUT(S~lrz=;eHuKk0QzA;ccKNa(P;!xwz*H!_O3omQC#socPYRH%?F-wuJ>A;W zV>yi#4uR_GqUN)BqH6bTldy9QXuM$<(!)ej>XCVP7#6A;hK62TwINq}!sM~PR}%+e z@_4fhQ0-jF3cX9AdVqyjj~;~~j*l1SDPp=nnWPX38C2qaA!|E35TLv8(Ec7!H-6W} zOcrK{u0!e8H8(>ORyUflli;rxGYN&tj&xD8_h%4I{`;1OYg{gvis*>B(ykib#u zgHxes1wV_B**jH2a9O@e#oH?Ov8PLS@Q({>2fk2izYnOIoJ?Ac%z zsk#^}9d96#1Ebi;=qjGXMYL)*OF{B6QOt)H8H+}&RKKOQwR(c&!nV&J_Qwfb7A^l6 zlD=r+!pv5!e-2OF!X=~=4$i4*+6i4aZbxJi8*p}ohIVfr^&L|wLGV1%l~%XD@B*GT zqC6lpl(iTq{yGH(JVCZLJjJV|%6al*Z~C)G4@52%mdz7{KeTth|QukfaaRLES`)@O6aC*P(*()T!^mgKsS?;oPOT-5aZ^ zVfehY?v>uppJ&Wo9z@j2dx-n;)1XLltD^M4ilQyO#ckmBvegt#9Ry&ts)c!R#U`H2 zcH_Jp6FhFvpcPDjX^c(kDYy_o5c;DVtsy!~Y_2aX_kH?-UzUA4a+KVIQJ2VXJa*@_1{`ixZ zI(|Qg1d^Frbpyv4w2uhB!66vWLxBbl!}yILz{4P*{@eN!%^&8q>%Q%k zYu9KYiQAY(qJ=>**||#>SDiLm>`OLxg9wvc37l;NV|x6Eh}jeg*v|qV3C0MlfJeby zxqZCFB zFKAKFniH&ukIbDKO``VL!=41HXvQ}%l%@NmUN>0UT3_})_$3TyW|`+;y^Qh=bXC8B zUkFAL74E@+Va%FeaDJ!iK&k|C`uXi!9_ogMzbRnE4RT1a$%5i$M6zpBQxk4VJ8Pm- zvm(wWB$OgcB?1qW7wrvc0$ZKZ2b5=ah}JTj6f|hxwuGDuYn+``@3lx<&Dy4XU3w-d zc$Dl=e`(gm4`WoBEKM~9iz?yZpf<5Dg&aqTt4~7% z|4bVXiN;}l!}spmwE0*#6aBv_xI6Eair|huD2)&>2qg@nIka#?ZfeE0023=3gj(dD~ z^4^*MKLsUH-vQ%+LZSDH0rLL^7BwbjfO)sHv>ZKh1P8~OmU9&U%FLufQhYF;6r}pg zI3#Q|FN${$KK}I8t4en*@#b_ovkeI3_pRyHH@v>F*733B1JZK0Z5>dp36L;we*(nKj+g4|HGVTHjq@TNup!pD{BwLU8kb7`Xml z3QLXLq6_~r0Yc55~IQ2JZONJ~Z%jN#eZ*l(S3 zPk0p;9xl3jaX}#X7)m5b6P6Qa9l{+kEq#?0wp~^?}nrfR!Rjcvo4Kv>bfEtq5&f#lE?x*`gKZZVs37 z1$udYU8p@m+GTcXm`bHn%SMT$o5`8>1B3rLezbLoN?p?+H8qZ8ljjdlnSi7R1$LuS zMvfSPB$m?Ow^B07Im2F$EDSw^Xx!1x&b78;7L8C;+$$-;z^C;lJ7L(#!T+3=Hk!7M z_Lzj{)_Z{00AI~hCJ*+L$Jr1`U^o)Ep0XTMzZkmx%F0SAj#{x{Z8%Chap}@7*PS2v zK_vqQK=`w&p>jXE@=R;pi7j=g?Ruw`O?_~X4w2K}Gh_-d4WI-Oil&K{Ob`^MMMGWS zZtJZkJ$i&ALu}VE9i?QaMC&9F)gk>49y&BuC%?Ot6cs2>vy<@aZDevWXAj9~y_A-b zQDI)5I8#jp%B6=aq3DI-LIHqN_X@UD0Qj<3^~SIw{xVz_lWAfR4r@2fJer5Rhr)&d z+pYrB2}uZ+;PUnKJ{dAALv=0kh$K%k5CMJ5>ie`+ZQltTA)%U`GFOG{D)iEj10 z#Eg0RfGH5^jT9?+rOB zr8!9YN8;}wR-%0u?y0@koGHi2$~=^wvZst!dHA>9$D+s z?n9>6A-EKW(U|Yqy6z7)&LgL%e4^E54nE!~iT%AVU-C$p1tXNDh^7ZHHfn0|U?VWq zPEKI4<7_eldoJ1;rNiIPaYi?i#5WWj<n$BcQ&?BcN% z`lzX>oe~i*mzPW5oc{&X0K0k5=Zh2nI)&7gMb1xha?1W1wkDsY?64^=ph&PFL{F6L zihpc78#xy(8H4E~H8cWR9&*@SH*CNyld}yTSo-xVv*-gnO1>1QO=S7$kRcx^3Ly8y z)jZw0W!PS%8WiN@)HiVe4%9PR(pj)^=1w~`W)LD9jGJPZ3qnamDe#XSw`ntNRf605OmbcvOqcLXw z*UBru#s_joe|e@s3zy7gOIa!y5Bo|Da$MVK1H42%c~cx_yn4Wsw z4h^eG1lxo^Bz1cmjOr^|uOQmNl(nN^erU{aef^&#GMFQymn@~Xy6(0Lpp=

*13d zwnn=i2u~hm9oMh^gFdcFfTid=lfPr38t7Qe7PKp5UVeJQ^peGku>fbV(Vk2T%2 z%(TAP20HffuM~c^Ax*AoNd4&&Ma|Op_cN(n=(mB0>3A;A^XwTId~&`MHej^){0>YY z&!0GPl{HbQ7D;DeHS+W5H@5b@E}i4o=Vr6!-Mu!iD?6&X+L-m{cMur_vDH_S79|KG z7s5ZBQ0e3A>c;HcH~g?CFWJT8GX$o1EHuTQoPQdJuB>JSSYR$EyKfC^R$l^BL&WjU z{Cr=xd3Q_bAUHBV>+35PY#bt?G?gD5wQ1?ur2nGL>G8PU7f2QT6tlo$B@GA)z{k-7 zCW^S8eMtplHGT+8${0*re*8R3?F=azj~%mr9xkcp(EQ;==g5o4u3Y)UqAuvKemy0W zX5#ZRpG`fOL$<4^oJpn^k{$E$Eu>eaRHj4b&%SGEN|=AZ1o}dILl-;ie);Ecj;I%iIk8KPadluWSCF3hI~7p4C#(gJNQt+xqXJ z22t;gsMd97SHalWINt2O%>Sp(N-Vf2Q1^bJ1l1rfgNazU*io8fUdE#z!7RGN1WPobIY%dbUVZLIFWAn7LJbkjN8;b z>fflsAOWWkhU1@y50OlaJz!3O9 zs9MOj>{*cYil(OgcKVdf1*aFo=x3R!p?ASfxOTjZm@mu^z-b3IBpr3z#yX(g6d=vbUOWQ9H!ZCV)xF9@Z^Ot{zG!k2 z5^U(yAlGmA4S*x`GiDh_@U|8v&^SD$+R@Vn!qFq12O|7NJC{jv_;)#ts6jo1wK7`)t=r~OfU|jeojK=_AFdAoT+i~7h&ufOC zm{=qufxPh{8Pc9p*f6DmAQ0qZe}+`z0fefi+kAq0Z=00;_;FC`N=|~7LJlA^jTR;N z0oF7>ESM_y6}>$oKN@Ice%!=2PoJ{d$AOdX{?!tn$h^^0d-F>5wuS&sr#h!ootn7{v-9AKek>fbk-42*OL3zF(8c&>yO$ zCHg6R{`{Fz+T&@-wDZQrl`)cD&O5H5QIN$K(9)6#z&q881`IQmh}pHRdg37h%h)p*-oeh3@I)>P@eYzbPuuu5z|=Gys?F^EY|kX z2M&mey3_*02(`O{DEmeUbdEO(E@x~kFwuonRB6~AoZ3{BmBU(724tO_vvg_B;}wD3 znfDO{AUCLXK#=`;+uPl(8~bbdOG_Ov2P}WYMu*X>6`HbnDL^1}q0?u~pweYuYI;*B zuZdAa_)2D&qi`$g+t+FB+VK0f5vY`fn(yCn2al$@lnG`OJ|AS1nTMVIYinx6z+c@1 zg?tS){bO%xSrOJovcN`e9MP4Oy6Rjt@@jB_<%k*C${-~rQp)w~yQaY!Y-dT`BQT0@7YikNFbMr7XzD?Pv70A1+2$PtAeGQ?N{&!fDQQQ z;JjJlv(mxS*~zIMB?z2SN?Ab|wr7TBbO%AVQr_j*RAgO?)I~cS1||h#^(Y*P1UijQ z3bO!v9d#9bHG+37J1<`(n{9isBs2&>QzQk36*Kxh#EJps3c5(^5uV!O zG#qRqbT*|h+16*Zbg>iAC%xrO@0M{wd~)*0apSJz?>=|#MRxA727;Akf-k%(;fQ|(J*XnYFfeVtLheuYXXKobQ(}~!2!Mc_h0Ma@Zga9c~!S@{X_4w z#v;C|OL=A_O9g~Pnn%vM`yv~8_j7Oxvgt6}PUW3HklL%!^ z;l$wd{O3JPOx5a@pVc^`F+A7nB)qwrFnx;2eDm`RhTgH()%BF5nZCG)M#;NNsG8m4 zcJY_SLmix@B|5VHX*D~4Vj6d5iQaYeJ#_#<1U+W(#E}b(qYknOhdEk({ov{0C-1av zpPDcStPv?Ba5v&Knhu}_2F_UXE|ol&U(p_H*X-MB0(+aB96bQ3WE1VS_t^zwqh^q8}ArKRGO@9(*2rHL!F(Q=_>qeTS$ClLp^op)3SJ$~j4i!$b- z`570x&e=KX=uwfH>d?WDa|on_jRQG+)_z^TYx<VoN9lP2u#9ixJ)&nnmgu$}|i-Bn1(0F1-GSg#%04nt2!W-upX_ zcO%}40?6E4-Ccvbv5U{ddl5AoSSjTonzVJRR*9Z!x3*j%7AO5Pt#&SIH zR5>B;D|F>blEf*0%NHDy(lZbz>$>w2Z4&xW7XGevW>SisOG@%#6{RQ=Kjx@y2P1>y zs$fh@hl6VDV{Tjc2Bn_%24Lna(F0lwNzPE03FcfdOi|_hr}nkd+nzsVmbY>~7mes# zp_dUy%R}IR_uJcs(ExIR`_@%%VX*4}bii6f?@w3wWF`0#f!5~8Bl7wydE&)nJtLfdqxEtQ`d6=AyZeIvs}zvCv=lYky{%UNlRjYPZ+$@UK6mib7z7$G zUJO!KhhT7Wa6sd5nYWD?;^OC@$t*7)&$h<$LZ!>B#Gw!4$RiD0HEsMPadyk^Gvlof z9}=9mP(1Txh-UoDw>P|>!FZ&1@PmHLor!vAKzd6{W!aqB6j=6*1G#Cpwh!kN$X>OHJsDIX8Zb z0b;_s7rlAZDy=qf;Jw=g$si)g)~IgzlZWl;me?rScEc__M>+)DacaaEzGep@W^5?2 zMDXSH2?7WzGXg`|j-XeOkRkRlaQ zhNMEIGDIOtB$`Jdy;4X>!b@gRh7ie6NK&LCAtX{XC_|mk&HMYWv(`ChooB6|<>#g6 zdG7mr?|toSU;Emaf(3tw^75@Y3(*`Br0!-fTIk6TJ4AjaeK@*$8%-{7 z@K|BiKp$+w^FiU#O6a02uakBO2Y?Gpj_j*+erkgqGlRRPI-^Y`0K}!AWwIEgvj5{Y za)juefqI^YFx>e6u0^FO@=KpwR~nbM z<-V>mOoZ$PoWrMpj>DdwMP&2X%Mg?wE-k+2r8W~Pnwkunlb$Ynmf;XJ#!+|248&+= zs?xsthDyT)v259e2DNJu|1x=X>(-%rd%57m!PuCX#+H_Byf$uL?bo!)Q-6!>_ItpW z)@@WVB9V>D$M^4BFm0kzeT6?cSEZx<=UFV@ZuXC!K?5e(cZTDOEa>9GUd_N2o&f-T zAsf4y4yNTOEgks@v)KQ7-uLm$O!JZqFS>PoqVV*-2I7%s4Z!EZ49zznJ*xw#8Q_23 zAP4wrVqD3_a6v}HVulR|A{fBg58v|P(Etjp%8T1nBO=gs%<_V51=}F9`cu5Bj@!+k z4#N2pC+;IGcRTe_FL4$O)8ogo5jo_ZoCS9U0=n%Vf?wVC#ZS2nLP3QA#J@0>z6uERZmh+XWWZ%k1dn9^Y|Cw zi9^9@Z{PUtfx@2A!e)%r)DeH|9bPhPL+|hA{Cz-t?Pg^PAoJF!d^f>})yWBxzNDZa z_CjCP!QgMf)MwXFi0pMaNaK5om?-F}!p=A*q!FW`yjMIB&Bzyqm`?buaGlwu2?JTB zD}61-+$(R{%9Y*MYCJECrF!Wi0%!CTVQJZ`Z{PLE4{5&w=U6}(WWQd+6Abb3~}df{Lrq zA8~rng*RSYDxqj7W~ioMaDvURNK@Nz$)MZt{*Q{`8m%s-D1@m`G@b&ztN4;f6)1W$ z>4DTq$^85GsqJ%gEO$P@rOaSIbuv}=Utmbwd0JVitEM&r>^H>z=*`=sc0StNFbUQD z^!4lrhFWLkOT@+vlZ3Id^D{RCF>-ECxs#2zeokk{BkrdT*&Q$VO_pc9Md;hRHZsU; zBdrhVy9+-1+%Ok$M)V~X0!=fQG(*RxJh>pvS~V@ zl#w^1nOlDGf@$7jVt7Hp=`&~kvC>31Nz0eyMR?>XK1=n?vocA21l54OJxDW&y#}1X zdWTe7ZAxLzm65WH=<%yfpWDs`^oKuj-zVPu?4n6^7ONv=o=)E_lW@D?ILUX5vN?u9 zgGj_9BoYCQutb4n1W)|I9Ty7OkNU9e6b-TMIy318k_UnJ6jgg38EuMD5i)UJ&(&mk zZVeA5F>GRy>HjZj-H9HLwwCEDBuUOHV?!}iGsX^GT{F{)zY_l!urp9$Sw5$ z13W2j0uanlJ(x~3_NmUJei&OJAwrV<|71yoHBBOtpgzyy-3j6eX|X(izJZ;^T$bxUwU~=(sWb7eqP>g_1`;+nBRMJQ3iPc}<`^9L*^E|ITg%R-x=)`_ovbCF)29c|lMU)aeqL^9670X0&6}4* zCscG0i5eJ%u*qmNoo9JDISlp?XOb%iKG7GlVfqO=xm5iP!5?`qDpH;#5*t)l8IR~| zyRjR#F(m=dDSTq==}`P`sBEW&FBCvb*cTiazwbk=M&7~H&z5fT0bk!lF(FLlRW(V( z?OU=1{sc;oP$4)?ZSz3kkKpY3T17gybiJ5Wdwyjb4_umbKW?@+HPZv^(;qzwMp6Zf zO6LTH5%>mC6n{6EVMt^U!S^<+x)$;H3RY1iB_vJaC;zvo$XtB~JSD6VRwu80=!KKb zVB;CWn?B~(Q5SkPl0L)6#ab>Y%pC8npJYen#a8e4iy5=Enl>$0Fc<9}cyD2L(AC;ddnR6<9ak6jetW}>poqfalOr0$ue_K0X z{^&&$rNU&bd{PwVHrn2v)mis#plfvk->ySVwYH%C0D9}aEgSD0NT(Z$UvmrNzg#)= zhatbdPNDHELOO&-+Isyy=(Mu*UTTrD{-?PtL`4eVL0mWhS#>phB&QIxM&F2aFlFWC zG8qFAb9i8&1fXDoqrp8T=-In_l&+W9=!$LP#v&<;>yk(N&r%r;7#O%cI&q^~Q~+WE4zlU;T%-ITYjtZbr?R%AD9q-EUUHqL@Bk%$2V>NY$Ba}xCmpkq!ATImi9~h%?XbCsE7rUkcqLIyYB61Y;YztLYHSPSD1@0cyg5MFL(TdX zD(S_NOfG4y(;r_A3OGd%NvHlkhTg+_PvO#Tw)+r%+X5vUuF$sP9`3oDi_u0ZX zDP4S_3_>0Tg{O)COesau0^%ZT{PN`sS(2$AVvUMN4|e?Sb|-BRxH5{Ti-_tc6swI7|l7U;^D- zdb+`^9YHE-?=1I2D1v6}8_jUwxiX=*hq^p{$-PHx?VdB|qI);Ac)wV6#OCGpQgx>af9GU=z8s*$z|bT>eGcr&V>$#n%Fe;z^FLa${!{j>o)pw8Y5Kjpu~MnQA4$qoRn#7Hm}JiC8<}JWYX`mqL&9BpmQ z);HoYbdE>s5A||I2)CzC@7N({vp0AxX8=wf>35HwJ?pdk)gY=z_k(fGM0k+Z^E;*b zMSip_`OX9j$_03l*a0TH3E;#a9&Z_3>uG)wgC0Bel9J%7a3MIR{K^X;2J;QTrv1PR zrQEiW9H1q;<U_{QrEbWrD(CMUwz>iO~=!-y809dn)_w`~`JdI{xfv~XK;2-*ZFTWNI zOeq|k@Qv3hdj#Y4DIx80-J&QvI0~d@ zs&uzQMa+~J{@_6AY07sKM(lYK4<8nEmgVIL3O>^WrDkQ>_qfgkSFYY;GeZAb$lder z;_1OMCQA>K0FCTZI7ZA0)7Z0f)~K}v`U)fFlq9T9VMQEGkx{5Mv0xe#xRHN{DftFO zT|NtZ(cSFZ=X9y>uT6P|)ep{Zr=F-&@i9_1O?mZNiYy0{z{{S#ZXFJBE1&V&ZPqE1X&dfQshS#W)$2y|kWg)xn+ z`rOP-o4O!mVCEX-*W#HoO7;mcY=qm}yFAuwkJttx&OR1HN-C>2HwZ{1=O9BJOr4)|gffoADV4i=J z3AWb0VSi6zs!J+hgW^M{uXrfI09eP96c%O<)k5Z=zD!84H#4KLe}l*C>77Hm8nRMI z0uWtnU}2{SH?0=Na4486zj%OO5VV%v2EkrKMx^^;Nx)^XHlHZ(FAwccKKNgyVBXa(yKw{XWeH%p)tcv9@ODy!Kht zf06Ma*A1ES9Tpyv*xJk4MZ7aL)8Nl0O}YvETKS^I)kwiOn0vE_v8DMWVnpHxV8lOQ2z=! z3(?JYJ^&*)G)My8inTRNVLF66p;NDN*x7Y-+$>_Z36K)yUUN$ecDJ8*C>5Eo z+!>{^a4FV)utD#@o*Z;5(JH}dhYwHmT`ukrZK%2Z9%Fg$ziuFiaH_#aZkO^H_F_1a zbGuseZG8M~y8wDcWC6GSRtC+jTMr%~o53XfDWAeQi#!vMC51P-N~I=Z*-svi*HoxD z)=%qu=T2d6AsnDV3D$!Y^5x&MKodxYD27#V=e#DLwVN|%G^h}83na^}sJQA>djHWQ zI!?~S4l?vrU$w|A2}%-I*8Lpei;x+wO%WbY`w3S#lB5KbuwHo= zp#b!%$d=XN00))`4W2=*xOj>`NOA4A#>PK^_b`^8>=~n6{u_B|F+{6O11AZgxAH~L z3BS%EVkf*M)|myny{)O)z%op(3ju2+Nd*8vV6CVKAa@{$pgDl$|9Hny{;|YQVgPWT zzW)hi#WQBCDoLBgJ=|xo6ux%!)2FF^w>~ry?Ae=?XHr-1mo>}h25&^8U}^MhTU**_ zZnZnE1?5K9U0R}H9cir9mfH%98dcX}IjCbZW>R3rK?!Ydf^duFkGtJ4YN z64W>#f*&lXzbIVHxDluWO-!873gzeHvl4G^d4AMk;-iaIsH{bhTuR{$jFQoDA~xlu zVd}~bgR-Nu=*QI7{<)O=Eo+1dKxEP(B>aXAtq<0tXIrG-4^`Ta*0=**)J0Qk zO1LTH&s`U=t0}?(hAYwZc+~6vX#oUdAwD>FygIj~&FY)L@}XB9yU&RaNfZIz(F(D| zkLWm}8o&JNb&*-!%I5DX`B<}Y;P%pXwT%_2pEwdjlV&Kh9rCbX6QQJ}L_s&l*7jiS zu*uG!XnUpvwIpEzClqv5rRA(pL{}{ce6Wc4;?g};Hw+l(4#Rxq+BN0=V}t-h|BOi- zD1zY&F2~i*w+&I1??$ueZzxYl03%@Z#$2tYxh48DqTe-_z7+ErJh_B%UVt~sUsxre z4W1*c_K@Cp_?JSqo`_O zvIGG6VA5|ibMbEK#9{7Q{;YEJFVg1Od$wraTfrV6o+N|u)?a20tbY1{qp)Mb!)m?W z-**4mrn%##I;}kx+H>J4I0+jhRdT}q{mP2RH6!9hW=98$g>G}`BuY9bA@V6)9b6&1 zl)G|!@rbsGR_(0}i-eg0NLAZL^p%nrH?Tgl!gbtbeoXCJ!gl5Wl!=!e*qHUcXvuk#=$+u%`#GhY3)wyRCC~ z3n||iiiL;pYX!>$4%@kVZNhWUi<)^1;PT4<(8$OR8WHZS&qKolQ9P`{W;%VbOsgg> zAg`xhB-}SOH0&{4{zM4vCr>hf{vYNs4J}x9!BOX%gB=HznKg4+=`Ok8ly_slop)pq zk)g``?!Y)JP2!@-x|%q)!iLPxpog?=?0Lsia7rj;MDzo^c^AU%xiL=*hF36Z6J4#jGV>b8Vbk zZXUOfC8+Y<1eByt7VaCveU=KZ@-`CDq3S7Ovk+a89Lq0drqkO}hN>;uAu?O0C1z%@ zdf!9)sfTvQXUDr;ux3Qu*5YcDTl7y&gP0*3weuHDjT4)ZpR3T{F}^^rqqy{GqjB|| ze6O@>wYH$0<1}wHi_C)WnS3@2PJF%5N=~HtYTh@Qq@7wJTl1pwQu^i><`0W|rAkbN z79wjAWq_GH3*TlOE&fQMPY&cr@f$aXS-o7?;HMEXG^={R#NT#gPUcpquhH|#A!iXE zCNw4JlQ11taU&$8r%tr(+?;h9wf$k|Z!No!E?_a0eWO;+fzoA`0xZ_t1Ber^s7Z@~k zvq;rv($#155L`Ep9_=F9GySOM1EX~{wnD~ONtqB_SB{sOI&0WGJcMVJcIAzL*`A~K zZF|Eo3o3F3zyNMavCEM22|JKi3p!GMW%T3l;fU*}G>w#PP^R%GfH7YDh6#_PRwBBa z!%ljZ#lh7XZi`z1O!P;9RuJ4;)>CS;RU^|T-PKBUjFj}(ijeq>xgpbA|)!g;fweeb6eclcC$q!v#I?(>xWb1DS<6j&*QaWg3^yeJw zqto)|B*)7RRkYE%aKdfft`|vxYVYd%*S?~ZhlCTyToeXPdVq0;kAPAM^*Cj)FU(ZYg3S!>_nX=BtcY^y&00YE`@ zNe~yQ>Kz>%v5mTte$N2iH{jor2@b4oB5fj9AkyHc$A5wh+>7N?aO+<f^;zb8 zMG#&*f&>C^S`TUIrWB?Og6=H%Y%1^pU@!y^Y>2+5)ki@gL2W42Jc+w|_wEMbQ#YBT zi>+*ErK*QT<^`IE&_+z;_HYf*#K=`j?Zma`GaBxcy%-Q59^Z6CqAbboo9&bOxcTuT zULBDcKg9L3*^uR1yVm`1&A!~fUan_a{tmqdv$}JT7^9+h-a@|R{jqZmnS^@p}N%F9nl_-Fvf)6 zJmaB%(IGlD1>HbaLx+JrV86b71)TInyS)z$QXXc_oNNFn`YN=f){av^-#}%I{CR=F zdBFfJUk>i-5`mp#zRCCnEhoRW{lZ64sO)G@;3Kg!aqhDc2llWLA2=vJo?}FhJq!VA z2sfFnN6lmK0-D;>&8;NZxX!6}w8aPDFPQawV~}7 z{geYnYZl}63)BzVo_Q1#fohmQY$6Qt_&zXCE>%}xcq(?p_Gi6}sjv}KKyzP&*>*-8 z;OuOjr49*eFYvBWbklSfr&BE}!Ky~qn^TN1O3&!rbl-H+g}((EobDJb{XCs#2hAgR zER1+R;=_^%m;cDH0OG_`8z6{10)EcDcSf5YWnaAJ z+ZiTWiZiCY@wsA=8khSzuJ`i%e^$En&g9CIJhqISy6H*0V1qd-^V2825lLmHrhZ8e z)kx&y26`dQG*nte^kuB0HmPYMrUBT4P=O*jtbtX;;c{KgWB703vKJTITU#HOTw%s_ z_;C`5hhYOExZfzwX`$&ySRtJI901!$Z4m<{?lmnLR=ka8|k6#&TKK|!;7cz9sNf2s9=ma!c6#0aN(Z00~ zWKdMf|I6oUwVda7@88Fp3q=kC+YsICGv|z1?=GSv|Ell@Ggf!mG|dGS46T%vf1Q7D z6I_#|p(!3!SI;U;3OiDD{($U$mVsBxjc;plTk@sxlhjc>zVr4llNZ>isY^Y-p%NZ` zv!cIEN|!;sMF&}EOJ|THMd~QOvev!lcQNQyREnz^3=ItY1(aj!S6OjUX=&+$2h-TW zJ~+l)xR_aJ{tHqjyn6n;6|xZ_&G?I}gMzM8X7eL?ZnkG`os_mxV1rg5T_RrspYVJ% z_`_)XS=-pG_wkuJeL4a&_@I(zwn6{Q-UcoTGPGaM7V|i4Q1sckQ1C#YvR}GK3k{Eu@@)Q?Pel-g6_2 z(p=XdV(A$CXK7HdMz87Sp#{2gHG5tETqYAc@YT!1Q}kE%^}gc$O|!Lae8rx`#7p!t zkbfYh5(Wlw8SXwea3T=G?*L9rwhj);5Oj3$*-Dif4FWPL&K)L9U8n%>(w(V zz$ZA!YHJ~5f!!!IJjV30>gCRbK9c3gGrW^g8(*tQJJ&BXF^|<=H0sG@FW4YRuT&Ud%{sLD_Pbk8 z{`LN%e9BSG#4mjRiwku`IoIGeVdDZm6&GM3y6szs(rjw{KeYLPQw)Zd>^-e)1a zcO7n!kM@p2AzZ_^!t-kUHGgymq)2W8HYEWYmPcmEl340@9XNoPIfNw~BqLBWKw1M$ z3k413xSg}qk3y;jBvLMGE>n0Qo@rdS@6AWWbMa~vz&+QLY3T8*@%hw-R2QpR#jeW!?k0eYU1V;X9e|^T=^|XxRQfBCxLjMY8_(+NlAZ z!&L>>BE;3a$j=x*+L)V%)gJP9SU*}q!pvMud3?7z6M?7@I}h?M=t{)1GmT1ujA>{tMG7L(<<{%mgQtFV9Mde$f`rL( zFC2)LvG)GwNtlHyuElZy3hv(`4^Sl3A1x`K5TlwdfS?XRmYqL11qlO_S^g~f9q($k zWQkz#fk~97r_Mz?%ikiN4ZUXIXa_3^325U}7EO^#Jz%)z%_P1iEm;6TCsvA5o-uW? zOc62v&|$+;Un;sAJgTX#KJub{oH}>DDV(54;YuJK!AF=o*N=rqB-6F)*B{N&{SOR` zVTUGfQJr}nhqP<9yDbkZ_UmW$W*Z)*U>P`b!mkGW1jaw@GpoLK zc59P;KLd&2jseEkR9K~O@@zI+FOo+rxl0#K$csb1?jnUD?50@>516=j?^M}H2BJtY z*czdu|I@Kd)y;kT756=1zJXgqlwlWh+J}|&2+7+^(;Z<3u&^2LDzb2v0rZc7Y0xKw zVb??aJAS6KTBLF5^XJ;~-6pHcB|fNYkY}0lmPvZqk@w!RzNw}39w>|;EV!961gzKP zJs?nolX#WZs9vOE`W_?QACcYz?@jz)X14q``VV1-uAjq=v^`;-C8rLRx9*UE+{PPd z&+rQfCIS-<5Sa*Dfl!&TpL(5MlH8`h@u+q_&+oX?lkO^->|db%b{m<|=)$`mtOXTT z5iy4a+sU^e0@Iys#x+DgVDvbDiHeIk3a;w{TSz6ipZX$j64IEwe91m{voW}ZlPdX# zcki0gA<4{q3SPN)&mGQ%`Uu9)NK=vz_{x_@k%enSNo8if4sSO-bYdHf234xwph0&L zfSyp2t(^~(c)bW!Cq_$7P+345YN*uq!w~madK>Kr10v;uAP{;>HuT=2bC<7P4WII- zw1;0ox>q9{Bjl}EOE|(=JpR;kWUsk%>zn>TtCMUqm(Cgd zkn#2H%e26p=o&6l2=J94pK!)~b7NrY?~lvA@rE%VF9Eka+Xhuf4f67<7W`K2S&2^O z4h|)xKjd{BT%b8q3npN#{kqYAF1~Gux_md1p5}){&9xIKpsODWzIF!|_;>FVCanLU z9_Hr>pn}KaQM3OJTPdfDH+K)$_Z_M{K}P!SjRSq8B=AIjmE}uM-qYJ#Fu<<-*)j9} zhem=Oq!+lE070XOZ^+_MhR7+B5v4q;X_%}YnPtNtW2!^@_0p^0X}-fd=B4NkY@Qov z8iL0HKx`jgzsM7`KkxTJ7SCN2ZZ^MjcpCaQ0{SAOfGle&k%owG2mt`~0)>y+23Dx%iHz7mW{{1(~5`hkSwy5n_Yrcgbf`?lbbbrdROdP=vF#j_h+PK3;f@X9oVks@LgSg#{>JV?S)nq zdrhA|mtvoVz0a94;W*#zlF%f?Yo(Yw%=(p}TjTq0!seB!0mRkcQo0E_o`9Ww2D{$j z!)N%Ueg?9(1!hAG@|0>mf`8;cnfv}5)X!X&xHtdOYQgY<5g>#Z-`{+kQ&O31BHK@j zLAWo<*NiHUvfe-db8MqY$mdEYvunpSzkKVYL!3HpJzi3R(LW+szyzi@pFbMWo}~er z{Vh|qB#5e$cZTO<6U9~K!8FeyO-TpmGcq3Dzh9f~dv(&WI|O!m>NFT4%F7>z_UYaG zf=3baO!q0R1XrwEQqxwr#(8R}zB$~MmXs&#%~-I&mldw=6Z{tWSp->A`7qi#-JG>anLe897?dKQnmhR{p_;oVQfK)t=I)lcb&%5Aws^u!} z7eTS}XcVSP>`W0Cp+wc#=C&VbCD!3XiO}?gIM0B&U|)mR2B1yP@!UfG07rz{tiQp~ zqCT=-}6%?b8eJkdU;Nyvm3!BvFVdktz zK&UWaLU14sk94>YfewtigNHOf^5LULx-5@PY&vWHmlxKhCLv-1#$H`sqahSP{^5=~ z%Py1=v?-e1;&!mAl&DJTW=W|=su&YxVbV`~uvRzz5+?L3RIcU5_+Lfd&Znuhg8rlKh-LDaAy7KhTPzqii6 zKX3-*$c>>Pz^l5ZC)6SaGL+%G824nDg3spr?{8a<2(=n+DmCmtXD0{P0m0f5sZK5R z(Faul8HLWl{BzEh`6CY%O@K*Klhj$FHd!_lZ_1Py%5^}(IbRS;!uZCUU`1Pf8SEW3R zHLfkb(=FZc8bX)trav~9FGd5yd;rmo!KAMf*Oqh$jJ__NEXJPf7cF|tV=Tamk~?&e z8&j5CDC5q7{W-SrQW_CCY-}M=)_K8i@$Ar>I&h$7Hh(qW>rl1Rkc|-M=Ix&>xPWX8 zXzk2|;!{b?c8oVPEVQ!PY^(h_Zl&k;KQJq9h|q`w5V>q6u%($m5AJ8q4oMxID7C@1 zl3lvsDl^Mj;V+D@nXvFeS^UbSn84fEpxU=%#`xSh)tS1u2xI#8x9km>Ln44CL(t5h z31}VE<}kM;I^9uLR@9>hrS3MBS8b*!Cz!Up8t|Q+4)uUDRBQnk@1B|K;$qXXF0i3W z44WD$38Dl%DOiv=!RyYTgK0PXf3>D#Da2ybtStXT<%S;O;a=BQQx3seuqb1nyX>nM zAydb!U#aD>5Tk16^u>1|M6d`w2SB3in&q_JN^>vY^KZsjxOlO}su5DYl0w*sb0bjXY57s#F8;FHas#pxr2O>nif&_oPi@Y>-g?0jS~>aG1XVWEW| zglFu}E?{|1#W>+xePI}wuuf4e4D0<7G$AR<>sq=vy%pA9(3+h*$uz2-lLe835(ngb zXM|8eWc7*89Sc>5u9POZCliQ*k4WSD*HZoeg6JPY+Zq4~zl?5_XOkD=0Ui_z6O_$- za(<m!n4Cir4yI;eG3YO*;PqgMOr8nJGQQ zyjHCuw#=A1mDTUCJ2c&Q+iDA{gQRtuf3>XYC8L1RKZTVVY@HA>F_u9Q%17p+!y*PY zgahgKctZ(in#*}=i4GX7?1UOWTH=i}TIF{LFX3G=#P(r1$P z?VI*SkggLN9TK-`18FQa4al!RuT4IM)nlrKGr?$NYO0_f#@+jRi!HE-?@47^6Ly|b zyT^1vev6R<4c_I39qFoxFQ^{Bt(^XXs z6_o0_LXi^1h*U-f&-k70gJf&pq3fnS=@$9`o+wX;n5;i~G~1C9{Jf{@`=16;&?3ic zS#Wf{yymdI-{-0S(*khA;S6;8CKN)^PWy6+oebl7wkaf9JOu{*2hwGnGj7nLAbyr1 z$l+P1wXgUtVzR7-Uh!iQRYLJGv%_NMpmXN@2jhMXy~rwkEoDrcWJrR@+sT%(%h2b;4MG{HqA1BAds}7!axfyWUTR` z0!p6K+HJs-t#vA-8E`CiC0>Aapgi;|_?G)#pT?GMK;<=ZGg@yTGEeDD-^qn9nB-^N zjF!r8b}f>vQ&$U36eqj~*K@-VAA^yF1oA^6T$Ocq(4`#&EBI96H1#aGoG0<#2Q=GX zBSK1MgFsOVL3KbD9w46qzUN%6T`SFG^ueTfUgw*G@}4~^t3Z+DZQms zwWVZ~LvNZH1@?0(YTowX9ZNJK=X5y_G6{gRo%p)r!s5c`1yxbhd zKU!sWy;vxJOG?(E!4-B)*J720{)T+#^5Vkr;~#0u0T6`HK76=Vu`1O%_h3N0+JH_W z$=Tj#@u8>o9WY)N3C!`*9W~LoPjSDKW>sG|U;u_nL|CRsLt*md&gQb@ z!S?ocm^{Y6keEN$l1JEEK_~DRYVdysj{kwmhk+I779Au%knM+|*B-Cje5a~L3I$dF zpJ(fO54Kn{LUXWqdt<|dAv%#)*1oR1URpoacc|vzh^^g@9LtSS`8m}(>|ZS_)8Y5? zL{3h7Ob6(?b`hOBAO6|%=ExmHrb=7j!u^~=l*DG1N*(?BiC;261TFns(7aPL~*D(Wo4I4cjOA#oM2P5Z1G}t!|VqA_e`5G zgKB}m!|N~5M~w`R=C*L}FWK8ym*_2CDQkuy)-a7*PI z4R9cK4PARQl`B&e0#{|F7b~oH{J!++^+N|*rfuV5aV)7NKpfQAY z&)AuXE4Obx?D85Cop&Lb{F@~k*~Ku`mW3WF7^=}%ViQDpIos6gK7PEiD7OpDEx7Vm zwA`V{ty}LC`i1@?WA+H;*g~{;F{(TO&CS=|JRVq^Oo>%`hiyewmHxp;IS>;5D}kQ^ z_W?_dBn@dM`XNMp$921@H60CZ>-^+N)%{)nR3z#}ckNwO>T2>)XS2)EQ__QGblOqV z9B}k#`0*jz2KI0b6uY!Kr}gXEvR5~&%Dw_PQcHVviy}nFj}VA^FoJ|R!gqLkULheN zuuqJ*Ojm05;W2{R9KYrb-0D)KdDMW%&v@KSGVZfKdC?o6QEIkTkxXP?X#NQ_wiu?F?ROAD2iSLo+lMNTATC4^7Ar zwB>+)hq+C9o}()mKrAU~VsfjstErOIIX{isJ~Wu{EjivM%i8c+gLO4K3tILwWHd~)-hH&g|TJ@A4m!)%6g$-oM}wQ$*08SBW+dc9)q2*wTG zRX6$Q;2GA37+nLzgS>pEoMA`edjAzZjOyQIhVh_d3$u(h17$h@Ni=F-hGQI zMmt{U;$djyC(~Cabjdv|%R`0-eUNEw3)`>!;#$|1mUDq)_m35?ztK~&XLxLnaT`1J z9(?QQjB_4x)$ejHy$avb^<0^)qg1p^Sn`1VbxLJB2jOmMJFAnE`DD^ zFOFt$LDNT(Xn}5IR9J>##zhN%0{G$C#zpvrWrAbe((mhm9DcG*rLK> z1fwi3Pg_&djk5|{>!2{od&{JA8%KJUbz-9a>)VF%j%LJbOy@1gT9;o?u!?Gm*4>vK z1_65Es_Y9>Ie%K?I6i!Wol)MRbyS69CSFDzV$GqbkC8dE0wgk!DV>Gx?xmP)tSCtn zbi?SPPn@U)G7$XN87Dt@$0q}$gtWa&gjl6|28WXo7_q54W`PJ3oQ}H;?6#<;DT-cj z=K1sSr+%J)Dbb0C`mM?7dk-JN+>K+H2w836hpShvtTEb;5SpVVa?D)u6d+5-d6ez1MsQ2sg{s-^=={F+$-dnV`eN7`JdG>qK!+Fqx@Aw+do z;NgBcnM4(TWo+uH7y0Yc_t-jUJ}gKXZ#Y7&JmtrVj)n_`n?HYc|9^~9i~q6 zdu6ShCq2(n1Km@&p-#oSU0+v3a{zYrV(eAG1Mz663S-rHkDc7=nCV| zo-tAc<(3`v6VoYt4j4b0+T$cH5?WH{e@RAZ_=4^74k1%0zAKKM)yolL!ZoQ)tTc$+n1o!!n2Lw)g$Nz2-@S zJ`lUfcrhHHU^HR4yjNL|tchAuzO|H})!JiSU0?B-oOtkYznN;kk;}FrI&HfU`&blq zy}w*Do9erU3xW(`3`Pus{4>^M6BwKF@i`AzV+<%IC53e}!u;dEY9)d`n2{}kzTs{V z|AoJeE|$J1K={w8-rR}O7!sc?n~@ZpY%oAZI3y`FLbmqs&YfoVy}NZc*?9l4?9icv z@~Wt1Vexc)Zk<~+z_s5%ncjoL|JAClHgg`J->>ju>C>=OH3^BE>FiOexJVdYXM9#~ zSoc$>U*A(%l;2AfN}6a{rL8B~rw{4l{)0tD>Y~u`0ipSkp(0f&{gDxG7JIA;DzNC= zH*R0|88giOdGq2@&pD^VLq+-{!p`aQ4~L(2AGP1K$J!4Twz8hDWE$$1ZLLlmv~f&E zMriKF7E9lnE6ZS!;W@Tg%3j1p$;;&dbY8;C=6FN=zH)cVNQj-^19 z51{c0AZ-8fNe>~BKnzWwu)E4~Y&386FRmOubH)_;522o+#<$+GB{u{!|1n-XJ)_mt zJBbF(Jb=#V4F!a~z_X?v0JK09U*~`9N$TA@fw;y~uvsmC803IK_wL%-B2yKQjF43d zG3K-6`bnpy;Zu?I^|6|fkHnKF#$$bsb-hLsEY;;Nu3FV^WS7-1YcHRd-5z+u3rOahpCEe8Ak$L@^@_eV)nWbk+pIHQ( z8jk6hu$sj2b(%?8U~`|(uX+Z2zcocAY+uE+!?7aZ+Vm6|YwLywdgqo%dR9tL_$_hZ zz(SAKj?DP@s>9o>2nrwVi~?F#^;Mq`_pDf4S3z{}oUG=6<@qzMu3lT(b|>cC`r+eJ zmUR)q5kE{qPjvI*D(7o`Ikc5CwdDnaf4~GUNN29_gbA)XeUZr^Uf?z}cak*Ska6M7 zwTow!{zpRMJw`y>&1!RWCU0lEUEjY`9)fs7z(g~Vk@2mwH@L57L!NT2X%J9vuxoXC za2$S+@IudiH@7URzy4itUFPLBjibgr)cnkx<*tzSHWo_@ZjUE~{X7uVD1vENr4R0G zAqpLyW$VX=3)tqDq#N3E>;(jF$(@iCLdY1Q-UzgmW4a$D+TdwuhqHmC2e zW`$D=%G!MDuS-tbjYos+ysoc;zMr^tbh_C1@y|25cInw=<;vDyYd3TRIcCWRx3_it ze3;yQ)vBrwk`zui3M?`+MWXC%TYK?KUK1zX?kJAc(keXgW9E?~X4-)tFDxGM`9;@| z-_2)ZM=raW=z6Q@u&lE5(4ifx#uCVbY@$aLBQ8U$akR(-kvKUTMo4Y!a=f79TeilC zY+nuT8-sS@7dk9BoQEkBCSVYU-lF!<<9$BsyY%h8TQ|x&Vd0%_&#&~Zu6F4dO5=qG zlfBQLWKXI`wpg})xmqu5&g3ZcCbS@L;Z-*V*Yt!Xr}B4T@=`={r0Nn}6>y|kNL~0g zgdy0(9XZ>Z@m1)K7eqVNHo0FIP19dwLGw8}TJq`S>n>JSc?{vuLw;LdKND5TEYVSA z;=$lkpCwOzDA7K^O$7?ic6O+hCM?)oR_gL3(7lLuHwmh6b#CN+(Oj&dkXP9L%mlkR zVL%Fk3tAjx0ON2di$PC|dag-5u?8ar8mms{-SQ!`(`QOs{O)HS8q;0BU&HrT9pzu% zbm}BFF8J5ygz}HYukZJP6@33Fs=@pDHO1Q6s%OI+zKS_HC1pzK#)A)Dd%^0trCs!h-Lfu9V3i|Y_4}D)@(ro&4Obvefy$Xt+6@c35FkB`6 zbpz$(7Qxp6Z6KY83>_+v&S@3z-ruSz(qG=|SA)3rP>Z!APc7&=VubgnzI*nJs~D_T zAM*L7pQHVU3dx3j1nW0$SG^t9Wc;&Y@`64q`^fzsvi1Cn!`f+PFQwF42ct)cyE&2lBxgPp{#O;AuM#R>TP*f6vB`YS4X#`KI&$SG4i zbf_w%LwwjU?=@i`i^FUrCrr2;q9WgC(S3QT9-U{;etzMDvu)vn?$@s0nR0o(Z&ZD@ zxZn3>-G&W|IH%8lds&b$IOkd4NmnZ-P076*yKq&H9XlFo(`I@9GP2$Ad6S9y z$Gb1D<`nmiw16%T46J;oSLXTrVh@*VqA64262yId9WTkq_X&Ft6(`&Jb&4qTdO+$K znP+DuMN(bGTwT#wz0@!MR5}rm{Ic8NnHCQ65BI1A8!708UmDZUCflpiw8VCkjwf1D zUBlc9%_esak9hq+Z&BgE);4!h=(`7tDz9}YfBXG2F0Ns<^rtIp7d_M2WAJZMF$gQ| zC6KuEtZTy2ZPfwXTU7D5JRrS0ZY1z&41j0EOnyQ)HsqA+jdnVRC=H>x;9Iw646{fX zsv(};F|hJlScK%FFE4sJeTO>aaA&Xm@DCd#Kw)(7ibsz+gLPFD@`Axe!L7k4R|J@bN>HDmF+BvS&qqgP14(1t))FmXLX z+0=ULp6RkbzrJo{mL>n)u%UaeO;Z*1J((ZysWvos`M1j26=}zpe{&h#U$bfO=~MD5 z3+zg!DCp!&IcsHQnp+SbIB4H&d-11FhtId0+&SxcNX)ly2UEX_J>X;JALMm;RHSWb?qYK{O)9LHSz^)R+1XX^nimzO55M=$;zn>o?d*|- z`KvNC;#Yt6>{zM6^Lh}UdFv7J&$hv%^I#JWXj=@Lp_uQ765!$OgCxcFhFoD2#{f7* z$eT6463!gC*!S6)sNX+xUJj5M==nZ2Y7%x^V-~m37Q>(djezqJQpY$HQ&o`gWHH?|69ptmGj3z;w&T6$^Aro^37k z+*7^MaQR%P?hDSePR~~~{}{ikbJv;9-MSq-Q(1jIUc)1Pt@GZ!4QtBEmn~TpKV(SI zlgDu>drWo)+9UIl!pZ3uOdM&M*4A6$dSwa!9e9GF~()d7+v*-jyk=-3Uc` zt!naEw#?Eu5C(MT>fg|>TM&y2hA1fR0n&;}N{^7kGeN+Z&66{qA|U=NVfujatgVP! zKU~T>>2{@(RAv%49I>HZp8>`EkbKG|^lAsjZB&1mV@`r%T5{5%SkyY`U@=x;jsf#m z+P&Yuf0qoU3}i+V^Q#2Q!^neC0o<&tY(IOWopsZcnTZ3@vEao*!H863MaQM3_PKpX z;9BxXhLV|(Ma$970##TqcJ5KjKLqM2(sA(e>Oil-*d(@A0UI}t%6j+wxg+CNx`_fq z2K@xA6jYtG6nW^N=Kk^PxiIH{T7d1_J7|T_-{DPz5pQGC#^t5EAue*%nM1P)NhSV! za7hsn!g6FB`=Tsf>)rT;wPRdzGW)Hr13oo1HGlEhh>nc9z>l&UbnM1&M{s+AIm07} ze}&o%PDA^3KZL{kPEgNk;L>~?y$P=qCj|4#+NUS;XRK((jO5gUE8j>12yvLv`oQ-b zaxo}r9>aryiTn^%>>asno;ivZcL8 zkKVqq7p;q*t=61S>S1q~zO$!c(TFoelajNHwY3e;e>(bOQs7j_b7g(kNvR$8c%GZN z=tO+(aby3cn@J;IFVGFRzcXs>hco&kKNWejo?kRHgH6C%=k6S6oE#(HO>OXpS66SV zA6R^~cTC*q{$p2-EiyVG-Zl&UWdJjt%+74`gR>_? zZ*BHRB{nG55)Tn|73GEZrbOBfzVprp?Y}Qi8xvJgg&(NkN->8|8NF(+1tq0%1P30v zp^(j*hhwG0=$F{3$x6Xbjznt!A+@|T+_n_0Hz@ZCT?QVpY3bY0R3l0z$7Ef(!b~f< zo9UnZ#=cY8zPMb4 zfTvJh(z2=E%*GAqK?VnTC=pbnWqSAJiz&08q&kmz-zOp9N{t7-f3JP|iT+$kNWo!!Q|s(UPVm?CAG*kT@{{8e z!X2~|Fd++>d0by>RP_8kKQydX#r+s&{X0`ju4VVOOaEl;c{tr@V=t<_DN|}H6m}0^ znOrbvaKy=B+Cy(0w{N(kaQZ?)&vLnF@kNVd`=T}QR?~5LadD|IV6mVzFqm=UQFqr- z*!%lu*=jSu@%iaVh2{6HEMoEIid&za)|)$BesPr(dTQ>XF!o3yc~euJ(ltzUaaBZ| zthaB}l6z)zzb_g6jZqyAD6H!mF&Sp0) zz|oY2Fj+8$4EW-Uku>ty`SW(o_FWWzyFoB9!76Cj zwr-tDPn`pV1-+G?b(onfS}D{}Pp%iT`jdx;W+vZ^<*!hX;v$xv@NImn?oCd1X6*9Pr7b`lyOH&{J12jxNy#`k)3SN+QM-7D=p{wcT2EicPj$2#u7CX59*%JB3hSsLD_4d+ z_+6+x)O*OYc^9(YEsiL-7KoA9KXjz!ELG9=$5zr4`Cm$j88-y zV-2QL`r;^{aJNw}M70^07wGQtW5=f6(4qGW3$Y8LuZwaZ{QD9YWb84M2U1({Vw{JY z+b|Dpcorf|K`skSA_k$FBR#AjiZQqGsgu`$B^h$5o4nmtXm%DRea5aG1UJ3HnY&Jt zBCE(!#9j+VkCZm%3WISXEIMqy;L_9B)TCL=0v<+yso7ASQ$1Y!u4121da2j>)tsd; zR4X*+Xirtw)g|xSH%u0RQ7!0;wjb_@9~qdlt~?J<^;gslvjQF<;bgKm-A6$&Jk0n5 zi{iTC^^OdB=+I809y`**P_%Rw9odoEFFmmdDuVA_FmUIdqeGYHXE`MEeHy=ipNW8T z{VoLCx{l{=zIrtQ?eNf{Q=6=g=Z?_Vx0*RqGE`VRZe(OwjsQ0LYBCIc4-r++(f$;n z5$si!>Dd!L{RTM&fec#SjN4gn54HSzu%X_l1o_^iIO@AYp*@ySW zY%fl?bPOf>fTFXb|gCpIsW6z2t2%IO$z*k;% zfldG|?bWMuzK@TS=DKmVxk+tTxRTyM9?KA2}b`xpl#-@I9@D~^zXR4LH1;Z1n6{Tzlf*#{{( znT_>}B}zRa&Shv#4C<-MFz)e!MrNcuNEcaq4XgrM{or5)~OjlUJ}$*AfbR_{OD zcykvn?}sPXQ#TdwAMNGaKI%D15c79jc_*~0f09NaTLA{->e_Yd6Mbd7{U9PchZwCN zfg<(8ciYSg;&$M#uZxUR9A)ku#=wL1#Kl^pfJ6Pk3x-p{SN_cuv4@V5p$}-sBb&F) z7&UtI3>>FH-pQSmDXGJIuP`|Vo)o-(eU9td1q8NAD3HGfGLr{eONM5U z-T5qAHrd7o9NXG$3`uKO(d|70r}_Q(P~Af36ABnPsNM)uARmzItF-1J#SPdq7QwMd zcBAcwz2ov{Hje%HophvaB}yI) z9XD8w- zt4{I)usdl6o$K1Y=SAi&0rKc>m$kO(-tlLCgKg48)%Ks;74)v%dZRUV5hyT6Fm`Vr znFkK!&ASJQqZTDYb2*W)+gKk;2u(izl17od}L3q{>1C*JSTh?te$21&F$_@DQcK`8pz& z4{i;L4A!WxUriQUQ{yHK#J)`gFDpy{=J8&RtN3SFF>w_)ZaEgZ-lu0amrMhtDfuOu zR0f#Y)Vj}_W!?R_?x-ofwvR^YI$+{@YfSd z*?hly@W9Bd12f|07cEw?xR!phh4I%%HGno{@G}nWG*hBzelKxB!7xv|@ifMI{OwaZQy?!i*Nu7-UW2>n=%(MD#}aHn>SB zxU{?3RmOC0$*&gE2sa(D{l+>@H%?P>ULxFUXbj-3Nc#Q*=%9Tc2x)s7fr@M4jcqb) zN1EA%dGJrPihnM0F09F2!m%9+DyH3RDcf{_`BeC|H@M24mKQ{!fiek+fnD7Qki7pI)XV^FfGs84zkmOJ{TLaU8Xwi+;qnMKGmn(m%wx{*xWE&RarS|pxNKT zmZD`B5rh3;xI>Q!OXHM{jBF>DUbpTSH0BMoWr=uBLF>dfcl+0kjwigeY+<8 z{Erv)m)#GY(mo*>5wq{R-?EGs^`S}A4dPa7zZf&dV(x&v{1-Bx9pd)7xuvBc5^6D? za{R>Bur7^_msMpB`X8vOLWSJ_k}7&c1B~e4wZ+AKCFiio-A%ramNSCGRa@#_XWuH8aV6%TVvnI;Mp{d3E zF-{8dN!Nef(x^=NM~C}vr{Ax?{i32Is%<1EVO0RH5L=m#03RJ)=tyK98k4pm=bTb_ zFVHe0iWf15m?>3h>HMQ~PtZ^UpM)FR|!L@MU14c^6j+)2e_x zvB}*RXzkez6OiiDFM#5#3R6(|9zg>ael<(&Xq@Br8})5%Z9rqbtZl)|B=7F8nUE+^ zdj-SwnLRYrO&{>OX483ss_lu6BmQUCYFZ!(4wq8Eaw1nEvi#_v5hM2eYvPEDg@6lP zy}C(SHBvL&NmWC6a>d-Zj2CvMaUn|#wmg(j{NR~u7ngN1J6P$6_TZ^ylY%2}Yv$)$ z%u%NCWG_8)=HJm4wT~OS-IkZNv~9{BruF#1C>&nSpP$Xy%#(lcAR5CT{5mgODA^R` z{5x|^6h{^BdTl@epENtZ?7nzVP;h%6P|8i6PoC-iIy=?Yw((i+Q8&dC)yt~T<8aKr%W0H-Dx-9y`p1my9lz!YWZ`MP>F?sS5 z(zZ&7nK@G}ECiYuicjKX6!#V#{g*^7%X4OO{Hm1I;7cgkkG8zxC!|Zf zbUe#QXR!8ow)_Xl1x&qR&1>9*0ZqjEQupEizw{cGEsONKT)!*2<#e@T?aKchJy(R7 zfLNw<0YXC*L6zm@*cFab)>ae296*8nf9($3{GqRFYPym9g2EkhCstV3&73vuZEYQ` zkEX#kN^t5bupm~hY%vM?B#34}n8>i0I{?gY2jS(xgQB38L*co4HpS7|YZ+ts|E2e_ zej8iv%H_+%Nm2nY{^5FhK@^+FlKPv5JguoQHZ}b#{2>mSqL5!?x|lpd%rsbdyQgSr z)5%?GA9>2;8WegLSSz^R^0s0hA(Qf_;6zOgeTRGJBXvOmIStlUcNvwe6DNLSqQ!Ku z=#eKUG+lnW{0D0Vwt~K%9z*s7cQ)M83<3+1G0eVO=)94{b7}f{LF+q77FB9SiVe>a=A2sv}5_ z%Fa~FC%_WRx{K%(T!Twjfi|zUA{37)!>8UB*K`=jz7Vd~Ry;+%*J-UiBRANxk8V8G zAj2u+_zDcd%v-OKB6DVXpdtY5fgsN2q92(0ZA7mLU zVx^77x=P_+q&Bq7;VKZwS?kD6g=`c~EgBgFv^;k~XavYjzQxg@&^+Vms$1~5&;IGM zIWe&sb3@zX!O#n#pn!6^|bav_Qajii~{B35}8gc?{_el2wR6d>QZZ z^4l+hc4CP2a!fl(eTCXks8vfJKBQO-<){x=v2D3cCcxrnDbpbANwGwOz&ik(aLpO{ z2Ln1T1TCClB5$IHSBLOH3I9+xFy+P9l5}t3f(0U`Z6Z3|W;G<)_y%ZQ4=E{{e2kOV zI^6#Ms;{AQa8|`uJj}3cW64lu^QdX~B+|hEf1($dZjs4Mst?R#GAI!61DI_qy}Zhs z%*q&I2kh*Qlm?<-Q0VwZFy9-bh<9 ztg1YC>~Q|0LQEzqXmoy_XkMUtxamNd+}&&r+ArWcG@lfj@9vmmQ?;6;4H^D;vTjaM z9OruU?Ag&@fAi$#m!CZ0_IP`%>vp%<pSFpr%f1e zdj6xy20-<=PTcVtiI+{|5VQo^Z*7Z^-{B5DO!%#WwC!UYoR%%;$G9Z$)0 zMdlMT@hiOR_xM?r;hct{`s5rwC!js$r#~+ z-E<|e*^Px37KYQrE?UcA4_^pT*nRvjQ2!jQH9&odOH190zkCh8EEqGiyyyfT5S>97 z#e~<^mKXCZWwdMYJ+m7U)BMyU&@!bim(&ox>Ss0iY;`?JGKS{ycU4nC&+-)LIxL zNeM%LqL#v@Y{{(FSe@Pzzh_)~`ZTG`n zVNk-8TMJ4hfzA)6dCiY5s7=3=5G9R;Lj7U{3sr^D$u9rMk$@%3|i9KTMz; zG~Y@q+*p`~aqg#WU93lcM?a9w*zufT8OxmKPae`@YZ+68m%$2woS>uQqo!o(a4b7J z`1d?&L)w}R-^6+Q)bp+HA8q$mW+)gm_$<#g5?G+UYHB*LZ(jhYK~Afkj^zr87qhLJ zw>*3&jN@|4lce37pG)oJu;1VfuNlZx4Ydo~f@r~PYU<`JPd8+zFJT_kt||g#0V?GB zome%0==+x(EEw%^z4veD$e`97M>XuD^!N_l0bmlFSN`yg#6>`SYZ5tvjvm$94=^E) zBYAYRK1j)_Q;4#?P1l`vvb>l5@2YJmQ;?95s9f!IkM&!oUdp}ApkKNfkXdw%EI?## zs6E!VY7on;uMXSrGjBF`u>)u@Onw`i?mp9prgyK<5*LAn+DHT@uKHnR_cXR~ycqK4 z=ll|k=}KYvW3QzyORJu~!|=J6+jw$E9aA(T#{_JnHOS@?Xj1+AgOIK#@rAD$Q&_sF zs7lZG|JcX~Q%s$8_QK8pe}C!|RsHTFI;@D=w~(9Dv!Q~tQLWfsfcZ299<55^M&-3@ z<{$q+RBhhV)9sI3lzh@uud|zPg~2Gj8gG$zELle<=3vi#`<$G`hRxR6Vyl)CR6Fok zi?MOqsoJ)nsaLhaYb2s<6x6)hX)@NYx%AoeZX@yS%^SR{$9i28_1Etju!{DL08n7n zz%fYD>X>2-`$fAs!$~RYu=u+N*R$--ELYanEq<0;p1b73@;OKdtE+?PwKJ6q$COp8 zSHJ%^nSV(A`&qePfGcuodM{jYN?IDWaY5P|woQwjo#m9J3-j{!-d`M^nLUU8X|q5jLEgeP-xsJM85&JqB#f@YMuXoVSRjH& z3OX~!tqE=J2M2eK2zIIlgdnIW(IDNsm!Ei3Uw;-WG!hW|!ki~1|A$70zuW(9qr<=; zdad-Bf{dpdk&l5MUi8RWDj`khf9TK;uU`Z2ex)#M!TbxgGk|K_ z%)EZM@{z!b3~L~4!aA4@ZMns{WAZ-R>KvTt?9gnhF1zE9LNQ*7RKJk_#$(zFH}ArV z=Yb8SazIsh5cvj3^}bIpm@4;Y^YfpzK`#X7E=R|lin!9GUYwKOwtM%OoRAM8g{JU! z#m9!uG()V`LHgm8-E^mW#k<$=g2=3C8GHigMpjpO!exYy3utlU4XE4ae{4Thytq?O zh6zJc-){0d=NfaM$5dU0%@&@hchtE#@R+Rj{%hxTp%Td6H7E-H5|;N(Z;lPf51{=$ zgAB)`2v^y$u(v2xQ&EJ%Zs&wL?AfR3)r1LNpS_YsOLXrQ-ncZ$l< zuMq61z<6`GYvdk1`i?%`8L@s%m)-h>A^O(|9SD;JgVp#lZH21)$hUlpT+M7nF|r}c zgX0Sf28JGjrUhNV_6ex&4v1cF-r&CpEs$?*I%-dklz-z|!B>0WMaMB-SG2u8ORS%p({uUhKvPKb1+`64zuP86c+vj zl+ZtoxkKRmYf$Qb9u`yH94L;k1Un`Pd+kc_I$Lyp$XWI&~Sc*%?qY1`n`LY$Z)BC@ciOGR3qz zZ*_OVpaE~FGDj?6HGxJ21C<2}U=2?a$kL6-u0Ftafm2u%@If*1R#R=EfQ=GJlc~yH zU!9RX8sUi9roSQlQ0Jc)ofK%ws;a23R}*-U)nGHeH!xs@ALt1b4D@&km-eTmFp{OT zeih&G4bu@!d_X~Q|8gQP#dYG=0>T~6ba>kX?KJRrSj5=k-zzJl@|d}G7s(+>3=z!0 zbVKIQoH@C->5kRlDRv5K3Ir+88;afJgoGcgGzLI2mxx+YaI+km@5GH-@O8rYsg+Rv_3Qn4+u;~L0(^r?*#XP>{u3`+9+?%c!xWXLV_LJ< z@o4-c3=#Qg+#`swkgtyS@tsUZv2WG1u5|6vCC@DHzJcYbhR(me-#$bc zj6KBs8#Ufa-mOVw*08w88ygc4?$y?+ZGA5pD$DeW@1g7j?Xl068*RVA+paR)euJD; zUBP=}=6rb)@i_mzvavH+^&ERF0?=1zy!2L)f>G~AdYjNb%?@87-^Zt5(`$aqDtwwyGHI3V^Cx7$@gL3&$F6?i0q zfEL&QAdF@MH0%1t#z9!EGid>9o`kCzWZkz&$gM_bE_dCEM1tcD`9)U|>|s!NZj;^v&7N(&?<1VXj>S>!0JBqIi@f{v$?=qBWfTpX)4~Edw zk&;U9bsi&F-i%0=1}B&jXCKD9A_xwlEEkv%WJR#9#|VI7Ol+(&MHq)Fl?S&2bg^er zmvkFY1~tgsSZx#LhZ6`~vbLdcTgY&eO z+QcH$e*HEd8sO#BBR%l;>n{eh@7Xj5M+pk9iB}2=R74z%#B1sysHH{u5d}$Xc$Sq3 zBg)D45Tk!-ZDo-s1Ufgab@AwV=+NhqfrOtk>(;8y9SD9I&vH6s5`?ckdY*N>?5c}8 zlIcdpZ`O?Ok5zNuGOKgXmixl9W74i-r1cSEB{NJ*4dcri)?6Y&$e(BOM;coLJc)Hh zmd$w2BVy)kaojkEiA37{2P4Gzds=I!UFDrEH7au=rm~QyJM+?r*^jQ-r%Yke${r?!FLx)DHEG}SjR^6UaE0!#o zT*Mw%%H5rP0ud6a(2Jnvng9+5v98@&zl+&@Prpk9^oLxoEVZnvtV$#ky|p-Z-Gl-E`lND%Gwzf~8Qy7IwZ~9bd$75I zjLf;s+6JYszu3N=W~ef#HglPxkC#-7LIPfMSv$u`EsYzHp#ALFe<7C@MFzss!oNBr zl_2XqpH#{~qj{m_Kq4|s?PjV5mOMg{g1oyH*||ugeci#V;J+*;ARn=jZ4!!Kfon}d zW=1$gdP4Z;u2yPtKKHtoXs^L}rJn4AYb zhb9eyd*_3jjB{|}{k~~w>7;agfY_LpG1+oWUxCZHBD>n8qg8FKDi+Ud?u zcdvgon;e_@@f zsu(Fm0y_6#0VMn@=w%R@3EPrmGLQF|eR`YLWUns^BzsHDdTjJ!A;&VPJq z1i28U-u!vpSvS*zpi%&a61Olpf=^{%*gxEOtdMo&QS`uef&9{+Nm=^aN?r@aEgOO! zg}sAADC|(?UtR9K#ks}gIZx>6)0dKivj>Nmn$g^C7ikf12M^x4d&Wr$0wA}4OHOYJ zFOG7>Cf{ZKLY8|{-SWW5Ihardhlp5*D&aeieRXNlVutV)78LL_u*qwR98r|^mZ438 zNcqf25nAGU>I3T*>+D*|h+>#gC+A*q8`Q_ICa(IyuCe*L^|NQFBo2@@SC-VYx+vVOw`Skiq<+=Y2pHEsdlH*LG7sM;&p zaeGI|%P)UD=gyfE@^sl*pV6bQxxCAcg4YD5QBky;?MdYB@^5?`x)A0l*;Vu$oA4bh zv}Wo){s5u{An%`FzZSoh%Z|TuKLYQ^Uu%&mfBp&o4Q>MR$d7=Y)Skiu0_ZErt*S4kMMAerz~hDUJT8p$ml2+EL2#rUU}!Sc zQAjGF$?z=vH$D6>PyCn1-gB#5il?2OREpz>L4#v13r5Nv24kZK?H#Mcmmuwyxjy-jyHDD^S-ti5_SzFStfY}TdmFNX$H4g0F^ zJF8C=YRdyF85oS80$ z>hq4Y2hk6=$H=1R9z5eE*v`YFo4_zR5`Y@!T@H2zX2mOx)KuVyUF{)sk`oBAqqtXI zCs6{j((IZyNMA9T&fiD6!^**8=rn8wjjAn-%{v~Dx>V0>$ajIn3nLr`FJEyo*WBY> zTwX3Xaus~n5+U_r$O+mDGqcog$_!US3=sm00dlZc4Pnx#x9?&j;1!dlB7Jx4LHJ$%Qw4!Cw@&-M1(3Lfp+d(_I{3u#MPbrDH9bP?H2 zoql(#?G)%U5~A!`oIIsob`2#W5gpC4cdl&W)U{{&rt81vb%B_Gm-X)1(*w4Ye6%;+ z49NgbZLz@`-R8JT?%UU?|6*yEbMw{Z1B_)Pk~aSOs*`-byAZ2}+_KeW$(G(_ny39` zUKWZ}oK3KL+P6|cK|fh7G%}~uM5u=wZxQ|$26@9h z;D23bXD%_=&$M13Gqh zleeE1_e)#R&U&QXp}21PWk+n|7|*;-JDHbFE>&2!($I3c3!NDVo3I_R*+C@4BDDJ# zYn8Mcm@K2C<21d?;ltOwL|eslbgp?_F2qjd@L~1#^`6$^t(^0cJ$qieCgNW=yY-a0 zUM@S;;rcaEPZ=?@u5tQI0{+qLethskUIOX=r8^buki5Z}4CgY^vS`e#y}HTFz~C!( zS=5Ri=e&2)eOXu1H9cpzu?k6+SXW%U8tXib$KV-!`{qq3aZQj>spsG*aB(_U9_t>u zk>AcPOWeQz5?mgi>PlbNVNZ@;)_BqDT^7}j;ZpPLC{zpRPVvO015|VCmbI`=#|SUn zR3%C{;%TZwFBN2VPI~BBFx=89$s%ip2mm4f3^4t+pOn4G)o=e`1`y6Ssbq(cSzgEzG?fxtl?$5yth`J?mB1snpxVvvvJGo{!#bp zEu>RfDU6^g02&ZX3jZ87h!tcVva7iN<=rA>-vF{gHlf`vv>>-{-%cIJY3Q`1xZd1n za37_s_7f8lES)O~+ZOr^E?>&J_%1)&raP~mL_6yG(|#<6n+={Sad#~4+_nE6Tp$bk ziGIeHI=GLVyzu4)?7$7wl+zOYo9+l$qr3aU7k=TUo*bL(c`GX`D%r-0%s+qr2o&p6 zq2)_-bj07@!&Y|3t}gHA_DO~5rJ%4DKnYk0Q8dsuS+hHP;lP;m=pp~l!U~x2PyBwb zFd+vjLT}6yPHxX`B>U|*#7b|HPnY?AUgn!oFZ;A=X|=ay>yb<22Mw9hVrzVcRA9)hBt$4EJ@)Oh zuDdTx!ajReuaHWSSE<>GuV)iK&WB+X8xvjD9GL1o! zfz4scqhFS5lt13LcogJA3M|O?h%~UyL**{SbF>O&8(JjgK-NMD&h#)%LuZh*aQqCP z`ZfO*S_96V^yNQObChH4z+sqo3+ zJ|2X#g>JXcm;6DNE2I!C?L#sj_~FS43Ob4^bW9pmKJaV|A4?-H@dFF~^5u)#kET4E z*qgJYm2_`>Jnu7c1+(j!CGZnkP1cvWlgN<&qR+3nG$h=#m-40LyKm09o+MHzM$RG> zIK)dCY(HT4cE^gz+%jvKS_#DxsanfKgZQ4`qcv=+29wqkuewt+KYa>0LDDRE5-?Bs zGYPd1AHQejSQ-9(I#R+eb4%k6NtxGsGRBua)c6a&11@x|;&53v$mb$*3>X#$d4|dh z3#jIU#icD*V9o;i_6JY^^^2f9MYzJNrzFb4a&c(bnv_7kLA z2x#ENXmv+{ZQ=xho3AC|x#qCO``oi<=YYvBi*g;LrS+&-d)|jn7oynk6cd{kyv%ZV zXm?`fQ%lNXTA27_Eiw5hZCA^(Bc-Mt&NPQVbQPyiEEkwkEYA+44@>N)^GR`JFU0A| zv7pH*y@`w9(GX+@-G9dzbxMF==BhX)~SaF*wqO&12KwMOnE{{QeG~5`rD-Gt<+1x zT=b^&R&CP`*My+M?`ptdG{FKV+u6dFE{a?rcDc+u6~{=_V!r#$!*Ef=El zmK1z>{lKp9uqrGwCXuPjN`CI^pXkEGU!V$-D-ezk2%Jut_z$qm9!wMV6lPExp$CjZ z9g!zZt>nRjV)*F?HZwRYC(0Wh`P;Wh1>Ynk_4D1a1hj(oIZy!ug*^)%XDr5~Wg{vN z@)ecmJb~5l8rYlQN;%otZEurTq6eP9B=L~mN}&(%GNIPn7urYKB4O`dJmim*ZqK1n zL46HW3qDJGj0=#8yq0}SVmy6+y#(q`7JMHJ36Hzyk(@hzx>w-$%y4&AroX!%wv*Ro`!m zbu8*_@hs-d&)J(^WehsMtE>2u)%h=P?_ALL>}=~ZgWN8RTQ;sl^?FBm8+5+>0 z5C)fd^x}KiH=LthEf^GTe0s)Fa1LfFj9zl>-tH#faBV$3hQ4;+8oPIImM}#5=L?Lv z1tI~eOzeP*24NM*^5oR+inGdnQX$$Blw>*$k5fI|{oPp$ey>l3Wj~4UnnKLm9 z4EFR?Tc>9sORCB#$f6`e#dDmZoUGc3K6}L@_~iN?7tf$41hH$_t4RLtM#rD+%3Pvy zHyQ6hrmYWyP{mDyx6=UOw%&dFg$8Zc?%m!7`@vikMy>zsSKw^5B%;L1N&-C+T{&t= z{PWq(9JTQbPO@3xW^x?)8mt%A07nXCGzwJ2ohFc^Nq30l0C;p#`GJLi?X$nuX`=k# zqn*ym5=Pt$8nq5_SD{oGv&?tdGN=iqAIgL=Fi?Xi;DlMxp&REpm%#Rnfb$r6t4FV1 zfk8n>3;Kr_>2|Yh)-yI%5ut;|xMSTmi@%`w_K zIutKp!`Z|8<$GFMhOwqGxO{1cR8&hcBPZt*Sr{}-)&?0NJ>RxGP3L9cfv~0bJCO^6{iPk=uM`T7%;dcJ}Ig3-Mb||K2jo5TN-9$2qC7aO$FtN z*WP`DYRB?3m$d>*L1FcQ?xN{$D3qejpFgh(Q%72Wi*8vckDjEHXvP{Q=NI$hUV)5| zm7PWxTNfJt`0KTVX8CSsy{>mz^TQ%c-6l%qFm9d*BxP^%CfLlBgHmBaB`G@TmcL7V z2e+HFe?P+xcTNbuQO`d?_bBgnd}`tQ#a=R!s^LD>Is0x`&UK;55AlsA01reA)2X?u zE~e#b+MIrtl=md&bJC7R($3d3f+4J!{~a`Xbo@d8Nv+NR!RVMoWU+lQw>x;Sryvv* z%#h)&aqnU;pRc^yx97}d);)|XYermS+lZ;7m>p>ajavRsR@#HDC9ef}G`)7pAJ$fe zu$GMl@?06i))8^fblHN-3ZG3p-G-AI?ml>RlVa-6u|`I5&(uiBD3_^arX06U9R@v< zjsd@nu*7a!{^JpZD7Y{j=zJrSIG}pGoUyySgeDR=FrFpG94(x6c-b6GNnt~jO|ui3 zGYFdjKFkA*R2+_Pi|W?vf=vRB(2pZB_0uvkikV|B;x`krF;~_IAN1|xv(bG1-iN;W z6dE1r`uvLL^tp2n5#iq5R2WseBgWi8CU&3o&0BIVr{%ZzR!BCIlU9%$eH5hV58+RcB+{7T5e;PxB)&L z5M~}g;$sBoGLl7lG9lla_PsQ4rh1H}^8fGw`iVYMK3~0(@7p)xtX{b3>`7hg-%Z{T zsSvNHkn&^UPCy2{Lbu#o!*~OF@zVr_x36zTfqvB%o*x?2(zVKzAM#T_uzY#@>`~%K z*+6{i<-1*f_l<>nI4i3(l%|_l8VO6=sE8Nd`GIMx1PYMf_|RGGbPHL8ntDeyv?Vo1 zjgk{}?>%6u>`k1(x`$MJh`Jnq0Yf-Qt?8~jIEpkqL{ci&9+z;_I|&PmuDo+#!xdAKMH4TEBc7o=bF2g z|L9flW`wzq&oOFE^$@0}%>HU#^$Y9}6$+C-aYK7OZ)5nNEz(vQfxzc-48DO$kA1Ra zKo8P#Tyq&qNz@<;0uygyULfa#yStK|rR4%pldE(QAwVb&cWaF}VVye7-Q7fA-;Y#? z*Kv@{BR3U5k#TW?v=@aM>G1NXWU$r}Z_aB> z`n)yL)&J!1=JV&ng*g{!Vg(urokctwH}!XbQto%4K`XxYwp%?*H`T1$$5FBD3|h$*|a$ky#lOA3NA(#@*>orEv)lGY3y0W(k^RWh-%${8h_YQl zVX5lfO@3}E$RSS_mSM*RNlL%mTSR{`wh`QCy3JKyn{CR2o0w-V&R^2Skv~`h0xf*eEF?yl4C# zs-u(7v{cd_MCABW(RX1X?8>pYcvJws4jnj9vqnNLQ*Y}3Sgzh52#jF^rA)hbX3v+a zlM#^|b^Fu)a;YRozLT@_m#<%IU`xVx!G0Ub8SDhpwsAY$JoKxPnL;^Z`N733udY6d zr*hHknI%J=f7ZWwbNKY>J@%TKt^01zk+JEiSiA8CMA;}=txq3(GrEcBeSjPIj8DcC2Qra_|JforNU{QRd_vri3{f9+3MLhKtzo$-T97bdDaHI8jIYhsa9I zyNhAj9eEp@@U30z-`WhD=h#hLPD8_LW}nz3+YXa_8Ot5((UXywaGUg0NL7^dJ+3{{ zl*~`u)nmc!o|aR0yA~bHK9N~)p!Ygd99S(-S+e!n*Hj;{UN*gax4hN{D_VLJ-rm~l z)(U6+XIhR48_;9lM3doBzW=ge%H?^%?&fU{Pd4;k{v?M{8JHd9eqYyZMhT7Msn*tu zu(N}WC@Cqa-f5;eI-2}5?9U|+ebH{!v7feH!DWDV?E&YD#$Y%5g^}6ma|R~Y_VJ&6 zvr($$iQA<6x5+7Cv5M3=z82XH?5|jV)W+(n)oz>Ipz@YK;>0p%%FHic))8^&z}K0m zXMej$q09bZUWZpp#NI-gv={ZY%Z3Q`+ye$|>aT}0HPoc8xdYE)TRT1twG7e7g8 zdpGd7y-zY}RZNU5YCVn}HZTN3rdF{(rh6*24|AsPnD@FCWfAl36V-RzzHLL-TYxQ=EkOPuVg#Sj z^@+6Fx^Jd~f8p@!|2#*k;lgzrD8~|rdT&E?xa_`6W{j$WoLUF7TtzSG4h*+%e|aWv zRPCSzhCBdRnr^BxVi@I+TVojv6p~RmcZH<_M`C>$@J66yrZI{7mw`6i34v%mErTaprL*FJWZ^95aM8jZ4mQp?GcM! zy~JIAeDn8$#deOCCpb|3d7lXL87!r?}9E4D0sxana~ zF9{XZ7oU!$k;bPTd)85ypxD@W?f2g#D)}Z52lfO)Fk*Yo*WNjlfpAV(R*(q#_ac4s#u-C!hcWgabZOPdCQGJHN&r-Fy2Ovg zp!C$K6;#atj3CX^nKDwpN_c#_x<|6IaM=O@J;nN^Mp-lNAZ)}(?^}VJIl-l`*0cC& z<#D!5)m0GHZAe2i4n~qz3)V`1liu2Yh?ph}CU{Y#CB!0B3)n!E5=yXK#Y5m2dQRe> zhQ{?bYXlE>nlS?ho<4k7TtqQLJ{`4lCv|^^R|&Wfme?JC{*>LVx2k54`TfPY0{8Fm zL9BAHC42@P4cu6~LG_P}RYg2!8q`HBS#;`Z0`TF~;%S;H4fpqRY;e%bf4)i~S_IUk2UW zaZ}oqHuIUXPM^jnWfQgf!*(@mH6(WPk#ay46@eog*Ev0*_7By3qUOX|fgIPkB|UgqJHl zVweRf7&NcpOtZuwTxbZ0h}KcSDr`V-i`xMWg~F7{N-W-@fUw6fcSkbaF)MzU@e{Yg zjKp&JQ75`_M1IJe{noN^=*`z(ct{B9;oaqXm&G|}+CX@hc9a5Z!0V&1uuxFsL7ky) z75??rdSlh)J&umyg(meM?E8eTnA2EpNA%z+K(g(s!03@L5Bh9%~940?mQ2x z%mn%FjJb3F)^!z2n^Q>apgaJVtEjB}3fZ<}3Ef-D+QI!hkXBvwe=lz#%Lj#fD6n+@ z<2N2aZ(p!y&WBnaNM7Dde;Hm7g|*i6?>~NksR<5R>()L#K8s`Ctg~bEy0vuffrnbu zt|Tn1JeU5{R7umgO%S?|8wUr56qOS};EFTBi(`{#aY~IUnR3WXY%@H0fB#m9^rh7u zoO&bhFQHwy&W`CN&+Vs7v6`SI{D~+VL0`*Hnwy*F&J)ci72#y@`#n0WD2c-nK0Adg zQxez2%21qbSvxi(a209+(mmQgcW~(v4o)8Qh!67`KE7p|*0Ez!B3Qdo;iM@v z7KF6N^SeaMH&ewv<{M2L-ZD9;;f;l#{+VZtGVu8HymtMMZfa`fkHwAET3gNCRq=)K zdl?zp8o(ik1eA93O}k_*TdvWsli&@}L1MAZR0@-Al5NmiPfdiw z8r>kWZix6~5L!$8CTDN`{HsHNyXitwn;{++<`2i|*prhHn$l0JB;Oa>Nfb7JVY5=p z0dgQ4E$=5FtUOlwbm_-?CHOa&l1#WuxWRaG7=lbJ5H ze=m9r8npT3Ft6O?m3tGf)=r+S*yx{DvDr~VEAxVCLr~YQvPwtux=IFY=KDd`n$UI; zMmPeQG$XKa->hB~6rMeMmbiT)I?tDH#GhZ-y1VCN@z5bC(8)XC{-CogxqTbf-LsmS zXaT$~jb(keRd)~F%i=rbS$Lj^(AH(KZv6N~cLenFNwj=y6=XlWaaX<@Qt?|bAO}4O zvl}Y+20oAgEi~tz`JUkh?ve)De{(qkx>!sF$#W0CTmnt(j9<>w*ibF z;Q`Eu`1ITOml4`o0`n5dG(fNz6+ut?38blK=N2`Dg-UAp($~!x4ohyX-ry2 z`hu9xpw6F;Be}u;>euQI-Yx?e0*mxEooTan4P<>qwVa`qf0o_pa&o%VEh`{LiULhCd{!# z!6@>=4gwa@zV`)E>%$97=mtK7YJY(9l{73qau8-y(CClgoo~=@H(120R|{a15_GT% zcSd*CR9WtF3bKQtVJjUjj&JAztvko>=F}&P9CX(&E&}tpAIA?F~uSf zFG+&8T#2&hARO%`0JZZSIhZN&y=_ZKu4OH2XR#t?OQSaJXic`sl+xU-O?&P7)DzkC z^)bB|7&2@~7t?`&nkqAAy%=4a87tTLeoL12<52U)e;Gcf=S~dz@T-1bN1&@0 zp0_g*94Lb!$j_Ds($Xc*MD5ApFs!5X^rI>N&NyRV^pcWNMg#NsO-OTF$X|eHTv1#- zJT8a)T0`gga+X56W3NY1jk&8Xd4Tm$U;$#y5Tt{-l9o|)8Q-lMN6JFLgoxAjKsmq& z{>5`JH9UvFUwGBHZt_-a0-Pn&FVM4n{puC|fXXz)l9DhPJu-FwtG92rjhZ|K$`L&m zdp9>K>_=?l!vdxTu{01KPHDpeiUzN(W!_(dCx~M9?HfY?F*4HC+D%iCi`;wM=sQZ+ zUjNUd>DRBA)Xo<+^Xs37YU|)$^}h}$o_mq$QlEg-m>x|H03o1qWarp+K6v+yWVo4n zp{Z%tjPL4II)+BY4^qy|?;7$`jd_Q)E7Ok=aA}fpQTAXJ|1Ed|B+1+TQT(s}`6=qz z7<~MvQtEV4oKmV`u#887?!gxl>H1>ABSbX0fZpdYMY54dA>T+1d-$&8)-Cc4QkYz5 zd_BhqvsQRq^z&i{EjRkjsRPIgE`$>Y(zz!8GY3~*x5mE=DglIIxSOw4oYer zrAO5zR+sW6wnKACh~Ze~pdL5bTp<3n@)O4=xnog5K@D{XA(anxv12H|Enbg1b($r< zsY6U(f2PZ$`Q#<&J=)n?P_Y@;f`tBVX=y7lVN>T{8pw@AMQFB2jUO+qyLN7J_(_BbLfXw|rb5U>v)J$l;xLUfZ`jRO&c zm1g$q^MjGPDe2wCEV5&-dl58a(r>ef4}flXs#p%Bf#iwh8tMaD4a^L|0xW65I)jaA zTb-8N@HV(nT#S7f7Cgs}y(jqc;V4=tx@%`6tz;SE&eU7Yn7*LDaANZq+lAtmuEXNN zx2bGlYzX)_LoQY%EI{h_=ir{5PVXwpMYnFPjE^q1_dI%Z(yYhNL-+3Mlr}NCYpPkL z$UU0`H0^y^>4yNG%k5|KXPNZVQ)l%Z=GkM(!>~l9ZsM?;9*YNzgfNAWmAl{-+%73W zBhG|m7%HtFs`vCXsd@H{y5#ku0VIxyHx;&Ce|m0_J-3bf8(_I$>%b&T$Bhu3Z8}Y=i8BmbL1+07DLf1ICs7;Po?vAIyPsU?+BDDSE+p4vRvaEdfS0&w{LhEp+d`HC zVXE%v-}4%pDv7n^`6AM0P1l)jXVNn>w^pACO}TTIhumYyz}#HS?1&M6Mzjn%7+UqH ztDW8P6O(6ZNs^l%@;I$Kc5F5CpuhpR=dlI`83l&nP8)j2MCjOWcHI8xX!<-e($O#? z72Wege*~HX2N+5*SO)|;@LDdq*f)BY$yv_31ZIVfpA%iEnsG$Mr~XgT@y_A0O*TRb zlLE@a-v0LLmh^Gy_qw>!V0;35|NF1rWG{NyN8aw^X>$I#1-pj;O<-{Uy8ziuqZ_jYP$p+LvmVW`f*1>R>} z!-g#ca-_d65|F8;CLl;7X#;`K=xNf_rKw5XtTScjfU?v7c&MM=oeSSF%V~=}rf9)#hR69ZY19p&;DRlqrZZM)@xyKC?dNUWBBT29!)0C8 zxQ?!_>88IOdQ!=OuCR;-Tf*%Z79c3Wq84ZzrHFq}BEOVul7;^lMazuUvZ%*=`+wO&GU#Wy6hQGrWAK1X!eqlJ9TSg`6l7 zDn3CT2(8&U_W#TG(dn3b(hwbkWV4peDnxg@BKmwm@3VQrm%vPj2~b} z(x6ByNccofSD(DHh%A#@%B66Em+B1v<~l!#Uvckm_fm@=k>IC2DGE6Ts4SB=Q$d8b zsZ>-SDJW>C5`m}&>73llIQh`6$ox9 z%=?CJfXo>PiG%~gYezud^dDQ^+q4d5K~W3{W1iQ(b3DH6y)G>%65XemUn^3UH~_eLU}W zCCPR_fA{ql;`z_^@5{c*1-8@;cRiyuZX5?i37?NU)k~D^A_`L{z%f0GmJOOUl6zWo zQ03Lv_f7vlae7FJyKg3G!$;vG5Gn&xmY(WvPz#7E414(b$rI>}RwwWA+pi9icr2G7 z8gZiU>^CuZ?3_Uvxy1{=`h+Ttda0HoED;jRY4-My9zRZD#`@gM-9>9?bkkv=y;=gN zK>(x4WCg>!rVQ#4XHU;i>QH2yWVGwotvfaEYEk^W^%Zu8Mn-}qJ8M)Jpa~*IcOzTi zg^>`sQnW8va-~X;E#`v?%}k1 ze2cv41c8M0&|hBuEA4qAENKfuB6rLignilElYKb@#_|f(3TQGfK3P(zE@?S!+Dafe zvUDCJKtFH-8hSYe1rsJU(fkGO#H|AISX;owNbm}N?$2@@x}oN`;_=hsU_v_QJC2$R%|j0LM!oneX$e&`s} z_2|(~R?N5MgVlmiqsbvnL(nE>zIyc+oLX6@xJz4=$c169clk0dKNgF3^I5rV!D3f# zOw4;5DqiNP0gb@%eNa~i%oaVtW7@Pm0xMx_P<+IxF;&Z_nx1MoB{R<7wIH_Vn7NEX z1xT4Zc?pZJpRZN+ewxw(tjfaY7{A)_^)Bhs=YLc!Q=DiZv$){j@cYrWRZ|wcGMgm_ zvVR06GmWeM{VD!D{)^mB)lSsHTx2%}rLMDQ+k66^?agwbNFq8BgignM#V)HKp(uUe zfJo%M=*676104pVyYAlPpAC?NM*57sh?j?L_8ro8-4pKX1t&$WxvAM zaHJ9-rv=aoUeiDQQx9Qj>{b~w#nSQ>%%hn~l@5&OdwA zB`Qm{qOyeSp^}}F$i8RGzVB+ zg8CbZK=cNfpYahT9v&#nDj~Nwg@hGdR}MOPz(@Ym_D7H2_xC>z*Fly+83hT51`+0o z|Et=o{G0YUrKK-o z77T7ZdebqFA9Qh6%4t$~cyQKC;eTMa0K-UPcf^Y$&KfDg1H;0S57ZP%mssht^77gS zT9%HWGyt#weKdd}Pkf6MVGIlss!*`ISyhSMrB>dP)X(h0!4#!A(L@jF2H(1>}glc>cV?^#=tB zO%RS4kVKk3u-%>_4Q zBqw9;Tm_zIp6gO|PkQT=+ zK3+AI%;efTV&~!U23w7Bz>zE1ZjkN{1v%PZ#88NmXn7PlNhpKKlwH)^4tOY^e!2JF zqes0!({bA2$6@w5O7A~QUqwnOKE`eGDlK)x=i9<{>|vbvHahAM4Am|#AhQ=kbP+x< zvoz$yIHB@JB@0Y%XSd4qeKbuDv%Nxy+QO0|LO^l7dq(ri%&7wQPhzOP;XeM#E(DNu}c*S=T1AUBMVev!21alqgtDCH9)ej%q zO2@qECWfz}umh+IIt`5lmi@%Thp@FnvAOfgvFT)ula+0v(lz5`F@M`dL%Og2k*Em?DFR0Uy4yEx@GC9BuG z^)a@g;p6k#(Q!u<5Ef2kX66W-*);Po72{QOG&b^9`uX_4u=EX3$uuh6md0c>cut3v zshpUh6$Cv2@MPC6q96gF0lEf%ldKjLUi0b!;~#5d7K+>XA3hj^Gy>m1G%YCl5k-m# zoI;C4dLId`<8PGlLveuOfs$iZ`UiAvjZV+rO_x(j+Y|w~1MLay)DZFQyzw2VM2!k< zAxs44`2+VIRV1>5h!cf0L3tb{3reO5qLwD{y6IVWqb`!UHq3$)MGVY@$k{X7S9<9@ zbQ(69iJ%|QF>-IlNtC*9D-hw9XffbC=T>mG1?YBuhw9<|(F(}rq`04h0?xc8N(&xl zJnHh0DX~E`jhS00(=osJe=OXvBV!8JF3T(ABs}_fLa_V8(S&m(T;v4$B@8{ou3%l} zb+%}a$m)7;vazd8^}j{%bnC>ugWcT;$vqxP>hfH)bRS>Qaqq!db?lfodd9js7-8jQ zWr_Lq03h$Z8UiSutQkjp)VJ#17I6>R3`06HGB2?}#R!1!2#iB$&YogF-UsNij*KFS z<}Zjoz`Yac{SZi+wZd>$+uHiDRS~A!vjdyG&qjldLNJ#TI#~iV-mwGa9X>!i0J1nA z_qF#v=+vQ-l$ag|uR_2&=)$6^XimOs0ue_tMy)l`hQEapMOIw=8$nWuC0OR@qKd*Z zh|Uy_`w7?Eit%Ghf}`%ndCvI6Af`q<;pc^gGnhIP4n1T6^vigt@XAmJLx-?cDFYA# z?9q_13TZ4OI(L&7@~9|J&O%LtRe>!lE+WDKH3&n0XMJ42&ch$yU$O!Hq2Z!Q`q1-d zy{V(u9si1u!O%*fNyXSV=>CG)Bq@xF_Vf15W1x{K>d|+7_E54DuFRK`h24C-PR8c55kq&%N zU-fC5#nj{^7C~4U@~6QxgwCmhE=GR+O*t#}py#h%1&ZYF>ZL|bNG#XjP`SgNcm`W( z@h2O%Q=h*L;s}jrn3#HS*!^DO$9H0;<3&ak6rBc2G)VISD-28$vJr@)2Rb`@&p-4E>6Ws*Hu96SOt@vAZZm6$4;A;jTfyg0m(b(=4uB;q$A(FrHB8 zN5aFkp_#=Z!iI-Kr0L(7KFt?BkeWaJrzYH|F#)I<9VH3`!3b*7!r@LptuT~z+CgfF z_yv&IIKL5pj*t-??GflhAcsS(jc{l)Jl6kt_RgO>2VFhXhaYa1K!uzEa5W@kpu2k$ z2@o~`sMXfyn@d+?Pzp9sPtOfZIGwyN1=VEU&=}8e@&3p%sXUc?a;e^0Nk| z3fBwdAEJ&0l8d{CBvOO?tJ~TwHdfFnfb+tc+oWe-=7&zJL+;uL00_z6Z&rxwLcep> z%E}c!L)4Y&Es4r_>!9GV+u?vl@$ygi%&5YX2%!l~`!yd~SXsk)E{6UP3m-%5XybcS zvbYPd!ZlSTp>{+;AEbs!Q_p*5u<`dUZQ|=qoSoy_Gj(lLLV@G4W@GccR?WTpwva*} zksG|ovy)f7Wm*gjOggklTz{9?$>{K^y~cDS>mNayp|a=;DHi{cJ1d?A zn;Vn(m1v@lOngTdg#HB^yxD{nb|GXr;Y5Zw5tZ!2Ll8$pwf14F1(lOM^6~CdYkYzpl1c00WB~D={zsc%wcUIdyJ@Fu{R+&0NES#9MYQCEdhR_ zAb>Jx7g8(HdtY7a-aGC}edrG%Sn__6V6S%{i%c$&o#f)~P6S&L5x{vCbcAcb8e1|rR^HP~2hzhJX|xU218X*dAV9UZk|3e2U*V z3uGDv^EJ(`0@E_C6nOph^`XbfFWAumFPXTM6de^6<6quKAx-Lioz$?cLhtY!g#k7q zK)~mte-Hvs$N{gQjz@b?KR|(Er!yMI%vn^mSOb`X_Fx~%1ZumjtRWO6Jc>BVz>p+& zf$hNMV~^+W!-yo}Uv!8*XJLXXFPC@s7Hbc4tEGzSi(FAOlEreK{X40^$s3}`T4WDRMpkr#zW5Q+`ps)4+nga7};o%hkmi~ zD^g>sZS2weCVO^WJt&WE&&&)BaHo@{v|8FKUJh}}aU&#-VA(t3ke9Q#;sHDq_&mHP zA8Y*Pj3+qx1el(4bg4g~recel!PzT-l95@ALvDMKjrepD{-Kdt0{y=|!J)#lR z)s2wSB_(y?$dQk55MildMT*9is!?eLw`}qBT>dKa_`nu=9*V?s%4sy10{iydA%ckK zz;4cWE1~NudZ2^sr+|5>B_rVp7sg*<_wdLJ{-@hRHL!C7uDcY-Lh(s~@21@;olet_GI7)K$nNLH7iyz;%L0`s z7oVxK@%2tp?FxBoq$wD>V5k2YU@hIj;XQ@BA3v867EZ@M5kEDaeWeB;-Ehu1D!!j9 zNlC`-oL8;y`A;ry{U0sBctiEjlUeIdOB@Q@Q@D{Wi;WlBB3#e|0Hi881EpnSV=}4& zERmiW_~y*$2_|vlmCCdOb{jz4!kDQ97#Z_RJimY164G$)?Ah$RJV=y@d_D?#PT&g~ zPEV*3Ujtf7%LH7Uj91z8%q~5 z9?;)dK(kD40xWIW-3L~v7> zPIna?0&rhwUWO2D0(mm36y&*rQw5dCgdKKEv>yL?U5h_#7W#j{#1o+XN_qjx3J%XJ z&|cv5!`@Cy`ro{+rD6Z?yso)t39su!&!7D!Rb}d>+em0yr68%o9)^9#POi)v^*L4^ zT!>EVYpxHaiD2wa6SjdVsFtgJjrFfbG>lURhhw(ZxpVvu0rv)zt_Nu029L$@dslGx z^@TneS`(4k0qP%4n5w~@$nB^lM{Y|it)`~(sjq(-enAa`1O%dQ$5+6`aTvjoH(`DW z<$zHxvG#I=g^h;}$lju76@|+Fh+*6;2IUg7hR`CTQAWGm(qfv2xL*YrD-eW%I($SO z<3ip%J1#zuj8X{=)DvHUDdi(n)R0-@gaP{}xO;aP2ebmDPIyXj=iurIcQ|-SR~Lix z&Ke-2M}g4ry+VRMW(g95kCICny-OcslfbJL-}w*(1AtVbgaq&h5OR9r+#^2kr$G6> z|M+1lz7w40kt0X&PtWW0wo}~$vxWG@XpHZJ!4CR=Y;{LfRB$w&MzB6?zc7gc!$55T zMm{X8Yj7|PuRA#zhC||n0b+-fl>ii~yvV>?j3MI;PnP#N$9)XoJul=rlMyN~Y~?6P zN#brlr?FB|cOiiT!Y$Ma4zdW{iNt3E?V>Bb4d*_7L1A7VGXF6xmWPDyoPq5?3hcAc z3;&EC0y={a6BQ32Dhks72aG(~k)MRhrV%B2R~KYzf$zU`6QnEV4%^( zaPRBwCGu(kp-}T}4r~h##Nq#z5`7nTUqA{}o_l1-CB@({Xc}*_hD;*Vm!h%#PK={~ zPQmFjei@>?V!7wEH=XM#a#d%J5LDbiK7-@s%Rj+NzaJc2uH5+B(bPo!!U|=+DlLWR zWvYYh&lKtY{?Rg^`;&`K0cxtIMt->gQ`|OqEuQ!i5&yR$;3Vts7o2j#-r0+)9Lruu z2d3tUE$5d#d1gnkd*G&_4J39oz+@2-2qhzdy{N&)gD3&~3Frx|E5XZ{Y*Ts94Es(D zq$`*nhsJUbPNW2wqf06FM{{s-K@Ybd1E9vg!$0{2rwL$VEEJ*#x?Kv*8QN$?AYrQu zm1DW)*vzQ=wim=;a{>r)U6vCJAv`D>P&5M%f&qdE({cn%i4rmV2Tk|Yd;n_9a(1#6S$W#&==^ed}CXiSPUh$0#96>X15 z5<%Ea{b<_KjJu726(1%_3HR|C7a0O|r6ze?8q?>vK5aOoMsmT2h)%S0h}=(8@COKA zWFEdjlUVdDiV4eQz^i34Y9kQ4&zLRdplgaBkvfiwxx@)&y;?G$I_Qj#gUIYt$5J`* zDEg>2lfWK4auyyQSY_wUCymIp$Pz^OCBskiSlP^(S-o6Zq0t8ndqG$9u@nurB00Q^ z-^rd`r40jSv86>H&`VfY15RxKcQgY|R#A(jI!fFct!Oqh>;_5H*e&+Jun6SzGLY8>1C z@N$Rj*uK5aSp4GvEtFp%U&a>}#2TZV ztU!80C?YWK2+1iaAvyWzx(58K&=^b*X$5eDp;6U{yK8s#D(}LcvFfer95Gh^r!A8F z9PL&P%rHky4#gUXqNX$Vd>MG?NjS<#*i`op_MjOdH41H4g&^q?BGy7e&fx7LG!Hm5 z!JZ88j+`T*$AS>|TFHI5c>l2`D-#t((jVS;ps@q|EP>4lTRlL3mCKi(%?2pyz@H7n ziLY-xq_N_|58y46OarTknM}xS#Og!=59-(3KKvb^FVtxOmY{mTpSX~1w|oTEITS@W zb)gD9W`{fv+BIj@&*t=oQY?cNj|QeoQ8bo|$U%5u^_xh0CNOH>pUz=W^ytU3v~(7eo{)*G0dh>vK;2=)_f z?o-jTY=4IP1_l8AV1)r%#6)m_;t_gktbvHjpdz9{v5(-wAtSyX4RL9o56)IY0;)i$ z*9}Ajfs@w4r0Ljb-d-2f9zf#V-B$r}It}Mrz32Y{nQ?tnlMrfD*uOB8h{!6XqCyNv z_;hphPiR#yBeoRszKJ&U&m@gAXBHq^$~z3R?2A(|&gk2ApNtBflP&5ZjFEQOGVq)s z?dV(SU3~nPFMB}kgF$LIz5_8Y;LI5YDk|L~J1$bFRw3G6)Z{lk(an+=%SENE05qUl zL!3onQ4xUyD(N2Oa2JMysGuK(R>Zf*q$+ei5%DiyH&$1F#G=J1h`P2Ca+c_dOOIM6 zgE?eg=j40`=zeWQN)6}6a2f&$TPC5|{P={WDF}gs2NHD+4E8mOZ5^|XI!8_dJOp9a z;`#Vbm7uI(OG*Vn#Cd_mmg@Bgl4W~WaLf>{3e=|Z@_+DyJrpZZpy3x|XXQdr)Pq;q zgSHT899UScZcNVH_aTPc`|K3oetJbkac9xiIJ(=b_u_e$mz4)916ZAS@yl=^2n z;|H6~=AeYeRb2dd1QpBahJTti@aW0N{6 z=|(yPC)yEc+p5O#<6Se3D0@+CVk*dyP%RknhCgjnNn?Wmi2?jNe*7{H>NLz2J&jyN zV%{aJ2Iw*Mpz2PK&#LzVk-iNeFTWvY^fp!(EQ(H z@Aplxoyp1J7$2&sA#7J*Gf16_hl;2c4rl9?;Vc0Li2muvZ;T8;6@<)%OBEij&{+dA z17(lT-iHUXNWLR`1JycYGt#+Sk1F%%~VJ`~vuSX{V={B_PD9e!Khajq?Aj{$z$Aq4-k{3DKZr)sPQLr#S z;v)Oz4qZ?XX+e!UGoxylUGo&#p4Tc=T8+c(+=||@3RlL}s2Kbr_Egt;&ptgH-3M+T z6$EowF?4cb--U0zi02RRog<2PXT3b8c?+e98wHbcWGz@NW zMjrwVI^svg`+RtN^#Hyc_E-*uAW-2JBK~W^xx9b>zO5~2^h=Kdj$ddV%u!sR=tdPj zIvO{7Q?U;7xQTOOxiYTF423d`EZ|{1z%8N9=A@rO*fR1aP)6X+VN48cYKA2@cVn*j z+OkCKX&!mUt0({@~yaF6J-o#*39}yc18{#K~u_NNk zBbx%vuyhPQZ`J)2r(X0Bh|qrE%BZEgXMO^MgrE12V5U_5)vjG1r#6uYEy&?>C{f>b zoRk6I&4xkBqYCzvgVOYkbYdo zSSNo(6w!`iVwO3o!Q&YAGDM4G2Q86G;#mPOX4{Vogk$|s^dnXT4G89@wW)dZ|Eqk% zPl4`*fAx=`Sz>+vkSd-uLvu*OKpYV{IUK$DXy0r*3AH53eh4%14)SNd2UGEpKe7|( zaDu=EIf}sM!QvqYn57bt$cAk+z5D|)!qcciv~m=C-|eL# zOOO`W-(Yt^EEe(*$p}G_c{7Xjw4|xEbtw)sL^xqK7yj`d=;Wa4!C?ex1%hR4JUmrk z;JySB+e3_{z(!nJnlPK;-flGp0)_y9F}zw#<|O-o2=omk3lf8bVFB2*3|bB^{1>RG zVfU;hMI3PHIlCa}8eUNCDJ)-7kOE|l+HU=O1J9yVex<@KLKC%6u}UOQEv{ytLaZxv z8=s&qCdBd6m#Fwsu9@A(q+jv4v*qNKgAd;GZ1OVTG}(3(`-^j>H>zO(*Z32(KO%BkxN_xO55)npgNg&| z1QZX7XuNp@is9)cqnkL6U(AL|hG@Z5g0NnJKmfyr#g_y5kv3W7gg7HK{n#!nXNjC) zolESp^v%uLg|BH9nk!13eeMbG_I6}3H`mRhAS3(sy*jJ%ZMSyUmTld#c)~TlnbN}=<7ghzMRInwDaY8Hy~(LRaNNkly3id(aWv3qa`_EtnMj(cjyT~o@Ru~$A^BB-yf$4ZXJ%XFS$Vgpigq) z5+OD~QN(ycerEe&25TPM9jf9MP`n8H#`E|mYxZjAu5H~tVd3|tuh!O{r?aO+a?{0& zeQE`T1wKJ^zp~V*T$|p$6*r~G&CPa|wCK3#DCM317@H}pgPE&BwIm8Q$loyHEFCoyNQ~-7}8K>A8A5;r}4(aJgcQK`524iC#3hSc9c__S#CG8 zj=x}hOQqQ`oNlZjyW(CcV#A86-lKHZsT zNXs|iz-M!!P-DF5_0dM{`?)9Cb4Ll9|0C{1H-&~kID_Ky2Xw#K zLt)eC7^B-%-YmWUuzy)Ue&Tn=+JwrXThzhYZG2pYI1^o6OU~{UMSmeChD5_Jnzxxh`G5Iyg#XOXJVVC8 zCbyv>k0_VW*s^Fk!8$jI+C1jpX^{%HYrFR4?VyIrkUkRyBhG`2kotc)9S8LF^ ziUIFPUsrc;X;l>FO6LVOJl>gI5#jRYslg$6xx24jPyqDS1ulQs{3sGrg&%UgnzqKh zWK@x7!v5lRgL4Xl%25fxpCwYts&eTl+=uXH-rY=zo=!In^F;k2RygZu;2l~xg}sD0 zRZ!tx%rg8sHKo2|Ax20^$rFY>oWkv`t%O3^$EOa%mLQgG|FrF^zWV5rMJb3d5EXL3eqt??Ar1HwpsR21Vebcvv|XlV4NvmvBG3)!Xz zDH+n)IKoO!i;C?HWXM%m*HaF45;&_6*BI`TQS_EQFmEtv?Ner9An_i%nFN@c@W#;l zyFvC2j)9td6UaA6{pip&!jX?IIbi=;2?3^*)C+VLZTCVLcvOV9kRuRFz zpr{h?4lVt@g49*_-zMDxw(lsInN@cj`}gxD&X$Jt5`z;VodZoU2gwKCOUjmw!GmU9MNdHGV5-txP@nUmAl zo`I55RzB(69#tJpD%W4n6#POIRb1tqzf_ei2$!<|Q_RwPVW%_%4CaB&4R39`0TtiA zdp_)h0s?S5ij0aM?FuZ`0^V;N0c-)x2cQY5abieF2YLbk{Vi%10^a!tU!Et5STNnt zDnTVLRQl|x0F!@FQIW1_#f@=aoIXh{d?|-9X95K(G<%^PqRoPM!*MU)`|S#8zyLBr zYJksSU_eG(yz{ni!+6dVx*L2vdZA%$&$F_!RQ_%dDzAyjFbx4%u#JzN26+_OF@=55 z6&Y1Hy`X=CB3P)jURp?rhno6=k?5)}#>M#hM!G_mk>1N6WPOV2V!NQ$%(Af`|q;wgs!9 ztAMflBIIgF)e-;%l5hv}@n9xQ%SnK!GK(81p_Jj*-j~cl?=^`fu8Mb70<{QY{Ai>Q zX9g{yD}XCZ+r%s)1%;jxA6D!-a*qpajpw|{H3Udi;}_^H_Hn!$uG<2PkB_T!<;U_g zKg$l&akbXC%>QHW85YCdQ~DPtB!Ia)ixbpAcU6Ze|2rq)!c0w_1RTA$SA)vxHimJb zZhnty9BLh`+&w69K(b<;3YG3x8O{S=0*xMs{_EJ#174>#102Dj2<`3xC^%IIR2pAl z0-?;*6Kqhq{;+J~KjMPEAL)K~m3b>4pnQZq5f^-5_!A56i$V-kAgDiKk;MlRFuecY z&8lbI>H~QR6{=1;I%G;9X05~{sS6x=*B0lqCKB9AueU1XelWEbmZi70&dyEOlyBA! zk(N$y=W-@RM6h<@z0pH^}jv--cE7o`FkSq5z@HgT{5BCu^dg;47kU|qO(h*U9b zr7+?M^=cSu1YOyRCmm`zO#Os4g^C=dC642N9pU$tHDDzxad!onj^DVE<6&cxql@ZC zPfu_CIC6Yq06}&Q4B!`GwO{#5F@w1ImoM3N?!>N|okLGYOFQV}Dt(0Qr}Ql3B%nu? z@U-Ed01H4ko4E5AU4UBHyfju1V%4MYR997fQprB`*hhs3_JI`$QihYB5ux-CI;NoI z$XPRSc3uKLIrNhNDf9A%^1XirY$id7A|)YlWel*po=c9}%`PNysJZOH)}s*<6%kRB z`w*=WYMn?80i4Wm<+C5W+6hYtByKDQyf5`#<-)_$oxbm6qlSn6;6Y1*Xox&e65v_C?g`ZAP?vV{?E z22(0KFEohKr9=&hKtq$yn0u2vC#e@iz%@8VN!RU32Q9g%*2nC#T~0; z#Har_IVa}^M#lqrBM4Ru9>;IMg%U;j2<67BmsqKwWxy|B`tieKy8s^yLYxYb0e`&f zZtsIe0Pzq-gamU?XqnTONXBq70HeeFKbWRLJ$kqI7F_xtEx;R(U18IpFaWnMj^*X% z#vO7E2QLn)$Xt_m8249}rvn2Bn?h8ao4Dm>Vi2Z3vOVkX*uQ0G9>MBN| zx`7x#=N1^)l3EDkt+z;)@2m0+iKu-w^Y2}z zxV{W;`Lk_3DL3!NY%6VOno~1LlGsB#dZ+l#S>Y7j(601!0lGq&S zkvFszaLvPq=NC1ptQDWe<;!tqTFcFc1e+jH|2$uq)6=dr!s%S)D9|j4i=qd;h5w{##Fmtxajb=m| z%y*{-Vz0%t0(AFgN7SUj38te@uA(FE1C^CIP#`35;cxKF;IJlWv~%YikiQE=ZfS`) zJc4FB4UY?GoO~sh{;S3>^h9F%R-3t}$(L@;QOKLBYv{8u-D6NX22AnVTXmlDiH|cI zE0mNByTlnu`;F>9R7+VF-{CSeB#GZS^tq!Ul&|el?2A1VbZqafbsrYcaNND&bZicx5)8}u2 zXCNA1phiWbZkW|~sw*|DpPw}lw}jBR;{xrBFCcL2?gpGg0(pk07=1mxCZ;=J8Z%;Q zfNlZ%-CMfGih#)~CJNDOygc7qo14Q=q>`}10F(L}KZEw8yu2Lrnkx79)U>o|91b8Q zF<0##(g#4luFRJ$1hY#8?6+s^_JFj7FseB^=5H!fN3ZJS;4lZ*HO!AJ7dG<+L7Wr$ z-_eI*I)b_`5~v2C%4maiyjDI4Q}%GjB2rU#$5@OZQcLBdDsg5pCZ2U!7(Ej{gTUQ*Y)cdHkQpG56F_Ejr0IjL&BzrWMVN3~!-_xq8~lDs4lLGOe2&OV3~ z$#D{)V5sj+5~lwUwr)xppZGT`y+@9!IHvL{Z2M*d>DWAf%V_m{6Zb_SC* zKOJ>1Nf)(IfF3@VCmecy{L1EFo`%N~@J)Iwf27HHohqYlXdx&nYHW{Ul+@T>zq&Bq z&P7fM3S>03x!L&2-8GM1w#l?|PwO{E1ye=Y%7%vTGyA@+E}$vml=t>$Cga^pC23*2 z>a6)>am`$x@?EO5w8n8VQgF>ok8Uwzb2HV}dwD;8=wDqY3ylecQE*uTNp5e}-OSlM z|N3m95oT!oeD$U)o#*wqLw8GD`w|p7EMaLuGZYUGXo`rpKt{u!dvGZ);g zsz{=`XI(G%>3G&qTGup`WQ3`$|K#<~-v?Mz3Iq6va{!1f&?caop}w%$VA|e8A9frs z=tv1@QfAEKTzRB@D_;OFYarZ`$adl1wF|%(pnF8b*81AwN91{2?7;4YhjYr@9!C`7kKY11yC+2BhZa&lYgyd}Dk!k&3Z|R9m;o!^NI@G8zjO zGgucO)W-GcQ_^%dmDMYVDsXf(JY<9N%1*T}+oUc4xaYj=<^O5FiHuU zjjP|9?FCZv78~iv$TO$fMnOn|aNKE@r!W(Xsuy)7vXl1VU~!s@(hz{t`Nz_dg?~MW zz8+U$Z64|L0*@UbIXQcU$l`*m_l?z=hHyv9?LlexdHr_lQ=i8>J-%TT{*KQg8`{CLJ%GyDGzg(xdMk*N$ z434Qv73Q_}4{^Fm74DX2fBkx=41GheRQ~x8Zo2ZApb@1Y+f$<)_8%6_S+-yJReEcJ zN?SYI!_{=4Z>zQaIxJh)|(A~_8g(IV&3~+ z!y4N;&LlLep-D7+DRuzK32+bXIW`O|4KUK`iS@yd8!v-U1bYUKjgYDb1#R~~2FMg( z6A)ye4)`Kt?8xn*4gHBa7^bpQOjT4=P`!Yjgd@XS#mYNWSdmoBEw#)y)gJKjFy1Ij~^a6N5HHFi% z$<6ZT;v$yAIme(Bx|Y_A{yI}l&B?TWQfq7apIc@x)!F-=hU$19yT_&QZ8ADLuO{wr zWOFTL^2_;PuGlufpq)1>6~?Xs>+ zru7G%4Kfqj+cv(+VEz4?`#u@{YyYw~y_adjxB0TcH*6=P`@heQd76$C3l@&7EgBwt zzjKG*YlFnpzS_P%p(&S?4iSngLMQ;@&tY* z&mortL~ohYKESyF&gjwTCKdJ$w9DvI;DN{-`N-LD18|B6Ru~NpA_=V8E<^+;Bl#D& zH=bk2r-V9?o(l1`^yZKT)5BuKo^%E?zUKON3i}eRwfCVj&d$;;2S(BJVGXM!0uui( zWTFT7527Z}xO7Q{JD(I#adW${5iBJ1AVB3JD=F<&O?U2aTL1q22`>Bi0>Ym?lykT~ zxm9t6oI^TcrIPK@Bi^v8cKVVMjWd3Ue540;I}eZ#ysoZGwGe;M(cnvW_M)$bciP_K zQj^IOJK2H9JW~wv+)ypykc$MV;z%StYT^!RHe5XKDX^W zkYW)dH7Z6bvLDbAu-T`;0sDI8hVa;Y#qGJYrD?6@)y-bWdr)R}|=2R`XC3NmQxv8m(>xFqgd4|GaO6AQBX14{;)EjwzZ07<3(`kEZ z`Dasfk*WH7_oI3x^A;R~l1}q7!ADQiEz?U3)=fjtS+ zU;#Q5NmR89V>p8d|1I!=xjCe{+_|fqFkPw<7^)!vat=b89@Ich`*XmeLm+n*sv8vF z?#Po%q7is@UN|TuWCP3``8M~|99M3MPs6!M)5s;ZOt=b3K|yZ4)0T8_bcg4TpE^5Yr8 z4+8~k_InMj9#%X9UK3s- zfB}O33tA3(7XvM=#A){9eo^rq?aC1Kkrl-74Y8bzPFDsRb+@x?o z-CC7ae=$gHC8aG?ixpi{)y#@l3asjs529*L~8b3ZsS@Y+9N= zTC}A$Iv*;Da>N zjb4|^S<&!>N5A?JqKX|qAO<0Oo#N_2g?HWLvEM@qwJ zV{>}Zknit@U;2iP^z z?6BGf)gVq_E=dd8kcQ2jzyXg(2*PDDhaDZDPgh@Z!Cn#4VAIy20YeRj>|*ZQ zrE5Vcx8Zm$cba28DbXIUGzRDtz}J*sJRyDqj1IR3F^@C-!YkbX2|OeMOhTpCiQPSP zDLFg)8%Rm4`=wvMP;`>xL_sW40qnKFfIBNkC${6(rlw$d-gs9CcQt{AB*qx69l+gWdxmOhKz z-mpLM;m+#GDTm9Mj{GfaOY5i#-w!vUoIiWQ5A$KL*3SI{}z zInpK}HA$L(5ik4lQDA_zt>y_<{+`~6jLZ_fykc+f=4k6T=8FtN`L^4Y{??L>{G7RP zt-q*@Sd;Zh#+(go91g?7bbZfaT5c~=zesvZ_AJZZyjJ|sn_$}!2&Yz0sI6a5H#j31 zk~AD6W@=vdBu3}-z^&{)-NL)3xr%XdQgd0EP4N}%lYN66bTazx-`OXOB2ScLh}wOq zN_R|-=XsIQnj;ygrNvq0>LzWS>NNYVNZ8?!HOsBZ6MZM?I5p^a(sKWBEPJ(d^jASS zb?x*k`UW+_8-&8Ey**CC)E5OOm(G)UI+GmC1;SL=m_!hr8Cj=P8o^b7c+0-? z_YX3M^4r-fmp{=!{{pzc@oR*RT!w{w*lmIxy14eLuxJoru*j4q|q@}ZSsvm5- za3)tP^PILYWnpkg!xKrOZIqJI)w>XE2@t$gU#64qjK+^AG2;uB+gQA}(0rKi{xv6Y zYybK4PY0jgC9`O+Exab{OndrtcEOeqod(;)L=vy3&$Uio63`ct^<}@0-@pBw`Jwav zvGkm%uUo6>GV}5q|WrXI;5MM#9`TuT=BNlfuGj zKQ=7~+O@wncr3?E!wUC{?O1TVQMt$b-gm#kGEG`{it2hjemo`CtsIss^S+nm#tk|t z6I+Cxin~j%tzDmGsaW2m;QXO~UvcTK1G&K~9J2rIj%kV}5^;(?A!jCQ)VOU=$qL5C zZe#Tw)P;&*;gHx|kB+JR!I3XCTG}d8?cmLFY1Fa#1wTD(L3>b&%y_!O+`K+Q?1qfQZiwks@1Rk_u#@y@6%9WmY2SoBf!Jzf zZ)~cI2Q zw4y{C1(I$EdniPh7_uPY{ACbJ9iwAKN?VsSu`fc6(9l4sj7I>BFG_2K5q*cQhKhU> z)OrJk?rr~YMq;2nGL*F)%f0tLjEft^Pn&|13<0YckQHV49$7aiYk$Ms5HjD-OKg_} zE{O}o{j+DHF<=!)Q1YQ9u(PxrfRzOLAE$-U_rQhVNx(zZ<@2vi&bLIYf=qk~Qr$5` zsiI;XRl6d*YdH7d;Z5Z{3?%fZL?Uc?~yu!~= zD99OcpVD-}(A(!@kj!lC3!lR8sWNaVlBmc#`|H%BVYpUM&?jb~Rac|?eCtg;ItuLO_j9FI4L=hz z?>m1xvy2M%&}_n{fgL6RIPA(2d>tht?QvXY9gBQ-Nf%0}GvfZ|^kLqix! z$2=L%^{DL=iM)76=c3y0`ES4K{F%iM+_U{A5d2DdBjHG~BlU|jI_BZrN)%`Jjg0IB za;RZ=I;Q9O5z%^m`wQ1jGi#(S&nsLmKKr%l)>vJVDu`E)U)vp>y7KnCt;xBvnV#qM z7s`3SL$$~;vAEVg+oxN`iUy^V58z|PpY)O$wTm$t!rqonIMRgP0*VwUZLr-Qnei@iD&-E-V5+T7&SpC1aN61kXg zYa!iaR$*|0!HdGers|Op`Yxrv-fWV_78k#!F5UzhZPoL1{rF2QLprg!qXsn-P3S9C zwrfu8)^XNxp=1XGq2| zZyB^e;`AjA1xTQsAq<2>3!KS|{QO>QSYu-w<-bRhgKLL(W4lCh1`&CIRRJyqX`(!L zmam97K2kN5;%tCr0ouVkG_oQ<7n^0#02}AT`M~SIZOttYK{ypp^9?Ax3PTcXdVgL&R_*6@M?5N&>2Zr;0n| z1@Oydl(k4B^}Pw2437yEGpYBBEg78(xeBAv;^WD@1ewg1~?1BZ)ifQg_!7o1IHr^FAE#{(M*jkvEG7#bV&?fT=Gn!%mJ!_)nAFJDGRwkTzM>`=~T=v4T8>A@&BHmf*GW1@DrcAhlaTsAiGgWktBF*D1`@rlxod4`m` z=iJ0l&-CQs{DY2P16~_^|8|8dE11L2bG^Db^074Ci_;(Hvclp+@+>7hWG@?R;|N?^ zYu56gYCEb%aqr&jppw*RmV97-wz7rb@>=tEpSHH|6UVt0SZu88X(6C7Fd)e~ZMClq zDtDJ~5NvMw_~qdv7BIKIbVqGP?M7?6k~@2BfJPW}fCHM_n||A6q|DEU=KHe5>3B6j zzi0YyWtV?f>m%!|vh`z-`B_+B_c605A?cnMX?f*{>Xy`0DjHx?gV|)5u>7}YkEh2b zso!cfZPIJiu76kzN~`KAgoG}fiHaWISZ82kll9nX z7P*EI_ZgWYAv~@`xy<=rzjl2kw)0=TOrOd@O}fr$iFhi+1KAJds&*BGI-g{g?6e3s$$f(mUV0MbDVX4~YN^ZF@b+y|`JDi;@X&@-JY#2gLS$>W zWgNn{pd!MBhe}KxuEt-5dt3P7Rp8jUlQ2v7nD6l;9ikC!F4E)Qs(1OaXqW~9A0a(& zIRTpcgh2RPOPIuQnK9@kZ1uuOHk=nog~TO)Yu*-svYp*1luej#fit1&@IE|sc!crP z?d!#lQ3ZAkr4TFv!z!@^#vZfRLuTvdHndyDsZNNTLN zJAYA*SEPan_3p2B*H7ek{uUf)DZaYRmwt;EHvKUEvlrEDMM2is4w6XBg2wZgY1tsQ zC#zUz|GiMtMkg%X*;kiqepaWUJ@&B-1F1i&;YB>CKoNCU!wSxm(Yts_*Z@gNYhHSJ zK;#CC7~T~D({+3INaNez-?{}`Apox*DS^Q(ICHRsS>$3>*Eap4U57Yr`i(nzGcNlp ztylGDk{}4*d5~&#>B8Y>isiZE%Aeys#c%BwV9GEG2~m3Ornr}CZUCIsRjVs)?4UA| zlCsUH?MA%|rPuyKGWqitnQ>jfbNk?MrawQcy{R8OJf^j+@Y>NLJG|twTQ#k;Gc!^} zzdxVy*f<=_N#^DHL)^)_&G05OvxJjyQqqS>pRez5_D}cM5!DE^zHk zeXYy1l$2Mk-*#=|@uW33PkD~Py|0!+DwPWDvzG46%;|{SoV&=W;G24q%=n`UUURI% z_d3KLtxPR{=IE83>{v9bub=LrBzdcd8U#p~3LD-2Nre(Jlo1eZ2Lp$6Rc%UQjnyyf zt5$tEJx@JYe0=c{e}89B5;vndco1cPloTyjz)a7pExYCp4KB^ADk~RkPN*2V_&VeF zHFNS!Uq<|2>1<=(%*B`K#($|511E^4F<_A z*Bu<7vPdb1SwqQl-2=)=gz&-CK_i7s^Xd#Wo%bnRVJA`v^MB=?+y6z}Lt1}wHY2Rp z82}|z{!f2BErc;rX4K_q*Y>az5In(}h3g+phiNaHF*_RrTJliT;R0(54hYI0%xA-S z3@r_!ehgoJ;YYYk4r1_)zAlIs>O#*^DH_rM&oeHQce_oEjn67HVn};x+O-UZ_zuJa zHbUAm2GId@Ahumw2|V9@h(SPCLRhGF507DwvW&mY%Efif z$W)x6`#Ay>k3r^ETMMB}wm(!gCsL7wbpe(_C@uhE?%1(oXu3P#b@adIe7w1}_05k~ zkURi%d*QD9`W1x&a$XM|I)p5^I4i7b zA-KNE0HC}@fl1{-64(_|6^aUQrl3h6JG4?l?TohW1|VJto8aknb#c**mG2uH8$*O1 zX#A+iXV2EU)OnB`Xb!a^1e#EZXgjJ-M6$B8BM_?|@a)R!>cU`7^3l5VVOCaGO;165 zn22CfoopVAT_%A`IvhoH5Xjwu1KnUwpf|#W?hX*ze@q8dS$rBR^fZ_fP8r z3Ojk2#`*t3L$JGpQ)Ti;<#cv0i~li{P56&{S+ULNPf2f#5^8p6BPYc%fg(%X7fK{4CyTtg;LTL_FLtaJ)DNofBY!A{Gc= zCInb*wtBpbgYVuUtJq&&-Tr7Z#OUGS6ZaqD;M#PTL;{cVQB^OhYiMX?JFU#W=G2js zvjKQ@j_5e_wnT^~#=t#){uxG>j~}~;(LS)ul$F8nEmW$lqJffEU=KeZnZLh=<}qz1 zCT5YJD^4w(2Wu*L7aV`X#Y$s%xzO8s*fkOq3CSSOewfl3< zSv(1lc~jyhV!i$S`xo|EwfBRLdEP@a|h^KNG6oIPFvEhf1QFs8Wf|USC z3z!L12uZ1!Aetg%=}8AWj7s8x&G=o5X9xlh#dxEO7wc72PJyGq>@+K5V+^3(Pjdp+ zR~*U!%di&k1xjAz$+K@$;|@{Zksl`l;0ah1bXK_V1x!+6Vhmm|aN=HJYanJH7rWocQY1^wY*4$5az- zbpCYpj^bYZ`dV~jmIW-@Gdbg_yoFI1?{v%A+uH;72Q#V=`|275!0;%yw6>;*WTiC0 z!uEf$xsoZ^{!sH)i5N+2wUy$X<_aA}eoTm*=w8}7iaV+7Npgv1Smz_i&1 zy-EA@>C?t)r4fG zJTHI}=u$D|HXHAWX>Q=Tk)RCq*5;8q_#%;gmvd>S_y4?3139x0^H z99DJt2T2YeT#+@!>NQ1K2VA5ugB!~gQZWpLg(|`P4B!ZQ z5Mj8@PSQIW8Ly)QMO8dtmq};k!l7?;{rWcu9PwdvV2Z`Sjd_3mlpxS&aK4m*5Xa(2 zv*xg|ejC&uOw{x9iWqPLZ9T3$X(tIj%un^>xg&dLtr*Mwi(d&M3(!1PBFpJ>{u>01 z5}~HMcl+FVB(ycY%+DW*(;-k)NQI;K$3nLn(k5WlKQ8B*t;o}L!lJ8K}aTpVistNHd+bkqi7{) zX+0p1hH>cksQW%H8~&{4&@tm9#89edN}h2I;{`tn(e4g*b~ivff};8tFIpgzJ3iiM zYM}zML}<}g9LGUAp-rj8VJ@$a;nWz>f;b+Vp337KqiR0*XgOfQz#v0BN@;VVFpO%y zJgBI+4qg*GHwHtwVnFz@T{%Fj78luNuO}e>1s#6(D>pi{nj1JhO(8OS`t(vzXlZ)- zEJoIPu1rP?%CyVdUB+gFP~fKqLROD(;^QqsS5GIoFY<&?%YS=K01$Nuo8f!hA1H}5 zbbz9m^@UM=Kk+%^xf5;ID3@eXndJ}T-Ir-GA@RT1dJ||a+qY}@hYZP_keP%ON~UBk zQz28x6e2Q|j1fghkttD#%#oD2kRq8vl6i_U6iNdsLwWb*exLVS-&)UaJx~ApzE_Fs zI?rR+$3FI!U{DtzIXl z+i~OhmJ1${^Yz9~!w58az!5D}ys^jM2W1PNyvI0xg7%gc+sr0lzrUbp-{r#`{z3i? z)TMwZC@PLX#dTZX=gG-(oF0gOOS}IdC{~S)y}xUYp-NL89cb^dSTF)+5Vd4yRTh=pIivD~#xzV*X+#^=|V=`pEW@Z!iy z$4mfGfd?%X5OO|SwCol~=K43-ZG!`NsNm*pGxfvD z4CKQUgH~Wwo^eLppt_`J0Ph@o{YZ$rRP?khh2piba|NjyPH-q$Sin{u1tbKgchK0N zF*^bc?k-C5I%rdZYjpC{Q81T=fW4>op-Fud9o>OP4;`bC8?)LnpwxlgkM!|!#}7ImEWw`PIhM}9tKjGE167_` z`7|JA+MNoWAKm?8Aiobh|A#XEz1q1L+=PSx5Kj>C@V)v%Mflj&+S;t$P^|%Nci%1O z$AM7wd17KKGxLY(X^_!d3a|Yyt1mJzdLL_Qnno$&lGY2PRvH>?Ae(|^a}aR{I}d>1 zKxKe1_ByDf5Xtw&aRX@z>x2x==ee7=v9o`}V7K+=&MyM#Q}B4$iYEcPhg6RPIRbJ8Z(ILDwIQ9t_h+I5tXM$!(WI70Wp0J zOO6eehEB%nnI4$cp*92q8_$;m!5&UegqsX}VPqg_f_e*y6ME_pvsc1K8F)n)PmiGo zLBxUTMPyNmqb|Ndvxnw(PENPsHH^^?1~*TiK81q?#KVXWE)xC>WNT^>6|l!X^(4OY z)473SHKZva7N8DL=!F^&q+5!gr&xYZqslQVfRrYRJrF7fvvv!Hl|x?s7IaPV!3AVv zCp5pI{EW{H^fs+$mTrHozD~>riQ-4n6JS z^4h`@dV5F<=un7Vo)?$bk@4l82~?zh{BZ#n`AKQ%(2L72z+uLzBM3J?Cv_kZjMEF) z`V-3!fr2bLiIBa)$H4N(P7c6FC=9?pk5#4E59jYUBUyjlLlBj{DI1qRp`?BzM0 z`sU{Q8012_GU#hXKPYUA6W{=S`qWlw$j^lG>KO)spe9hoB_vFI{n`<55(J)nuLaB5 zv`eSKtU%I7m_IXvnWTjtbamiO2Elx|@-i_qLx;W(KMXkEP<`&i{90fqVSEGjPvH-h z`1Ew%d!6UhU2#64nSo`0b4a=z6)Qdjb0aYNlbjLL(aoVn!ZUVK({ytBgef*aZ=J40 zmJQ}a3YrQBwI&2BOxH`yAEMwvC?Xh|^Msu=7SAB|pka1|MnE#-AzgBE;vtK+=N~`v zv%-6wYR{erxo}hcFpmCHqhC)UCz5vLX-J(ax8k+C+!rp`&YJvLZ9t2gxRD~C2_Z5) zMTZHBJLE8wmnXM^;%>8fPtOIYMBp?)uL&{7C_i2r3y3hw5r-qXPZI;IBqCw=4T2{G z{79$?;p>-a(4x>x949sjEBQ0;a!@+=aqPADCy+Y5u#DP;REa_aON|HvFiT~u(9BD^ zjGdGFD7WujTA6{{GhEI~Dl7ZCyH6GA%0$W{5$+8;W^3{4(3VNQ=js?f>cQ8uiFp zZGH4+p8(5;HGfQ-wuFB(K1B7cLLp)OfFIexpP6{brRP=tuC3wSL*{+p zPM$;SGpM5OF)!v97M`w(BBZP#ApvJ7)LwNMj8ByXl`=-5S4I!CHKjUmS&B56uM1cP zgME?*XyI5}L#7yt?)ejjHd^-G)?h++J^Uqjdbq}@MWY(+mo;YR_6SHzvwB{ns>@Id zB^5ssvu=vHB6Hl?qg?jjffiZvp%*8B99X4xl5v~JIk&b}%pSZ7#@jMPA zawSw*ARUg{ciUW#R!PIH4TL040gMDq4GqGz98!dRGTGQKoJ%3J!5;b%+7BBSxhSML zG=f@D@qy9_8x(ym{>|gIubM;CCT%Gy49PQxvdO*@$YTEVnuh&dP7YFUi~3zsj?u28zI{aU z#MGHM!y@+rf4*4%`#Ao1i7bSOP;0$Rw>uc&sAuzWTJAk~7ubOAeTM~cQS6&Z&3$yl zt~s(Es$~^a5=bh9p%-#NEjEU~JzI#uL5gDg4)W;FfK5J&+7>Zasor1W!oaIk zDlBY#Qs>KHXoaiYDPw$#^_a(aC;oT2iL5RLSO!fjKuTow@=D}OG@B&`*?27=4ZuWK z7E2kzH)^%7p#yyZk-?49_c65Qv*s|I;SNS++%I>?#)g*!gFMB#94H1A6c&1M1CcWs zGs0t|8lRh69U;dCKjDjxJc4Dh&lm}>VzWPm`x^o*4h7&*i0*qJ6qv3dX`{_Y7{a|E zcKC7nE8U=WjN(ms^-CGm&^^#0{;Uty{C=7@yUsX%ZlK9_@4(Y@RvM}jF0?k^Q+Bzq zpF891;yiZb!MVTB9P&=&`RmMC`uBfXEz%XIFV}4pl{`&XX`JU6$e zw&nTXmiZ4Ke!=c45Ez&4BK|Oi6qH=}`OpOaPS+Mvz<~yr9sR=kx6A85!hT5BE@F2$ zVJKf*Ftq*;?8&e^?f2uO28#zW?xlR0&)(H2m^)MD9$&oV2i(=Bb`JQzeF+DGuMM69 zFcD@TY3%I%dCY{g8RT$jOvH`@w*fB_sUPJsBp6lsNhAp56TFD|(ThMmayR$-D4VHIqcL-OJCPVK=!?n$@F{V$qqKM?jhP;{?RW&|AdthTmcx zD5X?Xv|V(*vzILWGVhRM*2V&VX0yGP;jJQ9RoU-Atb?$b1yP$jXXb>Va7vI*a0gMq z!9sWQR$(C_A;rIo-E?c7YypZ0+sw?&h{=B@6OIjeAHt!4i{QzirNrfQgg7AKwKm5% zW9Ctjq0&bmk<&dx(2}QapM>`yA?=39S#+W-ud?zN`UC7Mx#4cX-}Jbp^3&G=RaTX zMiE@)GiR!)*@XTBTGzm-0P%H5e#D+H_F-v5k(y25g_jb-Lce>zp{UnQaPdt@BncR4DcsD9&7?V z^#vvmP}ripkyKJjYqW=tq&x7LW6H}8mTpHSZmTR$CJYV^Dx`r=en3DVb1IeqJ9a;Q z=7}tYmG;W~qC;JCOMqWwo413I2=Sg7?*LS*U#yX9p8Rux1Sk6Np=6uKP!R8c@LOxE z!02}1?CyIxU}cP<0P>!R32PNF1HrLc$W`>572C}v8vqCL5K;?QU3xkbH(h-_6RU&8 z=PrsXSLzxY`+TzX^NX2qz)m%fFP_Qhw)^9O1IEG<-1)@Eaii_;sPjJMci7Mb^drnr zl>aUoTlQZWGWGXg&O8*Mo!|AJY&RVCisnJZhamnCFk1uuSNNmWgv>s1Rx!0 zVX2Ah9HtZ)+7PV}4koD>Ra#hB7~H<#{K!js4h<`UrU#jLVd2xjYq3u&mF$M!NzCJr z!AW}{vxp)e9qR=|2a+w=g~&(O6Lr%;7@2y2LKRECcM}truvmH8!J*jvA-+7I_JQ8s zZ6t(4M3Kw$BOuF1fQJp`fj3Zi#?HaH+9fv9L+hGf>;Jy3W5J*Xp_06=)UnO4i)CJL{KSgeagXZtq-nkC!6QVV;P*O3owpPLp7ycl6)#&Z}^U#2x@PX8P zt`V&45CrabZ>PHoGCJ@-NK(f(6FTxxlk6-9AmBP0pg@zRkBZDGX1`61uU?U9!m;{O z;^l@;dSM2BZ+D)&oO*E3IrEpIa9X}em_gf&cQqW9fGa?j0phI4Fo-lorbq90gKVko zs`>8rJ|Us7tKAv!yNt-`QZ;{0?#J7|dq)R&K+bf*nmFzo7&TUk2h~NOzWN=Zt3HwmEw`ss;oJutW)0FdWCB>bnxV!PP@G zC(0Ud@uJF`0O(~xp}rDqdo*nT<|>ALxd?pqfafHprhPX9@HJ4IT*B9Y!1ktc-Nrq<5Y}3^Y30;`8YKN zHwi@E9Dp^#@trZtuTei& zeKNf7%(@Y?y8GemE|@A1%cEF-fmsc@a}|}7_qzv&hkt+W3YB(*CeX2sMMI(VMu9K` zr~6&OsveKqvJGgqZOda4@>dCMqvU1$6L|LnXT>!OdJ+A)l2gDPO-!#mmb}5UWvhsK zprS`rr33@fq|kInk9H$Y-h>VbBC;j>6^j$VxG``6CINVCeteveR>v)6x496~Xg^pj z-Lq7L0sw;Q7&#EHwN<*qy=cdMuA=s_TL6fNwS+x+ThU(z;n9QTPC!#CJz>S4?eOPT zAbyUnKlX(fLe=Nb11}lNEYH^@0i@W@#zu_o+4`W<{q55yGw_8cx3(PmYS`@L?@`SW zuf4d`e-gtAOjc2{MlC)J8b~xTGb5fNsurY7ILu6WRtY`%^!2N?k+JEB%YL2{`fO?A&`@w8y4bJGM&Q1aeu39fDpQNk~iqToUy<&hrWcl;R z&`UcSpPd#(aM8FI$Q*8!a3Bw<$JUm=RSI0s!x|b(@DJ);O+#@!TfBGa8gD{9iCt3N zf-@(#zPHfUi8_?J;pus(2GDVk2Ie;Ks>&-fO=lt1`o6#aH^3L0V%v}+SGA&SR0}Zj z73yiR-3vvFgt)l9?nBan-&iWja66Zy<=$gvG=v_ZtW$ZoFBLq*JwPD}3ma6HB!aW@ z(f>(UR^I6Rge-dwNLA&d{3tLo%#kIad@~~E3gr>k4-tb!HKWZ1%>jzlQy0VB;Bdi% z#xvoVGW?TLQAA)Uw+e!Nofb5JfD;9R=7@J=x0eG=20lc_#_$?M+YZ;$dpTkajLx2& zCluRokcfsp(*T=hqWkv!$h~djIcLkqieixft$tb~u~UWCgG-3c2pbUm=QVXB`NJO0 z4LPyK794*b)vMf`lXld-3WyHOY+=5ecl@eAPXRR7N1g|z>Wb@G?1w0j5o@D^6mlKB z@V0N;rtt`Yu~>44I!$I1@#xj`=+~A-?#h#$Ib&c%E+Mhkg;n=14fxHcj%9C<92Y$h z0Kam}d+?(hd-$*&l!LyCjAqaWVtAEOFe6S%(#-AxqJV6kr=Lc6mCU^}_`Q=Y3Z`RF zvs8JLBIAnVg+uEcRfK{I&jTf*GFh;hjlUxlywLu*m%vAb$Y{W15Y!}2lsaJU3e=8x zA!wC{P>aKb-eR|FFL8TNZq+;sPJKs5mfim;-- z-A2g$1g$J0cveQgNkjGn=7H>W=k8rP5;2+ol;(%+_hEZWaS$Ocpv1y;#%*5$%HUEl z)Yv$6T_pWlEhgZ!HTwm_Eb`m#87k)exI5ujAn@HUUb8u^|nE2;@npaM6&wl zu#pES5g(nCnx%9k>`jAA3zeuGnN#SXAhb_^Q52CVfbLGfVf>{uh*#IQLQEjTKvkRO zRr8@h#T$H#@NM`nUX7CQqo$!cKz|JCXFw!aX~ThD;I?3*q>OGI1v&5ln5`|JC_4@4 z0%;|o;e+|5JEMO>rZoeShTS~}P&*^zfL2tQgVZ^x1ip;p4=J);pG$=4b!5fqX3%?9-_-}Py28UK%h6&JLlGRqZM#ho04qB4!qq?Y z*5H*GSX#E(?!_bqex}5;bQ>s!52aVl5gZUvo)0%(zHVDYDT`hGSEtLc&0-m?d1yXI z^!4jPJFkcLvZT!@4h%9~KMeZ7Gyu?+qs#Eq;k;KX?YEfG_(^E`)Vm)?-SsDo5^UET&NQW^KJvGsqy@l)Lwjm#1aSN}o$E5yEb%B7ARaZ>!CW_`m% ztTt%XcZ0Ke7Wo9>3xTuTLLB@(Vpd38mf7B@J)0;gKd>7j!B#LP(ndyRJO!aXlq~Cb#1s0+Ds$1mEW) z&?B9uPrO`AR20(E@7%dC^?IA7S(pM-X#IB_5mcpABxJ!~VCxK5XPtfJERCrJiVkDe z-0m58;3VF;<1Ed&D{=*OF=-r_39AOsU&xmy-1y)jkM6tASsJIvw#1x7Y>feidiHC` z6{H+i4Kh_+?-Q3NsAb92aGc1h*cRVeyIA4rk#XVLD!5GUU+F_q$}re$Hs% zj93bRul2571?YUUyKw62F?WFv78HmO_JqSxq@(hK8VC9#5n*9dGqWd+rcejN@Eaup zRK3P0CMZbKoVc-K;K|^Rp&h8`o!v$ZO|+|8-qH`9`9(KT719qRRL`kxpl z-5jLar)tuY+LtDq%;Xoz(BXcdspHe?Z#$f0fAe!N|dT(1~D-v+BDnvj_njSI(pj( zP75N7Sn6S#bxh42orX3a( zP{G(sMZ-`tn?OqGs6ubd^cJ#{r2j;?EnoNaVk{rQF+?SX7Yl%DavIYD1iQ0;1x&JI z%Pol*JGQ2_iXkwWEixZ{p9lKFrjztQt?w*_ewmu0Bw-6(mNOa?D9@^ARfpUi|4tgD z_RmaAG&o2VeY>?Z_J*1-kVK47run`OmQj-kkWARM@_8)JJ=4O`=Rq}4Kz#DV4~>$w zmDRt6d+WGbmi-zyUcf7mx>o=Ei5r_Zb+c^>Kfq}D85jv<`P-b~jg>=@iUR_Fql9)M zs62}C(6pO!^v2JTb8v@-A-*LN6Fa+>(&yf{k<4D=XA^JC^3Z4a~(*9!Pzwb@R{5I>d`R_Ke~=!ntxmJEKGW~fM9lDp#>(>7&#{P>BnU2`we zfHPRmOObAHA7CLNX})#nV6154VLCHnZe_KGghq#I2?OOtn)Df>_HpV+ zfkGPcXJteRTS8Vo9$p%1Wi+Aac7%6r#WWlI5m>ak5;Zn8L;25GR)H`J4K4ZX;-6Bu z1_KC!IeB@gE*lA39PEzJ6Co_C%J>#_y4anQZ^1l9%g)7E?76t-#GpZF*~1vC2iwFC zZ1XQKtB)9^RgYB_VgU!6uzj&KC@>+_oi0NOj!(M(bTZ`@Hkfn+LWyelFi`D49D~Gt z$G&9a{6KMk!GEyYl<0zeG%I7w zvVH-BIp^f`8#9f8YNnn&6&895GNprVxR~z>O0W$`q*H}S&t>eE@UXLk7x`&+Rspyu zo|SFG4T*=46h;-tsdDLAXedQ!JqkT_3b21L~Rc(&+1+@+80mg;t? zz-Bf^>yy(U8<34dSTR})z!>0_Q0&wXe$P{rSkgdMPr?K?;`XHlRX6 zT+cs7V~#Oo`l4K=hZe;3$!u|w>HEH8C{t#>XX@|%0uH*XO@3F2Y?@X zMGU=ODJtg)C?8|c@o{i;Oun3BT1Ylt^(o!8beekp6g7cc*}tN}5d{rqusZ29qW7!r zZZO(QGcxK{v}s0k8Kjh<(I>10zgjN_4YbYHvgzzR)G60?^UB zj4}!X!e;?XF7MdChCIHC5ES{-S#m1rpzG9ULveYLGl5CHc1PWR8YXexi!XE^DF-3{HbxRt8Jx^*%wg8fWdNUX&;1GNps@RP^Vtj)m+qMxg zgxovWqF{GT zFOO;Obo?g`fm&rCboz2K3BKOmLVPr!fXAQMpy7-+7%sM;$prsf?ev)(QTXX>CV|4$ z&Q}Fy5+638v+}Q9qd~CpbONs3Rz{l87#(nvzX_)ihA>E0H#YWSBh8sA-?>~q_6Eo*9N~|t z$gG1#$4J7Yb6}&23MDAf_}dv6pjln+BhF}mc4X_;iMcsq+SsImvSYM9Nq&Vo>)}Qbm@XWy|VCOCy z;>K5m9nsjvYA`d?^T@jAb)tz83+kQlFax@#parYuCZo-pd)AhFuF{)$O8HFD?qo9f z({Uw6S1cE%h)I(7KThnDlcNo`mnx_aEqF4Phul`}6ZLXo7xATKnq#s=RYwoO0bp6R zr!Sm;YiPX(I27m@xes_A2E?&lN(cxNb|pJM4OdHt4e3B(0c?;M?gKyZSg`Q{woaEH z+$9?NdNY%ywU+z#1ND~aC=3xqK<{u4%PPU*s(v}yWgU@)SgzMyjbFgYsG z4mjO{<%Nde^CRr5f~$0QY%Q}rT`9HWG=Yguo(6ae67;PjQwU99?VFxBv5V!p@BGLa zCntFAPI~%VSfrTmL8O6FGbBk_?sf9*vp)=g0)FvT^!F`_PM4TtK^aUj(%VUj+j~y1 zY~Oz7{aLRD>`o`o6>l(}2yW27@lZzIKTPnCJ6#5`T~&T(JEcJ7%P8m}2lN1jgI@N} zm-;NpL&m{Uqwj;mEvf>Tw46lKh>Se~40Oki353VKPy4)meIeD$&7k$TAM{YrTfdCG zc+q;OsMjUc^78*3NQun;e*>vS^s@k`+o`pROd%Jf4LbJoz`_20b`tm$=!6o1rFPFO zHp!fPcA-S(-)A=nzYzo-Ge*cnUvMgW zG;`g{GB2p_>^vsQ`g#h`9Ms2gky<1ypQ~CP2oOIY;*Z{W&t-O=s-6g?AaHc-F^7T+ z1F9Z!a`Keb!tsUWV@gZ6ri#(*{zHAT+w|cbpg1^6kgYYgw8S3G3+SUJb)5D~MtK)W zM|B9`Ye+bda8NQu6OWKQyuH6*=m*1D)TFIG`1-JdI+`wxV=T}!E5y>h*q3B%ZDyis z$QhhO)-=u{Wntd3OF(?e_xcWRuK(^2OI*O_5 z#EffJ-tF$A!(WM&Xp#r`Sb&&Ckw3ukM$AsQP6?kFVv19@eKYgy5E>cG7ttah5jNYG zkoZMKodIQ@4E)gu+|ooWv1rR-dbssKwHBB=R8B$^Q>#EUz(@jxBF>XbQPG_m$3U>9 z2n+xL2Vx~(?SE*p#x`Thl8W<$auA`&7a6v_T{l^`&w|o>CrF#vy+O&8D zNe`Tzu)}?QR8X*w5hKpbsg7x0BU95~I1LHp#2gJ-LAjW>G;?ur5oi{M3JB=ONhq8yU{oyDOOGUIgNnSdYajEckMVQSL8*>Q@d8Yd7ocJXrn}}1j(A`f&|Hbu z>~_?@@OB4g(}08t{v&<|fQ-NG`#VuR9+a1lQ?Ugx0Bk8tEeJaA<@MDuTo71;op(8d z0G)4aP>_F@TTDE9Wo#W~K*8;kc}+JmUpDO0YQFfDHz=qegrcCpnCM74m9u|+&3Qe@|SVf`Fr1qSX6C^2h#I&g8)A2&XP z^a2NT>nim$c{Lst{hcDlHGalurtbx57FlYETOScOSKYbOaK96gY$jVx0u_;hqB%8C zrj(SJtp797zBco6O7{Fd6=NCy%&z%pIy&hh5y6+`KL^ZR+Bv$}M2_X1ZqK-RGoNxx ze(uo%danFvt^(_tdV5s0b@ zFaeuWua*Q7gy#gb9>6y0b42u=pfd;y$s#HVIfB=(;pXnG(9Iz! zIldskPg+|G?u@8Y9bc#)<6HY%-`ktl>t{wwX;npjTe6|IFfMuX@^VH$MZ#u7!?!hZ zi!&5KtLpcZgZF>PjL0<#IZV#7Svxn6^7Z#CcJah{Bd!dbf87>j%!@_9eF8RFL6pH`_Q+{>w|CXeo0tn^mMFWfKQ z=3pyLPRj2!fXS_`^cCIHE4y}?OHe1$&d#Zcg|7q{6n;~BKt@eH?wR`ZX^q@@k*K9Q ziW^Mo?!*M}ifQ50!tzlV8C8216uHj$-q3`q2s(rP&jNOAbJ^IYy2pZe&Hi%bR*zEV=hLMss9Bvt97LtCY#Za zds%*i0t3tj^fpCRS|6e=S~l#sF?0$J<`0UpxL9-2J2)LOWpg+CcP+M8+wYkYY zt&(}Bb2G|HVlPLUXWqpkwp*`PKgRm_@W-pVf2}=qSYrC3$%ECtI(xEM>gUh%4nKV& z_va5Omiqnsx`~ijM)?DS&SOmKqeQO~PRzJbdSXmLMuv%AZq42ZPRKq1rqs?q59H)e zl9GCCgY912LIKXXdN%?r44_Ht*H=IepXrxf>7PG%T-v2Z*ThG zp&g|K(_bd0@lT(c;f}0_jkDo-a`hHM5gtQXH_$$?4um(_1>anIlv@PBK1%Yr^PB}j zcv%YE(}+5!$nrO4Bo{ASAk|^03kFR$`b3bH2CEgq-tM@mEtF$-86FOfaV3u)F_1oc z2dJv5#%f}*(cM~}pfo7#tXO&8lkNDcq?DyaYmR|o{6p8_U;BhMk&_447cVJ$pOKNt zyR)P9;Pm7jg<<~yb@PGRqt2pX;dT^n^mWDD1&hs%DeQj)$?0r4bVZ+~;4`2q}IJ?|;#iB?8w;Lbe z=eu^{o>2&}d_%L&2*Vak?C|S`Qvi@LUk{IBpAYW(g7I;hvD3b>Npc+x+TExujt(iw zn!{lC8$&Z~X3X`hdqk0w&1wpgPicQhW-{vfgTdfNnJ*PA%Z{4aJ-5eI&<}SF@GNGnQy86}PUKfpqM%-;`zxg|l78WvdHZ2B_u+&Jy z_=4S+ZcAte|G1~SwfApR%Zrkg+H4OBxlXgWy6C=8d)f8F#;vP+tD@4kQR$Pa8 zyEt*uUpxHUD0bU6eilffm>dsLB~49bbd!85mH~5mX+b+p;9w5Fn9|JD5^dXpyh;xn}|2avpHOy#cK~b zw%xmT=qQJ%s^;aDK6&zcX^F5c28#FdCw4o~mf(Y$Ymygl%tGX@k$PcoWTQRS*3rGO zfw*1bAF{ZMHLB4e2QCy~C9A3izj$#O&ku$(n`JEY-$&5o8l6C^2*B9T5X7eT2s0s; z<0d8un*mYhD2Y|b^?c4fPyds}x^Q8fb(W?goX|81XSV@&@mh3rg^zgbQBl^b5fNaq zH={79^bsd2eRX#Y!T3A(8TMZ8*dr-Q z3bfp0F%Z)`)#BDqKV2m(=dW1zJJvEvpISrX_Y@D99=BC}d@&vS{+k-S(k*0U94bLp zM!T*x{+6*4DruxTq3OlIK{DTCY}?gVc)dOA_U$v!JoLR7&YRffeB{#YB=s}9ZY8Se zY=++1iNV^uSSyK5n^X;$Hc_g@^5)TaYSY*rWDYZ+z)f4ZgdYSA1{4799xoG*GngQT zv%pP3tOOAa)euZwNARA)IHfqFLF&fQ1cI3pZWp>IVgJ;?fJsL>z~5h~FY_?lr00R_2T~Sdg!IK&uD4v7 z`bJ68ZtCLpb@Qx;Bo+M&+iPzdu#pEgHOy_l?|3ZmKeQ_4FPpurtVY0?Q2{ii_1^mw z7*TIolQi+8 zuD_qPY6m+X-}l8$Y;Ad~Z|BP`x?jCYN??_+#{FSSe zC!GAq(QjLn+1OLldC7t`L+k1;ikmew2uQOAERxpF39657N3wg427S)EdV>}aClMY7 zNt&^Hw{Nq|N}H^E8l#v}ec^=G z(iIhJhyW!&D8Eu~8)xg7P;wM2SQ|by$KFZCMW>A%ys@$p@RJ>ETuWo)Lu@Ucp_D&= z@Tz5Zp)BHqoewMVf-88^XKEAs1?&^ zQaY)X`97UEODVM-RuH%NPZv6`Mnr`;x(5%8he3nomC6Msuc_h)iO!fH%$ea|%+z z=K1-$srNN;sq^!B*>>}l*X~(lXc?IKJsxzq^nAwXI3-E-{vm_7T|c#d#@N|`N9$c( z6s1X1u|-$T_qf^>%JQt>J$^K80kBm|*y?qz9a z8y1+jR8&8Io?dP(&1fu^Xi?Pn(~v%00?82~N*!|IT&e(U-#JT5+;%;8E;engnxe|; zJwMs53jTQQJ?CU;8d3I0Yb)V5m3|XkHe1kxUit=jRl-F(+d`lLA3sXrKv64`0S)lS zya@qevH1cQJR|I(1t2 z&-O<9ecLA{Cl9}jLSlB9B?-bR;zdk2@$MI$dt5{%<#Kt$U#?1Q+xFYuNnbzDH&*DU zwtC#Zf8!GrWMuNW=XU28Qh-v>AXR1l{#L7MW^i@&#e}aGSzUF#+eSv}-oN*DccSKI zAdy1JBqT^AeSKBsUG`;s+`U<%#xIU#GdoBH*L(nmH>@okOmf~90t&+OjsQ{j71NJir3&M=d_7I{TE zh+ly-;5YP&>b|`d=-FvkT@po5lGp!!y9@ygJE`gOU@HhA9*T&7;n+4db{QoqNX|3@ z4u=4K4$)OvNyKYUdRBduc;{PwzQGW2@TMRB-2n_lym)BbV!m-R)S(2(CFbzMbmnO_q>KF8D1_rE?{Aa)?_~XyyO(X@L0XJKzkVYwp!;(i)>I!?v*Ew7%^NPB8i^j*?XxHSY zhOfhMiIjtbacT68jjD#@lbZ|;nRw{Cy58PrJglK+5Le`?K~q6R+!=&GrxJ6V!>FPy zGq*s!CtPJv;$v_K*i?C;eLrE^trQ@wpAw3I-wl{Z=!@v>wp^ovmsc=H-{MkXA(kkX zcm$Jn%?HRxM|vk|p`5ByXo#DDWfV8rmsv`9In8{aER6tkp1Ll+@TO?^*HGiHaa%D7=griCVAt!rPvTfE=h>L3+b|JIh=Z+EKg zUJj@|>gm7H&+f8KBY}@$fTJKr~Ul$H&6* z5l)ZTnFJe%Hx?}@;D*@d1{#n-(O}#^?S$TXd~ORA50z8}&t%PNw!x&QjBp1ytiw|aU)_E&e|#KjA$>;LkO>e4|**P)Nbha9lm z?qM{nfS=Lgv}nC(sm3WoU5ydn6fjZ@bufQDs;zwi*fsbdMMsH7r<$DQ^25SHSBZc5 zM9~-x(TlkyWJKG&Ee=wc`QUT%GkS#a2{)+6n);WgKF7gk!cX%-&r>8Bup7|kuEMWY%jlTAfzD}p*< z^SEE`A2SZe+!EMP%F3Vxw&Gr`5El+9SY_xcu@(Wg*|o!hH{+wRWCUg$2t3Q|54vaI zp}e{@rzQO2-{Vrc zvZ>{Sxz{8n)*j$mqML*OSjX`2K|HK3*^S$#9}&im&J~5)@#BferPmLmBFBN|XS&lF z2gmxrz`$p3Z0^%X9;@fDwzR;Kv0iEsD->qk2TuZ=txW&xK#;^RnLd^}E9 zh@_os6q%*X$wJa*Wg!W%Y$nA~C6H76zBr$wzO3n4=@*m3+hrD<~y%l(f>j~!FS1e?Z zib4OtY_4t6x$W!Ni_2K{pFZ}xRa1QZ$acCW=u7|vG%`0Ql!SogUFrZMnEMy%)u_gg zxZuqPdU6~ugnEc*7y>ZGJW}`AG1#V;8x=T6C0i6>dRP_vY@^okQ3cGZ)~Rv*usRze zYWuPVH8s!?Mv2>PpB6%|T)9fO-Tv%z?dh9MPbxQF#@ihp9>I00#ZsBt6VGFF)GPuN zP{A&5nIRw%ktTqhB4wp zgWbU1YtiBPqIFgDOtUl~Y&)XA#ZK)!h|`r4IiZlLLVgj-)WnnkT{y_3-hh|BF2t)4 zhr(h@RHNX57p9$hm3LA8w@po_f=KBsebez>$;~}-pXGEu-f6detW}3bqsM>(j z&H2EUd|YHv;Q|MgLs#htuHM5Nis;#}*9e4l{S}~fb*0n9awHaq#^+B2fpUmDh_(;Z zF%82>vxi;IcXaar6->BoA)fqKU5VS!DMrk<{AKkJXbLT%ahQ~Vy{Chz2PHMNv@j9u z8}WyOY5&&L5C84KTaJ5%wAG$lF+1ww)3Et*>r!ta&_<2M+IafBTG>zht>jI7*iDJ9 z->Y|8$%%m!Y{Lk#5+tv9vhCZykNRbFheS}*ae9Bdvd*m4VoE%7M0@POO~s4M%soJ> zWd!d&BO};o_<^&5W-@`{wyCm}79KcLX^dv}iPO8?@05L!dLJ-Xgepbu`B;6uT466x zXD{OaKfU?dl}&xG^T~Uvcai1g(jjsCNjd1@3)9V|jRDnlCgl2O{TwLDe2S(_x5)%y!$&MfAXGuO?^W1wg zf$Dvj|NW}|4a2iqIHv^$)%UYMdluYGfsXeVl``M6XLZ9|&gH(t;$a5;TKC7;eIGuK znCsWmX%1Q)pNJ(RsUNcYY``H)ca=W0MZ5UP6ZcjcpB;cGN}=R%ACnAOIY~P|jCL=A zwawz4@t2uQiuyq)CT-5of$6oA#s+ifTj`Fx4I1-3Ry$UST*_pbw#GDk6C4TS1>)CiJQ z#{`xE!GD2#ry>YD&z^xC#c5|eyzydd$dIo>{l7WGY?_! zl0%;9?p-$v33Y4ht$f?FBr>3Z28tzy{NJW)xpuO&;z;6rA|->agmqlCNCdvDenoWO>cF8?%K6_TZ}i@SXqk)zeEg$9m$1RsJ@p|l!=K6GSy6j zHE_^DJ%7P2Zm~#Hv)*G&G`v{&BzOp{8Z+JsyF;N@4^`0mtmUmwwg)PYb#^jdOd{|b zJp%M@u=jE&(qo5+2mtw{$HkLN{XfG8Iy+-Qt@GW03NV@vNQqLpNqIv>Fl;EqhEeVu z#@KlfV=2OkdfBJ9YZ6e4nl z|H5hHacRy}MNU-xSQ^0GocI(K$(-B@uqLVdBzZ9A_jqm*5fPBoiHM*+AuDPA-tDoH zCjPpiI9=iWFQocp)#o2Sd{`b>g>015kOklj?KXb9;}%Uq(GHfX@Av$7MR>Ln0qyI< zoK4^^Y+)b&a-!u873uRZdwL*?X7m;29d!*2eM@LwZL3RMXJP3EN;bibnNuG^t%co; zQB7}z>E%2wM~Bj7Wx`WES!;!&d&SYGXb^lJp;km0SuqG z4K%5y`ev+<%+9*B={jJlHPu!5z^}j}Qi+)tj)rQ{{!MpuiIrrW&aDs=2}V zSjheRMRSMpyI*>rV#kIcbSC}L?}MWbX5p_4)52qS<>PPO^!)r*AX;-PhQ!zxL;vu! zstU`78)0A*$pD2ekZ*w2_!YP{6HORfd!_oVy#%ZuA)lZ`JI1wkEh`^z+anK<2swTdHe?vw!T=cJkIe z7J1u7zd13?O&rwNI0ZDB)TK96Oiiz7J5)bq`3D31mDiFrHePO+!NCM=U1RHnDF12K1y3KDk-ul9NWs|?LESb9 zQB!&O~ZIX3&)GL5T}y zoHOp}VH|B73GA@~k;^hI#1Q-cQN=g1WE6pOhcrUWYoP<=fb1^qtLLjmgd3s)l|h}$ z4%RfI0Qcx+ z@cxxNJV4dLya$C36rbNSR455oSd2Q%mQ?BHy!knLk|dm=4~UpbNw()W?!y}7?%huj`qaCRwb+))N=yG9NBZn_{(IT;{_l9p`rJ_Y`lLA zGWSopP8T6 zpN@rh+0K4IxDJEO&6t#^T-t{+b=ourv`B)+CgaMMy{uz(x-*^N{9^?a0qfI`C-48^ z8v_>*&;(r5&N<3)?d71eE1;zwZj(R5l_3c$wkDeaIpfWZ3qB%kR{FA+$((pn4 zKhW?hD1^kv%ggKhd4aa+$_!vJ$905Q5Y~Z-7#A890PmW1>ZdAV)460QoNz+cbQ1{x zJ4OKSy!yXhn!dQFAqoTpUEyxi8W1S{i}-QsL>0)EnpewqU3JfMzp@9k4+_-^p2?+S zJ=)j(0A*za^@R%~mfydV*4{{}r)k(_7GzHFT@KczQshOHe061Hp_m+-kfDgWcx;Z=~R6-4gWwcBx$~ z+25t`UdTt3KpV{WG@Xs%5U@lPW`gn3=?79qFb8yDkdRkU@T{`hKt$eUP-4m&48Xzi zHntlu6G26yvhq0_RrB!huqB^lLMv?I*;!c^!7Mzepit@KUlf&KJZS*5JSYfSwJL@okiqMI_8b<6wDtJu>undGc&FEbI;T{qcx?* zCX+j)GFzrRxtiHp%j{RbZH)GbuqfvubFDFNe20!wB=J90J$>qW^yXKU@7|r?$s=wY zJNa?`Y&GAD4^alqc6;lhx$<%*lJ{ry9|CxDHKrlrkkjfbip;)Znic$pjEPxBJY8ye*Qq~jna!-Iq*;Bp$LoI%MLXsuq=%70Ss6L?BC-4enrKeYow#DB9<6g9xbH9 z?5B9qiD)Qv(4I@9A= z(*`Jrf0M70Rkywg^vR_Hm*jpore+lu*1(?(L_u~p5$koSnB0|*$%`USe4TyhePJ&- z$D>KDZY(c_-CbLyA{t8EjE;UBnyycqk0SdoMGA!NiN9XV)qZ(&T#zZaakzoxcfXVhlu)s}L+XetZfl3v(9L@^cXu{7g6aRNmX}1>Lyq z^$`nsI)R?P9v7d4Rt-;aOv%qvdo46JwQAs+aBvJ%{k$yh4YDTiJY~qK0Gj>Esz#sP z^%VFrvgR7nB$gA4eGYuiY@PZESQDAKx>_Mxb4Nleq62T*q#3Y5@=2)@9=96 z@-+r)hmaiZJ;+vz^E8Z&B#SpSeLJv8ktWk@;me7?&w8;byL0E;+JjKGm}m;Q?_}H% zvy%nRWU}rr56pGV(Pwj6MjRH*JfZZUuyBT6d?ik4f&MA}gCi;UQVl&M*LRZY0&9x? ze6KYT6HmAp{E;$V8$RG7Pf7@7->j?}^*UL-e`F*oDyo!}6aX30b>TYH_6`o%gVKxw z1GdXVQ2PG0>(@6g6a{bv8A>D`0nL`s<5|ZkfR?><{&_H%BYD(lYIVT6{R@^cuKg0>J!UN<6f`VBi8e zZ@@>Gk+|vVwu8CAtBBd|H$K=%xV!T}33q;;frJJM7CB(KbzsA_rG;k879_nIlr+#= zK&0}*Wr1WQK7ygH|25BAOulE96)4EB+Y*v_%~&zp$UBcUQgye-}3Rrhi=E8ReEm8;O?f z-~XZOJ;1r{`@i9z5h7(2*{dX3$tZ*nl9jzTr=3Jgg^(nBkBUTQHd!GNkv%g?k&%W- z8hBp6&g;7W_j5n@ANFN6I^qABh@H%(a+AB`_5N7+u4zdK4x)wcM1cpt)C=h8 zH^HimiJ_mQR}lU02`Up+D5%;mA zuZi?Z#kaLBIrePp>+|{{GQapNng^~TnyKV#Ywog}-nU}?0Y*+J|?1d#pno}MDKt{BDE zqVF2`9Zq*ei(UzVrf_GFgt;UEM!*L_%oG$v^qBsm>!2>f>OV_00`w?Y8Bm3`AnYFA zKA!&;|B#{syMFub9Vr1MD{Vxb!bd?=bZ+IRQl{9xeGX^=uq=qON0jPFsU|eRXI3yl z{_?knj~{n~fdR)+ptm5TEr0t4Ur{uUD8#l<0KuhG-@;<)?OVt+K*&dW0bC)lo1sV} z5U^e$IbB+LCFR^GcunF`#KefW_e)=Gz4tQT-Hicx`bwc_87#2j&>8H3D>0-&R(@ z&r5L}YkUVQAjn7YfH1Fqg9$ zEbEv3bxqGz#EoC9+UZ{iym_^c)p=(B{yGk;r;$z~wFh$qHP+sxUY^l$xqFu9Lt%6) zIn~PtbFul?QbLb8-XAikjmcA6Q00H3yP%p~WEgUDS}@{OHd{(u;5{Di%!ab%r#>mC zirdrM{=2k$%?s+;scAAxN_f7OK6$bkYAOO=QEbv$|8QbdkO3=s$NRuV6SCkbtDirS z>eknXPqVYVS(KW|1S=~s_q_t-?4Sf*U7=OaMl6!8t(gCHwTiu&On!9_*kHkxx#PnH zajj70m3O|^_N zkZsxY!0!Nx06@@iK?694<7$iswoNd(!RdNXP|(}g_b%)m;}7bK< zM>W6UPD2xpw~6%ul?lOrJ~ z(Pr0{8vy=QE)fFcoYlzR1ys462MThiYFHXhYFs=hB9hqP*!}z~Y}+6xL=yGL%a^yG z`T#SA*E{sl?r)yn&Axbh2vrIHfdfZ8;w&9qs`8UyTr);_Vy!n~r({xR0*$$Wq=k2@ ziA?sYfDqr!UN!_Ts9d-=k6f0TSzHhwRvr`;y?VclYa=-&YfloQgsle}_sNFgEXI{| zPr+Xv@*UtWueH)2W?HIe_hY6g4<|-62_S0&Cg7Ol4Ng^-+Rs^kD}X%3;$jymZB{UI z%9_IuJEmm9QC5@fqW3@`;%|?&)6kRHZk@JfAflnSlQARD0Or(YQ?gEb9S?s|PqTZ< z5W~TXm84*i;2F=M?8H|T+SVzq|9Iely31w$X!`&3$WU+wPCOjFJzy(+PR~7CK}w4I zeAcea>XW{b7IhTNB28oE(edPRoG{$5vU>Z8R@BooD2va*X;}39QL%Hp>@wu}a|cy& z$@_&{RCXZ(7u=RT;eFz%uuCmmx6(bUpPxm0&?>hdH1txcaXxN1rT z$IME#r2#*Tm@+!s_EafTS86ER;;XZn8EeELNADy1_V0)J-U7}hK&p7j=u}tnhAZ)G zA;4cr4Mbf8ts|&p?GyDNxNiZWfxL`pfCi^@kt9Euco86*$=WtJG=%nojA)Sn{@DSo z{Q_ztJKCQ=hw$^hNU=%j10YLsa`jK1B!6I!ojf_zcm(q%O2Sx)9GGqdXlf|@KwS5@ zQf}BVIM3bAS=*OsRH!oKC26T2d85}YGe2KLO6g1j@kAO>?i*G4H3Doe&FyBX?f99GJw6 z>_itAuW3@1lg(w0$cTef0?I|_sBA3UpAfA~E zI^v_uTnS4`0umC4waVBS+AVw_xGY2jcJC-rt1tV5N2@5r^q*AQu0*0@9B!-TFcg3{ zDn^)~#;CWfW1fb#L%8lNKw$_qF`Q{Q3!cu{`(UEC4(Ms{IoW?YksVs}uul(tp(zKT z+9!-ElaS$Rws>J+^@Q_FUDRjhp2Z(%lL~X#w`E2WhjfJ)ji`HOK6zr|xo8Lo4WtNc zaV@ROa`&(TQN1M#OUPDcXFG;&F$V61djjV3#7PCwdIXp*(0va?Hy-}sQFrR}>2Vm) zqerFK#d#G(or`a-RcD#q=uOkW_mO&Crhn3k$XWUKw9m|OR%L(KuNke$?r>ecUH4%a1q8R-DeRHF6rq6?aeIegRs62icB4+FzDXkz;{#c*q&U4OUo z6FIM#v_o0p^9IutVnGBFp^)0@@-lsRE2euS0XdI)mRDEN;@fFz?qHluPDt2Bc-6jn zvJQ4h1=-mrscgTENa+kvW*$^Vq3#Y7R$1B1{OQ<3ZT$zc)m%;`(c58_oWXH|4*=+E zN=U<75itS|Z6}fUn%$5{4b+BR-XLP!db->gT?T%mwN!#hgBt5pIcvoK@ zRav_~7s;QX0qX%yXxzbJi;YzZVnriEqG)cOcIx$k@SHxSv%8ek0m)stA`@{QHIRdy z)q;T?NJbJ}eM3VDBIuFdZ`cRRBmlnjs+j4=u zQ`2L1&u?MZ?E{CMn~o?j{`YBMLIB4@SWh}Y7lq_O6r)cpJfVg|Bw+H^2uN3;_+!|K zXpYj-bJz#)bVfN2dJ{QmGa5YnCs2pfm>2|jrZhRj)qmC--yeSoZf-Cv)x`)Ker+h- z2+&h(p&o!cNY}lMq$-uF*Pt>IGerah+7YB9BZH7R_?EWfzTuK|HNYUzP}1Bm3cQiu z++v}gFLf~@K;${7yV3^_c1%ri5)5cZV9&s9ekWVsLd1AkpvY@6qgwIg$q;t~JN&5l zw?Xz~_s7oElx0$cxvVfJ2PcLD>|^m6;^5UAnVCFs7tY}LFjDhns%#`KQ>+!zG=8_uMJm z>WqwHN66~=0$*!s?;IT?IjxeM!=Ie`tVbazR83ZjCevx*?R*>Bal}U)KtZ!_A92L{YJ=n3_!ue(sni{8 zZ4u#e1U3>*e4#B6uYGxhtONkdXm_9-ZtLq?M%!CpRCGHkYGhy_P42R{mzS8<%QVz_ z?qg+`%i)1x9t&|)a!N`_XsD=V?QUWo0!U>SftbUGfnb8FA5vzJfI&-x5j%{jo}!)b zn0Qi(NifzcW}PGfV1*#S<_WxLaS#wqlZZB1XxfEMN&;G@-7$DU-wc3P&)8U6Ow0uT z$7!K>^?gJiNB_+gt}#~;eqTS7$LlDRsXN!4om7BnB~chpJC{*5UbY_T3tV&kj)_io=gI zunBI)@GHUr1ph|-VVBFZ|29kwFzp2rfzdY+;=$dekPCnA%!e)`b58rI;(}{aUN@w%2+;DZ^ z15GPtA6R-IyOJql$0w`5z{U0y7Wo{Ldbq)I8R@A*05E`orokMnWDEaqY^Qw3R%#dd zlOjn4Nc4adCy92)j@9qq_ar%<7lD!4+86mNr*Us%Ep32C2R6d1_V(W4VNNj{xNnl- z)d8w$om;`*O4UP75ABBA3fu$HU^bk4e^XZg8hG69auI2NFqs2of#@}Y8c=iMUoY$b zJhrn@`GWh;MTdmwnwW4=n;IB23bEDL+YoYcY;2eH$oEm4xWEt@sjENG7vX&4on3BG z!W#kUg@fmZ;S*4LnBpi*ablKTw{BEkCKf-Nu%`fp`U0RMz*3k4z;e71j{!Z57koYN zfs@(W+jT&S`*}NJ0#@hG*x9}N+fLWSrKbxeXcQF|VuCP-$Q1}6pYLyV5OIjmq|Ys)_x<8+`XH}}%!AEFnm ztu3O@{${Kr9Bmv!acF0Th78x}aJsGBVL9@l`)(a7cj<#oh_} zU)7%U*li`yVt&i^st)lDUIsDFULA5gT^8uMWqoY1P zb$#YIpJT;9Nvo5El{6W#2wmkmI0jz>a)*{ zqoWSN60bu^f83IWni_}!bSl6ZmZql4(MIckI=_!**ytyJ-Mup*=y(@55|qISB_;Y?I%=f1AU; zcWlh})9WF?EBg9zvx+D{h-ozVVL{yvjci~=6NK##Y_hbZ#QD^5V3at8ASTB26-IoM zk>eLYtbnW>N^)9+^;9&W4gp_?H~}-1tZ>j|EvgTD<@{ase@aLUL3i!AvE=poHNvFD z+>F$!$udU<#>&4I`!{&|WU0DwSn>IMNXliszq|89_kCB7(kgFVvPUea9QZEqM_~A`BU<7P!M$!-*)?nkDFj-~$j0Ue`v!30ajg>7aWK%} zQ@!Kdan*{-_X&6yzs4{)$u_jDSQy|6`6@63ycs_rpEx=HCtANe(gqX5YP%u7E z%IFh9=W2>bbar2R7;a&wDyGu9|{93KH+**&z{4;$-gcy|0L#?`M$`J{;T``&qG|z(M#B_ zcOl%4Uwv#T>UJj+(^sbh6HOBlRFx_#-qKP>YQgzg0;GmU7lWV&NS8v%MRd=`<0`== z^D37%Q~NWHaANomdO0|lWa}*;=m*@r51&32;V|pdQbzYmPb&ZcWieVxJcET@P)$QM z3)UjeHWl78DBAFJgoU#Ulrl@IsuEMIjNowDYL^(TLJ<2KhWs$*mc<YBiuNs9h19 zmDCBd1qmssoC0LZ0rc@XArf3Vd2<`jss_Fy=9j`kNOf=A%4_&FkOQ3Qh=c^38?Fv< z+&}Iog>481K2*rN*pGfSym&Sf;{wFB07yXOT&|&@yIr(J0atZI#XmmwoiFyu%KBk# zfEU7Y;`ZLj|NSy@eUJ}~iDOUFn*gfzMOTw@3b-e9HK9>~C-a!@}Y`Ffy3!F3itsrXM{A9|(ZHZG~o3 zJkKNB=zqsbzh)L@9F5k=5|p9UO+T3!G-o}v=3k& z&ST72*rnV@vBT%yzaO}xkt!@M?hTkmBK>h$nKxE0fIK-)QN;P7AA~E>F#;w^Kply& zHzs`OMudbwTm1yp_upyFhc0k5(8uBjyB8g817k+>ns<@J!cY#g@$aZd&>(5L5e?qZ z)w=)=>cv3=LW^?fPQ3iyh~Q`(S`a%x9|P@0^Z@;_nW zvq=1E;o;_xw7_Nrbr`lX46DfrLVQ~=DEa;C*V@Msz!8W+#5*&vw!VMOhFBu5CT8id zy%cHB1F18vflp8wt~Ut@EPMAlySfSrH%)uRZ(dU`{y{=0Uj4VCbd|ES^zwGyw-mLX z^jlxn2sf!7cfi@FfhA%{Ivp+yyr82MKxa2FI1z!~2%b+kV*(Vp;i0+T~FoVaN^5hu|}9@rt-?ZO8zew zpxV{ly=&U*wPP-wQgJoHU(h4{#A4Ua(R8t*1&4@5{^}(sr<|Z592?-ZBg+Ku3G)jatiYiFSp4+| zn2Q885^V%5SF!zJELMZyBAlCJy8~{^%3u1b`1uK;1jIRbu%PNCny~s{Y=`HW)QJlH z`;Q;YQ~*lPg0>EGrjziw#3B6uKN4~5xw4m)brBE(+S(|hR>YkbohkClZ5qkH3ALYzw+)$!ctuZ!i z;OmOSs%*rL#1lo?2!Iy6w?D`pfPW{%02aVw;Ogwia+#Sq31~GjJO^ptiy-ORBj_~0 zvB;1AuN3+d>T~Rx{(e0f5+$$?LA|*)h|u`{&a13JCXmtp8921BC zg~DVSy3@(Nt$FMfBM?v$E-u=?lq%US3i-)%=0ER>%8gnc6c{nbIr~yC42wm|uOldePBwe}iq) zpPYqV3uni?l*i_ka|jKyO-gX0gUEj~hlM`5o=T!BZPTd={DPc%U}Jy)Hu~@X)H+Mi zYdn5^6m8E5;7Rb1gSv;6iD`IA1B6$cr^HM&R7p<84D|G+*yXtK?jJn|U0wdzcZt6L zH3k6=N9<)lG>nhm4eW^!t-cSYA8AL=@xH45$HU{e@1lW{Iu1%4CPwDwGz1ie`}b!9 zm|TnD9GjOhlzqu5EiZ3%PX03jd7<;$_-MU#J2Dd2`S9Q%j(H@w%%Nrkcd-Ujc93_F zhT?P!>-59>_eA+29$@*Zu@KWmNOaMDL)64Z_%o-lm4fsV{Hsh}D`sIxbTA@8`p6M1 zB0JBvBX=EHj*r<1QO0sGw#GbEer1twZfXio)qYBf84W>gvB~(0Dvy)H!#knC1dy|! zwLzTm{QeDtGHl+*LVRa!ZO`cH!rs*i{zibzF+e|64d|y(Fx0L9W|F<|Zh5^4Kp}XRh}4<)E4+ z4rUb;{07Ui&m}d@vIBJh9Egq}=M>lN4?w;c54)a_h^Rcdza+8x z%Kuu}5u#sh%`Gf!CrD)T(qO|N6$mwn4Cb#>Q}S4%SWHVE(QpP!PD{g8eu&A2<+$nJ zMUzOOi>(h@L%vz3(vU1~sJv5?3d1EBKO-qNCkM`#fr~LvW&NLHo$>i5Vw;m|NT)SySB)jYv2B-HdW|N7W# z)+ZKpREm}jJf3=j+X$C7*-1%lS}4~4oHwc3;qLyrY>tX&$biBISmrAvcV}eS04;~A zmV;p+IyDuqJT)$E;90RSY^Z>1!6_Ij7FB5}SFq+$1`*AT)TC#8pUry1`hD)>$2#;w z*k|yCL^1emXs9x4Jfzn=H09GRQ{8m>yo!o=x@U3&I{G~QO((!0G%}(Pz4!jn%Hihl z;v$zs6#`sMaVHi_lrtO|r>CXPJQJk(Ss9li(uHw*Vpc%NsHRJfr;vET6Za>8U-n^L zZ-(-(wBfPZ_mBsjy$7fhq#fjqm>b%d4qU!;32|7NAqnUSu;gWlc{$KRLP!k#8){H< zlSg`XrRx~p;vmQ_kT4TLX@(=wdq04}{~6)*UQSO_Ux@U60T)$x*fEBwl$l;e7&A^} zv_$AKu;l==-b+obg?ix1Csq3|K%@a5IbQ|`fZ+Vnat+4H?h{WABY_yQGvcs@%|n^d z@1^*aG6N2EsA3~ejk`>lpW0$At*(CLzb%jT=l^Z$H2N*@FS8wD#r}F`gk+GDp0KjI zr^uZ_BavJBxz)e}FU*_g9DsLklJi|kY#VofGCg?HQzEyPbz6luCR{PWQb0rmD$?!c zC)W=0fx!T@h<~aNH}LD%sTA@kOK}svOZ#hl5j@3-yU%gkQXJ3FP{Z!;>de$MJfgc8 z7&0;l-(c$VFta{#r?Xq*?n!leII6`bG(Wa1Ie$R&F17X5KK{E(RHgcylY2QiKY#i1 zWp)-wgru9>#|xf}d?>?b+GB+MdE*duGf`8%pRuRG5GCi0<-@P+ZEQ-w(gZsM^!fsn zxG0l}ZWFS&J}VE^SOk5l*EKTY&+h4ypk+KKkoHj5a|oyBtf6kAz?sq=cW>4B-rNf? zh33!KmR-Qd-HIORPGQE0(*#)u{kq?s&{@ghV!L!{9fdt8*Rc9{Ngh}E0Q;3-)2|FS z;NPf=K!R4-T<3eW8{qO!__M-t7{I@p5Yyk<$!bBtC|mX=M^evRxXJ@uW0aJX1HwSV ziAgy~MT1!~XdNK8)FO4&9DU^+DtCOZWZRCHFG&e#EmhNi>OTSdAI$-Nwk4EF5mlLC z$Nye$`8$Dm?vv#gZl3l^eoJxkmEWQ8+qVf#ot*_GCDD#EAiU7AvlC-ZpqMzH{ap5Qa&dQLot4ux-b8vsE3_XFWs$RkD}=My+)=i(A(eY9Q` z^Xh-;E2(-<^7C)s<3aD=g+bLR)Px9LIVCL~f*Kk~G-f9F!Vb&`98S)ks8rW|7zXjYcrH%$kW9VE_PZz)s7j8|Z04fU2CP9sRPvnS$BJ|P&X*t}YMVW0IY zbQJ4XuLJ!q7`#bGQ)1_p6wL6{Rg=fj-Cc7l{EUUoy=#wXG;b(7oxn}RPix17N3n3RvWqlsJ=)a9 zo6D|{2ME($Ab4|VF#kn;jPgnzK72kg@du{|A~)OrQ@PW=P+kGi2YiU))wm2G4467tQy^E|{+@f~5HMlKH^>4W!HNfc?-yl1bb#;> zLCbT1Dcn@m%Gz2%R(5=J^a;peU0qlM;OLwjYN}eAAs&TR_5cgug@{=Yn4tKK56pEz zqekCY5rFz0@Mus_5Kx7`0+PG<1%!`4OYuB5ILUajfxh6n!z>7W89q=?Lqr1j4kNXD zaPUIhXE?qf-UeKnWWkt$R{5N__XC=;pH*+%LwDlL1FtD01fC!SuLXu3TvN?O8d}?o zjc?rv4x*gyQ6M46uM-9bGis5$XtQwzM@d7PgfrcxD>w3wHH=zcGnBo6m?d}w)yjbM zVrHgDWnirADk$ei(Q_}b;o2eg*%w?qVs!oeP0z`z+yhgNu#qlY_>4qI#nUuZ9zmw% z22$dJ)SeRo%p`N)SUKWm9H?kRO2po-WM00=udhG7WJ*PKDa6vCGQaP0MLAQ|qZ|tS z^?B!8QIv){e|)=po(hGLKmEh-=TFmcRaP1?WQ#y>>I#TEaAHX7>`uzTq0GlSckEEy zhjeq>9!|`K-|+LUsvh-Y+Wam`M8Y-d4scBpgQ{R~kKnSNk&)^Iw)NXY5-lVv=zns$ zjt=hz!1UVG#^x<<;bO}=V#s`?CrvDxH{&yBnhVA01D8Y(Gcq>zpY957|7v%`p1>W9 z^IDL}=7ND?#^vND`Adhli(5LqqXO=btiCOKTXKX?zr)xznX_d}q>S?ILcJaFj?BaY zel7m~eH3v1Xe{v>tL^UiVT)1j*xP&i)H}#biOB)%>|Jv!m^Ki}{DMQc8NmjFTdi%& z&BJV%;XQF3%10JEl(A^qi6{F3@@FkAWMpI*a1w_c=vIh1Paj8mFi!*2^S4dM0sjNY za_URJ`+^EY(P^H*{ z7wOag&r6&r@X|$IM69mB1VnT|XfPDde*D-IHzR_IKlCK1!i5DUMXF2z%jMQSefBs&ay4YwG93-f|4uzM zX94};Uq%*yud)8~Cx`si(Km0n2t-XJ#$fPUZkMvh|Np;cm9Yi?K)Z&1G0sm7Qvp;| z&VP6Z+R9;-1q44oZ zWtqG*OMUeRhl)zmp;vOni`U#MWVQBPv}-Stvg{n!x1_DA(zPh8zp4FuEJW2LwRst>_({j zBA}i}lqxE77WMh825;=E(SJ-2nPQ@ymoj>z?~lJvH#;rNr@O78L*b1i^Xyz z^3l+SgJE?=Nr_Zzdz*^1;OEf-V^Krl7)WqG8tCiOY~OxHU%#NJ=o&`uSop+MU{wm- zXB@`>sy6^sSTi_-HAkcMG&&0wQN{lkDg9lE+W^vb{O|vSDgpdP-ns?2^6W1~uqyw* z+;|H^t~7ZgEG+c&`_Y%d<7Ou!U|oj1K27()?1`)JK zJbKP}Tr#|U#;5Gem9O41O*(w824f786g_4k&RW0Q8uh665Q+gTxldOX1y!iNt|`q#l*#} z;HJQx{`|R0ZFFKH1p& z66xDV{hzj^CdH7*%R{Z`;fJtgeQ8g{YR}%=%+2La&ASwue!OY<^OKfsWu;*lN1N zLdQ&5SRI2cUkU#^J-vVy5?Wfi@Dt{22ml`xSbs|f5xB!6`u^dzdDY<5;yn-8K<$tK zB?xXOJ~+j`v#kqK@u0`SI4~8o5KKK0frVl;iv8HLX)i>XVQkE{XOAR=SU|Pl1B&7r zwFO!o6eC1pIW)DMou~IP5MgYLm+^Hc%KwSNYI66ooUI*xr^U1<0K;`#UCQr zU>vi3`*z4dz)!d;Zw>3t;NY(GV=L%Dh*OHAUN#mM>HVAethsQ-#*HJR3!kCMNz1>h z9NodfWZe&pe^TOzqe~x2Sy^+#a#Jf(LhA|8%dh@fFYT{>%JPqmTg{d4`Hvp`1ELAk zVs;ipl8CQw<%DX@?tplARt3{8_U1AaJg9OfRI@v_9OgJY^}QEF>bLm^edHXjY&_}6lK!Q600Rrf?W-) ztfq(?{7vJ1T)^lmVq^78O}7)6n3yE~g!jxrky{H1Cg@}7d**%P!BD_}J2v(kHV2Ux zGBZ6=TAk^Z!-_x+`iq^wS$88Mw+y2&gHQ&Xh7BXy-L@tS=imO85=i!_oAY4wPe({ z9tEP0_-EQ5U!>jtEFQvHJXF9oR-N^LZF}JL4V!1=qfbhIzA(JXWj@MLLv4QjUWJQ~ z{oJ3W0`YUaqoazKE@2W5MaGrHL|rp#TpUTvSHF_%*qb39B(5sWJIGK(H~9oB5$Pys z+=kCi9;yW@3m9!1X&~?gG#;2oq{PO)TUy#dU{NAwF`$Anni#k+%%cL!Wp%E}&W`+q^O<|Zb)ckf=BtQ+a+ z`GV>jJIkV`@Q0|r5Xek#4t@F#C>0|ZfoeY=pH&P8oM}>|2Z1F6%%SL!Jex84dvvvw zG=$BmtU&0M(RVQOXxi~o5x* zHH#6UJbjFsp8)N_`djz{WSSVo;e$iM*Ec)H>Z*LB@5&9n!8|0ofD{Ud7$4AW5S@Wg z73$^1zj*&0y%T^Ua0iGfb0dIPyV?8v7I$mj+d%+#{mnJX#6()r*4E}c{jZ&(IQC8_ zJMWJVManeWvh-012$K zz>}Kh20t-RcJ~P?BO^LSvbk=QS+ElA>$CBorKf-U*~))@s9<_QfBpN&FTaSiV zwYzWJVC83q@d1o&mhIKm3HJ7*4QyA|+#hbt&LY#x)m7J=W*3)I&po=`EXlC_jVdTMvGEty{oNF%vW&f%`Ux#)5T>5*Vo+nIFk6r z&nW>ALdU>$-T6|QlJfMh@LTWcULKoo$LO97%Vx{}qUydMs<0VwCW}CLsORMy;x-b{ zaq59j@bt;A>57DK=9cW!-zOJFbUKm^jGld-jE*Ih=EIw^@zayhTOt>%VFF zwS&{7ZF{*1&WmByHYDS}+xt0AYV`QmQ1AI@T+7_~wxmLBNYT)+`PX;u-8VwEsqe#; zADxgbR~s{1UYvh@jnQN|2o#1t1`-lPifb3k(eo6KtwR?Ec#fk8f7`*hUsCt?kCrmW z=-7VO^JM@nT<^J!Wcd4Eiurzv_U|rz74AvS`yK^7Kr&Rz53_{LDx8URI|hGj1duBd z5}_RiJA{}x1t_?-Wo~7*R@I8Uzw}GH(&O&wmQb<)T>*zGa5@PAp`nyKGicK#Tp<#< z4j4Sb=&^~FVKH!49QkAMOfQS1?6JGrl}gPLt0doN=j>7ng_N8u0I0pMk20Da94V^U zns2?10w(jUQ-;GC0-EbSEglH&{h5kd3$#IyY=r2jUaxv_Jjl&$@9DwB{FIv7Kkd;x zC{ZwHwE5?W__cD_E@FD|>s1q44$N!D`hr*jKBG4%)d>gTzdA|MGECa!NLxv~V=Zkjj1ypyX$$Qxt zKU{boyI(~uG(Le|N!@TyX~jNKPluRVnRg4PsCatrGm?>!Dk>?dJMsUVrX*FQ*jXsb zpTHn1`)xpnR+yX{N@|hF^y8m|@aApm zcT1X5o`r8ta&vcgKko>O2YumI`H|`6Me9`Yklv4-|MXB1Y&|nNL^>N@>K*fYv4=$9 zXGdp&|M#@Bw`ye$3i1X=7nyG-Y^QR5NRn?+uTE&sJ@dWb%o&H*6-m?rkzSXN@dSVU zNgm)nswgh5uDOGRJBacS3u9^W4lZq{SG;-$d4k#HH3{kl@v+SYzTC$Ka_D!4-fE>a zPxXEm(>A4+___Uz?`Ef=Ky|*4XkxRiOH_YgegPjDWo(ap!JEz1gMGc+LO;k7uCJLc z{-Y4MN8xC`_Q}A2i6 z-7QgVJyX^fk$=H~$Jm`Xruq7HTG{C|kpg&!O*-;1Zsz!$(7wUJJGX8*S6r|8mVX6p zIOu~1n7<3aHqu<6?sa{jYeiIkg|Cl2nDi~5CTa$HdrR(E`TXUVWnS35XHRx!COrc~ ze~#KQ@BuJp%>SpUoOBkP+GuBoS&!Q9n3?~)cWED7m6~dV~O+*eSL71K(IuN&@={Y zz_ny*18J#g;FPLjd6y8q{C;~}PxDv`f$oEyXAdW-VvhFy;AqP_b%%XC!Rpx$-HadP znOcA7<0Dmk*7DJ~p&=}gBy-CQ%MoE#Ff;z9*PD>Nzi;@l_0y{|8aZ z+_`IOpSRz7_^5Gk-Ml(Jn4qdwUb)pNx}DJR$|HAX{tT(&a3TJk=g*TWu6^FGckuFh z2~Tb0enIUEG=8%}9LD?ncIU;<%*JFYvprzL_f2KZjH*9=70WW?M1-_r!u1U*Ld`{( zQME)NbX8V=yh|FKhWzFr?B~^@#WsOueMLK?@LF=!*4I=Ro9fg?X_Z@y;VsP5Ix~OjBiGWP52*tHQ7IShU>v%!aa-kO2ox zrNznvHf-6Z=4M+^Qo$mJWg?s21Ddub}u9oa&1`m{+Ysf6Um>N~94 z^bYop>-)6T((|#N4G=6aCL=73k}NDlr@ zO38A_SyJ8g9F7-^aYx21DmS0Ky!Q@Wl5cu@xLzq{Qrl+I&~FM5B%&m`q(+ zTY}M8((iZ8>6o@-!~C`@O{RPB=n(?Hm8c+;0hrroqqpO5OsWQ1#0S|F?>yit(=$e&`)eBDns1|i|wWn-m^XMs^0|bXv z=PGfb(Wnr!2YbAwNdsbH`k=~D;q3!^2%N~*0uN(D)c5@Y84^t0Hg_z6)5y?3XZHoi z;E=I37-d&sur9&;7B=LL7_4H!0n$WfN)pHz=zZUysZ>>^AQW2Ee1n>Y5Pk37Q_o2m z0+@rNus?=Yn!|uL0#=9ebmSI1H5TXbRxDIREL>HFO0a?gc7(VS9-rv2k*0o9|^{(6h37ihBnG zF#;7ebv{7-cZy*u4~n1uq9%aMf8ooNrLpmg{uen>dk9d7UxT44KrS=P#?g0Uk_*n1 zp_y6j**Efrucj*9lJb+Ncy0%Q)Bbq1m*X912#_8emXthx@pC$KVw6?nC=Qh7J%~ml zpl3zEoJd?ewp(m;7&>@Zm1sE(xK$k98Tx*D`W(I$z5%Fmpwj^TH8D2_oGU9Rn4c5Y zaroa>!v{Ad@Fxy2n*j6`aA6N^8N1|50KJ;(%NStu zySjqk_$P@DuacRX2iZLva7w=<^o38>aIVoJ#Jd33#JjicdXlL=l1Ql<7Z)#T2gi+;n4JOQKV;Y+UF7L>0iDe9$u3B znFKT1j<{Lr&6Qm~A1O#kzRuI9E4;b1A))WRl9O<4$Ubu|L*fH8GFMmo)PM`)=0`c} zY&)@E>1-4bC2S_|qva|V(k%+0M#dnh?7VudGe-s&Pb(jklYppyoGN2=f|FhHf^SP5J=?UKRx*LL8kJ}vnD0l}y zsbiEmpAbVo?bXiZAN~GCSjaXK?rKkZr?p~XbE?pR=<se~0r&AG9q@&msw14zUH#rs z{*P$HzH12$-i92;@kwd~^&}BdkHW|Nhm4|i6j11ErKyiRp4r-rN>|YFoZyb)8u=05 zKq92VYv-i;p*!JCxA-$DDe?fZAD0V@wi7asgmy%pGGoPIOK^Bj#lWO`<3{^~li$zg zs;dyF?ixnUDtdqDIl#X2Ouh8@eAtUk`7$3hoW$0Tm1+#L{WiWQy=*=+#A!(8yCskF zJSS)7&t+bQm~iH>Odb;Mg@tdQ{@Ge8ucsF}Q1XuQ(ZT!M#-4snUiX~Z#%L`z%yb5}xjqjaHc z5zH`&vWD5^OHg$~Rxm&R;jh0`gKzToyzwIyF^j`RkXyF#E{EM~GF_(N#k=f;USwhDW)5VSu){f4+%BR^66|o~pgd zgEmv$))wv7j=hTS-nCCPfL8S9qcyGmhdoTO35VDgk6le}mtRsnn?)KeY_4v~GFJZR zy6>3ygU8w;)}8{FKQg6A7jF*rC>%f;-MB$)&I*e<0?DvCV@}jJY>!eaENp)kf&}d4 zHDiNlNw@Y;uGj!VnG@|;MVMIiIzj!-Q-^UWaeE3Dg?kSlZ4qt3h6jJHk^JeLists~ zj9!?csjQ5wt*rWtSik(rVZ#F7JtIAq#%>?o6RONSLe_jMcB-7SEkXd!7*8;{y84s? z=bae(8@#p?_rt?K&dl8TogPf+_%RVx2nKH}^B%{giG%M~9IdbNlvgI)J$@*zBfq9P zCt}3s?IB~M&6#hDhGWTx#T9chc~;gEX*q@1q%?;gMRh$_p=f{lo0!uiVx4Ge-l)Ep zAbz^@c5FQRUGI-0o%szyrHd?y8jkR@YQ4@Znz)_3%wt^8^ZI5@VMfNcW0(J!NL?zq z)0r?f-pM4ISbG0;F!|VnlY7EHO$i?o$X(7XocZO;!d>T+_wDMej@`?Yn+RdzBu_LeYUaIzB1Y6lugCjq`xUunAqOiEX|JVzz&dtrb)Me#_ttI2S zYqL6U^A(PkvEIAg+FC}-COCZeh}zm$+g9y@Nz(IQGc-@1UTd?Wf{Rw};>Hi_U*kd7 z78YL;Qi6iqTZvN5*4TK@LT1Z4{MPNQ&oeXaPCbv4H@}@``T8!Yki9N{pOEI-3$C)U zaz{9avK(n{?jr1mkauiO0cDYS~=aFPEIwn4FS)>)d-f&c{#7SamN*{aR~{U@NIIx_EGgw(dM7gyK`jbw_q9 zvEEbQVS8+>fpb#8`g^Cu-4 z#bDV(lO4>=4i5Da`f8M6VI|f6ht=*`$X(f8?u3Fb{dl;>hJdS`!b3}zui z1q8DA_^-DHbd=;bP(^JbOAFj0L=ZX4z26B&N)fclsD8hfNz&3rw54nNaZF83K}VPG zuYN{YM&YGo*owZ9Q5A@-_%?9enFYCGn3iF|+gk}kAX16G>b0~h8ya`^LMcy9Zu8lq z!gU*AdU~{WkK4$z7iyEOlJN(0N?aJ9ZgEC%m+DN#cWHLr4JV^iY;mtIyK&=n(m|nM z1G7$XQW96^_&+xU$MQ6;z0Kbr11Fh8$A@~mnTE@D5IBq1_8JwP6Ct#=3LGkMOo?T< zrBW%RZ*=qBJF~=tqLlZoJH>Mw)vCh!M?wQn2zSoU58f*n=)WPj#d)r#QqT_p2^^%JkCGN=_NVx7ay%@|VX)qdzM;5j}@EIBvC;R6Ji@ z7%dOIB0U_$ctGr$3|t|Ztq03y^7Pxg+upT`zDki}Ib>whnaF%(Ph9vBr?>0p+$U}g z6_&B3KTCC+zN~Ob`AA1f> z2Iwrw$$S5e7SYB)WMstnKc``ZE{1qedNn{+1t6E$^H13!A|M>Ib(mU6gx$PF9C?Du z1?0^K+(|eOBB~zDl1pIKfCbQ3JfIN&7qMH!Xa}S+aO8g>Q3)WL_2g_lIH*%#&tN8f z#86&G|3sYnqlVPPxG6tL;ZJ|$V5QfUd>AMmCNfvEl5F-c+Yj)&za}S?J56Ur^=7?D z8#mu@Tl_vEsKE7cnCIwT7MA(J?Q3fw`V2f8xtHSX#K3s&gJ$d3iC~uplh5)kRRvpT zJ0WC$cYecZLZ~QkS5cVW{#V1Ji7vtWCHq>W4+qM$@$wEOi*I|RW2`Oh>Xuc{PC>C( zmI(^5Oy$fX+T+KsZXM5NvraO&?Kv5pcr$dDt=sQ@%k1p+pZ{p48I_vMbw9bvayu(G zF`>DS-qBHA>srjJp{59R$ow$vnKSF}ckN(XvujQ5k9hy$eUdeITwX19Evv|6JI+cr zX-^!Kiy&J7eMEg2gv4pNOJ4y5x_DXjyCby0il{(r4aaDkIG3)j_QxcZUpt*Bp!7{5 zrV7yYKfnvqN*3dhl3K$T!Y0qAzCPV5Upok&DhG6C3 zt)14^mI6+Wkh=fyN5QVLw6yeP#?UgD?i;bER*hiw#rJNzKwqZG56U9Z5(daUSf;XH z>fg`LUjq1p3juPeS0MY~Zva9(JCGA$Ac(UhPlXrJc0OKSNMXk%wu=H3i`~?CpA)DP zaE5`F0LAk`;;LGQQ|0V_$mZwZx$|Rnm0S#e2a*+tc2bg)mr%B0AEB&(y41YN{U<6# zdH835oj^l=19hZMs)P%8Q$&ObA}zicb+B0z8pj*KUBEwL6AV$nMkF}Oh@=x(M4UQB zE7VYp=Yp#aN}e5TQibTb;F(}o08qD-%-EZM+51Xy4oBb5%d;y3U%|r%L&&Ib6ds;0 z+#_{w%}w{S=85mkHQ5oEk?6R1PE1#xYj(C$DC?z7M*j0>i*91NDLdq>ggX^0n-vXN zXez_{hl;LAco|ZV4fO`}>-vQJV%;&=OLyhUfBw#$kYCh6fy2)SD|oFR1jo?3UVEXG zP^xQq*#Un$0Ryyq!4Kl|~sxZtWitrEtA;_~**{FE_bM1TwNh^U%$W+VC zP_Rh5`5w`%T2KK^fL}a#o74CWNMMOTBP{M< zaOP)^rr{69M%ZLd$5-4vJpLcHzB?Yv|9$&bLP|wel$~U?tn6fEBzt8P$xL=unuL%| zCCMlwn~KnqD9IjWL^88C={c_Y{C>|L&vU(A-}~cRx!tbo{XXC4d7Q^_oclBqIHGHj zGvQIgeUEg>+q)W(Y-k7_{$(+SW;@ZRM$v$b3}~)UY}y2_oFj;l$Z!$8p~?nQgb;`Z z>T?7^Y%Z|k@S&k1>6iia?mp7&nZb{^7g^R8XA3&IyNT1i3LUvCz(wsL*vAalQ#u>f zCozZ(%4dQb2Jea`Z#DJHeQKZ6`p>F)Dh>^`evT;f!_Xhh^ZoppEptMFU!?KEnR<^z zik>9?*T?=I1F&?2UqV7#)3rbf9y$q$zHYBWei9TkJ}yb5bk@z@d-CEgwB+`3!E6tG z0u*Y@B=r5j@v#XmK;DnAj`?py5)BH{Kkkn|s)aGH$s145RKYPo481HvPKkUHsS4UE zXgc7&N?u-D0xJ{W*?d3!HL6Xl*wks%-E*T}Rhv5w~@E?lTYZ&Y@9v?{;-4x17U- z0{l>05Z6hFXB&ysXaX6{-9uIs_twXY8lZ87p~M}Gwl*>0zbwnVZ%e^`WmbVqyXw2& z%Duo8$?IAVC#F-QW~AM{TN>{rMm}ZgT(OBmM1=mzSsYF<*~&ThkPZ)-u$BR_osNzU z5*0|Da85mZNufO8Ju9rPj$Cp$YYX4eXnr0GR(5!(y z^l!F)=jTI}?f0b&8w#iyO8dLZUd{yo$7Fz2j4fgA*5j}Tn(DDWuX4b2+2 zV?l+XRucCc@c$n!00lYu9PTC>u3dBQDgHexkf%%Snlt`O-cgG{(?6Q~gavcsSn!J? zm%MwdOgj>X3LJ@%+mlT#uMrRCr8m@OF=lV!#`1G$s2zn0o)!MQ8(QG*dE#VBQv%Bw zQ~3^8vkktqDYt&CQBxPF z?0tTfRXqO^6pf&^U0O6Nwr`y}N7tkvdMZxc(C`@!CoDZn@l6|EBNi^AQ$vJALBVmj z4=_>R#Cn0^20#PW0gM&rAb*;hb5zQsOq;+05=M23V-*n+%)4vXHlPJK(bUoc#`Mfy zoWNsq6P(0jp|ZO~yf>zTL7WOuq7*lP(1{xArQ*;A85nNqaWtFT*FZn~>mc#!DhcvU za7_cCX~#V!W@kDw%c4@a&`{#s+e4I$dv_8K#d`(hF~}}Fkmf13Hr)%0`3+KO{yl8^ zDz~ANFk67T{HLx-INYfyD-%PeVSIA7;1WnxB>LXm9DOrG{7xwD5#osvWA}E#MF}>Y zFh7WmkC*eF;eoZt+qcJE7@*le%CS#E!stPdx~Ar)SL;-IpP}hM6CT1X2&JIi$|<2> zh%l*5)SI?+=sKK~Ecxrn8G?t1cz}PS?e+I&aHeJUPrn*UeM04Tx!Um9>rlG|eIug+ z=2bdsIKnyJ%Xykwa7dABX;rs4@(xA%YsrpGL#!dR(GcZfXp1civN~RGC~#gecxqA` z9S(~ycr)P=u|61yK!h2=xO`UT>_7xXL_!0UtKqP{EuU|ogS~w?tM~-$L+qZM{TJZ6 z-__I*u?%@TW@QirYnZf_31r>WQ`LN% zDSBP#*%^Zwgv<)MHw;EjZm5ENC$wGXll|k8lKh80?*SVe`-^w)-p%A2mi4(H!$nGu z(N2dB(aLKI)T!*vO~dSA*gbM`o`Jm|Tq`|6OvTE9?G0{JAzEs<3wb6bb*T1{JEGA7 z^D;<&dFX&5h1CoY{}lETuTbO=s}2fS{lLl-YHF@tUSRzF#@#Y@paH8N0yaO{WSTig zG}sdpYqwcogla-UM`vgHf$L(-?*p%?YHIVY0e z-_J68OR&nw$+3W6m?S_qqG|ewso%!b28i;Voi8-+iQ$j2xnbNxP)5Msd2T;oxe3AwXbA@~F`8wR zgGitiZe@WIQ;9t|S-JWdLMrS@l!!WBN?FuYR3JF3z*M*YqO;H`{EQ_xSXx+LAAC_( z=7|gjB|H)eTv(eqC0mJi`yj9*v>H$2PZb6jBh9Es!>W4_b_`GmZK9-H9BbE-oyF-2 zAPuKwZc55`9IDW_INRG(qxHEFkrE*Y$KE7PV?adhC^;}30#9&b0)jGl42bhEjem}m z3U9ChMd~8GG?ZnQ@bl z+=T6sGT_(&LHIPFEd;Ko@JT8tn1)fQd#u-C?I}QrPmPO|3(~Sg5m)U2M}ok%F(1`3 z0SV&M5)&z=0C^EvB@AHj^ClOXItdu1pSt>2&p7HSD)HhB^|!^aCGC^>P@Ft52D z1y6?-^}q0WQjv?E{^b(?{>*bH&DrYe_?;Ck*eNK!v{S~fHW{`i&KzxPd*Y$^#D6v4 z`ov&lW=Tm(%GF5j>FJs~i}vl!sqWmIdAY{vtl9b?j^ILaf~Srq@ziM@9Xi(Q$8iI3 zP+}{OdO??>>_Ntr3D&sCfddDQ9MN50Dhvh-1=0V_5Sg!V{MgE2c-Db9f_$a=DFZ#d zBa&kvrzHD2342@Htt=w8D3l=5z-9v^=e)xFFU~w&@>?fVdB3{O+1M?LZWNILb$0bLrrDNYBu?JL?dGU@^!W3Y#~U}sOG6KrCwDPZf)-oI7i0Eb0!|K+>N^20h|?96#7GuIeK8H;g=5C zL%wt8&YCb*CN?(n2r2umNI7kQLZNy12fkXpK)w+o!k7;!bTj;ehy?`$jda-xx;oAp zFg~ccXnyK8Pgav@M3yPLGw4ajA*Z%}APDDAV2? ztQZABaa>?Zk@b19V@ctx>y$A>6%KVHB-j5Qc_N{f$FTeeMQDV2)>q-<()ki%- zIz{DB01$J}2N)O`3n#(Qiv2lt3H6t>XX&5-)_uP1eyOkMonn8XQIF+`G!_^BWS;d1 zg3tsG7o>4dA$rhX5(Q~c07IdQi!Vu=W0q_G`E1xQVR|w?7SfIN&MX+AqGYifmnI6L zJ3jkj)j;zo$74c;4~@me>JSFl6L%|Bl;MP)8*86LEW|Oa=Ov`6eBr_bA}oB-;E%W) zMI9|IoODR9;2c3?Rlg#I5YNBMBa+xVLSJCJ+m>s#u*ywJg1?RT)7fLcVz0p=D&k01 zw#rYSG>n2qkOA^;mq3!Ufbf;=d8Q6-i+G442|zym09)asAzYc1dp?EK9f=ktkv^4_ z{03{P#Y}al!KqU_XlbYWUT<6wCtyzU4P+!l-KbA8YlE3$9-@Ipvg~gf|HH&*-_hjW%A%7avhTq5bLV2kVF|8- z$B1L+OOs9wS+=RmA-K$im}-|r-f2HJ@?Jdm;Y0aD^B;z0mAE3Mx1bm|LS#IBT5$WO zx_v*UUmK?S^kQb7f#^+RR$WV)e8wFZ=QB1uOz4ls#t_;d%wuL|&fg3ixB4aT78m{u z=6mlR2LpaZy+P#aNVqXD9#-05E#~%@!6!)YCtrgUZq9~-qN1@8*1zD94B2#lzrykR zM5%D&Nk583WDjLHe^K02Vc;&xITRtzz-ne+Q?dj1e}~C^-6bMB4<`!3eS^rTg@xf0 zD=a*Ln}r`q7fgNy)Ule6aD|1gu*FQ2IG}r;W48qWvV>?bw9p)k z8z{e8^td_6@p*8-WA4s#*TE1F_K`fD|CBI|CYA0a>F*Np4cVpG>MLNN|M(79{1$cf zFC|BvH~d9BVlFstFmh82R@8w>_rvGUpXcOgu$>Uxzn?Z(G1g!|js{`j+_L?+slTdz zgXn>tW~>eW$gW+qDMxH>2S0xNo;~2zn@6(S3L7zw@((I1!n|R}j(m7@8}@7)+snOO z3h+6+%t>G!V?sMo>miEa71!KcOLKE}75Co?({2WQx(ZO-u)KZIZ$Vab;c~JFT=IOq zy(@k%d=1*RN5@O39@eCBDr|#z@?xdaTvr=LFSK~n5ohgcXVXdD$2V{K)XI$>fG2Pg+`>K&lM=nWo&)t@zt zX2g+=i#WSCF$(=SdjM~lHUjryqP$3XtK4#?c_tCkwucWnP$^4Fnk>Trwir zizj)qj9oa`ocVh6@ha_!1CVX6q#!eG&e&;9Q-iZ?)0Le&K$rv^r2E(UJg!BkT zs{R-smv(5&fpNi;a>fmC07mr$geM2E#|U!b@#M2GG*R}L^hIqer4Ar2& z9z5;~m=dWjJ-oGZi)ovO;9uK89{&-y2fFG@nycUpGlW+EH_e`PBbqv5e0;!@f@hgzdp1PQu0ASGIVhPKes(xuU_ z-L^<$GSbrce(vd1^zkWEshsW_cJZua9V5~4_XJ@=RIcdHo8f-#$PVr$p z7|yZS4WTnOA+eHz0BLas{h^Qw8w9o=vG!Py5C6Uc6FPE9dCJ|cxo}dlqUxt72xgWFJm+3c1s27 zJ|u4grO zMe_@Ns+|^w$pQi#zb^1E(kYk-R&Ra8U%{ZRcIwordQUyaRK8@pGh}An6mlj_BLAIw z$}?p=bf4}8S=C&e;;?Bj@Ddd|0U>(-r8XpB$bEG(=^KKIVFeT`?vutCL4*-I1q4U< zf1m>G|NgxI*&WKy;wM$s@Bjlq2>~PackYCVYBy4%xjFYZFYCw}Y?#00n7g;^aU?qk z^f*-Dj)@g!O{69h0|QF7505*e#$^PQ zkWwtF`UY|~49=`k%V%xBe(%nmi)glE${=C( z1)o`il z`*Z`V#~hzcy@DkNymv^SlL6*;Jln3D@ua+P2#F{AoXB_tL-fxii6yw!=bDa_=Fhh|4JqcPiwvPOil_>shbt=2dMq9O)jT&NqTAxd) z3t&BvPNzTe)b@h;vv*rLJ(Nb270fBqSx?B^sm;GEBj)(Z(Be$Dq=#YiHE1$XpyEu% zD$WTR{ml&>I*t9L`q<9JP0l5oFJwSu)jAc~&|p2*m6b3Nf{ZX)Cw6OJ5^;JhQx zz@a;ud$VPG%Bh6^Eme@{q5MGIoPoL$QQg`at02F6D-F%BU%yZpG7LnZ)#ITz@hmK>dg%Dc9`y8BPsNfuCzLTj=QW zUDHiI`kdrF-dlMq1mx~d^%iAgD;~QgZ!|w{)ib_6wV>?o9u|C@hUSttC;w=AqR#%} z;#20~W#;5reij-!bkKc-v3h)UZPnrC>Kh6wuyR>&OcK|(*h{Oxf{Ci>Vj&?%++4Fp z4huAJ@b4OX(WJ4B(tV!X&aub6Oq=iBQ`7vCn_)C2B|f^ooQh^R{zmH;d#!q;HIl=R z2g$!x5n+Q32=-V(13GGeOfmA3EWfZYYTur(#dZTo{YFRCoP~%gRZ$3iK-ATK7$WEE zyNbF=Gg-D`Z^SUl3T*R3HlGp@@3P7nn|2_zLWeCoOwI;rb$onLHDaIfr$#&hbnlQi z;1zoscqP8Z7Z^=fb{w+WEf|cW#HD@aOo}`Q28S#Cy%bXNu>|2e*KK<06bD@}x<;sR zB5I<=b#o;9kC2c{iQu^1 zO(0W1i^=^)iRk#arPW4L(~hn;bs;m-X(K7_+?iTK4OUG&TUoI1Qf8Kf(o*nX_U+wU zkd`Vvj{=1n)0DoVp$}Usc#}Nvaep!XIoUsWf5cs zxMH66#jAIy4GGLuWSi_Y!F06$GX-==MhX4m6drh#1@ybGPnUhkc(Zq zOmiLO>DWhXa?R@tbn_^I;lrSM$rw=c>Q18ShU+PwE~d@n71$UiQ_6*X>N(+0S+y%rOP%MNT=;AUC~qi1C2(sU40^ zF5^a`1N2%CZtFgt>LZi%(D9^iW#p#s|8|s|lKbc`DNoCFzaK*bkCQF!f*AxZ&hiQh z;%yIjn&@DpBrR*GO2n)0mhHkzOB_7pLk$CK-ZuizHu3QA_BV3>_@P%M#gM%+u>D+( zFx{DXdn)q$LIv-mm)B@BGxHu?&|9bC?=&olr6jkUx4$R>DJA80gMjyIYkK_i$pKRf zUyTaMr97`RsK}E9jI#a?ut67_=O9u~Pm?G6S<+EJ5 z7I~+m^j4ZGLK5Wj>*&FZcNS zWAsxCy^T%ZMgELI3;m(|>f!CCO;IQ`U-i{z*h0IsY^Ma0maV;l`j(80hY@F0b+t`G zu5C~gk6PKu7)ZEDAK*! z$tnZ+G@6+1BRXzwv&is3Uw!$)A8Mhuy}bd*S3S&7I8VS0UtLS<&(C|#B))Z<|4U&m zEX-;!v1kxrx3g-K(DKl27fj~A@sble0e(MgsDyEt5%clDXwk{lKFJk{`66&iScMy$ zzL!v10X$t1hJohb6&bYP42*-bC5kk@`*`C!@rlq8OKg9Lm^*G>cZ^O!wd9iY0}O#c z(i^P!7rd#;$+;cYCrD3i?5NF0&!552c>_)lq3G$_Kl?Q3YJ9K}l?9L`Y@c~uYfhyj zM~(niK`t&F|B=^7wGlfD@gH5zo@~1iFm;GpYv)deDwqM| zFmQZ%RtmSZy>3hv&1NH}hkvT0!wl;^2|DnYy;!EV8l}U0&}?w*0)Chv%V{%G_i`wxNI+ z)Iv~vJ$OJmcpIT ztky`d4{6>>S1XXg8Y_3LyIkO_q2~4r=`sc~RxU0F4`o)ih&kZaNA8NI<7aCm6T<3<`Jf@Vb;IrUZ8jr^T9|=b0opt3~>K~M@R9iEx%d! zA>ey?E#d&D=x9gYFC#6Dkr-2TrnV@hb#$WoorzJ2Hv$8}#VnAe&JoWGNDDhPaI_VR zr#?g1vB)oLht4GIJ6Lw?K!lTn8B-2=PBTAh=L{9~39?-NnYYlccfoMcqg~-HknDI2 zAVI)G&mZ zb@}GO__AgIwP@j!N7!Y2e3speHxB+Z&nApnqFP?8i~g zFaSd*H8o?0_UNMgfo;&=Yp{Wk4oOK##rc412aBI#!04r=HbVF3fj;?Cr4;~u$l0@m zW)b?4__o3Q?{DAU>KQ9VLV5zs5T!NRA;9vz?=)6d-+Z8_X=2U>!DjE}&>7dQ?BTEE znRk(0dA#qemGPh=Yn!v5cY{}^pz$g6+k-HgOVTkhdcry9wQk(xJhD?vtZpr z-x(exyfcGfo*Ni^sD1rF#_0Ku$jFPXS+`E|$7#>=d>G>EeIC*vufVc>IpK3j_>y3< zu@TkHXBYYT!Y6aApP#QjI%6oOpsMRN#^|$XPredc74E4FvZZV?cDnk^$en(;K(q#Ln!Tm z^o@>UOlx)qw{0VfAUDBiZ2zXvs`Z+1_(!GN{>`z%_cyoG4VKzW5Ecj#2h2JFfd96Q z(_&B!>ei6V8XmKdNur_gA z0N?->ZGL{=>CtcT#lpTS@PtVAO#Hr?`Fp#5K0J zdtJO}Ibwu9Oxw;DRMRN@(cpQ&T(6UD&{4(i_S5o*D)}aGEa3z7uwU1S@%BdKWQ+$W z%B|On8cvvy*eXdg7-CAs< zS#x=Wj`aNb%jfFLTKB?FioQsnnTcOXZ=Iu}zFD`BUPs1%)T%X0?A9(8>X&QJ^CRwE z=-zPUI^`iZUKIKJw9fWcj+QI%r}z!<%WmB4y>m21*BZ!f%pg4jcW`cQook55+!0Qp zIK7Y$svv}#b&uxN5zJ?@jTe^=-oMXMDxuI4B@aA!jyqyTIilsxl@=aQDfjQUgB)N~ zIBnU1=dmPwV}V``X3d@0cSFPl?h2DoxCCo;x9r7>%))$C9{x+=gCW%BaR|R?6eTBvxBkmA2Mw;%!ttVFR?TX>{Pmc&#xnO) zhSUDdqagh%ffwr4`b&P5Gk<7}>Q1ejt=GNUaO?8r%dI`89=u^cHSX^A6mF_Kd$W>*&&lEr{qFu3o7b(06)a z23X53y#FCzNM{@RR)x>p20IN9Qjz7ps+d<#`*-)b;S5e$?Z4-nG_`_js$FG55tS(CjeHH^lKZYhGg{;iKjpU}< z^7aZ@9iy(!?GR$f5-DXWojSc~boM6yL~gEr`eQ@Av(9-s^}@n@f;rMhj9CNaG8uUS5`RQi%1xW_$=RelbAaWN;Ov038Wv5&n6#Lf;($Mw(QD1x_x=0Z zATax$^+(PuufatDjsysCpbEp5nBc{nNZp3n5gtWb&=iHnTmwo}YXoC}hXnh%JTuL4 zP$jMZZQX>vbZhH_3T!54I7Z+GvO#Bu(gH(b>Cgt;vEv}-0PNlFP_q3Cej>nS(_gRg z*)X@~+S~7+z(oTu-^2e6pLdja^v4#^$_qMzeavi9_EN~}b z19%==W5Sgx^Ai$!T;cwK87ys!k^TpSg)!>|$R;0sq0OBfaZ{iyr}#cKG(_CKEhsE( zQ{NF162e1wqLl{DCWU9rjoC#3ilaEN866&GW@Rn04FJq<=rfKNy6h$|GrqjF0yd^ab{+%xy z%*CmhfTx8Z6Qxey(eV!TlK!elkwy88-9l5!t&fA~xDs7fd|=u7@r>Z$%?`Dnlug7B z9Xca7IZoM$PP(aSdG$Ker)yn^lj9!xJ%N~>$M_dMhPnQfwsHt?->n-( zRepPS!otGhPzXlPp!=FCQS;`_wLvC3Dm$+8XRqy5pIYoaAe&^@%>uU4NKjPC(r$?z zBse)6-R3+_(wpEDbLH8+r{KaKLBYO(>k)Fwf7TP^*j2(?UcA|_o9}gCVf^*&UHK*c zBe_jFYima`G_%v08N9uZ@x5z%YE)Hu_M{%Yu*LgFO09x9{S%`mvGGi7(()JcvtC15 zfeIuoE#Bmyd3j)^zr$&zb*i4qr;Zk)`nf4&%T=d6B&|fJ7i;AHa7ZjEks_;wJKY?A zndDeR{8^PFr#RcMm}73HS*Bf(Ch2tlj+%Yle*Q#Q&eu0jGPs7cwLM%swwZH2{W7=<>F;tH9za&?A}kHWPu1E-q(Y zt9UT=yhEk|mcNn=JN299W>`GL)5ssecuZn6b5oNmdfV95FJRwx1q@3$pE*8IdBns# z(Lhy5A;5eD98CE820#*RShS{>P-)ZbI!rEaZ$ApHRshm3v0oVMyRbJ>wa0sC4>}IO zw;XJ3cT0IXqWOt$VaEKmR(~8PwRx+Hf9qYFDr4)zxJAuq6=CYRh11|^;b$j(zt1jX z3vRf|!NGwtb3aCRfIJUJR9_<_<}1kmptb<>8dWq>AWF)hzsjJghodK8h8WMDDbF$d z?Zs@`iD-ha!U3Kd)I)T^IH6x=IP`*Bp4IILh#3oSuu31$V`n`Qt-Eywu1us>b_0~~ z)w*WQRy_37h}{4K9;K$@lYxQgiN=6|Q%N=gP0JjqHX^s_wSoV8{(v`n*`3n*XbK3M zl@$ZkgE-+6=Ow4j)fGfPc> zg7eh3NO9#uL;E5&9(L5QCe1kJzGP34F5*hQBPV1WbBZ?_!>FpA>h}FdV~L9;d-Y(- zI)hV^C>DjnJ zeX_Oq*g~kzp`{Pzd>z@;SF(1_^d{)<%Q~B{6($->4aF*g;B?`e4I9+I<14*MoF(BoII3Kho=qzjOU-gCBe+)6rjjQP+8 zm2k_S8YBY57vYHt`B5Ldv!k5p%$YB36hRwh*_jS-?W0Wg4;**=_F|)yl!OFHUY^vJ z^Ln6$;q_r>=S!FRF!*sC1NeCMRt&TL=({rKeyjS)N;J!!FwWx-({KLzddQWhxR`^E zQ*bL885NcM;snWF@co+&6ckf)Im}nPy7x>^^YLd%7#SS*J_pRdk<=5^ZRURBhu|V>NjiLlmSK~M%DMA7Q8Dxq zQg1tVoj4IYNf-R(DeEQaZ{>!EmX`Xfp9iqF=fYQ8Sy@$!GH7EkI-)2sjf|?J+dk($ zYE2KS361)pW#^eU6PCTcl}GdB@1OJzAv^|BL9QV;c9itZx-1Iko_<|_@3|M~Ir$|@ z$+E-Uto|zxbsxtErXe5ry=tg2HvFoE9<{K`K#R6GXBc!eC%V6t-8^JvX?1-IQ{RuY z347I4y;G;|Or0ipAT~A%3JQ99^yNCIQGUIConoI?BPkker_Fz^8nih8Uj&N|`dnbb z*o&AaIWeBZxd}~r$QeM~3IX4{q2WBc8X5S$C<#HmUxH+p%x}Kc5N+XKQ)_$Zmn(@h z%DOfR9W!iyVyF}-_dg&)0Kwg%i|L+$hB(rh|D;bj=T5fPRUt_zo4C0ra!ouwEQ}_i z#!6ESZ*tDTLF&vK@-v80`4439){kc@s2+jh3W`m%aiK{kWIm99-6klDN}^|QJ3u&wv87yRECs=3I7}lL z`KoYBj?12pT={}`UykevO=@+IPH(m^Tc)O8RjDfiV9zr1-cV2{T6+HLXhiyFvP?qNiVgyXQ%G?59*wn#Cf!_n z=BL0$6R-6lK=jGFRKLdu3x&Z0Su>lL$DCR>x6yQg5m51|@HVe+Bxd6|-Wz{bv}Q=+ zq)~Bx z9&hi8p4$CGxt5!mPG_KU+n%g-(lh6p0xPt$t!g$r`FUG^5B=(d*?7lQi_2sL9@~=n zWbSje{FN})>B%bFuZ$)p2gTlpFnnpXqm>Zn&eyO9zzE&2Ear4= zW!A(r08B9N(226vjIDZO9&=-qgue!xRa#Dtkb=W4(P}nZX7da;JkDOBnMJe}(w zKYmzam<$|jQ9re~C$wHLIN_9c(J+b40B8T0RWbYpp|HhvR3J;Y zpOz%pix#1D(7bCTh#@*KQgN`h{()%)sC!yt*O#)l6SQa}qYgxnn8iZeTQU8&;WIfD z^fPWD6^r!cGPSGAwWh~Y)C9G9YPBN!&6%r(KD3JTJevutvg0rP9erNYJ}I+9O1Jit z+R>BV-*)KJT@7KVlj1lWazfX8^-x>7h6_gesLJ@1^cut*<{@t=a+wRZXjY2gu;Vf3 ze4G#;l+`XcJeEzbqj%rVZu5%&Nh&)wIy(OT+lILuoMc^Hw!M{)jt!VPr|1jlKWi=* z*U@#E;{zdHGfrJqSHAu59Z837mNRF7SFf)Vl9C5G6W3IAAv%M%C~-|r=1HJ8B6#$u z@u8VZ$PDqT{`~PHe-koL`28C-q4(WLbS!IY@dXZqbC;t;zD#aG)M z;-c-cON875_1bwWr|fG^N6>zZ4|}-*es>#Bty*5o^UI3OT9H+d^Zqb-gQ1@Jrzq5=XNis!^iABK#--dPJrSvbZ$0LRxj2q3EiFNu0aVbNonAOzfW6hk<%R=Tg8F6GMYM4m znL&;8=XdX)O%xP_y$UP`q&&w#8~jhcX3C5G2aRqhqfnM7+I<;71!P@+5ak1yl_ejG zoqN}@3E^b`Y5kEggQ)xWccT|IIGEmFDQy0dst>YeZJlKxtgCl@wMC%DC@}h@ylhQ# zO#l1j4o$F+4Hg#%LRA)j$24Lt61v~mAuoHz5 z(7mxoWh_UI6hUT*d*g+kJ&x=jWxGj#ui-g+`-$ExkIcZ&#)uz@vL# zVSt>FnOfdU1y0V0L~+VXdg!T)W~#Kh+Su@J;U}7?a9On*C1@riFKzZ%q$XyfF@$sq z0ZxM#FoK(>CnnTj^Z`cH!Pe%|NP0ZFkD&U)mIA|zF;(MUVq&Ijyl`}4;z(a#{)O(c z0H`UlVu62Sek~B$|Z zI+o~ps-NeH|M+#OSd3*9Kw2EzB@iP1w zW1|^@6#-kIsY>{dq$e1>FAc5GBS}VLZ=>Y>g*hfQ143w~K}Ugoa+;|%7RZ>AvNC?_ zuSj#oO#VIohecVLDKxCMZz;GQT_Ks|UwK*aB6l;}rU$PlermggIBM!f(CdgCN_ilY zsS=4;Xemc6f{mw$Vu2M0HO zH8no<%47eRiq^I^duH6lB%JR}cMCSr5R`v04!9#_gDGmULm+14GssZ0bvqTz0=D-!j zvqQEI(LV3NgZYgdA~MY|#73~Ugnt0o`74Ogn1*J7nxpPWQ&R^xu9&Xa^5x4#{5?A6 z5FG*8_z9goXoqb&od|qRgSWe8ip8W_>ce|LLImOo*Mv`{#uYxIw42GVfrDQLIL?~A6MeY+*J^=x^(N6*r zWuV^FUh;26kVvmm!CdzCu6r&q7%NcM8({e0XzJR!@8H6(x)O(20RuiJVZF-b4A*|e z!Kv?RhKA{}u}$w3Pqchumysd9Zq+~P_Z)wlUR5Me-$#ec7U^+> zV4^Vo6toK$vn{ldNTRlEflB%u=TdG;Vd2b)GB2;%LuCKmK#$Q1y00A?1uyU4HQ%f~ z8QW2uc(yqT&QS#lhIMN9N25_v1DQ9Q`j#KpX^l&TR?s)0#rtUlJW3}Pmjrwx4)>=D)Oz z;}iP&0ljgtzXya(Q_BP*MS3Di#io~ecHAjAG`;+8fHqmnPj(k;uSKefoukHv*T2vG zpeG|q=Gi>HzcBYQ*><;NjJrE=^L&rv=7pU;`Db0+sY`JSQ`1Cu+S7WEV1l z2oMs+O9=`gGCwpa^Xp+eN6eb7ug9!wytc-7nn4;{bAjcZtEGTJPCk@wv$JmQ?vBrz z9psP}Ag^%4h))RrY9%+inbDF+A_w5rhu{vh4+cs|J@9SAU!NUlSMqS6zIpb|4YW-* zL*Vr~TvoNYL{k7XyFsyapmSFwup*KL*$y5`PZj4|rA>wYZK z2`BG!6boL>eOgv#66=Fr09ZvRbIe^_3hZBGWvP|8z)Zntv=L{W(38iUHx*LAm57X_ z4SEbqeY3AB%Miq+tbs=#Mn?R&en2 z{5+15`-jhkfQH=e@mh`$@)}1$RhF{M$6f}82G++c?h3f9zjRKpM*ID`{O$1%;|$j1 z&V(O>gCGE$6pnvpuEQ#hTSi>ApS0jME%^dV+r~v%OH1P@ z%@;e%8B5!MjTB$PSVjCLmsgtFEt-C7N;Qaa)X`O@krOMJkutzoHzu4^s17)xs&@4*=hTg7pY!>V+ zFc?Jtb=2nIkZrrV5uRQPc>%vet4GiiLIXAK{(Xp?Sa$B5trN&2=Fuv~z_bbFCvuv> zp`r7T(Dqb(t*`%uys2t!2B-NN9mXQRXLSY{6U+cuFt)a2Y@eH&vi11}GBDCo9EABY zj$cdbyStN|7%^1(_lgHwgcoWg3`;51L1GNdYttq>dwZk=sL%;#eT1ZI235?yU;z<^ z7IAU8#zjAYMeTb8xL+6!RFJ};H)oqp!3Bw<30&Tw-UPS@W+MM*8r))G@$?A)9)Lx zQ$JWRayR2{{r;}6&*F4N4tf7PzlB8V4m^F*#l`&>i&?p{VV;f+ubqSLpLG#G2_cJ< zva;4zZ#{xZQ^Q}%X&*2q-tO^@@SI4~&$b;h7>~lf7Rp=R!GYPHH@xm$)TeY3? z&}a=gTG*F*iVp_>K|R8$SWrMqeG^&d?gxlt(lW3$0j=>X?j5FoK*&v~&GD6~iHWNj zlk_+AS9*QMp2B@XjDzE$&{u(2H5gaG8mX?g*Mc`XY}b(tv~FP}P!SlYtg89}Isotn zq~MVW&eBbVNRR=dYY}4+$(&(Gg9;oS8Fij0Yzi0~!dh$q{$b)GB6^d$9dlQ4T!)3L zBZLc|hWDK+57#5;guqP4(KB=DC1D}-O1{7dt8gXx&)N_G74s7NRy0LH$&rzf>Af@% z2H1oSI;6;mhzJed(D3jJ6=P@61V;Jz2S(5pSeA;I<2T!=!cGk3eA@ELN1PBW;G?0- zO_(}@poaJ8c>8O7yrZ`Cu+LmWPngi2CyfcW6dytHv9REX?4Ae=At5u1i?E=E8^Yq^ zB6!1Q5Jh5RUAnY{)z~|J0i}m&R+hF@ZQO(X^Ytby3rI5X6l^TEY9?>EsQ`V?@4WP# z-V-l|OuTJa!)oz4aHC9F8cJWT|H~?_c(WX>E-ls*5#1|O@iz}AY0@+4Dv~QHLQsf& zT;FhKvew(c#@UAEsqZ50e7knJm~oM$ccrm@ACYvu!6?La;DF@i`#Cw!b15E!2;DbJPx4RQdD$(u?DmP0{(Nq zr?3w*w32i6_yKPKY8x9H3;xjANzh*5b)xw6{52o8+;qw;c5%q-Fo06ZF1QP!7V=%a&6^c%8Q$FAbc*jXoATafOU zfu_N^qV7GM<(*$$A;Uv&3ZuRWH^%F?kOida*rC;(8trs$u0`BoP=3@(0lh9%6t*Cr z;NhZWnO{^iFntMDkAMp^GTy&>b>)`lcn2*rvjm*$lGFVF+MFyFK_;`Hk_Hu+~7@!s=S` zlck+r_5(VO4S}K+@467i!WPkUe56Mv+a|AqY*?h+brz)rdia1 z(c8PR*si5YZjX#ws*0Q04tb{Zr%#>i>^glMauMYrPsHKC#K`z_a4_@2B>Z^b^^bw< zr}#SJ(2@~c>fl?qMQ7yv`Ji!bC>bE-D8iBhT7e?`e+n{336`4I8TTKpA7Uxtvr_Q!^pvbLb#DF-M#gpxiW5}O=V zY(C^Yyps}(WjJ1l#HRNJ(Gm8W^95 zjC7wL{e8;H7@Tiy994F7zlY>R9GMdn|HdIvRq;2vL*p8>v?2kr6>Eo|8Xr%-9FibS z5(oN@FbZX4vdtd@;dm^M!lhInsu?_FL2~28zPAim2jFrbsr(8W5!MlG0`ZXhQb#4l zacphG7*fFNYoOxeaK@+>I6k1K)x7ep^2;=W!G8J>JXl+M`_Bo7Qq$|P1WrDX_8$Ji z>G=$Wz%3AMS207*_9IUEmoNb$?3xO#H{Yvy5q8(#GIby>CI(3!oRsDlNr)7>x^Bn~ zKxT8Um^XlsAwhzMuM_>5uaoK-V_d+V1?7v`)LkHw!bN~6)ptdjX zj}XzN#GM0tHCbLoV35TSR0|sy@`#AEfbIeJDGg(BMj=#I6` zoZ{F)h-H|W!6KcPy>&XNJJr6$IZ8AIf!JC=|LSL;vigP56~D9_|MD!Jm6nSA73MrE zEQEpB=oT|4MfbVA15Xq)!X@|7(Q%fB==6(ap8EoBq2JypbtzQ+*6Wzh5ji@%AQ z3~?4ZU)6M-(lA(wgdW8M7o(OHlkx`RTKWN20D+I-6w%3SK@dkh3ZeX)O+~_1@Y>SJ zbO#{>Y}Tx;7Tm~q6hRDQ_I!q_76sULYU&kua(4=Vtu6p3Ew~v1KE42Y38wP|tF}IV zA@ui&OG-&0D?!N%z%=|Rd??q@*EP&B;*9_J&ngDKf~{Usm;;Sm?}1!^dF<7XwY8j& z8l7xsKMw)gN)ABQ3Y{__ExF=Au?KbnsgEm-)hP>~Ju^f|fHB4|*i`_l!c3lNxI1F3 zNrqin0p@-rmArW2T~zLr&JR>HQ6r;EUtOzU#YXG!_*2~^RZO@P2(p#r1t#SG=I`@2 z(Ka`K016abU+{_xbyZSQeH^sWonm;{f|t)@bzqG+J2x=mfNQx&FLrnFMJS|^ms=)% zKUg20XNv=44W$sKVm^7ohxXIY`g`~jTv=XcaVN)F-(YFkBqwAtA|*+FbCgVe)@Wra zG6SAh85#A{?A(uSZIsPcs&q)CE1tUA$DoyV{&H!aKQ=z~7&mDLt)0l-60*Kb;K$|x zN$&2$kCSbuEOWETu6Q@yAYZ_4KAN&u6F_QWO#P{4Fj}vO?hYudS2qAW)+ zcLDH?e}<7TIEPxleAxk!cx)^d34T==m!KddigZ+a^YcIia&mLUL`1BmAQuJ4A7?wX zVH}Ta*q0Fb%b!1g5)Ol?q0!O1kOcy0Z&E)1`(>PAh%8Yx1OAXBAP@dcxHmdFg4l|{ zP*G6%S)hBk)|oaf^EI;|1XN$mI0hgtw4yn3o`y zBJOZ{`rfhqA1*&UUard@D>%T%7z%`4ZG#hzTb>;|s^sR@)cBnMF-T=k5Mq3M9${U53v%a{cDQ*{#EJqL@WQX+i=6GP z#7P8WJiaA@8HjtHoZR5E1&Zwj950Y$XT9VuS2Cg`$#o6}eC)VOO&sbxpHB2cJTaE14i{vb5}*oUFp|F4<%) zMdH|~@F`K{A*`3tCy-kmKLUF(SUTbk?rbDXnh%&uV=@NLX8Z|~pXghq7@q}NHdxhS z{(Ue7zq~wiZhint*{4PYgqaH}GxR98QB$9_Fav5W2lZ-ohM^6%As)-n(2${-*>8B- zpve6SPbI)sA3hAf-7e?otMw3>=w(#L$St0>d_j~$D60gbsYuVvyo6sAu*wjOJUJc# z&;*gy2DKQDKOSQKmpu+G2<0?Y@I8PMD zi5jISpF!Hy`(6EIW$BqK*Hh`D`tTF#e*;^+4j(-pAeJXEO2H2Vwun~V0$C`eY@HHN z=*}C9;!Zvn-pvC0v+>Z^IaO#Q@cJrXZFNwfl*xLTs>vxR~Q*0 zO%ANC{#{=bN0o4Z<`%a+Y^(_i+^%w6nPf}R6!wbj#r?M2^f1=i-sH;Vz$L%jEgP_HJI@=H-j0r9U2E^Sy)j~{rA8yNBBZ&};WbM7QL ziS%#)ls`39RhYm3AIjc55UX}=8^4?9WG+IPLgu*$Ns=Kc^O($$c}he{$dqK3Awy=F zDnlr9lBr0Dl9`Z@3cq9Z?7iP_zrTOJZ~b9E&$H`xueGl0yw3ADj`KK8o`L2O5fPCy zwXk^nX)KHVYL9ULvJ3$NYmY)J{eM~*d(*4`H}ZY zEjnEvq4JZJ{Y8tIx~@1bH}N7RAA#u>Kf6H?hj{a=2yS2!-oMz~Z70D&Kk=$x>{m z-xu)Zu*rc-#sk@u7-6eU>;NN=2{vKt=|rSyDB_?ta{B)DEZ${)i&X@HFk@sGR2Y*C zGzcl^Hh|O1KxeA%H9s^bqx^Br|K2+(mr~Q66o4J;8byhKFs}bV(F_#8yG^JKvvPA; znQ`(VX^FDJa8XD|C-jXxZXN+egA@|NNnASbL}2-sMFcKbHS<-#)udksh;`z_%OahGY1GmqKT54x!;=w!B&E{mZz`QWEo`xO zbxmUR_u!9-$4$eVWQdu3|IiT_&x@!SpP2Zz>Xo6cuA&?WD&lbKDM-R$@GDQ|&``NO z$>&VO{rhOKBx>A0e>_3i0~uNQ{o921n1ZV6^1=dkHR17yB;h&l*k^W?IA>J9IIV$r z!N)ry076e--6gOrgJofU&hVXw4-L?p>Ea?1Ustv;DR=~cUpqN5dELS(_H zD6-A;pPj8%<*QcSMs}es5g;b%q2je`Wn9ylcO{Wx7ERXo0OGpsh=7RcBAtCkd1$>1;v)lI2 z!K+9Jg*yHkq#*VNblU)A0^dPizLgm^pJ3Q;K6@tCbNWOmuM;zFq#pM)8dH=pb%Auo2zyGLQZ|sR~57UK!2~e|4N>zO5S73v=jUwo`Id>?1@-Hh z(1R{o}4H8actQ}Ma_%jDYZT9z!;5(6I;(<&Xz1b2rpbFhDa2cZ{kbT!i zj~~DFbTcJ=9w*=9jOg$GJb*{(Y;^3{t2LCy3o6CpCeFfV)9Z#ioZ7-4A6fZ%uYm9K z-J>MQJqlv7XVlbA?xJaLlkU1c+cB1O@!9m`Mv|)5$&)V!D%>uv2cBlUCdsID{J6L{ zknKVASVi&;xH0E`s`6+YFejrz4ALn`1j=}ybY0(itUjuH`{vuB3HZRd-Rhd14<(j|gL?`ts*zh+gK%9H zAD;XC^~rJ2+oh{@5!K?C_F3SkTvNf5E_Mga|FLRtQ<;|J0&Ttis__w6T- z9(}>_!0uC8o!kYk**3A( zFTsh4X$5UAk)-z4Lj&6x&Ru41jXQnzY>Dxv7YlodHN6ZR8ZBHp9|W+iu;TC&&RB4D z4M1RmS1N4v6j(3sLfmUOSVU?s2WNm1e;$p)I114;PS}$lbIOR1r|)q&ImRBY0D0{X zOv^=|4tia{M6ui=!yVV8BqSt2aD*clVgbqJekUYU$kB_y5O2Mu)c&%ru`vlZ3rZYz zcQB&BzqrcC_!Jil^|+LVJrzE0Q=XC4?HkxSN~NNlxYCPQN-FXH^QU?^Sj_IiRi62k zub&;H--_CvRx-RBDBc1|1xcOW3V zecRN`Y!8#vANaa?U}i1Qz~}i>RTdE!ZOR+oJ!rS2#z&Pu{qA`8ZaI_1pD8{r&ch50 zj?RB7BvNyZepK2dvkl~-vwk#h$8;~^)i$!upY!?{Y27Y|{L#@-utlP1h;W|P32H>A zw#aJvNEIezYz?V_0(AQOOe^>Tm?~mN`Av=4Qn3 z0|Yf%Ea9nL&b zN!6F@G3PBhuEdB*HtWadmv!=PN=jMz`LPCvA8*Hp&AD@NjgP9_z56JW<8E+TE_Y}9 zq40n^yUW%sYDg$N$`wgIG{hp-)j9BDRdn?S<%{3ETeheH`@+%H&IM~2)H#3MVUq6M ztD%7iAwc1;qWmTNLl8zGOloc2!^60tJO=7F!a58K4$XD!?CjWDbIZ$+eO3Z%=}AB7 z2DO4c?i>`$5}24NWa-$3M%QObQMNG~5-YmBib{g&#^--)0sc~0P!jqA$L}$`eiaZn z&VGH`EputG$MN;`g&T3YI+rvW=%|lsj!#YH*tJI`Tuv2XV^cR8{3+w%K}NONRqcEuiOpI$jtnm((q3G0$20LxXMb{9sdrLzv(l@wSn|;>xBIH=Bo8X&D>7<#T5GhOcN$5zaJcA5;%kJ>Er5v2Z`4X ztqq(!b0IW9FV@suMzr4lBh5hhA<|PS<9|^@qZAnxgdICJuL}zF7Ni*KYn-O0RyRDS zQos)T$Rt%s#`zUf8|8)u@4=CIg+qr-hO1}4Lwv9=NmW-@KLKd4c_} z?&(2-vg5HGo4=0ACnkQKI15J3j)-=ouq}8x2aAe8rbtvL|Cz|agbqj;_m&G2Pv)EzngY>I{uyI);W0e><;!<& zvWGAp{qlvVT&Q*?nMxybLG}P>8lm(Y)K3N9lY^RDTH=K)y4F{Xr0wi_v<$DEJ=6{# zB@OkC4>6lJzFK~a4<|i;bXTZITFmym*NK0HzVV5(`T6d(TS*2R5c;e*B1^ob^K?(c z03(ovyp2i0Aa*@$iM z^d8ZAT1XUes53|oz*7ZvLZ4y$%i&}2>Vx2VW@_p;s5<)n`|S;g zjUe-kJwna#`=CQZyja%LD0fMZZ^!BmY)B4*zT|l98|9tblaFdyzUR`dPIPuD%?99DQvN>o^+F)v%Zx9)NBAFe-Im*piHPC=ZC-5(ht2!{N?2dP$beu(U#rMNo0x zt5Ze^R72C#f52z9!p+!V3EQtDyekA{Gys4#++ClUkUIquN2F>CKYmDJHa8J={^o$r zERM(6*j68!1&6X{!G15(dmTp{FYoO(=MBj%#7#4G*Ub;OHGfK!m9=a?gsPb2u8HCc zG$A}LK&a#V!s^83;2=N_4j@pDkn9onURa7a#49*N3d@013NIRY7;YZ^P!MD#@Z+9$ zP+|lkTJD-$Tu3uADd)iq9YLOgX_FV)gyR^h8Y7>K_8+?6_2yqlUQ(*8B z4?c%vpzm=U5kvZ|`xMPt*0j`9p`l-gPu2QIJU((vA_7_ujg2HpJ>;ksk@sa6M%C1* zKwvO=$sIpVoB}my$+?eZ*WDZ5Y5~kE9VB~cDV*czOWonmpx?8r-2pTNDi5fk;Ke?J zuY12`1Zu`O+&+#%5OgB^4>vg*AVI@~Ib`9u@xXw9rj{0j4Zs*oxbbJtmH{pxGoq0a zLOSR3O_4Vm;{;}r_I!F~$D}1vi8YU$jlhHg2@NFT0KyG0Ags26%I~j1T%D4Gh6zKU zz5(k*gFO^BkjoA9_vgc!k5Fmg2fQupD(8V^%3~0n%%StDVxnHj{{CmC7U9DNXHx)- zEtm^}MT9_x%AZK6(7p`ERJ<>YD>S`&^#wpNX=!QZ?7TdTnzK+;+$r%3L@-Q+^^QlQ zbVb674qJr&*@22@={w_XHFb0jP*Gv#s1Ah7AOyaBTf@B3xs^XrTT{}Dt$%O7?(PnU zNP;Ai_Le$&)EcTzr6_JJjn&WoOaR1)0}i(p7aNNaYIR**5i^w&=OOPA)g!o(R4G2y zHfRH+R)2KC&>R_c{uSb_kKg~ku>S4se#UcVX2{sHzXc=C$|{k@zumLFeNLGdcGQ-b zMfL3Q>hI>h_^DgqYqw^pzkU^(TgDRqsXRYFGyq_j_6N21Utnn$H|4QGJSr)PXyEX> zbB8Dy&@+k+f=5LUnE(vqfyqA4-|Mppsu9%S;04V=A-TIhSLb@)(cu6?5YHNTuBobq zO$nl6A|-}PLvDuR3grM$?*uA{d>}@s`ZakJ1CL^rMIq8bYUPCj6{rIQXee(akUC*S z;jo2;o~~{jRMh|>OH0k{CgsBzQNoI1FJNjL$O$Bn1DND`V&EUSMP4-PUsF9LMa2Ni z|0`ufHQM8VAY!XC(}~&YgGq+-F$NeYjdf<0nkrFe+i4mY%uGzIK=^|rItoIGyJ#sj z71V(q253mJZ~JuCiO%hf4Gmn8ui^g*eiW_Mh;x{u0L!&fbiiUxh5_nU4-aD8#2L)F zgY@RmrAac)#U$D%>Xio!f{%k@d_SlkN)k-ne=z{~R|>@s4X)^&tI06OK(y;YAa^uu`ZsP(HTbgx^&i z`iah*8N`G&@F}1Ppt+o!gj+_L^biEj5DVoW-GXoHu8X8~4)n6RhK7TN44QH99-&gJ zs#?S5`2?{R`hQUGGb41sVj%Ij3)j>}OEWVOuV2pT7trMr1LViZNL3CtHQ4t+Kqd{A z-#OjnIq`)0|53$&L#3pHk!WYaBknANWAan=lwansHr}ywC*Z#)B_*a|$8mJxc#=l; z3G_}xVtcDcFuARIASi#ZQj@QP{QORPd7b#Zk6lo(s5d2s-&nS5C)4n?YuV^2COT`t zfjDXtg{jPAmgtKYDA-ufdrE>TBqvwbSJu^KrC1$!*wGd7W3h~vij=&mYqXr?bL9Oq zKEFGis?r^u>CQ{sGapZPWjGj6l4Q1}rl*fU7Bn=(55>{@*YK1?MAisu1W9LZVL=&= z4FuQ?$1o@-lv}Q@G=Xx+H@@b3`Yfrz7mkL;6@8QV(+!P{m?DHs;asdBVaEOh-~%G}2uw9Tz)@F%xHUb$+qdz$ zVdGxaJ5Ha}2AL298s!I7w!2}WAmc@9NZB#c5*^qC>CGxcY~48idcQ+ChYvw9a1k2? z^+bDnO*f9neQHOus-hS_+(otb7S0f8Xh8}CX$yZ?BMbA=lImi`d(`tlVnO=a^*{go z?c1l4*&(q(&#ulgNqIj+cey$)WBK6yC*{y?W8HEnQ?g;Z*dxPDQNO1%mX>2_IY8PK-H#TgsRc>!xH&MKT zPDs1JNseSC>wc)s1|G(gi#Yr$(AxkJ71#{y>r-+VeZqwOg>VYX?U!fTEPT$S;jLrD z&E({9fb35*5ZwXYAg{(HCAEg?2~d?Bc4p&+@5s#lv8@A&6EnkrmvfwGddIMFRYLOH zI2Ng82$j4e_!JHAshJrSIe-k;(9WCWbrq>Oan3o9@2hC}WDVsHGVAJ&DC8CHD4mzF z4bbI_q&sEC-#vI6+D@)wq2Pqt0SBeU#er(?b-)#LS5074Ee8x3lDxC3s?iFplSW(@ zIjHgyT1?cNiXw6Mgnl3dQf~4SR}Rfu1wT<#I@K|~d@J#f{meLmA`&Z*R%1^IIjqm# z%st^{fM_sSLll?rB@jm>X_0eb{FGyKXXl6V+#mVoj;%}ie5NUAxU zejyfhE=34553u`a@9t)Vs0!d4Ruee!?O1mC)|j6nCopn&N$9O?!~iQ+ zRsw`XVuHrp04P5&F=l2R!75AbIz4eq7H}((!OTdEMIz+*c>R|yB`dH(UY7*XEhIPi z^DrxrLS~HYA37+h;g6uE0xjWSG;Is*M1fH?BNY{d2hv5h-oPQCy(T(K0PA3`B{Cdk zxt)HG{=OuvI9IfyKwl`1W-2snV6s-1@Bjum$jT9v9GoT;Sn(p^56bX62LKeIY>ae5 ziGHuylq~POS23oC=tENqcp}@GWlB&AnA}scEhiq5YdW~P+PZRR=4y914WZM@WmQ#mbU1l_11WjHk|R0GAQ*3s$h>jSeGJy5g- z-bin*?!nh=Yrv!|_|#m`(t2ElAJ3|)3=i#7juXZhzhyjSMognZB9}D(=N&M)uk-E* zm?mx@a3FFA#BS(0Uk`5ypg^kJG|2X}u&NI2gO(RiG6dNeSAKz;2E6Y8R31G&V&IP< z$);|FCCvZ9x<@fu_I>{emn-qgyHlP^|l_}XBa#nAW(=koTvVih(@BI5#g=R$;XGm z8F#>0lcNPu{`6^sDo-8w#2{4)*_y%@Ch!V0Bj9o7@PJmCnV}&dh^dwNB2N+tFXj2uXTzqF(vGx)$*DQn5GaCS zfp9PY9T3PVu@Nz55Y;-I2CPj?YBASA7k)qX22#XYWx#|5Z5S1#I;Y+RXspbRiI@K1 zJRBX5d;Ka&O&u=gM1RG0zgJMdVBX<{QbAaxzF7Vg1W*;jHkOx-u!)k|jy%GF3)@B< z?K7}CL2V9>CKd%>;5J zmcTl|+s9JVd}{`U71Cy4At;7g6X|m7G2d)5UPDWZ0HuJiF3rtBuLLHKn8Ro$*o#Li zz53(g;z>)d4}DUv(A4r1{b=a5T?2%fjrtsgZFI{BfIS2WG=gYD>w_;2^-zjB7gGL% z`}PrZe8wqbDE4gpcpfemCxpvzMe^#Fj04ZW8Iyo9EkY6mph5Eg>iGKguL_Cb#i_cg z)V#Yw9v+?TDXdhE1{?q=ZUTHYQ)FY1QfBg$*|P`qV@xI;X($%iA>tnQbPQ@zTwoL; zBiW)`0s~r=KNc8Ci}G;l)zo#j-^ZB=@C*+Zi7Cn{J(O}dXPvpNX&3*z}FH#5jOCzNQ&~?h#PpW2FJmO zW;DQEv9?bCE3SnO_4H{tW#vFrYiXI8pAYg36K9}v6^zZTtkh?ZzzjF&klBwMDYhFw z@!;momq0=#Od5h8dmVqcS4r&4-BZyH2r?jTkk%m`!1Ou?{b*uS&6NlXpI3Z6IB>vj zFe8qxvzz_MW1twDw(cu;C6Vk2Z0^_V7ONTEkH!AKmLCsP08t}=jPV8np6lvDFolw( zv#Sf@Bha>qn1Gmn81fO(*AgEQ87I2N4ygX#!f+C61u76oDzqO7h=^#w$37-zH}GaG zw|~u+7qX7tNMg9H%npbxk!zap@O>>skei`la;E511}chflfV5lCZ1#uOAL@X@BD9-VOdmD>Bg<#{N_9Ubn=g+qzcoRZth(aWX zkKIaQ3yB(gj|vc6gi4RwBj;h01cPU=8-YNm1OrE*w7z$5AHmrlCGZzZRSgX)%2PXb zc#B!)=3yqPqy0~bw}1p;_J`bqBzGH&lu1AU5{X-*z`UQ~ zIepy2ak?mm+{{e${{YWWOfSORp)B>H5zNW*lYRL;0MC~@yXit8w@=gMpxh+p3bXJ! z&CsUddF^lKvDT^2BEW%)^XIysnU~i(Obn6zvA75}37(k*byHf36dLaddkdi&%IpvM zy3#L^#1%I`pwH{U_#F-^Fs(!)fmWJFAKOq8e7ZghU34WT7r703(NdE01EvLC1SY{o z^vZZJM4-qx7l8Y~&JoMdw&T(1xR|{=h?}XNwkdb=|JI)pvmdE?XQx6I>&1&m(YNje z&D^|WL1rV#`8;qeu~+QbYjdaWH(L%I*L{AEap@&Hwn!Fs;EC^qdJ4CVY7%ChM4b){ zBl}6}O|jv$-Y-yy;;)K->5=z#PD0+i`)K(0iOu?GNC>~caf zg4c)PM#wY5VVWlU^o?eAxikfNSfdcIJ*?f;Bk$?nZ{+=i?#RZMvbVYQKU{!icmF-M zy*mB(uGZ+X7U^{x7A_9&+`JJF5&#Z<-jsp4gB4g&I<_LxqtMX3N=$?meE;Df)}pO< zvlW>8d`?p&wFYD*fWE{yMvVc0ELIp~S6ocY!y%>%0W!)U191D7J8O+c1Ouy3fx($; ztG}gd?@L4>dJ;p#KRme^0RJ1<{0+^_w7RIxSwh+Id%$gQ1}RO-d2XYsKaf)m0qUbA zD)~8aba)1(;uSdgUpC=nzw;X5_t%eP3Q6gR2SAjdg96Lw&nx-0n4&J%5XSEBW!w=9Pf;6S1*tCgQkrE-0@9uhl-di&=H4+$=&nw$F|w53IInq z?ub!hc>f|In4v?%qbq#nU8aAc!PToXsIdW~09E}mF>wI;O5jIBw5sEBtQ5`I9)L;q z(a=CAR|@SEn^M$}2vH6_RJySyoe_KP9DCUxCLxuIGN{mF2FOXt#j@q(mEPBHX!Gj2Ep_Q`Qmu> zqB}Mq!b-2D1=1x+j4f~bbOrZDU{)O+YOEB6a;Xs!lmsCIc~2vRmKtZzXe<>@$l_sN zyLPO_DF?&2kt%b~a_rlV7_qWmCwnjZ>Id_L1WuBSSjt`c?2Wg$MVfxmb^1OytVC0! z6NA&c<4rkz5syyssrR4WiCy|!@2~mF(LZWowOXjh&0+7zW@nnxM` zRL%3Q?}rrv3r2K7EYdGBZN{i}=t0`fcsvLB1|<@riyI_ZW%}R7#>8;MMjLv-;BcLj zdiUIIG(^L`<{IXspng(H?*w0qf#j7yh<|bs42iSn;^Koi59y|udolt7>cD?Z&0M6L z#wQg)iG8^hn}G~=JJz>eP%v84I3yDcy&^^JGNinogDoK?h9VOu`ay6e_5rE^HAsYo z+`Ea$ld&L?;Nyb6iD+Qppo%+ztVuQH{D%`P?1)TwN3fg&^tPg>6BX`9hjjLXIm!cI zBH#LM7ZwUUTiislKg|`XDRmz25XnUrkb%lak7Qk*AsKn}=$4r!-Ap5}Pbh2J#&T#r z)IF4BR4uJR`2HKa)pvPH83Bgn8IlztIn!{nD9Ghn9FEtH4fqh;9CAM(JJ-1Qtei)C z&yz*3r-l4c+-cj2`HOk)>W@{2|aMj~}U zW{bi&$zB>aLNGjNt3$L`~#1H~W)hGJFrg=QEUb8TtNPVa+MLD?z~P3g>zWqQh7TKeiDbLQK`@JK2YUw>&Ms^p8%%J@ zxGpaZ2HBu%UmE5=DW-$x$KK}_&@nK8Apu?@F0^2|xRhQ=>Gdl58iJG*3{}Ml#>28% zFV}w&vH7C5RNI2+ePaQvLdOlLlbUiQYvR`g%O7`;M7WPix=P6v5 zKTJy{**K^4!QBn~+%yI?z&Qr9H)m&NPT=*>8oIwks;H+IKQ)<56!v&xfT)jquX$=~ z$H=D4&Cka|AB4$`C~q1;XyFP$cbDSp)k7w-8wbiyv$4rpwr(f2hX9z7kyFr4194js{)Q4B|3IUZ+2P1Q2@dnw%Uo7MW@@-pTLO9UW5scv9?48aSzu zxJu5nRW1w-dWT47GYFG(gCb9T1x#$3pZ&nfN!g3Q%$&kr?#RlcdfCdyTBj%zKLI6oF~TB)B3K(=UkX zxMKhPZ9m%+#8fCu@w@lss2V=?V%yvPI{zXz z_E(#n&)d^4P9}5BG-f`t);PWCERV{ErB?M0nfIU7$xkh*Ca$gAxIisnx<1D=T&cdU zt`TUV@#XyDn&u)|!n-xTHzO_r75rYkw#Y|dTe}G6^`~BO-hmZQN9Rf=(;q+5 zHf$nL71ZoLEDB;9|Kz3JuKIavX@(``p47_i(KnFI2Z(I5$0bb zv~d#Aw|uR-bAQu+9lf77Gdx{3v8kuv@tpn6JzjUWU2Q%U))aU^sHr2oyI`znE3~d3 z>QZz45zVMuq>3u=s|a9J>!0j1yOnG+6!uYsp0Y!SC+WrCf^x+QNMZ2WpZHcV^LMQ z{Z*yGAC^>`)vX?|sH>e`)#Wr?%+H-znv5@{(6e#nV5Gm!*BJHwV)f+gCJjEW_q$XV zCpAX4oaLd*{H2xpv5ZS9^Z4z_k-Qs+MERT~5*cKcF>Pr7k_;xyg@<<_VgkH>fgoO4 ziN1+4-hIc>mQ)0<7hGtjg=h^nO+c`5aEH=~T)~S4SUmegNC|IC=Gg_EvsqcozJz8= zd3T{vhK{wohMRneIo>688vO=3%Akpy0?Wp|MNg97=WrexTJNh^c+NFdxjxKCL*9E* zXN!)yOuPP*1omf&XXvB38=E zq8U1|J2|%paNnA?{}4UMGq8q{z4@wb2H72mI>R>n--b zb?cW-@%oszg0g7`v(H!44ArrPwm#2~=489cEIOFY-#ouSd-e2`78TsM$-}2QSBx9W zMG<(1MT1M<&uI3%cy6qa&wI6-|4Mh7h(W}A_QNfA3PtIbni<3wxBL@wOTi5AE z73tY8(#vns>&-Jxj%tYgc;{MOQ2)%Iu!4Xlmr+noI7Cv>I$Ps5eJ#f2ey zs)WKjH=gsSCy&UIb=C>v>m3(VU*E~wMt`MKv-q6S9&SBFfx7`E)}UXF#0YuVAympm zH({tJJk7?$v#Rge46p-mPzAyU$pcZxtQ4A zgO`50e)5Xmw9WmGgVgWc($Y~p!`~|UM3rkyFTdwHmrzsd%W~%V6z^!;Hjbkvt>}vU z+C<*puU&e#%B#1KC}(QPj(I%TvgB5yaPHuG88m+3{q7W1x)*-aH1Kg{US0 z2Vx9wk#nJAIyA^^tgI;2xc+7h-3exp^5W@V1Q^q5v_q`lz830-O&d3I8|32So$*lz zrO(;q3UvKg9=xc&d1%U7ng8kyMq!1#1E=M_c5)7II2t#G6+3gzRw=EoNiOWZn4z5< z1_MC>H{O*MclRfkw~$FI8&vE(dh}K8R3FEkI~OjVlHG`|eUC4*ZJ%ooO1;Tc!weWl zHnC4l-Fdl&ArTi-H(6UxbofRai89}z_3rp``O%~2%Z90AU&@?zGbn0M8+o@z8wr~2 zOizFFu;l?~TE_P#7AopOZ?x52qrao0Q9s_XdGp+8ytYoE6{V0xk<*dkMj>k&RjISu z`)gtZ4jz;Bl=Snv?SD~U*;%+NqtK42D?`9^`?kF$Gc+TkovHo;ol$pITE(81Q_#q} ziXJ;gy7-ua()aP$$o1d<>;pNuv{Tvn`4DwUdi=;d_JxL?{yK7am;}|-*Qfs@v6@ER zJ5XF*T^)H^Dv2k066_T^tI=!1-*}+41!$BH(mu5ApkDxs{Y_v4PEPYaR^rX-BlTuw z-G8#-gLWvx@U#xeZTZ(B6H``rljOyxTT>%01z^q7PBoFQ{jqp@m4*M_;A-drq4Ca< zY?^x!wN7n?#+%;14`ynEEtgvj`$U6A&fKEer1}->iGlbBR9svb!G6r)R=&g9XHk$U(zY1EH)`>x@yXO-E9DUTIYzPhyq zdq`ro#5g8L6W*#v&h4YydETHkibpxFt~p}&fzBVhD_jL^69hh$uh&9+o}{Xy(`Tzz z8~#*EnUC-7!{JD+7>Vc)+7MawuDqJfA{H`nDd+(kf((EW4xLz@04#7xNmT){1DY`P zu`~xgPUzLaQ2SaxfXh?mZM-e-H6XtLlmc`xG4Ydq%4hnq*;%GeZA7c+oIetlL=iz9A=PU%ThE;N5_x$aLpag+5lcLJyJk+4axk zP1C)Y!|LCt!86oE&VG)S&9Apu=h@!3yEr$pQ`%LXwdJK3y%%?d_0O*#kjGg5H1dqt z#N?1i4Zq!OTE! zjax>-6&L4$Mr^{-sH6nlLJNCAyuu#|d^$KA6d1}IHDq!yv+UR_FAZz2ruU}S6C33|#tvOFyyjOQgd2?6Z|D)Yjd3XJ z@!WFt1+71SoDv=$5O3F>83b!M-W!pp7m{pD>A%;Z4dzX4)4i3eOZA57MfYd=dMj5h z@LpMKa&r_64{xBs2wtrobKb9G+W_)EHO8d&y2h?*@6=RBM+IfL8mUbdX58tP_Pb&A zEOXKLT;iLWn{N_ZzYXlBZVgj{Wx@mb<}>!vT4XvJ!+Ef!V_S&-yI zu8cl9cC5Af-7kzJ8_OvO2pvsY7na)X{7bm75Yh1h7`rDnu@36`2bsLzR9?&5^XH45 z+NnG;r)CPAa)ayUQ<^sx=xO*g%hibFfVj8|pd|XMJ}_>r0;cH!MFF5%=&@rLLh<}Y z#|=-{)L?PjU0RcK|fPL<;cX9$g=V)&a=l)_e zU>qA8gE5Sg&iWxNP8CcSIOZZQRFdGMgu%Xjo~LP z6;+IK1}K|5^z?~ku%S@7m3Z^!O@h~2S`vLMi~QHi)AQhz`3)>}@-k5>Dx_zF4+KP` z(paxpN19QQhcBHJx)}6FePqO@_toV4gVJwX#TI@J|C!Ws{^r^H)<{3NSV+ixAEj>u zWlg?;a!gG_$eV;6?G<7N4%F2j*h4PM;c%)7Y8jk6L3FRy zvm5nktQd=9`sHa~j3k7p&9A?_*UHK~#C)qxj?vwx&+Z6ssPDGkDh3OSTfS${-CJurgfy@kx z052Kf_2~HwAg%~B#~#4)brO0jL(324oe3R8bSY~X`MQtxjDAA6S#S`G2z5*z)1aJ1lw%h7M&-Xt`qhEY&CUwb<}c1C`yL4}~@KA+~g zi>d-v_va^z+ls6xt$Q4o2S`&rNcwL36`Joc@~ZDl-_3{-dpTO0-o(|Lgb7@dN!`>K zTHg{xCUvPUK&jHwL7+{#&26xwfJszT{Mh^(p_n6?0*~p}f1x=zIRit9Vuk$8rEB_s zQHL=MyHyVlojiCjM$pf!#ol3qxL4e@g`Zz`O;5*&hmTv9yO^wcFnS-nwBk7Wb|geh z`w8h%2Xhp+@o+;B0ab7ty?q@?;;Vjhip<#T{TKec-2K7C0d zpKC@7@F_qfSl8URA$1YgYjsKtvap07td%$;#>%eZ9R82RS;x zYG8&CHYZL8oUPb%e?A=U{Pd{`|0&wdnfPoP^^3I=T?yhRZMct|+n>@fZ9}pc`^9ZC zSoLG#)TQL2U_5$WBH@dDc%miVuE>_b%BtU$eqmJLhNu79*^UI;ck5RFSuTJ7fmg+h z&EoC;i%Lh>9sh`*2|cgBd+6Iaxy|9>w{P#?b@C)^n9DEYfNnWCAs>G9QPF+q;=2nh zW({ReT^ri)t%A(kTPfOXhoacse;exAzDkb-SY;0-yZ!oVFoV+Lb5Z%zih{A)g}11WlCTB+nMN(7i=9>ed5Qo2NpnBG zC6MyZ+@>R{j^A02oV#~V=GrlzXxh)88)^?)?A~36@y*o82(=#&ze&TEcm2;1yBGD* zMqj2{>~7SSSnWP&IZ^aqHz4=*dsgn(H?hBZ(6Jy&IrUCTjbY%=?KmIrB`v zFIkaiS$fbuBB1`gR@7{H=jZDhoxZc~*wG+seAuU0$k_Py9SX*CmYMVR&Lw{z?@Ux) z`mTKw?J(1tV7Dy~q%|D+>G1TbNe?gNSRW&e*6wp&+%L2hJ|bG2%*@fRO<$RQSsCLo z@K>lPHQ%#kOBAo{f1b?o>_46?)gSm}uMWye9s;uuuw|elkbdib@A}dP!6vEt-Fm!3O&0@{-e#Eue z6EKy7N%9|uZ_j<3BXDGEX(>e$vvvOG>Xf3Uc9?w75m0D*#mXsXqn_TzO%v~f=Iq&( zliln*mf1PB>zN(JjdGtHym>m`;N(ee{iaubrWOmI{cZXhR+lectZlo|aC?VxjEvmv zbfv$z#=l<#d70+Oh{$C9hbJs7|JsCLDkN!&q>G^EYLC{u9?J$Y0*x zfr`5=ar3sWvf}h9ETnKv#FNg%=M_R`J1=IShHx7!bUISuiU|GfTQHp&E5pD5kHLR3 z-@lu`DN@bwoUU${Yj9!VgQ$%k`Y0)6ONlAkDgwshxqDOA0wTwFf}=) zPNk;CZJ>DhQAhjyXaB5x^BNM%=zeOm39kPnf`8Wu?^zA%tSnZx@CR~^MTPfb6y)y| zo?8AUPup-d!u|VMlQL^9IHKc|qa(2!XABj#7n=)M)2ysae`?J)$TeswGW+qZmBEeQ zd^d~y(75IQ{`|Oz@DAbnmh3Rq)CRsk{5<%7K~v zjbUOmw{FcXYuzQ%K{~Z^wXes=CYm2`D#vcL|07=EI^TTcO?)Fu*ggu-lE{mm7(0Kn znUMXjw~)4)na|EryPYr2H`v9Y;XVcF=uuD4?Ymj|?-iQt*eQ4`_~y+Iy*lL{Si*n9 z(1Z*#OJMNVSPKr`(c-qB<19dsG4rP*90k}9OWTT&CIuA(;;j*1A7BaQhRn}P{?1KT z`ezfA-MhQ>o@)wj`kQtp}U&lPeC^vvA8Jv0@R#AIwNe(Ybrv<9Y$7MTJ8PbLg*tyZw+R0CuZd{tt?apJ7 ztgLq)7ID||UJ|-PHdar|x4K(IWH-ZWizKV9JBWJ-w^nlziH%K5yBDW;1)A4{V9>~f37_sa#zpxuwdtZ?xJ)oM9h8ek&)UJ?dLe)7HWRz` zh__Fij;ycp;V|+gd-^$3siOJsTk6b>qkEe;^5#Hir?}G{A&bf4-~$KLHC~2wo&Eir za$ilG_uCiC6#FeVAEFMXyno&8^`uDXM!~O@CU!Mq|={HJ0L15 zcbc5KUa0N7+Dk2?`Cbdpr2`9N7d7P-wm37_9 z%D=N(8r(jwn%q}i3Q9~GHZ|8R-y7~~{ed5I4cHqxUGSS*p4wTwrt%4-TZ4x4Z&mb%q!KNX(k)a|-I~f>eoQr5Bnh~3ySjS*JS^6a z!8?_UG%RO|TzSI7J%95IHxxQ^N=bRnZD6|5)RD@qjZ*CAFH{0*Y7Oa09(ON3cAq`* zts>0(k8iF20pZM2H7XhkhLBPbYU+a$@`F`>=EI(s6`Gt0qP-hxK7YBtKjwI(%hZQw zVatPKtINIBN!MrDI0ISEJb7xnR${KHdE1|ow&!WZ&KTuf-TFXEcX#`*+ua80|E!SA z%uuH_M;ttME1o__v*Vea^(o6GgMeTgbMC<#EsvAFzuX4Q$<5B%Etfh>>NV4vkN>t4 z9{l!)k~|$hpA@NVE~xtW#l=8Bu6ljPjyJKuXMw6ZvaPIKkp`m;_*?n(me^Q%cLAP| zAI_a!XO&o3d`pCP?hGEVxjMhpFo@B<8#iLY*kBUl2@FdbG$JR+1FJ!Vv2Z1IjrwpF zY!ob-r1g6dzNsvmw(d7>G_K{H)7nEG9-3@Ic=LW8i7qTcgE=OW)Xz$Aw96eZHufo5y(+28lF$?95+wMsl{E$F58>aG&BCeaj}zgaLWE zL!bSDpl95H%Q5Fg4j!{_`WecHMIz5Irep@JVhBgujy>racW!Ua&Yt^GH<*-qW&@*l z0&Ifb)YbbH3EsN3|3n;*9w|GgY(^BnmnUS-{x0B3^N+&NLw^*$v-@++2A_|*CclO` zFCuB&%kU_fL>o;r#mCFeb@%$L2pwCZ1XiZH#(b+7740+ElydjWr?>c%30^ZpZl z9|03_$J;;Mcka@of3-4;v5c+3W{X!GohCYJIi5#Km@|G{DJouBoxQf|;zK~IqkVP< z_-outBk^jLcnp?nHc(K+WnF7OR8$QX1}Vqzo%k;el}N8k@)p)1>SBy+SZW$ z^lP@gee_IBe^%!g)33V?_qLH?aK(!dZ$4rV>w6O~wS`5XL*e+1`7MQoA3p4(F=u5s z6MTrjy>l@zKwEa3vRKvpRx-(&?!0~{vYOwsLMB_Sdjzk>vE}?~wHqIZmtM`fdL}*n z^Q@}E_Q&To#3)Pt*w^=L!F#=t&-)tN>j&n@9hf@}zkZ$Tce42)<03NLSnQJ1!OF)S z9C1V-*501vK0-~yeQ8qt(>4G9hMi45l{^<`X4bAwY-HT@eBs>M0+XPiz2oJvbAo~~ zBD+vzQ69`M}dy}a-1y$VxPMc3Ql^;8k`}^qz(u1x&rt6*_ zsV{S?{Jzs^jDlV%jPaDXD;!AnPZC-HafxT{&;EH)_c|{K3M#0IB`$oY%QH7qGq^ep zJHRyRHt)SVFC1~ij+;of;W6+D&_5z8yL|_~zE24j?QjcU@3XM#^@o#JJeIzW#vc&8 z9dCQNhBQ6RZIF)_dSFyqZP3BL@VFI)_iy^ZK$=`)x(@G1=C^^Hzh-qpL$PSVn&?0> zjzD_RpaNAnvQh_TWLrPFa`m?DpE>oWL;lhiIU4RmQj9}^NBCp${QLD^w`AoC!?Df3 z&(@@NE93RxuE$yVptjsTeg5pkVx#>b$JX@h~{Z8d{~9~v9(91tR5584@}uA3G6 ziAdaz`sBxMV)ZERR8Fqx!11*?e|h?6wq_%W!$d;^U1})R>(#J=lh`wNd(hlIqx7)XuC7{<~8wRR1Cd(W)wY zYO*yNoNv~AZJzG8dU==k$bwPbuASTl{wUr=h8Nl#T+N4MOiI1Im!|Qzp4y6ZhN%2p z*|2#t>EQ9Y6U$F-oG7+fSn3OLjTiE-m>q3D{K?&y*68cX7&gCc87PZg>!k$*racwE zF?9dShLD5eHF?jTx(6J)6`P=JnpRlfM{ntHe_SsBvG%A1&z&unqVf39sfJU_1-`|8nY<)pWBpTPvH?76=Dy^eD8 zwur>HP2roj0z-Lv^-avn0P=>Letw`JtJhDcN;Ss_NUpH1tk6o7d#_Pm`eA9ZxY$$p zRJ43EHTC@Wmc^Vrs=;5+-&Rw%hE9F4Mpj(*DB+>b^Y)+azB=~&pFX)?6RGw-x3?x! zjnwt{qE7RNLYY({66Fz!eKnowG0JjsbK|La>(jjr`tS4lUeMEdRws&vWO9J;2oBD; z9u-Z0Sixz%noKIwdje?8aXn)*jX}Q=&uGt&-Lu)p)@d0Gq`P1!^k>S5z}h=4FONSL z@6LZwQ>uH7R<|P~<^8+4=xY9}x~U=6zo-oj5o;YBtbHHNtJqHQ7!=*Uw{LCL4*T-8 zA`On=4Mee_a0YW?n(>cP<~wCw-4oAiK~A)W z1)n^E%A8PK)cR5%b^mFc+Hy{VI`s^)`FOj_X7w2=z;NF_1Yw!0gSTdEOfqRe0yRI6 zq>S;LgFr`za(qLT7k=D3d{CUUj}D7q#}0Lk&l7>w(*9&lKlxMT)h@hx9og^BqW7%G zL!_+i$M{KiaR&z~T1x8r7t3^cY;6xs#?NPG{~V1U)my{2rNY2xQ?o*oZSi7Y{41B} z9!k(l{FubFf<^B;1$rt<)`dSc4R4v-*3SI)14uKm=mvA3-BaLEte-Spj-+%6g`E8$VDH&a9~ZyL+wNRsft+K{hJe^Zf}fNRn>BrR6ViOEveUfyD07K%3ZojI*14ql|sbwqdRwsI|uMp4b2&^{WfxRd{W9L z{2-I#(W8K1)AmD>lH5Rw6!e_mIJ5jO4qW_r(G_a!g)f^^Qb>^Z_r6Lyn;_YI@32bS z6KmSx26D!?fs~8hfy?uUrIU&Tef~Rb8SV)mJ>`h}qCgrJz~Q#~l`-R%f`Y-){+slk z@_QXul^)3KP^;Zk;cE8wprI$ZghbWv(Bx!!i5N8qvHEl0F>bsT5uol(5#>^MQ8mreL4+v#u84t^kz7cq3@xSQ`rne0t4b{IL z9f2xG8w$QHwxaa<_0Bt09|;xHHtni}GN)_9drZ2AuPtal3ssfQv+J|b)PM795n`Xh zLh<95ty`WuaO-QY+r9a6Ing_Dwkp*~+Q!D-@k^}5lVa<6*&v!i(;eQwDC0#7U3p9z zzjrE0E+4GHmR#DuX={n=$23;W0`pcnpZ7T{Gj( z8Tw&0+BzJ>_oUe5iyYC!JhSoChv$V875wh};o-T41D4$XoA3D39`|!_eWb84GaKgv zqgTm|-@j*zJ&*a5b*1l8ivIqi3&&coMM%8o@&M1L&g|^b+3HAY->uN-IQ`(*vZbz0 zcva^df#H1&%FdQQT)z+zH0qad@a|nYhVdaEfB*UMkJMyg=9hyK6Bn7x5$l1OgaBo8 z3{g}SE4OEmdh^oP)NI4gUv$QenH;uNv9<$$*HX@LoAQq7|AYJwm6$bc+^d|Ck>qIj zKcu~)>puQi_XQP4r`{(w->I8ikMMdk*%^YeJ@G`y@m~p2D(Cl|@-MP8658^P;b#NA z^U+hjd5-VKcdXI6nAF)LO6pkt?f%}n8y0vjQJi5oSv{}i| zFJ!M>jE-<4O>1*K`$>5+G8J-mY>v)v55@FgMPK@|jZ9jaU724qB4TBfet7<)wW;}K zv(pOO5&o&`lTYs6@ALTaX#n^Wb5iREEiAU~71sQ{40kh+CDSR*?mVFjiGZbM2gfrL z4pLBZa#}s`$juTMEw*h=IfY_jsz>O$s9m*JA$45a|JT-)heNr(VJZWWIskG+mNMfA)F{XF|x!7DMGS^7E6{GBkPcep|LAVN;&+VQCFwa`F($U z-fQOK^S$fy-uM09&#g3P^2Kf5ew*9$bp~INZ$Ye{>dK91qcsTlRhCzkn*V^rZ6&~f zi>IN1m)F23_@%lkGZgubwMfv%sZzYWaw&YT$%6<51q;ilurSuz+QvuK)iPk33i2-! zv{2{qEi7ETcDm{fG3f|AUMV20E%jU}Tg_m4I2&GQI-G4Qr{n8Auo@R0A`tjdV_o{w zUEZ~|-hRTelFRQQ*yBR9Vb>i>v6w3N>UZc#Z{e{k%87}Q z2o3{dk7B;xL@0r4^{gV@xx(#f%!0?J>Y56z+o{$icH1_y$`I3vJ1~G3&dl5^$jKbG zMLP864BnU?(h`yOepu{GFnxQuBRw8R<+#QEs1aU=PxW@c!xoN}_{dFB6pfk{%p^ zg9JC&)zm(BWt=+m?#DU+A~q+_wL79gd54`{UN&bwjE%w4-zbe%++*EA8z=1UJgR1B zv0X5Miuqd(9GQ9QmnJ`dW_n=WBw2BkpeI|eeTJo(oL$b3MDE_*R~{woI`-_VqIc{o zgPP(kq_W(rle&^c=P$QCJlfFskFq2!L1`J?KtN!y^&MlRgs9on-dJKHKe*4V9K~@ zGX~d04J%aMgvH9p0OO?^!lWyH+xLccLZs<0lyl@B?_7OZ*FDz$SJM#?q$18#5Fy4J zjoA#;@|(&h^IJLinU0vfh(7?UbV)lmKO8vs|H!99lKD0(b3#_@7?s8#W{~3fD}_+vi3Z7;?H z_~%4j7!KLOB29$ku$X!E#Rfm$g|P(5Xrye(WPzL8a1P0Pu2OS!O7R*ezJ|%xws06M zOcBDU)WE^FU))_>viMm@7t8K~GWwN#fz=sKw5|LY-QH8)<(>}7o*v~Wq3fecS~gBg zOzb#wmNEN-nnorsVxN4+*xRq1e7u4@@yYn`6NZr9C5TJkIf0UX(e3E*ritMb&y!OlMCpdIy6CD_xq$n%&-B+rP_v03rvmYc?-< z96qSlR!s_!3!U5mtcC`2*UF(ClTx zizXhC_9hYF6w1nQ<~%zML@vz?rpE3J4&n3pH-`!J=OD|7s$ORrA5=TJjnk#H_)c*5 z@7z4FT=d~+qy0})8QLA@H-p=@IecN;{-Uu_RO}x%dZPv4Z?FP*#jmY-^qQ8Z108WlAS zEs=$Z_jzE~tdGxr@m{Q6+OYLHZOI`opLu3>eo<`y7HeyK?J65vrg3gQmW|6{Xuy>R z(UvR?e2SPBZOU;n_*EqF+iuBbXS;oolaPRoAAw?E z$ZUfTiP@p5x@F6&ELLXbEn8{tV~V7PhQNBl4*Ica1u+eyZ7b?Tg^gDb^XdXAQmCO# z0rCM&(tbSaTcMDH@kE@}I0fMCJws$2x>d~Nq@A7M?4D2W4~m6s)auL(L|0gB)*!xq zJa*@s!J-8Nb>&dvAX8o*lcN&^BGCx^io5bFqgyk>3uD>MvZhV}onUI4+c5VVBF1pq+&*gSW-VAf;eRPr3vuEDELI}u&I=}E} zLJ+w47wW#t&T9vdNN4AJd38OB()fqPBUv%clxI~RuUlw+pJFzkoS%B31)Qq@G!vzy zSlTzo)l8NPhWFDPlU7N`H#L*T-Y6YLMloRYg}PP_EEc0OKVRFFYq;9cW!z;IA!lL` z^s<|lUsk56-xR!QZ9I_aK|z02;(g;HBcES71(kIp>^}*(f**8>#iFDncspNZAD_nH z6{USwBexqFPn%;mEiXT=7A~=@t`?3F&p&=V<*MoHicX`21=Lhry2}`-zu+wHe5kzq z@1|W9Qkz*9-UlMTVPyY2uhX8F;dbg3Z*LpC2j8_r2s0PSl@(roqu=c??CggQW!?*4^e1OV-rikBv&HzAZ7%ewbY(-62C0DBx<4a@G<3IDU$#!a_{(Hr zVaga`ad*icMimr0(Sue#|YxWWgxSC}W3*M}7Y;0>Q$< z&8wjYY)|n${ktGcv~asvOPOnlGAVR;_l}p(5Z5PHfU7Y3l$K$=?r3Nzn=2DoTv;Ww zPeV$ou1-ipP}tthMT#~qrr&;dQq$aA*^9RJ)rWSSpAaSRecXTl5f{Ojioz|}wX}94 zCOby!{P_8fImS~z7#f@)qH^_(ak#gZMI%r8?9CU2LpHrl}Pr&guYW9Ho}lgC45PIXN(*GV}wE@7gssZfthiLBhvJ zbARChdL%wqPf_U)LRgkqI(l^21~V`K8!mbI$B&sBH9>c$mkwu29zM$3aXRIbYjZ=+ zWcEOBZ(HaTnFLl{3n_1{tn{?CyQ1jbHfKO?6SXXXk{7=qpHc8Ao@QIqEU}4&rMnwm z1iactaSI5<8mu`aw9k_t884YpHIz27rAypiVawrp9O##oyG5~&NFS& zt(YBW&vy5^k49lW@+OEo^m_f$TCLiXKx0*w_YL4(14r%`o5zy~*>ejEk^WX1EaC}q zBeK|3k68L3xxKRTCP^V-Ty}hUDmchAT*=Ny)yu?kQpUovxV*64w^u_cJw56r>7-hw zs!>-57rOfH)dqXhqJseet8@j-{FV?_^QvDKoVaO*@=Mg+5;%uoZpA;DIz+*!nHfBC7c#@?aSA z<|CG&KTSy>_6jy}K`v@B5WQx7K*9W$aaC+_mxwh?nvo1a)z6oE4+v;}{@{C=%I~Bj uu=oFb(aAVC@ZZbbg~6cz_bQZJ7tx-nf1dcIz!=VWF==b)sTZo*1pg1s#0xS2 From e4f2de1f6e7bc59a24e787546423ab35d9189cd8 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Mon, 2 Nov 2020 08:10:09 +0100 Subject: [PATCH 359/627] update readme and changelog with ROS noetic support (#409) * update readme and changelog with ROS noetic support --- CHANGELOG.md | 1 + README.md | 8 ++++---- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 6a0c8aa4..8d3cca72 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Support noetic and python 3 * Have all sensor types in sensors.json * Update ad-demo rviz config to visualize more sensor types * Remove CarlaRadarMeasurement message publishing (radar data is published as PointCloud2 only) diff --git a/README.md b/README.md index 01b74782..60aa73fe 100644 --- a/README.md +++ b/README.md @@ -61,7 +61,7 @@ This will install carla-ros-bridge in /opt/carla-ros-bridge git submodule update --init cd ../catkin_ws/src ln -s ../../ros-bridge - source /opt/ros//setup.bash + source /opt/ros//setup.bash cd .. #install required ros-dependencies @@ -87,7 +87,7 @@ Wait a few seconds ##### For Users - source /opt/carla-ros-bridge//setup.bash + source /opt/carla-ros-bridge//setup.bash ##### For Developers @@ -210,7 +210,7 @@ Currently the following sensors are supported: | Topic | Type | | ------------------------ | --------------------------------------------------------------------------------- | -| `/carla//imu` | [sensor_msgs.Imu](https://docs.ros.org/melodic/api/sensor_msgs/html/msg/Imu.html) | +| `/carla//imu` | [sensor_msgs.Imu](https://docs.ros.org/api/sensor_msgs/html/msg/Imu.html) | ##### GNSS @@ -323,7 +323,7 @@ You can find further documentation [here](carla_ackermann_control/README.md). ### TF -The tf data is published for all traffic participants and sensors. +The tf data is published for all traffic participants and sensors. #### TF for traffic participants From 9311dd8b9ddd1ef9392fbd0db405a058cfda0287 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Mon, 2 Nov 2020 17:06:39 +0100 Subject: [PATCH 360/627] Update CARLA and ROS Bridge compatibility note (#384) * Updated ros-bridge and carla compatibility note * Merge branch 'master' of https://github.com/carla-simulator/ros-bridge into joel-mb/bridge_carla_compatibility * Merge branch 'master' of https://github.com/carla-simulator/ros-bridge into joel-mb/bridge_carla_compatibility * update to 0.9.10 --- README.md | 2 +- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 15 ++++++++------- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index 60aa73fe..06b28e95 100644 --- a/README.md +++ b/README.md @@ -4,7 +4,7 @@ This ROS package aims at providing a simple ROS bridge for CARLA simulator. ![rviz setup](./docs/images/ad_demo.png "AD Demo") -**This version requires CARLA 0.9.9.5** +**This version requires CARLA 0.9.10** ## Features diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 10e003a4..e3795aec 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -57,7 +57,7 @@ class CarlaRosBridge(object): Carla Ros bridge """ - CARLA_VERSION = "0.9.9" + CARLA_VERSION = "0.9.10" def __init__(self, carla_world, params): """ @@ -586,16 +586,17 @@ def main(): # check carla version dist = pkg_resources.get_distribution("carla") - if LooseVersion(dist.version) < LooseVersion(CarlaRosBridge.CARLA_VERSION): + if LooseVersion(dist.version) != LooseVersion(CarlaRosBridge.CARLA_VERSION): rospy.logfatal("CARLA python module version {} required. Found: {}".format( CarlaRosBridge.CARLA_VERSION, dist.version)) sys.exit(1) - if LooseVersion(carla_client.get_server_version()) < \ - LooseVersion(CarlaRosBridge.CARLA_VERSION): - rospy.logfatal("CARLA Server version {} required. Found: {}".format( - CarlaRosBridge.CARLA_VERSION, carla_client.get_server_version())) - sys.exit(1) + if LooseVersion(carla_client.get_server_version()) != \ + LooseVersion(carla_client.get_client_version()): + rospy.logwarn( + "Version mismatch detected: You are trying to connect to a simulator that might be incompatible with this API. Client API version: {}. Simulator API version: {}" + .format(carla_client.get_client_version(), + carla_client.get_server_version())) carla_world = carla_client.get_world() From 5e9802a80333f4128f6201d79fcb5d6b33f66537 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 2 Nov 2020 17:37:10 +0100 Subject: [PATCH 361/627] Fix lidar parsing in noetic --- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 4 ++-- .../carla_ros_scenario_runner.py | 8 ++++---- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index d5ee9a29..7d50e326 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -66,7 +66,7 @@ def sensor_data_updated(self, carla_lidar_measurement): ] lidar_data = numpy.fromstring( - carla_lidar_measurement.raw_data, dtype=numpy.float32) + bytes(carla_lidar_measurement.raw_data), dtype=numpy.float32) lidar_data = numpy.reshape( lidar_data, (int(lidar_data.shape[0] / 4), 4)) # we take the oposite of y axis @@ -123,7 +123,7 @@ def sensor_data_updated(self, carla_lidar_measurement): PointField('ObjTag', 20, PointField.UINT32, 1), ] - lidar_data = numpy.fromstring(carla_lidar_measurement.raw_data, + lidar_data = numpy.fromstring(bytes(carla_lidar_measurement.raw_data), dtype=numpy.dtype([ ('x', numpy.float32), ('y', numpy.float32), diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py index a23e83d6..bd4821c3 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -26,16 +26,16 @@ try: import carla # pylint: disable=unused-import except ImportError: - print "ERROR: CARLA Python Egg not available. Please add \ + print("ERROR: CARLA Python Egg not available. Please add \ /PythonAPI/carla/dist/carla--\ - py-linux-x86_64.egg to your PYTHONPATH." + py-linux-x86_64.egg to your PYTHONPATH.") sys.exit(1) try: from agents.navigation.local_planner import LocalPlanner # pylint: disable=unused-import except ImportError: - print "ERROR: CARLA Python Agents not available. \ - Please add /PythonAPI/carla to your PYTHONPATH." + print("ERROR: CARLA Python Agents not available. \ + Please add /PythonAPI/carla to your PYTHONPATH.") sys.exit(1) From cb83740c5af49f67b8340c9755bcf9ec1fadb434 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Tue, 3 Nov 2020 17:23:21 +0100 Subject: [PATCH 362/627] read packaging version from latest git tag --- packaging/CreateROSbridgeDebian.sh | 27 +++++++++++++-------------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/packaging/CreateROSbridgeDebian.sh b/packaging/CreateROSbridgeDebian.sh index aa01b723..1095afe7 100644 --- a/packaging/CreateROSbridgeDebian.sh +++ b/packaging/CreateROSbridgeDebian.sh @@ -1,7 +1,7 @@ #!/bin/sh #This script builds debian package for CARLA ROS Bridge -#Tested with Ubuntu 14.04, 16.04, 18.04 and 19.10 +#Tested with Ubuntu 14.04, 16.04, 18.04, 19.10 and 20.04 sudo apt-get install build-essential dh-make @@ -11,9 +11,10 @@ export DEBFULLNAME #carla-ros-bridge github repository ROS_BRIDGE_GIT=https://github.com/carla-simulator/ros-bridge.git +RELEASE_VERSION=$(git describe --tags --abbrev=0) mkdir -p carla-ros-debian/carla-ros-bridge/catkin_ws/src -mkdir -p carla-ros-debian/carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ +mkdir -p carla-ros-debian/carla-ros-bridge-$(rosversion -d)-"$RELEASE_VERSION"/carla-ros-bridge/ cd carla-ros-debian/carla-ros-bridge @@ -28,20 +29,20 @@ source /opt/ros/$(rosversion -d)/setup.bash #installing required dependency packages to build catkin_make sudo apt install ros-$(rosversion -d)-derived-object-msgs \ -ros-$(rosversion -d)-ackermann-msgs ros-$(rosversion -d)-carla-msgs ros-$(rosversion -d)-pcl-conversions \ -ros-$(rosversion -d)-rviz ros-$(rosversion -d)-rqt ros-$(rosversion -d)-pcl-ros + ros-$(rosversion -d)-ackermann-msgs ros-$(rosversion -d)-carla-msgs ros-$(rosversion -d)-pcl-conversions \ + ros-$(rosversion -d)-rviz ros-$(rosversion -d)-rqt ros-$(rosversion -d)-pcl-ros catkin_make install -cp -r install ../../carla-ros-bridge-$(rosversion -d)-0.9.8/carla-ros-bridge/ +cp -r install ../../carla-ros-bridge-$(rosversion -d)-"$RELEASE_VERSION"/carla-ros-bridge/ -cd ../../carla-ros-bridge-$(rosversion -d)-0.9.8/ +cd ../../carla-ros-bridge-$(rosversion -d)-"$RELEASE_VERSION"/ mv carla-ros-bridge/install carla-ros-bridge/$(rosversion -d) rm Makefile #Making debian package to install Carla-ros-bridge in /opt folder -cat >> Makefile <>Makefile <> control <>control < Build-Depends: debhelper (>= 9) -Standards-Version:0.9.7 +Standards-Version:$RELEASE_VERSION Homepage: https://github.com/carla-simulator/ros-bridge Package: carla-ros-bridge-$(rosversion -d) @@ -105,14 +106,12 @@ EOF rm copyright cp ../../../carla-ros-bridge/ros-bridge/LICENSE ./copyright - #Updating debian/Changelog -awk '{sub(/UNRELEASED/,"stable")}1' changelog > tmp && mv tmp changelog -awk '{sub(/unstable/,"stable")}1' changelog > tmp && mv tmp changelog +awk '{sub(/UNRELEASED/,"stable")}1' changelog >tmp && mv tmp changelog +awk '{sub(/unstable/,"stable")}1' changelog >tmp && mv tmp changelog cd .. dpkg-buildpackage -uc -us -b #building debian package #install debian package using "sudo dpkg -i ../carla_ros-bridge-_amd64.deb" - From 533e46d193cebc2a1ad102e3d6a5f8bc16a3e45c Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 6 Nov 2020 16:32:58 +0100 Subject: [PATCH 363/627] first iteration spawn sensors using services --- carla_common/src/carla_common/transforms.py | 36 ++++++++++ carla_ego_vehicle/config/sensors.json | 4 ++ .../carla_ego_vehicle/carla_ego_vehicle.py | 38 +++++++--- .../src/carla_ros_bridge/bridge.py | 72 +++++++++++++++---- 4 files changed, 126 insertions(+), 24 deletions(-) diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index d27f9181..add4b187 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -10,6 +10,8 @@ Tool functions to convert transforms from carla to ROS coordinate system """ +import carla + import math import numpy @@ -332,3 +334,37 @@ def carla_location_to_pose(carla_location): ros_pose.position = carla_location_to_ros_point(carla_location) ros_pose.orientation.w = 1.0 return ros_pose + + +def ros_point_to_carla_location(ros_point): + return carla.Location(ros_point.x, -ros_point.y, ros_point.z) + + +def ros_quaternion_to_RPY(ros_quaternion): + quaternion = ( + ros_quaternion.x, + ros_quaternion.y, + ros_quaternion.z, + ros_quaternion.w + ) + return tf.transformations.euler_from_quaternion(quaternion) + + +def RPY_to_carla_rotation(roll, pitch, yaw): + return carla.Rotation(roll=math.degrees(roll), + pitch=-math.degrees(pitch), + yaw=-math.degrees(yaw)) + + +def ros_quaternion_to_carla_rotation(ros_quaternion): + roll, pitch, yaw = ros_quaternion_to_RPY(ros_quaternion) + return RPY_to_carla_rotation(roll, pitch, yaw) + + +def ros_pose_to_carla_transform(ros_pose): + """ + Convert a ROS pose a carla transform. + """ + return carla.Transform( + ros_point_to_carla_location(ros_pose.position), + ros_quaternion_to_carla_rotation(ros_pose.orientation)) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 160f6114..f2f6f90d 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -195,6 +195,10 @@ "type": "sensor.other.lane_invasion", "id": "laneinvasion1", "x": 0.0, "y": 0.0, "z": 0.0 + }, + { + "type": "sensor.pseudo.object_sensor", + "id": "objectsensor1" } ] } diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index af992762..71f0b72c 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -26,11 +26,16 @@ import json import rospy from tf.transformations import euler_from_quaternion, quaternion_from_euler +from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import PoseWithCovarianceStamped, Pose from carla_msgs.msg import CarlaWorldInfo import carla +import carla_common.transforms as trans + +from carla_msgs.srv import SpawnObject, SpawnObjectRequest + secure_random = random.SystemRandom() # ============================================================================== @@ -87,6 +92,9 @@ def __init__(self): rospy.loginfo('listening to server %s:%s', self.host, self.port) rospy.loginfo('using vehicle filter: %s', self.actor_filter) + rospy.wait_for_service('/carla/spawn_object') + self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) + def on_initialpose(self, initial_pose): """ Callback for /initialpose @@ -198,19 +206,28 @@ def setup_sensors(self, sensors): sensor_spec['id'])) sensor_names.append(sensor_name) - sensor_location = carla.Location(x=sensor_spec.pop("x"), - y=sensor_spec.pop("y"), - z=sensor_spec.pop("z")) + sensor_location = carla.Location(x=sensor_spec.pop("x", 0.0), + y=sensor_spec.pop("y", 0.0), + z=sensor_spec.pop("z", 0.0)) sensor_rotation = carla.Rotation( pitch=sensor_spec.pop('pitch', 0.0), roll=sensor_spec.pop('roll', 0.0), yaw=sensor_spec.pop('yaw', 0.0)) sensor_transform = carla.Transform(sensor_location, sensor_rotation) - bp = bp_library.find(sensor_type) - bp.set_attribute('role_name', sensor_id) + spawn_object_request = SpawnObjectRequest() + spawn_object_request.type = sensor_type + spawn_object_request.id = sensor_id + spawn_object_request.attach_to = self.player.id + spawn_object_request.transform = trans.carla_transform_to_ros_pose( + sensor_transform) for attribute, value in sensor_spec.items(): - bp.set_attribute(str(attribute), str(value)) + spawn_object_request.attributes.append( + KeyValue(str(attribute), str(value))) + + response = self.spawn_object_service(spawn_object_request) + if response.id == -1: + raise Exception(response.error_string) except KeyError as e: rospy.logfatal( @@ -218,15 +235,14 @@ def setup_sensors(self, sensors): .format(e)) raise e - except IndexError as e: + except Exception as e: rospy.logfatal( "Sensor {} will not be spawned, {}".format(sensor_name, e)) raise e - # create sensor - sensor = self.world.spawn_actor(bp, sensor_transform, - attach_to=self.player) - actors.append(sensor) + if response.id > 0: + sensor = self.world.get_actor(response.id) + actors.append(sensor) return actors @abstractmethod diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index e3795aec..2cb3dd28 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -27,6 +27,8 @@ import carla +import carla_common.transforms as trans + from carla_ros_bridge.actor import Actor from carla_ros_bridge.sensor import Sensor @@ -48,7 +50,9 @@ from carla_ros_bridge.walker import Walker from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor + from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters +from carla_msgs.srv import SpawnObject, SpawnObjectResponse class CarlaRosBridge(object): @@ -110,6 +114,10 @@ def __init__(self, carla_world, params): self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds) + self.spawn_object_service = rospy.Service('/carla/spawn_object', + SpawnObject, + self.spawn_object) + # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. # Before tick(), the list is filled and the loop waits until the list is empty. @@ -167,6 +175,57 @@ def __init__(self, carla_world, params): node=self, actor_list=self.actors)) + + def _spawn_actor(self, req): + blueprint = self.carla_world.get_blueprint_library().find(req.type) + blueprint.set_attribute('role_name', req.id) + for attribute in req.attributes: + blueprint.set_attribute(attribute.key, attribute.value) + + transform = trans.ros_pose_to_carla_transform(req.transform) + + attach_to = None + if req.attach_to != 0: + attach_to = self.carla_world.get_actor(req.attach_to) + if attach_to is None: + raise IndexError("Parent object {} not found".format(req.attach_to)) + + carla_actor = self.carla_world.spawn_actor(blueprint, transform, attach_to) + return carla_actor.id + + def _spawn_pseudo_sensor(self, req): + if req.attach_to != 0: + if req.attach_to not in self.actors: + raise IndexError("Parent object {} not found".format(req.attach_to)) + parent = self.actors[req.attach_to] + else: + parent = None + + if req.type == "sensor.pseudo.object_sensor": + filtered_id = parent.carla_actor.id if parent is not None else None + pseudo_sensor = ObjectSensor(parent=parent, node=self, actor_list=self.actors, filtered_id=filtered_id) + + with self.update_lock: + self.pseudo_actors.append(pseudo_sensor) + + rospy.loginfo("Created {}(parent_id={}, prefix={})".format( + pseudo_sensor.__class__.__name__, + pseudo_sensor.get_parent_id(), + pseudo_sensor.get_prefix())) + + def spawn_object(self, req): + try: + if req.type.startswith("sensor.pseudo"): + self._spawn_pseudo_sensor(req) + return SpawnObjectResponse(0, "") + + else: + actor_id = self._spawn_actor(req) + return SpawnObjectResponse(actor_id, "") + + except Exception as e: + return SpawnObjectResponse(-1, str(e)) + def destroy(self): """ Function to destroy this object. @@ -395,7 +454,6 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m parent = self._create_actor(carla_actor.parent) actor = None - pseudo_actors = [] if carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": actor = TrafficLight(carla_actor, parent, node=self) @@ -406,10 +464,6 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m in self.parameters['ego_vehicle']['role_name']: actor = EgoVehicle( carla_actor, parent, self, self._ego_vehicle_control_applied_callback) - pseudo_actors.append(ObjectSensor(parent=actor, - node=self, - actor_list=self.actors, - filtered_id=carla_actor.id)) else: actor = Vehicle(carla_actor, parent, self) elif carla_actor.type_id.startswith("sensor"): @@ -475,14 +529,6 @@ def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-m with self.update_lock: self.actors[carla_actor.id] = actor - for pseudo_actor in pseudo_actors: - rospy.loginfo("Created {}(parent_id={}, prefix={})".format( - pseudo_actor.__class__.__name__, - pseudo_actor.get_parent_id(), - pseudo_actor.get_prefix())) - with self.update_lock: - self.pseudo_actors.append(pseudo_actor) - return actor def run(self): From ac1a1269b3138d1d4dd7c4e3cfacda1e21cceaa7 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Tue, 10 Nov 2020 14:32:05 +0100 Subject: [PATCH 364/627] Spawn sensors using services * Traffic light global sensor removed. * Added sensor id to pseudo sensor prefix. * Code formatting. --- carla_ego_vehicle/config/sensors.json | 2 +- .../src/carla_ros_bridge/bridge.py | 43 +++++++++++-------- .../src/carla_ros_bridge/object_sensor.py | 9 ++-- .../carla_ros_bridge/traffic_lights_sensor.py | 10 +++-- 4 files changed, 38 insertions(+), 26 deletions(-) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index f2f6f90d..6b98dc62 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -197,7 +197,7 @@ "x": 0.0, "y": 0.0, "z": 0.0 }, { - "type": "sensor.pseudo.object_sensor", + "type": "sensor.pseudo.objects", "id": "objectsensor1" } ] diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 2cb3dd28..2a9c54f5 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -163,18 +163,9 @@ def __init__(self, carla_world, params): self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, node=self)) - # add global object sensor - self.pseudo_actors.append(ObjectSensor(parent=None, - node=self, - actor_list=self.actors, - filtered_id=None)) + # add debug helper self.debug_helper = DebugHelper(carla_world.debug) - # add traffic light pseudo sensor - self.pseudo_actors.append(TrafficLightsSensor(parent=None, - node=self, - actor_list=self.actors)) - def _spawn_actor(self, req): blueprint = self.carla_world.get_blueprint_library().find(req.type) @@ -188,29 +179,45 @@ def _spawn_actor(self, req): if req.attach_to != 0: attach_to = self.carla_world.get_actor(req.attach_to) if attach_to is None: - raise IndexError("Parent object {} not found".format(req.attach_to)) + raise IndexError("Parent object {} not found".format( + req.attach_to)) - carla_actor = self.carla_world.spawn_actor(blueprint, transform, attach_to) + carla_actor = self.carla_world.spawn_actor(blueprint, transform, + attach_to) return carla_actor.id def _spawn_pseudo_sensor(self, req): if req.attach_to != 0: if req.attach_to not in self.actors: - raise IndexError("Parent object {} not found".format(req.attach_to)) + raise IndexError("Parent object {} not found".format( + req.attach_to)) parent = self.actors[req.attach_to] else: parent = None - if req.type == "sensor.pseudo.object_sensor": - filtered_id = parent.carla_actor.id if parent is not None else None - pseudo_sensor = ObjectSensor(parent=parent, node=self, actor_list=self.actors, filtered_id=filtered_id) + if req.type == "sensor.pseudo.objects": + filtered_id = parent.carla_actor.id if parent is not None else None + pseudo_sensor = ObjectSensor( + name=req.id, + parent=parent, + node=self, + actor_list=self.actors, + filtered_id=filtered_id, + ) + + elif req.type == "sensor.pseudo.traffic_lights": + pseudo_sensor = TrafficLightsSensor( + name=req.id, + parent=parent, + node=self, + actor_list=self.actors, + ) with self.update_lock: self.pseudo_actors.append(pseudo_sensor) rospy.loginfo("Created {}(parent_id={}, prefix={})".format( - pseudo_sensor.__class__.__name__, - pseudo_sensor.get_parent_id(), + pseudo_sensor.__class__.__name__, pseudo_sensor.get_parent_id(), pseudo_sensor.get_prefix())) def spawn_object(self, req): diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index c808c37b..3640231e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -23,9 +23,11 @@ class ObjectSensor(PseudoActor): Pseudo object sensor """ - def __init__(self, parent, node, actor_list, filtered_id): + def __init__(self, name, parent, node, actor_list, filtered_id): """ Constructor + :param name: name identiying the sensor + :type name: string :param carla_world: carla world object :type carla_world: carla.World :param parent: the parent of this @@ -40,10 +42,11 @@ def __init__(self, parent, node, actor_list, filtered_id): super(ObjectSensor, self).__init__(parent=parent, node=node, - prefix='objects') + prefix='objects/' + name) self.actor_list = actor_list self.filtered_id = filtered_id - self.object_publisher = rospy.Publisher(self.get_topic_prefix(), + self.object_publisher = rospy.Publisher(self.get_topic_prefix() + + "/objects", ObjectArray, queue_size=10) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 7151e36c..62539b4c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -22,9 +22,11 @@ class TrafficLightsSensor(PseudoActor): a sensor that reports the state of all traffic lights """ - def __init__(self, parent, node, actor_list): + def __init__(self, name, parent, node, actor_list): """ Constructor + :param name: name identiying the sensor + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle @@ -35,18 +37,18 @@ def __init__(self, parent, node, actor_list): super(TrafficLightsSensor, self).__init__(parent=parent, node=node, - prefix="") + prefix="traffic_light/" + name) self.actor_list = actor_list self.traffic_light_status = CarlaTrafficLightStatusList() self.traffic_light_actors = [] self.traffic_lights_info_publisher = rospy.Publisher( - self.get_topic_prefix() + "traffic_lights_info", + self.get_topic_prefix() + "/traffic_lights_info", CarlaTrafficLightInfoList, queue_size=10, latch=True) self.traffic_lights_status_publisher = rospy.Publisher( - self.get_topic_prefix() + "traffic_lights", + self.get_topic_prefix() + "/traffic_lights", CarlaTrafficLightStatusList, queue_size=10, latch=True) From 50ba56de6339070b383480c2cfb1ef5fd190155a Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Tue, 10 Nov 2020 14:52:20 +0100 Subject: [PATCH 365/627] using services to spawn infrastructure sensors --- .../carla_infrastructure.py | 37 ++++++++++++++----- 1 file changed, 27 insertions(+), 10 deletions(-) diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 9e3a978e..9481bf5f 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -14,7 +14,12 @@ import os import json import rospy + +import carla_common.transforms as trans + +from diagnostic_msgs.msg import KeyValue from carla_msgs.msg import CarlaWorldInfo +from carla_msgs.srv import SpawnObject, SpawnObjectRequest import carla @@ -38,6 +43,9 @@ def __init__(self): self.world = None self.sensor_actors = [] + rospy.wait_for_service('/carla/spawn_object') + self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) + def restart(self): """ Spawns the infrastructure sensors @@ -79,19 +87,28 @@ def setup_sensors(self, sensors): sensor_spec['id'])) sensor_names.append(sensor_name) - sensor_location = carla.Location(x=sensor_spec.pop("x"), - y=sensor_spec.pop("y"), - z=sensor_spec.pop("z")) + sensor_location = carla.Location(x=sensor_spec.pop("x", 0.0), + y=sensor_spec.pop("y", 0.0), + z=sensor_spec.pop("z", 0.0)) sensor_rotation = carla.Rotation( pitch=sensor_spec.pop('pitch', 0.0), roll=sensor_spec.pop('roll', 0.0), yaw=sensor_spec.pop('yaw', 0.0)) sensor_transform = carla.Transform(sensor_location, sensor_rotation) - bp = bp_library.find(sensor_type) - bp.set_attribute('role_name', sensor_id) + spawn_object_request = SpawnObjectRequest() + spawn_object_request.type = sensor_type + spawn_object_request.id = sensor_id + spawn_object_request.attach_to = 0 + spawn_object_request.transform = trans.carla_transform_to_ros_pose( + sensor_transform) for attribute, value in sensor_spec.items(): - bp.set_attribute(str(attribute), str(value)) + spawn_object_request.attributes.append( + KeyValue(str(attribute), str(value))) + + response = self.spawn_object_service(spawn_object_request) + if response.id == -1: + raise Exception(response.error_string) except KeyError as e: rospy.logfatal( @@ -99,14 +116,14 @@ def setup_sensors(self, sensors): .format(e)) raise e - except IndexError as e: + except Exception as e: rospy.logfatal( "Sensor {} will not be spawned, {}".format(sensor_name, e)) raise e - # create sensor - sensor = self.world.spawn_actor(bp, sensor_transform) - actors.append(sensor) + if response.id > 0: + sensor = self.world.get_actor(response.id) + actors.append(sensor) return actors def destroy(self): From 2c449090e5984abae97f631ff74cbb508e2a3fec Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 11 Nov 2020 09:13:20 +0100 Subject: [PATCH 366/627] refactor code --- .../src/carla_ros_bridge/bridge.py | 57 ++++++++++--------- 1 file changed, 30 insertions(+), 27 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 2a9c54f5..d3d82865 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -186,7 +186,7 @@ def _spawn_actor(self, req): attach_to) return carla_actor.id - def _spawn_pseudo_sensor(self, req): + def _spawn_pseudo_actor(self, req): if req.attach_to != 0: if req.attach_to not in self.actors: raise IndexError("Parent object {} not found".format( @@ -195,35 +195,12 @@ def _spawn_pseudo_sensor(self, req): else: parent = None - if req.type == "sensor.pseudo.objects": - filtered_id = parent.carla_actor.id if parent is not None else None - pseudo_sensor = ObjectSensor( - name=req.id, - parent=parent, - node=self, - actor_list=self.actors, - filtered_id=filtered_id, - ) - - elif req.type == "sensor.pseudo.traffic_lights": - pseudo_sensor = TrafficLightsSensor( - name=req.id, - parent=parent, - node=self, - actor_list=self.actors, - ) - - with self.update_lock: - self.pseudo_actors.append(pseudo_sensor) - - rospy.loginfo("Created {}(parent_id={}, prefix={})".format( - pseudo_sensor.__class__.__name__, pseudo_sensor.get_parent_id(), - pseudo_sensor.get_prefix())) + self._create_pseudo_actor(req.type, req.id, parent) def spawn_object(self, req): try: - if req.type.startswith("sensor.pseudo"): - self._spawn_pseudo_sensor(req) + if "pseudo" in req.type: + self._spawn_pseudo_actor(req) return SpawnObjectResponse(0, "") else: @@ -449,6 +426,32 @@ def publish_actor_list(self): self.actor_list_publisher.publish(ros_actor_list) + def _create_pseudo_actor(self, type_id, name, parent): + if type_id == "sensor.pseudo.objects": + filtered_id = parent.carla_actor.id if parent is not None else None + pseudo_sensor = ObjectSensor( + name=name, + parent=parent, + node=self, + actor_list=self.actors, + filtered_id=filtered_id, + ) + + elif type_id == "sensor.pseudo.traffic_lights": + pseudo_sensor = TrafficLightsSensor( + name=name, + parent=parent, + node=self, + actor_list=self.actors, + ) + + with self.update_lock: + self.pseudo_actors.append(pseudo_sensor) + + rospy.loginfo("Created {}(parent_id={}, prefix={})".format( + pseudo_sensor.__class__.__name__, pseudo_sensor.get_parent_id(), + pseudo_sensor.get_prefix())) + def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-many-statements """ create an actor From b9c446bb15454549bcca5f96eec97d628b928b3d Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 11 Nov 2020 09:18:38 +0100 Subject: [PATCH 367/627] Added odometry pseudo sensor --- .../src/carla_ros_bridge/bridge.py | 6 +- .../src/carla_ros_bridge/odom_sensor.py | 55 +++++++++++++++++++ .../carla_ros_bridge/traffic_participant.py | 18 ------ 3 files changed, 60 insertions(+), 19 deletions(-) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index d3d82865..97f8aede 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -50,6 +50,7 @@ from carla_ros_bridge.walker import Walker from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor +from carla_ros_bridge.odom_sensor import OdometrySensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, SpawnObjectResponse @@ -427,7 +428,10 @@ def publish_actor_list(self): self.actor_list_publisher.publish(ros_actor_list) def _create_pseudo_actor(self, type_id, name, parent): - if type_id == "sensor.pseudo.objects": + if type_id == "sensor.pseudo.odom": + pseudo_sensor = OdometrySensor(name=name, parent=parent, node=self) + + elif type_id == "sensor.pseudo.objects": filtered_id = parent.carla_actor.id if parent is not None else None pseudo_sensor = ObjectSensor( name=name, diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py new file mode 100644 index 00000000..c22a6db2 --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -0,0 +1,55 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +handle a odom sensor +""" + +import rospy + +from carla_ros_bridge.pseudo_actor import PseudoActor + +from nav_msgs.msg import Odometry + + +class OdometrySensor(PseudoActor): + + """ + Pseudo odometry sensor + """ + + def __init__(self, name, parent, node): + """ + Constructor + :param name: name identiying the sensor + :type name: string + :param carla_world: carla world object + :type carla_world: carla.World + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + """ + + super(OdometrySensor, self).__init__(parent=parent, + node=node, + prefix='odometry/' + name) + + self.odometry_publisher = rospy.Publisher(self.get_topic_prefix() + + "/odometry", + Odometry, + queue_size=10) + + def update(self, frame, timestamp): + """ + Function (override) to update this object. + """ + odometry = Odometry(header=self.parent.get_msg_header("map")) + odometry.child_frame_id = self.parent.get_prefix() + odometry.pose.pose = self.parent.get_current_ros_pose() + odometry.twist.twist = self.parent.get_current_ros_twist_rotated() + self.odometry_publisher.publish(odometry) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index a1821201..a52a20d1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -13,7 +13,6 @@ import rospy from derived_object_msgs.msg import Object -from nav_msgs.msg import Odometry from shape_msgs.msg import SolidPrimitive from carla_ros_bridge.actor import Actor @@ -44,11 +43,6 @@ def __init__(self, carla_actor, parent, node, prefix): node=node, prefix=prefix) - self.odometry_publisher = rospy.Publisher(self.get_topic_prefix() + - "/odometry", - Odometry, - queue_size=10) - def update(self, frame, timestamp): """ Function (override) to update this object. @@ -63,21 +57,9 @@ def update(self, frame, timestamp): self.classification_age += 1 self.publish_transform(self.get_ros_transform(None, None, str(self.get_id()))) self.publish_marker() - self.send_odometry() super(TrafficParticipant, self).update(frame, timestamp) - def send_odometry(self): - """ - Sends odometry - :return: - """ - odometry = Odometry(header=self.get_msg_header("map")) - odometry.child_frame_id = self.get_prefix() - odometry.pose.pose = self.get_current_ros_pose() - odometry.twist.twist = self.get_current_ros_twist_rotated() - self.odometry_publisher.publish(odometry) - def get_object_info(self): """ Function to send object messages of this traffic participant. From 0726fe853790425e51029ec7634a50e83476f2a5 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 11 Nov 2020 09:42:34 +0100 Subject: [PATCH 368/627] Added tf pseudo sensor --- .../src/carla_ros_bridge/bridge.py | 6 ++- .../src/carla_ros_bridge/ego_vehicle.py | 4 -- .../src/carla_ros_bridge/tf_sensor.py | 48 +++++++++++++++++++ .../carla_ros_bridge/traffic_participant.py | 1 - 4 files changed, 53 insertions(+), 6 deletions(-) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 97f8aede..c8771070 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -51,6 +51,7 @@ from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_ros_bridge.odom_sensor import OdometrySensor +from carla_ros_bridge.tf_sensor import TFSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, SpawnObjectResponse @@ -428,7 +429,10 @@ def publish_actor_list(self): self.actor_list_publisher.publish(ros_actor_list) def _create_pseudo_actor(self, type_id, name, parent): - if type_id == "sensor.pseudo.odom": + if type_id == "sensor.pseudo.tf": + pseudo_sensor = TFSensor(name=name, parent=parent, node=self) + + elif type_id == "sensor.pseudo.odom": pseudo_sensor = OdometrySensor(name=name, parent=parent, node=self) elif type_id == "sensor.pseudo.objects": diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 8ab8525c..d9808adf 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -175,10 +175,6 @@ def update(self, frame, timestamp): """ self.send_vehicle_msgs() super(EgoVehicle, self).update(frame, timestamp) - no_rotation = Transform() - no_rotation.rotation.w = 1.0 - self.publish_transform(self.get_ros_transform( - no_rotation, frame_id=str(self.get_id()), child_frame_id=self.get_prefix())) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py new file mode 100644 index 00000000..1fbdd389 --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -0,0 +1,48 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +handle a tf sensor +""" + +import rospy + +from carla_ros_bridge.pseudo_actor import PseudoActor + +from tf2_msgs.msg import TFMessage + + +class TFSensor(PseudoActor): + + """ + Pseudo tf sensor + """ + + def __init__(self, name, parent, node): + """ + Constructor + :param name: name identiying the sensor + :type name: string + :param carla_world: carla world object + :type carla_world: carla.World + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + """ + + super(TFSensor, self).__init__(parent=parent, node=node, prefix=None) + + self.tf_publisher = rospy.Publisher('tf', TFMessage, queue_size=100) + + def update(self, frame, timestamp): + """ + Function (override) to update this object. + """ + tf_to_publish = [self.parent.get_ros_transform()] + tf_msg = TFMessage(tf_to_publish) + self.tf_publisher.publish(tf_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index a52a20d1..39c006e1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -55,7 +55,6 @@ def update(self, frame, timestamp): :return: """ self.classification_age += 1 - self.publish_transform(self.get_ros_transform(None, None, str(self.get_id()))) self.publish_marker() super(TrafficParticipant, self).update(frame, timestamp) From cca4cc6a53b5d3cb7dc1d86f2cea43730f30ecc1 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 11 Nov 2020 12:42:57 +0100 Subject: [PATCH 369/627] marker pseudo sensor added --- .../src/carla_ros_bridge/actor.py | 45 ------------ .../src/carla_ros_bridge/bridge.py | 11 +-- .../src/carla_ros_bridge/marker_sensor.py | 70 +++++++++++++++++++ .../src/carla_ros_bridge/tf_sensor.py | 14 ++-- .../carla_ros_bridge/traffic_participant.py | 43 +++++++++++- 5 files changed, 127 insertions(+), 56 deletions(-) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 35ce9f8b..911a2b50 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -12,8 +12,6 @@ import numpy as np from geometry_msgs.msg import TransformStamped -from std_msgs.msg import ColorRGBA -from visualization_msgs.msg import Marker from carla_ros_bridge.pseudo_actor import PseudoActor import carla_common.transforms as trans @@ -135,46 +133,3 @@ def publish_transform(self, ros_transform_msg): :return: """ self.node.publish_tf_message(ros_transform_msg) - - def get_marker_color(self): # pylint: disable=no-self-use - """ - Function (override) to return the color for marker messages. - - :return: the color used by a walkers marker - :rtpye : std_msgs.msg.ColorRGBA - """ - color = ColorRGBA() - color.r = 0 - color.g = 0 - color.b = 255 - return color - - def get_marker(self): - """ - Helper function to create a ROS visualization_msgs.msg.Marker for the actor - - :return: - visualization_msgs.msg.Marker - """ - marker = Marker( - header=self.get_msg_header(frame_id=str(self.get_id()))) - marker.color = self.get_marker_color() - marker.color.a = 0.3 - marker.id = self.get_id() - return marker - - def publish_marker(self): - """ - Function to send marker messages of this walker. - - :return: - """ - marker = self.get_marker() - marker.type = Marker.CUBE - - marker.pose = trans.carla_location_to_pose( - self.carla_actor.bounding_box.location) - marker.scale.x = self.carla_actor.bounding_box.extent.x * 2.0 - marker.scale.y = self.carla_actor.bounding_box.extent.y * 2.0 - marker.scale.z = self.carla_actor.bounding_box.extent.z * 2.0 - self.node.marker_publisher.publish(marker) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index c8771070..ad014314 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -23,7 +23,6 @@ from rosgraph_msgs.msg import Clock from tf2_msgs.msg import TFMessage -from visualization_msgs.msg import Marker import carla @@ -52,6 +51,7 @@ from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_ros_bridge.odom_sensor import OdometrySensor from carla_ros_bridge.tf_sensor import TFSensor +from carla_ros_bridge.marker_sensor import MarkerSensor from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, SpawnObjectResponse @@ -104,9 +104,6 @@ def __init__(self, carla_world, params): # Communication topics self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10) self.tf_publisher = rospy.Publisher('tf', TFMessage, queue_size=100) - self.marker_publisher = rospy.Publisher('/carla/marker', - Marker, - queue_size=10) self.actor_list_publisher = rospy.Publisher('/carla/actor_list', CarlaActorList, queue_size=10, @@ -435,6 +432,12 @@ def _create_pseudo_actor(self, type_id, name, parent): elif type_id == "sensor.pseudo.odom": pseudo_sensor = OdometrySensor(name=name, parent=parent, node=self) + elif type_id == "sensor.pseudo.markers": + pseudo_sensor = MarkerSensor(name=name, + parent=parent, + node=self, + actor_list=self.actors) + elif type_id == "sensor.pseudo.objects": filtered_id = parent.carla_actor.id if parent is not None else None pseudo_sensor = ObjectSensor( diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py new file mode 100644 index 00000000..d32af6b8 --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -0,0 +1,70 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +handle a marker sensor +""" + +import rospy + +from carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.traffic_participant import TrafficParticipant + +from visualization_msgs.msg import MarkerArray + + +class MarkerSensor(PseudoActor): + + """ + Pseudo marker sensor + """ + + def __init__(self, name, parent, node, actor_list): + """ + Constructor + :param name: name identiying the sensor + :type name: string + :param carla_world: carla world object + :type carla_world: carla.World + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + :param actor_list: current list of actors + :type actor_list: map(carla-actor-id -> python-actor-object) + """ + + super(MarkerSensor, self).__init__(parent=parent, + node=node, + prefix='markers/' + name) + self.actor_list = actor_list + + self.marker_publisher = rospy.Publisher(self.get_topic_prefix() + + "/marker_array", + MarkerArray, + queue_size=10) + + def destroy(self): + """ + Function to destroy this object. + :return: + """ + self.actor_list = None + super(MarkerSensor, self).destroy() + + def update(self, frame, timestamp): + """ + Function (override) to update this object. + On update map sends: + - tf global frame + :return: + """ + marker_array_msg = MarkerArray() + for actor in self.actor_list.values(): + if isinstance(actor, TrafficParticipant): + marker_array_msg.markers.append(actor.get_marker()) + self.marker_publisher.publish(marker_array_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 1fbdd389..d346b767 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -13,7 +13,7 @@ from carla_ros_bridge.pseudo_actor import PseudoActor -from tf2_msgs.msg import TFMessage +import tf class TFSensor(PseudoActor): @@ -37,12 +37,16 @@ def __init__(self, name, parent, node): super(TFSensor, self).__init__(parent=parent, node=node, prefix=None) - self.tf_publisher = rospy.Publisher('tf', TFMessage, queue_size=100) + self.tf_broadcaster = tf.TransformBroadcaster() def update(self, frame, timestamp): """ Function (override) to update this object. """ - tf_to_publish = [self.parent.get_ros_transform()] - tf_msg = TFMessage(tf_to_publish) - self.tf_publisher.publish(tf_msg) + pose = self.parent.get_current_ros_pose() + position = pose.position + orientation = pose.orientation + self.tf_broadcaster.sendTransform( + (position.x, position.y, position.z), + (orientation.x, orientation.y, orientation.z, orientation.w), + rospy.Time.now(), self.parent.get_prefix(), "map") diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 39c006e1..efa46e57 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -14,8 +14,11 @@ from derived_object_msgs.msg import Object from shape_msgs.msg import SolidPrimitive +from std_msgs.msg import ColorRGBA +from visualization_msgs.msg import Marker from carla_ros_bridge.actor import Actor +import carla_common.transforms as trans class TrafficParticipant(Actor): @@ -55,8 +58,6 @@ def update(self, frame, timestamp): :return: """ self.classification_age += 1 - self.publish_marker() - super(TrafficParticipant, self).update(frame, timestamp) def get_object_info(self): @@ -97,3 +98,41 @@ def get_classification(self): # pylint: disable=no-self-use Function to get object classification (overridden in subclasses) """ return Object.CLASSIFICATION_UNKNOWN + + def get_marker_color(self): # pylint: disable=no-self-use + """ + Function (override) to return the color for marker messages. + + :return: the color used by a walkers marker + :rtpye : std_msgs.msg.ColorRGBA + """ + color = ColorRGBA() + color.r = 0 + color.g = 0 + color.b = 255 + return color + + def get_marker(self): + """ + Helper function to create a ROS visualization_msgs.msg.Marker for the actor + + :return: + visualization_msgs.msg.Marker + """ + # marker = Marker( + # header=self.get_msg_header(frame_id=str(self.get_id()))) + marker = Marker( + header=self.get_msg_header(frame_id="map")) + marker.color = self.get_marker_color() + marker.color.a = 0.3 + marker.id = self.get_id() + marker.type = Marker.CUBE + + # marker.pose = trans.carla_location_to_pose( + # self.carla_actor.bounding_box.location) + marker.pose = trans.carla_transform_to_ros_pose( + self.carla_actor.get_transform()) + marker.scale.x = self.carla_actor.bounding_box.extent.x * 2.0 + marker.scale.y = self.carla_actor.bounding_box.extent.y * 2.0 + marker.scale.z = self.carla_actor.bounding_box.extent.z * 2.0 + return marker From a221298b3c53f630fd51b05402fe9451d2a98f21 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 11 Nov 2020 16:34:11 +0100 Subject: [PATCH 370/627] ActorList, Speedometer and OpenDrive pseudo sensors added --- .../src/carla_ros_bridge/actor_list_sensor.py | 79 +++++++++++++++++++ .../src/carla_ros_bridge/bridge.py | 57 ++++++------- .../src/carla_ros_bridge/opendrive_sensor.py | 57 +++++++++++++ .../carla_ros_bridge/speedometer_sensor.py | 65 +++++++++++++++ 4 files changed, 223 insertions(+), 35 deletions(-) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py create mode 100644 carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py create mode 100644 carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py new file mode 100644 index 00000000..daca3a2b --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -0,0 +1,79 @@ +#!/usr/bin/env python +# +# Copyright (c) 2019 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +handle a actor list sensor +""" + +import rospy + +from carla_ros_bridge.pseudo_actor import PseudoActor +from carla_msgs.msg import CarlaActorList, CarlaActorInfo + + +class ActorListSensor(PseudoActor): + + """ + Pseudo actor list sensor + """ + + def __init__(self, name, parent, node, actor_list): + """ + Constructor + :param name: name identiying the sensor + :type name: string + :param carla_world: carla world object + :type carla_world: carla.World + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + :param actor_list: current list of actors + :type actor_list: map(carla-actor-id -> python-actor-object) + """ + + super(ActorListSensor, self).__init__(parent=parent, + node=node, + prefix='actor_list/' + name) + self.actor_list = actor_list + self.actor_list_publisher = rospy.Publisher(self.get_topic_prefix() + + "actor_list", + CarlaActorList, + queue_size=10) + + def destroy(self): + """ + Function to destroy this object. + :return: + """ + self.actor_list = None + super(ActorListSensor, self).destroy() + + def update(self, frame, timestamp): + """ + Function (override) to update this object. + """ + ros_actor_list = CarlaActorList() + + for actor_id in self.actor_list.keys(): + actor = self.actor_list[actor_id].carla_actor + ros_actor = CarlaActorInfo() + ros_actor.id = actor.id + ros_actor.type = actor.type_id + try: + ros_actor.rolename = str(actor.attributes.get('role_name')) + except ValueError: + pass + + if actor.parent: + ros_actor.parent_id = actor.parent.id + else: + ros_actor.parent_id = 0 + + ros_actor_list.actors.append(ros_actor) + + self.actor_list_publisher.publish(ros_actor_list) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index ad014314..40536cad 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -50,10 +50,13 @@ from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_ros_bridge.odom_sensor import OdometrySensor +from carla_ros_bridge.speedometer_sensor import SpeedometerSensor from carla_ros_bridge.tf_sensor import TFSensor from carla_ros_bridge.marker_sensor import MarkerSensor +from carla_ros_bridge.actor_list_sensor import ActorListSensor +from carla_ros_bridge.opendrive_sensor import OpenDriveSensor -from carla_msgs.msg import CarlaActorList, CarlaActorInfo, CarlaControl, CarlaWeatherParameters +from carla_msgs.msg import CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, SpawnObjectResponse @@ -104,10 +107,6 @@ def __init__(self, carla_world, params): # Communication topics self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10) self.tf_publisher = rospy.Publisher('tf', TFMessage, queue_size=100) - self.actor_list_publisher = rospy.Publisher('/carla/actor_list', - CarlaActorList, - queue_size=10, - latch=True) self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode, @@ -395,36 +394,6 @@ def _update_actors(self, current_actors): updated_pseudo_actors.append(pseudo_actor) self.pseudo_actors = updated_pseudo_actors - # publish actor list on change - if new_actors or deleted_actors: - self.publish_actor_list() - - def publish_actor_list(self): - """ - publish list of carla actors - :return: - """ - ros_actor_list = CarlaActorList() - - for actor_id in self.actors: - actor = self.actors[actor_id].carla_actor - ros_actor = CarlaActorInfo() - ros_actor.id = actor.id - ros_actor.type = actor.type_id - try: - ros_actor.rolename = str(actor.attributes.get('role_name')) - except ValueError: - pass - - if actor.parent: - ros_actor.parent_id = actor.parent.id - else: - ros_actor.parent_id = 0 - - ros_actor_list.actors.append(ros_actor) - - self.actor_list_publisher.publish(ros_actor_list) - def _create_pseudo_actor(self, type_id, name, parent): if type_id == "sensor.pseudo.tf": pseudo_sensor = TFSensor(name=name, parent=parent, node=self) @@ -432,12 +401,23 @@ def _create_pseudo_actor(self, type_id, name, parent): elif type_id == "sensor.pseudo.odom": pseudo_sensor = OdometrySensor(name=name, parent=parent, node=self) + elif type_id == "sensor.pseudo.speedometer": + pseudo_sensor = SpeedometerSensor(name=name, + parent=parent, + node=self) + elif type_id == "sensor.pseudo.markers": pseudo_sensor = MarkerSensor(name=name, parent=parent, node=self, actor_list=self.actors) + elif type_id == "sensor.pseudo.actor_list": + pseudo_sensor = ActorListSensor(name=name, + parent=parent, + node=self, + actor_list=self.actors) + elif type_id == "sensor.pseudo.objects": filtered_id = parent.carla_actor.id if parent is not None else None pseudo_sensor = ObjectSensor( @@ -456,6 +436,13 @@ def _create_pseudo_actor(self, type_id, name, parent): actor_list=self.actors, ) + elif type_id == "sensor.pseudo.opendrive_map": + pseudo_sensor = OpenDriveSensor( + name=name, + parent=parent, + node=self, + carla_map=self.carla_world.get_map()) + with self.update_lock: self.pseudo_actors.append(pseudo_sensor) diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py new file mode 100644 index 00000000..d4f83485 --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -0,0 +1,57 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +handle a opendrive sensor +""" + +import rospy +import numpy as np + +from carla_ros_bridge.pseudo_actor import PseudoActor + +from std_msgs.msg import String + + +class OpenDriveSensor(PseudoActor): + + """ + Pseudo opendrive sensor + """ + + def __init__(self, name, parent, node, carla_map): + """ + Constructor + :param name: name identiying the sensor + :type name: string + :param carla_world: carla world object + :type carla_world: carla.World + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + :param carla_map: carla map object + :type carla_map: carla.Map + """ + super(OpenDriveSensor, self).__init__(parent=parent, + node=node, + prefix='opendrive/' + name) + + self.carla_map = carla_map + self._map_published = False + self.map_publisher = rospy.Publisher(self.get_topic_prefix() + "/map", + String, + queue_size=10, + latch=True) + + def update(self, frame, timestamp): + """ + Function (override) to update this object. + """ + if not self._map_published: + self.map_publisher.publish(String(self.carla_map.to_opendrive())) + self._map_published = True diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py new file mode 100644 index 00000000..6f33820f --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -0,0 +1,65 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +handle a speedometer sensor +""" + +import rospy +import numpy as np + +from carla_ros_bridge.pseudo_actor import PseudoActor + +from std_msgs.msg import Float32 + + +class SpeedometerSensor(PseudoActor): + + """ + Pseudo speedometer sensor + """ + + def __init__(self, name, parent, node): + """ + Constructor + :param name: name identiying the sensor + :type name: string + :param carla_world: carla world object + :type carla_world: carla.World + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + """ + + super(SpeedometerSensor, self).__init__(parent=parent, + node=node, + prefix='speedometer/' + name) + + self.speedometer_publisher = rospy.Publisher(self.get_topic_prefix() + + "/speedometer", + Float32, + queue_size=10) + + def update(self, frame, timestamp): + """ + Function (override) to update this object. + """ + velocity = self.parent.carla_actor.get_velocity() + transform = self.parent.carla_actor.get_transform() + + vel_np = np.array([velocity.x, velocity.y, velocity.z]) + pitch = np.deg2rad(transform.rotation.pitch) + yaw = np.deg2rad(transform.rotation.yaw) + orientation = np.array([ + np.cos(pitch) * np.cos(yaw), + np.cos(pitch) * np.sin(yaw), + np.sin(pitch) + ]) + speed = np.dot(vel_np, orientation) + + self.speedometer_publisher.publish(Float32(speed)) From a0ff1c884d9c98abf0b87e8a0dbed6a27f25f7e3 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Thu, 12 Nov 2020 17:11:30 +0100 Subject: [PATCH 371/627] move format check to github actions --- .github/workflows/ci.yml | 19 +++++++++++++++++++ .travis.yml | 7 ------- 2 files changed, 19 insertions(+), 7 deletions(-) create mode 100644 .github/workflows/ci.yml diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml new file mode 100644 index 00000000..6cd2bda7 --- /dev/null +++ b/.github/workflows/ci.yml @@ -0,0 +1,19 @@ +name: CI + +on: [push, pull_request] + +jobs: + check: + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v2 + - name: Set up Python 3.8 + uses: actions/setup-python@v1 + with: + python-version: 3.8 + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install -r requirements.txt + - name: Check + run: make check_format diff --git a/.travis.yml b/.travis.yml index eaf1fb28..c8d75d66 100644 --- a/.travis.yml +++ b/.travis.yml @@ -8,7 +8,6 @@ os: linux stages: - - check - test - docker @@ -22,12 +21,6 @@ addons: jobs: include: - - name: "Check code formatting" - stage: check - before_install: skip - install: pip install --user -r requirements.txt - script: - - make check_format - name: "Xenial Kinetic" stage: test dist: xenial From eb2bd83d3298cbd98c934930c770684d87a89a68 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Thu, 12 Nov 2020 17:25:21 +0100 Subject: [PATCH 372/627] add badges to readme --- README.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/README.md b/README.md index 06b28e95..3a19b9cb 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,10 @@ # ROS bridge for CARLA simulator +[![Actions Status](https://github.com/carla-simulator/ros-bridge/workflows/CI/badge.svg)](https://github.com/carla-simulator/ros-bridge) +[![Build Status](https://travis-ci.com/carla-simulator/ros-bridge.svg?branch=master)](https://travis-ci.com/carla-simulator/ros-bridge) +[![GitHub](https://img.shields.io/github/license/carla-simulator/ros-bridge)](https://github.com/carla-simulator/ros-bridge/blob/master/LICENSE) +[![GitHub release (latest by date)](https://img.shields.io/github/v/release/carla-simulator/ros-bridge)](https://github.com/carla-simulator/ros-bridge/releases/latest) + This ROS package aims at providing a simple ROS bridge for CARLA simulator. ![rviz setup](./docs/images/ad_demo.png "AD Demo") From 704f209819afa4b95d28f5ef251efc7a6553a899 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Sun, 15 Nov 2020 21:02:27 +0100 Subject: [PATCH 373/627] reworked actor management * Added unique identifier to pseudo sensors. * Actor discovery moved to ActorFactory --- .../src/carla_ros_bridge/actor.py | 11 +- .../src/carla_ros_bridge/actor_factory.py | 257 ++++++++++++ .../src/carla_ros_bridge/actor_list_sensor.py | 15 +- .../src/carla_ros_bridge/bridge.py | 365 +++--------------- .../src/carla_ros_bridge/camera.py | 35 +- .../src/carla_ros_bridge/collision_sensor.py | 7 +- .../src/carla_ros_bridge/ego_vehicle.py | 7 +- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 7 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 7 +- .../carla_ros_bridge/lane_invasion_sensor.py | 7 +- .../src/carla_ros_bridge/lidar.py | 14 +- .../src/carla_ros_bridge/marker_sensor.py | 8 +- .../src/carla_ros_bridge/object_sensor.py | 13 +- .../src/carla_ros_bridge/odom_sensor.py | 8 +- .../src/carla_ros_bridge/opendrive_sensor.py | 8 +- .../src/carla_ros_bridge/pseudo_actor.py | 11 +- .../src/carla_ros_bridge/radar.py | 8 +- .../src/carla_ros_bridge/rss_sensor.py | 7 +- .../src/carla_ros_bridge/sensor.py | 6 +- .../src/carla_ros_bridge/spectator.py | 7 +- .../carla_ros_bridge/speedometer_sensor.py | 8 +- .../src/carla_ros_bridge/tf_sensor.py | 10 +- .../src/carla_ros_bridge/traffic.py | 14 +- .../carla_ros_bridge/traffic_lights_sensor.py | 9 +- .../carla_ros_bridge/traffic_participant.py | 7 +- .../src/carla_ros_bridge/vehicle.py | 7 +- .../src/carla_ros_bridge/walker.py | 7 +- .../src/carla_ros_bridge/world_info.py | 3 +- 28 files changed, 496 insertions(+), 377 deletions(-) create mode 100755 carla_ros_bridge/src/carla_ros_bridge/actor_factory.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 911a2b50..f6d63b67 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -23,9 +23,12 @@ class Actor(PseudoActor): Generic base class for all carla actors """ - def __init__(self, carla_actor, parent, node, prefix=None): + def __init__(self, uid, carla_actor, parent, node, prefix=None): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla vehicle actor object :type carla_actor: carla.Vehicle :param parent: the parent of this @@ -35,12 +38,8 @@ def __init__(self, carla_actor, parent, node, prefix=None): :param prefix: the topic prefix to be used for this actor :type prefix: string """ - super(Actor, self).__init__(parent=parent, prefix=prefix, node=node) + super(Actor, self).__init__(uid=uid, parent=parent, prefix=prefix, node=node) self.carla_actor = carla_actor - - if carla_actor.id > np.iinfo(np.uint32).max: - raise ValueError("Actor ID exceeds maximum supported value '{}'".format(carla_actor.id)) - self.carla_actor_id = carla_actor.id def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py new file mode 100755 index 00000000..a927a54e --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -0,0 +1,257 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +import rospy + +try: + import queue +except ImportError: + import Queue as queue + +from threading import Thread, Lock +import itertools + +import carla + +import carla_common.transforms as trans + +from carla_ros_bridge.actor import Actor +from carla_ros_bridge.spectator import Spectator +from carla_ros_bridge.traffic import Traffic, TrafficLight +from carla_ros_bridge.vehicle import Vehicle +from carla_ros_bridge.lidar import Lidar, SemanticLidar +from carla_ros_bridge.radar import Radar +from carla_ros_bridge.gnss import Gnss +from carla_ros_bridge.imu import ImuSensor +from carla_ros_bridge.ego_vehicle import EgoVehicle +from carla_ros_bridge.collision_sensor import CollisionSensor +from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor +from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera +from carla_ros_bridge.object_sensor import ObjectSensor +from carla_ros_bridge.rss_sensor import RssSensor +from carla_ros_bridge.walker import Walker +from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor +from carla_ros_bridge.odom_sensor import OdometrySensor +from carla_ros_bridge.speedometer_sensor import SpeedometerSensor +from carla_ros_bridge.tf_sensor import TFSensor +from carla_ros_bridge.marker_sensor import MarkerSensor +from carla_ros_bridge.actor_list_sensor import ActorListSensor +from carla_ros_bridge.opendrive_sensor import OpenDriveSensor + + +class ActorFactory(object): + def __init__(self, node, world, sync_mode=False): + self.node = node + self.world = world + self.sync_mode = sync_mode + + self.actors = {} + + self.lock = Lock() + self.spawn_lock = Lock() + + # id generator for pseudo sensors + self.id_gen = itertools.count(10000) + + def start(self): + # create initially existing actors + self.update() + + self.thread = Thread(target=self._update_thread) + self.thread.start() + + def _update_thread(self): + """ + execution loop for async mode actor discovery + """ + while not self.node.shutdown.is_set(): + if self.node.on_carla_tick.wait(1): + with self.spawn_lock: + self.update() + self.node.on_carla_tick.clear() + + def update(self): + """ + update the available actors + """ + # get only carla actors + previous_actors = set([x.uid for x in self.actors.values() if isinstance(x, Actor)]) + current_actors = set([x.id for x in self.world.get_actors()]) + + new_actors = current_actors - previous_actors + for carla_actor in self.world.get_actors(list(new_actors)): + self._create_carla_actor(carla_actor) + + for actor_id, actor in self.actors.items(): + if isinstance(actor, Actor): + if self.world.get_actor(actor_id) is None: + self.destroy(actor_id) + + def clear(self): + ids = self.actors.keys() + for id_ in ids: + self.destroy(id_) + + def _create_carla_actor(self, carla_actor): + parent = None + if carla_actor.parent: + if carla_actor.parent.id in self.actors: + parent = self.actors[carla_actor.parent.id] + else: + parent = self._create_carla_actor(carla_actor.parent) + + parent_id = 0 + if parent is not None: + parent_id = parent.uid + + return self.create(carla_actor.type_id, carla_actor.attributes.get("rolename", ""), + parent_id, carla_actor) + + def create(self, type_id, name, attach_to, carla_actor=None): + with self.lock: + # check that the actor is not already created. + if carla_actor is not None and carla_actor.id in self.actors: + return None + + if attach_to != 0: + if attach_to not in self.actors: + raise IndexError("Parent object {} not found".format(attach_to)) + parent = self.actors[attach_to] + else: + parent = None + + if carla_actor is not None: + uid = carla_actor.id + else: + uid = next(self.id_gen) + + actor = self._create_object(uid, type_id, name, parent, carla_actor) + self.actors[actor.uid] = actor + + rospy.loginfo("Created {}(id={})".format(actor.__class__.__name__, actor.uid)) + + return actor + + def destroy(self, actor_id): + # remove actors that have the actor to be removed as parent. + for actor in self.actors.values(): + if actor.parent is not None and actor.parent.uid == actor_id: + self.destroy(actor.uid) + + with self.lock: + # check that the actor is not already removed. + if actor_id not in self.actors: + return + + actor = self.actors.pop(actor_id) + actor.destroy() + + rospy.loginfo("Removed {}(id={})".format(actor.__class__.__name__, actor.uid)) + + def _create_object(self, uid, type_id, name, parent, carla_actor=None): + + if type_id == "sensor.pseudo.tf": + actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) + + elif type_id == "sensor.pseudo.odom": + actor = OdometrySensor(uid=uid, name=name, parent=parent, node=self.node) + + elif type_id == "sensor.pseudo.speedometer": + actor = SpeedometerSensor(uid=uid, name=name, parent=parent, node=self.node) + + elif type_id == "sensor.pseudo.markers": + actor = MarkerSensor(uid=uid, + name=name, + parent=parent, + node=self.node, + actor_list=self.actors) + + elif type_id == "sensor.pseudo.actor_list": + actor = ActorListSensor(uid=uid, + name=name, + parent=parent, + node=self.node, + actor_list=self.actors) + + elif type_id == "sensor.pseudo.objects": + actor = ObjectSensor( + uid=uid, + name=name, + parent=parent, + node=self.node, + actor_list=self.actors, + ) + + elif type_id == "sensor.pseudo.traffic_lights": + actor = TrafficLightsSensor( + uid=uid, + name=name, + parent=parent, + node=self.node, + actor_list=self.actors, + ) + + elif type_id == "sensor.pseudo.opendrive_map": + actor = OpenDriveSensor(uid=uid, + name=name, + parent=parent, + node=self.node, + carla_map=self.world.get_map()) + + elif carla_actor.type_id.startswith('traffic'): + if carla_actor.type_id == "traffic.traffic_light": + actor = TrafficLight(uid, carla_actor, parent, node=self.node) + else: + actor = Traffic(uid, carla_actor, parent, node=self.node) + elif carla_actor.type_id.startswith("vehicle"): + if carla_actor.attributes.get('role_name')\ + in self.node.parameters['ego_vehicle']['role_name']: + actor = EgoVehicle(uid, carla_actor, parent, self.node, + self.node._ego_vehicle_control_applied_callback) + else: + actor = Vehicle(uid, carla_actor, parent, self.node) + elif carla_actor.type_id.startswith("sensor"): + if carla_actor.type_id.startswith("sensor.camera"): + if carla_actor.type_id.startswith("sensor.camera.rgb"): + actor = RgbCamera(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.camera.depth"): + actor = DepthCamera(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.camera.semantic_segmentation"): + actor = SemanticSegmentationCamera(uid, carla_actor, parent, self.node, + self.sync_mode) + elif carla_actor.type_id.startswith("sensor.camera.dvs"): + actor = DVSCamera(uid, carla_actor, parent, self.node, self.sync_mode) + else: + actor = Camera(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.lidar"): + if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): + actor = Lidar(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.endswith("sensor.lidar.ray_cast_semantic"): + actor = SemanticLidar(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.radar"): + actor = Radar(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.gnss"): + actor = Gnss(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.imu"): + actor = ImuSensor(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.collision"): + actor = CollisionSensor(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.rss"): + actor = RssSensor(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): + actor = LaneInvasionSensor(uid, carla_actor, parent, self.node, self.sync_mode) + else: + actor = Sensor(uid, carla_actor, parent, self.node, self.sync_mode) + elif carla_actor.type_id.startswith("spectator"): + actor = Spectator(uid, carla_actor, parent, self.node) + elif carla_actor.type_id.startswith("walker"): + actor = Walker(uid, carla_actor, parent, self.node) + else: + actor = Actor(uid, carla_actor, parent, self.node) + + return actor diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py index daca3a2b..ab3a6a24 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -11,6 +11,7 @@ import rospy +from carla_ros_bridge.actor import Actor from carla_ros_bridge.pseudo_actor import PseudoActor from carla_msgs.msg import CarlaActorList, CarlaActorInfo @@ -21,9 +22,11 @@ class ActorListSensor(PseudoActor): Pseudo actor list sensor """ - def __init__(self, name, parent, node, actor_list): + def __init__(self, uid, name, parent, node, actor_list): """ Constructor + :param uid: unique identifier for this object. + :type uid: int :param name: name identiying the sensor :type name: string :param carla_world: carla world object @@ -36,9 +39,10 @@ def __init__(self, name, parent, node, actor_list): :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(ActorListSensor, self).__init__(parent=parent, - node=node, - prefix='actor_list/' + name) + super(ActorListSensor, self).__init__(uid, + parent=parent, + node=node, + prefix='actor_list/' + name) self.actor_list = actor_list self.actor_list_publisher = rospy.Publisher(self.get_topic_prefix() + "actor_list", @@ -60,6 +64,9 @@ def update(self, frame, timestamp): ros_actor_list = CarlaActorList() for actor_id in self.actor_list.keys(): + if not isinstance(self.actor_list[actor_id], Actor): + continue + actor = self.actor_list[actor_id].carla_actor ros_actor = CarlaActorInfo() ros_actor.id = actor.id diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 40536cad..5481b90a 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -28,33 +28,11 @@ import carla_common.transforms as trans -from carla_ros_bridge.actor import Actor -from carla_ros_bridge.sensor import Sensor +from carla_ros_bridge.actor_factory import ActorFactory from carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher -from carla_ros_bridge.world_info import WorldInfo -from carla_ros_bridge.spectator import Spectator -from carla_ros_bridge.traffic import Traffic, TrafficLight -from carla_ros_bridge.vehicle import Vehicle -from carla_ros_bridge.lidar import Lidar, SemanticLidar -from carla_ros_bridge.radar import Radar -from carla_ros_bridge.gnss import Gnss -from carla_ros_bridge.imu import ImuSensor -from carla_ros_bridge.ego_vehicle import EgoVehicle -from carla_ros_bridge.collision_sensor import CollisionSensor -from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera -from carla_ros_bridge.object_sensor import ObjectSensor -from carla_ros_bridge.rss_sensor import RssSensor -from carla_ros_bridge.walker import Walker from carla_ros_bridge.debug_helper import DebugHelper -from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor -from carla_ros_bridge.odom_sensor import OdometrySensor -from carla_ros_bridge.speedometer_sensor import SpeedometerSensor -from carla_ros_bridge.tf_sensor import TFSensor -from carla_ros_bridge.marker_sensor import MarkerSensor -from carla_ros_bridge.actor_list_sensor import ActorListSensor -from carla_ros_bridge.opendrive_sensor import OpenDriveSensor +from carla_ros_bridge.world_info import WorldInfo from carla_msgs.msg import CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, SpawnObjectResponse @@ -78,12 +56,11 @@ def __init__(self, carla_world, params): :type params: dict """ self.parameters = params - self.actors = {} - self.pseudo_actors = [] self.carla_world = carla_world self.synchronous_mode_update_thread = None self.shutdown = Event() + # set carla world settings self.carla_settings = carla_world.get_settings() @@ -100,10 +77,16 @@ def __init__(self, carla_world, params): self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) - self.update_lock = Lock() - self.carla_control_queue = queue.Queue() + # actor factory + self.actor_factory = ActorFactory(self, carla_world, self.carla_settings.synchronous_mode) + + # add world info + self.world_info = WorldInfo(carla_world=self.carla_world, node=self) + # add debug helper + self.debug_helper = DebugHelper(carla_world.debug) + # Communication topics self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10) self.tf_publisher = rospy.Publisher('tf', TFMessage, queue_size=100) @@ -136,19 +119,8 @@ def __init__(self, carla_world, params): else: self.timestamp_last_run = 0.0 - self.update_actors_queue = queue.Queue(maxsize=1) - - # start thread to update actors - self.update_actor_thread = Thread( - target=self._update_actors_thread) - self.update_actor_thread.start() - - # create initially existing actors - self.update_actors_queue.put( - set([x.id for x in self.carla_world.get_snapshot()])) - - # wait for first actors creation to be finished - self.update_actors_queue.join() + self.on_carla_tick = Event() + self.actor_factory.start() # register callback to update actors self.on_tick_id = self.carla_world.on_tick(self._carla_time_tick) @@ -157,14 +129,6 @@ def __init__(self, carla_world, params): rospy.Subscriber("/carla/weather_control", CarlaWeatherParameters, self.on_weather_changed) - # add world info - self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, - node=self)) - - # add debug helper - self.debug_helper = DebugHelper(carla_world.debug) - - def _spawn_actor(self, req): blueprint = self.carla_world.get_blueprint_library().find(req.type) blueprint.set_attribute('role_name', req.id) @@ -177,55 +141,29 @@ def _spawn_actor(self, req): if req.attach_to != 0: attach_to = self.carla_world.get_actor(req.attach_to) if attach_to is None: - raise IndexError("Parent object {} not found".format( - req.attach_to)) + raise IndexError("Parent actor {} not found".format(req.attach_to)) - carla_actor = self.carla_world.spawn_actor(blueprint, transform, - attach_to) - return carla_actor.id + carla_actor = self.carla_world.spawn_actor(blueprint, transform, attach_to) + actor = self.actor_factory.create(req.type, req.id, req.attach_to, carla_actor) + return actor.uid def _spawn_pseudo_actor(self, req): - if req.attach_to != 0: - if req.attach_to not in self.actors: - raise IndexError("Parent object {} not found".format( - req.attach_to)) - parent = self.actors[req.attach_to] - else: - parent = None - - self._create_pseudo_actor(req.type, req.id, parent) + actor = self.actor_factory.create(req.type, req.id, req.attach_to) + return actor.uid def spawn_object(self, req): - try: - if "pseudo" in req.type: - self._spawn_pseudo_actor(req) - return SpawnObjectResponse(0, "") - - else: - actor_id = self._spawn_actor(req) - return SpawnObjectResponse(actor_id, "") - - except Exception as e: - return SpawnObjectResponse(-1, str(e)) - - def destroy(self): - """ - Function to destroy this object. + with self.actor_factory.spawn_lock: + try: + if "pseudo" in req.type: + id_ = self._spawn_pseudo_actor(req) + return SpawnObjectResponse(id_, "") - :return: - """ - rospy.signal_shutdown("") - self.debug_helper.destroy() - self.shutdown.set() - self.carla_weather_subscriber.unregister() - self.carla_control_queue.put(CarlaControl.STEP_ONCE) - if not self.carla_settings.synchronous_mode: - if self.on_tick_id: - self.carla_world.remove_on_tick(self.on_tick_id) - self.update_actor_thread.join() - self._update_actors(set()) + else: + id_ = self._spawn_actor(req) + return SpawnObjectResponse(id_, "") - rospy.loginfo("Exiting Bridge") + except Exception as e: + return SpawnObjectResponse(-1, str(e)) def on_weather_changed(self, weather_parameters): """ @@ -286,7 +224,7 @@ def _synchronous_mode_update(self): # fill list of available ego vehicles self._expected_ego_vehicle_control_command_ids = [] with self._expected_ego_vehicle_control_command_ids_lock: - for actor_id, actor in self.actors.items(): + for actor_id, actor in self.actor_factory.actors.items(): if isinstance(actor, EgoVehicle): self._expected_ego_vehicle_control_command_ids.append( actor_id) @@ -298,9 +236,10 @@ def _synchronous_mode_update(self): self.update_clock(world_snapshot.timestamp) rospy.logdebug("Tick for frame {} returned. Waiting for sensor data...".format( frame)) - self._update(frame, world_snapshot.timestamp.elapsed_seconds) + with self.actor_factory.lock: + self._update(frame, world_snapshot.timestamp.elapsed_seconds) rospy.logdebug("Waiting for sensor data finished.") - self._update_actors(set([x.id for x in world_snapshot])) + self.actor_factory.update() if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: # wait for all ego vehicles to send a vehicle control command @@ -326,218 +265,16 @@ def _carla_time_tick(self, carla_snapshot): :return: """ if not self.shutdown.is_set(): - if self.update_lock.acquire(False): + if self.actor_factory.lock.acquire(False): if self.timestamp_last_run < carla_snapshot.timestamp.elapsed_seconds: self.timestamp_last_run = carla_snapshot.timestamp.elapsed_seconds self.update_clock(carla_snapshot.timestamp) self.status_publisher.set_frame(carla_snapshot.frame) self._update(carla_snapshot.frame, carla_snapshot.timestamp.elapsed_seconds) - self.update_lock.release() - - # if possible push current snapshot to update-actors-thread - try: - self.update_actors_queue.put_nowait( - set([x.id for x in carla_snapshot])) - except queue.Full: - pass - - def _update_actors_thread(self): - """ - execution loop for async mode actor list updates - """ - while not self.shutdown.is_set(): - try: - current_actors = self.update_actors_queue.get(timeout=1) - if current_actors: - self._update_actors(current_actors) - self.update_actors_queue.task_done() - except queue.Empty: - pass - - def _update_actors(self, current_actors): - """ - update the available actors - """ - previous_actors = set(self.actors) - - new_actors = current_actors - previous_actors - deleted_actors = previous_actors - current_actors - - if new_actors: - for carla_actor in self.carla_world.get_actors(list(new_actors)): - self._create_actor(carla_actor) - - if deleted_actors: - for id_to_delete in deleted_actors: - # remove actor - actor = self.actors[id_to_delete] - with self.update_lock: - rospy.loginfo("Remove {}(id={}, parent_id={}, prefix={})".format( - actor.__class__.__name__, actor.get_id(), - actor.get_parent_id(), - actor.get_prefix())) - actor.destroy() - del self.actors[id_to_delete] - - # remove pseudo-actors that have actor as parent - updated_pseudo_actors = [] - for pseudo_actor in self.pseudo_actors: - if pseudo_actor.get_parent_id() == id_to_delete: - rospy.loginfo("Remove {}(parent_id={}, prefix={})".format( - pseudo_actor.__class__.__name__, - pseudo_actor.get_parent_id(), - pseudo_actor.get_prefix())) - pseudo_actor.destroy() - del pseudo_actor - else: - updated_pseudo_actors.append(pseudo_actor) - self.pseudo_actors = updated_pseudo_actors - - def _create_pseudo_actor(self, type_id, name, parent): - if type_id == "sensor.pseudo.tf": - pseudo_sensor = TFSensor(name=name, parent=parent, node=self) - - elif type_id == "sensor.pseudo.odom": - pseudo_sensor = OdometrySensor(name=name, parent=parent, node=self) - - elif type_id == "sensor.pseudo.speedometer": - pseudo_sensor = SpeedometerSensor(name=name, - parent=parent, - node=self) - - elif type_id == "sensor.pseudo.markers": - pseudo_sensor = MarkerSensor(name=name, - parent=parent, - node=self, - actor_list=self.actors) - - elif type_id == "sensor.pseudo.actor_list": - pseudo_sensor = ActorListSensor(name=name, - parent=parent, - node=self, - actor_list=self.actors) - - elif type_id == "sensor.pseudo.objects": - filtered_id = parent.carla_actor.id if parent is not None else None - pseudo_sensor = ObjectSensor( - name=name, - parent=parent, - node=self, - actor_list=self.actors, - filtered_id=filtered_id, - ) - - elif type_id == "sensor.pseudo.traffic_lights": - pseudo_sensor = TrafficLightsSensor( - name=name, - parent=parent, - node=self, - actor_list=self.actors, - ) - - elif type_id == "sensor.pseudo.opendrive_map": - pseudo_sensor = OpenDriveSensor( - name=name, - parent=parent, - node=self, - carla_map=self.carla_world.get_map()) - - with self.update_lock: - self.pseudo_actors.append(pseudo_sensor) - - rospy.loginfo("Created {}(parent_id={}, prefix={})".format( - pseudo_sensor.__class__.__name__, pseudo_sensor.get_parent_id(), - pseudo_sensor.get_prefix())) - - def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-many-statements - """ - create an actor - """ - parent = None - if carla_actor.parent: - if carla_actor.parent.id in self.actors: - parent = self.actors[carla_actor.parent.id] - else: - parent = self._create_actor(carla_actor.parent) + self.actor_factory.lock.release() - actor = None - if carla_actor.type_id.startswith('traffic'): - if carla_actor.type_id == "traffic.traffic_light": - actor = TrafficLight(carla_actor, parent, node=self) - else: - actor = Traffic(carla_actor, parent, node=self) - elif carla_actor.type_id.startswith("vehicle"): - if carla_actor.attributes.get('role_name')\ - in self.parameters['ego_vehicle']['role_name']: - actor = EgoVehicle( - carla_actor, parent, self, self._ego_vehicle_control_applied_callback) - else: - actor = Vehicle(carla_actor, parent, self) - elif carla_actor.type_id.startswith("sensor"): - if carla_actor.type_id.startswith("sensor.camera"): - if carla_actor.type_id.startswith("sensor.camera.rgb"): - actor = RgbCamera( - carla_actor, parent, self, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.camera.depth"): - actor = DepthCamera( - carla_actor, parent, self, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.camera.semantic_segmentation"): - actor = SemanticSegmentationCamera( - carla_actor, parent, self, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.camera.dvs"): - actor = DVSCamera(carla_actor, parent, self, - self.carla_settings.synchronous_mode) - else: - actor = Camera( - carla_actor, parent, self, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.lidar"): - if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): - actor = Lidar(carla_actor, parent, self, - self.carla_settings.synchronous_mode) - elif carla_actor.type_id.endswith("sensor.lidar.ray_cast_semantic"): - actor = SemanticLidar(carla_actor, parent, self, - self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.lidar"): - actor = Lidar(carla_actor, parent, self, - self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.other.radar"): - actor = Radar(carla_actor, parent, self, - self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.other.gnss"): - actor = Gnss(carla_actor, parent, self, - self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.other.imu"): - actor = ImuSensor( - carla_actor, parent, self, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.other.collision"): - actor = CollisionSensor( - carla_actor, parent, self, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.other.rss"): - actor = RssSensor( - carla_actor, parent, self, self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): - actor = LaneInvasionSensor( - carla_actor, parent, self, self.carla_settings.synchronous_mode) - else: - actor = Sensor(carla_actor, parent, self, - self.carla_settings.synchronous_mode) - elif carla_actor.type_id.startswith("spectator"): - actor = Spectator(carla_actor, parent, self) - elif carla_actor.type_id.startswith("walker"): - actor = Walker(carla_actor, parent, self) - else: - actor = Actor(carla_actor, parent, self) - - rospy.loginfo("Created {}(id={}, parent_id={}," - " type={}, prefix={}, attributes={})".format( - actor.__class__.__name__, actor.get_id(), - actor.get_parent_id(), carla_actor.type_id, - actor.get_prefix(), carla_actor.attributes)) - with self.update_lock: - self.actors[carla_actor.id] = actor - - return actor + self.on_carla_tick.set() def run(self): """ @@ -565,17 +302,16 @@ def _update(self, frame_id, timestamp): update all actors :return: """ - # update all pseudo actors - for actor in self.pseudo_actors: - actor.update(frame_id, timestamp) + # update world info + self.world_info.update(frame_id, timestamp) # update all carla actors - for actor_id in self.actors: + for actor_id in self.actor_factory.actors: try: - self.actors[actor_id].update(frame_id, timestamp) + self.actor_factory.actors[actor_id].update(frame_id, timestamp) except RuntimeError as e: rospy.logwarn("Update actor {}({}) failed: {}".format( - self.actors[actor_id].__class__.__name__, actor_id, e)) + self.actor_factory.actors[actor_id].__class__.__name__, actor_id, e)) continue def _ego_vehicle_control_applied_callback(self, ego_vehicle_id): @@ -618,6 +354,25 @@ def publish_tf_message(self, msg): except Exception as error: # pylint: disable=broad-except self.logwarn("Failed to publish message: {}".format(error)) + def destroy(self): + """ + Function to destroy this object. + + :return: + """ + rospy.signal_shutdown("") + self.debug_helper.destroy() + self.shutdown.set() + self.carla_weather_subscriber.unregister() + self.carla_control_queue.put(CarlaControl.STEP_ONCE) + if not self.carla_settings.synchronous_mode: + if self.on_tick_id: + self.carla_world.remove_on_tick(self.on_tick_id) + self.actor_factory.thread.join() + self.actor_factory.clear() + + rospy.loginfo("Exiting Bridge") + def main(): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 600943de..5d6f7584 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -34,10 +34,12 @@ class Camera(Sensor): # global cv bridge to convert image between opencv and ros cv_bridge = CvBridge() - def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments + def __init__(self, uid, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -49,7 +51,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # """ if not prefix: prefix = 'camera' - super(Camera, self).__init__(carla_actor=carla_actor, + super(Camera, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, @@ -180,10 +183,12 @@ class RgbCamera(Camera): Camera implementation details for rgb camera """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -193,7 +198,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(RgbCamera, self).__init__(carla_actor=carla_actor, + super(RgbCamera, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, @@ -237,10 +243,12 @@ class DepthCamera(Camera): Camera implementation details for depth camera """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -250,7 +258,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(DepthCamera, self).__init__(carla_actor=carla_actor, + super(DepthCamera, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, @@ -316,10 +325,12 @@ class SemanticSegmentationCamera(Camera): Camera implementation details for segmentation camera """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -330,7 +341,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :type synchronous_mode: bool """ super( - SemanticSegmentationCamera, self).__init__(carla_actor=carla_actor, + SemanticSegmentationCamera, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, @@ -375,10 +387,12 @@ class DVSCamera(Camera): Sensor implementation details for dvs cameras """ - def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments + def __init__(self, uid, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -388,7 +402,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # :param prefix: the topic prefix to be used for this actor :type prefix: string """ - super(DVSCamera, self).__init__(carla_actor=carla_actor, + super(DVSCamera, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index edc824fb..1568db2a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -22,10 +22,12 @@ class CollisionSensor(Sensor): Actor implementation details for a collision sensor """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -35,7 +37,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(CollisionSensor, self).__init__(carla_actor=carla_actor, + super(CollisionSensor, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index d9808adf..eceb1b4d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -34,10 +34,12 @@ class EgoVehicle(Vehicle): Vehicle implementation details for the ego vehicle """ - def __init__(self, carla_actor, parent, node, vehicle_control_applied_callback): + def __init__(self, uid, carla_actor, parent, node, vehicle_control_applied_callback): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -45,7 +47,8 @@ def __init__(self, carla_actor, parent, node, vehicle_control_applied_callback): :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge """ - super(EgoVehicle, self).__init__(carla_actor=carla_actor, + super(EgoVehicle, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, prefix=carla_actor.attributes.get('role_name')) diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index cae3de6b..0c1143af 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -23,10 +23,12 @@ class Gnss(Sensor): Actor implementation details for gnss sensor """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -36,7 +38,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(Gnss, self).__init__(carla_actor=carla_actor, + super(Gnss, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 33de5bf6..e3d820bb 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -21,10 +21,12 @@ class ImuSensor(Sensor): Actor implementation details for imu sensor """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor : carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -34,7 +36,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(ImuSensor, self).__init__(carla_actor=carla_actor, + super(ImuSensor, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 9d2b8f2e..f66e3b08 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -22,10 +22,12 @@ class LaneInvasionSensor(Sensor): Actor implementation details for a lane invasion sensor """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -35,7 +37,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(LaneInvasionSensor, self).__init__(carla_actor=carla_actor, + super(LaneInvasionSensor, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 7d50e326..0151db8b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -26,10 +26,12 @@ class Lidar(Sensor): Actor implementation details for lidars """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -37,7 +39,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge """ - super(Lidar, self).__init__(carla_actor=carla_actor, + super(Lidar, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, @@ -82,10 +85,12 @@ class SemanticLidar(Sensor): Actor implementation details for semantic lidars """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -93,7 +98,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge """ - super(SemanticLidar, self).__init__(carla_actor=carla_actor, + super(SemanticLidar, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index d32af6b8..289018be 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -23,9 +23,12 @@ class MarkerSensor(PseudoActor): Pseudo marker sensor """ - def __init__(self, name, parent, node, actor_list): + def __init__(self, uid, name, parent, node, actor_list): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param name: name identiying the sensor :type name: string :param carla_world: carla world object @@ -38,7 +41,8 @@ def __init__(self, name, parent, node, actor_list): :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(MarkerSensor, self).__init__(parent=parent, + super(MarkerSensor, self).__init__(uid, + parent=parent, node=node, prefix='markers/' + name) self.actor_list = actor_list diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 3640231e..82974c6d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -23,9 +23,12 @@ class ObjectSensor(PseudoActor): Pseudo object sensor """ - def __init__(self, name, parent, node, actor_list, filtered_id): + def __init__(self, uid, name, parent, node, actor_list): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param name: name identiying the sensor :type name: string :param carla_world: carla world object @@ -36,15 +39,13 @@ def __init__(self, name, parent, node, actor_list, filtered_id): :type node: carla_ros_bridge.CarlaRosBridge :param actor_list: current list of actors :type actor_list: map(carla-actor-id -> python-actor-object) - :param filtered_id: id to filter from actor_list - :type filtered_id: int """ - super(ObjectSensor, self).__init__(parent=parent, + super(ObjectSensor, self).__init__(uid, + parent=parent, node=node, prefix='objects/' + name) self.actor_list = actor_list - self.filtered_id = filtered_id self.object_publisher = rospy.Publisher(self.get_topic_prefix() + "/objects", ObjectArray, @@ -68,7 +69,7 @@ def update(self, frame, timestamp): ros_objects = ObjectArray(header=self.get_msg_header("map")) for actor_id in self.actor_list.keys(): # currently only Vehicles and Walkers are added to the object array - if self.filtered_id != actor_id: + if self.parent is None or self.parent.uid == actor_id: actor = self.actor_list[actor_id] if isinstance(actor, Vehicle): ros_objects.objects.append(actor.get_object_info()) diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index c22a6db2..95fd3525 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -22,9 +22,12 @@ class OdometrySensor(PseudoActor): Pseudo odometry sensor """ - def __init__(self, name, parent, node): + def __init__(self, uid, name, parent, node): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param name: name identiying the sensor :type name: string :param carla_world: carla world object @@ -35,7 +38,8 @@ def __init__(self, name, parent, node): :type node: carla_ros_bridge.CarlaRosBridge """ - super(OdometrySensor, self).__init__(parent=parent, + super(OdometrySensor, self).__init__(uid, + parent=parent, node=node, prefix='odometry/' + name) diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index d4f83485..3e3f4567 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -23,9 +23,12 @@ class OpenDriveSensor(PseudoActor): Pseudo opendrive sensor """ - def __init__(self, name, parent, node, carla_map): + def __init__(self, uid, name, parent, node, carla_map): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param name: name identiying the sensor :type name: string :param carla_world: carla world object @@ -37,7 +40,8 @@ def __init__(self, name, parent, node, carla_map): :param carla_map: carla map object :type carla_map: carla.Map """ - super(OpenDriveSensor, self).__init__(parent=parent, + super(OpenDriveSensor, self).__init__(uid, + parent=parent, node=node, prefix='opendrive/' + name) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 0a9b2c6c..2295f1dd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -11,7 +11,7 @@ from std_msgs.msg import Header import rospy - +import numpy as np class PseudoActor(object): @@ -19,9 +19,12 @@ class PseudoActor(object): Generic base class for Pseudo actors (that are not existing in Carla world) """ - def __init__(self, parent, node, prefix=None): + def __init__(self, uid, parent, node, prefix=None): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param parent: the parent of this :type parent: carla_ros_bridge.PseudoActor :param prefix: the topic prefix to be used for this actor @@ -29,6 +32,10 @@ def __init__(self, parent, node, prefix=None): :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge """ + self.uid = uid + if self.uid > np.iinfo(np.uint32).max: + raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) + self.parent = parent if self.parent: self.parent_id = parent.get_id() diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 00320166..53bd2faa 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -27,9 +27,12 @@ class Radar(Sensor): Actor implementation details of Carla RADAR """ - def __init__(self, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, carla_actor, parent, node, synchronous_mode): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -39,7 +42,8 @@ def __init__(self, carla_actor, parent, node, synchronous_mode): :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ - super(Radar, self).__init__(carla_actor=carla_actor, + super(Radar, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py index 98ee4b63..16ca2909 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py @@ -22,10 +22,12 @@ class RssSensor(Actor): utilization it's not handled as a sensor here. """ - def __init__(self, carla_actor, parent, node, _): + def __init__(self, uid, carla_actor, parent, node, _): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -34,7 +36,8 @@ def __init__(self, carla_actor, parent, node, _): :type node: carla_ros_bridge.CarlaRosBridge """ - super(RssSensor, self).__init__(carla_actor=carla_actor, + super(RssSensor, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, prefix="rss") diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 15d03d15..90ff4c24 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -28,6 +28,7 @@ class Sensor(Actor): """ def __init__(self, # pylint: disable=too-many-arguments + uid, carla_actor, parent, node, @@ -40,6 +41,8 @@ def __init__(self, # pylint: disable=too-many-arguments """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -53,7 +56,8 @@ def __init__(self, # pylint: disable=too-many-arguments """ if prefix is None: prefix = 'sensor' - super(Sensor, self).__init__(carla_actor=carla_actor, + super(Sensor, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, prefix=prefix) diff --git a/carla_ros_bridge/src/carla_ros_bridge/spectator.py b/carla_ros_bridge/src/carla_ros_bridge/spectator.py index 46df6046..e8d3695f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/spectator.py +++ b/carla_ros_bridge/src/carla_ros_bridge/spectator.py @@ -19,10 +19,12 @@ class Spectator(Actor): Actor implementation details for spectators """ - def __init__(self, carla_actor, parent, node): + def __init__(self, uid, carla_actor, parent, node): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -30,7 +32,8 @@ def __init__(self, carla_actor, parent, node): :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge """ - super(Spectator, self).__init__(carla_actor=carla_actor, + super(Spectator, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, prefix='spectator', node=node) diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 6f33820f..0567da1b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -23,9 +23,12 @@ class SpeedometerSensor(PseudoActor): Pseudo speedometer sensor """ - def __init__(self, name, parent, node): + def __init__(self, uid, name, parent, node): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param name: name identiying the sensor :type name: string :param carla_world: carla world object @@ -36,7 +39,8 @@ def __init__(self, name, parent, node): :type node: carla_ros_bridge.CarlaRosBridge """ - super(SpeedometerSensor, self).__init__(parent=parent, + super(SpeedometerSensor, self).__init__(uid, + parent=parent, node=node, prefix='speedometer/' + name) diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index d346b767..391dcc6d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -22,9 +22,12 @@ class TFSensor(PseudoActor): Pseudo tf sensor """ - def __init__(self, name, parent, node): + def __init__(self, uid, name, parent, node): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param name: name identiying the sensor :type name: string :param carla_world: carla world object @@ -35,7 +38,10 @@ def __init__(self, name, parent, node): :type node: carla_ros_bridge.CarlaRosBridge """ - super(TFSensor, self).__init__(parent=parent, node=node, prefix=None) + super(TFSensor, self).__init__(uid, + parent=parent, + node=node, + prefix=None) self.tf_broadcaster = tf.TransformBroadcaster() diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 043069be..cb765a94 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -22,10 +22,12 @@ class Traffic(Actor): Actor implementation details for traffic objects """ - def __init__(self, carla_actor, parent, node): + def __init__(self, uid, carla_actor, parent, node): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -33,7 +35,8 @@ def __init__(self, carla_actor, parent, node): :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge """ - super(Traffic, self).__init__(carla_actor=carla_actor, + super(Traffic, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, prefix='traffic') @@ -45,10 +48,12 @@ class TrafficLight(Actor): Traffic implementation details for traffic lights """ - def __init__(self, carla_actor, parent, node): + def __init__(self, uid, carla_actor, parent, node): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.TrafficLight :param parent: the parent of this @@ -56,7 +61,8 @@ def __init__(self, carla_actor, parent, node): :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge """ - super(TrafficLight, self).__init__(carla_actor=carla_actor, + super(TrafficLight, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, prefix='traffic.traffic_light') diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 62539b4c..9d2f95f8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -22,9 +22,12 @@ class TrafficLightsSensor(PseudoActor): a sensor that reports the state of all traffic lights """ - def __init__(self, name, parent, node, actor_list): + def __init__(self, uid, name, parent, node, actor_list): """ Constructor + + :param uid: unique identifier for this object + :type uid: int :param name: name identiying the sensor :type name: string :param parent: the parent of this @@ -35,9 +38,11 @@ def __init__(self, name, parent, node, actor_list): :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(TrafficLightsSensor, self).__init__(parent=parent, + super(TrafficLightsSensor, self).__init__(uid, + parent=parent, node=node, prefix="traffic_light/" + name) + self.actor_list = actor_list self.traffic_light_status = CarlaTrafficLightStatusList() self.traffic_light_actors = [] diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index efa46e57..69658a25 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -27,10 +27,12 @@ class TrafficParticipant(Actor): actor implementation details for traffic participant """ - def __init__(self, carla_actor, parent, node, prefix): + def __init__(self, uid, carla_actor, parent, node, prefix): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla actor object :type carla_actor: carla.Actor :param parent: the parent of this @@ -41,7 +43,8 @@ def __init__(self, carla_actor, parent, node, prefix): :type prefix: string """ self.classification_age = 0 - super(TrafficParticipant, self).__init__(carla_actor=carla_actor, + super(TrafficParticipant, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, prefix=prefix) diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index ae3bef93..48da2c64 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -22,10 +22,12 @@ class Vehicle(TrafficParticipant): Actor implementation details for vehicles """ - def __init__(self, carla_actor, parent, node, prefix=None): + def __init__(self, uid, carla_actor, parent, node, prefix=None): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla vehicle actor object :type carla_actor: carla.Vehicle :param parent: the parent of this @@ -51,7 +53,8 @@ def __init__(self, carla_actor, parent, node, prefix=None): elif carla_actor.attributes['object_type'] == 'other': self.classification = Object.CLASSIFICATION_OTHER_VEHICLE - super(Vehicle, self).__init__(carla_actor=carla_actor, + super(Vehicle, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, prefix=prefix) diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index 090859ef..bbd3ec0e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -23,10 +23,12 @@ class Walker(TrafficParticipant): Actor implementation details for pedestrians """ - def __init__(self, carla_actor, parent, node): + def __init__(self, uid, carla_actor, parent, node): """ Constructor + :param uid: unique identifier for this object + :type uid: int :param carla_actor: carla walker actor object :type carla_actor: carla.Walker :param parent: the parent of this @@ -41,7 +43,8 @@ def __init__(self, carla_actor, parent, node): else: prefix = "walker/{:03}".format(carla_actor.id) - super(Walker, self).__init__(carla_actor=carla_actor, + super(Walker, self).__init__(uid=uid, + carla_actor=carla_actor, parent=parent, node=node, prefix=prefix) diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index 91be9d84..bace4bba 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -32,7 +32,8 @@ def __init__(self, carla_world, node): :type node: carla_ros_bridge.CarlaRosBridge """ - super(WorldInfo, self).__init__(parent=None, + super(WorldInfo, self).__init__(uid=None, + parent=None, node=node, prefix="world_info") From 731241272ca92fe5a330ff4224d264872df3acdc Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Sun, 15 Nov 2020 21:04:49 +0100 Subject: [PATCH 374/627] spawn ego vehicle using services --- .../carla_ego_vehicle/carla_ego_vehicle.py | 28 +++++++++++++------ 1 file changed, 19 insertions(+), 9 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 71f0b72c..be822007 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -121,6 +121,7 @@ def restart(self): if blueprint.has_attribute('color'): color = secure_random.choice(blueprint.get_attribute('color').recommended_values) blueprint.set_attribute('color', color) + # Spawn the vehicle. if not rospy.get_param('~spawn_ego_vehicle'): actors = self.world.get_actors().filter(self.actor_filter) @@ -129,6 +130,8 @@ def restart(self): self.player = actor break else: + spawn_point = None + if self.actor_spawnpoint: spawn_point = carla.Transform() spawn_point.location.x = self.actor_spawnpoint.position.x @@ -150,9 +153,6 @@ def restart(self): spawn_point.rotation.yaw)) if self.player is not None: self.player.set_transform(spawn_point) - while self.player is None: - self.player = self.world.try_spawn_actor(blueprint, spawn_point) - self.player_created = True else: if self.player is not None: @@ -161,12 +161,22 @@ def restart(self): spawn_point.rotation.roll = 0.0 spawn_point.rotation.pitch = 0.0 self.player.set_transform(spawn_point) - while self.player is None: - spawn_points = self.world.get_map().get_spawn_points() - spawn_point = secure_random.choice( - spawn_points) if spawn_points else carla.Transform() - self.player = self.world.try_spawn_actor(blueprint, spawn_point) - self.player_created = True + + spawn_object_request = SpawnObjectRequest() + spawn_object_request.type = blueprint.id + spawn_object_request.id = self.role_name + spawn_object_request.attach_to = 0 + + while self.player is None: + if not self.actor_spawnpoint: + spawn_points = self.world.get_map().get_spawn_points() + spawn_point = secure_random.choice(spawn_points) if spawn_points else carla.Transform() + + spawn_object_request.transform = trans.carla_transform_to_ros_pose(spawn_point) + response = self.spawn_object_service(spawn_object_request) + if response.id != -1: + self.player = self.world.get_actor(response.id) + self.player_created = True if self.player_created: # Read sensors from file From be6cb8c48fd7f26eac74b8b1b88e6e907845005b Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 16 Nov 2020 16:04:40 +0100 Subject: [PATCH 375/627] destroying objects using services --- .../carla_ego_vehicle/carla_ego_vehicle.py | 20 +++++++-------- .../carla_infrastructure.py | 16 ++++++------ .../src/carla_ros_bridge/actor_factory.py | 23 ++++++++++------- .../src/carla_ros_bridge/bridge.py | 25 ++++++++++++++----- 4 files changed, 51 insertions(+), 33 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index be822007..4dd05e1a 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -34,7 +34,7 @@ import carla_common.transforms as trans -from carla_msgs.srv import SpawnObject, SpawnObjectRequest +from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest secure_random = random.SystemRandom() @@ -94,6 +94,7 @@ def __init__(self): rospy.wait_for_service('/carla/spawn_object') self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) + self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) def on_initialpose(self, initial_pose): """ @@ -250,9 +251,7 @@ def setup_sensors(self, sensors): "Sensor {} will not be spawned, {}".format(sensor_name, e)) raise e - if response.id > 0: - sensor = self.world.get_actor(response.id) - actors.append(sensor) + actors.append(response.id) return actors @abstractmethod @@ -266,14 +265,15 @@ def destroy(self): """ destroy the current ego vehicle and its sensors """ - for i, _ in enumerate(self.sensor_actors): - if self.sensor_actors[i] is not None: - self.sensor_actors[i].destroy() - self.sensor_actors[i] = None + for actor_id in self.sensor_actors: + destroy_object_request = DestroyObjectRequest(actor_id) + self.destroy_object_service(destroy_object_request) + self.sensor_actors = [] if self.player and self.player.is_alive: - self.player.destroy() + destroy_object_request = DestroyObjectRequest(self.player.id) + self.destroy_object_service(destroy_object_request) self.player = None def run(self): @@ -289,7 +289,7 @@ def run(self): sys.exit(1) rospy.loginfo("CARLA world available. Spawn ego vehicle...") - + rospy.on_shutdown(self.destroy) client = carla.Client(self.host, self.port) client.set_timeout(self.timeout) self.world = client.get_world() diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 9481bf5f..a5b5c0eb 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -19,7 +19,7 @@ from diagnostic_msgs.msg import KeyValue from carla_msgs.msg import CarlaWorldInfo -from carla_msgs.srv import SpawnObject, SpawnObjectRequest +from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest import carla @@ -45,6 +45,7 @@ def __init__(self): rospy.wait_for_service('/carla/spawn_object') self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) + self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) def restart(self): """ @@ -121,19 +122,17 @@ def setup_sensors(self, sensors): "Sensor {} will not be spawned, {}".format(sensor_name, e)) raise e - if response.id > 0: - sensor = self.world.get_actor(response.id) - actors.append(sensor) + actors.append(response.id) return actors def destroy(self): """ destroy the current ego vehicle and its sensors """ - for i, _ in enumerate(self.sensor_actors): - if self.sensor_actors[i] is not None: - self.sensor_actors[i].destroy() - self.sensor_actors[i] = None + for actor_id in self.sensor_actors: + destroy_object_request = DestroyObjectRequest(actor_id) + self.destroy_object_service(destroy_object_request) + self.sensor_actors = [] def run(self): @@ -148,6 +147,7 @@ def run(self): rospy.logerr("Timeout while waiting for world info!") raise e rospy.loginfo("CARLA world available. Spawn infrastructure...") + rospy.on_shutdown(self.destroy) client = carla.Client(self.host, self.port) client.set_timeout(self.timeout) self.world = client.get_world() diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index a927a54e..54b4b1a2 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -13,6 +13,7 @@ except ImportError: import Queue as queue +import time from threading import Thread, Lock import itertools @@ -45,6 +46,9 @@ class ActorFactory(object): + + TIME_BETWEEN_UPDATES = 0.1 + def __init__(self, node, world, sync_mode=False): self.node = node self.world = world @@ -70,10 +74,11 @@ def _update_thread(self): execution loop for async mode actor discovery """ while not self.node.shutdown.is_set(): - if self.node.on_carla_tick.wait(1): - with self.spawn_lock: - self.update() - self.node.on_carla_tick.clear() + time.sleep(ActorFactory.TIME_BETWEEN_UPDATES) + + with self.spawn_lock: + self.world.wait_for_tick() + self.update() def update(self): """ @@ -84,13 +89,13 @@ def update(self): current_actors = set([x.id for x in self.world.get_actors()]) new_actors = current_actors - previous_actors - for carla_actor in self.world.get_actors(list(new_actors)): + for actor_id in new_actors: + carla_actor = self.world.get_actor(actor_id) self._create_carla_actor(carla_actor) - for actor_id, actor in self.actors.items(): - if isinstance(actor, Actor): - if self.world.get_actor(actor_id) is None: - self.destroy(actor_id) + deleted_actors = previous_actors -current_actors + for actor_id in deleted_actors: + self.destroy(actor_id) def clear(self): ids = self.actors.keys() diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 5481b90a..d38f0507 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -28,6 +28,7 @@ import carla_common.transforms as trans +from carla_ros_bridge.actor import Actor from carla_ros_bridge.actor_factory import ActorFactory from carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher @@ -35,7 +36,7 @@ from carla_ros_bridge.world_info import WorldInfo from carla_msgs.msg import CarlaControl, CarlaWeatherParameters -from carla_msgs.srv import SpawnObject, SpawnObjectResponse +from carla_msgs.srv import SpawnObject, SpawnObjectResponse, DestroyObject, DestroyObjectResponse class CarlaRosBridge(object): @@ -95,9 +96,10 @@ def __init__(self, carla_world, params): self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds) - self.spawn_object_service = rospy.Service('/carla/spawn_object', - SpawnObject, + self.spawn_object_service = rospy.Service("/carla/spawn_object", SpawnObject, self.spawn_object) + self.destroy_object_service = rospy.Service("/carla/destroy_object", DestroyObject, + self.destroy_object) # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. @@ -119,7 +121,6 @@ def __init__(self, carla_world, params): else: self.timestamp_last_run = 0.0 - self.on_carla_tick = Event() self.actor_factory.start() # register callback to update actors @@ -165,6 +166,20 @@ def spawn_object(self, req): except Exception as e: return SpawnObjectResponse(-1, str(e)) + def destroy_object(self, req): + with self.actor_factory.spawn_lock: + + if req.id not in self.actor_factory.actors: + return DestroyObjectResponse(False) + + actor = self.actor_factory.actors[req.id] + if isinstance(actor, Actor): + actor.carla_actor.destroy() + + self.actor_factory.destroy(req.id) + + return DestroyObjectResponse(True) + def on_weather_changed(self, weather_parameters): """ Callback on new weather parameters @@ -274,8 +289,6 @@ def _carla_time_tick(self, carla_snapshot): carla_snapshot.timestamp.elapsed_seconds) self.actor_factory.lock.release() - self.on_carla_tick.set() - def run(self): """ Run the bridge functionality. From 5e74e081a5ed94b9ba622d520f7ee23d32e72bca Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 16 Nov 2020 19:21:04 +0100 Subject: [PATCH 376/627] fixed bug destroying actors --- .../src/carla_ego_vehicle/carla_ego_vehicle.py | 18 ++++++++++++++---- .../carla_infrastructure.py | 11 +++++++++-- 2 files changed, 23 insertions(+), 6 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 4dd05e1a..f6341eb2 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -265,15 +265,25 @@ def destroy(self): """ destroy the current ego vehicle and its sensors """ + # destroy sensors for actor_id in self.sensor_actors: - destroy_object_request = DestroyObjectRequest(actor_id) - self.destroy_object_service(destroy_object_request) + carla_actor = self.world.get_actor(actor_id) + if carla_actor is not None: + carla_actor.destroy() + + else: + destroy_object_request = DestroyObjectRequest(actor_id) + try: + response = self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) self.sensor_actors = [] + # destroy player if self.player and self.player.is_alive: - destroy_object_request = DestroyObjectRequest(self.player.id) - self.destroy_object_service(destroy_object_request) + self.player.destroy() + self.player = None def run(self): diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index a5b5c0eb..fd93246b 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -130,8 +130,15 @@ def destroy(self): destroy the current ego vehicle and its sensors """ for actor_id in self.sensor_actors: - destroy_object_request = DestroyObjectRequest(actor_id) - self.destroy_object_service(destroy_object_request) + carla_actor = self.world.get_actor(actor_id) + if carla_actor is not None: + carla_actor.destroy() + else: + destroy_object_request = DestroyObjectRequest(actor_id) + try: + self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) self.sensor_actors = [] From 7a419b7a602f0f60095d59c639c79c7c2a17713f Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Fri, 13 Nov 2020 10:53:38 +0100 Subject: [PATCH 377/627] move dependency installation to script --- README.md | 1 - packaging/install_dependencies.sh | 34 +++++++++++++++++++++++++++++++ 2 files changed, 34 insertions(+), 1 deletion(-) create mode 100755 packaging/install_dependencies.sh diff --git a/README.md b/README.md index 3a19b9cb..d1c062e1 100644 --- a/README.md +++ b/README.md @@ -37,7 +37,6 @@ Beside the bridging functionality, there are many more features provided in sepa For a quick overview, after following the [Setup section](#setup), please run the [CARLA AD Demo](carla_ad_demo/README.md). It provides a ready-to-use demonstrator of many of the features. - ## Setup ### For Users diff --git a/packaging/install_dependencies.sh b/packaging/install_dependencies.sh new file mode 100755 index 00000000..586b1aed --- /dev/null +++ b/packaging/install_dependencies.sh @@ -0,0 +1,34 @@ +#!/usr/bin/env bash + +SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" +ROS_VERSION=$(rosversion -d) +if [ "$ROS_VERSION" = "noetic" ]; then + PYTHON_SUFFIX=3 +else + PYTHON_SUFFIX="" +fi + +sudo apt update +sudo apt-get install --no-install-recommends -y \ + python$PYTHON_SUFFIX-pip \ + python$PYTHON_SUFFIX-osrf-pycommon \ + python$PYTHON_SUFFIX-catkin-tools \ + python$PYTHON_SUFFIX-catkin-pkg \ + python$PYTHON_SUFFIX-catkin-pkg-modules \ + python$PYTHON_SUFFIX-rosdep \ + python$PYTHON_SUFFIX-wstool \ + ros-$ROS_VERSION-opencv-apps \ + ros-$ROS_VERSION-ackermann-msgs \ + ros-$ROS_VERSION-derived-object-msgs \ + ros-$ROS_VERSION-cv-bridge \ + ros-$ROS_VERSION-vision-opencv \ + ros-$ROS_VERSION-rospy-message-converter \ + ros-$ROS_VERSION-rviz \ + ros-$ROS_VERSION-rqt-image-view \ + ros-$ROS_VERSION-rqt-gui-py \ + ros-$ROS_VERSION-rviz \ + qt5-default \ + ros-$ROS_VERSION-pcl-conversions \ + ros-$ROS_VERSION-pcl-ros + +pip$PYTHON_SUFFIX install -r $SCRIPT_DIR/../requirements.txt From 9534d06d5d36a9018bc17a1a03ca0a219cf34b7a Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Fri, 13 Nov 2020 10:54:02 +0100 Subject: [PATCH 378/627] move ros ci job to github actions --- .github/workflows/ci.yml | 39 ++++++++++++++++++++++++ .travis.yml | 66 ++++------------------------------------ 2 files changed, 45 insertions(+), 60 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 6cd2bda7..d18ea823 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -17,3 +17,42 @@ jobs: pip install -r requirements.txt - name: Check run: make check_format + + ros: + runs-on: ubuntu-latest + container: ros:${{ matrix.ros-version }}-robot + strategy: + matrix: + ros-version: [melodic, noetic] + env: + SCENARIO_RUNNER_PATH: "" + DEBIAN_FRONTEND: "noninteractive" + steps: + - uses: actions/checkout@v2 + # TODO cleaner solution but currently not working because git version is below 2.18 + # with: + # submodules: true + - name: Setup + run: | + sudo apt-get update && sudo apt-get install wget unzip -y + rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/master.zip + unzip master.zip -d carla_msgs && rm master.zip + packaging/install_dependencies.sh + - name: Init Workspace + run: | + mkdir -p $GITHUB_WORKSPACE/../catkin_ws/src + cd $GITHUB_WORKSPACE/../catkin_ws/src + ln -s $GITHUB_WORKSPACE + cd .. + catkin init + - name: Build, Test, Lint + shell: bash + run: | + source /opt/ros/${{ matrix.ros-version }}/setup.bash + cd $GITHUB_WORKSPACE/../catkin_ws && + catkin build --summarize --no-status --force-color + catkin run_tests --no-status --force-color && catkin_test_results + catkin config --install && source devel/setup.bash + cd $GITHUB_WORKSPACE + # make pylint + # TODO enable pylint diff --git a/.travis.yml b/.travis.yml index c8d75d66..92d7d781 100644 --- a/.travis.yml +++ b/.travis.yml @@ -6,10 +6,7 @@ # os: linux - -stages: - - test - - docker +services: docker cache: - apt @@ -21,67 +18,16 @@ addons: jobs: include: - - name: "Xenial Kinetic" - stage: test - dist: xenial - env: - - ROS_DISTRO=kinetic - - PYTHON_SUFFIX="" - - name: "Bionic Melodic" - dist: bionic + - name: "Docker Melodic" env: - ROS_DISTRO=melodic - - PYTHON_SUFFIX="" - - name: "Focal Noetic" - dist: focal + - PYTHON_SUFFIX="2.7" + - name: "Docker Noetic" env: - ROS_DISTRO=noetic - - PYTHON_SUFFIX=3 - addons: - apt: - packages: - - python3-pip - - name: "Docker Melodic" - stage: docker - services: docker - before_install: skip - install: skip - script: cd docker && ./build.sh --build-arg ROS_VERSION=melodic - - name: "Docker Noetic" - services: docker - before_install: skip - install: skip - script: cd docker && ./build.sh --build-arg ROS_VERSION=noetic --build-arg PYTHON_VERSION=3.7 - -before_install: - - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' - - sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 - - sudo apt update - - sudo apt install -y ros-$ROS_DISTRO-desktop-full python$PYTHON_SUFFIX-osrf-pycommon python$PYTHON_SUFFIX-catkin-tools python$PYTHON_SUFFIX-catkin-pkg python$PYTHON_SUFFIX-catkin-pkg-modules python$PYTHON_SUFFIX-rosdep python$PYTHON_SUFFIX-wstool - -install: - - pip$PYTHON_SUFFIX install --user -r requirements.txt - - mkdir ros-bridge/ - - shopt -s dotglob - - shopt -s extglob - - mv !(ros-bridge) ros-bridge/ - - mkdir -p catkin_ws/src - - cd catkin_ws/src - - ln -s ../../ros-bridge - - cd .. - - source /opt/ros/$ROS_DISTRO/setup.bash - - sudo rosdep init - - rosdep update - - rosdep install --from-paths src --ignore-src -r + - PYTHON_SUFFIX="3.7" -script: - - catkin build - - export SCENARIO_RUNNER_PATH="" # the env var needs to be set for testing - - if [ ! $ROS_DISTRO -eq kinetic ]; then catkin test; fi; - - catkin config --install - - source devel/setup.bash - - cd src/ros-bridge - - if [ ! $ROS_DISTRO -eq noetic ]; then make pylint; fi; +script: cd docker && ./build.sh --build-arg ROS_VERSION=$ROS_DISTRO --build-arg PYTHON_VERSION=$PYTHON_SUFFIX after_failure: - tail --lines=2000 build.log From c73d9cc6fe4a361f194a79cbf58e8a04ce94840e Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 25 Nov 2020 12:13:24 +0100 Subject: [PATCH 379/627] destroying the remaining registered actors in the bridge node --- .../carla_ego_vehicle/carla_ego_vehicle.py | 21 +++++------ .../carla_infrastructure.py | 14 +++---- .../src/carla_ros_bridge/bridge.py | 37 ++++++++++++------- 3 files changed, 39 insertions(+), 33 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index f6341eb2..fd181fc2 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -267,22 +267,21 @@ def destroy(self): """ # destroy sensors for actor_id in self.sensor_actors: - carla_actor = self.world.get_actor(actor_id) - if carla_actor is not None: - carla_actor.destroy() - - else: - destroy_object_request = DestroyObjectRequest(actor_id) - try: - response = self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) + destroy_object_request = DestroyObjectRequest(actor_id) + try: + response = self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) self.sensor_actors = [] # destroy player if self.player and self.player.is_alive: - self.player.destroy() + destroy_object_request = DestroyObjectRequest(self.player.id) + try: + self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) self.player = None diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index fd93246b..6467ef41 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -130,15 +130,11 @@ def destroy(self): destroy the current ego vehicle and its sensors """ for actor_id in self.sensor_actors: - carla_actor = self.world.get_actor(actor_id) - if carla_actor is not None: - carla_actor.destroy() - else: - destroy_object_request = DestroyObjectRequest(actor_id) - try: - self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) + destroy_object_request = DestroyObjectRequest(actor_id) + try: + response = self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) self.sensor_actors = [] diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index d38f0507..0703798c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -96,6 +96,7 @@ def __init__(self, carla_world, params): self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds) + self._registered_actors = [] self.spawn_object_service = rospy.Service("/carla/spawn_object", SpawnObject, self.spawn_object) self.destroy_object_service = rospy.Service("/carla/destroy_object", DestroyObject, @@ -157,28 +158,33 @@ def spawn_object(self, req): try: if "pseudo" in req.type: id_ = self._spawn_pseudo_actor(req) - return SpawnObjectResponse(id_, "") - else: id_ = self._spawn_actor(req) - return SpawnObjectResponse(id_, "") + + self._registered_actors.append(id_) + return SpawnObjectResponse(id_, "") except Exception as e: return SpawnObjectResponse(-1, str(e)) - def destroy_object(self, req): - with self.actor_factory.spawn_lock: - - if req.id not in self.actor_factory.actors: - return DestroyObjectResponse(False) + def _destroy_actor(self, uid): + if uid not in self.actor_factory.actors: + return False - actor = self.actor_factory.actors[req.id] - if isinstance(actor, Actor): - actor.carla_actor.destroy() + actor = self.actor_factory.actors[uid] + if isinstance(actor, Actor): + actor.carla_actor.destroy() - self.actor_factory.destroy(req.id) + self.actor_factory.destroy(uid) + return True - return DestroyObjectResponse(True) + def destroy_object(self, req): + with self.actor_factory.spawn_lock: + result = self._destroy_actor(req.id) + if result and req.id in self._registered_actors: + self._registered_actors.remove(req.id) + + return DestroyObjectResponse(result) def on_weather_changed(self, weather_parameters): """ @@ -382,6 +388,11 @@ def destroy(self): if self.on_tick_id: self.carla_world.remove_on_tick(self.on_tick_id) self.actor_factory.thread.join() + + with self.actor_factory.spawn_lock: + # remove actors in reverse order to destroy parent actors first. + for uid in self._registered_actors[::-1]: + self._destroy_actor(uid) self.actor_factory.clear() rospy.loginfo("Exiting Bridge") From 8cfc7c62ca2c0cda400021f5dc7783851acd3d20 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 25 Nov 2020 14:50:30 +0100 Subject: [PATCH 380/627] Support GetBlueprints() service --- .../carla_ego_vehicle/carla_ego_vehicle.py | 19 +++++++------- carla_msgs | 2 +- .../src/carla_ros_bridge/actor_factory.py | 26 ++++++++++++------- .../src/carla_ros_bridge/actor_list_sensor.py | 8 ++++++ .../src/carla_ros_bridge/bridge.py | 20 ++++++++++++-- .../src/carla_ros_bridge/marker_sensor.py | 8 ++++++ .../src/carla_ros_bridge/object_sensor.py | 8 ++++++ .../src/carla_ros_bridge/odom_sensor.py | 8 ++++++ .../src/carla_ros_bridge/opendrive_sensor.py | 8 ++++++ .../src/carla_ros_bridge/pseudo_actor.py | 10 +++++++ .../carla_ros_bridge/speedometer_sensor.py | 8 ++++++ .../src/carla_ros_bridge/tf_sensor.py | 8 ++++++ .../carla_ros_bridge/traffic_lights_sensor.py | 8 ++++++ .../carla_ros_bridge/traffic_participant.py | 4 +-- .../src/carla_ros_bridge/world_info.py | 8 ++++++ 15 files changed, 130 insertions(+), 23 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index fd181fc2..bdea19db 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -169,15 +169,16 @@ def restart(self): spawn_object_request.attach_to = 0 while self.player is None: - if not self.actor_spawnpoint: - spawn_points = self.world.get_map().get_spawn_points() - spawn_point = secure_random.choice(spawn_points) if spawn_points else carla.Transform() - - spawn_object_request.transform = trans.carla_transform_to_ros_pose(spawn_point) - response = self.spawn_object_service(spawn_object_request) - if response.id != -1: - self.player = self.world.get_actor(response.id) - self.player_created = True + if not self.actor_spawnpoint: + spawn_points = self.world.get_map().get_spawn_points() + spawn_point = secure_random.choice( + spawn_points) if spawn_points else carla.Transform() + + spawn_object_request.transform = trans.carla_transform_to_ros_pose(spawn_point) + response = self.spawn_object_service(spawn_object_request) + if response.id != -1: + self.player = self.world.get_actor(response.id) + self.player_created = True if self.player_created: # Read sensors from file diff --git a/carla_msgs b/carla_msgs index cbb02a44..8888667e 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit cbb02a44638df43236c12be169c3a19a87bdddc8 +Subproject commit 8888667efd4bd6a4d575d155593b0ee7411d822b diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 54b4b1a2..5319ce94 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -28,6 +28,7 @@ from carla_ros_bridge.lidar import Lidar, SemanticLidar from carla_ros_bridge.radar import Radar from carla_ros_bridge.gnss import Gnss +from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.imu import ImuSensor from carla_ros_bridge.ego_vehicle import EgoVehicle from carla_ros_bridge.collision_sensor import CollisionSensor @@ -93,7 +94,7 @@ def update(self): carla_actor = self.world.get_actor(actor_id) self._create_carla_actor(carla_actor) - deleted_actors = previous_actors -current_actors + deleted_actors = previous_actors - current_actors for actor_id in deleted_actors: self.destroy(actor_id) @@ -158,32 +159,39 @@ def destroy(self, actor_id): rospy.loginfo("Removed {}(id={})".format(actor.__class__.__name__, actor.uid)) + def get_pseudo_sensor_types(self): + pseudo_sensors = [] + for cls in PseudoActor.__subclasses__(): + if cls.__name__ != "Actor": + pseudo_sensors.append(cls.get_blueprint_name()) + return pseudo_sensors + def _create_object(self, uid, type_id, name, parent, carla_actor=None): - if type_id == "sensor.pseudo.tf": + if type_id == TFSensor.get_blueprint_name(): actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) - elif type_id == "sensor.pseudo.odom": + elif type_id == OdometrySensor.get_blueprint_name(): actor = OdometrySensor(uid=uid, name=name, parent=parent, node=self.node) - elif type_id == "sensor.pseudo.speedometer": + elif type_id == SpeedometerSensor.get_blueprint_name(): actor = SpeedometerSensor(uid=uid, name=name, parent=parent, node=self.node) - elif type_id == "sensor.pseudo.markers": + elif type_id == MarkerSensor.get_blueprint_name(): actor = MarkerSensor(uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors) - elif type_id == "sensor.pseudo.actor_list": + elif type_id == ActorListSensor.get_blueprint_name(): actor = ActorListSensor(uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors) - elif type_id == "sensor.pseudo.objects": + elif type_id == ObjectSensor.get_blueprint_name(): actor = ObjectSensor( uid=uid, name=name, @@ -192,7 +200,7 @@ def _create_object(self, uid, type_id, name, parent, carla_actor=None): actor_list=self.actors, ) - elif type_id == "sensor.pseudo.traffic_lights": + elif type_id == TrafficLightsSensor.get_blueprint_name(): actor = TrafficLightsSensor( uid=uid, name=name, @@ -201,7 +209,7 @@ def _create_object(self, uid, type_id, name, parent, carla_actor=None): actor_list=self.actors, ) - elif type_id == "sensor.pseudo.opendrive_map": + elif type_id == OpenDriveSensor.get_blueprint_name(): actor = OpenDriveSensor(uid=uid, name=name, parent=parent, diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py index ab3a6a24..cdaf1545 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -57,6 +57,14 @@ def destroy(self): self.actor_list = None super(ActorListSensor, self).destroy() + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.actor_list" + def update(self, frame, timestamp): """ Function (override) to update this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 0703798c..37a984c1 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -36,7 +36,7 @@ from carla_ros_bridge.world_info import WorldInfo from carla_msgs.msg import CarlaControl, CarlaWeatherParameters -from carla_msgs.srv import SpawnObject, SpawnObjectResponse, DestroyObject, DestroyObjectResponse +from carla_msgs.srv import SpawnObject, SpawnObjectResponse, DestroyObject, DestroyObjectResponse, GetBlueprints, GetBlueprintsResponse class CarlaRosBridge(object): @@ -102,6 +102,9 @@ def __init__(self, carla_world, params): self.destroy_object_service = rospy.Service("/carla/destroy_object", DestroyObject, self.destroy_object) + self.get_blueprints_service = rospy.Service("/carla/get_blueprints", GetBlueprints, + self.get_blueprints) + # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. # Before tick(), the list is filled and the loop waits until the list is empty. @@ -174,7 +177,7 @@ def _destroy_actor(self, uid): actor = self.actor_factory.actors[uid] if isinstance(actor, Actor): actor.carla_actor.destroy() - + self.actor_factory.destroy(uid) return True @@ -186,6 +189,19 @@ def destroy_object(self, req): return DestroyObjectResponse(result) + def get_blueprints(self, req): + response = GetBlueprintsResponse() + if req.filter: + bp_filter = req.filter + else: + bp_filter = "*" + + response.blueprints = [ + bp.id for bp in self.carla_world.get_blueprint_library().filter(bp_filter)] + response.blueprints.extend(self.actor_factory.get_pseudo_sensor_types()) + response.blueprints.sort() + return response + def on_weather_changed(self, weather_parameters): """ Callback on new weather parameters diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index 289018be..4f8adce0 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -60,6 +60,14 @@ def destroy(self): self.actor_list = None super(MarkerSensor, self).destroy() + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.markers" + def update(self, frame, timestamp): """ Function (override) to update this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 82974c6d..a81c1533 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -59,6 +59,14 @@ def destroy(self): self.actor_list = None super(ObjectSensor, self).destroy() + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.objects" + def update(self, frame, timestamp): """ Function (override) to update this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 95fd3525..6c9ff76f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -48,6 +48,14 @@ def __init__(self, uid, name, parent, node): Odometry, queue_size=10) + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.odom" + def update(self, frame, timestamp): """ Function (override) to update this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 3e3f4567..a0a9649d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -52,6 +52,14 @@ def __init__(self, uid, name, parent, node, carla_map): queue_size=10, latch=True) + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.opendrive_map" + def update(self, frame, timestamp): """ Function (override) to update this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 2295f1dd..9e69339f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -13,6 +13,7 @@ import rospy import numpy as np + class PseudoActor(object): """ @@ -60,6 +61,15 @@ def destroy(self): """ self.parent = None + @classmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + raise NotImplementedError( + "The pseudo actor is missing a blueprint name") + def get_msg_header(self, frame_id=None, timestamp=None): """ Get a filled ROS message header diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 0567da1b..fd914911 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -49,6 +49,14 @@ def __init__(self, uid, name, parent, node): Float32, queue_size=10) + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.speedometer" + def update(self, frame, timestamp): """ Function (override) to update this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 391dcc6d..83b11924 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -45,6 +45,14 @@ def __init__(self, uid, name, parent, node): self.tf_broadcaster = tf.TransformBroadcaster() + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.tf" + def update(self, frame, timestamp): """ Function (override) to update this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 9d2f95f8..ad9d1ad7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -66,6 +66,14 @@ def destroy(self): self.actor_list = None super(TrafficLightsSensor, self).destroy() + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.traffic_lights" + def update(self, frame, timestamp): """ Get the state of all known traffic lights diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 69658a25..ac2a1c1f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -123,7 +123,7 @@ def get_marker(self): visualization_msgs.msg.Marker """ # marker = Marker( - # header=self.get_msg_header(frame_id=str(self.get_id()))) + # header=self.get_msg_header(frame_id=str(self.get_id()))) marker = Marker( header=self.get_msg_header(frame_id="map")) marker.color = self.get_marker_color() @@ -132,7 +132,7 @@ def get_marker(self): marker.type = Marker.CUBE # marker.pose = trans.carla_location_to_pose( - # self.carla_actor.bounding_box.location) + # self.carla_actor.bounding_box.location) marker.pose = trans.carla_transform_to_ros_pose( self.carla_actor.get_transform()) marker.scale.x = self.carla_actor.bounding_box.extent.x * 2.0 diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index bace4bba..0ea11d1d 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -59,6 +59,14 @@ def destroy(self): self.carla_map = None super(WorldInfo, self).destroy() + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo sensor + :return: name + """ + return "sensor.pseudo.world_info" + def update(self, frame, timestamp): """ Function (override) to update this object. From f288cc4c8639c56b2a9155cafbc64f399340faaa Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 26 Nov 2020 13:17:37 +0100 Subject: [PATCH 381/627] Add pseudo actor control --- .../carla_ego_vehicle/carla_ego_vehicle.py | 2 +- .../src/carla_ros_bridge/actor_control.py | 102 ++++++++++++++++++ .../src/carla_ros_bridge/actor_factory.py | 4 + .../src/carla_ros_bridge/bridge.py | 2 + .../src/carla_ros_bridge/ego_vehicle.py | 30 +----- .../src/carla_ros_bridge/pseudo_actor.py | 2 +- 6 files changed, 111 insertions(+), 31 deletions(-) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/actor_control.py diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index bdea19db..c3a6527a 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -303,8 +303,8 @@ def run(self): client = carla.Client(self.host, self.port) client.set_timeout(self.timeout) self.world = client.get_world() - self.restart() try: + self.restart() rospy.spin() except rospy.ROSInterruptException: pass diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py new file mode 100644 index 00000000..39efce4e --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -0,0 +1,102 @@ +#!/usr/bin/env python +# +# Copyright (c) 2019 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +provide functions to control actors +""" + +import rospy +import numpy +import carla_common.transforms as trans +from carla_ros_bridge.pseudo_actor import PseudoActor +from geometry_msgs.msg import Pose, Twist + + +class ActorControl(PseudoActor): + + """ + provide functions to control actors + """ + + def __init__(self, uid, name, parent, node): + """ + Constructor + + :param uid: unique identifier for this object + :type uid: int + :param name: name identifying the sensor + :type name: string + :param carla_world: carla world object + :type carla_world: carla.World + :param parent: the parent of this + :type parent: carla_ros_bridge.Parent + :param node: node-handle + :type node: carla_ros_bridge.CarlaRosBridge + + """ + + super(ActorControl, self).__init__(uid, + parent=parent, + node=node) + + self.set_location_subscriber = rospy.Subscriber(self.get_topic_prefix() + + "/set_transform", + Pose, + self.on_pose) + + self.twist_control_subscriber = rospy.Subscriber( + self.get_topic_prefix() + "/set_target_velocity", + Twist, self.on_twist) + + def destroy(self): + """ + Function (override) to destroy this object. + + Terminate ROS subscriptions + Finally forward call to super class. + + :return: + """ + self.set_location_subscriber.unregister() + self.set_location_subscriber = None + self.twist_control_subscriber.unregister() + self.twist_control_subscriber = None + super(ActorControl, self).destroy() + + @staticmethod + def get_blueprint_name(): + """ + Get the blueprint identifier for the pseudo actor + :return: name + """ + return "pseudo.actor.control" + + def on_pose(self, pose): + if self.parent and self.parent.carla_actor.is_alive: + self.parent.carla_actor.set_transform(trans.ros_pose_to_carla_transform(pose)) + + def on_twist(self, twist): + """ + Set angular/linear velocity (this does not respect vehicle dynamics) + """ + if not self.vehicle_control_override: + angular_velocity = Vector3D() + angular_velocity.z = math.degrees(twist.angular.z) + + rotation_matrix = transforms.carla_rotation_to_numpy_rotation_matrix( + self.carla_actor.get_transform().rotation) + linear_vector = numpy.array([twist.linear.x, twist.linear.y, twist.linear.z]) + rotated_linear_vector = rotation_matrix.dot(linear_vector) + linear_velocity = Vector3D() + linear_velocity.x = rotated_linear_vector[0] + linear_velocity.y = -rotated_linear_vector[1] + linear_velocity.z = rotated_linear_vector[2] + + rospy.logdebug("Set velocity linear: {}, angular: {}".format( + linear_velocity, angular_velocity)) + self.carla_actor.set_target_velocity(linear_velocity) + self.carla_actor.set_target_angular_velocity(angular_velocity) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 5319ce94..c9a4ab97 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -44,6 +44,7 @@ from carla_ros_bridge.marker_sensor import MarkerSensor from carla_ros_bridge.actor_list_sensor import ActorListSensor from carla_ros_bridge.opendrive_sensor import OpenDriveSensor +from carla_ros_bridge.actor_control import ActorControl class ActorFactory(object): @@ -216,6 +217,9 @@ def _create_object(self, uid, type_id, name, parent, carla_actor=None): node=self.node, carla_map=self.world.get_map()) + elif type_id == ActorControl.get_blueprint_name(): + actor = ActorControl(uid=uid, name=name, parent=parent, node=self.node) + elif carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": actor = TrafficLight(uid, carla_actor, parent, node=self.node) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 37a984c1..9ad1530c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -34,6 +34,7 @@ from carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher from carla_ros_bridge.debug_helper import DebugHelper from carla_ros_bridge.world_info import WorldInfo +from carla_ros_bridge.ego_vehicle import EgoVehicle from carla_msgs.msg import CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, SpawnObjectResponse, DestroyObject, DestroyObjectResponse, GetBlueprints, GetBlueprintsResponse @@ -168,6 +169,7 @@ def spawn_object(self, req): return SpawnObjectResponse(id_, "") except Exception as e: + rospy.logwarn("Error spawning object '{}: {}".format(req.type, e)) return SpawnObjectResponse(-1, str(e)) def _destroy_actor(self, uid): diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index eceb1b4d..f8eedf29 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -16,7 +16,7 @@ from std_msgs.msg import ColorRGBA from std_msgs.msg import Bool -from geometry_msgs.msg import Twist, Transform +from geometry_msgs.msg import Transform from carla import VehicleControl from carla import Vector3D @@ -85,10 +85,6 @@ def __init__(self, uid, carla_actor, parent, node, vehicle_control_applied_callb self.get_topic_prefix() + "/enable_autopilot", Bool, self.enable_autopilot_updated) - self.twist_control_subscriber = rospy.Subscriber( - self.get_topic_prefix() + "/twist_cmd", - Twist, self.twist_command_updated) - def get_marker_color(self): """ Function (override) to return the color for marker messages. @@ -193,36 +189,12 @@ def destroy(self): self.control_subscriber = None self.enable_autopilot_subscriber.unregister() self.enable_autopilot_subscriber = None - self.twist_control_subscriber.unregister() - self.twist_control_subscriber = None self.control_override_subscriber.unregister() self.control_override_subscriber = None self.manual_control_subscriber.unregister() self.manual_control_subscriber = None super(EgoVehicle, self).destroy() - def twist_command_updated(self, twist): - """ - Set angular/linear velocity (this does not respect vehicle dynamics) - """ - if not self.vehicle_control_override: - angular_velocity = Vector3D() - angular_velocity.z = math.degrees(twist.angular.z) - - rotation_matrix = transforms.carla_rotation_to_numpy_rotation_matrix( - self.carla_actor.get_transform().rotation) - linear_vector = numpy.array([twist.linear.x, twist.linear.y, twist.linear.z]) - rotated_linear_vector = rotation_matrix.dot(linear_vector) - linear_velocity = Vector3D() - linear_velocity.x = rotated_linear_vector[0] - linear_velocity.y = -rotated_linear_vector[1] - linear_velocity.z = rotated_linear_vector[2] - - rospy.logdebug("Set velocity linear: {}, angular: {}".format( - linear_velocity, angular_velocity)) - self.carla_actor.set_target_velocity(linear_velocity) - self.carla_actor.set_target_angular_velocity(angular_velocity) - def control_command_override(self, enable): """ Set the vehicle control mode according to ros topic diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 9e69339f..c308ea56 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -61,7 +61,7 @@ def destroy(self): """ self.parent = None - @classmethod + @staticmethod def get_blueprint_name(): """ Get the blueprint identifier for the pseudo sensor From 8bddf7da3e4722538531631bd7290e27b8e45f73 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 26 Nov 2020 13:20:53 +0100 Subject: [PATCH 382/627] cleanup --- carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index c3a6527a..bdea19db 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -303,8 +303,8 @@ def run(self): client = carla.Client(self.host, self.port) client.set_timeout(self.timeout) self.world = client.get_world() + self.restart() try: - self.restart() rospy.spin() except rospy.ROSInterruptException: pass From 321e1827933791ed7c68fd22ed39a62e5c7405ee Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 27 Nov 2020 16:35:31 +0100 Subject: [PATCH 383/627] new packaging pipeline --- packaging/CreateROSbridgeDebian.sh | 117 ----------------------------- packaging/build-deb.sh | 20 +++++ packaging/debian/changelog | 5 ++ packaging/debian/compat | 1 + packaging/debian/control | 38 ++++++++++ packaging/debian/copyright | 30 ++++++++ packaging/debian/rules | 27 +++++++ packaging/debian/source/format | 1 + 8 files changed, 122 insertions(+), 117 deletions(-) delete mode 100644 packaging/CreateROSbridgeDebian.sh create mode 100755 packaging/build-deb.sh create mode 100644 packaging/debian/changelog create mode 100644 packaging/debian/compat create mode 100644 packaging/debian/control create mode 100644 packaging/debian/copyright create mode 100755 packaging/debian/rules create mode 100644 packaging/debian/source/format diff --git a/packaging/CreateROSbridgeDebian.sh b/packaging/CreateROSbridgeDebian.sh deleted file mode 100644 index 1095afe7..00000000 --- a/packaging/CreateROSbridgeDebian.sh +++ /dev/null @@ -1,117 +0,0 @@ -#!/bin/sh - -#This script builds debian package for CARLA ROS Bridge -#Tested with Ubuntu 14.04, 16.04, 18.04, 19.10 and 20.04 - -sudo apt-get install build-essential dh-make - -#Adding maintainer name -DEBFULLNAME=Carla\ Simulator\ Team -export DEBFULLNAME - -#carla-ros-bridge github repository -ROS_BRIDGE_GIT=https://github.com/carla-simulator/ros-bridge.git -RELEASE_VERSION=$(git describe --tags --abbrev=0) - -mkdir -p carla-ros-debian/carla-ros-bridge/catkin_ws/src -mkdir -p carla-ros-debian/carla-ros-bridge-$(rosversion -d)-"$RELEASE_VERSION"/carla-ros-bridge/ - -cd carla-ros-debian/carla-ros-bridge - -#cloning carla-ros-bridge git repository -git clone ${ROS_BRIDGE_GIT} -rm -r ros-bridge/carla_msgs -cp -a ros-bridge/* catkin_ws/src/ - -cd catkin_ws - -source /opt/ros/$(rosversion -d)/setup.bash - -#installing required dependency packages to build catkin_make -sudo apt install ros-$(rosversion -d)-derived-object-msgs \ - ros-$(rosversion -d)-ackermann-msgs ros-$(rosversion -d)-carla-msgs ros-$(rosversion -d)-pcl-conversions \ - ros-$(rosversion -d)-rviz ros-$(rosversion -d)-rqt ros-$(rosversion -d)-pcl-ros - -catkin_make install - -cp -r install ../../carla-ros-bridge-$(rosversion -d)-"$RELEASE_VERSION"/carla-ros-bridge/ - -cd ../../carla-ros-bridge-$(rosversion -d)-"$RELEASE_VERSION"/ -mv carla-ros-bridge/install carla-ros-bridge/$(rosversion -d) - -rm Makefile - -#Making debian package to install Carla-ros-bridge in /opt folder -cat >>Makefile <>control < -Build-Depends: debhelper (>= 9) -Standards-Version:$RELEASE_VERSION -Homepage: https://github.com/carla-simulator/ros-bridge - -Package: carla-ros-bridge-$(rosversion -d) -Architecture: amd64 -Depends: ros-$(rosversion -d)-carla-msgs, - ros-$(rosversion -d)-roslaunch, - ros-$(rosversion -d)-catkin, - ros-$(rosversion -d)-rospy, - ros-$(rosversion -d)-nav-msgs, - ros-$(rosversion -d)-ackermann-msgs, - ros-$(rosversion -d)-std-msgs, - ros-$(rosversion -d)-dynamic-reconfigure, - ros-$(rosversion -d)-topic-tools, - ros-$(rosversion -d)-sensor-msgs, - ros-$(rosversion -d)-message-runtime, - ros-$(rosversion -d)-geometry-msgs, - ros-$(rosversion -d)-message-generation, - ros-$(rosversion -d)-visualization-msgs, - ros-$(rosversion -d)-tf, - ros-$(rosversion -d)-tf2, - ros-$(rosversion -d)-rviz, - ros-$(rosversion -d)-cv-bridge, - ros-$(rosversion -d)-rosbag-storage, - ros-$(rosversion -d)-derived-object-msgs, - ros-$(rosversion -d)-shape-msgs, - ros-$(rosversion -d)-tf2-msgs, - ros-$(rosversion -d)-rosgraph-msgs, - ros-$(rosversion -d)-roscpp, - ros-$(rosversion -d)-pcl-conversions, - ros-$(rosversion -d)-pcl-ros, - ros-$(rosversion -d)-rostopic, - ros-$(rosversion -d)-rqt-gui-py -Description: The carla_ros_bridge package aims at providing a simple ROS bridge for CARLA simulator. -EOF - -rm copyright -cp ../../../carla-ros-bridge/ros-bridge/LICENSE ./copyright - -#Updating debian/Changelog -awk '{sub(/UNRELEASED/,"stable")}1' changelog >tmp && mv tmp changelog -awk '{sub(/unstable/,"stable")}1' changelog >tmp && mv tmp changelog - -cd .. - -dpkg-buildpackage -uc -us -b #building debian package - -#install debian package using "sudo dpkg -i ../carla_ros-bridge-_amd64.deb" diff --git a/packaging/build-deb.sh b/packaging/build-deb.sh new file mode 100755 index 00000000..68a1fb04 --- /dev/null +++ b/packaging/build-deb.sh @@ -0,0 +1,20 @@ +#!/usr/bin/env bash + +set -e + +SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" +BUILD_DIR=${SCRIPT_DIR}/build/$(rosversion -d) +WORKSPACE_DIR=${BUILD_DIR}/catkin_ws + +mkdir -p ${BUILD_DIR} ${WORKSPACE_DIR} + +# bring the code +rsync -r ${SCRIPT_DIR}/../* ${WORKSPACE_DIR}/src --exclude packaging +# init ros workspace +source /opt/ros/$(rosversion -d)/setup.bash +cd ${WORKSPACE_DIR} && catkin_init_workspace +# add debian files +cp -r ${SCRIPT_DIR}/debian ${WORKSPACE_DIR} +sed -i "s/{ROS_DIST}/$(rosversion -d)/g" ${WORKSPACE_DIR}/debian/control +# build debian package +cd ${WORKSPACE_DIR} && dpkg-buildpackage -uc -us -b diff --git a/packaging/debian/changelog b/packaging/debian/changelog new file mode 100644 index 00000000..3755d295 --- /dev/null +++ b/packaging/debian/changelog @@ -0,0 +1,5 @@ +carla-ros-bridge (0.9.10-1) release; urgency=medium + + * CARLA ROS Bridge 0.9.10 pre-release + + -- Carla Simulator Team Mon, 24 Aug 2020 15:12:25 +0200 diff --git a/packaging/debian/compat b/packaging/debian/compat new file mode 100644 index 00000000..f599e28b --- /dev/null +++ b/packaging/debian/compat @@ -0,0 +1 @@ +10 diff --git a/packaging/debian/control b/packaging/debian/control new file mode 100644 index 00000000..77712816 --- /dev/null +++ b/packaging/debian/control @@ -0,0 +1,38 @@ +Source: carla-ros-bridge +Section: misc +Priority: optional +Maintainer: Carla Simulator Team +Build-Depends: debhelper (>= 9) +Standards-Version: 4.1.2 +Homepage: https://github.com/carla-simulator/ros-bridge + +Package: carla-ros-bridge +Architecture: amd64 +Depends: ros-{ROS_DIST}-roslaunch, + ros-{ROS_DIST}-catkin, + ros-{ROS_DIST}-rospy, + ros-{ROS_DIST}-nav-msgs, + ros-{ROS_DIST}-ackermann-msgs, + ros-{ROS_DIST}-std-msgs, + ros-{ROS_DIST}-dynamic-reconfigure, + ros-{ROS_DIST}-topic-tools, + ros-{ROS_DIST}-sensor-msgs, + ros-{ROS_DIST}-message-runtime, + ros-{ROS_DIST}-geometry-msgs, + ros-{ROS_DIST}-message-generation, + ros-{ROS_DIST}-visualization-msgs, + ros-{ROS_DIST}-tf, + ros-{ROS_DIST}-tf2, + ros-{ROS_DIST}-rviz, + ros-{ROS_DIST}-cv-bridge, + ros-{ROS_DIST}-rosbag-storage, + ros-{ROS_DIST}-derived-object-msgs, + ros-{ROS_DIST}-shape-msgs, + ros-{ROS_DIST}-tf2-msgs, + ros-{ROS_DIST}-rosgraph-msgs, + ros-{ROS_DIST}-roscpp, + ros-{ROS_DIST}-pcl-conversions, + ros-{ROS_DIST}-pcl-ros, + ros-{ROS_DIST}-rostopic, + ros-{ROS_DIST}-rqt-gui-py +Description: The carla_ros_bridge package aims at providing a simple ROS bridge for CARLA simulator. \ No newline at end of file diff --git a/packaging/debian/copyright b/packaging/debian/copyright new file mode 100644 index 00000000..9648840e --- /dev/null +++ b/packaging/debian/copyright @@ -0,0 +1,30 @@ +Format: https://www.debian.org/doc/packaging-manuals/copyright-format/1.0/ +Upstream-Name: carla-ros-bridge +Source: https://github.com/carla-simulator/ros-bridge + +Files: * +Copyright: 2017 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +License: MIT License + +Files: debian/* +Copyright: 2020 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). +License: MIT License + +License: MIT License + Permission is hereby granted, free of charge, to any person obtaining a copy + of this software and associated documentation files (the "Software"), to deal + in the Software without restriction, including without limitation the rights + to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + . + The above copyright notice and this permission notice shall be included in all + copies or substantial portions of the Software. + . + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + SOFTWARE. diff --git a/packaging/debian/rules b/packaging/debian/rules new file mode 100755 index 00000000..8bd02b52 --- /dev/null +++ b/packaging/debian/rules @@ -0,0 +1,27 @@ +#!/usr/bin/make -f +# See debhelper(7) (uncomment to enable) +# output every command that modifies files on the build system. +#export DH_VERBOSE = 1 + + +# see FEATURE AREAS in dpkg-buildflags(1) +#export DEB_BUILD_MAINT_OPTIONS = hardening=+all + +# see ENVIRONMENT in dpkg-buildflags(1) +# package maintainers to append CFLAGS +#export DEB_CFLAGS_MAINT_APPEND = -Wall -pedantic +# package maintainers to append LDFLAGS +#export DEB_LDFLAGS_MAINT_APPEND = -Wl,--as-needed + +# Uncomment this to turn on verbose mode. +#export DH_VERBOSE=1 +# Explicitly enable -DNDEBUG, see: +# https://github.com/ros-infrastructure/bloom/issues/327 +export DEB_CXXFLAGS_MAINT_APPEND=-DNDEBUG + +%: + dh $@ + +override_dh_auto_configure: + dh_auto_configure -- \ + -DCMAKE_INSTALL_PREFIX="/opt/carla-ros-bridge" diff --git a/packaging/debian/source/format b/packaging/debian/source/format new file mode 100644 index 00000000..163aaf8d --- /dev/null +++ b/packaging/debian/source/format @@ -0,0 +1 @@ +3.0 (quilt) From ff9c622a3b0bd55622e2a8f9e680035a45d810f8 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 27 Nov 2020 17:37:36 +0100 Subject: [PATCH 384/627] CHANGELOG updated --- CHANGELOG.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 8d3cca72..58a08ba5 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,9 @@ ## Latest changed +* Updated debian packaging pipeline + +## CARLA-ROS-Bridge 0.9.10.1 + * Support noetic and python 3 * Have all sensor types in sensors.json * Update ad-demo rviz config to visualize more sensor types From 4474450f5570742091457e4603a77b6fbe52bf96 Mon Sep 17 00:00:00 2001 From: Ilia Baltashov Date: Tue, 1 Dec 2020 16:26:25 +0300 Subject: [PATCH 385/627] Fix build error when CATKIN_ENABLE_TESTING=OFF --- carla_ackermann_control/CMakeLists.txt | 4 +++- carla_ad_agent/CMakeLists.txt | 4 +++- carla_ad_demo/CMakeLists.txt | 4 +++- carla_ego_vehicle/CMakeLists.txt | 4 +++- carla_infrastructure/CMakeLists.txt | 4 +++- carla_manual_control/CMakeLists.txt | 5 ++++- carla_ros_bridge/CMakeLists.txt | 6 ++++-- carla_ros_scenario_runner/CMakeLists.txt | 4 +++- carla_spectator_camera/CMakeLists.txt | 4 +++- carla_twist_to_control/CMakeLists.txt | 4 +++- carla_walker_agent/CMakeLists.txt | 4 +++- carla_waypoint_publisher/CMakeLists.txt | 4 +++- pcl_recorder/CMakeLists.txt | 4 +++- 13 files changed, 41 insertions(+), 14 deletions(-) diff --git a/carla_ackermann_control/CMakeLists.txt b/carla_ackermann_control/CMakeLists.txt index 1cbe1d28..5ff13eab 100644 --- a/carla_ackermann_control/CMakeLists.txt +++ b/carla_ackermann_control/CMakeLists.txt @@ -23,7 +23,9 @@ generate_messages(DEPENDENCIES std_msgs carla_msgs) generate_dynamic_reconfigure_options(config/EgoVehicleControlParameter.cfg) -roslaunch_add_file_check(launch) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() catkin_package() diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index ac90c3e6..1da3d913 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() catkin_package(CATKIN_DEPENDS rospy) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 2a6504fb..6fa8cdc0 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -3,7 +3,9 @@ project(carla_ad_demo) find_package(catkin REQUIRED COMPONENTS roslaunch) -roslaunch_add_file_check(launch) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() catkin_package() diff --git a/carla_ego_vehicle/CMakeLists.txt b/carla_ego_vehicle/CMakeLists.txt index caae5a98..401e6e2a 100644 --- a/carla_ego_vehicle/CMakeLists.txt +++ b/carla_ego_vehicle/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) +endif() catkin_package(CATKIN_DEPENDS rospy) diff --git a/carla_infrastructure/CMakeLists.txt b/carla_infrastructure/CMakeLists.txt index 925b4159..972c1313 100644 --- a/carla_infrastructure/CMakeLists.txt +++ b/carla_infrastructure/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) +endif() catkin_package(CATKIN_DEPENDS rospy) diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index 03c6a55a..7c57ea34 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -5,7 +5,10 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() + catkin_package(CATKIN_DEPENDS rospy) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index c5ff0e04..27b91d1d 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -9,8 +9,10 @@ catkin_python_setup() catkin_package() -roslaunch_add_file_check(launch) -roslaunch_add_file_check(test) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) + roslaunch_add_file_check(test) +endif() include_directories(${catkin_INCLUDE_DIRS}) diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt index 90bfe9a0..bda894d8 100644 --- a/carla_ros_scenario_runner/CMakeLists.txt +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) +endif() catkin_package() diff --git a/carla_spectator_camera/CMakeLists.txt b/carla_spectator_camera/CMakeLists.txt index dbc2c555..aef4b66a 100644 --- a/carla_spectator_camera/CMakeLists.txt +++ b/carla_spectator_camera/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch geometry_msgs) catkin_python_setup() -roslaunch_add_file_check(launch) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() catkin_package(CATKIN_DEPENDS rospy) diff --git a/carla_twist_to_control/CMakeLists.txt b/carla_twist_to_control/CMakeLists.txt index c4878e70..1e2bda72 100644 --- a/carla_twist_to_control/CMakeLists.txt +++ b/carla_twist_to_control/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() catkin_package(CATKIN_DEPENDS rospy) diff --git a/carla_walker_agent/CMakeLists.txt b/carla_walker_agent/CMakeLists.txt index f59f0cc6..6ad8709a 100644 --- a/carla_walker_agent/CMakeLists.txt +++ b/carla_walker_agent/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() catkin_package(CATKIN_DEPENDS rospy) diff --git a/carla_waypoint_publisher/CMakeLists.txt b/carla_waypoint_publisher/CMakeLists.txt index 6f2a336a..90511347 100644 --- a/carla_waypoint_publisher/CMakeLists.txt +++ b/carla_waypoint_publisher/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() catkin_package(CATKIN_DEPENDS rospy) diff --git a/pcl_recorder/CMakeLists.txt b/pcl_recorder/CMakeLists.txt index fe8b16bf..76476829 100644 --- a/pcl_recorder/CMakeLists.txt +++ b/pcl_recorder/CMakeLists.txt @@ -6,7 +6,9 @@ find_package(catkin REQUIRED COMPONENTS pcl_conversions pcl_ros roscpp catkin_package() -roslaunch_add_file_check(launch DEPENDENCIES ${PROJECT_NAME}_node) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch DEPENDENCIES ${PROJECT_NAME}_node) +endif() include_directories(include ${catkin_INCLUDE_DIRS}) From 49761f297d16e6f754a51075dcf35967d4e03409 Mon Sep 17 00:00:00 2001 From: Ilia Baltashov Date: Tue, 1 Dec 2020 20:17:01 +0300 Subject: [PATCH 386/627] Fix cmake format --- carla_manual_control/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/carla_manual_control/CMakeLists.txt b/carla_manual_control/CMakeLists.txt index 7c57ea34..1a1b943c 100644 --- a/carla_manual_control/CMakeLists.txt +++ b/carla_manual_control/CMakeLists.txt @@ -9,7 +9,6 @@ if(CATKIN_ENABLE_TESTING) roslaunch_add_file_check(launch) endif() - catkin_package(CATKIN_DEPENDS rospy) catkin_install_python(PROGRAMS src/carla_manual_control/carla_manual_control.py From e7804584fa41b6fb8a3c07b53c59010799951675 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Wed, 25 Nov 2020 10:38:37 +0100 Subject: [PATCH 387/627] add debian package build to github actions --- .github/workflows/ci.yml | 16 +++++++++++++++- .gitignore | 1 + packaging/.gitignore | 1 + packaging/build-deb.sh | 16 +++++++++++++++- 4 files changed, 32 insertions(+), 2 deletions(-) create mode 100644 packaging/.gitignore diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index d18ea823..42da6094 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -52,7 +52,21 @@ jobs: cd $GITHUB_WORKSPACE/../catkin_ws && catkin build --summarize --no-status --force-color catkin run_tests --no-status --force-color && catkin_test_results - catkin config --install && source devel/setup.bash + source devel/setup.bash cd $GITHUB_WORKSPACE # make pylint # TODO enable pylint + + debian: + runs-on: ubuntu-latest + container: ros:${{ matrix.ros-version }}-robot + strategy: + matrix: + ros-version: [melodic, noetic] + env: + SCENARIO_RUNNER_PATH: "" + DEBIAN_FRONTEND: "noninteractive" + steps: + - uses: actions/checkout@v2 + - name: Build Debian Package + run: packaging/build-deb.sh diff --git a/.gitignore b/.gitignore index cef1d6ac..0765bb13 100644 --- a/.gitignore +++ b/.gitignore @@ -3,5 +3,6 @@ build.gradle /CMakeLists.txt .catkin_workspace +# IDE .vscode .idea diff --git a/packaging/.gitignore b/packaging/.gitignore new file mode 100644 index 00000000..567609b1 --- /dev/null +++ b/packaging/.gitignore @@ -0,0 +1 @@ +build/ diff --git a/packaging/build-deb.sh b/packaging/build-deb.sh index 68a1fb04..d8aebe25 100755 --- a/packaging/build-deb.sh +++ b/packaging/build-deb.sh @@ -5,14 +5,28 @@ set -e SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" BUILD_DIR=${SCRIPT_DIR}/build/$(rosversion -d) WORKSPACE_DIR=${BUILD_DIR}/catkin_ws +if [ "$(rosversion -d)" = "noetic" ]; then + PYTHON_SUFFIX=3 +else + PYTHON_SUFFIX="" +fi +sudo apt update +sudo apt-get install --no-install-recommends -y \ + python$PYTHON_SUFFIX-osrf-pycommon \ + python$PYTHON_SUFFIX-catkin-tools \ + rsync \ + build-essential \ + dh-make + +rm -rf ${WORKSPACE_DIR} mkdir -p ${BUILD_DIR} ${WORKSPACE_DIR} # bring the code rsync -r ${SCRIPT_DIR}/../* ${WORKSPACE_DIR}/src --exclude packaging # init ros workspace source /opt/ros/$(rosversion -d)/setup.bash -cd ${WORKSPACE_DIR} && catkin_init_workspace +cd ${WORKSPACE_DIR} && catkin init # add debian files cp -r ${SCRIPT_DIR}/debian ${WORKSPACE_DIR} sed -i "s/{ROS_DIST}/$(rosversion -d)/g" ${WORKSPACE_DIR}/debian/control From e66e41334e428562a2d20ca9b188b7da2c826a5b Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 26 Nov 2020 15:28:34 +0100 Subject: [PATCH 388/627] using ros coordinate frame to define spawn points --- carla_ad_demo/launch/carla_ad_demo.launch | 2 +- carla_common/src/carla_common/transforms.py | 5 +++ carla_ego_vehicle/config/sensors.json | 6 ++- .../carla_ego_vehicle/carla_ego_vehicle.py | 43 ++++++------------- .../carla_infrastructure.py | 20 ++++----- .../carla_manual_control.py | 2 +- .../carla_waypoint_publisher.py | 26 ++--------- 7 files changed, 37 insertions(+), 67 deletions(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index ce4ad9fe..93f8d056 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -14,7 +14,7 @@ - + diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index add4b187..8547a4e2 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -336,6 +336,11 @@ def carla_location_to_pose(carla_location): return ros_pose +def RPY_to_ros_quaternion(roll, pitch, yaw): + quat = tf.transformations.quaternion_from_euler(roll, pitch, yaw) + return Quaternion(*quat) + + def ros_point_to_carla_location(ros_point): return carla.Location(ros_point.x, -ros_point.y, ros_point.z) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 6b98dc62..a513131e 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -49,7 +49,7 @@ { "type": "sensor.camera.rgb", "id": "view", - "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, + "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0, "image_size_x": 800, "image_size_y": 600, "fov": 90.0, @@ -199,6 +199,10 @@ { "type": "sensor.pseudo.objects", "id": "objectsensor1" + }, + { + "type": "sensor.pseudo.tf", + "id": "tf1" } ] } diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index bdea19db..7ba1e342 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -27,7 +27,7 @@ import rospy from tf.transformations import euler_from_quaternion, quaternion_from_euler from diagnostic_msgs.msg import KeyValue -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose +from geometry_msgs.msg import Point, PoseWithCovarianceStamped, Pose from carla_msgs.msg import CarlaWorldInfo import carla @@ -73,8 +73,8 @@ def __init__(self): raise ValueError("Invalid spawnpoint '{}'".format(spawn_point_param)) pose = Pose() pose.position.x = float(spawn_point[0]) - pose.position.y = -float(spawn_point[1]) - pose.position.z = float(spawn_point[2]) + pose.position.y = float(spawn_point[1]) + pose.position.z = float(spawn_point[2]) + 2 quat = quaternion_from_euler( math.radians(float(spawn_point[3])), math.radians(float(spawn_point[4])), @@ -134,24 +134,7 @@ def restart(self): spawn_point = None if self.actor_spawnpoint: - spawn_point = carla.Transform() - spawn_point.location.x = self.actor_spawnpoint.position.x - spawn_point.location.y = -self.actor_spawnpoint.position.y - spawn_point.location.z = self.actor_spawnpoint.position.z + \ - 2 # spawn 2m above ground - quaternion = ( - self.actor_spawnpoint.orientation.x, - self.actor_spawnpoint.orientation.y, - self.actor_spawnpoint.orientation.z, - self.actor_spawnpoint.orientation.w - ) - _, _, yaw = euler_from_quaternion(quaternion) - spawn_point.rotation.yaw = -math.degrees(yaw) - rospy.loginfo("Spawn {} at x={} y={} z={} yaw={}".format(self.role_name, - spawn_point.location.x, - spawn_point.location.y, - spawn_point.location.z, - spawn_point.rotation.yaw)) + spawn_point = trans.ros_pose_to_carla_transform(self.actor_spawnpoint) if self.player is not None: self.player.set_transform(spawn_point) @@ -218,21 +201,19 @@ def setup_sensors(self, sensors): sensor_spec['id'])) sensor_names.append(sensor_name) - sensor_location = carla.Location(x=sensor_spec.pop("x", 0.0), - y=sensor_spec.pop("y", 0.0), - z=sensor_spec.pop("z", 0.0)) - sensor_rotation = carla.Rotation( - pitch=sensor_spec.pop('pitch', 0.0), - roll=sensor_spec.pop('roll', 0.0), - yaw=sensor_spec.pop('yaw', 0.0)) - sensor_transform = carla.Transform(sensor_location, sensor_rotation) + sensor_location = Point(x=sensor_spec.pop("x", 0.0), + y=sensor_spec.pop("y", 0.0), + z=sensor_spec.pop("z", 0.0)) + sensor_rotation = trans.RPY_to_ros_quaternion( + roll=math.radians(sensor_spec.pop('roll', 0.0)), + pitch=math.radians(sensor_spec.pop('pitch', 0.0)), + yaw=math.radians(sensor_spec.pop('yaw', 0.0))) spawn_object_request = SpawnObjectRequest() spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id spawn_object_request.attach_to = self.player.id - spawn_object_request.transform = trans.carla_transform_to_ros_pose( - sensor_transform) + spawn_object_request.transform = Pose(sensor_location, sensor_rotation) for attribute, value in sensor_spec.items(): spawn_object_request.attributes.append( KeyValue(str(attribute), str(value))) diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 6467ef41..10958e95 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -18,6 +18,8 @@ import carla_common.transforms as trans from diagnostic_msgs.msg import KeyValue +from geometry_msgs.msg import Point, Pose + from carla_msgs.msg import CarlaWorldInfo from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest @@ -88,21 +90,19 @@ def setup_sensors(self, sensors): sensor_spec['id'])) sensor_names.append(sensor_name) - sensor_location = carla.Location(x=sensor_spec.pop("x", 0.0), - y=sensor_spec.pop("y", 0.0), - z=sensor_spec.pop("z", 0.0)) - sensor_rotation = carla.Rotation( - pitch=sensor_spec.pop('pitch', 0.0), - roll=sensor_spec.pop('roll', 0.0), - yaw=sensor_spec.pop('yaw', 0.0)) - sensor_transform = carla.Transform(sensor_location, sensor_rotation) + sensor_location = Point(x=sensor_spec.pop("x", 0.0), + y=sensor_spec.pop("y", 0.0), + z=sensor_spec.pop("z", 0.0)) + sensor_rotation = trans.RPY_to_ros_quaternion( + roll=math.radians(sensor_spec.pop('roll', 0.0)), + pitch=math.radians(sensor_spec.pop('pitch', 0.0)), + yaw=math.radians(sensor_spec.pop('yaw', 0.0))) spawn_object_request = SpawnObjectRequest() spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id spawn_object_request.attach_to = 0 - spawn_object_request.transform = trans.carla_transform_to_ros_pose( - sensor_transform) + spawn_object_request.transform = Pose(sensor_location, sensor_rotation) for attribute, value in sensor_spec.items(): spawn_object_request.attributes.append( KeyValue(str(attribute), str(value))) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 57eb4107..4800231b 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -376,7 +376,7 @@ def update_info_text(self): _, _, yaw = tf.transformations.euler_from_quaternion(quaternion) yaw = -math.degrees(yaw) x = position[0] - y = -position[1] + y = position[1] z = position[2] except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException): x = 0 diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index fce5b3a7..9cfa4362 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -26,6 +26,7 @@ from tf.transformations import euler_from_quaternion from nav_msgs.msg import Path from geometry_msgs.msg import PoseStamped +import carla_common.transforms as trans from carla_msgs.msg import CarlaWorldInfo from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint @@ -141,19 +142,7 @@ def on_goal(self, goal): :return: """ rospy.loginfo("Received goal, trigger rerouting...") - carla_goal = carla.Transform() - carla_goal.location.x = goal.pose.position.x - carla_goal.location.y = -goal.pose.position.y - carla_goal.location.z = goal.pose.position.z + 2 # 2m above ground - quaternion = ( - goal.pose.orientation.x, - goal.pose.orientation.y, - goal.pose.orientation.z, - goal.pose.orientation.w - ) - _, _, yaw = euler_from_quaternion(quaternion) - carla_goal.rotation.yaw = -math.degrees(yaw) - + carla_goal = trans.ros_pose_to_carla_transform(goal.pose) self.goal = carla_goal self.reroute() @@ -235,16 +224,7 @@ def publish_waypoints(self): if self.current_route is not None: for wp in self.current_route: pose = PoseStamped() - pose.pose.position.x = wp[0].transform.location.x - pose.pose.position.y = -wp[0].transform.location.y - pose.pose.position.z = wp[0].transform.location.z - - quaternion = tf.transformations.quaternion_from_euler( - 0, 0, -math.radians(wp[0].transform.rotation.yaw)) - pose.pose.orientation.x = quaternion[0] - pose.pose.orientation.y = quaternion[1] - pose.pose.orientation.z = quaternion[2] - pose.pose.orientation.w = quaternion[3] + pose.pose = trans.carla_transform_to_ros_pose(wp[0].transform) msg.poses.append(pose) self.waypoint_publisher.publish(msg) From 7f9b7c664e3b18f6c57340092da41cd8e1fc705c Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 26 Nov 2020 18:42:37 +0100 Subject: [PATCH 389/627] fixed marker pose for vehicles --- .../src/carla_ros_bridge/actor_list_sensor.py | 2 +- .../carla_ros_bridge/traffic_lights_sensor.py | 2 +- .../carla_ros_bridge/traffic_participant.py | 21 +++++++++++-------- .../src/carla_ros_bridge/vehicle.py | 14 +++++++++++++ 4 files changed, 28 insertions(+), 11 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py index cdaf1545..4ca3520a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -45,7 +45,7 @@ def __init__(self, uid, name, parent, node, actor_list): prefix='actor_list/' + name) self.actor_list = actor_list self.actor_list_publisher = rospy.Publisher(self.get_topic_prefix() + - "actor_list", + "/actor_list", CarlaActorList, queue_size=10) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index ad9d1ad7..3b6777ed 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -41,7 +41,7 @@ def __init__(self, uid, name, parent, node, actor_list): super(TrafficLightsSensor, self).__init__(uid, parent=parent, node=node, - prefix="traffic_light/" + name) + prefix="traffic_lights/" + name) self.actor_list = actor_list self.traffic_light_status = CarlaTrafficLightStatusList() diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index ac2a1c1f..2267d728 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -106,7 +106,7 @@ def get_marker_color(self): # pylint: disable=no-self-use """ Function (override) to return the color for marker messages. - :return: the color used by a walkers marker + :return: default color used by traffic participants :rtpye : std_msgs.msg.ColorRGBA """ color = ColorRGBA() @@ -115,6 +115,15 @@ def get_marker_color(self): # pylint: disable=no-self-use color.b = 255 return color + def get_marker_pose(self): + """ + Function to return the pose for traffic participants. + + :return: the pose of the traffic participant. + :rtype: geometry_msgs.msg.Pose + """ + return trans.carla_transform_to_ros_pose(self.carla_actor.get_transform()) + def get_marker(self): """ Helper function to create a ROS visualization_msgs.msg.Marker for the actor @@ -122,19 +131,13 @@ def get_marker(self): :return: visualization_msgs.msg.Marker """ - # marker = Marker( - # header=self.get_msg_header(frame_id=str(self.get_id()))) - marker = Marker( - header=self.get_msg_header(frame_id="map")) + marker = Marker(header=self.get_msg_header(frame_id="map")) marker.color = self.get_marker_color() marker.color.a = 0.3 marker.id = self.get_id() marker.type = Marker.CUBE - # marker.pose = trans.carla_location_to_pose( - # self.carla_actor.bounding_box.location) - marker.pose = trans.carla_transform_to_ros_pose( - self.carla_actor.get_transform()) + marker.pose = self.get_marker_pose() marker.scale.x = self.carla_actor.bounding_box.extent.x * 2.0 marker.scale.y = self.carla_actor.bounding_box.extent.y * 2.0 marker.scale.z = self.carla_actor.bounding_box.extent.z * 2.0 diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 48da2c64..cc7051c2 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -13,6 +13,7 @@ from std_msgs.msg import ColorRGBA from derived_object_msgs.msg import Object +import carla_common.transforms as trans from carla_ros_bridge.traffic_participant import TrafficParticipant @@ -71,6 +72,19 @@ def get_marker_color(self): # pylint: disable=no-self-use color.g = 0 color.b = 0 return color + + def get_marker_pose(self): + """ + Function to return the pose for vehicles. + + :return: the pose of the vehicle + :rtype: geometry_msgs.msg.Pose + """ + # Moving pivot point from the bottom (CARLA) to the center (ROS) of the bounding box. + extent = self.carla_actor.bounding_box.extent + marker_transform = self.carla_actor.get_transform() + marker_transform.location -= marker_transform.get_up_vector() * extent.z + return trans.carla_transform_to_ros_pose(marker_transform) def get_classification(self): """ From 0a9031fd6e55a1b17519ceb24602ab073e6698ff Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 26 Nov 2020 18:44:30 +0100 Subject: [PATCH 390/627] added specific sensor configuration file for ad demo --- carla_ad_agent/src/carla_ad_agent/agent.py | 3 +- .../src/carla_ad_agent/basic_agent.py | 8 +- carla_ad_demo/config/carla_ad_demo.rviz | 157 +++--------------- carla_ad_demo/config/sensors.json | 51 ++++++ carla_ad_demo/launch/carla_ad_demo.launch | 2 +- .../launch/carla_ad_demo_with_scenario.launch | 2 +- 6 files changed, 85 insertions(+), 138 deletions(-) create mode 100644 carla_ad_demo/config/sensors.json diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 610cafe9..e0d174fe 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -52,7 +52,8 @@ def __init__(self, role_name, vehicle_id, avoid_risk): self._traffic_lights = [] self._traffic_light_status_subscriber = rospy.Subscriber( - "/carla/traffic_lights", CarlaTrafficLightStatusList, self.traffic_lights_updated) + "/carla/{}/traffic_lights/traffic_lights1/traffic_lights".format(role_name), + CarlaTrafficLightStatusList, self.traffic_lights_updated) self._world_info_subscriber = rospy.Subscriber( "/carla/world_info", CarlaWorldInfo, self.world_info_updated) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index ba0cec6c..6796949a 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -47,16 +47,18 @@ def __init__(self, role_name, ego_vehicle_id, avoid_risk=True): self._vehicle_id_list = [] self._lights_id_list = [] self._actors_subscriber = rospy.Subscriber( - "/carla/actor_list", CarlaActorList, self.actors_updated) + "/carla/{}/actor_list/actor_list1/actor_list".format(role_name), CarlaActorList, + self.actors_updated) self._objects = [] self._objects_subscriber = rospy.Subscriber( - "/carla/{}/objects".format(role_name), ObjectArray, self.objects_updated) + "/carla/{}/objects/objectsensor1/objects".format(role_name), ObjectArray, + self.objects_updated) self._get_actor_waypoint_client = rospy.ServiceProxy( '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), GetActorWaypoint) self._odometry_subscriber = rospy.Subscriber( - "/carla/{}/odometry".format(role_name), Odometry, self.odometry_updated) + "/carla/{}/odometry/odom1/odometry".format(role_name), Odometry, self.odometry_updated) def get_actor_waypoint(self, actor_id): """ diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index c37a00f4..fc8cf531 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -1,11 +1,11 @@ Panels: - Class: rviz/Displays - Help Height: 104 + Help Height: 0 Name: Displays Property Tree Widget: Expanded: ~ Splitter Ratio: 0.5 - Tree Height: 420 + Tree Height: 255 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -34,6 +34,14 @@ Toolbars: Visualization Manager: Class: "" Displays: + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /carla/ego_vehicle/markers/markers1/marker_array + Name: Markers + Namespaces: + "": true + Queue Size: 100 + Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path @@ -57,18 +65,10 @@ Visualization Manager: Topic: /carla/ego_vehicle/waypoints Unreliable: false Value: true - - Class: rviz/Marker - Enabled: true - Marker Topic: /carla/marker - Name: Marker - Namespaces: - "": true - Queue Size: 100 - Value: true - Class: rviz/Camera Enabled: true Image Rendering: background and overlay - Image Topic: /carla/ego_vehicle/camera/rgb/spectator_view/image_color + Image Topic: /carla/ego_vehicle/camera/rgb/front/image_color Name: RGB Camera Overlay Alpha: 0.5 Queue Size: 2 @@ -76,15 +76,10 @@ Visualization Manager: Unreliable: false Value: true Visibility: - DVS Camera: true - Depth Camera: true Lidar: true - Marker: true + Markers: true Path: true - Radar: true - Semantic Camera: true - Semantic Lidar: true - Value: true + Value: false Zoom Factor: 1 - Alpha: 1 Autocompute Intensity Bounds: true @@ -98,119 +93,23 @@ Visualization Manager: Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 - Enabled: false + Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 0.9843747615814209 + Max Intensity: 0.9852800369262695 Min Color: 0; 0; 0 - Min Intensity: 0.8187852501869202 + Min Intensity: 0.818818211555481 Name: Lidar Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 - Size (m): 0.029999999329447746 + Size (m): 0.05000000074505806 Style: Flat Squares Topic: /carla/ego_vehicle/lidar/lidar1/point_cloud Unreliable: false Use Fixed Frame: true Use rainbow: true - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: ObjTag - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 20 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Semantic Lidar - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.029999999329447746 - Style: Flat Squares - Topic: /carla/ego_vehicle/semantic_lidar/lidar1/point_cloud - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: Range - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: false - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 93.02222442626953 - Min Color: 0; 0; 0 - Min Intensity: 18.348487854003906 - Name: Radar - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.10000000149011612 - Style: Flat Squares - Topic: /carla/ego_vehicle/radar/front/radar_points - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: false - - Class: rviz/Image - Enabled: true - Image Topic: /carla/ego_vehicle/camera/dvs/front/image_events - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: DVS Camera - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /carla/ego_vehicle/camera/semantic_segmentation/front/image_segmentation - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Semantic Camera - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /carla/ego_vehicle/camera/depth/front/image_depth - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Depth Camera - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false Value: true Enabled: true Global Options: @@ -240,7 +139,7 @@ Visualization Manager: Views: Current: Class: rviz/ThirdPersonFollower - Distance: 15.07965087890625 + Distance: 35.58787155151367 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -255,36 +154,30 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.17539866268634796 + Pitch: 0.19539858400821686 Target Frame: ego_vehicle Value: ThirdPersonFollower (rviz) - Yaw: 3.155400276184082 + Yaw: 3.1354012489318848 Saved: ~ Window Geometry: CarlaControl: collapsed: false - DVS Camera: - collapsed: false - Depth Camera: - collapsed: false Displays: collapsed: false - Height: 1050 + Height: 1145 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 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 + QMainWindow State: 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 RGB Camera: collapsed: false Selection: collapsed: false - Semantic Camera: - collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false - Width: 1918 - X: 0 - Y: 29 + Width: 1871 + X: 49 + Y: 27 diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json new file mode 100644 index 00000000..82d38ed3 --- /dev/null +++ b/carla_ad_demo/config/sensors.json @@ -0,0 +1,51 @@ +{ + "sensors": [ + { + "type": "sensor.camera.rgb", + "id": "front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 + }, + { + "type": "sensor.camera.rgb", + "id": "view", + "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0 + }, + { + "type": "sensor.lidar.ray_cast", + "id": "lidar1", + "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05, + "noise_stddev": 0.0 + }, + { + "type": "sensor.pseudo.tf", + "id": "tf1" + }, + { + "type": "sensor.pseudo.odom", + "id": "odom1" + }, + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list1" + }, + { + "type": "sensor.pseudo.objects", + "id": "objectsensor1" + }, + { + "type": "sensor.pseudo.traffic_lights", + "id": "traffic_lights1" + }, + { + "type": "sensor.pseudo.markers", + "id": "markers1" + } + ] +} diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 93f8d056..3fcb6905 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -42,7 +42,7 @@ - + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index bd489866..6d258869 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -41,7 +41,7 @@ - + From 7a25ad232884d103854dde0f039f2b8c85ca5185 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Tue, 1 Dec 2020 12:14:20 +0100 Subject: [PATCH 391/627] new structure topic names topic names are now structured as follows: /carla///[ if more than one topic available ] --- carla_ad_agent/src/carla_ad_agent/agent.py | 2 +- .../src/carla_ad_agent/basic_agent.py | 6 +- carla_ad_demo/config/carla_ad_demo.rviz | 10 +- carla_ad_demo/config/sensors.json | 14 +- carla_ego_vehicle/config/sensors.json | 46 ++++-- .../carla_ego_vehicle/carla_ego_vehicle.py | 7 +- carla_infrastructure/config/sensors.json | 20 +++ .../carla_infrastructure.py | 8 +- .../carla_manual_control.py | 2 +- .../config/carla_default_rviz.cfg.rviz | 110 ++++++++------ .../src/carla_ros_bridge/actor.py | 12 +- .../src/carla_ros_bridge/actor_control.py | 8 +- .../src/carla_ros_bridge/actor_factory.py | 48 ++++--- .../src/carla_ros_bridge/actor_list_sensor.py | 13 +- .../src/carla_ros_bridge/camera.py | 135 ++++++------------ .../src/carla_ros_bridge/collision_sensor.py | 14 +- .../src/carla_ros_bridge/ego_vehicle.py | 12 +- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 16 ++- carla_ros_bridge/src/carla_ros_bridge/imu.py | 14 +- .../carla_ros_bridge/lane_invasion_sensor.py | 14 +- .../src/carla_ros_bridge/lidar.py | 37 +++-- .../src/carla_ros_bridge/marker_sensor.py | 11 +- .../src/carla_ros_bridge/object_sensor.py | 11 +- .../src/carla_ros_bridge/odom_sensor.py | 11 +- .../src/carla_ros_bridge/opendrive_sensor.py | 11 +- .../src/carla_ros_bridge/pseudo_actor.py | 48 ++----- .../src/carla_ros_bridge/radar.py | 17 +-- .../src/carla_ros_bridge/rss_sensor.py | 12 +- .../src/carla_ros_bridge/sensor.py | 15 +- .../src/carla_ros_bridge/spectator.py | 14 +- .../carla_ros_bridge/speedometer_sensor.py | 9 +- .../src/carla_ros_bridge/tf_sensor.py | 6 +- .../src/carla_ros_bridge/traffic.py | 24 ++-- .../carla_ros_bridge/traffic_lights_sensor.py | 10 +- .../carla_ros_bridge/traffic_participant.py | 14 +- .../src/carla_ros_bridge/vehicle.py | 17 +-- .../src/carla_ros_bridge/walker.py | 19 +-- .../src/carla_ros_bridge/world_info.py | 4 +- 38 files changed, 405 insertions(+), 396 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index e0d174fe..c4a8164c 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -52,7 +52,7 @@ def __init__(self, role_name, vehicle_id, avoid_risk): self._traffic_lights = [] self._traffic_light_status_subscriber = rospy.Subscriber( - "/carla/{}/traffic_lights/traffic_lights1/traffic_lights".format(role_name), + "/carla/{}/traffic_lights/status".format(role_name), CarlaTrafficLightStatusList, self.traffic_lights_updated) self._world_info_subscriber = rospy.Subscriber( diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 6796949a..b58f8f48 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -47,18 +47,18 @@ def __init__(self, role_name, ego_vehicle_id, avoid_risk=True): self._vehicle_id_list = [] self._lights_id_list = [] self._actors_subscriber = rospy.Subscriber( - "/carla/{}/actor_list/actor_list1/actor_list".format(role_name), CarlaActorList, + "/carla/{}/actor_list".format(role_name), CarlaActorList, self.actors_updated) self._objects = [] self._objects_subscriber = rospy.Subscriber( - "/carla/{}/objects/objectsensor1/objects".format(role_name), ObjectArray, + "/carla/{}/objects".format(role_name), ObjectArray, self.objects_updated) self._get_actor_waypoint_client = rospy.ServiceProxy( '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), GetActorWaypoint) self._odometry_subscriber = rospy.Subscriber( - "/carla/{}/odometry/odom1/odometry".format(role_name), Odometry, self.odometry_updated) + "/carla/{}/odometry".format(role_name), Odometry, self.odometry_updated) def get_actor_waypoint(self, actor_id): """ diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index fc8cf531..e9a09631 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -36,7 +36,7 @@ Visualization Manager: Displays: - Class: rviz/MarkerArray Enabled: true - Marker Topic: /carla/ego_vehicle/markers/markers1/marker_array + Marker Topic: /carla/ego_vehicle/markers Name: Markers Namespaces: "": true @@ -68,7 +68,7 @@ Visualization Manager: - Class: rviz/Camera Enabled: true Image Rendering: background and overlay - Image Topic: /carla/ego_vehicle/camera/rgb/front/image_color + Image Topic: /carla/ego_vehicle/rgb_front/image Name: RGB Camera Overlay Alpha: 0.5 Queue Size: 2 @@ -96,9 +96,9 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 0.9852800369262695 + Max Intensity: 0.9798204302787781 Min Color: 0; 0; 0 - Min Intensity: 0.818818211555481 + Min Intensity: 0.8189767003059387 Name: Lidar Position Transformer: XYZ Queue Size: 10 @@ -106,7 +106,7 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.05000000074505806 Style: Flat Squares - Topic: /carla/ego_vehicle/lidar/lidar1/point_cloud + Topic: /carla/ego_vehicle/lidar1 Unreliable: false Use Fixed Frame: true Use rainbow: true diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json index 82d38ed3..61260036 100644 --- a/carla_ad_demo/config/sensors.json +++ b/carla_ad_demo/config/sensors.json @@ -2,12 +2,12 @@ "sensors": [ { "type": "sensor.camera.rgb", - "id": "front", + "id": "rgb_front", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 }, { "type": "sensor.camera.rgb", - "id": "view", + "id": "rgb_view", "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0 }, { @@ -29,23 +29,23 @@ }, { "type": "sensor.pseudo.odom", - "id": "odom1" + "id": "odometry" }, { "type": "sensor.pseudo.actor_list", - "id": "actor_list1" + "id": "actor_list" }, { "type": "sensor.pseudo.objects", - "id": "objectsensor1" + "id": "objects" }, { "type": "sensor.pseudo.traffic_lights", - "id": "traffic_lights1" + "id": "traffic_lights" }, { "type": "sensor.pseudo.markers", - "id": "markers1" + "id": "markers" } ] } diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index a513131e..d461d228 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -2,7 +2,7 @@ "sensors": [ { "type": "sensor.camera.rgb", - "id": "front", + "id": "rgb_front", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "image_size_x": 800, "image_size_y": 600, @@ -48,7 +48,7 @@ }, { "type": "sensor.camera.rgb", - "id": "view", + "id": "rgb_view", "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0, "image_size_x": 800, "image_size_y": 600, @@ -94,7 +94,7 @@ }, { "type": "sensor.lidar.ray_cast", - "id": "lidar1", + "id": "lidar", "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "range": 50, "channels": 32, @@ -107,7 +107,7 @@ }, { "type": "sensor.lidar.ray_cast_semantic", - "id": "lidar1", + "id": "semantic_lidar", "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "range": 50, "channels": 32, @@ -119,7 +119,7 @@ }, { "type": "sensor.other.radar", - "id": "front", + "id": "radar_front", "x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "horizontal_fov": 30.0, "vertical_fov": 10.0, @@ -128,7 +128,7 @@ }, { "type": "sensor.camera.semantic_segmentation", - "id": "front", + "id": "semantic_segmentation_front", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "fov": 90.0, "image_size_x": 400, @@ -143,7 +143,7 @@ }, { "type": "sensor.camera.depth", - "id": "front", + "id": "depth_front", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "fov": 90.0, "image_size_x": 400, @@ -158,7 +158,7 @@ }, { "type": "sensor.camera.dvs", - "id": "front", + "id": "dvs_front", "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "fov": 90.0, "image_size_x": 400, @@ -173,14 +173,14 @@ }, { "type": "sensor.other.gnss", - "id": "gnss1", + "id": "gnss", "x": 1.0, "y": 0.0, "z": 2.0, "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": "imu1", + "id": "imu", "x": 2.0, "y": 0.0, "z": 2.0, "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, @@ -188,21 +188,37 @@ }, { "type": "sensor.other.collision", - "id": "collision1", + "id": "collision", "x": 0.0, "y": 0.0, "z": 0.0 }, { "type": "sensor.other.lane_invasion", - "id": "laneinvasion1", + "id": "lane_invasion", "x": 0.0, "y": 0.0, "z": 0.0 }, + { + "type": "sensor.pseudo.tf", + "id": "tf" + }, { "type": "sensor.pseudo.objects", - "id": "objectsensor1" + "id": "objects" }, { - "type": "sensor.pseudo.tf", - "id": "tf1" + "type": "actor.pseudo.control", + "id": "control" + }, + { + "type": "sensor.pseudo.odom", + "id": "odometry" + }, + { + "type": "sensor.pseudo.speedometer", + "id": "speedometer" + }, + { + "type": "sensor.pseudo.markers", + "id": "markers" } ] } diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 7ba1e342..73618f3f 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -191,15 +191,14 @@ def setup_sensors(self, sensors): sensor_type = str(sensor_spec.pop("type")) sensor_id = str(sensor_spec.pop("id")) - sensor_name = sensor_type + "/" + sensor_id - if sensor_name in sensor_names: + if sensor_id in sensor_names: rospy.logfatal( "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) raise NameError( "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) - sensor_names.append(sensor_name) + sensor_names.append(sensor_id) sensor_location = Point(x=sensor_spec.pop("x", 0.0), y=sensor_spec.pop("y", 0.0), @@ -230,7 +229,7 @@ def setup_sensors(self, sensors): except Exception as e: rospy.logfatal( - "Sensor {} will not be spawned, {}".format(sensor_name, e)) + "Sensor {} will not be spawned, {}".format(sensor_id, e)) raise e actors.append(response.id) diff --git a/carla_infrastructure/config/sensors.json b/carla_infrastructure/config/sensors.json index b7ad0b92..5847828a 100644 --- a/carla_infrastructure/config/sensors.json +++ b/carla_infrastructure/config/sensors.json @@ -53,6 +53,26 @@ "upper_fov": 2.0, "lower_fov": -26.8, "rotation_frequency": 20 + }, + { + "type": "sensor.pseudo.traffic_lights", + "id": "traffic_lights" + }, + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list" + }, + { + "type": "sensor.pseudo.markers", + "id": "markers" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, + { + "type": "sensor.pseudo.opendrive_map", + "id": "map" } ] } diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py index 10958e95..631a0656 100755 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py @@ -13,6 +13,7 @@ import os import json +import math import rospy import carla_common.transforms as trans @@ -80,15 +81,14 @@ def setup_sensors(self, sensors): sensor_type = str(sensor_spec.pop("type")) sensor_id = str(sensor_spec.pop("id")) - sensor_name = sensor_type + "/" + sensor_id - if sensor_name in sensor_names: + if sensor_id in sensor_names: rospy.logfatal( "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) raise NameError( "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) - sensor_names.append(sensor_name) + sensor_names.append(sensor_id) sensor_location = Point(x=sensor_spec.pop("x", 0.0), y=sensor_spec.pop("y", 0.0), @@ -119,7 +119,7 @@ def setup_sensors(self, sensors): except Exception as e: rospy.logfatal( - "Sensor {} will not be spawned, {}".format(sensor_name, e)) + "Sensor {} will not be spawned, {}".format(sensor_id, e)) raise e actors.append(response.id) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 4800231b..23ffe764 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -86,7 +86,7 @@ def __init__(self, role_name, hud): self.hud = hud self.role_name = role_name self.image_subscriber = rospy.Subscriber( - "/carla/{}/camera/rgb/view/image_color".format(self.role_name), + "/carla/{}/rgb_view/image".format(self.role_name), Image, self.on_view_image) self.collision_subscriber = rospy.Subscriber( "/carla/{}/collision".format(self.role_name), CarlaCollisionEvent, self.on_collision) diff --git a/carla_ros_bridge/config/carla_default_rviz.cfg.rviz b/carla_ros_bridge/config/carla_default_rviz.cfg.rviz index 1a249b9a..3f3f0d17 100644 --- a/carla_ros_bridge/config/carla_default_rviz.cfg.rviz +++ b/carla_ros_bridge/config/carla_default_rviz.cfg.rviz @@ -7,10 +7,8 @@ Panels: - /Global Options1 - /Status1 - /Grid1 - - /Marker1 - - /Image1 - Splitter Ratio: 0.600000024 - Tree Height: 362 + Splitter Ratio: 0.6000000238418579 + Tree Height: 366 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -19,11 +17,10 @@ Panels: - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties - Splitter Ratio: 0.588679016 + Splitter Ratio: 0.5886790156364441 - Class: rviz/Views Expanded: - /Current View1 - - /Current View1/Focal Point1 Name: Views Splitter Ratio: 0.5 - Class: rviz/Time @@ -38,7 +35,11 @@ Panels: Expanded: - /PointCloud21 Splitter Ratio: 0.5 - Tree Height: 791 + Tree Height: 818 +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 Visualization Manager: Class: "" Displays: @@ -48,7 +49,7 @@ Visualization Manager: Color: 160; 160; 164 Enabled: true Line Style: - Line Width: 0.0299999993 + Line Width: 0.029999999329447746 Value: Lines Name: Grid Normal Cell Count: 0 @@ -60,21 +61,25 @@ Visualization Manager: Plane Cell Count: 10 Reference Frame: ego_vehicle Value: true - - Class: rviz/Marker + - Class: rviz/Image Enabled: true - Marker Topic: /carla/vehicle_marker - Name: Marker - Namespaces: - "": true - Queue Size: 100 + Image Topic: /carla/ego_vehicle/rgb_front/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: RGB Camera + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false Value: true - Class: rviz/Image Enabled: true - Image Topic: /carla/ego_vehicle/camera/rgb/front/image_color + Image Topic: /carla/ego_vehicle/dvs_front/image Max Value: 1 Median window: 5 Min Value: 0 - Name: Image + Name: DVS Camera Normalize Range: true Queue Size: 2 Transport Hint: raw @@ -82,11 +87,11 @@ Visualization Manager: Value: true - Class: rviz/Image Enabled: true - Image Topic: /carla/ego_vehicle/camera/depth/front/image_depth + Image Topic: /carla/ego_vehicle/depth_front/image Max Value: 1 Median window: 5 Min Value: 0 - Name: Image + Name: Depth Camera Normalize Range: true Queue Size: 2 Transport Hint: raw @@ -94,11 +99,11 @@ Visualization Manager: Value: true - Class: rviz/Image Enabled: true - Image Topic: /carla/ego_vehicle/camera/semantic_segmentation/front/image_segmentation + Image Topic: /carla/ego_vehicle/semantic_segmentation_front/image Max Value: 1 Median window: 5 Min Value: 0 - Name: Image + Name: Semantic Segmentation Camera Normalize Range: true Queue Size: 2 Transport Hint: raw @@ -115,25 +120,33 @@ Visualization Manager: Class: rviz/PointCloud2 Color: 255; 255; 255 Color Transformer: Intensity - Decay Time: 1 + Decay Time: 0 Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 + Max Intensity: 0.9806249737739563 Min Color: 0; 0; 0 - Min Intensity: 0 + Min Intensity: 0.8187550902366638 Name: PointCloud2 Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 - Size (m): 0.00999999978 - Style: Points - Topic: /carla/ego_vehicle/lidar/front/point_cloud + Size (m): 0.05000000074505806 + Style: Squares + Topic: /carla/ego_vehicle/lidar Unreliable: false Use Fixed Frame: true Use rainbow: true Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /carla/ego_vehicle/markers + Name: Markers + Namespaces: + "": true + Queue Size: 100 + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -149,7 +162,10 @@ Visualization Manager: - Class: rviz/FocusCamera - Class: rviz/Measure - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 - Class: rviz/SetGoal Topic: /move_base_simple/goal - Class: rviz/PublishPoint @@ -158,44 +174,50 @@ Visualization Manager: Value: true Views: Current: - Class: rviz/Orbit - Distance: 66.8334961 + Class: rviz/ThirdPersonFollower + Distance: 17.369640350341797 Enable Stereo Rendering: - Stereo Eye Separation: 0.0599999987 + Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0.899166584 - Y: -3.9905889 - Z: 4.50506401 - Focal Shape Fixed Size: true - Focal Shape Size: 0.0500000007 + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View - Near Clip Distance: 0.00999999978 - Pitch: 0.249798894 + Near Clip Distance: 0.009999999776482582 + Pitch: 0.21539832651615143 Target Frame: ego_vehicle - Value: Orbit (rviz) - Yaw: 1.92412555 + Value: ThirdPersonFollower (rviz) + Yaw: 3.180402994155884 Saved: ~ Window Geometry: + DVS Camera: + collapsed: false + Depth Camera: + collapsed: false Displays: collapsed: false - Height: 1103 + Height: 1145 Hide Left Dock: false Hide Right Dock: false - Image: + QMainWindow State: 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 + RGB Camera: collapsed: false - QMainWindow State: 000000ff00000000fd0000000400000000000002bd000003c1fc020000000cfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000028000000d7000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650100000028000001330000001600fffffffb0000000a0049006d00610067006501000001610000015e0000001600fffffffb0000000a0049006d00610067006501000002c5000001240000001600fffffffb0000000a0049006d00610067006501000002b8000001310000000000000000000000010000016a000003c1fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fc00000028000003c1000000f50100001dfa000000000100000002fb000000100044006900730070006c0061007900730100000000ffffffff0000016a00fffffffb0000000a00560069006500770073010000063a0000010f0000010f00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000074900000042fc0100000002fb0000000800540069006d00650100000000000007490000030000fffffffb0000000800540069006d0065010000000000000450000000000000000000000316000003c100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false + Semantic Segmentation Camera: + collapsed: false Time: collapsed: false Tool Properties: collapsed: false Views: collapsed: false - Width: 1865 - X: 55 - Y: 30 + Width: 1871 + X: 49 + Y: 27 diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index f6d63b67..c660db77 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -23,22 +23,22 @@ class Actor(PseudoActor): Generic base class for all carla actors """ - def __init__(self, uid, carla_actor, parent, node, prefix=None): + def __init__(self, uid, name, parent, node, carla_actor): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla vehicle actor object - :type carla_actor: carla.Vehicle + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge - :param prefix: the topic prefix to be used for this actor - :type prefix: string + :param carla_actor: carla actor object + :type carla_actor: carla.Actor """ - super(Actor, self).__init__(uid=uid, parent=parent, prefix=prefix, node=node) + super(Actor, self).__init__(uid=uid, name=name, parent=parent, node=node) self.carla_actor = carla_actor self.carla_actor_id = carla_actor.id diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index 39efce4e..e8ae9edd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -28,7 +28,7 @@ def __init__(self, uid, name, parent, node): :param uid: unique identifier for this object :type uid: int - :param name: name identifying the sensor + :param name: name identifying this object :type name: string :param carla_world: carla world object :type carla_world: carla.World @@ -36,10 +36,10 @@ def __init__(self, uid, name, parent, node): :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge - """ - super(ActorControl, self).__init__(uid, + super(ActorControl, self).__init__(uid=uid, + name=name, parent=parent, node=node) @@ -73,7 +73,7 @@ def get_blueprint_name(): Get the blueprint identifier for the pseudo actor :return: name """ - return "pseudo.actor.control" + return "actor.pseudo.control" def on_pose(self, pose): if self.parent and self.parent.carla_actor.is_alive: diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index c9a4ab97..1c38a207 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -116,8 +116,10 @@ def _create_carla_actor(self, carla_actor): if parent is not None: parent_id = parent.uid - return self.create(carla_actor.type_id, carla_actor.attributes.get("rolename", ""), - parent_id, carla_actor) + name = carla_actor.attributes.get("rolename", "") + if not name: + name = str(carla_actor.id) + return self.create(carla_actor.type_id, name, parent_id, carla_actor) def create(self, type_id, name, attach_to, carla_actor=None): with self.lock: @@ -222,53 +224,53 @@ def _create_object(self, uid, type_id, name, parent, carla_actor=None): elif carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": - actor = TrafficLight(uid, carla_actor, parent, node=self.node) + actor = TrafficLight(uid, name, parent, self.node, carla_actor) else: - actor = Traffic(uid, carla_actor, parent, node=self.node) + actor = Traffic(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("vehicle"): if carla_actor.attributes.get('role_name')\ in self.node.parameters['ego_vehicle']['role_name']: - actor = EgoVehicle(uid, carla_actor, parent, self.node, + actor = EgoVehicle(uid, name, parent, self.node, carla_actor, self.node._ego_vehicle_control_applied_callback) else: - actor = Vehicle(uid, carla_actor, parent, self.node) + actor = Vehicle(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("sensor"): if carla_actor.type_id.startswith("sensor.camera"): if carla_actor.type_id.startswith("sensor.camera.rgb"): - actor = RgbCamera(uid, carla_actor, parent, self.node, self.sync_mode) + actor = RgbCamera(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.depth"): - actor = DepthCamera(uid, carla_actor, parent, self.node, self.sync_mode) + actor = DepthCamera(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.semantic_segmentation"): - actor = SemanticSegmentationCamera(uid, carla_actor, parent, self.node, + actor = SemanticSegmentationCamera(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.dvs"): - actor = DVSCamera(uid, carla_actor, parent, self.node, self.sync_mode) + actor = DVSCamera(uid, name, parent, self.node, carla_actor, self.sync_mode) else: - actor = Camera(uid, carla_actor, parent, self.node, self.sync_mode) + actor = Camera(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.lidar"): if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): - actor = Lidar(uid, carla_actor, parent, self.node, self.sync_mode) + actor = Lidar(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.endswith("sensor.lidar.ray_cast_semantic"): - actor = SemanticLidar(uid, carla_actor, parent, self.node, self.sync_mode) + actor = SemanticLidar(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): - actor = Radar(uid, carla_actor, parent, self.node, self.sync_mode) + actor = Radar(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): - actor = Gnss(uid, carla_actor, parent, self.node, self.sync_mode) + actor = Gnss(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): - actor = ImuSensor(uid, carla_actor, parent, self.node, self.sync_mode) + actor = ImuSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): - actor = CollisionSensor(uid, carla_actor, parent, self.node, self.sync_mode) + actor = CollisionSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.rss"): - actor = RssSensor(uid, carla_actor, parent, self.node, self.sync_mode) + actor = RssSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): - actor = LaneInvasionSensor(uid, carla_actor, parent, self.node, self.sync_mode) + actor = LaneInvasionSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) else: - actor = Sensor(uid, carla_actor, parent, self.node, self.sync_mode) + actor = Sensor(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("spectator"): - actor = Spectator(uid, carla_actor, parent, self.node) + actor = Spectator(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("walker"): - actor = Walker(uid, carla_actor, parent, self.node) + actor = Walker(uid, name, parent, self.node, carla_actor) else: - actor = Actor(uid, carla_actor, parent, self.node) + actor = Actor(uid, name, parent, self.node, carla_actor) return actor diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py index 4ca3520a..27ecf769 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -25,9 +25,9 @@ class ActorListSensor(PseudoActor): def __init__(self, uid, name, parent, node, actor_list): """ Constructor - :param uid: unique identifier for this object. + :param uid: unique identifier for this object :type uid: int - :param name: name identiying the sensor + :param name: name identiying this object :type name: string :param carla_world: carla world object :type carla_world: carla.World @@ -39,13 +39,12 @@ def __init__(self, uid, name, parent, node, actor_list): :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(ActorListSensor, self).__init__(uid, + super(ActorListSensor, self).__init__(uid=uid, + name=name, parent=parent, - node=node, - prefix='actor_list/' + name) + node=node) self.actor_list = actor_list - self.actor_list_publisher = rospy.Publisher(self.get_topic_prefix() + - "/actor_list", + self.actor_list_publisher = rospy.Publisher(self.get_topic_prefix(), CarlaActorList, queue_size=10) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 5d6f7584..f0e675ce 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -34,35 +34,35 @@ class Camera(Sensor): # global cv bridge to convert image between opencv and ros cv_bridge = CvBridge() - def __init__(self, uid, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): # pylint: disable=too-many-arguments """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge - :param prefix: the topic prefix to be used for this actor - :type prefix: string + :param carla_actor: carla actor object + :type carla_actor: carla.Actor + :param synchronous_mode: use in synchronous mode? + :type synchronous_mode: bool """ - if not prefix: - prefix = 'camera' super(Camera, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix=prefix) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) if self.__class__.__name__ == "Camera": rospy.logwarn("Created Unsupported Camera Actor" - "(id={}, parent_id={}, type={}, attributes={})".format( - self.get_id(), self.get_parent_id(), - self.carla_actor.type_id, self.carla_actor.attributes)) + "(id={}, type={}, attributes={})".format(self.get_id(), + self.carla_actor.type_id, + self.carla_actor.attributes)) else: self._build_camera_info() @@ -71,8 +71,7 @@ def __init__(self, uid, carla_actor, parent, node, synchronous_mode, prefix=None CameraInfo, queue_size=10) - self.camera_image_publisher = rospy.Publisher(self.get_topic_prefix() + '/' + - self.get_image_topic_name(), + self.camera_image_publisher = rospy.Publisher(self.get_topic_prefix() + '/' + 'image', Image, queue_size=10) @@ -165,17 +164,6 @@ def get_carla_image_data_array(self, carla_camera_data): raise NotImplementedError( "This function has to be re-implemented by derived classes") - @abstractmethod - def get_image_topic_name(self): - """ - Virtual function to provide the actual image topic name - - :return image topic name - :rtype string - """ - raise NotImplementedError( - "This function has to be re-implemented by derived classes") - class RgbCamera(Camera): @@ -183,28 +171,29 @@ class RgbCamera(Camera): Camera implementation details for rgb camera """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(RgbCamera, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix='camera/rgb/' + - carla_actor.attributes.get('role_name')) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) self.listen() @@ -227,15 +216,6 @@ def get_carla_image_data_array(self, carla_image): return carla_image_data_array, 'bgra8' - def get_image_topic_name(self): - """ - virtual function to provide the actual image topic name - - :return image topic name - :rtype string - """ - return "image_color" - class DepthCamera(Camera): @@ -243,28 +223,29 @@ class DepthCamera(Camera): Camera implementation details for depth camera """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(DepthCamera, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix='camera/depth/' + - carla_actor.attributes.get('role_name')) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) self.listen() @@ -309,15 +290,6 @@ def get_carla_image_data_array(self, carla_image): # which is automatically selected by cv bridge with passthrough return depth_image, 'passthrough' - def get_image_topic_name(self): - """ - Function (override) to provide the actual image topic name - - :return image topic name - :rtype string - """ - return "image_depth" - class SemanticSegmentationCamera(Camera): @@ -325,29 +297,30 @@ class SemanticSegmentationCamera(Camera): Camera implementation details for segmentation camera """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super( SemanticSegmentationCamera, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, synchronous_mode=synchronous_mode, - prefix='camera/semantic_segmentation/' + - carla_actor.attributes.get('role_name')) + carla_actor=carla_actor) self.listen() @@ -371,15 +344,6 @@ def get_carla_image_data_array(self, carla_image): dtype=numpy.uint8, buffer=carla_image.raw_data) return carla_image_data_array, 'bgra8' - def get_image_topic_name(self): - """ - Function (override) to provide the actual image topic name - - :return image topic name - :rtype string - """ - return "image_segmentation" - class DVSCamera(Camera): @@ -387,27 +351,27 @@ class DVSCamera(Camera): Sensor implementation details for dvs cameras """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): # pylint: disable=too-many-arguments """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge - :param prefix: the topic prefix to be used for this actor - :type prefix: string + :param carla_actor: carla actor object + :type carla_actor: carla.Actor + :param synchronous_mode: use in synchronous mode? + :type synchronous_mode: bool """ super(DVSCamera, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix='camera/dvs/' + carla_actor.attributes.get('role_name')) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) self._dvs_events = None self.dvs_camera_publisher = rospy.Publisher(self.get_topic_prefix() + @@ -466,12 +430,3 @@ def get_carla_image_data_array(self, carla_dvs_event_array): self._dvs_events[:]['pol'] * 2] = 255 return carla_image_data_array, 'bgr8' - - def get_image_topic_name(self): - """ - Function (override) to provide the actual image topic name - - :return image topic name - :rtype string - """ - return "image_events" diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index 1568db2a..b590cb12 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -22,28 +22,30 @@ class CollisionSensor(Sensor): Actor implementation details for a collision sensor """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(CollisionSensor, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, + carla_actor=carla_actor, synchronous_mode=synchronous_mode, - is_event_sensor=True, - prefix="collision") + is_event_sensor=True) self.collision_publisher = rospy.Publisher(self.get_topic_prefix(), CarlaCollisionEvent, diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index f8eedf29..d449afc3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -34,24 +34,26 @@ class EgoVehicle(Vehicle): Vehicle implementation details for the ego vehicle """ - def __init__(self, uid, carla_actor, parent, node, vehicle_control_applied_callback): + def __init__(self, uid, name, parent, node, carla_actor, vehicle_control_applied_callback): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor """ super(EgoVehicle, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - prefix=carla_actor.attributes.get('role_name')) + carla_actor=carla_actor) self.vehicle_info_published = False self.vehicle_control_override = False diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index 0c1143af..163d2cbf 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -23,29 +23,31 @@ class Gnss(Sensor): Actor implementation details for gnss sensor """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(Gnss, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix="gnss/" + carla_actor.attributes.get('role_name')) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) - self.gnss_publisher = rospy.Publisher(self.get_topic_prefix() + '/fix', + self.gnss_publisher = rospy.Publisher(self.get_topic_prefix(), NavSatFix, queue_size=10) self.listen() diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index e3d820bb..b34fdd4a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -21,27 +21,29 @@ class ImuSensor(Sensor): Actor implementation details for imu sensor """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor : carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor : carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(ImuSensor, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix="imu/" + carla_actor.attributes.get('role_name')) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) self.imu_publisher = rospy.Publisher(self.get_topic_prefix(), Imu, queue_size=10) self.listen() diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index f66e3b08..668e85a3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -22,28 +22,30 @@ class LaneInvasionSensor(Sensor): Actor implementation details for a lane invasion sensor """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(LaneInvasionSensor, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, + carla_actor=carla_actor, synchronous_mode=synchronous_mode, - is_event_sensor=True, - prefix="lane_invasion") + is_event_sensor=True) self.lane_invasion_publisher = rospy.Publisher(self.get_topic_prefix(), CarlaLaneInvasionEvent, diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 0151db8b..91aba283 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -26,28 +26,31 @@ class Lidar(Sensor): Actor implementation details for lidars """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor + :param synchronous_mode: use in synchronous mode? + :type synchronous_mode: bool """ super(Lidar, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix='lidar/' + carla_actor.attributes.get('role_name')) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) - self.lidar_publisher = rospy.Publisher(self.get_topic_prefix() + - "/point_cloud", + self.lidar_publisher = rospy.Publisher(self.get_topic_prefix(), PointCloud2, queue_size=10) self.listen() @@ -85,28 +88,32 @@ class SemanticLidar(Sensor): Actor implementation details for semantic lidars """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor + :param synchronous_mode: use in synchronous mode? + :type synchronous_mode: bool """ super(SemanticLidar, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix='semantic_lidar/' + carla_actor.attributes.get('role_name')) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) self.semantic_lidar_publisher = rospy.Publisher( - self.get_topic_prefix() + "/point_cloud", + self.get_topic_prefix(), PointCloud2, queue_size=10) self.listen() diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index 4f8adce0..7a4df585 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -29,7 +29,7 @@ def __init__(self, uid, name, parent, node, actor_list): :param uid: unique identifier for this object :type uid: int - :param name: name identiying the sensor + :param name: name identiying this object :type name: string :param carla_world: carla world object :type carla_world: carla.World @@ -41,14 +41,13 @@ def __init__(self, uid, name, parent, node, actor_list): :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(MarkerSensor, self).__init__(uid, + super(MarkerSensor, self).__init__(uid=uid, + name=name, parent=parent, - node=node, - prefix='markers/' + name) + node=node) self.actor_list = actor_list - self.marker_publisher = rospy.Publisher(self.get_topic_prefix() + - "/marker_array", + self.marker_publisher = rospy.Publisher(self.get_topic_prefix(), MarkerArray, queue_size=10) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index a81c1533..60d0a98d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -29,7 +29,7 @@ def __init__(self, uid, name, parent, node, actor_list): :param uid: unique identifier for this object :type uid: int - :param name: name identiying the sensor + :param name: name identiying this object :type name: string :param carla_world: carla world object :type carla_world: carla.World @@ -41,13 +41,12 @@ def __init__(self, uid, name, parent, node, actor_list): :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(ObjectSensor, self).__init__(uid, + super(ObjectSensor, self).__init__(uid=uid, + name=name, parent=parent, - node=node, - prefix='objects/' + name) + node=node) self.actor_list = actor_list - self.object_publisher = rospy.Publisher(self.get_topic_prefix() + - "/objects", + self.object_publisher = rospy.Publisher(self.get_topic_prefix(), ObjectArray, queue_size=10) diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 6c9ff76f..6813da30 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -28,7 +28,7 @@ def __init__(self, uid, name, parent, node): :param uid: unique identifier for this object :type uid: int - :param name: name identiying the sensor + :param name: name identiying this object :type name: string :param carla_world: carla world object :type carla_world: carla.World @@ -38,13 +38,12 @@ def __init__(self, uid, name, parent, node): :type node: carla_ros_bridge.CarlaRosBridge """ - super(OdometrySensor, self).__init__(uid, + super(OdometrySensor, self).__init__(uid=uid, + name=name, parent=parent, - node=node, - prefix='odometry/' + name) + node=node) - self.odometry_publisher = rospy.Publisher(self.get_topic_prefix() + - "/odometry", + self.odometry_publisher = rospy.Publisher(self.get_topic_prefix(), Odometry, queue_size=10) diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index a0a9649d..7b3b1f2e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -29,7 +29,7 @@ def __init__(self, uid, name, parent, node, carla_map): :param uid: unique identifier for this object :type uid: int - :param name: name identiying the sensor + :param name: name identiying this object :type name: string :param carla_world: carla world object :type carla_world: carla.World @@ -40,14 +40,13 @@ def __init__(self, uid, name, parent, node, carla_map): :param carla_map: carla map object :type carla_map: carla.Map """ - super(OpenDriveSensor, self).__init__(uid, + super(OpenDriveSensor, self).__init__(uid=uid, + name=name, parent=parent, - node=node, - prefix='opendrive/' + name) - + node=node) self.carla_map = carla_map self._map_published = False - self.map_publisher = rospy.Publisher(self.get_topic_prefix() + "/map", + self.map_publisher = rospy.Publisher(self.get_topic_prefix(), String, queue_size=10, latch=True) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index c308ea56..26578657 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -20,39 +20,26 @@ class PseudoActor(object): Generic base class for Pseudo actors (that are not existing in Carla world) """ - def __init__(self, uid, parent, node, prefix=None): + def __init__(self, uid, name, parent, node): """ Constructor :param uid: unique identifier for this object :type uid: int + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.PseudoActor - :param prefix: the topic prefix to be used for this actor - :type prefix: string :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge """ self.uid = uid - if self.uid > np.iinfo(np.uint32).max: - raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) - + self.name = name self.parent = parent - if self.parent: - self.parent_id = parent.get_id() - else: - self.parent_id = None - self.node = node - # Concatenate the onw prefix to the the parent topic name if not empty. - self.prefix = "" - if parent: - self.prefix = parent.get_prefix() - if prefix: - if self.prefix: - self.prefix += "/" - self.prefix += prefix + if self.uid > np.iinfo(np.uint32).max: + raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) def destroy(self): """ @@ -87,13 +74,16 @@ def get_msg_header(self, frame_id=None, timestamp=None): header.stamp = self.node.ros_timestamp return header - def get_parent_id(self): + def get_prefix(self): """ - Getter for the carla_id of the parent. - :return: unique carla_id of the parent of this child - :rtype: int64 + get the fully qualified prefix of object + :return: prefix + :rtype: string """ - return self.parent_id + if self.parent is not None: + return self.parent.get_prefix() + "/" + self.name + else: + return self.name def get_topic_prefix(self): """ @@ -102,15 +92,7 @@ def get_topic_prefix(self): :return: the final topic name of this object :rtype: string """ - return "/carla/" + self.prefix - - def get_prefix(self): - """ - get the fully qualified prefix of object - :return: prefix - :rtype: string - """ - return self.prefix + return "/carla/" + self.get_prefix() def update(self, frame, timestamp): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 53bd2faa..622498e8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -27,30 +27,31 @@ class Radar(Sensor): Actor implementation details of Carla RADAR """ - def __init__(self, uid, carla_actor, parent, node, synchronous_mode): + def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool """ super(Radar, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - synchronous_mode=synchronous_mode, - prefix="radar/" + carla_actor.attributes.get('role_name')) + carla_actor=carla_actor, + synchronous_mode=synchronous_mode) - self.radar_publisher = rospy.Publisher(self.get_topic_prefix() + - "/radar_points", + self.radar_publisher = rospy.Publisher(self.get_topic_prefix(), PointCloud2, queue_size=10) self.listen() diff --git a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py index 16ca2909..1376dd4d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py @@ -22,22 +22,24 @@ class RssSensor(Actor): utilization it's not handled as a sensor here. """ - def __init__(self, uid, carla_actor, parent, node, _): + def __init__(self, uid, name, parent, node, carla_actor, _): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor """ super(RssSensor, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - prefix="rss") + carla_actor=carla_actor) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 90ff4c24..6cdc8fbc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -29,9 +29,10 @@ class Sensor(Actor): def __init__(self, # pylint: disable=too-many-arguments uid, - carla_actor, + name, parent, node, + carla_actor, synchronous_mode, is_event_sensor=False, # only relevant in synchronous_mode: # if a sensor only delivers data on special events, @@ -43,24 +44,24 @@ def __init__(self, # pylint: disable=too-many-arguments :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor :param synchronous_mode: use in synchronous mode? :type synchronous_mode: bool :param prefix: the topic prefix to be used for this actor :type prefix: string """ - if prefix is None: - prefix = 'sensor' super(Sensor, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - prefix=prefix) + carla_actor=carla_actor) self.synchronous_mode = synchronous_mode self.queue = queue.Queue() diff --git a/carla_ros_bridge/src/carla_ros_bridge/spectator.py b/carla_ros_bridge/src/carla_ros_bridge/spectator.py index e8d3695f..bcde6a6d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/spectator.py +++ b/carla_ros_bridge/src/carla_ros_bridge/spectator.py @@ -19,21 +19,23 @@ class Spectator(Actor): Actor implementation details for spectators """ - def __init__(self, uid, carla_actor, parent, node): + def __init__(self, uid, name, parent, node, carla_actor): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor """ super(Spectator, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, - prefix='spectator', - node=node) + node=node, + carla_actor=carla_actor) diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index fd914911..68282efe 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -39,13 +39,12 @@ def __init__(self, uid, name, parent, node): :type node: carla_ros_bridge.CarlaRosBridge """ - super(SpeedometerSensor, self).__init__(uid, + super(SpeedometerSensor, self).__init__(uid=uid, + name=name, parent=parent, - node=node, - prefix='speedometer/' + name) + node=node) - self.speedometer_publisher = rospy.Publisher(self.get_topic_prefix() + - "/speedometer", + self.speedometer_publisher = rospy.Publisher(self.get_topic_prefix(), Float32, queue_size=10) diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 83b11924..3af7183f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -38,10 +38,10 @@ def __init__(self, uid, name, parent, node): :type node: carla_ros_bridge.CarlaRosBridge """ - super(TFSensor, self).__init__(uid, + super(TFSensor, self).__init__(uid=uid, + name=name, parent=parent, - node=node, - prefix=None) + node=node) self.tf_broadcaster = tf.TransformBroadcaster() diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index cb765a94..f0e387bc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -22,24 +22,26 @@ class Traffic(Actor): Actor implementation details for traffic objects """ - def __init__(self, uid, carla_actor, parent, node): + def __init__(self, uid, name, parent, node, carla_actor): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.Actor """ super(Traffic, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - prefix='traffic') + carla_actor=carla_actor) class TrafficLight(Actor): @@ -48,24 +50,26 @@ class TrafficLight(Actor): Traffic implementation details for traffic lights """ - def __init__(self, uid, carla_actor, parent, node): + def __init__(self, uid, name, parent, node, carla_actor): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.TrafficLight + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge + :param carla_actor: carla actor object + :type carla_actor: carla.TrafficLight """ super(TrafficLight, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - prefix='traffic.traffic_light') + carla_actor=carla_actor) def get_status(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 3b6777ed..db46258f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -38,22 +38,22 @@ def __init__(self, uid, name, parent, node, actor_list): :type actor_list: map(carla-actor-id -> python-actor-object) """ - super(TrafficLightsSensor, self).__init__(uid, + super(TrafficLightsSensor, self).__init__(uid=uid, + name=name, parent=parent, - node=node, - prefix="traffic_lights/" + name) + node=node) self.actor_list = actor_list self.traffic_light_status = CarlaTrafficLightStatusList() self.traffic_light_actors = [] self.traffic_lights_info_publisher = rospy.Publisher( - self.get_topic_prefix() + "/traffic_lights_info", + self.get_topic_prefix() + "/info", CarlaTrafficLightInfoList, queue_size=10, latch=True) self.traffic_lights_status_publisher = rospy.Publisher( - self.get_topic_prefix() + "/traffic_lights", + self.get_topic_prefix() + "/status", CarlaTrafficLightStatusList, queue_size=10, latch=True) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 2267d728..97f7f294 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -27,27 +27,27 @@ class TrafficParticipant(Actor): actor implementation details for traffic participant """ - def __init__(self, uid, carla_actor, parent, node, prefix): + def __init__(self, uid, name,parent, node, carla_actor): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla actor object - :type carla_actor: carla.Actor + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge - :param prefix: the topic prefix to be used for this actor - :type prefix: string + :param carla_actor: carla actor object + :type carla_actor: carla.Actor """ self.classification_age = 0 super(TrafficParticipant, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - prefix=prefix) + carla_actor=carla_actor) def update(self, frame, timestamp): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index cc7051c2..9c0b9efe 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -23,24 +23,21 @@ class Vehicle(TrafficParticipant): Actor implementation details for vehicles """ - def __init__(self, uid, carla_actor, parent, node, prefix=None): + def __init__(self, uid, name, parent, node, carla_actor): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla vehicle actor object - :type carla_actor: carla.Vehicle + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge - :param prefix: the topic prefix to be used for this actor - :type prefix: string + :param carla_actor: carla vehicle actor object + :type carla_actor: carla.Vehicle """ - if not prefix: - prefix = "vehicle/{:03}".format(carla_actor.id) - self.classification = Object.CLASSIFICATION_CAR if 'object_type' in carla_actor.attributes: if carla_actor.attributes['object_type'] == 'car': @@ -55,10 +52,10 @@ def __init__(self, uid, carla_actor, parent, node, prefix=None): self.classification = Object.CLASSIFICATION_OTHER_VEHICLE super(Vehicle, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - prefix=prefix) + carla_actor=carla_actor) def get_marker_color(self): # pylint: disable=no-self-use """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index bbd3ec0e..98df4b82 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -23,31 +23,26 @@ class Walker(TrafficParticipant): Actor implementation details for pedestrians """ - def __init__(self, uid, carla_actor, parent, node): + def __init__(self, uid, name, parent, node, carla_actor): """ Constructor :param uid: unique identifier for this object :type uid: int - :param carla_actor: carla walker actor object - :type carla_actor: carla.Walker + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge - :param prefix: the topic prefix to be used for this actor - :type prefix: string + :param carla_actor: carla walker actor object + :type carla_actor: carla.Walker """ - if carla_actor.attributes.get('role_name'): - prefix = carla_actor.attributes.get('role_name') - else: - prefix = "walker/{:03}".format(carla_actor.id) - super(Walker, self).__init__(uid=uid, - carla_actor=carla_actor, + name=name, parent=parent, node=node, - prefix=prefix) + carla_actor=carla_actor) self.control_subscriber = rospy.Subscriber( self.get_topic_prefix() + "/walker_control_cmd", diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index 0ea11d1d..b0b7c551 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -33,9 +33,9 @@ def __init__(self, carla_world, node): """ super(WorldInfo, self).__init__(uid=None, + name="world_info", parent=None, - node=node, - prefix="world_info") + node=node) self.carla_map = carla_world.get_map() From 8cf55a7c9fba336dc240ac116972558450bc6b88 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Tue, 1 Dec 2020 13:09:38 +0100 Subject: [PATCH 392/627] README updated --- README.md | 126 ++++++++++++++++++++++++++++++------------------------ 1 file changed, 70 insertions(+), 56 deletions(-) diff --git a/README.md b/README.md index d1c062e1..afd650e0 100644 --- a/README.md +++ b/README.md @@ -155,90 +155,137 @@ A [CARLA Control rqt plugin](rqt_carla_control/README.md) is available to publis ## Available ROS Topics -### Ego Vehicle +### Sensors -#### Sensors +Sensor data is provided via topic with prefix `/carla/[]//[]` -The ego vehicle sensors are provided via topics with prefix /carla/ego_vehicle/<sensor_topic> +The following sensors are available: -Currently the following sensors are supported: +#### CARLA sensors ##### RGB camera | Topic | Type | | -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla//camera/rgb//image_color` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | -| `/carla//camera/rgb//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | +| `/carla/[]//image` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | ##### Depth camera | Topic | Type | | -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla//camera/depth//image_depth` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | -| `/carla//camera/depth//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | +| `/carla/[]//image` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | ##### Semantic segmentation camera | Topic | Type | | -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla//camera/semantic_segmentation//image_segmentation` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | -| `/carla//camera/semantic_segmentation//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | +| `/carla/[]//image` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | ##### DVS camera | Topic | Type | | -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla//camera/dvs//events` | [sensor_msgs.PointCloud2](http://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | -| `/carla//camera/dvs//image_events` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | -| `/carla//camera/dvs//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | +| `/carla/[]//events` | [sensor_msgs.PointCloud2](http://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]//image` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | ##### Lidar | Topic | Type | | --------------------------------------------------------- | ---------------------------------------------------------------------------------------- | -| `/carla//lidar//point_cloud` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]/` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | ##### Semantic lidar | Topic | Type | | --------------------------------------------------------- | ---------------------------------------------------------------------------------------- | -| `/carla//semantic_lidar//point_cloud` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]/` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | ##### Radar | Topic | Type | | -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla//radar//radar_points` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]/` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | ##### IMU | Topic | Type | | ------------------------ | --------------------------------------------------------------------------------- | -| `/carla//imu` | [sensor_msgs.Imu](https://docs.ros.org/api/sensor_msgs/html/msg/Imu.html) | +| `/carla/[]/` | [sensor_msgs.Imu](https://docs.ros.org/api/sensor_msgs/html/msg/Imu.html) | ##### GNSS | Topic | Type | Description | | ------------------------------------------------ | ------------------------------------------------------------------------------------ | --------------------- | -| `/carla//gnss//fix` | [sensor_msgs.NavSatFix](http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html) | publish gnss location | +| `/carla/[]/` | [sensor_msgs.NavSatFix](http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html) | publish gnss location | ##### Collision Sensor | Topic | Type | Description | | ------------------------------ | ------------------------------------------------------------------------ | ------------------------ | -| `/carla//collision` | [carla_msgs.CarlaCollisionEvent](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaCollisionEvent.msg) | publish collision events | +| `/carla/[]/` | [carla_msgs.CarlaCollisionEvent](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaCollisionEvent.msg) | publish collision events | ##### Lane Invasion Sensor | Topic | Type | Description | | ---------------------------------- | ------------------------------------------------------------------------------ | ------------------------------- | -| `/carla//lane_invasion` | [carla_msgs.CarlaLaneInvasionEvent](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaLaneInvasionEvent.msg) | publish events on lane-invasion | +| `/carla/[]/` | [carla_msgs.CarlaLaneInvasionEvent](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaLaneInvasionEvent.msg) | publish events on lane-invasion | + +#### Pseudo sensors + +##### TF Sensor + +The tf data for the ego vehicle is published when this pseudo sensor is spawned. + +**Note**: Sensors publish the tf data when the measurement is done. The `child_frame_id` corresponds with the prefix of the sensor topics. + +##### Odometry Sensor + +| Topic | Type | Description | +| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | +| `/carla//` | [nav_msgs.Odometry](http://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | odometry of the parent actor | + +##### Speedometer Sensor + +| Topic | Type | Description | +| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | +| `/carla//` | [std_msgs.Float32](http://docs.ros.org/en/api/std_msgs/html/msg/Float32.html) | speed of the parent actor | + +##### Map Sensor + +| Topic | Type | Description | +| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | +| `/carla/[]/` | [std_msgs.String](http://docs.ros.org/en/api/std_msgs/html/msg/String.html) | OpenDRIVE map content | + +##### Object Sensor + +| Topic | Type | Description | +| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | +| `/carla/[]/` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers, except the parent actor if any | -#### Object Sensor +##### Marker Sensor | Topic | Type | Description | | ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla//objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers, except the ego vehicle | +| `/carla/[]/` | [visualization_msgs.Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) | visualization of vehicles and walkers | + +##### Traffic Lights Sensor + +| Topic | Type | Description | +| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | +| `/carla/[]//status` | [carla_msgs.CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightStatusList.msg) | list of all traffic lights with their status | +| `/carla/[]//info` | [carla_msgs.CarlaTrafficLightInfoList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightInfoList.msg) | static information for all traffic lights (e.g. position)| + +##### Actor List Sensor + +| Topic | Type | Description | +| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | +| `/carla/[]/` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaActorList.msg) | list of all carla actors | + +### Ego Vehicle #### Control @@ -292,17 +339,10 @@ In certain cases, the [Carla Control Command](https://github.com/carla-simulator Therefore a ROS-based node `carla_ackermann_control` is provided which reads [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) messages. You can find further documentation [here](carla_ackermann_control/README.md). -### Other Topics - -#### Object information of other actors +### Other topics | Topic | Type | Description | | ------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------- | -| `/carla/objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers | -| `/carla/marker` | [visualization_msgs.Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) | visualization of vehicles and walkers | -| `/carla/actor_list` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaActorList.msg) | list of all carla actors | -| `/carla/traffic_lights` | [carla_msgs.CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightStatusList.msg) | list of all traffic lights with their status | -| `/carla/traffic_lights_info` | [carla_msgs.CarlaTrafficLightInfoList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightInfoList.msg) | static information for all traffic lights (e.g. position)| | `/carla/weather_control` | [carla_msgs.CarlaWeatherParameters](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWeatherParameters.msg) | set the CARLA weather parameters| #### Status of CARLA @@ -312,32 +352,6 @@ You can find further documentation [here](carla_ackermann_control/README.md). | `/carla/status` | [carla_msgs.CarlaStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaStatus.msg) | | | `/carla/world_info` | [carla_msgs.CarlaWorldInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWorldInfo.msg) | Info about the CARLA world/level (e.g. OPEN Drive map) | -### Walker - -| Topic | Type | Description | -| ---------------------------------------------------- | ---------------------------------------------------------------------------- | ------------------ | -| `/carla/walker//walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWalkerControl.msg) | Control a walker | -| `/carla/walker//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of walker | - -### Other Vehicles - -| Topic | Type | Description | -| ------------------------------ | ---------------------------------------------------------------------------- | ------------------- | -| `/carla/vehicle//odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | odometry of vehicle | - -### TF - -The tf data is published for all traffic participants and sensors. - -#### TF for traffic participants - -The `child_frame_id` corresponds with the CARLA actor id. -If a role name is specified, an additional (static) transform with role name as child_frame_id is published. - -#### TF for sensors - -Sensors publish the transform, when the measurement is done. The `child_frame_id` corresponds with the prefix of the sensor topics. - ### Debug Marker It is possible to draw markers in CARLA. From f450d6a85f83acdc4b1a3eda0d0826b71bf0c8c9 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 2 Dec 2020 14:52:02 +0100 Subject: [PATCH 393/627] review changes * Removed specific sensor configuration file for ad demo. * Updated README --- README.md | 13 +- carla_ad_demo/config/carla_ad_demo.rviz | 151 +++++++++++++++--- carla_ad_demo/config/sensors.json | 51 ------ carla_ad_demo/launch/carla_ad_demo.launch | 4 +- .../launch/carla_ad_demo_with_scenario.launch | 2 +- carla_ego_vehicle/config/sensors.json | 20 ++- .../carla_ego_vehicle/carla_ego_vehicle.py | 2 +- .../src/carla_ros_bridge/actor_factory.py | 2 +- 8 files changed, 160 insertions(+), 85 deletions(-) delete mode 100644 carla_ad_demo/config/sensors.json diff --git a/README.md b/README.md index afd650e0..83c71055 100644 --- a/README.md +++ b/README.md @@ -252,19 +252,19 @@ The tf data for the ego vehicle is published when this pseudo sensor is spawned. | Topic | Type | Description | | ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla//` | [std_msgs.Float32](http://docs.ros.org/en/api/std_msgs/html/msg/Float32.html) | speed of the parent actor | +| `/carla//` | [std_msgs.Float32](http://docs.ros.org/en/api/std_msgs/html/msg/Float32.html) | speed of the parent actor. Units: m/s | ##### Map Sensor | Topic | Type | Description | | ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla/[]/` | [std_msgs.String](http://docs.ros.org/en/api/std_msgs/html/msg/String.html) | OpenDRIVE map content | +| `/carla/[]/` | [std_msgs.String](http://docs.ros.org/en/api/std_msgs/html/msg/String.html) | provides the OpenDRIVE map as a string on a latched topic. | ##### Object Sensor | Topic | Type | Description | | ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla/[]/` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | all vehicles and walkers, except the parent actor if any | +| `/carla/[]/` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | publishes all vehicles and walker. If attached to a parent, the parent is not contained. | ##### Marker Sensor @@ -352,6 +352,13 @@ You can find further documentation [here](carla_ackermann_control/README.md). | `/carla/status` | [carla_msgs.CarlaStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaStatus.msg) | | | `/carla/world_info` | [carla_msgs.CarlaWorldInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWorldInfo.msg) | Info about the CARLA world/level (e.g. OPEN Drive map) | +#### Walker + +| Topic | Type | Description | +| ---------------------------------------------------- | ---------------------------------------------------------------------------- | ------------------ | +| `/carla//walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWalkerControl.msg) | Control a walker | + + ### Debug Marker It is possible to draw markers in CARLA. diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index e9a09631..593847eb 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -5,7 +5,7 @@ Panels: Property Tree Widget: Expanded: ~ Splitter Ratio: 0.5 - Tree Height: 255 + Tree Height: 632 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -24,7 +24,7 @@ Panels: Experimental: false Name: Time SyncMode: 0 - SyncSource: RGB Camera + SyncSource: DVS Camera - Class: rviz_carla_plugin/CarlaControl Name: CarlaControl Preferences: @@ -34,14 +34,6 @@ Toolbars: Visualization Manager: Class: "" Displays: - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /carla/ego_vehicle/markers - Name: Markers - Namespaces: - "": true - Queue Size: 100 - Value: true - Alpha: 1 Buffer Length: 1 Class: rviz/Path @@ -65,10 +57,18 @@ Visualization Manager: Topic: /carla/ego_vehicle/waypoints Unreliable: false Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /carla/ego_vehicle/markers + Name: MarkerArray + Namespaces: + "": true + Queue Size: 100 + Value: true - Class: rviz/Camera Enabled: true Image Rendering: background and overlay - Image Topic: /carla/ego_vehicle/rgb_front/image + Image Topic: /carla/ego_vehicle/spectator_view/image Name: RGB Camera Overlay Alpha: 0.5 Queue Size: 2 @@ -76,10 +76,15 @@ Visualization Manager: Unreliable: false Value: true Visibility: + DVS Camera: true + Depth Camera: true Lidar: true - Markers: true + MarkerArray: true Path: true - Value: false + Radar: true + Semantic Camera: true + Semantic Lidar: true + Value: true Zoom Factor: 1 - Alpha: 1 Autocompute Intensity Bounds: true @@ -93,23 +98,119 @@ Visualization Manager: Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 - Enabled: true + Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 0.9798204302787781 + Max Intensity: 0.9843747615814209 Min Color: 0; 0; 0 - Min Intensity: 0.8189767003059387 + Min Intensity: 0.8187852501869202 Name: Lidar Position Transformer: XYZ Queue Size: 10 Selectable: true Size (Pixels): 3 - Size (m): 0.05000000074505806 + Size (m): 0.029999999329447746 + Style: Flat Squares + Topic: /carla/ego_vehicle/lidar/lidar1/point_cloud + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: ObjTag + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 20 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Semantic Lidar + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.029999999329447746 Style: Flat Squares - Topic: /carla/ego_vehicle/lidar1 + Topic: /carla/ego_vehicle/semantic_lidar/lidar1/point_cloud Unreliable: false Use Fixed Frame: true Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: Range + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 93.02222442626953 + Min Color: 0; 0; 0 + Min Intensity: 18.348487854003906 + Name: Radar + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.10000000149011612 + Style: Flat Squares + Topic: /carla/ego_vehicle/radar/front/radar_points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: false + - Class: rviz/Image + Enabled: true + Image Topic: /carla/ego_vehicle/dvs_front/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: DVS Camera + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /carla/ego_vehicle/semantic_segmentation_front/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Semantic Camera + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /carla/ego_vehicle/depth_front/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Depth Camera + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false Value: true Enabled: true Global Options: @@ -139,7 +240,7 @@ Visualization Manager: Views: Current: Class: rviz/ThirdPersonFollower - Distance: 35.58787155151367 + Distance: 15.07965087890625 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -154,24 +255,30 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.19539858400821686 + Pitch: 0.17539866268634796 Target Frame: ego_vehicle Value: ThirdPersonFollower (rviz) - Yaw: 3.1354012489318848 + Yaw: 3.155400276184082 Saved: ~ Window Geometry: CarlaControl: collapsed: false + DVS Camera: + collapsed: false + Depth Camera: + collapsed: false Displays: collapsed: false Height: 1145 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 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 + QMainWindow State: 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 RGB Camera: collapsed: false Selection: collapsed: false + Semantic Camera: + collapsed: false Time: collapsed: false Tool Properties: diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json deleted file mode 100644 index 61260036..00000000 --- a/carla_ad_demo/config/sensors.json +++ /dev/null @@ -1,51 +0,0 @@ -{ - "sensors": [ - { - "type": "sensor.camera.rgb", - "id": "rgb_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0 - }, - { - "type": "sensor.camera.rgb", - "id": "rgb_view", - "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0 - }, - { - "type": "sensor.lidar.ray_cast", - "id": "lidar1", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, - "rotation_frequency": 20, - "sensor_tick": 0.05, - "noise_stddev": 0.0 - }, - { - "type": "sensor.pseudo.tf", - "id": "tf1" - }, - { - "type": "sensor.pseudo.odom", - "id": "odometry" - }, - { - "type": "sensor.pseudo.actor_list", - "id": "actor_list" - }, - { - "type": "sensor.pseudo.objects", - "id": "objects" - }, - { - "type": "sensor.pseudo.traffic_lights", - "id": "traffic_lights" - }, - { - "type": "sensor.pseudo.markers", - "id": "markers" - } - ] -} diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 3fcb6905..2f4f115a 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -14,7 +14,7 @@ - + @@ -42,7 +42,7 @@ - + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index 6d258869..bd489866 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -41,7 +41,7 @@ - + diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index d461d228..572ea232 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -204,10 +204,6 @@ "type": "sensor.pseudo.objects", "id": "objects" }, - { - "type": "actor.pseudo.control", - "id": "control" - }, { "type": "sensor.pseudo.odom", "id": "odometry" @@ -216,9 +212,25 @@ "type": "sensor.pseudo.speedometer", "id": "speedometer" }, + { + "type": "actor.pseudo.control", + "id": "control" + }, + { + "type": "sensor.pseudo.traffic_lights", + "id": "traffic_lights" + }, + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list" + }, { "type": "sensor.pseudo.markers", "id": "markers" + }, + { + "type": "sensor.pseudo.opendrive_map", + "id": "map" } ] } diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index 73618f3f..ff636f36 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -74,7 +74,7 @@ def __init__(self): pose = Pose() pose.position.x = float(spawn_point[0]) pose.position.y = float(spawn_point[1]) - pose.position.z = float(spawn_point[2]) + 2 + pose.position.z = float(spawn_point[2]) quat = quaternion_from_euler( math.radians(float(spawn_point[3])), math.radians(float(spawn_point[4])), diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 1c38a207..ce3a5f89 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -116,7 +116,7 @@ def _create_carla_actor(self, carla_actor): if parent is not None: parent_id = parent.uid - name = carla_actor.attributes.get("rolename", "") + name = carla_actor.attributes.get("role_name", "") if not name: name = str(carla_actor.id) return self.create(carla_actor.type_id, name, parent_id, carla_actor) From 6e219e1732dac9405edaac058b98ebee2d59f375 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 2 Dec 2020 16:16:39 +0100 Subject: [PATCH 394/627] using carla_infrastructure to spawn global sensors --- carla_ad_agent/src/carla_ad_agent/agent.py | 2 +- .../src/carla_ad_agent/basic_agent.py | 3 +- carla_ad_demo/config/carla_ad_demo.rviz | 20 +- carla_ad_demo/launch/carla_ad_demo.launch | 8 + .../launch/carla_ad_demo_with_scenario.launch | 8 + carla_ad_demo/package.xml | 1 + carla_ego_vehicle/config/sensors.json | 16 -- carla_infrastructure/config/sensors.json | 58 ----- .../config/carla_default_rviz.cfg.rviz | 6 +- ...ros_bridge_with_example_ego_vehicle.launch | 7 + carla_ros_bridge/package.xml | 1 + carla_ros_bridge/test/ros_bridge_client.py | 72 +++--- carla_ros_bridge/test/ros_bridge_client.test | 8 + .../test/test_infrastructure_sensors.json | 24 ++ carla_ros_bridge/test/test_sensors.json | 216 +++++++++--------- 15 files changed, 217 insertions(+), 233 deletions(-) create mode 100644 carla_ros_bridge/test/test_infrastructure_sensors.json diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index c4a8164c..4073d6fc 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -52,7 +52,7 @@ def __init__(self, role_name, vehicle_id, avoid_risk): self._traffic_lights = [] self._traffic_light_status_subscriber = rospy.Subscriber( - "/carla/{}/traffic_lights/status".format(role_name), + "/carla/traffic_lights/status", CarlaTrafficLightStatusList, self.traffic_lights_updated) self._world_info_subscriber = rospy.Subscriber( diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index b58f8f48..86037ee7 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -47,8 +47,7 @@ def __init__(self, role_name, ego_vehicle_id, avoid_risk=True): self._vehicle_id_list = [] self._lights_id_list = [] self._actors_subscriber = rospy.Subscriber( - "/carla/{}/actor_list".format(role_name), CarlaActorList, - self.actors_updated) + "/carla/actor_list", CarlaActorList, self.actors_updated) self._objects = [] self._objects_subscriber = rospy.Subscriber( "/carla/{}/objects".format(role_name), ObjectArray, diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index 593847eb..1121ee30 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -59,7 +59,7 @@ Visualization Manager: Value: true - Class: rviz/MarkerArray Enabled: true - Marker Topic: /carla/ego_vehicle/markers + Marker Topic: /carla/markers Name: MarkerArray Namespaces: "": true @@ -98,12 +98,12 @@ Visualization Manager: Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 - Enabled: false + Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 0.9843747615814209 + Max Intensity: 0.9798224568367004 Min Color: 0; 0; 0 - Min Intensity: 0.8187852501869202 + Min Intensity: 0.8187355995178223 Name: Lidar Position Transformer: XYZ Queue Size: 10 @@ -111,11 +111,11 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.029999999329447746 Style: Flat Squares - Topic: /carla/ego_vehicle/lidar/lidar1/point_cloud + Topic: /carla/ego_vehicle/lidar Unreliable: false Use Fixed Frame: true Use rainbow: true - Value: false + Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: @@ -141,7 +141,7 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.029999999329447746 Style: Flat Squares - Topic: /carla/ego_vehicle/semantic_lidar/lidar1/point_cloud + Topic: /carla/ego_vehicle/semantic_lidar Unreliable: false Use Fixed Frame: true Use rainbow: true @@ -161,9 +161,9 @@ Visualization Manager: Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 93.02222442626953 + Max Intensity: 98.80625915527344 Min Color: 0; 0; 0 - Min Intensity: 18.348487854003906 + Min Intensity: 21.431447982788086 Name: Radar Position Transformer: XYZ Queue Size: 10 @@ -171,7 +171,7 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.10000000149011612 Style: Flat Squares - Topic: /carla/ego_vehicle/radar/front/radar_points + Topic: /carla/ego_vehicle/radar_front Unreliable: false Use Fixed Frame: true Use rainbow: true diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 2f4f115a..70921017 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -47,6 +47,14 @@ + + + + + + + + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index bd489866..84c5417e 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -45,6 +45,14 @@ + + + + + + + + diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 050c468e..0b4f5fcd 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -8,6 +8,7 @@ catkin carla_ros_bridge carla_ego_vehicle + carla_infrastructure carla_waypoint_publisher carla_ad_agent carla_manual_control diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json index 572ea232..d6a564fc 100644 --- a/carla_ego_vehicle/config/sensors.json +++ b/carla_ego_vehicle/config/sensors.json @@ -215,22 +215,6 @@ { "type": "actor.pseudo.control", "id": "control" - }, - { - "type": "sensor.pseudo.traffic_lights", - "id": "traffic_lights" - }, - { - "type": "sensor.pseudo.actor_list", - "id": "actor_list" - }, - { - "type": "sensor.pseudo.markers", - "id": "markers" - }, - { - "type": "sensor.pseudo.opendrive_map", - "id": "map" } ] } diff --git a/carla_infrastructure/config/sensors.json b/carla_infrastructure/config/sensors.json index 5847828a..320e4e33 100644 --- a/carla_infrastructure/config/sensors.json +++ b/carla_infrastructure/config/sensors.json @@ -1,59 +1,5 @@ { "sensors": [ - { - "type": "sensor.camera.rgb", - "id": "camera01", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "image_size_x": 800, - "image_size_y": 600, - "fov": 100, - "gamma": 2.2, - "shutter_speed": 60.0, - "iso": 100.0, - "fstop": 1.4, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 - }, - { - "type": "sensor.lidar.ray_cast", - "id": "lidar01", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, - "rotation_frequency": 20 - }, { "type": "sensor.pseudo.traffic_lights", "id": "traffic_lights" @@ -66,10 +12,6 @@ "type": "sensor.pseudo.markers", "id": "markers" }, - { - "type": "sensor.pseudo.objects", - "id": "objects" - }, { "type": "sensor.pseudo.opendrive_map", "id": "map" diff --git a/carla_ros_bridge/config/carla_default_rviz.cfg.rviz b/carla_ros_bridge/config/carla_default_rviz.cfg.rviz index 3f3f0d17..3671fe6d 100644 --- a/carla_ros_bridge/config/carla_default_rviz.cfg.rviz +++ b/carla_ros_bridge/config/carla_default_rviz.cfg.rviz @@ -124,9 +124,9 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 0.9806249737739563 + Max Intensity: 0.9799321889877319 Min Color: 0; 0; 0 - Min Intensity: 0.8187550902366638 + Min Intensity: 0.8193743228912354 Name: PointCloud2 Position Transformer: XYZ Queue Size: 10 @@ -141,7 +141,7 @@ Visualization Manager: Value: true - Class: rviz/MarkerArray Enabled: true - Marker Topic: /carla/ego_vehicle/markers + Marker Topic: /carla/markers Name: Markers Namespaces: "": true diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index e96a7e37..f20abdf5 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -38,6 +38,13 @@ + + + + + + + diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index ef4e9c12..aeb7b944 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -26,6 +26,7 @@ cv_bridge carla_msgs carla_ego_vehicle + carla_infrastructure carla_manual_control diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 889f3589..0a89d800 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -14,7 +14,7 @@ import unittest import rospy import rostest -from std_msgs.msg import Header +from std_msgs.msg import Header, String from rosgraph_msgs.msg import Clock from sensor_msgs.msg import CameraInfo, NavSatFix, Image, PointCloud2, Imu from geometry_msgs.msg import Quaternion, Vector3, Pose @@ -94,8 +94,8 @@ def test_gnss(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/gnss/gnss1/fix", NavSatFix, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/gnss/gnss1") + "/carla/ego_vehicle/gnss", NavSatFix, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/gnss") self.assertNotEqual(msg.latitude, 0.0) self.assertNotEqual(msg.longitude, 0.0) self.assertNotEqual(msg.altitude, 0.0) @@ -117,8 +117,8 @@ def test_camera_info(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/camera/rgb/front/camera_info", CameraInfo, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/rgb/front") + "/carla/ego_vehicle/rgb_front/camera_info", CameraInfo, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/rgb_front") self.assertEqual(msg.height, 600) self.assertEqual(msg.width, 800) @@ -128,8 +128,8 @@ def test_camera_image(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/camera/rgb/front/image_color", Image, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/rgb/front") + "/carla/ego_vehicle/rgb_front/image", Image, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/rgb_front") self.assertEqual(msg.height, 600) self.assertEqual(msg.width, 800) self.assertEqual(msg.encoding, "bgra8") @@ -140,8 +140,8 @@ def test_dvs_camera_info(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/camera/dvs/front/camera_info", CameraInfo, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/dvs/front") + "/carla/ego_vehicle/dvs_front/camera_info", CameraInfo, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") self.assertEqual(msg.height, 600) self.assertEqual(msg.width, 800) @@ -151,8 +151,8 @@ def test_dvs_camera_image(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/camera/dvs/front/image_events", Image, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/dvs/front") + "/carla/ego_vehicle/dvs_front/image", Image, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") self.assertEqual(msg.height, 600) self.assertEqual(msg.width, 800) self.assertEqual(msg.encoding, "bgr8") @@ -163,8 +163,8 @@ def test_dvs_camera_events(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/camera/dvs/front/events", PointCloud2, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/camera/dvs/front") + "/carla/ego_vehicle/dvs_front/events", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") def test_lidar(self): """ @@ -172,8 +172,8 @@ def test_lidar(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/lidar/lidar1/point_cloud", PointCloud2, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/lidar/lidar1") + "/carla/ego_vehicle/lidar", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/lidar") def test_semantic_lidar(self): """ @@ -181,8 +181,8 @@ def test_semantic_lidar(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/semantic_lidar/lidar1/point_cloud", PointCloud2, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/semantic_lidar/lidar1") + "/carla/ego_vehicle/semantic_lidar", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/semantic_lidar") def test_radar(self): """ @@ -190,8 +190,8 @@ def test_radar(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/ego_vehicle/radar/front/radar_points", PointCloud2, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle/radar/front") + "/carla/ego_vehicle/radar_front", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/radar_front") def test_ego_vehicle_objects(self): """ @@ -217,15 +217,27 @@ def test_marker(self): Tests marker """ rospy.init_node('test_node', anonymous=True) - msg = rospy.wait_for_message("/carla/marker", Marker, timeout=TIMEOUT) - self.assertEqual(msg.header.frame_id, "ego_vehicle") - self.assertNotEqual(msg.id, 0) - self.assertEqual(msg.type, 1) - self.assertNotEqual(msg.pose, Pose()) - self.assertNotEqual(msg.scale, Vector3()) - self.assertEqual(msg.color.r, 0.0) - self.assertEqual(msg.color.g, 255.0) - self.assertEqual(msg.color.b, 0.0) + msg = rospy.wait_for_message("/carla/markers", MarkerArray, timeout=TIMEOUT) + self.assertEqual(len(msg.markers), 1) # only ego vehicle exists + + ego_marker = msg.markers[0] + self.assertEqual(ego_marker.header.frame_id, "map") + self.assertNotEqual(ego_marker.id, 0) + self.assertEqual(ego_marker.type, 1) + self.assertNotEqual(ego_marker.pose, Pose()) + self.assertNotEqual(ego_marker.scale, Vector3()) + self.assertEqual(ego_marker.color.r, 0.0) + self.assertEqual(ego_marker.color.g, 255.0) + self.assertEqual(ego_marker.color.b, 0.0) + + def test_map(self): + """ + Tests map + """ + rospy.init_node('test_node', anonymous=True) + msg = rospy.wait_for_message( + "/carla/map", String, timeout=TIMEOUT) + self.assertNotEqual(len(msg.data), 0) def test_world_info(self): """ @@ -252,7 +264,7 @@ def test_traffic_lights(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/traffic_lights", CarlaTrafficLightStatusList, timeout=TIMEOUT) + "/carla/traffic_lights/status", CarlaTrafficLightStatusList, timeout=TIMEOUT) self.assertNotEqual(len(msg.traffic_lights), 0) def test_traffic_lights_info(self): @@ -261,7 +273,7 @@ def test_traffic_lights_info(self): """ rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( - "/carla/traffic_lights_info", CarlaTrafficLightInfoList, timeout=TIMEOUT) + "/carla/traffic_lights/info", CarlaTrafficLightInfoList, timeout=TIMEOUT) self.assertNotEqual(len(msg.traffic_lights), 0) diff --git a/carla_ros_bridge/test/ros_bridge_client.test b/carla_ros_bridge/test/ros_bridge_client.test index 8362066d..cecb51f6 100644 --- a/carla_ros_bridge/test/ros_bridge_client.test +++ b/carla_ros_bridge/test/ros_bridge_client.test @@ -5,6 +5,7 @@ + @@ -19,5 +20,12 @@ + + + + + + + diff --git a/carla_ros_bridge/test/test_infrastructure_sensors.json b/carla_ros_bridge/test/test_infrastructure_sensors.json new file mode 100644 index 00000000..a3b426fc --- /dev/null +++ b/carla_ros_bridge/test/test_infrastructure_sensors.json @@ -0,0 +1,24 @@ +{ + "sensors": [ + { + "type": "sensor.pseudo.traffic_lights", + "id": "traffic_lights" + }, + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list" + }, + { + "type": "sensor.pseudo.markers", + "id": "markers" + }, + { + "type": "sensor.pseudo.opendrive_map", + "id": "map" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + } + ] +} diff --git a/carla_ros_bridge/test/test_sensors.json b/carla_ros_bridge/test/test_sensors.json index 27999671..d0a444d2 100644 --- a/carla_ros_bridge/test/test_sensors.json +++ b/carla_ros_bridge/test/test_sensors.json @@ -2,21 +2,16 @@ "sensors": [ { "type": "sensor.camera.rgb", - "id": "front", - "x": 2.0, - "y": 0.0, - "z": 2.0, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0, + "id": "rgb_front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "image_size_x": 800, "image_size_y": 600, - "fov": 100, + "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, - "shutter_speed": 60.0, + "shutter_speed": 200.0, "iso": 100.0, - "fstop": 1.4, + "fstop": 8.0, "min_fstop": 1.2, "blade_count": 5, "exposure_mode": "histogram", @@ -47,53 +42,22 @@ "lens_k": -1.0, "lens_kcube": 0.0, "lens_x_size": 0.08, - "lens_y_size": 0.08 - }, - { - "type": "sensor.camera.depth", - "id": "front", - "x": 2.0, - "y": 0.0, - "z": 2.0, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0, - "image_size_x": 800, - "image_size_y": 600, - "fov": 100, - "sensor_tick": 0.05 - }, - { - "type": "sensor.camera.semantic_segmentation", - "id": "front", - "x": 2.0, - "y": 0.0, - "z": 2.0, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0, - "image_size_x": 800, - "image_size_y": 600, - "fov": 100, - "sensor_tick": 0.05 + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 }, { - "type": "sensor.camera.dvs", - "id": "front", - "x": 2.0, - "y": 0.0, - "z": 2.0, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0, + "type": "sensor.camera.rgb", + "id": "rgb_view", + "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0, "image_size_x": 800, "image_size_y": 600, - "fov": 100, + "fov": 90.0, "sensor_tick": 0.05, "gamma": 2.2, - "shutter_speed": 60.0, + "shutter_speed": 200.0, "iso": 100.0, - "fstop": 1.4, + "fstop": 8.0, "min_fstop": 1.2, "blade_count": 5, "exposure_mode": "histogram", @@ -125,40 +89,26 @@ "lens_kcube": 0.0, "lens_x_size": 0.08, "lens_y_size": 0.08, - "positive_threshold": 0.3, - "negative_threshold": 0.3, - "sigma_positive_threshold": 0, - "sigma_negative_threshold": 0, - "refractory_period_ns": 0, - "use_log": "True", - "log_eps": 0.001 + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 }, { "type": "sensor.lidar.ray_cast", - "id": "lidar1", - "x": 0.0, - "y": 0.0, - "z": 2.4, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0, + "id": "lidar", + "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "range": 50, "channels": 32, "points_per_second": 320000, "upper_fov": 2.0, "lower_fov": -26.8, "rotation_frequency": 20, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "noise_stddev": 0.0 }, { "type": "sensor.lidar.ray_cast_semantic", - "id": "lidar1", - "x": 0.0, - "y": 0.0, - "z": 2.4, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0, + "id": "semantic_lidar", + "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "range": 50, "channels": 32, "points_per_second": 320000, @@ -169,63 +119,103 @@ }, { "type": "sensor.other.radar", - "id": "front", - "x": 2.0, - "y": 0.0, - "z": 1.5, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0, + "id": "radar_front", + "x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "horizontal_fov": 30.0, "vertical_fov": 10.0, "points_per_second": 1500, "range": 100.0 }, + { + "type": "sensor.camera.semantic_segmentation", + "id": "semantic_segmentation_front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.depth", + "id": "depth_front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.dvs", + "id": "dvs_front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "positive_threshold": 0.3, + "negative_threshold": 0.3, + "sigma_positive_threshold": 0.0, + "sigma_negative_threshold": 0.0, + "use_log": true, + "log_eps": 0.001 + }, { "type": "sensor.other.gnss", - "id": "gnss1", - "x": 1.0, - "y": 0.0, - "z": 2.0, - "noise_alt_stddev": 0.1, - "noise_lat_stddev": 0.1, - "noise_lon_stddev": 0.1, - "noise_alt_bias": 0.0, - "noise_lat_bias": 0.0, - "noise_lon_bias": 0.0 + "id": "gnss", + "x": 1.0, "y": 0.0, "z": 2.0, + "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": "imu1", - "x": 2.0, - "y": 0.0, - "z": 2.0, - "roll": 0.0, - "pitch": 0.0, - "yaw": 0.0, - "noise_accel_stddev_x": 0.1, - "noise_accel_stddev_y": 0.1, - "noise_accel_stddev_z": 0.1, - "noise_gyro_stddev_x": 0.01, - "noise_gyro_stddev_y": 0.01, - "noise_gyro_stddev_z": 0.01, - "noise_gyro_bias_x": 0.0, - "noise_gyro_bias_y": 0.0, - "noise_gyro_bias_z": 0.0 + "id": "imu", + "x": 2.0, "y": 0.0, "z": 2.0, "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, + "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 }, { "type": "sensor.other.collision", - "id": "collision1", - "x": 0.0, - "y": 0.0, - "z": 0.0 + "id": "collision", + "x": 0.0, "y": 0.0, "z": 0.0 }, { "type": "sensor.other.lane_invasion", - "id": "laneinvasion1", - "x": 0.0, - "y": 0.0, - "z": 0.0 + "id": "lane_invasion", + "x": 0.0, "y": 0.0, "z": 0.0 + }, + { + "type": "sensor.pseudo.tf", + "id": "tf" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, + { + "type": "sensor.pseudo.odom", + "id": "odometry" + }, + { + "type": "sensor.pseudo.speedometer", + "id": "speedometer" + }, + { + "type": "actor.pseudo.control", + "id": "control" } ] } + From 3126470201453e53fc6907712aba525d1edf626e Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 2 Dec 2020 19:38:32 +0100 Subject: [PATCH 395/627] added object pseudo sensor to carla infrastructure --- carla_infrastructure/config/sensors.json | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/carla_infrastructure/config/sensors.json b/carla_infrastructure/config/sensors.json index 320e4e33..905a7dc6 100644 --- a/carla_infrastructure/config/sensors.json +++ b/carla_infrastructure/config/sensors.json @@ -4,6 +4,10 @@ "type": "sensor.pseudo.traffic_lights", "id": "traffic_lights" }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, { "type": "sensor.pseudo.actor_list", "id": "actor_list" From 0aa39569167e724bbcf220604c38855c5c523787 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 3 Dec 2020 14:05:24 +0100 Subject: [PATCH 396/627] Fixes for DVSCamera --- carla_ad_demo/config/carla_ad_demo_ros2.rviz | 215 ++++++++++++++---- .../carla_ego_vehicle/carla_ego_vehicle.py | 2 +- .../src/carla_ros_bridge/bridge.py | 2 +- .../src/carla_ros_bridge/camera.py | 44 ++-- .../src/carla_ros_bridge/sensor.py | 8 +- 5 files changed, 208 insertions(+), 63 deletions(-) diff --git a/carla_ad_demo/config/carla_ad_demo_ros2.rviz b/carla_ad_demo/config/carla_ad_demo_ros2.rviz index 1b457181..b4dd8017 100644 --- a/carla_ad_demo/config/carla_ad_demo_ros2.rviz +++ b/carla_ad_demo/config/carla_ad_demo_ros2.rviz @@ -3,17 +3,14 @@ Panels: Help Height: 78 Name: Displays Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 + Expanded: ~ Splitter Ratio: 0.5 - Tree Height: 78 + Tree Height: 468 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties Expanded: - /2D Pose Estimate1 - - /2D Nav Goal1 - /Publish Point1 Name: Tool Properties Splitter Ratio: 0.5886790156364441 @@ -24,10 +21,6 @@ Panels: Splitter Ratio: 0.5 - Class: rviz_carla_plugin/CarlaControl Name: CarlaControl -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 Visualization Manager: Class: "" Displays: @@ -69,23 +62,35 @@ Visualization Manager: Radius: 0.029999999329447746 Shaft Diameter: 0.10000000149011612 Shaft Length: 0.10000000149011612 - Topic: /carla/ego_vehicle/waypoints - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/waypoints Value: true - Class: rviz_default_plugins/Camera Enabled: true Image Rendering: background and overlay - Topic: /carla/ego_vehicle/camera/rgb/spectator_view/image_color - Name: Camera + Name: RGB Camera Overlay Alpha: 0.5 - Queue Size: 2 - Transport Hint: raw - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/camera/rgb/spectator_view/image_color Value: true Visibility: + DVS Camera: true + Depth Camera: true Grid: true + Lidar: true Marker: true Path: true + Radar: true + Semantic Camera: true + Semantic Lidar: true Value: true Zoom Factor: 1 - Alpha: 1 @@ -103,33 +108,147 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 + Max Intensity: 0.9798242449760437 Min Color: 0; 0; 0 - Min Intensity: 0 - Name: PointCloud2 + Min Intensity: 0.8191799521446228 + Name: Lidar Position Transformer: XYZ - Queue Size: 10 Selectable: true Size (Pixels): 3 Size (m): 0.029999999329447746 Style: Flat Squares - Topic: /carla/ego_vehicle/lidar/lidar1/point_cloud - Unreliable: false + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/lidar/lidar1/point_cloud Use Fixed Frame: true Use rainbow: true Value: true - Class: rviz_default_plugins/Marker Enabled: true - Topic: /carla/marker Name: Marker Namespaces: "": true - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/marker + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Depth Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/camera/depth/front/image_depth + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Semantic Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/camera/semantic_segmentation/front/image_segmentation + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: DVS Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/camera/dvs/front/image_events + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: false + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Semantic Lidar + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/semantic_lidar/lidar1/point_cloud + Use Fixed Frame: true + Use rainbow: true + Value: false + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: Radar + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/radar/front/radar + Use Fixed Frame: true + Use rainbow: true Value: true Enabled: true Global Options: Background Color: 48; 48; 48 - Default Light: true Fixed Frame: map Frame Rate: 30 Name: root @@ -140,16 +259,32 @@ Visualization Manager: - Class: rviz_default_plugins/Select - Class: rviz_default_plugins/FocusCamera - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 - Class: rviz_default_plugins/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose - Class: rviz_default_plugins/SetGoal - Topic: /move_base_simple/goal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /move_base_simple/goal - Class: rviz_default_plugins/PublishPoint Single click: true - Topic: /clicked_point + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF Value: true Views: Current: @@ -175,24 +310,28 @@ Visualization Manager: Yaw: 3.1504008769989014 Saved: ~ Window Geometry: - Camera: - collapsed: false CarlaControl: collapsed: false + DVS Camera: + collapsed: false + Depth Camera: + collapsed: false Displays: collapsed: false - Height: 1050 + Height: 1090 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 000000ff00000000fd0000000400000000000001fe00000367fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000046000000e6000000e600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002870000001a0000000000000000fb0000000a0049006d00610067006501000002a70000001a0000000000000000fb0000000a0049006d00610067006501000002c70000001a0000000000000000fb0000000c00430061006d0065007200610100000132000001960000001a00fffffffb00000018004300610072006c00610043006f006e00740072006f006c01000002ce000000df000000df00ffffff000000010000010f00000367fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004600000367000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077e00000044fc0100000002fb0000000800540069006d006501000000000000077e000002e400fffffffb0000000800540069006d00650100000000000004500000000000000000000004650000036700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 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 + RGB Camera: + collapsed: false Selection: collapsed: false - Time: + Semantic Camera: collapsed: false Tool Properties: collapsed: false Views: collapsed: false - Width: 1918 + Width: 1920 X: 0 - Y: 27 + Y: 24 diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index f4b277f0..cae6aafa 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -108,7 +108,7 @@ def __init__(self): CarlaWorldInfo, '/carla/world_info', self.run, - QoSProfile(depth=1, durability=False) + QoSProfile(depth=1, durability=True) ) # pylint: disable=inconsistent-return-statements diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 5c582db1..1dbedf52 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -46,7 +46,7 @@ from carla_ros_bridge.ego_vehicle import EgoVehicle from carla_ros_bridge.collision_sensor import CollisionSensor from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera +from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera from carla_ros_bridge.object_sensor import ObjectSensor from carla_ros_bridge.rss_sensor import RssSensor from carla_ros_bridge.walker import Walker diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index b5fc0cfd..9e8c4c4c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -14,11 +14,11 @@ from abc import abstractmethod import numpy from cv_bridge import CvBridge # pylint: disable=import-error -from sensor_msgs.msg import CameraInfo, Image # pylint: disable=import-error +from sensor_msgs.msg import CameraInfo, Image, PointCloud2, PointField # pylint: disable=import-error import carla import carla_common.transforms as trans -from carla_ros_bridge.sensor import Sensor +from carla_ros_bridge.sensor import Sensor, create_cloud from ros_compatibility import quaternion_from_matrix, quaternion_multiply @@ -370,7 +370,8 @@ class DVSCamera(Camera): Sensor implementation details for dvs cameras """ - def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # pylint: disable=too-many-arguments + def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None, + sensor_name="DVSCamera"): # pylint: disable=too-many-arguments """ Constructor @@ -387,58 +388,57 @@ def __init__(self, carla_actor, parent, node, synchronous_mode, prefix=None): # parent=parent, node=node, synchronous_mode=synchronous_mode, - prefix='camera/dvs/' + carla_actor.attributes.get('role_name')) + prefix='camera/dvs/' + carla_actor.attributes.get('role_name'), + sensor_name=sensor_name) self._dvs_events = None self.dvs_camera_publisher = node.new_publisher( PointCloud2, self.get_topic_prefix() + '/events') - self.listen() - - # pylint: disable=arguments-differ - def sensor_data_updated(self, carla_dvs_event_array): + def sensor_data_updated(self, carla_image): """ Function to transform the received DVS event array into a ROS message - :param carla_dvs_event_array: dvs event array object + :param carla_image: dvs event array object :type carla_image: carla.DVSEventArray """ - super(DVSCamera, self).sensor_data_updated(carla_dvs_event_array) + super(DVSCamera, self).sensor_data_updated(carla_image) - header = self.get_msg_header(timestamp=carla_dvs_event_array.timestamp) + header = self.get_msg_header(timestamp=carla_image.timestamp) + fields = [ - PointField('x', 0, PointField.UINT16, 1), - PointField('y', 2, PointField.UINT16, 1), - PointField('t', 4, PointField.FLOAT64, 1), - PointField('pol', 12, PointField.INT8, 1), + PointField(name='x', offset=0, datatype=PointField.UINT16, count=1), + PointField(name='y', offset=2, datatype=PointField.UINT16, count=1), + PointField(name='t', offset=4, datatype=PointField.FLOAT64, count=1), + PointField(name='pol', offset=12, datatype=PointField.INT8, count=1) ] dvs_events_msg = create_cloud(header, fields, self._dvs_events.tolist()) self.dvs_camera_publisher.publish(dvs_events_msg) # pylint: disable=arguments-differ - def get_carla_image_data_array(self, carla_dvs_event_array): + def get_carla_image_data_array(self, carla_image): """ Function (override) to convert the carla dvs event array to a numpy data array as input for the cv_bridge.cv2_to_imgmsg() function The carla.DVSEventArray is converted into a 3-channel int8 color image format (bgr). - :param carla_dvs_event_array: dvs event array object - :type carla_dvs_event_array: carla.DVSEventArray + :param carla_image: dvs event array object + :type carla_image: carla.DVSEventArray :return tuple (numpy data array containing the image information, encoding) :rtype tuple(numpy.ndarray, string) """ - self._dvs_events = numpy.frombuffer(carla_dvs_event_array.raw_data, + self._dvs_events = numpy.frombuffer(carla_image.raw_data, dtype=numpy.dtype([ ('x', numpy.uint16), ('y', numpy.uint16), - ('t', numpy.int64), - ('pol', numpy.bool) + ('t', numpy.double), + ('pol', numpy.int8) ])) carla_image_data_array = numpy.zeros( - (carla_dvs_event_array.height, carla_dvs_event_array.width, 3), + (carla_image.height, carla_image.width, 3), dtype=numpy.uint8) # Blue is positive, red is negative carla_image_data_array[self._dvs_events[:]['y'], self._dvs_events[:]['x'], diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index d3fed010..23d079d8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -33,8 +33,14 @@ from sensor_msgs.msg import PointCloud2, PointField _DATATYPES = {} +_DATATYPES[PointField.INT8] = ('b', 1) +_DATATYPES[PointField.UINT8] = ('B', 1) +_DATATYPES[PointField.INT16] = ('h', 2) +_DATATYPES[PointField.UINT16] = ('H', 2) +_DATATYPES[PointField.INT32] = ('i', 4) +_DATATYPES[PointField.UINT32] = ('I', 4) _DATATYPES[PointField.FLOAT32] = ('f', 4) -_DATATYPES[PointField.UINT32] = ('I', 4) +_DATATYPES[PointField.FLOAT64] = ('d', 8) class Sensor(Actor): From ec3af9834b50158994473968f182abfffbaedd92 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 2 Dec 2020 16:40:19 -0500 Subject: [PATCH 397/627] fix bug preventing the bridge to start, uid of pseudoactor worldinfo was None but compared to an int --- carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 26578657..56d10443 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -38,6 +38,15 @@ def __init__(self, uid, name, parent, node): self.parent = parent self.node = node + if self.uid is None: + raise TypeError("Actor ID is not set") + + if self.uid > np.iinfo(np.uint32).max: + raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) + + self.parent = parent + self.node = node + if self.uid > np.iinfo(np.uint32).max: raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) From 015d61204b88e9869156bbcadf600f9ba4621b82 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 2 Dec 2020 16:41:22 -0500 Subject: [PATCH 398/627] new node to spawn sensors and vehicles --- carla_spawn_actors/CMakeLists.txt | 19 + carla_spawn_actors/README.md | 3 + carla_spawn_actors/config/actors.json | 255 +++++++++++++ .../launch/carla_spawn_actors.launch | 35 ++ carla_spawn_actors/package.xml | 16 + carla_spawn_actors/setup.py | 13 + .../src/carla_spawn_actors/__init__.py | 0 .../carla_spawn_actors/carla_spawn_actors.py | 347 ++++++++++++++++++ 8 files changed, 688 insertions(+) create mode 100644 carla_spawn_actors/CMakeLists.txt create mode 100644 carla_spawn_actors/README.md create mode 100644 carla_spawn_actors/config/actors.json create mode 100644 carla_spawn_actors/launch/carla_spawn_actors.launch create mode 100644 carla_spawn_actors/package.xml create mode 100644 carla_spawn_actors/setup.py create mode 100644 carla_spawn_actors/src/carla_spawn_actors/__init__.py create mode 100755 carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py diff --git a/carla_spawn_actors/CMakeLists.txt b/carla_spawn_actors/CMakeLists.txt new file mode 100644 index 00000000..54a3219d --- /dev/null +++ b/carla_spawn_actors/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_spawn_actors) + +find_package(catkin REQUIRED COMPONENTS rospy roslaunch) + +catkin_python_setup() + +roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) + +catkin_package(CATKIN_DEPENDS rospy) + +catkin_install_python(PROGRAMS src/carla_spawn_actors/carla_spawn_actors.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) + +install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) diff --git a/carla_spawn_actors/README.md b/carla_spawn_actors/README.md new file mode 100644 index 00000000..634557d7 --- /dev/null +++ b/carla_spawn_actors/README.md @@ -0,0 +1,3 @@ +# carla_spawn_actors + +TODO \ No newline at end of file diff --git a/carla_spawn_actors/config/actors.json b/carla_spawn_actors/config/actors.json new file mode 100644 index 00000000..c9d3711b --- /dev/null +++ b/carla_spawn_actors/config/actors.json @@ -0,0 +1,255 @@ +{ + "actors": + [ + { + "type": "sensor.camera.rgb", + "id": "camera01", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "image_size_x": 800, + "image_size_y": 600, + "fov": 100, + "gamma": 2.2, + "shutter_speed": 60.0, + "iso": 100.0, + "fstop": 1.4, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "histogram", + "exposure_compensation": 0.0, + "exposure_min_bright": 7.0, + "exposure_max_bright": 9.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "vehicle.audi.tt", + "id": "ego_vehicle", + "sensors": + [ + { + "type": "sensor.camera.rgb", + "id": "front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "image_size_x": 800, + "image_size_y": 600, + "fov": 90.0, + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 200.0, + "iso": 100.0, + "fstop": 8.0, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "histogram", + "exposure_compensation": 0.0, + "exposure_min_bright": 7.0, + "exposure_max_bright": 9.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 + }, + { + "type": "sensor.camera.rgb", + "id": "view", + "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, + "image_size_x": 800, + "image_size_y": 600, + "fov": 90.0, + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 200.0, + "iso": 100.0, + "fstop": 8.0, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "histogram", + "exposure_compensation": 0.0, + "exposure_min_bright": 7.0, + "exposure_max_bright": 9.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 + }, + { + "type": "sensor.lidar.ray_cast", + "id": "lidar1", + "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05, + "noise_stddev": 0.0 + }, + { + "type": "sensor.lidar.ray_cast_semantic", + "id": "lidar1", + "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05 + }, + { + "type": "sensor.other.radar", + "id": "front", + "x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "horizontal_fov": 30.0, + "vertical_fov": 10.0, + "points_per_second": 1500, + "range": 100.0 + }, + { + "type": "sensor.camera.semantic_segmentation", + "id": "front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.depth", + "id": "front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.dvs", + "id": "front", + "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "positive_threshold": 0.3, + "negative_threshold": 0.3, + "sigma_positive_threshold": 0.0, + "sigma_negative_threshold": 0.0, + "use_log": true, + "log_eps": 0.001 + }, + { + "type": "sensor.other.gnss", + "id": "gnss1", + "x": 1.0, "y": 0.0, "z": 2.0, + "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": "imu1", + "x": 2.0, "y": 0.0, "z": 2.0, "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, + "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 + }, + { + "type": "sensor.other.collision", + "id": "collision1", + "x": 0.0, "y": 0.0, "z": 0.0 + }, + { + "type": "sensor.other.lane_invasion", + "id": "laneinvasion1", + "x": 0.0, "y": 0.0, "z": 0.0 + }, + { + "type": "sensor.pseudo.objects", + "id": "objectsensor1" + } + ] + } + ] +} diff --git a/carla_spawn_actors/launch/carla_spawn_actors.launch b/carla_spawn_actors/launch/carla_spawn_actors.launch new file mode 100644 index 00000000..b459d67d --- /dev/null +++ b/carla_spawn_actors/launch/carla_spawn_actors.launch @@ -0,0 +1,35 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/carla_spawn_actors/package.xml b/carla_spawn_actors/package.xml new file mode 100644 index 00000000..320f43ea --- /dev/null +++ b/carla_spawn_actors/package.xml @@ -0,0 +1,16 @@ + + + carla_spawn_actors + 0.0.0 + The carla_spawn_actors package + CARLA Simulator Team + MIT + catkin + rospy + roslaunch + rospy + rospy + topic_tools + + + diff --git a/carla_spawn_actors/setup.py b/carla_spawn_actors/setup.py new file mode 100644 index 00000000..b7aed7c2 --- /dev/null +++ b/carla_spawn_actors/setup.py @@ -0,0 +1,13 @@ +""" +Setup for carla_spawn_actors +""" + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_spawn_actors'], + package_dir={'': 'src'} +) + +setup(**d) diff --git a/carla_spawn_actors/src/carla_spawn_actors/__init__.py b/carla_spawn_actors/src/carla_spawn_actors/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py new file mode 100755 index 00000000..c9f3d33a --- /dev/null +++ b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py @@ -0,0 +1,347 @@ +#!/usr/bin/env python +# +# Copyright (c) 2019 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +""" +base class for spawning a Ego Vehicle in ROS + +Two modes are available: +- spawn at random Carla Spawnpoint +- spawn at the pose read from ROS topic /initialpose + +Whenever a pose is received via /initialpose, the vehicle gets respawned at that +position. If no /initialpose is set at startup, a random spawnpoint is used. + +/initialpose might be published via RVIZ '2D Pose Estimate" button. +""" + +from abc import abstractmethod + +import os +import sys +import random +import math +import json +import rospy +from tf.transformations import euler_from_quaternion, quaternion_from_euler +from diagnostic_msgs.msg import KeyValue +from geometry_msgs.msg import PoseWithCovarianceStamped, Pose +from carla_msgs.msg import CarlaWorldInfo + +import carla + +import carla_common.transforms as trans + +from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest + +secure_random = random.SystemRandom() + +# ============================================================================== +# -- CarlaEgoVehicle ------------------------------------------------------------ +# ============================================================================== + + +class CarlaSpawnActors(object): + + """ + Handles the spawning of the ego vehicle and its sensors + + Derive from this class and implement method sensors() + """ + + def __init__(self): + rospy.init_node('spawn_actors_node', anonymous=True) + self.host = rospy.get_param('carla/host', '127.0.0.1') + self.port = rospy.get_param('carla/port', 2000) + self.timeout = rospy.get_param('carla/timeout', 10) + self.actors_definition_file = rospy.get_param('~actors_definition_file') + self.world = None + self.role_name = rospy.get_param('~role_name', 'ego_vehicle') + + self.players = [] + self.vehicles_sensors = [] + self.global_sensors = [] + self.ego_player = None + + self.initial_pose_ego_subscriber = rospy.Subscriber( + "/carla/{}/initialpose".format(self.role_name), + PoseWithCovarianceStamped, + self.on_initialpose) + rospy.loginfo('listening to server %s:%s', self.host, self.port) + + rospy.wait_for_service('/carla/spawn_object') + self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) + self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) + + def on_initialpose(self, initial_pose): + """ + Callback for /initialpose + + Receiving an initial pose (e.g. from RVIZ '2D Pose estimate') triggers a respawn of ego vehicle. + + :return: + """ + if self.ego_player is None: + rospy.loginfo("Cannot respawn ego ego vehicle, not created yet") + return + + new_initial_ego_pose = initial_pose.pose.pose + + # Compute new spawn point + spawn_point = carla.Transform() + spawn_point.location.x = new_initial_ego_pose.x + spawn_point.location.y = -new_initial_ego_pose.y + spawn_point.location.z = new_initial_ego_pose.z + \ + 2 # spawn 2m above ground + quaternion = ( + new_initial_ego_pose.x, + new_initial_ego_pose.y, + new_initial_ego_pose.z, + new_initial_ego_pose.w + ) + _, _, yaw = euler_from_quaternion(quaternion) + spawn_point.rotation.yaw = -math.degrees(yaw) + rospy.loginfo("Respawning ego vehicle at: x={} y={} z={} yaw={}".format( + spawn_point.location.x, + spawn_point.location.y, + spawn_point.location.z, + spawn_point.rotation.yaw)) + + self.ego_player.set_transform(spawn_point) + + + def spawn_actors(self): + """ + Spawns the actors + + Either at a given actor_spawnpoint or at a random Carla spawnpoint + + :return: + """ + # Read sensors from file + if not os.path.exists(self.actors_definition_file): + raise RuntimeError( + "Could not read sensor-definition from {}".format(self.actors_definition_file)) + json_sensors = None + with open(self.actors_definition_file) as handle: + json_actors = json.loads(handle.read()) + + global_sensors = [] + vehicles = [] + for actor in json_actors["actors"]: + actor_type = actor["type"].split('.')[0] + if actor_type == "sensor": + global_sensors.append(actor) + elif actor_type == "vehicle": + vehicles.append(actor) + else : + rospy.logerr("Actor with type {} is not a vehicle nor a sensor".format(actor["type"])) + + try: + self.global_sensors = self.setup_sensors(global_sensors) + except Exception as e: + rospy.logerr("Setting up gloabl sensors failed with error: {}".format(e)) + + try: + self.players = self.setup_vehicles(vehicles) + except Exception as e: + rospy.logerr("Setting up vehicles failed with error: {}".format(e)) + + def setup_vehicles(self, vehicles): + players = [] + for vehicle in vehicles: + # Get vehicle blueprint. + blueprint = secure_random.choice( + self.world.get_blueprint_library().filter(vehicle["type"])) + blueprint.set_attribute('role_name', "{}".format(vehicle["id"])) + if blueprint.has_attribute('color'): + color = secure_random.choice(blueprint.get_attribute('color').recommended_values) + blueprint.set_attribute('color', color) + + player = None + spawn_point = None + + if "spawn_point" in vehicle: + spawn_point = carla.Transform() + spawn_point.location.x = vehicle["spawn_point"]["x"] + spawn_point.location.y = -vehicle["spawn_point"]["y"] + spawn_point.location.z = vehicle["spawn_point"]["z"] + \ + 2 # spawn 2m above ground + spawn_point.rotation.yaw = -vehicle["spawn_point"]["yaw"] + rospy.loginfo("Spawn {} at x={} y={} z={} yaw={}".format(vehicle["id"], + spawn_point.location.x, + spawn_point.location.y, + spawn_point.location.z, + spawn_point.rotation.yaw)) + else: + spawn_points = self.world.get_map().get_spawn_points() + spawn_point = secure_random.choice(spawn_points) if spawn_points else carla.Transform() + + + spawn_object_request = SpawnObjectRequest() + spawn_object_request.type = blueprint.id + spawn_object_request.id = vehicle["id"] + spawn_object_request.attach_to = 0 + + while player is None: + spawn_object_request.transform = trans.carla_transform_to_ros_pose(spawn_point) + response = self.spawn_object_service(spawn_object_request) + if response.id != -1: + player = self.world.get_actor(response.id) + players.append(player) + + if vehicle["id"] == "ego_vehicle": + self.ego_player = player + + # Set up the sensors + self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], player.id)) + + return players + + def setup_sensors(self, sensors, attached_vehicle_id=0): + """ + Create the sensors defined by the user and attach them to the vehicle + (or not if global sensor) + :param sensors: list of sensors + :return: + """ + actors = [] + bp_library = self.world.get_blueprint_library() + sensor_names = [] + for sensor_spec in sensors: + try: + sensor_type = str(sensor_spec.pop("type")) + sensor_id = str(sensor_spec.pop("id")) + + sensor_name = sensor_type + "/" + sensor_id + if sensor_name in sensor_names: + rospy.logfatal( + "Sensor rolename '{}' is only allowed to be used once.".format( + sensor_spec['id'])) + raise NameError( + "Sensor rolename '{}' is only allowed to be used once.".format( + sensor_spec['id'])) + sensor_names.append(sensor_name) + + sensor_location = carla.Location(x=sensor_spec.pop("x", 0.0), + y=sensor_spec.pop("y", 0.0), + z=sensor_spec.pop("z", 0.0)) + sensor_rotation = carla.Rotation( + pitch=sensor_spec.pop('pitch', 0.0), + roll=sensor_spec.pop('roll', 0.0), + yaw=sensor_spec.pop('yaw', 0.0)) + sensor_transform = carla.Transform(sensor_location, sensor_rotation) + + spawn_object_request = SpawnObjectRequest() + spawn_object_request.type = sensor_type + spawn_object_request.id = sensor_id + spawn_object_request.attach_to = attached_vehicle_id + spawn_object_request.transform = trans.carla_transform_to_ros_pose( + sensor_transform) + for attribute, value in sensor_spec.items(): + spawn_object_request.attributes.append( + KeyValue(str(attribute), str(value))) + + response = self.spawn_object_service(spawn_object_request) + if response.id == -1: + raise Exception(response.error_string) + + except KeyError as e: + rospy.logfatal( + "Sensor will not be spawned, the mandatory attribute {} is missing" + .format(e)) + raise e + + except Exception as e: + rospy.logfatal( + "Sensor {} will not be spawned, {}".format(sensor_name, e)) + raise e + + actors.append(response.id) + return actors + + @abstractmethod + def sensors(self): + """ + return a list of sensors attached + """ + return [] + + def destroy(self): + """ + destroy all the players and sensors + """ + # destroy global sensors + for actor_id in self.global_sensors: + destroy_object_request = DestroyObjectRequest(actor_id) + try: + response = self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) + self.global_sensors = [] + + # destroy vehicles sensors + for vehicle_sensors_id in self.vehicles_sensors: + for actor_id in vehicle_sensors_id: + destroy_object_request = DestroyObjectRequest(actor_id) + try: + response = self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) + self.vehicles_sensors = [] + + # destroy player + for player in self.players: + if player and player.is_alive: + destroy_object_request = DestroyObjectRequest(player.id) + try: + self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) + self.players = [] + + + def run(self): + """ + main loop + """ + # wait for ros-bridge to set up CARLA world + rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") + try: + rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) + except rospy.ROSException: + rospy.logerr("Timeout while waiting for world info!") + sys.exit(1) + + rospy.loginfo("CARLA world available. Spawn ego vehicle...") + rospy.on_shutdown(self.destroy) + client = carla.Client(self.host, self.port) + client.set_timeout(self.timeout) + self.world = client.get_world() + self.spawn_actors() + try: + rospy.spin() + except rospy.ROSInterruptException: + pass + +# ============================================================================== +# -- main() -------------------------------------------------------------------- +# ============================================================================== + + +def main(): + """ + main function + """ + spawn_actors_node = CarlaSpawnActors() + try: + spawn_actors_node.run() + finally: + if spawn_actors_node is not None: + spawn_actors_node.destroy() + + +if __name__ == '__main__': + main() From f8ab2e446975296751e1c45e4ecd410f11da6f7b Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 2 Dec 2020 16:52:48 -0500 Subject: [PATCH 399/627] remove hard coded ego_vehicle name --- carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py index c9f3d33a..29eee8cb 100755 --- a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py +++ b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py @@ -192,7 +192,7 @@ def setup_vehicles(self, vehicles): player = self.world.get_actor(response.id) players.append(player) - if vehicle["id"] == "ego_vehicle": + if vehicle["id"] == self.role_name: self.ego_player = player # Set up the sensors From 75a353a25bf028d61aa131c197163678600be642 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Fri, 4 Dec 2020 15:11:49 +0100 Subject: [PATCH 400/627] Ignore packaging/build from Makefile search path --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index 79d045f4..c9c0f857 100644 --- a/Makefile +++ b/Makefile @@ -1,4 +1,4 @@ -file_finder = find . -type f $(1) -not \( -path './venv/*' -o -path './carla_msgs/*' \) +file_finder = find . -type f $(1) -not \( -path './venv/*' -o -path './carla_msgs/*' -o -path './packaging/build/*' \) CMAKE_FILES = $(call file_finder,-name "*.cmake" -o -name "CMakeLists.txt") PY_FILES = $(call file_finder,-name "*.py") From 91b669bf54b7bb4a81998e3c3f4f4588dbac544e Mon Sep 17 00:00:00 2001 From: jmagnin Date: Thu, 3 Dec 2020 06:37:30 -0500 Subject: [PATCH 401/627] remove pseudo actor inheritance from WorldInfo --- .../src/carla_ros_bridge/bridge.py | 2 +- .../src/carla_ros_bridge/world_info.py | 22 +++---------------- 2 files changed, 4 insertions(+), 20 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 9ad1530c..f6e84efc 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -85,7 +85,7 @@ def __init__(self, carla_world, params): self.actor_factory = ActorFactory(self, carla_world, self.carla_settings.synchronous_mode) # add world info - self.world_info = WorldInfo(carla_world=self.carla_world, node=self) + self.world_info = WorldInfo(carla_world=self.carla_world) # add debug helper self.debug_helper = DebugHelper(carla_world.debug) diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index b0b7c551..d63db978 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -13,35 +13,27 @@ import rospy from carla_msgs.msg import CarlaWorldInfo -from carla_ros_bridge.pseudo_actor import PseudoActor -class WorldInfo(PseudoActor): +class WorldInfo(object): """ Publish the map """ - def __init__(self, carla_world, node): + def __init__(self, carla_world): """ Constructor :param carla_world: carla world object :type carla_world: carla.World - :param node: node-handle - :type node: carla_ros_bridge.CarlaRosBridge """ - super(WorldInfo, self).__init__(uid=None, - name="world_info", - parent=None, - node=node) - self.carla_map = carla_world.get_map() self.map_published = False - self.world_info_publisher = rospy.Publisher(self.get_topic_prefix(), + self.world_info_publisher = rospy.Publisher("/carla/world_info", CarlaWorldInfo, queue_size=10, latch=True) @@ -59,14 +51,6 @@ def destroy(self): self.carla_map = None super(WorldInfo, self).destroy() - @staticmethod - def get_blueprint_name(): - """ - Get the blueprint identifier for the pseudo sensor - :return: name - """ - return "sensor.pseudo.world_info" - def update(self, frame, timestamp): """ Function (override) to update this object. From 9f6f3520ea710b926d4985e577868c424aeefea3 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Thu, 3 Dec 2020 15:34:24 -0500 Subject: [PATCH 402/627] fix carla_spawn_agents according to comments --- .../src/carla_ros_bridge/bridge.py | 14 +- carla_spawn_actors/CMakeLists.txt | 2 + carla_spawn_actors/config/actors.json | 137 +--------- .../launch/carla_spawn_actors.launch | 26 +- .../launch/set_initial_pose.launch | 8 + .../carla_spawn_actors/carla_spawn_actors.py | 258 +++++++++--------- .../carla_spawn_actors/set_initial_pose.py | 54 ++++ 7 files changed, 215 insertions(+), 284 deletions(-) create mode 100644 carla_spawn_actors/launch/set_initial_pose.launch create mode 100644 carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index f6e84efc..c5834eac 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -21,6 +21,8 @@ import pkg_resources import rospy +import random + from rosgraph_msgs.msg import Clock from tf2_msgs.msg import TFMessage @@ -40,6 +42,9 @@ from carla_msgs.srv import SpawnObject, SpawnObjectResponse, DestroyObject, DestroyObjectResponse, GetBlueprints, GetBlueprintsResponse +# to generate a random spawning position or vehicles +secure_random = random.SystemRandom() + class CarlaRosBridge(object): """ @@ -140,8 +145,13 @@ def _spawn_actor(self, req): blueprint.set_attribute('role_name', req.id) for attribute in req.attributes: blueprint.set_attribute(attribute.key, attribute.value) - - transform = trans.ros_pose_to_carla_transform(req.transform) + if req.random_pose is False: + transform = trans.ros_pose_to_carla_transform(req.transform) + else: + # get a random pose + spawn_points = self.carla_world.get_map().get_spawn_points() + transform = secure_random.choice( + spawn_points) if spawn_points else carla.Transform() attach_to = None if req.attach_to != 0: diff --git a/carla_spawn_actors/CMakeLists.txt b/carla_spawn_actors/CMakeLists.txt index 54a3219d..4b24c297 100644 --- a/carla_spawn_actors/CMakeLists.txt +++ b/carla_spawn_actors/CMakeLists.txt @@ -11,6 +11,8 @@ catkin_package(CATKIN_DEPENDS rospy) catkin_install_python(PROGRAMS src/carla_spawn_actors/carla_spawn_actors.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) +catkin_install_python(PROGRAMS src/carla_spawn_actors/set_initial_pose.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_spawn_actors/config/actors.json b/carla_spawn_actors/config/actors.json index c9d3711b..d28a3528 100644 --- a/carla_spawn_actors/config/actors.json +++ b/carla_spawn_actors/config/actors.json @@ -8,47 +8,18 @@ "image_size_x": 800, "image_size_y": 600, "fov": 100, - "gamma": 2.2, - "shutter_speed": 60.0, - "iso": 100.0, - "fstop": 1.4, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 + "sensor_tick": 0.05 }, { "type": "vehicle.audi.tt", "id": "ego_vehicle", + "spawn_point": {"x": 392.5, "y": -87.0, "z": 0.3, "roll": 0.0, "pitch": 0.0, "yaw": 90.0}, "sensors": [ + { + "type": "pseudo.actor.control", + "id": "ego_vehicle_pose_controller" + }, { "type": "sensor.camera.rgb", "id": "front", @@ -56,90 +27,16 @@ "image_size_x": 800, "image_size_y": 600, "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 + "sensor_tick": 0.05 }, { "type": "sensor.camera.rgb", "id": "view", - "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, + "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0, "image_size_x": 800, "image_size_y": 600, "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 + "sensor_tick": 0.05 }, { "type": "sensor.lidar.ray_cast", @@ -182,13 +79,7 @@ "fov": 90.0, "image_size_x": 400, "image_size_y": 70, - "sensor_tick": 0.05, - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 + "sensor_tick": 0.05 }, { "type": "sensor.camera.depth", @@ -197,13 +88,7 @@ "fov": 90.0, "image_size_x": 400, "image_size_y": 70, - "sensor_tick": 0.05, - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 + "sensor_tick": 0.05 }, { "type": "sensor.camera.dvs", diff --git a/carla_spawn_actors/launch/carla_spawn_actors.launch b/carla_spawn_actors/launch/carla_spawn_actors.launch index b459d67d..080b0681 100644 --- a/carla_spawn_actors/launch/carla_spawn_actors.launch +++ b/carla_spawn_actors/launch/carla_spawn_actors.launch @@ -3,33 +3,17 @@ - - - - - - - - - - - - - - + + + + - - - + diff --git a/carla_spawn_actors/launch/set_initial_pose.launch b/carla_spawn_actors/launch/set_initial_pose.launch new file mode 100644 index 00000000..121b35b2 --- /dev/null +++ b/carla_spawn_actors/launch/set_initial_pose.launch @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py index 29eee8cb..3a8dac3e 100755 --- a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py +++ b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py @@ -1,11 +1,11 @@ #!/usr/bin/env python # -# Copyright (c) 2019 Intel Corporation +# Copyright (c) 2019-2020 Intel Corporation # # This work is licensed under the terms of the MIT license. # For a copy, see . """ -base class for spawning a Ego Vehicle in ROS +base class for spawning actors in ROS Two modes are available: - spawn at random Carla Spawnpoint @@ -21,25 +21,19 @@ import os import sys -import random import math import json import rospy -from tf.transformations import euler_from_quaternion, quaternion_from_euler +from tf.transformations import quaternion_from_euler from diagnostic_msgs.msg import KeyValue -from geometry_msgs.msg import PoseWithCovarianceStamped, Pose +from geometry_msgs.msg import Pose from carla_msgs.msg import CarlaWorldInfo -import carla - -import carla_common.transforms as trans from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest -secure_random = random.SystemRandom() - # ============================================================================== -# -- CarlaEgoVehicle ------------------------------------------------------------ +# -- CarlaSpawnActors ------------------------------------------------------------ # ============================================================================== @@ -57,61 +51,20 @@ def __init__(self): self.port = rospy.get_param('carla/port', 2000) self.timeout = rospy.get_param('carla/timeout', 10) self.actors_definition_file = rospy.get_param('~actors_definition_file') - self.world = None self.role_name = rospy.get_param('~role_name', 'ego_vehicle') + self.spawn_point_param = rospy.get_param('~spawn_point', None) + self.players = [] self.vehicles_sensors = [] self.global_sensors = [] - self.ego_player = None - self.initial_pose_ego_subscriber = rospy.Subscriber( - "/carla/{}/initialpose".format(self.role_name), - PoseWithCovarianceStamped, - self.on_initialpose) rospy.loginfo('listening to server %s:%s', self.host, self.port) rospy.wait_for_service('/carla/spawn_object') self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) - def on_initialpose(self, initial_pose): - """ - Callback for /initialpose - - Receiving an initial pose (e.g. from RVIZ '2D Pose estimate') triggers a respawn of ego vehicle. - - :return: - """ - if self.ego_player is None: - rospy.loginfo("Cannot respawn ego ego vehicle, not created yet") - return - - new_initial_ego_pose = initial_pose.pose.pose - - # Compute new spawn point - spawn_point = carla.Transform() - spawn_point.location.x = new_initial_ego_pose.x - spawn_point.location.y = -new_initial_ego_pose.y - spawn_point.location.z = new_initial_ego_pose.z + \ - 2 # spawn 2m above ground - quaternion = ( - new_initial_ego_pose.x, - new_initial_ego_pose.y, - new_initial_ego_pose.z, - new_initial_ego_pose.w - ) - _, _, yaw = euler_from_quaternion(quaternion) - spawn_point.rotation.yaw = -math.degrees(yaw) - rospy.loginfo("Respawning ego vehicle at: x={} y={} z={} yaw={}".format( - spawn_point.location.x, - spawn_point.location.y, - spawn_point.location.z, - spawn_point.rotation.yaw)) - - self.ego_player.set_transform(spawn_point) - - def spawn_actors(self): """ Spawns the actors @@ -134,69 +87,75 @@ def spawn_actors(self): actor_type = actor["type"].split('.')[0] if actor_type == "sensor": global_sensors.append(actor) - elif actor_type == "vehicle": + elif actor_type == "vehicle" or actor_type == "walker": vehicles.append(actor) else : - rospy.logerr("Actor with type {} is not a vehicle nor a sensor".format(actor["type"])) + rospy.logwarn("Actor with type {} is not a vehicle nor a sensor, ignoring".format(actor["type"])) try: self.global_sensors = self.setup_sensors(global_sensors) except Exception as e: - rospy.logerr("Setting up gloabl sensors failed with error: {}".format(e)) + raise Exception("Setting up global sensors failed: {}".format(e)) try: self.players = self.setup_vehicles(vehicles) except Exception as e: - rospy.logerr("Setting up vehicles failed with error: {}".format(e)) + raise Exception("Setting up vehicles failed: {}".format(e)) def setup_vehicles(self, vehicles): players = [] for vehicle in vehicles: - # Get vehicle blueprint. - blueprint = secure_random.choice( - self.world.get_blueprint_library().filter(vehicle["type"])) - blueprint.set_attribute('role_name', "{}".format(vehicle["id"])) - if blueprint.has_attribute('color'): - color = secure_random.choice(blueprint.get_attribute('color').recommended_values) - blueprint.set_attribute('color', color) - - player = None - spawn_point = None - - if "spawn_point" in vehicle: - spawn_point = carla.Transform() - spawn_point.location.x = vehicle["spawn_point"]["x"] - spawn_point.location.y = -vehicle["spawn_point"]["y"] - spawn_point.location.z = vehicle["spawn_point"]["z"] + \ - 2 # spawn 2m above ground - spawn_point.rotation.yaw = -vehicle["spawn_point"]["yaw"] - rospy.loginfo("Spawn {} at x={} y={} z={} yaw={}".format(vehicle["id"], - spawn_point.location.x, - spawn_point.location.y, - spawn_point.location.z, - spawn_point.rotation.yaw)) - else: - spawn_points = self.world.get_map().get_spawn_points() - spawn_point = secure_random.choice(spawn_points) if spawn_points else carla.Transform() - - spawn_object_request = SpawnObjectRequest() - spawn_object_request.type = blueprint.id + spawn_object_request.type = vehicle["type"] spawn_object_request.id = vehicle["id"] spawn_object_request.attach_to = 0 + spawn_object_request.random_pose = False + + spawn_point = None - while player is None: - spawn_object_request.transform = trans.carla_transform_to_ros_pose(spawn_point) + if (self.spawn_point_param is not None + and self.role_name == vehicle["id"]): + # try to use spawn_point from parameters + # only for vehicle with id role_name + try: + spawn_point = self.check_spawn_point_param(self.spawn_point_param) + rospy.loginfo("Spawn point from ros parameters") + except Exception as e: + rospy.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"])+ + "the spawn point from config file will be used. Error is: {}".format(e)) + + if "spawn_point" in vehicle and spawn_point is None: + # get spawn point from config file + try: + spawn_point = self.create_spawn_point( + vehicle["spawn_point"]["x"], + vehicle["spawn_point"]["y"], + vehicle["spawn_point"]["z"], + vehicle["spawn_point"]["roll"], + vehicle["spawn_point"]["pitch"], + vehicle["spawn_point"]["yaw"] + ) + rospy.loginfo("Spawn point from configuration file") + except KeyError as e: + rospy.logerr("{}: Could not use the spawn point from config file, ".format(vehicle["id"]) + + "the mandatory attribute {} is missing, a random spawn point will be used".format(e)) + + if spawn_point is None : + # pose not specified, ask for a random one in the service call + rospy.loginfo("Spawn point selected at random") + spawn_point = Pose() # empty pose + spawn_object_request.random_pose = True + + player_spawned = False + while not player_spawned: + spawn_object_request.transform = spawn_point response = self.spawn_object_service(spawn_object_request) if response.id != -1: - player = self.world.get_actor(response.id) - players.append(player) - - if vehicle["id"] == self.role_name: - self.ego_player = player - + player_spawned = True + players.append(response.id) # Set up the sensors - self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], player.id)) + self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], response.id)) + return players @@ -205,10 +164,10 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): Create the sensors defined by the user and attach them to the vehicle (or not if global sensor) :param sensors: list of sensors - :return: + :param attached_vehicle_id: id of vehicle to attach the sensors to + :return actors: list of ids of actors created """ actors = [] - bp_library = self.world.get_blueprint_library() sensor_names = [] for sensor_spec in sensors: try: @@ -217,29 +176,36 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): sensor_name = sensor_type + "/" + sensor_id if sensor_name in sensor_names: - rospy.logfatal( - "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) raise NameError( "Sensor rolename '{}' is only allowed to be used once.".format( sensor_spec['id'])) sensor_names.append(sensor_name) - sensor_location = carla.Location(x=sensor_spec.pop("x", 0.0), - y=sensor_spec.pop("y", 0.0), - z=sensor_spec.pop("z", 0.0)) - sensor_rotation = carla.Rotation( - pitch=sensor_spec.pop('pitch', 0.0), - roll=sensor_spec.pop('roll', 0.0), - yaw=sensor_spec.pop('yaw', 0.0)) - sensor_transform = carla.Transform(sensor_location, sensor_rotation) + if attached_vehicle_id == 0: + sensor_transform = self.create_spawn_point( + sensor_spec.pop("x"), + sensor_spec.pop("y"), + sensor_spec.pop("z"), + sensor_spec.pop("roll", 0.0), + sensor_spec.pop("pitch", 0.0), + sensor_spec.pop("yaw", 0.0)) + else: + # if sensor attached to a vehicle, allow default pose + sensor_transform = self.create_spawn_point( + sensor_spec.pop("x", 0.0), + sensor_spec.pop("y", 0.0), + sensor_spec.pop("z", 0.0), + sensor_spec.pop("roll", 0.0), + sensor_spec.pop("pitch", 0.0), + sensor_spec.pop("yaw", 0.0)) spawn_object_request = SpawnObjectRequest() spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id spawn_object_request.attach_to = attached_vehicle_id - spawn_object_request.transform = trans.carla_transform_to_ros_pose( - sensor_transform) + spawn_object_request.transform = sensor_transform + spawn_object_request.random_pose = False # never set a random pose for a sensor + for attribute, value in sensor_spec.items(): spawn_object_request.attributes.append( KeyValue(str(attribute), str(value))) @@ -249,25 +215,48 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): raise Exception(response.error_string) except KeyError as e: - rospy.logfatal( - "Sensor will not be spawned, the mandatory attribute {} is missing" - .format(e)) - raise e + rospy.logerr( + "Sensor {} will not be spawned, the mandatory attribute {} is missing".format(sensor_name, e)) + break except Exception as e: - rospy.logfatal( - "Sensor {} will not be spawned, {}".format(sensor_name, e)) - raise e + rospy.logerr( + "Sensor {} will not be spawned: {}".format(sensor_name, e)) + break actors.append(response.id) return actors + + def create_spawn_point(self, x, y, z, roll, pitch, yaw): + spawn_point = Pose() + spawn_point.position.x = x + spawn_point.position.y = y + spawn_point.position.z = z + quat = quaternion_from_euler( + math.radians(roll), + math.radians(pitch), + math.radians(yaw)) + + spawn_point.orientation.x = quat[0] + spawn_point.orientation.y = quat[1] + spawn_point.orientation.z = quat[2] + spawn_point.orientation.w = quat[3] + return spawn_point + + def check_spawn_point_param(self, spawn_point_parameter): + components = spawn_point_parameter.split(',') + if len(components) != 6: + raise ValueError("Invalid spawnpoint '{}'".format(spawn_point_parameter)) + spawn_point = self.create_spawn_point( + float(components[0]), + float(components[1]), + float(components[2]), + float(components[3]), + float(components[4]), + float(components[5]) + ) + return spawn_point - @abstractmethod - def sensors(self): - """ - return a list of sensors attached - """ - return [] def destroy(self): """ @@ -293,13 +282,12 @@ def destroy(self): self.vehicles_sensors = [] # destroy player - for player in self.players: - if player and player.is_alive: - destroy_object_request = DestroyObjectRequest(player.id) - try: - self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) + for player_id in self.players: + destroy_object_request = DestroyObjectRequest(player_id) + try: + self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) self.players = [] @@ -317,9 +305,6 @@ def run(self): rospy.loginfo("CARLA world available. Spawn ego vehicle...") rospy.on_shutdown(self.destroy) - client = carla.Client(self.host, self.port) - client.set_timeout(self.timeout) - self.world = client.get_world() self.spawn_actors() try: rospy.spin() @@ -335,9 +320,12 @@ def main(): """ main function """ - spawn_actors_node = CarlaSpawnActors() try: + spawn_actors_node = CarlaSpawnActors() spawn_actors_node.run() + except Exception as e: + rospy.logfatal( + "Exception caught: {}".format(e)) finally: if spawn_actors_node is not None: spawn_actors_node.destroy() diff --git a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py new file mode 100644 index 00000000..f51f2cf9 --- /dev/null +++ b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python +# +# Copyright (c) 2019-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +""" +Node to re-spawn vehicle in the ros-bridge + +Subscribes to ROS topic /initialpose and publishes the pose on /carla//set_transform + +Uses ROS parameter: role_name + +Whenever a pose is received via /initialpose, the vehicle gets respawned at that +position. + +/initialpose might be published via RVIZ '2D Pose Estimate" button. +""" + +import rospy +from geometry_msgs.msg import PoseWithCovarianceStamped, Pose + +class SetInitialPose(object): + + def __init__(self): + + rospy.init_node('set_initial_pose', anonymous=True) + + self.role_name = rospy.get_param('~role_name', 'ego_vehicle') + + self.transform_publisher = rospy.Publisher( + "/carla/{}/set_transform".format(self.role_name), Pose, queue_size=10) + + self.initial_pose_subscriber = rospy.Subscriber( + "/initialpose", PoseWithCovarianceStamped, self.intial_pose_callback) + + + def intial_pose_callback(self, initial_pose): + pose_to_publish = initial_pose.pose.pose + pose_to_publish.position.z += 2.0 + self.transform_publisher.publish(pose_to_publish) + + + +def main(): + """ + main function + """ + set_initial_pose_node = SetInitialPose() + rospy.spin() + + +if __name__ == '__main__': + main() \ No newline at end of file From 012520901c4e74102bd8fa99159de8e059de3e20 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 4 Dec 2020 13:46:03 -0500 Subject: [PATCH 403/627] fix last problems and comments in carla_spawn_actors --- carla_spawn_actors/CMakeLists.txt | 4 +- carla_spawn_actors/README.md | 55 ++++- carla_spawn_actors/config/actors.json | 35 ++-- .../launch/carla_example_ego_vehicle.launch | 22 ++ .../launch/carla_spawn_actors.launch | 23 +-- carla_spawn_actors/package.xml | 1 + .../carla_spawn_actors/carla_spawn_actors.py | 195 ++++++++++-------- 7 files changed, 221 insertions(+), 114 deletions(-) create mode 100644 carla_spawn_actors/launch/carla_example_ego_vehicle.launch diff --git a/carla_spawn_actors/CMakeLists.txt b/carla_spawn_actors/CMakeLists.txt index 4b24c297..5e37501a 100644 --- a/carla_spawn_actors/CMakeLists.txt +++ b/carla_spawn_actors/CMakeLists.txt @@ -5,7 +5,9 @@ find_package(catkin REQUIRED COMPONENTS rospy roslaunch) catkin_python_setup() -roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) +if(CATKIN_ENABLE_TESTING) + roslaunch_add_file_check(launch) +endif() catkin_package(CATKIN_DEPENDS rospy) diff --git a/carla_spawn_actors/README.md b/carla_spawn_actors/README.md index 634557d7..61946c24 100644 --- a/carla_spawn_actors/README.md +++ b/carla_spawn_actors/README.md @@ -1,3 +1,54 @@ -# carla_spawn_actors +# ROS Carla Spawn Actors -TODO \ No newline at end of file +The reference Carla client `carla_spawn_actors` can be used to spawn actors (vehicels, sensors, walkers) with attached sensors. + +Info: To be able to use `carla_manual_control` a camera with role-name 'view' and resolution of 800x600 is required. + +If no specific position is set for vehicles, they will be spawned at a random position. + +## Spawning at specific position + +- It is possible to specify the position at which the vehicle will be spawned, by defining a ros parameter named `spawn_point_vehicle_name`, the `vehicle_name` part being the same as the one specified in the config file. +- It is also possible to specify the initial position directly in the config file. This is also how the initial positions of sensors should be declared. + +It is possible to re-spawn a vehicle at a specific location by publishing to `/carla//initialpose`, but only if a `actor.pseudo.control` pseudo-actor is attached to the vehicle. The node `set_initial-pose` should also be running to handle the message on the topic. It can be launched using [set_initial_pose.launch](launch/set_initial_pose.launch) + +The preferred way to publish the new pose message is to use RVIZ: + +![Autoware Runtime Manager Settings](../docs/images/rviz_set_start_goal.png) + +Selecting a Pose with '2D Pose Estimate' will delete the current ego_vehicle and respawn it at the specified position. + +## Attach sensor to an existing vehicle + +It possible to attach sensors to an existing vehicle. To do so, a `sensor.pseudo.actor_list` should also be spawned (define it in the config file) to give access to a list of active actors. The ROS parameter `spawn_sensors_only` should also be set to True. `carla_spawn_actors` will then check if an actor with same id and type as the one specified in its config file is already active, and if yes attach the sensors to this actor. + +## Create your own sensor setup + +Sensors, attached to vehicles or not, can be defined via a json file. `carla_spawn_actors` reads it from the file location defined via the private ros parameter `actors_definition_file`. + +The format is defined like that: + + { "actors" = [ + { + "type": "", + "id": "", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + + }, + { + "type": "", + "id": "", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "sensors": + [ + + ] + } + ... + ] + } + +Define sensors with their attributes as described in the Carla Documentation about [Cameras and Sensors](https://github.com/carla-simulator/carla/blob/master/Docs/cameras_and_sensors.md). + +An example is provided by [carla_example_ego_vehicle.launch](launch/carla_example_ego_vehicle.launch). It uses the sensors from [actors.json](config/actors.json) diff --git a/carla_spawn_actors/config/actors.json b/carla_spawn_actors/config/actors.json index d28a3528..fc477e47 100644 --- a/carla_spawn_actors/config/actors.json +++ b/carla_spawn_actors/config/actors.json @@ -4,26 +4,29 @@ { "type": "sensor.camera.rgb", "id": "camera01", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "image_size_x": 800, "image_size_y": 600, "fov": 100, "sensor_tick": 0.05 }, + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list" + }, { "type": "vehicle.audi.tt", "id": "ego_vehicle", - "spawn_point": {"x": 392.5, "y": -87.0, "z": 0.3, "roll": 0.0, "pitch": 0.0, "yaw": 90.0}, "sensors": [ { - "type": "pseudo.actor.control", - "id": "ego_vehicle_pose_controller" + "type": "actor.pseudo.control", + "id": "" }, { "type": "sensor.camera.rgb", "id": "front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "image_size_x": 800, "image_size_y": 600, "fov": 90.0, @@ -32,7 +35,7 @@ { "type": "sensor.camera.rgb", "id": "view", - "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0, + "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0}, "image_size_x": 800, "image_size_y": 600, "fov": 90.0, @@ -41,7 +44,7 @@ { "type": "sensor.lidar.ray_cast", "id": "lidar1", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "range": 50, "channels": 32, "points_per_second": 320000, @@ -54,7 +57,7 @@ { "type": "sensor.lidar.ray_cast_semantic", "id": "lidar1", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "range": 50, "channels": 32, "points_per_second": 320000, @@ -66,7 +69,7 @@ { "type": "sensor.other.radar", "id": "front", - "x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "horizontal_fov": 30.0, "vertical_fov": 10.0, "points_per_second": 1500, @@ -75,7 +78,7 @@ { "type": "sensor.camera.semantic_segmentation", "id": "front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "fov": 90.0, "image_size_x": 400, "image_size_y": 70, @@ -84,7 +87,7 @@ { "type": "sensor.camera.depth", "id": "front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "fov": 90.0, "image_size_x": 400, "image_size_y": 70, @@ -93,7 +96,7 @@ { "type": "sensor.camera.dvs", "id": "front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "fov": 90.0, "image_size_x": 400, "image_size_y": 70, @@ -108,14 +111,14 @@ { "type": "sensor.other.gnss", "id": "gnss1", - "x": 1.0, "y": 0.0, "z": 2.0, + "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0}, "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": "imu1", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "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, "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 @@ -123,12 +126,12 @@ { "type": "sensor.other.collision", "id": "collision1", - "x": 0.0, "y": 0.0, "z": 0.0 + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} }, { "type": "sensor.other.lane_invasion", "id": "laneinvasion1", - "x": 0.0, "y": 0.0, "z": 0.0 + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} }, { "type": "sensor.pseudo.objects", diff --git a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch b/carla_spawn_actors/launch/carla_example_ego_vehicle.launch new file mode 100644 index 00000000..e3a3ca49 --- /dev/null +++ b/carla_spawn_actors/launch/carla_example_ego_vehicle.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/carla_spawn_actors/launch/carla_spawn_actors.launch b/carla_spawn_actors/launch/carla_spawn_actors.launch index 080b0681..a9e0481d 100644 --- a/carla_spawn_actors/launch/carla_spawn_actors.launch +++ b/carla_spawn_actors/launch/carla_spawn_actors.launch @@ -1,19 +1,16 @@ - - - - - - - + + + + + - - - - + - - + + diff --git a/carla_spawn_actors/package.xml b/carla_spawn_actors/package.xml index 320f43ea..b8e1eb6e 100644 --- a/carla_spawn_actors/package.xml +++ b/carla_spawn_actors/package.xml @@ -11,6 +11,7 @@ rospy rospy topic_tools + carla_msgs diff --git a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py index 3a8dac3e..009a6d1e 100755 --- a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py +++ b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py @@ -7,14 +7,12 @@ """ base class for spawning actors in ROS -Two modes are available: -- spawn at random Carla Spawnpoint -- spawn at the pose read from ROS topic /initialpose +Gets config file from ros parameter ~actors_definition_file and spawns corresponding actors +through ROS service /carla/spawn_object. -Whenever a pose is received via /initialpose, the vehicle gets respawned at that -position. If no /initialpose is set at startup, a random spawnpoint is used. +Looks for an initial spawn point first in the launchfile, then in the config file, and +finally ask for a random one to the spawn service. -/initialpose might be published via RVIZ '2D Pose Estimate" button. """ from abc import abstractmethod @@ -27,7 +25,7 @@ from tf.transformations import quaternion_from_euler from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import Pose -from carla_msgs.msg import CarlaWorldInfo +from carla_msgs.msg import CarlaWorldInfo, CarlaActorList from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest @@ -47,19 +45,12 @@ class CarlaSpawnActors(object): def __init__(self): rospy.init_node('spawn_actors_node', anonymous=True) - self.host = rospy.get_param('carla/host', '127.0.0.1') - self.port = rospy.get_param('carla/port', 2000) - self.timeout = rospy.get_param('carla/timeout', 10) self.actors_definition_file = rospy.get_param('~actors_definition_file') - self.role_name = rospy.get_param('~role_name', 'ego_vehicle') - - self.spawn_point_param = rospy.get_param('~spawn_point', None) + self.spawn_sensors_only = rospy.get_param('~spawn_sensors_only', None) self.players = [] self.vehicles_sensors = [] self.global_sensors = [] - - rospy.loginfo('listening to server %s:%s', self.host, self.port) rospy.wait_for_service('/carla/spawn_object') self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) @@ -83,19 +74,36 @@ def spawn_actors(self): global_sensors = [] vehicles = [] + found_sensor_actor_list = False + for actor in json_actors["actors"]: actor_type = actor["type"].split('.')[0] - if actor_type == "sensor": + if actor["type"] == "sensor.pseudo.actor_list" and self.spawn_sensors_only: + global_sensors.append(actor) + found_sensor_actor_list = True + elif actor_type == "sensor": global_sensors.append(actor) elif actor_type == "vehicle" or actor_type == "walker": vehicles.append(actor) else : - rospy.logwarn("Actor with type {} is not a vehicle nor a sensor, ignoring".format(actor["type"])) - + rospy.logwarn("Actor with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"])) + print(f'======={self.spawn_sensors_only}') + if self.spawn_sensors_only is True and found_sensor_actor_list is False: + raise Exception("Parameter 'spawn_sensors_only' enabled, " + + "but 'sensor.pseudo.actor_list' is not instantiated, add it to your config file.") + try: self.global_sensors = self.setup_sensors(global_sensors) except Exception as e: raise Exception("Setting up global sensors failed: {}".format(e)) + + if self.spawn_sensors_only is True: + # get vehicle id from topic /carla/actor_list for all vehicles listed in config file + actor_info_list = rospy.wait_for_message("/carla/actor_list", CarlaActorList) + for vehicle in vehicles: + for actor_info in actor_info_list.actors: + if actor_info.type == vehicle["type"] and actor_info.rolename == vehicle["id"]: + vehicle["carla_id"] = actor_info.id try: self.players = self.setup_vehicles(vehicles) @@ -105,56 +113,74 @@ def spawn_actors(self): def setup_vehicles(self, vehicles): players = [] for vehicle in vehicles: - spawn_object_request = SpawnObjectRequest() - spawn_object_request.type = vehicle["type"] - spawn_object_request.id = vehicle["id"] - spawn_object_request.attach_to = 0 - spawn_object_request.random_pose = False - - spawn_point = None - - if (self.spawn_point_param is not None - and self.role_name == vehicle["id"]): - # try to use spawn_point from parameters - # only for vehicle with id role_name + if self.spawn_sensors_only is True: + # spawn sensors of already spawned vehicles try: - spawn_point = self.check_spawn_point_param(self.spawn_point_param) - rospy.loginfo("Spawn point from ros parameters") - except Exception as e: - rospy.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"])+ - "the spawn point from config file will be used. Error is: {}".format(e)) - - if "spawn_point" in vehicle and spawn_point is None: - # get spawn point from config file - try: - spawn_point = self.create_spawn_point( - vehicle["spawn_point"]["x"], - vehicle["spawn_point"]["y"], - vehicle["spawn_point"]["z"], - vehicle["spawn_point"]["roll"], - vehicle["spawn_point"]["pitch"], - vehicle["spawn_point"]["yaw"] - ) - rospy.loginfo("Spawn point from configuration file") + carla_id = vehicle["carla_id"] except KeyError as e: - rospy.logerr("{}: Could not use the spawn point from config file, ".format(vehicle["id"]) + - "the mandatory attribute {} is missing, a random spawn point will be used".format(e)) - - if spawn_point is None : - # pose not specified, ask for a random one in the service call - rospy.loginfo("Spawn point selected at random") - spawn_point = Pose() # empty pose - spawn_object_request.random_pose = True - - player_spawned = False - while not player_spawned: - spawn_object_request.transform = spawn_point - response = self.spawn_object_service(spawn_object_request) - if response.id != -1: - player_spawned = True - players.append(response.id) - # Set up the sensors - self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], response.id)) + rospy.logerr("Could not spawn sensors of vehicle {}, its carla ID is not known.".format(vehicle["id"])) + break + # spawn the vehicle's sensors + try: + self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], carla_id)) + except Exception as e: + raise Exception("Setting up sensors of already spawned vehicle {} failed with error: {}".format(vehicle["id"], e)) + else: + spawn_object_request = SpawnObjectRequest() + spawn_object_request.type = vehicle["type"] + spawn_object_request.id = vehicle["id"] + spawn_object_request.attach_to = 0 + spawn_object_request.random_pose = False + + spawn_point = None + + # check if there's a spawn_point corresponding to this vehicle + spawn_point_param = rospy.get_param("~spawn_point_" + vehicle["id"], None) + spawn_param_used = False + if (spawn_point_param is not None): + # try to use spawn_point from parameters + try: + spawn_point = self.check_spawn_point_param(spawn_point_param) + rospy.loginfo("Spawn point from ros parameters") + spawn_param_used = True + except Exception as e: + rospy.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"])+ + "the spawn point from config file will be used. Error is: {}".format(e)) + + if "spawn_point" in vehicle and spawn_param_used is False: + # get spawn point from config file + try: + spawn_point = self.create_spawn_point( + vehicle["spawn_point"]["x"], + vehicle["spawn_point"]["y"], + vehicle["spawn_point"]["z"], + vehicle["spawn_point"]["roll"], + vehicle["spawn_point"]["pitch"], + vehicle["spawn_point"]["yaw"] + ) + rospy.loginfo("Spawn point from configuration file") + except KeyError as e: + rospy.logerr("{}: Could not use the spawn point from config file, ".format(vehicle["id"]) + + "the mandatory attribute {} is missing, a random spawn point will be used".format(e)) + + if spawn_point is None : + # pose not specified, ask for a random one in the service call + rospy.loginfo("Spawn point selected at random") + spawn_point = Pose() # empty pose + spawn_object_request.random_pose = True + + player_spawned = False + while not player_spawned: + spawn_object_request.transform = spawn_point + response = self.spawn_object_service(spawn_object_request) + if response.id != -1: + player_spawned = True + players.append(response.id) + # Set up the sensors + try: + self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], response.id)) + except KeyError: + rospy.logwarn("Vehicle {} have no 'sensors' field in his config file, none will be spawned") return players @@ -181,23 +207,28 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): sensor_spec['id'])) sensor_names.append(sensor_name) - if attached_vehicle_id == 0: + if attached_vehicle_id == 0 and sensor_type != "sensor.pseudo.actor_list": + spawn_point = sensor_spec.pop("spawn_point") sensor_transform = self.create_spawn_point( - sensor_spec.pop("x"), - sensor_spec.pop("y"), - sensor_spec.pop("z"), - sensor_spec.pop("roll", 0.0), - sensor_spec.pop("pitch", 0.0), - sensor_spec.pop("yaw", 0.0)) + spawn_point.pop("x"), + spawn_point.pop("y"), + spawn_point.pop("z"), + spawn_point.pop("roll", 0.0), + spawn_point.pop("pitch", 0.0), + spawn_point.pop("yaw", 0.0)) else: - # if sensor attached to a vehicle, allow default pose - sensor_transform = self.create_spawn_point( - sensor_spec.pop("x", 0.0), - sensor_spec.pop("y", 0.0), - sensor_spec.pop("z", 0.0), - sensor_spec.pop("roll", 0.0), - sensor_spec.pop("pitch", 0.0), - sensor_spec.pop("yaw", 0.0)) + # if sensor attached to a vehicle, or is a 'sensor.pseudo.actor_list', allow default pose + spawn_point = sensor_spec.pop("spawn_point", 0) + if spawn_point == 0: + sensor_transform = self.create_spawn_point(0.0, 0.0, 0.0, 0.0, 0.0, 0.0) + else: + sensor_transform = self.create_spawn_point( + spawn_point.pop("x", 0.0), + spawn_point.pop("y", 0.0), + spawn_point.pop("z", 0.0), + spawn_point.pop("roll", 0.0), + spawn_point.pop("pitch", 0.0), + spawn_point.pop("yaw", 0.0)) spawn_object_request = SpawnObjectRequest() spawn_object_request.type = sensor_type @@ -303,7 +334,7 @@ def run(self): rospy.logerr("Timeout while waiting for world info!") sys.exit(1) - rospy.loginfo("CARLA world available. Spawn ego vehicle...") + rospy.loginfo("World info is available. Spawning acotrs...") rospy.on_shutdown(self.destroy) self.spawn_actors() try: From f2e43764bee9935e6b401d155288d5d2c01396be Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 4 Dec 2020 13:46:51 -0500 Subject: [PATCH 404/627] corrected launchfiles to fit with new carla_spawn_actors --- carla_ad_demo/launch/carla_ad_demo.launch | 14 +++++--------- .../launch/carla_ad_demo_with_scenario.launch | 11 ++++------- ...arla_ros_bridge_with_example_ego_vehicle.launch | 13 ++++++------- 3 files changed, 15 insertions(+), 23 deletions(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 70921017..ffb4514f 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -13,7 +13,6 @@ - @@ -37,14 +36,11 @@ - - - - - - - - + + + + + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index 84c5417e..ccb57438 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -36,13 +36,10 @@ - - - - - - - + + + + diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index f20abdf5..12bc6c56 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -29,13 +29,12 @@ - - - - - - - + + + + + + From eaf99bdf8bd6055f1d84a75088de1d44b667a5ee Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 4 Dec 2020 13:49:39 -0500 Subject: [PATCH 405/627] delete carla_ego_vehicle and carla_infrastructure --- carla_ego_vehicle/CMakeLists.txt | 19 -- carla_ego_vehicle/README.md | 45 --- carla_ego_vehicle/config/sensors.json | 220 ------------- .../launch/carla_ego_vehicle.launch | 35 -- .../launch/carla_example_ego_vehicle.launch | 23 -- carla_ego_vehicle/package.xml | 16 - carla_ego_vehicle/setup.py | 13 - .../src/carla_ego_vehicle/__init__.py | 0 .../carla_ego_vehicle/carla_ego_vehicle.py | 310 ------------------ carla_infrastructure/CMakeLists.txt | 19 -- carla_infrastructure/README.md | 3 - carla_infrastructure/config/sensors.json | 24 -- .../launch/carla_infrastructure.launch | 16 - carla_infrastructure/package.xml | 15 - carla_infrastructure/setup.py | 13 - .../src/carla_infrastructure/__init__.py | 0 .../carla_infrastructure.py | 181 ---------- 17 files changed, 952 deletions(-) delete mode 100644 carla_ego_vehicle/CMakeLists.txt delete mode 100644 carla_ego_vehicle/README.md delete mode 100644 carla_ego_vehicle/config/sensors.json delete mode 100644 carla_ego_vehicle/launch/carla_ego_vehicle.launch delete mode 100644 carla_ego_vehicle/launch/carla_example_ego_vehicle.launch delete mode 100644 carla_ego_vehicle/package.xml delete mode 100644 carla_ego_vehicle/setup.py delete mode 100644 carla_ego_vehicle/src/carla_ego_vehicle/__init__.py delete mode 100755 carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py delete mode 100644 carla_infrastructure/CMakeLists.txt delete mode 100644 carla_infrastructure/README.md delete mode 100644 carla_infrastructure/config/sensors.json delete mode 100644 carla_infrastructure/launch/carla_infrastructure.launch delete mode 100644 carla_infrastructure/package.xml delete mode 100644 carla_infrastructure/setup.py delete mode 100644 carla_infrastructure/src/carla_infrastructure/__init__.py delete mode 100755 carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py diff --git a/carla_ego_vehicle/CMakeLists.txt b/carla_ego_vehicle/CMakeLists.txt deleted file mode 100644 index caae5a98..00000000 --- a/carla_ego_vehicle/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(carla_ego_vehicle) - -find_package(catkin REQUIRED COMPONENTS rospy roslaunch) - -catkin_python_setup() - -roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) - -catkin_package(CATKIN_DEPENDS rospy) - -catkin_install_python(PROGRAMS src/carla_ego_vehicle/carla_ego_vehicle.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) - -install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) diff --git a/carla_ego_vehicle/README.md b/carla_ego_vehicle/README.md deleted file mode 100644 index bcad5ed5..00000000 --- a/carla_ego_vehicle/README.md +++ /dev/null @@ -1,45 +0,0 @@ -# ROS Ego Vehicle - -The reference Carla client `carla_ego_vehicle` can be used to spawn an ego vehicle (role-name: "ego_vehicle") with attached sensors. - -Info: To be able to use `carla_manual_control` a camera with role-name 'view' and resolution of 800x600 is required. - -If no specific position is set, the ego vehicle is spawned at a random position. - -## Spawning at specific position - -It is possible to (re)spawn the ego vehicle at the specific location by publishing to `/carla//initialpose`. - -The preferred way of doing that is using RVIZ: - -![Autoware Runtime Manager Settings](../docs/images/rviz_set_start_goal.png) - -Selecting a Pose with '2D Pose Estimate' will delete the current ego_vehicle and respawn it at the specified position. - -## Re-use existing vehicle as ego-vehicle - -It is possible to re-use an existing vehicle as ego-vehicle, instead of spawning a new vehicle. In this case, the role_name is used to identify the vehicle -among all CARLA actors through the rolename attribute. Upon success, the requested sensors are attached to this actor, and the actor becomes the new ego vehicle. - -To make use of this option, set the ROS parameter spawn_ego_vehicle to false. - -## Create your own sensor setup - -Sensors, attached to the ego vehicle can be defined via a json file. `carla_ego_vehicle` reads it from the file location defined via the private ros parameter `sensor_definition_file`. - -The format is defined like that: - - { "sensors" = [ - { - "type": "", - "id": "", - "x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, # pose of the sensor, relative to the vehicle - - }, - ... - ] - } - -Define sensors with their attributes as described in the Carla Documentation about [Cameras and Sensors](https://github.com/carla-simulator/carla/blob/master/Docs/cameras_and_sensors.md). - -An example is provided by [carla_example_ego_vehicle.launch](launch/carla_example_ego_vehicle.launch). It uses the sensors from [sensors.json](config/sensors.json) diff --git a/carla_ego_vehicle/config/sensors.json b/carla_ego_vehicle/config/sensors.json deleted file mode 100644 index d6a564fc..00000000 --- a/carla_ego_vehicle/config/sensors.json +++ /dev/null @@ -1,220 +0,0 @@ -{ - "sensors": [ - { - "type": "sensor.camera.rgb", - "id": "rgb_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "image_size_x": 800, - "image_size_y": 600, - "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 - }, - { - "type": "sensor.camera.rgb", - "id": "rgb_view", - "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0, - "image_size_x": 800, - "image_size_y": 600, - "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 - }, - { - "type": "sensor.lidar.ray_cast", - "id": "lidar", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, - "rotation_frequency": 20, - "sensor_tick": 0.05, - "noise_stddev": 0.0 - }, - { - "type": "sensor.lidar.ray_cast_semantic", - "id": "semantic_lidar", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, - "rotation_frequency": 20, - "sensor_tick": 0.05 - }, - { - "type": "sensor.other.radar", - "id": "radar_front", - "x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "horizontal_fov": 30.0, - "vertical_fov": 10.0, - "points_per_second": 1500, - "range": 100.0 - }, - { - "type": "sensor.camera.semantic_segmentation", - "id": "semantic_segmentation_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "fov": 90.0, - "image_size_x": 400, - "image_size_y": 70, - "sensor_tick": 0.05, - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 - }, - { - "type": "sensor.camera.depth", - "id": "depth_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "fov": 90.0, - "image_size_x": 400, - "image_size_y": 70, - "sensor_tick": 0.05, - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 - }, - { - "type": "sensor.camera.dvs", - "id": "dvs_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "fov": 90.0, - "image_size_x": 400, - "image_size_y": 70, - "sensor_tick": 0.05, - "positive_threshold": 0.3, - "negative_threshold": 0.3, - "sigma_positive_threshold": 0.0, - "sigma_negative_threshold": 0.0, - "use_log": true, - "log_eps": 0.001 - }, - { - "type": "sensor.other.gnss", - "id": "gnss", - "x": 1.0, "y": 0.0, "z": 2.0, - "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": "imu", - "x": 2.0, "y": 0.0, "z": 2.0, "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, - "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 - }, - { - "type": "sensor.other.collision", - "id": "collision", - "x": 0.0, "y": 0.0, "z": 0.0 - }, - { - "type": "sensor.other.lane_invasion", - "id": "lane_invasion", - "x": 0.0, "y": 0.0, "z": 0.0 - }, - { - "type": "sensor.pseudo.tf", - "id": "tf" - }, - { - "type": "sensor.pseudo.objects", - "id": "objects" - }, - { - "type": "sensor.pseudo.odom", - "id": "odometry" - }, - { - "type": "sensor.pseudo.speedometer", - "id": "speedometer" - }, - { - "type": "actor.pseudo.control", - "id": "control" - } - ] -} diff --git a/carla_ego_vehicle/launch/carla_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_ego_vehicle.launch deleted file mode 100644 index ecc6be22..00000000 --- a/carla_ego_vehicle/launch/carla_ego_vehicle.launch +++ /dev/null @@ -1,35 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch b/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch deleted file mode 100644 index 9026a127..00000000 --- a/carla_ego_vehicle/launch/carla_example_ego_vehicle.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/carla_ego_vehicle/package.xml b/carla_ego_vehicle/package.xml deleted file mode 100644 index 9e07e85b..00000000 --- a/carla_ego_vehicle/package.xml +++ /dev/null @@ -1,16 +0,0 @@ - - - carla_ego_vehicle - 0.0.0 - The carla_ego_vehicle package - CARLA Simulator Team - MIT - catkin - rospy - roslaunch - rospy - rospy - topic_tools - - - diff --git a/carla_ego_vehicle/setup.py b/carla_ego_vehicle/setup.py deleted file mode 100644 index 4449d475..00000000 --- a/carla_ego_vehicle/setup.py +++ /dev/null @@ -1,13 +0,0 @@ -""" -Setup for carla_ego_vehicle -""" - -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup - -d = generate_distutils_setup( - packages=['carla_ego_vehicle'], - package_dir={'': 'src'} -) - -setup(**d) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/__init__.py b/carla_ego_vehicle/src/carla_ego_vehicle/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py deleted file mode 100755 index ff636f36..00000000 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ /dev/null @@ -1,310 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -""" -base class for spawning a Ego Vehicle in ROS - -Two modes are available: -- spawn at random Carla Spawnpoint -- spawn at the pose read from ROS topic /initialpose - -Whenever a pose is received via /initialpose, the vehicle gets respawned at that -position. If no /initialpose is set at startup, a random spawnpoint is used. - -/initialpose might be published via RVIZ '2D Pose Estimate" button. -""" - -from abc import abstractmethod - -import os -import sys -import random -import math -import json -import rospy -from tf.transformations import euler_from_quaternion, quaternion_from_euler -from diagnostic_msgs.msg import KeyValue -from geometry_msgs.msg import Point, PoseWithCovarianceStamped, Pose -from carla_msgs.msg import CarlaWorldInfo - -import carla - -import carla_common.transforms as trans - -from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest - -secure_random = random.SystemRandom() - -# ============================================================================== -# -- CarlaEgoVehicle ------------------------------------------------------------ -# ============================================================================== - - -class CarlaEgoVehicle(object): - - """ - Handles the spawning of the ego vehicle and its sensors - - Derive from this class and implement method sensors() - """ - - def __init__(self): - rospy.init_node('ego_vehicle', anonymous=True) - self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', 2000) - self.timeout = rospy.get_param('/carla/timeout', 10) - self.sensor_definition_file = rospy.get_param('~sensor_definition_file') - self.world = None - self.player = None - self.player_created = False - self.sensor_actors = [] - self.actor_filter = rospy.get_param('~vehicle_filter', 'vehicle.*') - self.actor_spawnpoint = None - self.role_name = rospy.get_param('~role_name', 'ego_vehicle') - # check argument and set spawn_point - spawn_point_param = rospy.get_param('~spawn_point') - if spawn_point_param and rospy.get_param('~spawn_ego_vehicle'): - rospy.loginfo("Using ros parameter for spawnpoint: {}".format(spawn_point_param)) - spawn_point = spawn_point_param.split(',') - if len(spawn_point) != 6: - raise ValueError("Invalid spawnpoint '{}'".format(spawn_point_param)) - pose = Pose() - pose.position.x = float(spawn_point[0]) - pose.position.y = float(spawn_point[1]) - pose.position.z = float(spawn_point[2]) - quat = quaternion_from_euler( - math.radians(float(spawn_point[3])), - math.radians(float(spawn_point[4])), - math.radians(float(spawn_point[5]))) - pose.orientation.x = quat[0] - pose.orientation.y = quat[1] - pose.orientation.z = quat[2] - pose.orientation.w = quat[3] - self.actor_spawnpoint = pose - - self.initialpose_subscriber = rospy.Subscriber( - "/carla/{}/initialpose".format(self.role_name), - PoseWithCovarianceStamped, - self.on_initialpose) - rospy.loginfo('listening to server %s:%s', self.host, self.port) - rospy.loginfo('using vehicle filter: %s', self.actor_filter) - - rospy.wait_for_service('/carla/spawn_object') - self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) - self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) - - def on_initialpose(self, initial_pose): - """ - Callback for /initialpose - - Receiving an initial pose (e.g. from RVIZ '2D Pose estimate') triggers a respawn. - - :return: - """ - self.actor_spawnpoint = initial_pose.pose.pose - self.restart() - - def restart(self): - """ - (Re)spawns the vehicle - - Either at a given actor_spawnpoint or at a random Carla spawnpoint - - :return: - """ - # Get vehicle blueprint. - blueprint = secure_random.choice( - self.world.get_blueprint_library().filter(self.actor_filter)) - blueprint.set_attribute('role_name', "{}".format(self.role_name)) - if blueprint.has_attribute('color'): - color = secure_random.choice(blueprint.get_attribute('color').recommended_values) - blueprint.set_attribute('color', color) - - # Spawn the vehicle. - if not rospy.get_param('~spawn_ego_vehicle'): - actors = self.world.get_actors().filter(self.actor_filter) - for actor in actors: - if actor.attributes['role_name'] == self.role_name: - self.player = actor - break - else: - spawn_point = None - - if self.actor_spawnpoint: - spawn_point = trans.ros_pose_to_carla_transform(self.actor_spawnpoint) - if self.player is not None: - self.player.set_transform(spawn_point) - - else: - if self.player is not None: - spawn_point = self.player.get_transform() - spawn_point.location.z += 2.0 - spawn_point.rotation.roll = 0.0 - spawn_point.rotation.pitch = 0.0 - self.player.set_transform(spawn_point) - - spawn_object_request = SpawnObjectRequest() - spawn_object_request.type = blueprint.id - spawn_object_request.id = self.role_name - spawn_object_request.attach_to = 0 - - while self.player is None: - if not self.actor_spawnpoint: - spawn_points = self.world.get_map().get_spawn_points() - spawn_point = secure_random.choice( - spawn_points) if spawn_points else carla.Transform() - - spawn_object_request.transform = trans.carla_transform_to_ros_pose(spawn_point) - response = self.spawn_object_service(spawn_object_request) - if response.id != -1: - self.player = self.world.get_actor(response.id) - self.player_created = True - - if self.player_created: - # Read sensors from file - if not os.path.exists(self.sensor_definition_file): - raise RuntimeError( - "Could not read sensor-definition from {}".format(self.sensor_definition_file)) - json_sensors = None - with open(self.sensor_definition_file) as handle: - json_sensors = json.loads(handle.read()) - - # Set up the sensors - self.sensor_actors = self.setup_sensors(json_sensors["sensors"]) - - self.player_created = False - - def setup_sensors(self, sensors): - """ - Create the sensors defined by the user and attach them to the ego-vehicle - :param sensors: list of sensors - :return: - """ - actors = [] - bp_library = self.world.get_blueprint_library() - sensor_names = [] - for sensor_spec in sensors: - try: - sensor_type = str(sensor_spec.pop("type")) - sensor_id = str(sensor_spec.pop("id")) - - if sensor_id in sensor_names: - rospy.logfatal( - "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) - raise NameError( - "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) - sensor_names.append(sensor_id) - - sensor_location = Point(x=sensor_spec.pop("x", 0.0), - y=sensor_spec.pop("y", 0.0), - z=sensor_spec.pop("z", 0.0)) - sensor_rotation = trans.RPY_to_ros_quaternion( - roll=math.radians(sensor_spec.pop('roll', 0.0)), - pitch=math.radians(sensor_spec.pop('pitch', 0.0)), - yaw=math.radians(sensor_spec.pop('yaw', 0.0))) - - spawn_object_request = SpawnObjectRequest() - spawn_object_request.type = sensor_type - spawn_object_request.id = sensor_id - spawn_object_request.attach_to = self.player.id - spawn_object_request.transform = Pose(sensor_location, sensor_rotation) - for attribute, value in sensor_spec.items(): - spawn_object_request.attributes.append( - KeyValue(str(attribute), str(value))) - - response = self.spawn_object_service(spawn_object_request) - if response.id == -1: - raise Exception(response.error_string) - - except KeyError as e: - rospy.logfatal( - "Sensor will not be spawned, the mandatory attribute {} is missing" - .format(e)) - raise e - - except Exception as e: - rospy.logfatal( - "Sensor {} will not be spawned, {}".format(sensor_id, e)) - raise e - - actors.append(response.id) - return actors - - @abstractmethod - def sensors(self): - """ - return a list of sensors attached - """ - return [] - - def destroy(self): - """ - destroy the current ego vehicle and its sensors - """ - # destroy sensors - for actor_id in self.sensor_actors: - destroy_object_request = DestroyObjectRequest(actor_id) - try: - response = self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) - - self.sensor_actors = [] - - # destroy player - if self.player and self.player.is_alive: - destroy_object_request = DestroyObjectRequest(self.player.id) - try: - self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) - - self.player = None - - def run(self): - """ - main loop - """ - # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") - try: - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException: - rospy.logerr("Timeout while waiting for world info!") - sys.exit(1) - - rospy.loginfo("CARLA world available. Spawn ego vehicle...") - rospy.on_shutdown(self.destroy) - client = carla.Client(self.host, self.port) - client.set_timeout(self.timeout) - self.world = client.get_world() - self.restart() - try: - rospy.spin() - except rospy.ROSInterruptException: - pass - -# ============================================================================== -# -- main() -------------------------------------------------------------------- -# ============================================================================== - - -def main(): - """ - main function - """ - ego_vehicle = CarlaEgoVehicle() - try: - ego_vehicle.run() - finally: - if ego_vehicle is not None: - ego_vehicle.destroy() - - -if __name__ == '__main__': - main() diff --git a/carla_infrastructure/CMakeLists.txt b/carla_infrastructure/CMakeLists.txt deleted file mode 100644 index 925b4159..00000000 --- a/carla_infrastructure/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(carla_infrastructure) - -find_package(catkin REQUIRED COMPONENTS rospy roslaunch) - -catkin_python_setup() - -roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) - -catkin_package(CATKIN_DEPENDS rospy) - -catkin_install_python(PROGRAMS src/carla_infrastructure/carla_infrastructure.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) - -install(DIRECTORY config/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) diff --git a/carla_infrastructure/README.md b/carla_infrastructure/README.md deleted file mode 100644 index 30af2b9f..00000000 --- a/carla_infrastructure/README.md +++ /dev/null @@ -1,3 +0,0 @@ -# ROS Infrastructure - -The reference Carla client `carla_infrastructure` can be used to spawn infrastructure sensors. diff --git a/carla_infrastructure/config/sensors.json b/carla_infrastructure/config/sensors.json deleted file mode 100644 index 905a7dc6..00000000 --- a/carla_infrastructure/config/sensors.json +++ /dev/null @@ -1,24 +0,0 @@ -{ - "sensors": [ - { - "type": "sensor.pseudo.traffic_lights", - "id": "traffic_lights" - }, - { - "type": "sensor.pseudo.objects", - "id": "objects" - }, - { - "type": "sensor.pseudo.actor_list", - "id": "actor_list" - }, - { - "type": "sensor.pseudo.markers", - "id": "markers" - }, - { - "type": "sensor.pseudo.opendrive_map", - "id": "map" - } - ] -} diff --git a/carla_infrastructure/launch/carla_infrastructure.launch b/carla_infrastructure/launch/carla_infrastructure.launch deleted file mode 100644 index 6fa4dddd..00000000 --- a/carla_infrastructure/launch/carla_infrastructure.launch +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/carla_infrastructure/package.xml b/carla_infrastructure/package.xml deleted file mode 100644 index 988f63e7..00000000 --- a/carla_infrastructure/package.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - carla_infrastructure - 0.0.0 - The carla_infrastructure package - CARLA Simulator Team - MIT - catkin - rospy - roslaunch - rospy - rospy - - - diff --git a/carla_infrastructure/setup.py b/carla_infrastructure/setup.py deleted file mode 100644 index 611caca2..00000000 --- a/carla_infrastructure/setup.py +++ /dev/null @@ -1,13 +0,0 @@ -""" -Setup for carla_infrastructure -""" - -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup - -d = generate_distutils_setup( - packages=['carla_infrastructure'], - package_dir={'': 'src'} -) - -setup(**d) diff --git a/carla_infrastructure/src/carla_infrastructure/__init__.py b/carla_infrastructure/src/carla_infrastructure/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py b/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py deleted file mode 100755 index 631a0656..00000000 --- a/carla_infrastructure/src/carla_infrastructure/carla_infrastructure.py +++ /dev/null @@ -1,181 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2019 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . - -""" -base class for spawning infrastructure sensors in ROS -""" - -from __future__ import print_function - -import os -import json -import math -import rospy - -import carla_common.transforms as trans - -from diagnostic_msgs.msg import KeyValue -from geometry_msgs.msg import Point, Pose - -from carla_msgs.msg import CarlaWorldInfo -from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest - -import carla - -# ============================================================================== -# -- CarlaInfrastructure ------------------------------------------------------------ -# ============================================================================== - - -class CarlaInfrastructure(object): - - """ - Handles the spawning of the infrastructure sensors - """ - - def __init__(self): - rospy.init_node('infrastructure', anonymous=True) - self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', 2000) - self.timeout = rospy.get_param('/carla/timeout', 10) - self.sensor_definition_file = rospy.get_param('~infrastructure_sensor_definition_file') - self.world = None - self.sensor_actors = [] - - rospy.wait_for_service('/carla/spawn_object') - self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) - self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) - - def restart(self): - """ - Spawns the infrastructure sensors - - :return: - """ - # Read sensors from file - if not os.path.exists(self.sensor_definition_file): - raise RuntimeError( - "Could not read sensor-definition from {}".format(self.sensor_definition_file)) - json_sensors = None - with open(self.sensor_definition_file) as handle: - json_sensors = json.loads(handle.read()) - - # Set up the sensors - self.sensor_actors = self.setup_sensors(json_sensors["sensors"]) - - def setup_sensors(self, sensors): - """ - Create the sensors defined by the user and spawn them in the world - :param sensors: list of sensors - :return: - """ - actors = [] - bp_library = self.world.get_blueprint_library() - sensor_names = [] - for sensor_spec in sensors: - try: - sensor_type = str(sensor_spec.pop("type")) - sensor_id = str(sensor_spec.pop("id")) - - if sensor_id in sensor_names: - rospy.logfatal( - "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) - raise NameError( - "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) - sensor_names.append(sensor_id) - - sensor_location = Point(x=sensor_spec.pop("x", 0.0), - y=sensor_spec.pop("y", 0.0), - z=sensor_spec.pop("z", 0.0)) - sensor_rotation = trans.RPY_to_ros_quaternion( - roll=math.radians(sensor_spec.pop('roll', 0.0)), - pitch=math.radians(sensor_spec.pop('pitch', 0.0)), - yaw=math.radians(sensor_spec.pop('yaw', 0.0))) - - spawn_object_request = SpawnObjectRequest() - spawn_object_request.type = sensor_type - spawn_object_request.id = sensor_id - spawn_object_request.attach_to = 0 - spawn_object_request.transform = Pose(sensor_location, sensor_rotation) - for attribute, value in sensor_spec.items(): - spawn_object_request.attributes.append( - KeyValue(str(attribute), str(value))) - - response = self.spawn_object_service(spawn_object_request) - if response.id == -1: - raise Exception(response.error_string) - - except KeyError as e: - rospy.logfatal( - "Sensor will not be spawned, the mandatory attribute {} is missing" - .format(e)) - raise e - - except Exception as e: - rospy.logfatal( - "Sensor {} will not be spawned, {}".format(sensor_id, e)) - raise e - - actors.append(response.id) - return actors - - def destroy(self): - """ - destroy the current ego vehicle and its sensors - """ - for actor_id in self.sensor_actors: - destroy_object_request = DestroyObjectRequest(actor_id) - try: - response = self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) - - self.sensor_actors = [] - - def run(self): - """ - main loop - """ - # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") - try: - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException as e: - rospy.logerr("Timeout while waiting for world info!") - raise e - rospy.loginfo("CARLA world available. Spawn infrastructure...") - rospy.on_shutdown(self.destroy) - client = carla.Client(self.host, self.port) - client.set_timeout(self.timeout) - self.world = client.get_world() - self.restart() - try: - rospy.spin() - except rospy.ROSInterruptException: - pass - -# ============================================================================== -# -- main() -------------------------------------------------------------------- -# ============================================================================== - - -def main(): - """ - main function - """ - infrastructure = CarlaInfrastructure() - try: - infrastructure.run() - finally: - if infrastructure is not None: - infrastructure.destroy() - - -if __name__ == '__main__': - main() From 1571494c1f95e23a51042a329639c3a4df3e13e6 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 7 Dec 2020 05:16:46 -0500 Subject: [PATCH 406/627] remove debug line and fix format --- .../src/carla_ros_bridge/pseudo_actor.py | 2 +- .../carla_spawn_actors/carla_spawn_actors.py | 75 ++++++++++--------- .../carla_spawn_actors/set_initial_pose.py | 7 +- 3 files changed, 42 insertions(+), 42 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 56d10443..cf5fc107 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -40,7 +40,7 @@ def __init__(self, uid, name, parent, node): if self.uid is None: raise TypeError("Actor ID is not set") - + if self.uid > np.iinfo(np.uint32).max: raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) diff --git a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py index 009a6d1e..ac76f2b1 100755 --- a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py +++ b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py @@ -51,7 +51,7 @@ def __init__(self): self.players = [] self.vehicles_sensors = [] self.global_sensors = [] - + rospy.wait_for_service('/carla/spawn_object') self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) @@ -85,12 +85,12 @@ def spawn_actors(self): global_sensors.append(actor) elif actor_type == "vehicle" or actor_type == "walker": vehicles.append(actor) - else : - rospy.logwarn("Actor with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"])) - print(f'======={self.spawn_sensors_only}') + else: + rospy.logwarn( + "Actor with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"])) if self.spawn_sensors_only is True and found_sensor_actor_list is False: - raise Exception("Parameter 'spawn_sensors_only' enabled, " + - "but 'sensor.pseudo.actor_list' is not instantiated, add it to your config file.") + raise Exception("Parameter 'spawn_sensors_only' enabled, " + + "but 'sensor.pseudo.actor_list' is not instantiated, add it to your config file.") try: self.global_sensors = self.setup_sensors(global_sensors) @@ -104,12 +104,12 @@ def spawn_actors(self): for actor_info in actor_info_list.actors: if actor_info.type == vehicle["type"] and actor_info.rolename == vehicle["id"]: vehicle["carla_id"] = actor_info.id - + try: self.players = self.setup_vehicles(vehicles) except Exception as e: raise Exception("Setting up vehicles failed: {}".format(e)) - + def setup_vehicles(self, vehicles): players = [] for vehicle in vehicles: @@ -118,13 +118,15 @@ def setup_vehicles(self, vehicles): try: carla_id = vehicle["carla_id"] except KeyError as e: - rospy.logerr("Could not spawn sensors of vehicle {}, its carla ID is not known.".format(vehicle["id"])) + rospy.logerr( + "Could not spawn sensors of vehicle {}, its carla ID is not known.".format(vehicle["id"])) break # spawn the vehicle's sensors try: self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], carla_id)) except Exception as e: - raise Exception("Setting up sensors of already spawned vehicle {} failed with error: {}".format(vehicle["id"], e)) + raise Exception( + "Setting up sensors of already spawned vehicle {} failed with error: {}".format(vehicle["id"], e)) else: spawn_object_request = SpawnObjectRequest() spawn_object_request.type = vehicle["type"] @@ -138,14 +140,14 @@ def setup_vehicles(self, vehicles): spawn_point_param = rospy.get_param("~spawn_point_" + vehicle["id"], None) spawn_param_used = False if (spawn_point_param is not None): - # try to use spawn_point from parameters + # try to use spawn_point from parameters try: spawn_point = self.check_spawn_point_param(spawn_point_param) rospy.loginfo("Spawn point from ros parameters") spawn_param_used = True except Exception as e: - rospy.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"])+ - "the spawn point from config file will be used. Error is: {}".format(e)) + rospy.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"]) + + "the spawn point from config file will be used. Error is: {}".format(e)) if "spawn_point" in vehicle and spawn_param_used is False: # get spawn point from config file @@ -161,12 +163,12 @@ def setup_vehicles(self, vehicles): rospy.loginfo("Spawn point from configuration file") except KeyError as e: rospy.logerr("{}: Could not use the spawn point from config file, ".format(vehicle["id"]) + - "the mandatory attribute {} is missing, a random spawn point will be used".format(e)) - - if spawn_point is None : + "the mandatory attribute {} is missing, a random spawn point will be used".format(e)) + + if spawn_point is None: # pose not specified, ask for a random one in the service call rospy.loginfo("Spawn point selected at random") - spawn_point = Pose() # empty pose + spawn_point = Pose() # empty pose spawn_object_request.random_pose = True player_spawned = False @@ -178,10 +180,11 @@ def setup_vehicles(self, vehicles): players.append(response.id) # Set up the sensors try: - self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], response.id)) + self.vehicles_sensors.append( + self.setup_sensors(vehicle["sensors"], response.id)) except KeyError: - rospy.logwarn("Vehicle {} have no 'sensors' field in his config file, none will be spawned") - + rospy.logwarn( + "Vehicle {} have no 'sensors' field in his config file, none will be spawned") return players @@ -210,12 +213,12 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): if attached_vehicle_id == 0 and sensor_type != "sensor.pseudo.actor_list": spawn_point = sensor_spec.pop("spawn_point") sensor_transform = self.create_spawn_point( - spawn_point.pop("x"), - spawn_point.pop("y"), - spawn_point.pop("z"), - spawn_point.pop("roll", 0.0), - spawn_point.pop("pitch", 0.0), - spawn_point.pop("yaw", 0.0)) + spawn_point.pop("x"), + spawn_point.pop("y"), + spawn_point.pop("z"), + spawn_point.pop("roll", 0.0), + spawn_point.pop("pitch", 0.0), + spawn_point.pop("yaw", 0.0)) else: # if sensor attached to a vehicle, or is a 'sensor.pseudo.actor_list', allow default pose spawn_point = sensor_spec.pop("spawn_point", 0) @@ -223,19 +226,19 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): sensor_transform = self.create_spawn_point(0.0, 0.0, 0.0, 0.0, 0.0, 0.0) else: sensor_transform = self.create_spawn_point( - spawn_point.pop("x", 0.0), - spawn_point.pop("y", 0.0), - spawn_point.pop("z", 0.0), - spawn_point.pop("roll", 0.0), - spawn_point.pop("pitch", 0.0), - spawn_point.pop("yaw", 0.0)) + spawn_point.pop("x", 0.0), + spawn_point.pop("y", 0.0), + spawn_point.pop("z", 0.0), + spawn_point.pop("roll", 0.0), + spawn_point.pop("pitch", 0.0), + spawn_point.pop("yaw", 0.0)) spawn_object_request = SpawnObjectRequest() spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id spawn_object_request.attach_to = attached_vehicle_id spawn_object_request.transform = sensor_transform - spawn_object_request.random_pose = False # never set a random pose for a sensor + spawn_object_request.random_pose = False # never set a random pose for a sensor for attribute, value in sensor_spec.items(): spawn_object_request.attributes.append( @@ -257,7 +260,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): actors.append(response.id) return actors - + def create_spawn_point(self, x, y, z, roll, pitch, yaw): spawn_point = Pose() spawn_point.position.x = x @@ -288,7 +291,6 @@ def check_spawn_point_param(self, spawn_point_parameter): ) return spawn_point - def destroy(self): """ destroy all the players and sensors @@ -321,7 +323,6 @@ def destroy(self): rospy.logwarn_once(str(e)) self.players = [] - def run(self): """ main loop @@ -356,7 +357,7 @@ def main(): spawn_actors_node.run() except Exception as e: rospy.logfatal( - "Exception caught: {}".format(e)) + "Exception caught: {}".format(e)) finally: if spawn_actors_node is not None: spawn_actors_node.destroy() diff --git a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py index f51f2cf9..fe28149c 100644 --- a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py +++ b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py @@ -20,6 +20,7 @@ import rospy from geometry_msgs.msg import PoseWithCovarianceStamped, Pose + class SetInitialPose(object): def __init__(self): @@ -33,14 +34,12 @@ def __init__(self): self.initial_pose_subscriber = rospy.Subscriber( "/initialpose", PoseWithCovarianceStamped, self.intial_pose_callback) - def intial_pose_callback(self, initial_pose): pose_to_publish = initial_pose.pose.pose pose_to_publish.position.z += 2.0 self.transform_publisher.publish(pose_to_publish) - def main(): """ @@ -48,7 +47,7 @@ def main(): """ set_initial_pose_node = SetInitialPose() rospy.spin() - + if __name__ == '__main__': - main() \ No newline at end of file + main() From 7f1c913b713bdfe4c624c35c869e2d949acdcf50 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 7 Dec 2020 06:06:31 -0500 Subject: [PATCH 407/627] made carla_spawn_actors node anonymous in launchfile --- carla_ad_demo/launch/carla_ad_demo.launch | 2 +- carla_ad_demo/launch/carla_ad_demo_with_scenario.launch | 2 +- .../launch/carla_ros_bridge_with_example_ego_vehicle.launch | 2 +- carla_spawn_actors/launch/carla_example_ego_vehicle.launch | 5 ++--- carla_spawn_actors/launch/carla_spawn_actors.launch | 3 +-- .../src/carla_spawn_actors/carla_spawn_actors.py | 1 + 6 files changed, 7 insertions(+), 8 deletions(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index ffb4514f..27cfc41b 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -38,7 +38,7 @@ - + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index ccb57438..893b00ec 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -38,7 +38,7 @@ - + diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index 12bc6c56..09259b32 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -32,7 +32,7 @@ - + diff --git a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch b/carla_spawn_actors/launch/carla_example_ego_vehicle.launch index e3a3ca49..3ee74da4 100644 --- a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch +++ b/carla_spawn_actors/launch/carla_example_ego_vehicle.launch @@ -1,6 +1,6 @@ - + - + diff --git a/carla_spawn_actors/launch/carla_spawn_actors.launch b/carla_spawn_actors/launch/carla_spawn_actors.launch index a9e0481d..9957de4e 100644 --- a/carla_spawn_actors/launch/carla_spawn_actors.launch +++ b/carla_spawn_actors/launch/carla_spawn_actors.launch @@ -1,6 +1,5 @@ - + diff --git a/carla_spawn_actors/README.md b/carla_spawn_actors/README.md index 61946c24..12fb2b28 100644 --- a/carla_spawn_actors/README.md +++ b/carla_spawn_actors/README.md @@ -1,6 +1,6 @@ # ROS Carla Spawn Actors -The reference Carla client `carla_spawn_actors` can be used to spawn actors (vehicels, sensors, walkers) with attached sensors. +`carla_spawn_actors` can be used to spawn actors (vehicles, sensors, walkers) with attached sensors. Info: To be able to use `carla_manual_control` a camera with role-name 'view' and resolution of 800x600 is required. @@ -8,8 +8,9 @@ If no specific position is set for vehicles, they will be spawned at a random po ## Spawning at specific position -- It is possible to specify the position at which the vehicle will be spawned, by defining a ros parameter named `spawn_point_vehicle_name`, the `vehicle_name` part being the same as the one specified in the config file. +- It is possible to specify the position at which the vehicle will be spawned, by defining a ros parameter named `spawn_point_`, with `` specified in the `id` field of the vehicle, in the config file. - It is also possible to specify the initial position directly in the config file. This is also how the initial positions of sensors should be declared. +- The `spawn_point` specified for a sensor attached to a vehicle, will be considered relative to the vehicle. It is possible to re-spawn a vehicle at a specific location by publishing to `/carla//initialpose`, but only if a `actor.pseudo.control` pseudo-actor is attached to the vehicle. The node `set_initial-pose` should also be running to handle the message on the topic. It can be launched using [set_initial_pose.launch](launch/set_initial_pose.launch) @@ -38,7 +39,7 @@ The format is defined like that: }, { "type": "", - "id": "", + "id": "", "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "sensors": [ From f88159c9fb7def22fecfef26c0484851dddad4bb Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 7 Dec 2020 12:43:09 +0100 Subject: [PATCH 409/627] Fix formatting --- carla_msgs | 2 +- carla_ros_bridge/src/carla_ros_bridge/actor_factory.py | 5 +++-- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 1 + carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/vehicle.py | 2 +- carla_spawn_actors/CMakeLists.txt | 2 +- 6 files changed, 8 insertions(+), 6 deletions(-) diff --git a/carla_msgs b/carla_msgs index 8888667e..06bf63d0 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 8888667efd4bd6a4d575d155593b0ee7411d822b +Subproject commit 06bf63d0d959feed73c427857c030269f3d79620 diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index ce3a5f89..05a0128c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -118,7 +118,7 @@ def _create_carla_actor(self, carla_actor): name = carla_actor.attributes.get("role_name", "") if not name: - name = str(carla_actor.id) + name = str(carla_actor.id) return self.create(carla_actor.type_id, name, parent_id, carla_actor) def create(self, type_id, name, attach_to, carla_actor=None): @@ -263,7 +263,8 @@ def _create_object(self, uid, type_id, name, parent, carla_actor=None): elif carla_actor.type_id.startswith("sensor.other.rss"): actor = RssSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): - actor = LaneInvasionSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = LaneInvasionSensor(uid, name, parent, self.node, + carla_actor, self.sync_mode) else: actor = Sensor(uid, name, parent, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("spectator"): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index c5834eac..36e7903f 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -45,6 +45,7 @@ # to generate a random spawning position or vehicles secure_random = random.SystemRandom() + class CarlaRosBridge(object): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 97f7f294..95b6dedf 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -27,7 +27,7 @@ class TrafficParticipant(Actor): actor implementation details for traffic participant """ - def __init__(self, uid, name,parent, node, carla_actor): + def __init__(self, uid, name, parent, node, carla_actor): """ Constructor diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 9c0b9efe..44c48eb1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -69,7 +69,7 @@ def get_marker_color(self): # pylint: disable=no-self-use color.g = 0 color.b = 0 return color - + def get_marker_pose(self): """ Function to return the pose for vehicles. diff --git a/carla_spawn_actors/CMakeLists.txt b/carla_spawn_actors/CMakeLists.txt index 5e37501a..f6391a49 100644 --- a/carla_spawn_actors/CMakeLists.txt +++ b/carla_spawn_actors/CMakeLists.txt @@ -14,7 +14,7 @@ catkin_package(CATKIN_DEPENDS rospy) catkin_install_python(PROGRAMS src/carla_spawn_actors/carla_spawn_actors.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) catkin_install_python(PROGRAMS src/carla_spawn_actors/set_initial_pose.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) From c999e31e1745e20e19bdd842e465ebb58ae8a2a0 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 7 Dec 2020 13:26:35 +0100 Subject: [PATCH 410/627] update roslaunch check according to http://wiki.ros.org/roslaunch#Overview --- carla_ad_demo/CMakeLists.txt | 3 ++- carla_ad_demo/package.xml | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 6fa8cdc0..c6e42761 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -1,9 +1,10 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ad_demo) -find_package(catkin REQUIRED COMPONENTS roslaunch) +find_package(catkin REQUIRED) if(CATKIN_ENABLE_TESTING) + find_package(roslaunch REQUIRED) roslaunch_add_file_check(launch) endif() diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 0b4f5fcd..e0ecda67 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -6,6 +6,7 @@ CARLA Simulator Team MIT catkin + roslaunch carla_ros_bridge carla_ego_vehicle carla_infrastructure From 3b5881d53d34c4c53ba3467a88d521c334db9e95 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 7 Dec 2020 14:44:55 +0100 Subject: [PATCH 411/627] Update roslaunch check --- carla_ad_demo/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index c6e42761..7cfc9f5e 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -1,11 +1,11 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ad_demo) -find_package(catkin REQUIRED) +find_package(catkin REQUIRED COMPONENTS roslaunch) if(CATKIN_ENABLE_TESTING) find_package(roslaunch REQUIRED) - roslaunch_add_file_check(launch) + roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) endif() catkin_package() From 2a76a7b7c4ab41a5b6769542fc0ba876740def66 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 7 Dec 2020 16:23:31 +0100 Subject: [PATCH 412/627] removed carla_ego_vehicle and carla_infrastructure as dependencies --- carla_ad_demo/launch/carla_ad_demo.launch | 8 -------- carla_ad_demo/launch/carla_ad_demo_with_scenario.launch | 8 -------- carla_ad_demo/package.xml | 3 +-- .../carla_ros_bridge_with_example_ego_vehicle.launch | 7 ------- carla_ros_bridge/package.xml | 3 +-- .../src/carla_spawn_actors/set_initial_pose.py | 0 6 files changed, 2 insertions(+), 27 deletions(-) mode change 100644 => 100755 carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 27cfc41b..21ff7278 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -43,14 +43,6 @@ - - - - - - - - diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index 893b00ec..e147cd24 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -42,14 +42,6 @@ - - - - - - - - diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index e0ecda67..b602b6b5 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -8,8 +8,7 @@ catkin roslaunch carla_ros_bridge - carla_ego_vehicle - carla_infrastructure + carla_spawn_actors carla_waypoint_publisher carla_ad_agent carla_manual_control diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index 59b60d8c..4090adf7 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -37,13 +37,6 @@ - - - - - - - diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index aeb7b944..1a8c4a25 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -25,8 +25,7 @@ rosgraph_msgs cv_bridge carla_msgs - carla_ego_vehicle - carla_infrastructure + carla_spawn_objects carla_manual_control diff --git a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py old mode 100644 new mode 100755 From 71c172feb0ee5a21456c7b066a722c3174736edf Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 8 Dec 2020 15:08:58 -0500 Subject: [PATCH 413/627] remove duplicate in pseudo_actor.py --- carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py | 5 ----- 1 file changed, 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index cf5fc107..7886e210 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -44,11 +44,6 @@ def __init__(self, uid, name, parent, node): if self.uid > np.iinfo(np.uint32).max: raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) - self.parent = parent - self.node = node - - if self.uid > np.iinfo(np.uint32).max: - raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) def destroy(self): """ From 82f8a301ad6acedfd376690ba2709cb73f98d8e5 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 8 Dec 2020 16:03:56 -0500 Subject: [PATCH 414/627] fixed problem with name of actor.pseudo.control id, adapted launchfile accordingly, corrected list of sensors in config file, correct some bugs in carla_spawn_actors --- carla_spawn_actors/config/actors.json | 161 +++++++++++++++--- .../launch/carla_example_ego_vehicle.launch | 7 +- .../launch/carla_spawn_actors.launch | 2 +- .../launch/set_initial_pose.launch | 3 + .../carla_spawn_actors/carla_spawn_actors.py | 8 +- .../carla_spawn_actors/set_initial_pose.py | 7 +- 6 files changed, 151 insertions(+), 37 deletions(-) diff --git a/carla_spawn_actors/config/actors.json b/carla_spawn_actors/config/actors.json index fc477e47..f48b6c8f 100644 --- a/carla_spawn_actors/config/actors.json +++ b/carla_spawn_actors/config/actors.json @@ -2,48 +2,125 @@ "actors": [ { - "type": "sensor.camera.rgb", - "id": "camera01", - "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - "image_size_x": 800, - "image_size_y": 600, - "fov": 100, - "sensor_tick": 0.05 + "type": "sensor.pseudo.traffic_lights", + "id": "traffic_lights" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" }, { "type": "sensor.pseudo.actor_list", "id": "actor_list" }, + { + "type": "sensor.pseudo.markers", + "id": "markers" + }, + { + "type": "sensor.pseudo.opendrive_map", + "id": "map" + }, { "type": "vehicle.audi.tt", "id": "ego_vehicle", "sensors": [ - { - "type": "actor.pseudo.control", - "id": "" - }, { "type": "sensor.camera.rgb", - "id": "front", + "id": "rgb_front", "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "image_size_x": 800, "image_size_y": 600, "fov": 90.0, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 200.0, + "iso": 100.0, + "fstop": 8.0, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "histogram", + "exposure_compensation": 0.0, + "exposure_min_bright": 7.0, + "exposure_max_bright": 9.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 }, { "type": "sensor.camera.rgb", - "id": "view", + "id": "rgb_view", "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0}, "image_size_x": 800, "image_size_y": 600, "fov": 90.0, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 200.0, + "iso": 100.0, + "fstop": 8.0, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "histogram", + "exposure_compensation": 0.0, + "exposure_min_bright": 7.0, + "exposure_max_bright": 9.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 }, { "type": "sensor.lidar.ray_cast", - "id": "lidar1", + "id": "lidar", "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "range": 50, "channels": 32, @@ -56,7 +133,7 @@ }, { "type": "sensor.lidar.ray_cast_semantic", - "id": "lidar1", + "id": "semantic_lidar", "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "range": 50, "channels": 32, @@ -68,7 +145,7 @@ }, { "type": "sensor.other.radar", - "id": "front", + "id": "radar_front", "spawn_point": {"x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "horizontal_fov": 30.0, "vertical_fov": 10.0, @@ -77,25 +154,37 @@ }, { "type": "sensor.camera.semantic_segmentation", - "id": "front", + "id": "semantic_segmentation_front", "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "fov": 90.0, "image_size_x": 400, "image_size_y": 70, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 }, { "type": "sensor.camera.depth", - "id": "front", + "id": "depth_front", "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "fov": 90.0, "image_size_x": 400, "image_size_y": 70, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 }, { "type": "sensor.camera.dvs", - "id": "front", + "id": "dvs_front", "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "fov": 90.0, "image_size_x": 400, @@ -110,14 +199,14 @@ }, { "type": "sensor.other.gnss", - "id": "gnss1", + "id": "gnss", "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0}, "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": "imu1", + "id": "imu", "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "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, @@ -125,17 +214,33 @@ }, { "type": "sensor.other.collision", - "id": "collision1", + "id": "collision", "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} }, { "type": "sensor.other.lane_invasion", - "id": "laneinvasion1", + "id": "lane_invasion", "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} }, + { + "type": "sensor.pseudo.tf", + "id": "tf" + }, { "type": "sensor.pseudo.objects", - "id": "objectsensor1" + "id": "objects" + }, + { + "type": "sensor.pseudo.odom", + "id": "odometry" + }, + { + "type": "sensor.pseudo.speedometer", + "id": "speedometer" + }, + { + "type": "actor.pseudo.control", + "id": "control" } ] } diff --git a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch b/carla_spawn_actors/launch/carla_example_ego_vehicle.launch index 3ee74da4..b0c6ed6a 100644 --- a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch +++ b/carla_spawn_actors/launch/carla_example_ego_vehicle.launch @@ -5,17 +5,20 @@ - + + + - + + diff --git a/carla_spawn_actors/launch/carla_spawn_actors.launch b/carla_spawn_actors/launch/carla_spawn_actors.launch index 9957de4e..819753e8 100644 --- a/carla_spawn_actors/launch/carla_spawn_actors.launch +++ b/carla_spawn_actors/launch/carla_spawn_actors.launch @@ -4,7 +4,7 @@ - + diff --git a/carla_spawn_actors/launch/set_initial_pose.launch b/carla_spawn_actors/launch/set_initial_pose.launch index 121b35b2..aa55ac88 100644 --- a/carla_spawn_actors/launch/set_initial_pose.launch +++ b/carla_spawn_actors/launch/set_initial_pose.launch @@ -1,8 +1,11 @@ + + + diff --git a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py index b8b870ab..4e7c5fc0 100755 --- a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py +++ b/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py @@ -210,7 +210,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): sensor_spec['id'])) sensor_names.append(sensor_name) - if attached_vehicle_id == 0 and sensor_type != "sensor.pseudo.actor_list": + if attached_vehicle_id == 0 and "pseudo" not in sensor_type: spawn_point = sensor_spec.pop("spawn_point") sensor_transform = self.create_spawn_point( spawn_point.pop("x"), @@ -220,7 +220,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): spawn_point.pop("pitch", 0.0), spawn_point.pop("yaw", 0.0)) else: - # if sensor attached to a vehicle, or is a 'sensor.pseudo.actor_list', allow default pose + # if sensor attached to a vehicle, or is a 'pseudo_actor', allow default pose spawn_point = sensor_spec.pop("spawn_point", 0) if spawn_point == 0: sensor_transform = self.create_spawn_point(0.0, 0.0, 0.0, 0.0, 0.0, 0.0) @@ -251,12 +251,12 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): except KeyError as e: rospy.logerr( "Sensor {} will not be spawned, the mandatory attribute {} is missing".format(sensor_name, e)) - break + continue except Exception as e: rospy.logerr( "Sensor {} will not be spawned: {}".format(sensor_name, e)) - break + continue actors.append(response.id) return actors diff --git a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py index fe28149c..ae1829c7 100755 --- a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py +++ b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py @@ -28,9 +28,12 @@ def __init__(self): rospy.init_node('set_initial_pose', anonymous=True) self.role_name = rospy.get_param('~role_name', 'ego_vehicle') - + # control_id should correspond to the id of the actor.pseudo.control + # actor that is set in the config file used to spawn it + self.control_id = rospy.get_param('~control_id', 'control') + print("/carla/{}/{}/set_transform".format(self.role_name, self.control_id)) self.transform_publisher = rospy.Publisher( - "/carla/{}/set_transform".format(self.role_name), Pose, queue_size=10) + "/carla/{}/{}/set_transform".format(self.role_name, self.control_id), Pose, queue_size=10) self.initial_pose_subscriber = rospy.Subscriber( "/initialpose", PoseWithCovarianceStamped, self.intial_pose_callback) From a80521e63de6e8ca9def6b4232375f671b735573 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 8 Dec 2020 16:08:29 -0500 Subject: [PATCH 415/627] corrected carla_spawn_agents readme --- carla_spawn_actors/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_spawn_actors/README.md b/carla_spawn_actors/README.md index 12fb2b28..7acdfd9b 100644 --- a/carla_spawn_actors/README.md +++ b/carla_spawn_actors/README.md @@ -12,7 +12,7 @@ If no specific position is set for vehicles, they will be spawned at a random po - It is also possible to specify the initial position directly in the config file. This is also how the initial positions of sensors should be declared. - The `spawn_point` specified for a sensor attached to a vehicle, will be considered relative to the vehicle. -It is possible to re-spawn a vehicle at a specific location by publishing to `/carla//initialpose`, but only if a `actor.pseudo.control` pseudo-actor is attached to the vehicle. The node `set_initial-pose` should also be running to handle the message on the topic. It can be launched using [set_initial_pose.launch](launch/set_initial_pose.launch) +It is possible to re-spawn a vehicle at a specific location by publishing to `/carla///initialpose`, but only if an `actor.pseudo.control` pseudo-actor (with id ``) is attached to the vehicle. The node `set_initial_pose` should also be running to handle the message on the topic. It can be launched using [set_initial_pose.launch](launch/set_initial_pose.launch), and `` should be specified by setting the ros parameter called `controller_id`. The preferred way to publish the new pose message is to use RVIZ: From de95c11c60b97ccf1ccfff21e38b733673da0ab9 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 8 Dec 2020 16:22:12 -0500 Subject: [PATCH 416/627] replaced carla_ego_vehicle and carla_infrastructure with carla_spawn_actors in ros_bridge tests and dockerfile --- carla_ros_bridge/test/ros_bridge_client.test | 17 +- carla_ros_bridge/test/test_actors.json | 248 ++++++++++++++++++ .../test/test_infrastructure_sensors.json | 24 -- carla_ros_bridge/test/test_sensors.json | 221 ---------------- docker/Dockerfile | 3 +- 5 files changed, 252 insertions(+), 261 deletions(-) create mode 100644 carla_ros_bridge/test/test_actors.json delete mode 100644 carla_ros_bridge/test/test_infrastructure_sensors.json delete mode 100644 carla_ros_bridge/test/test_sensors.json diff --git a/carla_ros_bridge/test/ros_bridge_client.test b/carla_ros_bridge/test/ros_bridge_client.test index cecb51f6..725b0218 100644 --- a/carla_ros_bridge/test/ros_bridge_client.test +++ b/carla_ros_bridge/test/ros_bridge_client.test @@ -4,8 +4,7 @@ - - + @@ -13,18 +12,8 @@ - - - - - - - - - - - - + + diff --git a/carla_ros_bridge/test/test_actors.json b/carla_ros_bridge/test/test_actors.json new file mode 100644 index 00000000..f48b6c8f --- /dev/null +++ b/carla_ros_bridge/test/test_actors.json @@ -0,0 +1,248 @@ +{ + "actors": + [ + { + "type": "sensor.pseudo.traffic_lights", + "id": "traffic_lights" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list" + }, + { + "type": "sensor.pseudo.markers", + "id": "markers" + }, + { + "type": "sensor.pseudo.opendrive_map", + "id": "map" + }, + { + "type": "vehicle.audi.tt", + "id": "ego_vehicle", + "sensors": + [ + { + "type": "sensor.camera.rgb", + "id": "rgb_front", + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "image_size_x": 800, + "image_size_y": 600, + "fov": 90.0, + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 200.0, + "iso": 100.0, + "fstop": 8.0, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "histogram", + "exposure_compensation": 0.0, + "exposure_min_bright": 7.0, + "exposure_max_bright": 9.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 + }, + { + "type": "sensor.camera.rgb", + "id": "rgb_view", + "spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0}, + "image_size_x": 800, + "image_size_y": 600, + "fov": 90.0, + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 200.0, + "iso": 100.0, + "fstop": 8.0, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "histogram", + "exposure_compensation": 0.0, + "exposure_min_bright": 7.0, + "exposure_max_bright": 9.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08, + "bloom_intensity": 0.675, + "lens_flare_intensity": 0.1 + }, + { + "type": "sensor.lidar.ray_cast", + "id": "lidar", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05, + "noise_stddev": 0.0 + }, + { + "type": "sensor.lidar.ray_cast_semantic", + "id": "semantic_lidar", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "range": 50, + "channels": 32, + "points_per_second": 320000, + "upper_fov": 2.0, + "lower_fov": -26.8, + "rotation_frequency": 20, + "sensor_tick": 0.05 + }, + { + "type": "sensor.other.radar", + "id": "radar_front", + "spawn_point": {"x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "horizontal_fov": 30.0, + "vertical_fov": 10.0, + "points_per_second": 1500, + "range": 100.0 + }, + { + "type": "sensor.camera.semantic_segmentation", + "id": "semantic_segmentation_front", + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.depth", + "id": "depth_front", + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + }, + { + "type": "sensor.camera.dvs", + "id": "dvs_front", + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "fov": 90.0, + "image_size_x": 400, + "image_size_y": 70, + "sensor_tick": 0.05, + "positive_threshold": 0.3, + "negative_threshold": 0.3, + "sigma_positive_threshold": 0.0, + "sigma_negative_threshold": 0.0, + "use_log": true, + "log_eps": 0.001 + }, + { + "type": "sensor.other.gnss", + "id": "gnss", + "spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0}, + "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": "imu", + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "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, + "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 + }, + { + "type": "sensor.other.collision", + "id": "collision", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} + }, + { + "type": "sensor.other.lane_invasion", + "id": "lane_invasion", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0} + }, + { + "type": "sensor.pseudo.tf", + "id": "tf" + }, + { + "type": "sensor.pseudo.objects", + "id": "objects" + }, + { + "type": "sensor.pseudo.odom", + "id": "odometry" + }, + { + "type": "sensor.pseudo.speedometer", + "id": "speedometer" + }, + { + "type": "actor.pseudo.control", + "id": "control" + } + ] + } + ] +} diff --git a/carla_ros_bridge/test/test_infrastructure_sensors.json b/carla_ros_bridge/test/test_infrastructure_sensors.json deleted file mode 100644 index a3b426fc..00000000 --- a/carla_ros_bridge/test/test_infrastructure_sensors.json +++ /dev/null @@ -1,24 +0,0 @@ -{ - "sensors": [ - { - "type": "sensor.pseudo.traffic_lights", - "id": "traffic_lights" - }, - { - "type": "sensor.pseudo.actor_list", - "id": "actor_list" - }, - { - "type": "sensor.pseudo.markers", - "id": "markers" - }, - { - "type": "sensor.pseudo.opendrive_map", - "id": "map" - }, - { - "type": "sensor.pseudo.objects", - "id": "objects" - } - ] -} diff --git a/carla_ros_bridge/test/test_sensors.json b/carla_ros_bridge/test/test_sensors.json deleted file mode 100644 index d0a444d2..00000000 --- a/carla_ros_bridge/test/test_sensors.json +++ /dev/null @@ -1,221 +0,0 @@ -{ - "sensors": [ - { - "type": "sensor.camera.rgb", - "id": "rgb_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "image_size_x": 800, - "image_size_y": 600, - "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 - }, - { - "type": "sensor.camera.rgb", - "id": "rgb_view", - "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0, - "image_size_x": 800, - "image_size_y": 600, - "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 - }, - { - "type": "sensor.lidar.ray_cast", - "id": "lidar", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, - "rotation_frequency": 20, - "sensor_tick": 0.05, - "noise_stddev": 0.0 - }, - { - "type": "sensor.lidar.ray_cast_semantic", - "id": "semantic_lidar", - "x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "range": 50, - "channels": 32, - "points_per_second": 320000, - "upper_fov": 2.0, - "lower_fov": -26.8, - "rotation_frequency": 20, - "sensor_tick": 0.05 - }, - { - "type": "sensor.other.radar", - "id": "radar_front", - "x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "horizontal_fov": 30.0, - "vertical_fov": 10.0, - "points_per_second": 1500, - "range": 100.0 - }, - { - "type": "sensor.camera.semantic_segmentation", - "id": "semantic_segmentation_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "fov": 90.0, - "image_size_x": 400, - "image_size_y": 70, - "sensor_tick": 0.05, - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 - }, - { - "type": "sensor.camera.depth", - "id": "depth_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "fov": 90.0, - "image_size_x": 400, - "image_size_y": 70, - "sensor_tick": 0.05, - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 - }, - { - "type": "sensor.camera.dvs", - "id": "dvs_front", - "x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0, - "fov": 90.0, - "image_size_x": 400, - "image_size_y": 70, - "sensor_tick": 0.05, - "positive_threshold": 0.3, - "negative_threshold": 0.3, - "sigma_positive_threshold": 0.0, - "sigma_negative_threshold": 0.0, - "use_log": true, - "log_eps": 0.001 - }, - { - "type": "sensor.other.gnss", - "id": "gnss", - "x": 1.0, "y": 0.0, "z": 2.0, - "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": "imu", - "x": 2.0, "y": 0.0, "z": 2.0, "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, - "noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0 - }, - { - "type": "sensor.other.collision", - "id": "collision", - "x": 0.0, "y": 0.0, "z": 0.0 - }, - { - "type": "sensor.other.lane_invasion", - "id": "lane_invasion", - "x": 0.0, "y": 0.0, "z": 0.0 - }, - { - "type": "sensor.pseudo.tf", - "id": "tf" - }, - { - "type": "sensor.pseudo.objects", - "id": "objects" - }, - { - "type": "sensor.pseudo.odom", - "id": "odometry" - }, - { - "type": "sensor.pseudo.speedometer", - "id": "speedometer" - }, - { - "type": "actor.pseudo.control", - "id": "control" - } - ] -} - diff --git a/docker/Dockerfile b/docker/Dockerfile index ec5476b3..36354761 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -31,8 +31,7 @@ ENV PYTHONPATH=/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py$PYTHON_VE COPY carla_ackermann_control /opt/carla-ros-bridge/src/carla_ackermann_control COPY carla_common /opt/carla-ros-bridge/src/carla_common -COPY carla_ego_vehicle /opt/carla-ros-bridge/src/carla_ego_vehicle -COPY carla_infrastructure /opt/carla-ros-bridge/src/carla_infrastructure +COPY carla_spawn_actors /opt/carla-ros-bridge/src/carla_spawn_actors COPY carla_manual_control /opt/carla-ros-bridge/src/carla_manual_control COPY carla_msgs /opt/carla-ros-bridge/src/carla_msgs COPY carla_ros_bridge /opt/carla-ros-bridge/src/carla_ros_bridge From 4344279dc062855ceb81b60bdb3ba805661f48e2 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 9 Dec 2020 05:37:47 -0500 Subject: [PATCH 417/627] remove ref to carla_ego_vehicle and carla_infrastructure in readme --- README.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/README.md b/README.md index 83c71055..4324cab3 100644 --- a/README.md +++ b/README.md @@ -24,9 +24,8 @@ Beside the bridging functionality, there are many more features provided in sepa | Name | Description | | --------------------------------- | ------------------------------------------------------------------------------------------------------- | -| [Carla Ego Vehicle](carla_ego_vehicle/README.md) | Provides a generic way to spawn an ego vehicle and attach sensors to it. | +| [Carla Spawn Actors](carla_spawn_actors/README.md) | Provides a generic way to spawn actors | | [Carla Manual Control](carla_manual_control/README.md) | A ROS-based visualization and control tool for an ego vehicle (similar to carla_manual_control.py provided by CARLA) | -| [Carla Infrastructure](carla_infrastructure/README.md) | Provides a generic way to spawn a set of infrastructure sensors defined in a config file. | | [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API | | [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. | | [Carla Ackermann Control](carla_ackermann_control/README.md) | A controller to convert ackermann commands to steer/throttle/brake| From 86a3bf7be7f7b1e61c12aa31dc5abf39b5a8d078 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 9 Dec 2020 06:07:06 -0500 Subject: [PATCH 418/627] fix missing argument in carla_example_ego launchfile --- carla_spawn_actors/launch/carla_example_ego_vehicle.launch | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch b/carla_spawn_actors/launch/carla_example_ego_vehicle.launch index b0c6ed6a..335791fc 100644 --- a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch +++ b/carla_spawn_actors/launch/carla_example_ego_vehicle.launch @@ -5,14 +5,15 @@ - + + - + From 103961c949706f4b065167dc96f321d1db95e4a3 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 9 Dec 2020 06:18:31 -0500 Subject: [PATCH 419/627] Revert "Update roslaunch check" This reverts commit 3b5881d53d34c4c53ba3467a88d521c334db9e95. --- carla_ad_demo/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 7cfc9f5e..c6e42761 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -1,11 +1,11 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ad_demo) -find_package(catkin REQUIRED COMPONENTS roslaunch) +find_package(catkin REQUIRED) if(CATKIN_ENABLE_TESTING) find_package(roslaunch REQUIRED) - roslaunch_add_file_check(launch IGNORE_UNSET_ARGS) + roslaunch_add_file_check(launch) endif() catkin_package() From 6d8bea0d1f3dc17f460fd54133bba3a888caaa38 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 9 Dec 2020 06:19:11 -0500 Subject: [PATCH 420/627] Revert "update roslaunch check" This reverts commit c999e31e1745e20e19bdd842e465ebb58ae8a2a0. --- carla_ad_demo/CMakeLists.txt | 3 +-- carla_ad_demo/package.xml | 1 - 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index c6e42761..6fa8cdc0 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -1,10 +1,9 @@ cmake_minimum_required(VERSION 2.8.3) project(carla_ad_demo) -find_package(catkin REQUIRED) +find_package(catkin REQUIRED COMPONENTS roslaunch) if(CATKIN_ENABLE_TESTING) - find_package(roslaunch REQUIRED) roslaunch_add_file_check(launch) endif() diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index b602b6b5..05de4da2 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -6,7 +6,6 @@ CARLA Simulator Team MIT catkin - roslaunch carla_ros_bridge carla_spawn_actors carla_waypoint_publisher From c814edf8c531c3e983c3345ef2ff5b77d3d8a59c Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 9 Dec 2020 06:44:43 -0500 Subject: [PATCH 421/627] remove leftover from debugging and some sensor parameters in actors.json --- carla_spawn_actors/config/actors.json | 94 +------------------ .../carla_spawn_actors/set_initial_pose.py | 1 - 2 files changed, 4 insertions(+), 91 deletions(-) diff --git a/carla_spawn_actors/config/actors.json b/carla_spawn_actors/config/actors.json index f48b6c8f..7735848e 100644 --- a/carla_spawn_actors/config/actors.json +++ b/carla_spawn_actors/config/actors.json @@ -33,44 +33,7 @@ "image_size_x": 800, "image_size_y": 600, "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 + "sensor_tick": 0.05 }, { "type": "sensor.camera.rgb", @@ -79,44 +42,7 @@ "image_size_x": 800, "image_size_y": 600, "fov": 90.0, - "sensor_tick": 0.05, - "gamma": 2.2, - "shutter_speed": 200.0, - "iso": 100.0, - "fstop": 8.0, - "min_fstop": 1.2, - "blade_count": 5, - "exposure_mode": "histogram", - "exposure_compensation": 0.0, - "exposure_min_bright": 7.0, - "exposure_max_bright": 9.0, - "exposure_speed_up": 3.0, - "exposure_speed_down": 1.0, - "calibration_constant": 16.0, - "focal_distance": 1000.0, - "blur_amount": 1.0, - "blur_radius": 0.0, - "motion_blur_intensity": 0.45, - "motion_blur_max_distortion": 0.35, - "motion_blur_min_object_screen_size": 0.1, - "slope": 0.88, - "toe": 0.55, - "shoulder": 0.26, - "black_clip": 0.0, - "white_clip": 0.04, - "temp": 6500.0, - "tint": 0.0, - "chromatic_aberration_intensity": 0.0, - "chromatic_aberration_offset": 0.0, - "enable_postprocess_effects": "True", - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08, - "bloom_intensity": 0.675, - "lens_flare_intensity": 0.1 + "sensor_tick": 0.05 }, { "type": "sensor.lidar.ray_cast", @@ -159,13 +85,7 @@ "fov": 90.0, "image_size_x": 400, "image_size_y": 70, - "sensor_tick": 0.05, - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 + "sensor_tick": 0.05 }, { "type": "sensor.camera.depth", @@ -174,13 +94,7 @@ "fov": 90.0, "image_size_x": 400, "image_size_y": 70, - "sensor_tick": 0.05, - "lens_circle_falloff": 5.0, - "lens_circle_multiplier": 0.0, - "lens_k": -1.0, - "lens_kcube": 0.0, - "lens_x_size": 0.08, - "lens_y_size": 0.08 + "sensor_tick": 0.05 }, { "type": "sensor.camera.dvs", diff --git a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py index ae1829c7..db878ab1 100755 --- a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py +++ b/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py @@ -31,7 +31,6 @@ def __init__(self): # control_id should correspond to the id of the actor.pseudo.control # actor that is set in the config file used to spawn it self.control_id = rospy.get_param('~control_id', 'control') - print("/carla/{}/{}/set_transform".format(self.role_name, self.control_id)) self.transform_publisher = rospy.Publisher( "/carla/{}/{}/set_transform".format(self.role_name, self.control_id), Pose, queue_size=10) From 330eb340f929180d963298b9b1552598ffa3eab0 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 9 Dec 2020 07:06:01 -0500 Subject: [PATCH 422/627] possbility to use wildcard for vehicle type when spawning --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 6 +++++- carla_spawn_actors/config/actors.json | 2 +- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 36e7903f..0bcf3955 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -142,7 +142,11 @@ def __init__(self, carla_world, params): CarlaWeatherParameters, self.on_weather_changed) def _spawn_actor(self, req): - blueprint = self.carla_world.get_blueprint_library().find(req.type) + if "*" in req.type: + blueprint = secure_random.choice( + self.carla_world.get_blueprint_library().filter(req.type)) + else: + blueprint = self.carla_world.get_blueprint_library().find(req.type) blueprint.set_attribute('role_name', req.id) for attribute in req.attributes: blueprint.set_attribute(attribute.key, attribute.value) diff --git a/carla_spawn_actors/config/actors.json b/carla_spawn_actors/config/actors.json index 7735848e..c6ea612a 100644 --- a/carla_spawn_actors/config/actors.json +++ b/carla_spawn_actors/config/actors.json @@ -22,7 +22,7 @@ "id": "map" }, { - "type": "vehicle.audi.tt", + "type": "vehicle.*", "id": "ego_vehicle", "sensors": [ From 8b19a3fb38c873a237d782eed6c9df73acf25a26 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 9 Dec 2020 07:19:13 -0500 Subject: [PATCH 423/627] typo in carla_ros_bridge dependency --- carla_ros_bridge/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 1a8c4a25..ba5bd1cf 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -25,7 +25,7 @@ rosgraph_msgs cv_bridge carla_msgs - carla_spawn_objects + carla_spawn_actors carla_manual_control From 4e4b71b42b108848d51ee49ab8c651b1a67e2821 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 9 Dec 2020 08:05:34 -0500 Subject: [PATCH 424/627] renamed carla_spawn_actors to carla_spawn_objects --- README.md | 2 +- carla_ad_demo/launch/carla_ad_demo.launch | 4 +- .../launch/carla_ad_demo_with_scenario.launch | 4 +- carla_ad_demo/package.xml | 2 +- ...ros_bridge_with_example_ego_vehicle.launch | 4 +- carla_ros_bridge/package.xml | 2 +- carla_ros_bridge/test/ros_bridge_client.test | 6 +-- .../{test_actors.json => test_objects.json} | 2 +- .../CMakeLists.txt | 6 +-- .../README.md | 10 ++--- .../config/objects.json | 2 +- .../launch/carla_example_ego_vehicle.launch | 10 ++--- .../launch/carla_spawn_objects.launch | 8 ++-- .../launch/set_initial_pose.launch | 2 +- .../package.xml | 4 +- .../setup.py | 4 +- .../src/carla_spawn_objects}/__init__.py | 0 .../carla_spawn_objects.py | 44 +++++++++---------- .../carla_spawn_objects}/set_initial_pose.py | 0 docker/Dockerfile | 2 +- 20 files changed, 59 insertions(+), 59 deletions(-) rename carla_ros_bridge/test/{test_actors.json => test_objects.json} (99%) rename {carla_spawn_actors => carla_spawn_objects}/CMakeLists.txt (75%) rename {carla_spawn_actors => carla_spawn_objects}/README.md (86%) rename carla_spawn_actors/config/actors.json => carla_spawn_objects/config/objects.json (99%) rename {carla_spawn_actors => carla_spawn_objects}/launch/carla_example_ego_vehicle.launch (66%) rename carla_spawn_actors/launch/carla_spawn_actors.launch => carla_spawn_objects/launch/carla_spawn_objects.launch (53%) rename {carla_spawn_actors => carla_spawn_objects}/launch/set_initial_pose.launch (71%) rename {carla_spawn_actors => carla_spawn_objects}/package.xml (83%) rename {carla_spawn_actors => carla_spawn_objects}/setup.py (72%) rename {carla_spawn_actors/src/carla_spawn_actors => carla_spawn_objects/src/carla_spawn_objects}/__init__.py (100%) rename carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py => carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py (92%) rename {carla_spawn_actors/src/carla_spawn_actors => carla_spawn_objects/src/carla_spawn_objects}/set_initial_pose.py (100%) diff --git a/README.md b/README.md index 4324cab3..88c38437 100644 --- a/README.md +++ b/README.md @@ -24,7 +24,7 @@ Beside the bridging functionality, there are many more features provided in sepa | Name | Description | | --------------------------------- | ------------------------------------------------------------------------------------------------------- | -| [Carla Spawn Actors](carla_spawn_actors/README.md) | Provides a generic way to spawn actors | +| [Carla Spawn Actors](carla_spawn_objects/README.md) | Provides a generic way to spawn actors | | [Carla Manual Control](carla_manual_control/README.md) | A ROS-based visualization and control tool for an ego vehicle (similar to carla_manual_control.py provided by CARLA) | | [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API | | [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. | diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 21ff7278..35734a3b 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -36,8 +36,8 @@ - - + + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index e147cd24..f12ad255 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -36,8 +36,8 @@ - - + + diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 05de4da2..94e2453f 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -7,7 +7,7 @@ MIT catkin carla_ros_bridge - carla_spawn_actors + carla_spawn_objects carla_waypoint_publisher carla_ad_agent carla_manual_control diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index 4090adf7..cc469d5e 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -30,8 +30,8 @@ - - + + diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index ba5bd1cf..1a8c4a25 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -25,7 +25,7 @@ rosgraph_msgs cv_bridge carla_msgs - carla_spawn_actors + carla_spawn_objects carla_manual_control diff --git a/carla_ros_bridge/test/ros_bridge_client.test b/carla_ros_bridge/test/ros_bridge_client.test index 725b0218..abc0e5ce 100644 --- a/carla_ros_bridge/test/ros_bridge_client.test +++ b/carla_ros_bridge/test/ros_bridge_client.test @@ -4,7 +4,7 @@ - + @@ -12,8 +12,8 @@ - - + + diff --git a/carla_ros_bridge/test/test_actors.json b/carla_ros_bridge/test/test_objects.json similarity index 99% rename from carla_ros_bridge/test/test_actors.json rename to carla_ros_bridge/test/test_objects.json index f48b6c8f..cf461ce6 100644 --- a/carla_ros_bridge/test/test_actors.json +++ b/carla_ros_bridge/test/test_objects.json @@ -1,5 +1,5 @@ { - "actors": + "objects": [ { "type": "sensor.pseudo.traffic_lights", diff --git a/carla_spawn_actors/CMakeLists.txt b/carla_spawn_objects/CMakeLists.txt similarity index 75% rename from carla_spawn_actors/CMakeLists.txt rename to carla_spawn_objects/CMakeLists.txt index f6391a49..95b383a7 100644 --- a/carla_spawn_actors/CMakeLists.txt +++ b/carla_spawn_objects/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(carla_spawn_actors) +project(carla_spawn_objects) find_package(catkin REQUIRED COMPONENTS rospy roslaunch) @@ -11,9 +11,9 @@ endif() catkin_package(CATKIN_DEPENDS rospy) -catkin_install_python(PROGRAMS src/carla_spawn_actors/carla_spawn_actors.py +catkin_install_python(PROGRAMS src/carla_spawn_objects/carla_spawn_objects.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) -catkin_install_python(PROGRAMS src/carla_spawn_actors/set_initial_pose.py +catkin_install_python(PROGRAMS src/carla_spawn_objects/set_initial_pose.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ diff --git a/carla_spawn_actors/README.md b/carla_spawn_objects/README.md similarity index 86% rename from carla_spawn_actors/README.md rename to carla_spawn_objects/README.md index 7acdfd9b..00602cdd 100644 --- a/carla_spawn_actors/README.md +++ b/carla_spawn_objects/README.md @@ -1,6 +1,6 @@ -# ROS Carla Spawn Actors +# ROS Carla Spawn Objects -`carla_spawn_actors` can be used to spawn actors (vehicles, sensors, walkers) with attached sensors. +`carla_spawn_objects` can be used to spawn actors (vehicles, sensors, walkers) with attached sensors. Info: To be able to use `carla_manual_control` a camera with role-name 'view' and resolution of 800x600 is required. @@ -22,11 +22,11 @@ Selecting a Pose with '2D Pose Estimate' will delete the current ego_vehicle and ## Attach sensor to an existing vehicle -It possible to attach sensors to an existing vehicle. To do so, a `sensor.pseudo.actor_list` should also be spawned (define it in the config file) to give access to a list of active actors. The ROS parameter `spawn_sensors_only` should also be set to True. `carla_spawn_actors` will then check if an actor with same id and type as the one specified in its config file is already active, and if yes attach the sensors to this actor. +It possible to attach sensors to an existing vehicle. To do so, a `sensor.pseudo.actor_list` should also be spawned (define it in the config file) to give access to a list of active actors. The ROS parameter `spawn_sensors_only` should also be set to True. `carla_spawn_objects` will then check if an actor with same id and type as the one specified in its config file is already active, and if yes attach the sensors to this actor. ## Create your own sensor setup -Sensors, attached to vehicles or not, can be defined via a json file. `carla_spawn_actors` reads it from the file location defined via the private ros parameter `actors_definition_file`. +Sensors, attached to vehicles or not, can be defined via a json file. `carla_spawn_objects` reads it from the file location defined via the private ros parameter `objects_definition_file`. The format is defined like that: @@ -52,4 +52,4 @@ The format is defined like that: Define sensors with their attributes as described in the Carla Documentation about [Cameras and Sensors](https://github.com/carla-simulator/carla/blob/master/Docs/cameras_and_sensors.md). -An example is provided by [carla_example_ego_vehicle.launch](launch/carla_example_ego_vehicle.launch). It uses the sensors from [actors.json](config/actors.json) +An example is provided by [carla_example_ego_vehicle.launch](launch/carla_example_ego_vehicle.launch). It uses the sensors from [objects.json](config/objects.json) diff --git a/carla_spawn_actors/config/actors.json b/carla_spawn_objects/config/objects.json similarity index 99% rename from carla_spawn_actors/config/actors.json rename to carla_spawn_objects/config/objects.json index c6ea612a..717a7981 100644 --- a/carla_spawn_actors/config/actors.json +++ b/carla_spawn_objects/config/objects.json @@ -1,5 +1,5 @@ { - "actors": + "objects": [ { "type": "sensor.pseudo.traffic_lights", diff --git a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch b/carla_spawn_objects/launch/carla_example_ego_vehicle.launch similarity index 66% rename from carla_spawn_actors/launch/carla_example_ego_vehicle.launch rename to carla_spawn_objects/launch/carla_example_ego_vehicle.launch index 335791fc..3029d963 100644 --- a/carla_spawn_actors/launch/carla_example_ego_vehicle.launch +++ b/carla_spawn_objects/launch/carla_example_ego_vehicle.launch @@ -1,24 +1,24 @@ - + + as many spawn_point as vehicles defined in objects_definition_file--> - - + + - + diff --git a/carla_spawn_actors/launch/carla_spawn_actors.launch b/carla_spawn_objects/launch/carla_spawn_objects.launch similarity index 53% rename from carla_spawn_actors/launch/carla_spawn_actors.launch rename to carla_spawn_objects/launch/carla_spawn_objects.launch index 819753e8..d5df19a5 100644 --- a/carla_spawn_actors/launch/carla_spawn_actors.launch +++ b/carla_spawn_objects/launch/carla_spawn_objects.launch @@ -1,14 +1,14 @@ - + + as many spawn_point as vehicles defined in objects_definition_file--> - - + + diff --git a/carla_spawn_actors/launch/set_initial_pose.launch b/carla_spawn_objects/launch/set_initial_pose.launch similarity index 71% rename from carla_spawn_actors/launch/set_initial_pose.launch rename to carla_spawn_objects/launch/set_initial_pose.launch index aa55ac88..ba4647b6 100644 --- a/carla_spawn_actors/launch/set_initial_pose.launch +++ b/carla_spawn_objects/launch/set_initial_pose.launch @@ -4,7 +4,7 @@ - + diff --git a/carla_spawn_actors/package.xml b/carla_spawn_objects/package.xml similarity index 83% rename from carla_spawn_actors/package.xml rename to carla_spawn_objects/package.xml index b8e1eb6e..810b4fb1 100644 --- a/carla_spawn_actors/package.xml +++ b/carla_spawn_objects/package.xml @@ -1,8 +1,8 @@ - carla_spawn_actors + carla_spawn_objects 0.0.0 - The carla_spawn_actors package + The carla_spawn_objects package CARLA Simulator Team MIT catkin diff --git a/carla_spawn_actors/setup.py b/carla_spawn_objects/setup.py similarity index 72% rename from carla_spawn_actors/setup.py rename to carla_spawn_objects/setup.py index b7aed7c2..62d5f1f5 100644 --- a/carla_spawn_actors/setup.py +++ b/carla_spawn_objects/setup.py @@ -1,12 +1,12 @@ """ -Setup for carla_spawn_actors +Setup for carla_spawn_objects """ from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup d = generate_distutils_setup( - packages=['carla_spawn_actors'], + packages=['carla_spawn_objects'], package_dir={'': 'src'} ) diff --git a/carla_spawn_actors/src/carla_spawn_actors/__init__.py b/carla_spawn_objects/src/carla_spawn_objects/__init__.py similarity index 100% rename from carla_spawn_actors/src/carla_spawn_actors/__init__.py rename to carla_spawn_objects/src/carla_spawn_objects/__init__.py diff --git a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py similarity index 92% rename from carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py rename to carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 4e7c5fc0..d6e36168 100755 --- a/carla_spawn_actors/src/carla_spawn_actors/carla_spawn_actors.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -5,9 +5,9 @@ # This work is licensed under the terms of the MIT license. # For a copy, see . """ -base class for spawning actors in ROS +base class for spawning objects (carla actors and pseudo_actors) in ROS -Gets config file from ros parameter ~actors_definition_file and spawns corresponding actors +Gets config file from ros parameter ~objects_definition_file and spawns corresponding objects through ROS service /carla/spawn_object. Looks for an initial spawn point first in the launchfile, then in the config file, and @@ -31,11 +31,11 @@ from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest # ============================================================================== -# -- CarlaSpawnActors ------------------------------------------------------------ +# -- CarlaSpawnObjects ------------------------------------------------------------ # ============================================================================== -class CarlaSpawnActors(object): +class CarlaSpawnObjects(object): """ Handles the spawning of the ego vehicle and its sensors @@ -44,8 +44,8 @@ class CarlaSpawnActors(object): """ def __init__(self): - rospy.init_node('spawn_actors_node', anonymous=True) - self.actors_definition_file = rospy.get_param('~actors_definition_file') + rospy.init_node('spawn_objects_node', anonymous=True) + self.objects_definition_file = rospy.get_param('~objects_definition_file') self.spawn_sensors_only = rospy.get_param('~spawn_sensors_only', None) self.players = [] @@ -56,27 +56,27 @@ def __init__(self): self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) - def spawn_actors(self): + def spawn_objects(self): """ - Spawns the actors + Spawns the objects - Either at a given actor_spawnpoint or at a random Carla spawnpoint + Either at a given spawnpoint or at a random Carla spawnpoint :return: """ # Read sensors from file - if not os.path.exists(self.actors_definition_file): + if not os.path.exists(self.objects_definition_file): raise RuntimeError( - "Could not read sensor-definition from {}".format(self.actors_definition_file)) + "Could not read sensor-definition from {}".format(self.objects_definition_file)) json_sensors = None - with open(self.actors_definition_file) as handle: + with open(self.objects_definition_file) as handle: json_actors = json.loads(handle.read()) global_sensors = [] vehicles = [] found_sensor_actor_list = False - for actor in json_actors["actors"]: + for actor in json_actors["objects"]: actor_type = actor["type"].split('.')[0] if actor["type"] == "sensor.pseudo.actor_list" and self.spawn_sensors_only: global_sensors.append(actor) @@ -87,7 +87,7 @@ def spawn_actors(self): vehicles.append(actor) else: rospy.logwarn( - "Actor with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"])) + "Object with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"])) if self.spawn_sensors_only is True and found_sensor_actor_list is False: raise Exception("Parameter 'spawn_sensors_only' enabled, " + "but 'sensor.pseudo.actor_list' is not instantiated, add it to your config file.") @@ -194,7 +194,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): (or not if global sensor) :param sensors: list of sensors :param attached_vehicle_id: id of vehicle to attach the sensors to - :return actors: list of ids of actors created + :return actors: list of ids of objects created """ actors = [] sensor_names = [] @@ -335,9 +335,9 @@ def run(self): rospy.logerr("Timeout while waiting for world info!") sys.exit(1) - rospy.loginfo("World info is available. Spawning acotrs...") + rospy.loginfo("World info is available. Spawning objects...") rospy.on_shutdown(self.destroy) - self.spawn_actors() + self.spawn_objects() try: rospy.spin() except rospy.ROSInterruptException: @@ -352,16 +352,16 @@ def main(): """ main function """ - spawn_actors_node = None + spawn_objects_node = None try: - spawn_actors_node = CarlaSpawnActors() - spawn_actors_node.run() + spawn_objects_node = CarlaSpawnObjects() + spawn_objects_node.run() except Exception as e: rospy.logfatal( "Exception caught: {}".format(e)) finally: - if spawn_actors_node is not None: - spawn_actors_node.destroy() + if spawn_objects_node is not None: + spawn_objects_node.destroy() if __name__ == '__main__': diff --git a/carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py similarity index 100% rename from carla_spawn_actors/src/carla_spawn_actors/set_initial_pose.py rename to carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py diff --git a/docker/Dockerfile b/docker/Dockerfile index 36354761..4c13d726 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -31,7 +31,7 @@ ENV PYTHONPATH=/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py$PYTHON_VE COPY carla_ackermann_control /opt/carla-ros-bridge/src/carla_ackermann_control COPY carla_common /opt/carla-ros-bridge/src/carla_common -COPY carla_spawn_actors /opt/carla-ros-bridge/src/carla_spawn_actors +COPY carla_spawn_objects /opt/carla-ros-bridge/src/carla_spawn_objects COPY carla_manual_control /opt/carla-ros-bridge/src/carla_manual_control COPY carla_msgs /opt/carla-ros-bridge/src/carla_msgs COPY carla_ros_bridge /opt/carla-ros-bridge/src/carla_ros_bridge From 3364c95a163311bf2194fc0ad4568b3eb0222b65 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Thu, 10 Dec 2020 16:11:48 +0100 Subject: [PATCH 425/627] Sensor TFs with respect to vehicle in sync mode (#430) * using relative tfs for sensors in sync mode * merged leaderboard branch * using relative spawn pose only in sensors * uncomment tf publication --- .../src/carla_ros_bridge/actor.py | 5 +- .../src/carla_ros_bridge/actor_control.py | 2 - .../src/carla_ros_bridge/actor_factory.py | 80 +++++++++++++------ .../src/carla_ros_bridge/bridge.py | 20 +---- .../src/carla_ros_bridge/camera.py | 27 +++++-- .../src/carla_ros_bridge/collision_sensor.py | 5 +- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 5 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 5 +- .../carla_ros_bridge/lane_invasion_sensor.py | 5 +- .../src/carla_ros_bridge/lidar.py | 10 ++- .../src/carla_ros_bridge/object_sensor.py | 2 - .../src/carla_ros_bridge/opendrive_sensor.py | 2 - .../src/carla_ros_bridge/radar.py | 5 +- .../src/carla_ros_bridge/rss_sensor.py | 5 +- .../src/carla_ros_bridge/sensor.py | 50 +++++++++--- .../carla_ros_bridge/speedometer_sensor.py | 2 - .../src/carla_ros_bridge/tf_sensor.py | 2 - .../src/carla_ros_bridge/world_info.py | 1 - 18 files changed, 155 insertions(+), 78 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index c660db77..fb696554 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -38,7 +38,10 @@ def __init__(self, uid, name, parent, node, carla_actor): :param carla_actor: carla actor object :type carla_actor: carla.Actor """ - super(Actor, self).__init__(uid=uid, name=name, parent=parent, node=node) + super(Actor, self).__init__(uid=uid, + name=name, + parent=parent, + node=node) self.carla_actor = carla_actor self.carla_actor_id = carla_actor.id diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index e8ae9edd..dc69b3e0 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -30,8 +30,6 @@ def __init__(self, uid, name, parent, node): :type uid: int :param name: name identifying this object :type name: string - :param carla_world: carla world object - :type carla_world: carla.World :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 05a0128c..a05df023 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -119,9 +119,9 @@ def _create_carla_actor(self, carla_actor): name = carla_actor.attributes.get("role_name", "") if not name: name = str(carla_actor.id) - return self.create(carla_actor.type_id, name, parent_id, carla_actor) + return self.create(carla_actor.type_id, name, parent_id, None, carla_actor) - def create(self, type_id, name, attach_to, carla_actor=None): + def create(self, type_id, name, attach_to, spawn_pose, carla_actor=None): with self.lock: # check that the actor is not already created. if carla_actor is not None and carla_actor.id in self.actors: @@ -139,7 +139,7 @@ def create(self, type_id, name, attach_to, carla_actor=None): else: uid = next(self.id_gen) - actor = self._create_object(uid, type_id, name, parent, carla_actor) + actor = self._create_object(uid, type_id, name, parent, spawn_pose, carla_actor) self.actors[actor.uid] = actor rospy.loginfo("Created {}(id={})".format(actor.__class__.__name__, actor.uid)) @@ -169,16 +169,22 @@ def get_pseudo_sensor_types(self): pseudo_sensors.append(cls.get_blueprint_name()) return pseudo_sensors - def _create_object(self, uid, type_id, name, parent, carla_actor=None): + def _create_object(self, uid, type_id, name, parent, spawn_pose, carla_actor=None): if type_id == TFSensor.get_blueprint_name(): actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) elif type_id == OdometrySensor.get_blueprint_name(): - actor = OdometrySensor(uid=uid, name=name, parent=parent, node=self.node) + actor = OdometrySensor(uid=uid, + name=name, + parent=parent, + node=self.node) elif type_id == SpeedometerSensor.get_blueprint_name(): - actor = SpeedometerSensor(uid=uid, name=name, parent=parent, node=self.node) + actor = SpeedometerSensor(uid=uid, + name=name, + parent=parent, + node=self.node) elif type_id == MarkerSensor.get_blueprint_name(): actor = MarkerSensor(uid=uid, @@ -220,7 +226,10 @@ def _create_object(self, uid, type_id, name, parent, carla_actor=None): carla_map=self.world.get_map()) elif type_id == ActorControl.get_blueprint_name(): - actor = ActorControl(uid=uid, name=name, parent=parent, node=self.node) + actor = ActorControl(uid=uid, + name=name, + parent=parent, + node=self.node) elif carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": @@ -230,43 +239,62 @@ def _create_object(self, uid, type_id, name, parent, carla_actor=None): elif carla_actor.type_id.startswith("vehicle"): if carla_actor.attributes.get('role_name')\ in self.node.parameters['ego_vehicle']['role_name']: - actor = EgoVehicle(uid, name, parent, self.node, carla_actor, - self.node._ego_vehicle_control_applied_callback) + actor = EgoVehicle( + uid, name, parent, self.node, carla_actor, + self.node._ego_vehicle_control_applied_callback) else: actor = Vehicle(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("sensor"): if carla_actor.type_id.startswith("sensor.camera"): if carla_actor.type_id.startswith("sensor.camera.rgb"): - actor = RgbCamera(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = RgbCamera(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.depth"): - actor = DepthCamera(uid, name, parent, self.node, carla_actor, self.sync_mode) - elif carla_actor.type_id.startswith("sensor.camera.semantic_segmentation"): - actor = SemanticSegmentationCamera(uid, name, parent, self.node, carla_actor, + actor = DepthCamera(uid, name, parent, spawn_pose, + self.node, carla_actor, self.sync_mode) + elif carla_actor.type_id.startswith( + "sensor.camera.semantic_segmentation"): + actor = SemanticSegmentationCamera(uid, name, parent, + spawn_pose, self.node, + carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.dvs"): - actor = DVSCamera(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = DVSCamera(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) else: - actor = Camera(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = Camera(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.lidar"): if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): - actor = Lidar(uid, name, parent, self.node, carla_actor, self.sync_mode) - elif carla_actor.type_id.endswith("sensor.lidar.ray_cast_semantic"): - actor = SemanticLidar(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = Lidar(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) + elif carla_actor.type_id.endswith( + "sensor.lidar.ray_cast_semantic"): + actor = SemanticLidar(uid, name, parent, spawn_pose, + self.node, carla_actor, + self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): - actor = Radar(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = Radar(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): - actor = Gnss(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = Gnss(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): - actor = ImuSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = ImuSensor(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): - actor = CollisionSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = CollisionSensor(uid, name, parent, spawn_pose, + self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.rss"): - actor = RssSensor(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = RssSensor(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): - actor = LaneInvasionSensor(uid, name, parent, self.node, - carla_actor, self.sync_mode) + actor = LaneInvasionSensor(uid, name, parent, spawn_pose, + self.node, carla_actor, + self.sync_mode) else: - actor = Sensor(uid, name, parent, self.node, carla_actor, self.sync_mode) + actor = Sensor(uid, name, parent, spawn_pose, self.node, + carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("spectator"): actor = Spectator(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("walker"): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 0bcf3955..544ab26d 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -24,7 +24,6 @@ import random from rosgraph_msgs.msg import Clock -from tf2_msgs.msg import TFMessage import carla @@ -97,7 +96,6 @@ def __init__(self, carla_world, params): # Communication topics self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10) - self.tf_publisher = rospy.Publisher('tf', TFMessage, queue_size=100) self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode, @@ -165,11 +163,11 @@ def _spawn_actor(self, req): raise IndexError("Parent actor {} not found".format(req.attach_to)) carla_actor = self.carla_world.spawn_actor(blueprint, transform, attach_to) - actor = self.actor_factory.create(req.type, req.id, req.attach_to, carla_actor) + actor = self.actor_factory.create(req.type, req.id, req.attach_to, req.transform, carla_actor) return actor.uid def _spawn_pseudo_actor(self, req): - actor = self.actor_factory.create(req.type, req.id, req.attach_to) + actor = self.actor_factory.create(req.type, req.id, req.attach_to, req.transform) return actor.uid def spawn_object(self, req): @@ -392,20 +390,6 @@ def update_clock(self, carla_timestamp): carla_timestamp.elapsed_seconds) self.clock_publisher.publish(Clock(self.ros_timestamp)) - def publish_tf_message(self, msg): - """ - Function to publish ROS TF message. - """ - # prepare tf message - tf_msg = None - tf_to_publish = [] - tf_to_publish.append(msg) - tf_msg = TFMessage(tf_to_publish) - try: - self.tf_publisher.publish(tf_msg) - except Exception as error: # pylint: disable=broad-except - self.logwarn("Failed to publish message: {}".format(error)) - def destroy(self): """ Function to destroy this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index f0e675ce..9affa6e0 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -34,7 +34,7 @@ class Camera(Sensor): # global cv bridge to convert image between opencv and ros cv_bridge = CvBridge() - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): # pylint: disable=too-many-arguments + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): # pylint: disable=too-many-arguments """ Constructor @@ -44,6 +44,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): # p :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -54,6 +56,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): # p super(Camera, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) @@ -171,7 +174,7 @@ class RgbCamera(Camera): Camera implementation details for rgb camera """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -181,6 +184,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -191,6 +196,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(RgbCamera, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) @@ -223,7 +229,7 @@ class DepthCamera(Camera): Camera implementation details for depth camera """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -233,6 +239,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -243,6 +251,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(DepthCamera, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) @@ -297,7 +306,7 @@ class SemanticSegmentationCamera(Camera): Camera implementation details for segmentation camera """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -307,6 +316,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -318,6 +329,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): SemanticSegmentationCamera, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, synchronous_mode=synchronous_mode, carla_actor=carla_actor) @@ -351,14 +363,18 @@ class DVSCamera(Camera): Sensor implementation details for dvs cameras """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): # pylint: disable=too-many-arguments + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): # pylint: disable=too-many-arguments """ Constructor :param uid: unique identifier for this object :type uid: int + :param name: name identiying this object + :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -369,6 +385,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): # p super(DVSCamera, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index b590cb12..22da7ea8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -22,7 +22,7 @@ class CollisionSensor(Sensor): Actor implementation details for a collision sensor """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -32,6 +32,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -42,6 +44,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(CollisionSensor, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index 163d2cbf..ac5bf738 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -23,7 +23,7 @@ class Gnss(Sensor): Actor implementation details for gnss sensor """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -33,6 +33,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -43,6 +45,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(Gnss, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index b34fdd4a..7421ff35 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -21,7 +21,7 @@ class ImuSensor(Sensor): Actor implementation details for imu sensor """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -31,6 +31,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor : carla actor object @@ -41,6 +43,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(ImuSensor, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 668e85a3..8b8c1d90 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -22,7 +22,7 @@ class LaneInvasionSensor(Sensor): Actor implementation details for a lane invasion sensor """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -32,6 +32,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -42,6 +44,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(LaneInvasionSensor, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode, diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 91aba283..dd54176c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -26,7 +26,7 @@ class Lidar(Sensor): Actor implementation details for lidars """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -36,6 +36,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -46,6 +48,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(Lidar, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) @@ -88,7 +91,7 @@ class SemanticLidar(Sensor): Actor implementation details for semantic lidars """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -98,6 +101,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -108,6 +113,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(SemanticLidar, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 60d0a98d..c04c77a0 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -31,8 +31,6 @@ def __init__(self, uid, name, parent, node, actor_list): :type uid: int :param name: name identiying this object :type name: string - :param carla_world: carla world object - :type carla_world: carla.World :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 7b3b1f2e..8ad5e1b8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -31,8 +31,6 @@ def __init__(self, uid, name, parent, node, carla_map): :type uid: int :param name: name identiying this object :type name: string - :param carla_world: carla world object - :type carla_world: carla.World :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 622498e8..afe48253 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -27,7 +27,7 @@ class Radar(Sensor): Actor implementation details of Carla RADAR """ - def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): """ Constructor @@ -37,6 +37,8 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -47,6 +49,7 @@ def __init__(self, uid, name, parent, node, carla_actor, synchronous_mode): super(Radar, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, synchronous_mode=synchronous_mode) diff --git a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py index 1376dd4d..c545f7ad 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/rss_sensor.py @@ -22,7 +22,7 @@ class RssSensor(Actor): utilization it's not handled as a sensor here. """ - def __init__(self, uid, name, parent, node, carla_actor, _): + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, _): """ Constructor @@ -32,6 +32,8 @@ def __init__(self, uid, name, parent, node, carla_actor, _): :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -41,5 +43,6 @@ def __init__(self, uid, name, parent, node, carla_actor, _): super(RssSensor, self).__init__(uid=uid, name=name, parent=parent, + relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 6cdc8fbc..5acaf075 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -16,6 +16,8 @@ import rospy +import tf2_ros +from geometry_msgs.msg import TransformStamped from carla_ros_bridge.actor import Actor import carla_common.transforms as trans @@ -31,6 +33,7 @@ def __init__(self, # pylint: disable=too-many-arguments uid, name, parent, + relative_spawn_pose, node, carla_actor, synchronous_mode, @@ -48,6 +51,8 @@ def __init__(self, # pylint: disable=too-many-arguments :type name: string :param parent: the parent of this :type parent: carla_ros_bridge.Parent + :param relative_spawn_pose: the relative spawn pose of this + :type relative_spawn_pose: geometry_msgs.Pose :param node: node-handle :type node: carla_ros_bridge.CarlaRosBridge :param carla_actor: carla actor object @@ -63,6 +68,7 @@ def __init__(self, # pylint: disable=too-many-arguments node=node, carla_actor=carla_actor) + self.relative_spawn_pose = relative_spawn_pose self.synchronous_mode = synchronous_mode self.queue = queue.Queue() self.next_data_expected_time = None @@ -74,6 +80,38 @@ def __init__(self, # pylint: disable=too-many-arguments except (KeyError, ValueError): self.sensor_tick_time = None + self._tf_broadcaster = tf2_ros.TransformBroadcaster() + + def publish_tf(self, pose=None): + if self.synchronous_mode: + pose = self.relative_spawn_pose + child_frame_id = self.get_prefix() + if self.parent is not None: + frame_id = self.parent.get_prefix() + else: + frame_id = "map" + + else: + child_frame_id = self.get_prefix() + frame_id = "map" + + if pose is not None: + transform = TransformStamped() + transform.header.stamp = rospy.Time.now() + transform.header.frame_id = frame_id + transform.child_frame_id = child_frame_id + + transform.transform.translation.x = pose.position.x + transform.transform.translation.y = pose.position.y + transform.transform.translation.z = pose.position.z + + transform.transform.rotation.x = pose.orientation.x + transform.transform.rotation.y = pose.orientation.y + transform.transform.rotation.z = pose.orientation.z + transform.transform.rotation.w = pose.orientation.w + + self._tf_broadcaster.sendTransform(transform) + def listen(self): self.carla_actor.listen(self._callback_sensor_data) @@ -105,8 +143,7 @@ def _callback_sensor_data(self, carla_sensor_data): float(self.sensor_tick_time) self.queue.put(carla_sensor_data) else: - self.publish_transform(self.get_ros_transform( - trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) + self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform)) self.sensor_data_updated(carla_sensor_data) @abstractmethod @@ -134,9 +171,7 @@ def _update_synchronous_event_sensor(self, frame): frame)) rospy.logdebug("{}({}): process {}".format( self.__class__.__name__, self.get_id(), frame)) - self.publish_transform( - self.get_ros_transform( - trans.carla_transform_to_ros_transform(carla_sensor_data.transform))) + self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform)) self.sensor_data_updated(carla_sensor_data) except queue.Empty: return @@ -152,10 +187,7 @@ def _update_synchronous_sensor(self, frame, timestamp): if carla_sensor_data.frame == frame: rospy.logdebug("{}({}): process {}".format( self.__class__.__name__, self.get_id(), frame)) - self.publish_transform( - self.get_ros_transform( - trans.carla_transform_to_ros_transform( - carla_sensor_data.transform))) + self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform)) self.sensor_data_updated(carla_sensor_data) return elif carla_sensor_data.frame < frame: diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 68282efe..3bf3a3c4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -31,8 +31,6 @@ def __init__(self, uid, name, parent, node): :type uid: int :param name: name identiying the sensor :type name: string - :param carla_world: carla world object - :type carla_world: carla.World :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 3af7183f..6bb94463 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -30,8 +30,6 @@ def __init__(self, uid, name, parent, node): :type uid: int :param name: name identiying the sensor :type name: string - :param carla_world: carla world object - :type carla_world: carla.World :param parent: the parent of this :type parent: carla_ros_bridge.Parent :param node: node-handle diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index d63db978..82cf4d1f 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -49,7 +49,6 @@ def destroy(self): """ rospy.logdebug("Destroying WorldInfo()") self.carla_map = None - super(WorldInfo, self).destroy() def update(self, frame, timestamp): """ From 0c1d8aaebceeb86dced23ccae18873128365c50e Mon Sep 17 00:00:00 2001 From: joel-mb Date: Thu, 10 Dec 2020 18:07:38 +0100 Subject: [PATCH 426/627] Added passive parameter (#434) * added configure_world parameter * Merge branch 'leaderboard' into joel-mb/ticking * added passive parameter * added warning passive mode and sync mode --- carla_ad_demo/launch/carla_ad_demo.launch | 2 + .../launch/carla_ad_demo_with_scenario.launch | 2 + carla_ros_bridge/config/settings.yaml | 2 + .../launch/carla_ros_bridge.launch | 2 + ...ros_bridge_with_example_ego_vehicle.launch | 4 ++ .../src/carla_ros_bridge/bridge.py | 38 +++++++++++-------- .../carla_status_publisher.py | 2 + 7 files changed, 36 insertions(+), 16 deletions(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 35734a3b..258bec8b 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -7,6 +7,7 @@ + @@ -30,6 +31,7 @@ + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index f12ad255..873aea77 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -5,6 +5,7 @@ + @@ -30,6 +31,7 @@ + diff --git a/carla_ros_bridge/config/settings.yaml b/carla_ros_bridge/config/settings.yaml index 991fd791..fb19a8b4 100644 --- a/carla_ros_bridge/config/settings.yaml +++ b/carla_ros_bridge/config/settings.yaml @@ -4,6 +4,8 @@ carla: host: localhost port: 2000 timeout: 10 + # enable/disable passive mode. + passive: False # enable/disable synchronous mode. If enabled ros-bridge waits until # expected data is received for all sensors synchronous_mode: false diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index b7a5707a..2b114713 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -4,6 +4,7 @@ + @@ -13,6 +14,7 @@ + + + + @@ -24,6 +27,7 @@ + diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 544ab26d..7eac8b96 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -68,26 +68,32 @@ def __init__(self, carla_world, params): self.synchronous_mode_update_thread = None self.shutdown = Event() - # set carla world settings self.carla_settings = carla_world.get_settings() - - # workaround: settings can only applied within non-sync mode - if self.carla_settings.synchronous_mode: - self.carla_settings.synchronous_mode = False + if not self.parameters["passive"]: + # workaround: settings can only applied within non-sync mode + if self.carla_settings.synchronous_mode: + self.carla_settings.synchronous_mode = False + carla_world.apply_settings(self.carla_settings) + + rospy.loginfo("synchronous_mode: {}".format( + self.parameters["synchronous_mode"])) + self.carla_settings.synchronous_mode = self.parameters["synchronous_mode"] + rospy.loginfo("fixed_delta_seconds: {}".format( + self.parameters["fixed_delta_seconds"])) + self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) - rospy.loginfo("synchronous_mode: {}".format( - self.parameters["synchronous_mode"])) - self.carla_settings.synchronous_mode = self.parameters["synchronous_mode"] - rospy.loginfo("fixed_delta_seconds: {}".format( - self.parameters["fixed_delta_seconds"])) - self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] - carla_world.apply_settings(self.carla_settings) + # active sync mode in the ros bridge only if CARLA world is configured in sync mode and + # passive mode is not enabled. + self.sync_mode = self.carla_settings.synchronous_mode and not self.parameters["passive"] + if self.carla_settings.synchronous_mode and self.parameters["passive"] + rospy.loginfo( + "Passive mode is enabled and CARLA world is configured in synchronous mode. This configuration requires another client ticking the CARLA world.") self.carla_control_queue = queue.Queue() # actor factory - self.actor_factory = ActorFactory(self, carla_world, self.carla_settings.synchronous_mode) + self.actor_factory = ActorFactory(self, carla_world, self.sync_mode) # add world info self.world_info = WorldInfo(carla_world=self.carla_world) @@ -117,7 +123,7 @@ def __init__(self, carla_world, params): self._expected_ego_vehicle_control_command_ids = [] self._expected_ego_vehicle_control_command_ids_lock = Lock() - if self.carla_settings.synchronous_mode: + if self.sync_mode: self.carla_run_state = CarlaControl.PLAY self.carla_control_subscriber = \ @@ -365,7 +371,7 @@ def _update(self, frame_id, timestamp): continue def _ego_vehicle_control_applied_callback(self, ego_vehicle_id): - if not self.carla_settings.synchronous_mode or \ + if not self.sync_mode or \ not self.parameters['synchronous_mode_wait_for_vehicle_control_command']: return with self._expected_ego_vehicle_control_command_ids_lock: @@ -401,7 +407,7 @@ def destroy(self): self.shutdown.set() self.carla_weather_subscriber.unregister() self.carla_control_queue.put(CarlaControl.STEP_ONCE) - if not self.carla_settings.synchronous_mode: + if not self.sync_mode: if self.on_tick_id: self.carla_world.remove_on_tick(self.on_tick_id) self.actor_factory.thread.join() diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 0f296750..2fc77f6d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -29,6 +29,8 @@ def __init__(self, synchronous_mode, fixed_delta_seconds): self.synchronous_mode = synchronous_mode self.synchronous_mode_running = True self.fixed_delta_seconds = fixed_delta_seconds + if self.fixed_delta_seconds is None: + self.fixed_delta_seconds = 0 self.frame = 0 self.carla_status_publisher = rospy.Publisher( "/carla/status", CarlaStatus, queue_size=10, latch=True) From 1b0114221a13203ad4a0fc18d053f013e089537d Mon Sep 17 00:00:00 2001 From: joel-mb Date: Mon, 14 Dec 2020 11:18:27 +0100 Subject: [PATCH 427/627] Using services to spawn spectator camera (#435) * using services to spawn spectator camera --- .../src/carla_ros_bridge/bridge.py | 2 +- .../carla_spectator_camera.py | 59 ++++++++++++------- 2 files changed, 39 insertions(+), 22 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 7eac8b96..1307b6b0 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -86,7 +86,7 @@ def __init__(self, carla_world, params): # active sync mode in the ros bridge only if CARLA world is configured in sync mode and # passive mode is not enabled. self.sync_mode = self.carla_settings.synchronous_mode and not self.parameters["passive"] - if self.carla_settings.synchronous_mode and self.parameters["passive"] + if self.carla_settings.synchronous_mode and self.parameters["passive"]: rospy.loginfo( "Passive mode is enabled and CARLA world is configured in synchronous mode. This configuration requires another client ticking the CARLA world.") diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index b9f3e332..599c391a 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -11,15 +11,20 @@ to /carla//spectator_position. """ -import sys import math +import sys + +import carla import rospy + from tf.transformations import euler_from_quaternion -import tf -from geometry_msgs.msg import PoseStamped + from carla_msgs.msg import CarlaWorldInfo +from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest +from diagnostic_msgs.msg import KeyValue +from geometry_msgs.msg import PoseStamped -import carla +import carla_common.transforms as trans # ============================================================================== # -- CarlaSpectatorCamera ------------------------------------------------------------ @@ -39,7 +44,6 @@ def __init__(self): Constructor """ rospy.init_node('spectator_camera', anonymous=True) - self.listener = tf.TransformListener() self.role_name = rospy.get_param("/role_name", "ego_vehicle") self.camera_resolution_x = rospy.get_param("~resolution_x", 800) self.camera_resolution_y = rospy.get_param("~resolution_y", 600) @@ -51,6 +55,11 @@ def __init__(self): self.pose = None self.camera_actor = None self.ego_vehicle = None + + rospy.wait_for_service('/carla/spawn_object') + self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) + self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) + rospy.Subscriber("/carla/{}/spectator_pose".format(self.role_name), PoseStamped, self.pose_received) @@ -96,24 +105,27 @@ def create_camera(self, ego_actor): """ Attach the camera to the ego vehicle """ - bp_library = self.world.get_blueprint_library() - try: - bp = bp_library.find("sensor.camera.rgb") - bp.set_attribute('role_name', "spectator_view") - rospy.loginfo("Creating camera with resolution {}x{}, fov {}".format( - self.camera_resolution_x, - self.camera_resolution_y, - self.camera_fov)) - bp.set_attribute('image_size_x', str(self.camera_resolution_x)) - bp.set_attribute('image_size_y', str(self.camera_resolution_y)) - bp.set_attribute('fov', str(self.camera_fov)) - except KeyError as e: - rospy.logfatal("Camera could not be spawned: '{}'".format(e)) transform = self.get_camera_transform() if not transform: transform = carla.Transform() - self.camera_actor = self.world.spawn_actor(bp, transform, - attach_to=ego_actor) + + spawn_object_request = SpawnObjectRequest() + spawn_object_request.type = "sensor.camera.rgb" + spawn_object_request.id = "spectator_view" + spawn_object_request.attach_to = ego_actor.id + spawn_object_request.transform = trans.carla_transform_to_ros_pose(transform) + spawn_object_request.random_pose = False + spawn_object_request.attributes.extend([ + KeyValue("image_size_x", str(self.camera_resolution_x)), + KeyValue("image_size_y", str(self.camera_resolution_y)), + KeyValue("fov", str(self.camera_fov)) + ]) + + response = self.spawn_object_service(spawn_object_request) + if response.id == -1: + raise Exception(response.error_string) + + self.camera_actor = self.world.get_actor(response.id) def find_ego_vehicle_actor(self): """ @@ -147,7 +159,12 @@ def destroy(self): destroy the camera """ if self.camera_actor: - self.camera_actor.destroy() + destroy_object_request = DestroyObjectRequest(self.camera_actor.id) + try: + self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) + self.camera_actor = None def run(self): From ce5556d36207b0a87cb43ceec56edceef2b37435 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 15 Dec 2020 13:47:28 +0100 Subject: [PATCH 428/627] Removed waiting for world info topic (#437) * removed waiting for world info topic --- .../src/carla_ros_bridge/actor_factory.py | 2 +- .../src/carla_ros_bridge/bridge.py | 19 ++++++++++--------- .../carla_spawn_objects.py | 11 ++--------- .../carla_spectator_camera.py | 11 ++--------- 4 files changed, 15 insertions(+), 28 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index a05df023..59e1a2bb 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -78,8 +78,8 @@ def _update_thread(self): while not self.node.shutdown.is_set(): time.sleep(ActorFactory.TIME_BETWEEN_UPDATES) + self.world.wait_for_tick() with self.spawn_lock: - self.world.wait_for_tick() self.update() def update(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 1307b6b0..3bf13884 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -107,15 +107,6 @@ def __init__(self, carla_world, params): self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds) - self._registered_actors = [] - self.spawn_object_service = rospy.Service("/carla/spawn_object", SpawnObject, - self.spawn_object) - self.destroy_object_service = rospy.Service("/carla/destroy_object", DestroyObject, - self.destroy_object) - - self.get_blueprints_service = rospy.Service("/carla/get_blueprints", GetBlueprints, - self.get_blueprints) - # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. # Before tick(), the list is filled and the loop waits until the list is empty. @@ -141,6 +132,16 @@ def __init__(self, carla_world, params): # register callback to update actors self.on_tick_id = self.carla_world.on_tick(self._carla_time_tick) + # services configuration. + self._registered_actors = [] + self.spawn_object_service = rospy.Service("/carla/spawn_object", SpawnObject, + self.spawn_object) + self.destroy_object_service = rospy.Service("/carla/destroy_object", DestroyObject, + self.destroy_object) + + self.get_blueprints_service = rospy.Service("/carla/get_blueprints", GetBlueprints, + self.get_blueprints) + self.carla_weather_subscriber = \ rospy.Subscriber("/carla/weather_control", CarlaWeatherParameters, self.on_weather_changed) diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index d6e36168..ee0c34f7 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -53,6 +53,8 @@ def __init__(self): self.global_sensors = [] rospy.wait_for_service('/carla/spawn_object') + rospy.wait_for_service('/carla/destroy_object') + self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) @@ -327,15 +329,6 @@ def run(self): """ main loop """ - # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") - try: - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException: - rospy.logerr("Timeout while waiting for world info!") - sys.exit(1) - - rospy.loginfo("World info is available. Spawning objects...") rospy.on_shutdown(self.destroy) self.spawn_objects() try: diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 599c391a..8af5405e 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -57,6 +57,8 @@ def __init__(self): self.ego_vehicle = None rospy.wait_for_service('/carla/spawn_object') + rospy.wait_for_service('/carla/destroy_object') + self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) @@ -171,15 +173,6 @@ def run(self): """ main loop """ - # wait for ros-bridge to set up CARLA world - rospy.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") - try: - rospy.wait_for_message("/carla/world_info", CarlaWorldInfo, timeout=10.0) - except rospy.ROSException: - rospy.logerr("Error while waiting for world info!") - sys.exit(1) - rospy.loginfo("CARLA world available. Waiting for ego vehicle...") - client = carla.Client(self.host, self.port) client.set_timeout(self.timeout) self.world = client.get_world() From 151ad1293161864e72318679b527cd6c6af4baae Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 15 Dec 2020 15:23:43 +0100 Subject: [PATCH 429/627] Update changelog --- CHANGELOG.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 58a08ba5..f058e3d7 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,9 @@ ## Latest changed +* Support spawning of pseudo-actors through service +* Use new spawning service to combine carla_infrastructure and carla_ego_vehicle into carla_spawn_objects +* Reworked ROS topics +* rework tf in sync mode to represent attachment of sensors to a vehicle * Updated debian packaging pipeline ## CARLA-ROS-Bridge 0.9.10.1 From c9b82b47e783136e45d60aa0aab9f2e5b490751a Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 15 Dec 2020 15:36:00 +0100 Subject: [PATCH 430/627] cleanup --- CHANGELOG.md | 1 + carla_ros_bridge/src/carla_ros_bridge/bridge.py | 5 +++-- carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py | 1 - carla_ros_bridge/src/carla_ros_bridge/sensor.py | 3 ++- .../src/carla_spawn_objects/set_initial_pose.py | 2 +- .../src/carla_spectator_camera/carla_spectator_camera.py | 4 ++-- 6 files changed, 9 insertions(+), 7 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index f058e3d7..9e9ff0fa 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Added passive mode. Wordl configuration and ticking are performed by other clients. * Support spawning of pseudo-actors through service * Use new spawning service to combine carla_infrastructure and carla_ego_vehicle into carla_spawn_objects * Reworked ROS topics diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 3bf13884..ac49929c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -149,7 +149,7 @@ def __init__(self, carla_world, params): def _spawn_actor(self, req): if "*" in req.type: blueprint = secure_random.choice( - self.carla_world.get_blueprint_library().filter(req.type)) + self.carla_world.get_blueprint_library().filter(req.type)) else: blueprint = self.carla_world.get_blueprint_library().find(req.type) blueprint.set_attribute('role_name', req.id) @@ -170,7 +170,8 @@ def _spawn_actor(self, req): raise IndexError("Parent actor {} not found".format(req.attach_to)) carla_actor = self.carla_world.spawn_actor(blueprint, transform, attach_to) - actor = self.actor_factory.create(req.type, req.id, req.attach_to, req.transform, carla_actor) + actor = self.actor_factory.create( + req.type, req.id, req.attach_to, req.transform, carla_actor) return actor.uid def _spawn_pseudo_actor(self, req): diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 7886e210..c9722256 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -44,7 +44,6 @@ def __init__(self, uid, name, parent, node): if self.uid > np.iinfo(np.uint32).max: raise ValueError("Actor ID exceeds maximum supported value '{}'".format(self.uid)) - def destroy(self): """ Function to destroy this object. diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 5acaf075..65775475 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -187,7 +187,8 @@ def _update_synchronous_sensor(self, frame, timestamp): if carla_sensor_data.frame == frame: rospy.logdebug("{}({}): process {}".format( self.__class__.__name__, self.get_id(), frame)) - self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform)) + self.publish_tf(trans.carla_transform_to_ros_pose( + carla_sensor_data.transform)) self.sensor_data_updated(carla_sensor_data) return elif carla_sensor_data.frame < frame: diff --git a/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py index db878ab1..d2e46939 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py +++ b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py @@ -28,7 +28,7 @@ def __init__(self): rospy.init_node('set_initial_pose', anonymous=True) self.role_name = rospy.get_param('~role_name', 'ego_vehicle') - # control_id should correspond to the id of the actor.pseudo.control + # control_id should correspond to the id of the actor.pseudo.control # actor that is set in the config file used to spawn it self.control_id = rospy.get_param('~control_id', 'control') self.transform_publisher = rospy.Publisher( diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 8af5405e..a892afc8 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -112,7 +112,7 @@ def create_camera(self, ego_actor): transform = carla.Transform() spawn_object_request = SpawnObjectRequest() - spawn_object_request.type = "sensor.camera.rgb" + spawn_object_request.type = "sensor.camera.rgb" spawn_object_request.id = "spectator_view" spawn_object_request.attach_to = ego_actor.id spawn_object_request.transform = trans.carla_transform_to_ros_pose(transform) @@ -161,7 +161,7 @@ def destroy(self): destroy the camera """ if self.camera_actor: - destroy_object_request = DestroyObjectRequest(self.camera_actor.id) + destroy_object_request = DestroyObjectRequest(self.camera_actor.id) try: self.destroy_object_service(destroy_object_request) except rospy.ServiceException as e: From 427ad4f175365d98cb6438095089d37e4da9f05e Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 15 Dec 2020 15:58:21 +0100 Subject: [PATCH 431/627] Cleanup --- carla_ros_bridge/src/carla_ros_bridge/actor.py | 1 - carla_ros_bridge/src/carla_ros_bridge/actor_factory.py | 9 --------- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 4 ---- .../src/carla_ros_bridge/opendrive_sensor.py | 1 - .../src/carla_ros_bridge/traffic_participant.py | 2 -- .../src/carla_spawn_objects/carla_spawn_objects.py | 10 ++++------ .../src/carla_spawn_objects/set_initial_pose.py | 5 ++++- .../carla_spectator_camera/carla_spectator_camera.py | 2 -- .../carla_waypoint_publisher.py | 2 -- 9 files changed, 8 insertions(+), 28 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index fb696554..ae0321bc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -10,7 +10,6 @@ Base Classes to handle Actor objects """ -import numpy as np from geometry_msgs.msg import TransformStamped from carla_ros_bridge.pseudo_actor import PseudoActor diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 59e1a2bb..f4d556e3 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -8,19 +8,10 @@ import rospy -try: - import queue -except ImportError: - import Queue as queue - import time from threading import Thread, Lock import itertools -import carla - -import carla_common.transforms as trans - from carla_ros_bridge.actor import Actor from carla_ros_bridge.spectator import Spectator from carla_ros_bridge.traffic import Traffic, TrafficLight diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index d449afc3..8928db26 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -10,19 +10,15 @@ Classes to handle Carla vehicles """ import math -import numpy import rospy from std_msgs.msg import ColorRGBA from std_msgs.msg import Bool -from geometry_msgs.msg import Transform from carla import VehicleControl -from carla import Vector3D from carla_ros_bridge.vehicle import Vehicle -import carla_common.transforms as transforms from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel,\ CarlaEgoVehicleControl, CarlaEgoVehicleStatus diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 8ad5e1b8..5fb8e8c8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -10,7 +10,6 @@ """ import rospy -import numpy as np from carla_ros_bridge.pseudo_actor import PseudoActor diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 95b6dedf..f38d5d92 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -10,8 +10,6 @@ Classes to handle Carla traffic participants """ -import rospy - from derived_object_msgs.msg import Object from shape_msgs.msg import SolidPrimitive from std_msgs.msg import ColorRGBA diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index ee0c34f7..22f1908e 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -10,22 +10,19 @@ Gets config file from ros parameter ~objects_definition_file and spawns corresponding objects through ROS service /carla/spawn_object. -Looks for an initial spawn point first in the launchfile, then in the config file, and +Looks for an initial spawn point first in the launchfile, then in the config file, and finally ask for a random one to the spawn service. """ -from abc import abstractmethod - import os -import sys import math import json import rospy from tf.transformations import quaternion_from_euler from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import Pose -from carla_msgs.msg import CarlaWorldInfo, CarlaActorList +from carla_msgs.msg import CarlaActorList from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest @@ -70,7 +67,6 @@ def spawn_objects(self): if not os.path.exists(self.objects_definition_file): raise RuntimeError( "Could not read sensor-definition from {}".format(self.objects_definition_file)) - json_sensors = None with open(self.objects_definition_file) as handle: json_actors = json.loads(handle.read()) @@ -302,6 +298,8 @@ def destroy(self): destroy_object_request = DestroyObjectRequest(actor_id) try: response = self.destroy_object_service(destroy_object_request) + if response.id == -1: + rospy.logwarn(response.error_string) except rospy.ServiceException as e: rospy.logwarn_once(str(e)) self.global_sensors = [] diff --git a/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py index d2e46939..c7752f54 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py +++ b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py @@ -48,7 +48,10 @@ def main(): main function """ set_initial_pose_node = SetInitialPose() - rospy.spin() + try: + rospy.spin() + finally: + del set_initial_pose_node if __name__ == '__main__': diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index a892afc8..c4098dfc 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -12,14 +12,12 @@ """ import math -import sys import carla import rospy from tf.transformations import euler_from_quaternion -from carla_msgs.msg import CarlaWorldInfo from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import PoseStamped diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 9cfa4362..20a8d0a4 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -22,8 +22,6 @@ import threading import rospy -import tf -from tf.transformations import euler_from_quaternion from nav_msgs.msg import Path from geometry_msgs.msg import PoseStamped import carla_common.transforms as trans From 32e4e04b065bc87bdb0da90db45c2b2b554c0cac Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 15 Dec 2020 16:37:46 +0100 Subject: [PATCH 432/627] Revert "Cleanup" This reverts commit 427ad4f175365d98cb6438095089d37e4da9f05e. --- carla_ros_bridge/src/carla_ros_bridge/actor.py | 1 + carla_ros_bridge/src/carla_ros_bridge/actor_factory.py | 9 +++++++++ carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 4 ++++ .../src/carla_ros_bridge/opendrive_sensor.py | 1 + .../src/carla_ros_bridge/traffic_participant.py | 2 ++ .../src/carla_spawn_objects/carla_spawn_objects.py | 10 ++++++---- .../src/carla_spawn_objects/set_initial_pose.py | 5 +---- .../carla_spectator_camera/carla_spectator_camera.py | 2 ++ .../carla_waypoint_publisher.py | 2 ++ 9 files changed, 28 insertions(+), 8 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index ae0321bc..fb696554 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -10,6 +10,7 @@ Base Classes to handle Actor objects """ +import numpy as np from geometry_msgs.msg import TransformStamped from carla_ros_bridge.pseudo_actor import PseudoActor diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index f4d556e3..59e1a2bb 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -8,10 +8,19 @@ import rospy +try: + import queue +except ImportError: + import Queue as queue + import time from threading import Thread, Lock import itertools +import carla + +import carla_common.transforms as trans + from carla_ros_bridge.actor import Actor from carla_ros_bridge.spectator import Spectator from carla_ros_bridge.traffic import Traffic, TrafficLight diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 8928db26..d449afc3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -10,15 +10,19 @@ Classes to handle Carla vehicles """ import math +import numpy import rospy from std_msgs.msg import ColorRGBA from std_msgs.msg import Bool +from geometry_msgs.msg import Transform from carla import VehicleControl +from carla import Vector3D from carla_ros_bridge.vehicle import Vehicle +import carla_common.transforms as transforms from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel,\ CarlaEgoVehicleControl, CarlaEgoVehicleStatus diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 5fb8e8c8..8ad5e1b8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -10,6 +10,7 @@ """ import rospy +import numpy as np from carla_ros_bridge.pseudo_actor import PseudoActor diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index f38d5d92..95b6dedf 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -10,6 +10,8 @@ Classes to handle Carla traffic participants """ +import rospy + from derived_object_msgs.msg import Object from shape_msgs.msg import SolidPrimitive from std_msgs.msg import ColorRGBA diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 22f1908e..ee0c34f7 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -10,19 +10,22 @@ Gets config file from ros parameter ~objects_definition_file and spawns corresponding objects through ROS service /carla/spawn_object. -Looks for an initial spawn point first in the launchfile, then in the config file, and +Looks for an initial spawn point first in the launchfile, then in the config file, and finally ask for a random one to the spawn service. """ +from abc import abstractmethod + import os +import sys import math import json import rospy from tf.transformations import quaternion_from_euler from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import Pose -from carla_msgs.msg import CarlaActorList +from carla_msgs.msg import CarlaWorldInfo, CarlaActorList from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest @@ -67,6 +70,7 @@ def spawn_objects(self): if not os.path.exists(self.objects_definition_file): raise RuntimeError( "Could not read sensor-definition from {}".format(self.objects_definition_file)) + json_sensors = None with open(self.objects_definition_file) as handle: json_actors = json.loads(handle.read()) @@ -298,8 +302,6 @@ def destroy(self): destroy_object_request = DestroyObjectRequest(actor_id) try: response = self.destroy_object_service(destroy_object_request) - if response.id == -1: - rospy.logwarn(response.error_string) except rospy.ServiceException as e: rospy.logwarn_once(str(e)) self.global_sensors = [] diff --git a/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py index c7752f54..d2e46939 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py +++ b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py @@ -48,10 +48,7 @@ def main(): main function """ set_initial_pose_node = SetInitialPose() - try: - rospy.spin() - finally: - del set_initial_pose_node + rospy.spin() if __name__ == '__main__': diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index c4098dfc..a892afc8 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -12,12 +12,14 @@ """ import math +import sys import carla import rospy from tf.transformations import euler_from_quaternion +from carla_msgs.msg import CarlaWorldInfo from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import PoseStamped diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 20a8d0a4..9cfa4362 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -22,6 +22,8 @@ import threading import rospy +import tf +from tf.transformations import euler_from_quaternion from nav_msgs.msg import Path from geometry_msgs.msg import PoseStamped import carla_common.transforms as trans From 9f572968d81fb955d757948f46fb133fe05fb64b Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 16 Dec 2020 11:18:53 +0100 Subject: [PATCH 433/627] submodule updated --- carla_msgs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_msgs b/carla_msgs index 06bf63d0..4857d817 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 06bf63d0d959feed73c427857c030269f3d79620 +Subproject commit 4857d81705a87d88435ee69bb2252aa6e3b9e70e From 80d48cdf89c23f9c119808d25b59da4de095b3f4 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 16 Dec 2020 15:58:29 +0100 Subject: [PATCH 434/627] Continue porting after merge --- .../carla_ackermann_control_node.py | 7 +- .../src/carla_ad_agent/carla_ad_agent.py | 12 ++- carla_ad_demo/launch/carla_ad_demo.launch.py | 10 +-- .../carla_ad_demo_with_scenario.launch.py | 10 +-- carla_ad_demo/setup.py | 2 +- .../carla_manual_control.py | 13 +++- carla_msgs | 2 +- ..._bridge_with_example_ego_vehicle.launch.py | 7 +- .../src/carla_ros_bridge/actor_control.py | 13 ++-- .../src/carla_ros_bridge/actor_factory.py | 6 +- .../src/carla_ros_bridge/actor_list_sensor.py | 6 +- .../src/carla_ros_bridge/bridge.py | 65 ++++++---------- .../src/carla_ros_bridge/camera.py | 2 +- .../src/carla_ros_bridge/marker_sensor.py | 7 +- .../src/carla_ros_bridge/odom_sensor.py | 6 +- .../src/carla_ros_bridge/opendrive_sensor.py | 4 +- .../src/carla_ros_bridge/pseudo_actor.py | 2 +- .../carla_ros_bridge/speedometer_sensor.py | 7 +- .../src/carla_ros_bridge/tf_sensor.py | 13 +++- .../carla_ros_scenario_runner_node.py | 11 ++- .../ros_vehicle_control.py | 3 +- .../carla_spawn_objects.py | 78 ++++++++++--------- .../carla_spectator_camera.py | 8 +- .../carla_twist_to_control.py | 12 ++- .../carla_walker_agent/carla_walker_agent.py | 12 ++- .../carla_waypoint_publisher.py | 8 +- ros_compatibility/__init__.py | 1 - ros_compatibility/setup.py | 5 -- ros_compatibility/src/__init__.py | 0 .../src/ros_compatibility/__init__.py | 3 +- .../ros_compatibility/ros_compatible_node.py | 6 ++ 31 files changed, 168 insertions(+), 173 deletions(-) delete mode 100644 ros_compatibility/__init__.py delete mode 100644 ros_compatibility/src/__init__.py diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index 6a28b68f..680672c7 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -20,7 +20,7 @@ from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module,import-error from carla_ackermann_msgs.msg import EgoVehicleControlInfo # pylint: disable=no-name-in-module,import-error -from ros_compatibility import CompatibleNode, QoSProfile +from ros_compatibility import CompatibleNode, QoSProfile, ros_init from carla_ackermann_control import carla_control_physics as phys from simple_pid import PID # pylint: disable=import-error,wrong-import-order @@ -586,15 +586,14 @@ def loop(timer_event=None): self.spin() -def main(): +def main(args=None): """ main function :return: """ - if ROS_VERSION == 2: - rclpy.init() + ros_init(args) controller = CarlaAckermannControl() controller.run() diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index bd7be1c3..177a1e17 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -13,7 +13,14 @@ from nav_msgs.msg import Path # pylint: disable=import-error from std_msgs.msg import Float64 # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl # pylint: disable=import-error -from ros_compatibility import CompatibleNode, ROSInterruptException, ros_ok, QoSProfile, ROSException, latch_on +from ros_compatibility import ( + CompatibleNode, + ROSInterruptException, + ros_ok, + QoSProfile, + ROSException, + latch_on, + ros_init) import os ROS_VERSION = int(os.environ['ROS_VERSION']) @@ -163,8 +170,7 @@ def main(args=None): :return: """ - if ROS_VERSION == 2: - rclpy.init() + ros_init(args) controller = CarlaAdAgent() try: diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index f46b104c..e1e282b4 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -80,15 +80,11 @@ def generate_launch_description(): launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( - 'carla_ego_vehicle'), 'carla_example_ego_vehicle.launch.py') + 'carla_spawn_actors'), 'carla_example_ego_vehicle.launch.py') ), launch_arguments={ - 'host': launch.substitutions.LaunchConfiguration('host'), - 'port': launch.substitutions.LaunchConfiguration('port'), - 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'), - 'sensor_definition_file': get_package_share_directory('carla_ego_vehicle') + '/config/sensors.json', - 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'object_definition_file': get_package_share_directory('carla_spawn_actors') + '/config/sensors.json', + 'role_name_' + launch.substitutions.LaunchConfiguration('role_name'): launch.substitutions.LaunchConfiguration('role_name'), 'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point') }.items() ), diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index 4fca23d7..da2dd18d 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -109,15 +109,11 @@ def generate_launch_description(): launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( - 'carla_ego_vehicle'), 'carla_example_ego_vehicle.launch.py') + 'carla_spawn_actors'), 'carla_example_ego_vehicle.launch.py') ), launch_arguments={ - 'host': launch.substitutions.LaunchConfiguration('host'), - 'port': launch.substitutions.LaunchConfiguration('port'), - 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'vehicle_filter': launch.substitutions.LaunchConfiguration('vehicle_filter'), - 'sensor_definition_file': get_package_share_directory('carla_ego_vehicle') + '/config/sensors.json', - 'role_name': launch.substitutions.LaunchConfiguration('role_name') + 'object_definition_file': get_package_share_directory('carla_spawn_actors') + '/config/objects.json', + 'role_name_' + launch.substitutions.LaunchConfiguration('role_name'): launch.substitutions.LaunchConfiguration('role_name') }.items() ), launch.actions.IncludeLaunchDescription( diff --git a/carla_ad_demo/setup.py b/carla_ad_demo/setup.py index b2bdad70..cdf6f054 100644 --- a/carla_ad_demo/setup.py +++ b/carla_ad_demo/setup.py @@ -1,5 +1,5 @@ """ -Setup for carla_ego_vehicle +Setup for carla_ad_demo """ import os from glob import glob diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 7f319a40..d43f6680 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -36,7 +36,12 @@ from sensor_msgs.msg import Image from sensor_msgs.msg import NavSatFix from std_msgs.msg import Bool -from ros_compatibility import CompatibleNode, latch_on, euler_from_quaternion, ros_ok +from ros_compatibility import ( + CompatibleNode, + latch_on, + euler_from_quaternion, + ros_ok, + ros_init) import os import datetime import math @@ -467,12 +472,12 @@ def update_info_text(self): try: (position, quaternion) = self.tf_listener.lookupTransform( '/map', self.role_name, rospy.Time()) - _, _, yaw = tf.transformations.euler_from_quaternion(quaternion) + _, _, yaw = euler_from_quaternion(quaternion) yaw = -math.degrees(yaw) x = position[0] y = -position[1] z = position[2] - except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException): + except (LookupException, ConnectivityException, ExtrapolationException): x = 0 y = 0 z = 0 @@ -675,11 +680,11 @@ def main(args=None): """ main function """ + ros_init(args) if ROS_VERSION == 1: rospy.init_node('carla_manual_control', anonymous=True) role_name = rospy.get_param("~role_name", "ego_vehicle") elif ROS_VERSION == 2: - rclpy.init(args=args) node = rclpy.create_node('carla_manual_control') role_name = rclpy.Parameter("~role_name", value="ego_vehicle").value thread = Thread() diff --git a/carla_msgs b/carla_msgs index 06bf63d0..d2e8f131 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 06bf63d0d959feed73c427857c030269f3d79620 +Subproject commit d2e8f1319769ed8231d7f4a9ed9d82fc8fb96d8e diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py index 7a6f5495..938d56a4 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py @@ -36,6 +36,10 @@ def generate_launch_description(): name='town', default_value='Town01' ), + launch.actions.DeclareLaunchArgument( + name='passive', + default_value='False' + ), launch.actions.DeclareLaunchArgument( name='synchronous_mode', default_value='False' @@ -58,6 +62,7 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'town': launch.substitutions.LaunchConfiguration('town'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'passive': launch.substitutions.LaunchConfiguration('passive'), 'synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode'), 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') @@ -66,7 +71,7 @@ def generate_launch_description(): launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( - 'carla_ego_vehicle'), 'carla_example_ego_vehicle.launch.py') + 'carla_spawn_objects'), 'carla_example_ego_vehicle.launch.py') ), launch_arguments={ 'host': launch.substitutions.LaunchConfiguration('host'), diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index dc69b3e0..34b462ba 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -9,11 +9,11 @@ provide functions to control actors """ -import rospy import numpy import carla_common.transforms as trans from carla_ros_bridge.pseudo_actor import PseudoActor from geometry_msgs.msg import Pose, Twist +from carla import Vector3D class ActorControl(PseudoActor): @@ -41,14 +41,13 @@ def __init__(self, uid, name, parent, node): parent=parent, node=node) - self.set_location_subscriber = rospy.Subscriber(self.get_topic_prefix() + - "/set_transform", - Pose, + self.set_location_subscriber = self.node.create_subscriber(Pose, + self.get_topic_prefix() + "/set_transform", self.on_pose) - self.twist_control_subscriber = rospy.Subscriber( + self.twist_control_subscriber = self.node.create_subscriber(Twist, self.get_topic_prefix() + "/set_target_velocity", - Twist, self.on_twist) + self.on_twist) def destroy(self): """ @@ -94,7 +93,7 @@ def on_twist(self, twist): linear_velocity.y = -rotated_linear_vector[1] linear_velocity.z = rotated_linear_vector[2] - rospy.logdebug("Set velocity linear: {}, angular: {}".format( + self.node.logdebug("Set velocity linear: {}, angular: {}".format( linear_velocity, angular_velocity)) self.carla_actor.set_target_velocity(linear_velocity) self.carla_actor.set_target_angular_velocity(angular_velocity) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 59e1a2bb..9630480f 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -6,8 +6,6 @@ # For a copy, see . # -import rospy - try: import queue except ImportError: @@ -142,7 +140,7 @@ def create(self, type_id, name, attach_to, spawn_pose, carla_actor=None): actor = self._create_object(uid, type_id, name, parent, spawn_pose, carla_actor) self.actors[actor.uid] = actor - rospy.loginfo("Created {}(id={})".format(actor.__class__.__name__, actor.uid)) + self.node.loginfo("Created {}(id={})".format(actor.__class__.__name__, actor.uid)) return actor @@ -160,7 +158,7 @@ def destroy(self, actor_id): actor = self.actors.pop(actor_id) actor.destroy() - rospy.loginfo("Removed {}(id={})".format(actor.__class__.__name__, actor.uid)) + self.node.loginfo("Removed {}(id={})".format(actor.__class__.__name__, actor.uid)) def get_pseudo_sensor_types(self): pseudo_sensors = [] diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py index 27ecf769..155df619 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -9,8 +9,6 @@ handle a actor list sensor """ -import rospy - from carla_ros_bridge.actor import Actor from carla_ros_bridge.pseudo_actor import PseudoActor from carla_msgs.msg import CarlaActorList, CarlaActorInfo @@ -44,9 +42,7 @@ def __init__(self, uid, name, parent, node, actor_list): parent=parent, node=node) self.actor_list = actor_list - self.actor_list_publisher = rospy.Publisher(self.get_topic_prefix(), - CarlaActorList, - queue_size=10) + self.actor_list_publisher = sel.new_publisher(CarlaActorList, self.get_topic_prefix()) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 8089d0e3..aa7ae86b 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -17,7 +17,8 @@ ros_shutdown, ros_timestamp, QoSProfile, - latch_on) + latch_on, + ros_init) try: import queue @@ -43,8 +44,7 @@ from carla_ros_bridge.ego_vehicle import EgoVehicle from carla_msgs.msg import CarlaControl, CarlaWeatherParameters -from carla_msgs.srv import SpawnObject, SpawnObjectResponse, DestroyObject, DestroyObjectResponse, GetBlueprints, GetBlueprintsResponse - +from carla_msgs.srv import SpawnObject, DestroyObject, GetBlueprints # to generate a random spawning position or vehicles secure_random = random.SystemRandom() @@ -54,6 +54,7 @@ if ROS_VERSION == 1: import rospy # pylint: disable=import-error + from carla_msgs.srv import SpawnObjectResponse, DestroyObjectResponse, GetBlueprintsResponse elif ROS_VERSION == 2: import rclpy # pylint: disable=import-error from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error @@ -107,10 +108,10 @@ def initialize_bridge(self, carla_world, params): self.carla_settings.synchronous_mode = False carla_world.apply_settings(self.carla_settings) - rospy.loginfo("synchronous_mode: {}".format( + self.loginfo("synchronous_mode: {}".format( self.parameters["synchronous_mode"])) self.carla_settings.synchronous_mode = self.parameters["synchronous_mode"] - rospy.loginfo("fixed_delta_seconds: {}".format( + self.loginfo("fixed_delta_seconds: {}".format( self.parameters["fixed_delta_seconds"])) self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) @@ -123,7 +124,7 @@ def initialize_bridge(self, carla_world, params): # passive mode is not enabled. self.sync_mode = self.carla_settings.synchronous_mode and not self.parameters["passive"] if self.carla_settings.synchronous_mode and self.parameters["passive"]: - rospy.loginfo( + self.loginfo( "Passive mode is enabled and CARLA world is configured in synchronous mode. This configuration requires another client ticking the CARLA world.") self.carla_control_queue = queue.Queue() @@ -132,9 +133,9 @@ def initialize_bridge(self, carla_world, params): self.actor_factory = ActorFactory(self, carla_world, self.sync_mode) # add world info - self.world_info = WorldInfo(carla_world=self.carla_world) + self.world_info = WorldInfo(carla_world=self.carla_world, node=self) # add debug helper - self.debug_helper = DebugHelper(carla_world.debug) + self.debug_helper = DebugHelper(carla_world.debug, self) # Communication topics if ROS_VERSION == 1: @@ -144,7 +145,8 @@ def initialize_bridge(self, carla_world, params): self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode, - self.carla_settings.fixed_delta_seconds) + self.carla_settings.fixed_delta_seconds, + self) # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. @@ -174,12 +176,12 @@ def initialize_bridge(self, carla_world, params): # services configuration. self._registered_actors = [] - self.spawn_object_service = rospy.Service("/carla/spawn_object", SpawnObject, + self.spawn_object_service = self.new_service(SpawnObject, "/carla/spawn_object", self.spawn_object) - self.destroy_object_service = rospy.Service("/carla/destroy_object", DestroyObject, + self.destroy_object_service = self.new_service(DestroyObject, "/carla/destroy_object", self.destroy_object) - self.get_blueprints_service = rospy.Service("/carla/get_blueprints", GetBlueprints, + self.get_blueprints_service = self.new_service(GetBlueprints, "/carla/get_blueprints", self.get_blueprints) self.carla_weather_subscriber = \ @@ -230,7 +232,7 @@ def spawn_object(self, req): return SpawnObjectResponse(id_, "") except Exception as e: - rospy.logwarn("Error spawning object '{}: {}".format(req.type, e)) + self.logwarn("Error spawning object '{}: {}".format(req.type, e)) return SpawnObjectResponse(-1, str(e)) def _destroy_actor(self, uid): @@ -372,27 +374,6 @@ def _carla_time_tick(self, carla_snapshot): carla_snapshot.timestamp.elapsed_seconds) self.actor_factory.lock.release() - def run(self): - """ - Run the bridge functionality. - - Registers on shutdown callback at rospy and spins ROS. - - :return: - """ - rospy.on_shutdown(self.on_shutdown) - rospy.spin() - - def on_shutdown(self): - """ - Function to be called on shutdown. - - This function is registered at rospy as shutdown handler. - - """ - rospy.loginfo("Shutdown requested") - self.destroy() - def _update(self, frame_id, timestamp): """ update all actors @@ -432,9 +413,11 @@ def update_clock(self, carla_timestamp): :type carla_timestamp: carla.Timestamp :return: """ - self.ros_timestamp = rospy.Time.from_sec( - carla_timestamp.elapsed_seconds) - self.clock_publisher.publish(Clock(self.ros_timestamp)) + self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) + if ROS_VERSION == 1: + self.clock_publisher.publish(Clock(self.ros_timestamp)) + elif ROS_VERSION == 2: + self.clock_publisher.publish(Clock(clock=self.ros_timestamp)) def destroy(self): """ @@ -442,10 +425,9 @@ def destroy(self): :return: """ - self.shutdown() self.debug_helper.destroy() self.shutdown.set() - self.carla_weather_subscriber.unregister() + destroy_subscription(self.carla_weather_subscriber) self.carla_control_queue.put(CarlaControl.STEP_ONCE) if not self.sync_mode: if self.on_tick_id: @@ -462,11 +444,12 @@ def destroy(self): super(CarlaRosBridge, self).destroy() -def main(): +def main(args=None): """ main function for carla simulator ROS bridge maintaining the communication client and the CarlaBridge object """ + ros_init(args) carla_bridge = None carla_world = None carla_client = None @@ -477,7 +460,6 @@ def main(): # rospy.init_node('carla_ros_bridge', anonymous=True) elif ROS_VERSION == 2: - rclpy.init(args=None) executor = rclpy.executors.MultiThreadedExecutor(num_threads=12) carla_bridge = CarlaRosBridge(executor=executor) # init_node = rclpy.create_node("init_ros_bridge") @@ -486,6 +468,7 @@ def main(): parameters['host'] = carla_bridge.get_param('host', 'localhost') parameters['port'] = carla_bridge.get_param('port', 2000) parameters['timeout'] = carla_bridge.get_param('timeout', 2) + parameters['passive'] = carla_bridge.get_param('passive', False) parameters['synchronous_mode'] = carla_bridge.get_param('synchronous_mode', False) parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( 'synchronous_mode_wait_for_vehicle_control_command', False) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index bf4f7c02..96e4b828 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -144,7 +144,7 @@ def get_ros_image(self, carla_camera_data): """ if ((carla_camera_data.height != self._camera_info.height) or (carla_camera_data.width != self._camera_info.width)): - rospy.logerr( + self.node.logerr( "Camera{} received image not matching configuration".format(self.get_prefix())) image_data_array, encoding = self.get_carla_image_data_array( carla_camera_data) diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index 7a4df585..26698a57 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -9,8 +9,6 @@ handle a marker sensor """ -import rospy - from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.traffic_participant import TrafficParticipant @@ -47,9 +45,8 @@ def __init__(self, uid, name, parent, node, actor_list): node=node) self.actor_list = actor_list - self.marker_publisher = rospy.Publisher(self.get_topic_prefix(), - MarkerArray, - queue_size=10) + self.marker_publisher = node.new_publisher(MarkerArray, + self.get_topic_prefix()) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 6813da30..1405641e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -9,8 +9,6 @@ handle a odom sensor """ -import rospy - from carla_ros_bridge.pseudo_actor import PseudoActor from nav_msgs.msg import Odometry @@ -43,8 +41,8 @@ def __init__(self, uid, name, parent, node): parent=parent, node=node) - self.odometry_publisher = rospy.Publisher(self.get_topic_prefix(), - Odometry, + self.odometry_publisher = node.new_publisher(Odometry, + self.get_topic_prefix(), queue_size=10) @staticmethod diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 8ad5e1b8..8278925c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -9,7 +9,6 @@ handle a opendrive sensor """ -import rospy import numpy as np from carla_ros_bridge.pseudo_actor import PseudoActor @@ -44,8 +43,7 @@ def __init__(self, uid, name, parent, node, carla_map): node=node) self.carla_map = carla_map self._map_published = False - self.map_publisher = rospy.Publisher(self.get_topic_prefix(), - String, + self.map_publisher = node.new_publisher(String, self.get_topic_prefix(), queue_size=10, latch=True) diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index f2da3a98..b36c0cc4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -8,7 +8,7 @@ """ Base Class to handle Pseudo Actors (that are not existing in Carla world) """ - +import numpy as np from std_msgs.msg import Header from ros_compatibility import ( diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 3bf3a3c4..7056a9fe 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -9,14 +9,12 @@ handle a speedometer sensor """ -import rospy import numpy as np from carla_ros_bridge.pseudo_actor import PseudoActor from std_msgs.msg import Float32 - class SpeedometerSensor(PseudoActor): """ @@ -42,9 +40,8 @@ def __init__(self, uid, name, parent, node): parent=parent, node=node) - self.speedometer_publisher = rospy.Publisher(self.get_topic_prefix(), - Float32, - queue_size=10) + self.speedometer_publisher = node.new_publisher(Float32, + self.get_topic_prefix()) @staticmethod def get_blueprint_name(): diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 6bb94463..d66eeaf7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -9,11 +9,16 @@ handle a tf sensor """ -import rospy - +import os from carla_ros_bridge.pseudo_actor import PseudoActor -import tf +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + import tf +elif ROS_VERSION == 2: + import tf2_ros + class TFSensor(PseudoActor): @@ -61,4 +66,4 @@ def update(self, frame, timestamp): self.tf_broadcaster.sendTransform( (position.x, position.y, position.z), (orientation.x, orientation.y, orientation.z, orientation.w), - rospy.Time.now(), self.parent.get_prefix(), "map") + ros_timestamp(self.ros_node.get_time(), from_sec=True), self.parent.get_prefix(), "map") diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py index 7ecf7ab4..a07c82ab 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py @@ -25,7 +25,11 @@ from carla_ros_scenario_runner.application_runner import ApplicationStatus # pylint: disable=relative-import from carla_ros_scenario_runner.scenario_runner_runner import ScenarioRunnerRunner # pylint: disable=relative-import -from ros_compatibility import CompatibleNode, QoSProfile, ros_ok +from ros_compatibility import ( + CompatibleNode, + QoSProfile, + ros_ok, + ros_init) # Check Python dependencies of scenario runner try: @@ -160,15 +164,14 @@ def run(self): self._scenario_runner.shutdown() -def main(): +def main(args=None): """ main function :return: """ - if ROS_VERSION == 2: - rclpy.init() + ros_init(args) scenario_runner = CarlaRosScenarioRunner() diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 104aeea5..87d4277b 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -32,8 +32,7 @@ class RosVehicleControl(BasicControl): def __init__(self, actor, args=None): super(RosVehicleControl, self).__init__(actor) - if ROS_VERSION == 2: - rclpy.init() + ros_init(args=None) self._carla_actor = actor self._role_name = actor.attributes["role_name"] diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index ee0c34f7..ff7b18a1 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -21,21 +21,32 @@ import sys import math import json -import rospy -from tf.transformations import quaternion_from_euler + from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import Pose from carla_msgs.msg import CarlaWorldInfo, CarlaActorList -from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest +from carla_msgs.srv import SpawnObject, DestroyObject + +from ros_compatibility import ( + CompatibleNode, + ROSInterruptException, + ServiceException, + quaternion_from_euler +) + +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + from carla_msgs.srv import SpawnObjectRequest, DestroyObjectRequest # ============================================================================== # -- CarlaSpawnObjects ------------------------------------------------------------ # ============================================================================== -class CarlaSpawnObjects(object): +class CarlaSpawnObjects(CompatibleNode): """ Handles the spawning of the ego vehicle and its sensors @@ -44,19 +55,16 @@ class CarlaSpawnObjects(object): """ def __init__(self): - rospy.init_node('spawn_objects_node', anonymous=True) - self.objects_definition_file = rospy.get_param('~objects_definition_file') - self.spawn_sensors_only = rospy.get_param('~spawn_sensors_only', None) + super(CarlaSpawnObjects, self).__init__('carla_spawn_objects') + self.objects_definition_file = self.get_param('~objects_definition_file') + self.spawn_sensors_only = self.get_param('~spawn_sensors_only', None) self.players = [] self.vehicles_sensors = [] self.global_sensors = [] - rospy.wait_for_service('/carla/spawn_object') - rospy.wait_for_service('/carla/destroy_object') - - self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) - self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) + self.spawn_object_service = self.create_service_client("/carla/spawn_object", SpawnObject) + self.destroy_object_service = self.create_service_client("/carla/destroy_object", DestroyObject) def spawn_objects(self): """ @@ -88,7 +96,7 @@ def spawn_objects(self): elif actor_type == "vehicle" or actor_type == "walker": vehicles.append(actor) else: - rospy.logwarn( + self.logwarn( "Object with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"])) if self.spawn_sensors_only is True and found_sensor_actor_list is False: raise Exception("Parameter 'spawn_sensors_only' enabled, " + @@ -101,7 +109,7 @@ def spawn_objects(self): if self.spawn_sensors_only is True: # get vehicle id from topic /carla/actor_list for all vehicles listed in config file - actor_info_list = rospy.wait_for_message("/carla/actor_list", CarlaActorList) + actor_info_list = self.wait_for_one_message("/carla/actor_list", CarlaActorList) for vehicle in vehicles: for actor_info in actor_info_list.actors: if actor_info.type == vehicle["type"] and actor_info.rolename == vehicle["id"]: @@ -120,7 +128,7 @@ def setup_vehicles(self, vehicles): try: carla_id = vehicle["carla_id"] except KeyError as e: - rospy.logerr( + self.logerr( "Could not spawn sensors of vehicle {}, its carla ID is not known.".format(vehicle["id"])) break # spawn the vehicle's sensors @@ -139,16 +147,16 @@ def setup_vehicles(self, vehicles): spawn_point = None # check if there's a spawn_point corresponding to this vehicle - spawn_point_param = rospy.get_param("~spawn_point_" + vehicle["id"], None) + spawn_point_param = self.get_param("~spawn_point_" + vehicle["id"], None) spawn_param_used = False if (spawn_point_param is not None): # try to use spawn_point from parameters try: spawn_point = self.check_spawn_point_param(spawn_point_param) - rospy.loginfo("Spawn point from ros parameters") + self.loginfo("Spawn point from ros parameters") spawn_param_used = True except Exception as e: - rospy.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"]) + + self.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"]) + "the spawn point from config file will be used. Error is: {}".format(e)) if "spawn_point" in vehicle and spawn_param_used is False: @@ -162,14 +170,14 @@ def setup_vehicles(self, vehicles): vehicle["spawn_point"]["pitch"], vehicle["spawn_point"]["yaw"] ) - rospy.loginfo("Spawn point from configuration file") + self.loginfo("Spawn point from configuration file") except KeyError as e: - rospy.logerr("{}: Could not use the spawn point from config file, ".format(vehicle["id"]) + + self.logerr("{}: Could not use the spawn point from config file, ".format(vehicle["id"]) + "the mandatory attribute {} is missing, a random spawn point will be used".format(e)) if spawn_point is None: # pose not specified, ask for a random one in the service call - rospy.loginfo("Spawn point selected at random") + self.loginfo("Spawn point selected at random") spawn_point = Pose() # empty pose spawn_object_request.random_pose = True @@ -185,7 +193,7 @@ def setup_vehicles(self, vehicles): self.vehicles_sensors.append( self.setup_sensors(vehicle["sensors"], response.id)) except KeyError: - rospy.logwarn( + self.logwarn( "Vehicle {} have no 'sensors' field in his config file, none will be spawned") return players @@ -251,12 +259,12 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): raise Exception(response.error_string) except KeyError as e: - rospy.logerr( + self.logerr( "Sensor {} will not be spawned, the mandatory attribute {} is missing".format(sensor_name, e)) continue except Exception as e: - rospy.logerr( + self.logerr( "Sensor {} will not be spawned: {}".format(sensor_name, e)) continue @@ -268,7 +276,7 @@ def create_spawn_point(self, x, y, z, roll, pitch, yaw): spawn_point.position.x = x spawn_point.position.y = y spawn_point.position.z = z - quat = quaternion_from_euler( + quat = trans.quaternion_from_euler( math.radians(roll), math.radians(pitch), math.radians(yaw)) @@ -302,8 +310,8 @@ def destroy(self): destroy_object_request = DestroyObjectRequest(actor_id) try: response = self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) + except ServiceException as e: + self.logwarn_once(str(e)) self.global_sensors = [] # destroy vehicles sensors @@ -312,8 +320,8 @@ def destroy(self): destroy_object_request = DestroyObjectRequest(actor_id) try: response = self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) + except ServiceException as e: + self.logwarn_once(str(e)) self.vehicles_sensors = [] # destroy player @@ -321,19 +329,19 @@ def destroy(self): destroy_object_request = DestroyObjectRequest(player_id) try: self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) + except ServiceException as e: + self.logwarn_once(str(e)) self.players = [] def run(self): """ main loop """ - rospy.on_shutdown(self.destroy) + self.on_shutdown(self.destroy) self.spawn_objects() try: - rospy.spin() - except rospy.ROSInterruptException: + self.spin() + except ROSInterruptException: pass # ============================================================================== @@ -350,7 +358,7 @@ def main(): spawn_objects_node = CarlaSpawnObjects() spawn_objects_node.run() except Exception as e: - rospy.logfatal( + print( "Exception caught: {}".format(e)) finally: if spawn_objects_node is not None: diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 64040b49..314f39f9 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -27,7 +27,8 @@ euler_from_quaternion, QoSProfile, ROSException, - ROSInterruptException + ROSInterruptException, + ros_init ) # ============================================================================== # -- CarlaSpectatorCamera ------------------------------------------------------------ @@ -190,12 +191,11 @@ def run(self): # ============================================================================== -def main(): +def main(args=None): """ main function """ - if ROS_VERSION == 2: - rclpy.init() + ros_init(args) carla_spectator_camera = CarlaSpectatorCamera() try: diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index cebd2260..34e44bee 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -9,7 +9,12 @@ use max wheel steer angle """ -from ros_compatibility import CompatibleNode, ros_ok, ROSException, ROSInterruptException +from ros_compatibility import ( + CompatibleNode, + ros_ok, + ROSException, + ROSInterruptException, + ros_init) import sys from geometry_msgs.msg import Twist # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo # pylint: disable=import-error @@ -110,13 +115,13 @@ def twist_received(self, twist): self.logwarn("Error while publishing control: {}".format(e)) -def main(): +def main(args=None): """ main function :return: """ - # rospy.init_node('convert_twist_to_vehicle_control', anonymous=True) + ros_init(args) role_name = None twist_to_vehicle_control = None @@ -125,7 +130,6 @@ def main(): twist_to_vehicle_control = TwistToVehicleControl() role_name = rospy.get_param("~role_name", "ego_vehicle") elif ROS_VERSION == 2: - rclpy.init(args=None) twist_to_vehicle_control = TwistToVehicleControl() executor = rclpy.executors.MultiThreadedExecutor() executor.add_node(twist_to_vehicle_control) diff --git a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py index 014db1cf..ffd500ff 100755 --- a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py +++ b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py @@ -13,7 +13,12 @@ from std_msgs.msg import Float64 from geometry_msgs.msg import Pose, Vector3 from carla_msgs.msg import CarlaWalkerControl -from ros_compatibility import CompatibleNode, QoSProfile, ros_ok, ROSInterruptException +from ros_compatibility import ( + CompatibleNode, + QoSProfile, + ros_ok, + ROSInterruptException, + ros_init) import os ROS_VERSION = int(os.environ['ROS_VERSION']) @@ -139,15 +144,14 @@ def run(self): pass -def main(): +def main(args=None): """ main function :return: """ - if ROS_VERSION == 2: - rclpy.init() + ros_init(args) controller = CarlaWalkerAgent() diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 0d58e1f1..207b43a9 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -33,8 +33,7 @@ from geometry_msgs.msg import PoseStamped import carla_common.transforms as trans from carla_msgs.msg import CarlaWorldInfo -from carla_waypoint_types.srv import GetWaypointResponse, GetWaypoint -from carla_waypoint_types.srv import GetActorWaypointResponse, GetActorWaypoint +from carla_waypoint_types.srv import GetWaypoint, GetActorWaypoint import carla @@ -43,6 +42,8 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +if ROS_VERSION == 1: + from carla_waypoint_types.srv import GetWaypointResponse, GetActorWaypointResponse class CarlaToRosWaypointConverter(CompatibleNode): @@ -272,8 +273,7 @@ def main(args=None): """ main function """ - if ROS_VERSION == 2: - rclpy.init(args=None) + ros_init(args) try: waypointConverter = CarlaToRosWaypointConverter() diff --git a/ros_compatibility/__init__.py b/ros_compatibility/__init__.py deleted file mode 100644 index 3d5facb7..00000000 --- a/ros_compatibility/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from ros_compatibility.src.ros_compatibility.ros_compatible_node import * diff --git a/ros_compatibility/setup.py b/ros_compatibility/setup.py index d67894d3..9863d61a 100644 --- a/ros_compatibility/setup.py +++ b/ros_compatibility/setup.py @@ -37,10 +37,5 @@ description='The ros_compatibility package', license='MIT', tests_require=['pytest'], - entry_points={ - 'console_scripts': [ - 'ros_compatible_node = ros_compatibility.ros_compatible_node:main' - ], - }, package_dir={'': 'src'}, ) diff --git a/ros_compatibility/src/__init__.py b/ros_compatibility/src/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py index 63dae51c..5760b616 100644 --- a/ros_compatibility/src/ros_compatibility/__init__.py +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -1,2 +1 @@ -# pylint: disable=no-name-in-module,import-error -from ros_compatibility.ros_compatible_node import * +from ros_compatibility.ros_compatible_node import * \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 8e88dd01..42fb7bb3 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -9,6 +9,9 @@ latch_on = True + def ros_init(args=None): + pass + def ros_timestamp(sec=0, nsec=0, from_sec=False): if from_sec: return rospy.Time.from_sec(sec) @@ -151,6 +154,9 @@ def on_shutdown(self, handler): latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL + def ros_init(args=None): + rclpy.init(args=args) + def ros_timestamp(sec=0, nsec=0, from_sec=False): time = Time() if from_sec: From 16b76ed9d714ae99b000e0617cb5aaa358cae126 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 16 Dec 2020 15:59:10 +0100 Subject: [PATCH 435/627] Git ignore colcon folders --- .gitignore | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.gitignore b/.gitignore index 0765bb13..c915d27c 100644 --- a/.gitignore +++ b/.gitignore @@ -6,3 +6,8 @@ build.gradle # IDE .vscode .idea + +#colcon +build/ +install/ +log/ From e9e438e7cd1543e1bff704df8449d3f572c60478 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 16 Dec 2020 16:07:35 +0100 Subject: [PATCH 436/627] ROS2 launch files: rename node_executable to executable --- .../launch/carla_ackermann_control.launch.py | 2 +- carla_ad_agent/launch/carla_ad_agent.launch.py | 2 +- carla_ad_demo/launch/carla_ad_demo.launch.py | 2 +- carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py | 4 ++-- carla_infrastructure/launch/carla_infrastructure.launch.py | 2 +- carla_manual_control/launch/carla_manual_control.launch.py | 2 +- carla_ros_bridge/launch/carla_ros_bridge.launch.py | 2 +- carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py | 2 +- .../launch/carla_ros_scenario_runner.launch.py | 2 +- carla_spawn_objects/launch/carla_spawn_objects.launch.py | 2 +- .../launch/carla_spectator_camera.launch.py | 2 +- .../launch/carla_twist_to_control.launch.py | 2 +- carla_walker_agent/launch/carla_walker_agent.launch.py | 2 +- .../launch/carla_waypoint_publisher.launch.py | 2 +- pcl_recorder/launch/pcl_recorder.launch.py | 4 ++-- 15 files changed, 17 insertions(+), 17 deletions(-) diff --git a/carla_ackermann_control/launch/carla_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ackermann_control.launch.py index d1ff9238..97b822d6 100644 --- a/carla_ackermann_control/launch/carla_ackermann_control.launch.py +++ b/carla_ackermann_control/launch/carla_ackermann_control.launch.py @@ -13,7 +13,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_ackermann_control', - node_executable='carla_ackermann_control_node', + executable='carla_ackermann_control_node', node_name='carla_ackermann_control', output='screen', parameters=[ diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 5660d837..0bd5672f 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -21,7 +21,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_ad_agent', - node_executable='carla_ad_agent', + executable='carla_ad_agent', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', parameters=[ diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index e1e282b4..4b9d84d6 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -59,7 +59,7 @@ def generate_launch_description(): # TODO: adapt this to ROS2 # launch_ros.actions.Node( # package='rostopic', - # node_executable='rostopic', + # executable='rostopic', # name='publish_goal' # ), launch.actions.IncludeLaunchDescription( diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index da2dd18d..1288a9ac 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -70,7 +70,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_twist_to_control', - node_executable='carla_twist_to_control', + executable='carla_twist_to_control', name='carla_twist_to_control', remappings=[ ( @@ -158,7 +158,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='rviz2', - node_executable='rviz2', + executable='rviz2', name='rviz2', output='screen', arguments=[ diff --git a/carla_infrastructure/launch/carla_infrastructure.launch.py b/carla_infrastructure/launch/carla_infrastructure.launch.py index 3ceadfef..18aa56dd 100644 --- a/carla_infrastructure/launch/carla_infrastructure.launch.py +++ b/carla_infrastructure/launch/carla_infrastructure.launch.py @@ -24,7 +24,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_infrastructure', - node_executable='carla_infrastructure', + executable='carla_infrastructure', name='carla_infrastructure', output='screen', emulate_tty='True', diff --git a/carla_manual_control/launch/carla_manual_control.launch.py b/carla_manual_control/launch/carla_manual_control.launch.py index 332404c8..2f2f8615 100644 --- a/carla_manual_control/launch/carla_manual_control.launch.py +++ b/carla_manual_control/launch/carla_manual_control.launch.py @@ -13,7 +13,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_manual_control', - node_executable='carla_manual_control', + executable='carla_manual_control', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', parameters=[ diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch.py b/carla_ros_bridge/launch/carla_ros_bridge.launch.py index c1615943..6e2ae1f5 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch.py @@ -47,7 +47,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_ros_bridge', - node_executable='bridge', + executable='bridge', name='carla_ros_bridge', output='screen', emulate_tty='True', diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py index f9a46fa2..d1b092a0 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py @@ -10,7 +10,7 @@ def generate_launch_description(): ld = launch.LaunchDescription([ launch_ros.actions.Node( package='rviz', - node_executable='rviz', + executable='rviz', name='rviz' ), launch.actions.IncludeLaunchDescription( diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py index 99e75571..c9255fa7 100644 --- a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py @@ -28,7 +28,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_ros_scenario_runner', - node_executable='carla_ros_scenario_runner', + executable='carla_ros_scenario_runner', name='carla_ros_scenario_runner', output='screen', emulate_tty='True', diff --git a/carla_spawn_objects/launch/carla_spawn_objects.launch.py b/carla_spawn_objects/launch/carla_spawn_objects.launch.py index 6082a403..9e9bd1a6 100644 --- a/carla_spawn_objects/launch/carla_spawn_objects.launch.py +++ b/carla_spawn_objects/launch/carla_spawn_objects.launch.py @@ -22,7 +22,7 @@ def generate_launch_description(): launch_ros.actions.Node( package='carla_spawn_objects', - node_executable='carla_spawn_objects', + executable='carla_spawn_objects', name='carla_spawn_objects', output='screen', parameters=[ diff --git a/carla_spectator_camera/launch/carla_spectator_camera.launch.py b/carla_spectator_camera/launch/carla_spectator_camera.launch.py index cc6745b4..6e44769d 100644 --- a/carla_spectator_camera/launch/carla_spectator_camera.launch.py +++ b/carla_spectator_camera/launch/carla_spectator_camera.launch.py @@ -37,7 +37,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_spectator_camera', - node_executable='carla_spectator_camera', + executable='carla_spectator_camera', name='carla_spectator_camera', output='screen', emulate_tty='True', diff --git a/carla_twist_to_control/launch/carla_twist_to_control.launch.py b/carla_twist_to_control/launch/carla_twist_to_control.launch.py index d2142c59..3977a0b5 100644 --- a/carla_twist_to_control/launch/carla_twist_to_control.launch.py +++ b/carla_twist_to_control/launch/carla_twist_to_control.launch.py @@ -13,7 +13,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_twist_to_control', - node_executable='carla_twist_to_control', + executable='carla_twist_to_control', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', emulate_tty='True', diff --git a/carla_walker_agent/launch/carla_walker_agent.launch.py b/carla_walker_agent/launch/carla_walker_agent.launch.py index f45a26f6..300135cd 100644 --- a/carla_walker_agent/launch/carla_walker_agent.launch.py +++ b/carla_walker_agent/launch/carla_walker_agent.launch.py @@ -21,7 +21,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_walker_agent', - node_executable='carla_walker_agent', + executable='carla_walker_agent', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', emulate_tty='True', diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py index 9d738afb..4a334e6c 100644 --- a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py @@ -25,7 +25,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_waypoint_publisher', - node_executable='carla_waypoint_publisher', + executable='carla_waypoint_publisher', name='carla_waypoint_publisher', output='screen', emulate_tty='True', diff --git a/pcl_recorder/launch/pcl_recorder.launch.py b/pcl_recorder/launch/pcl_recorder.launch.py index 2ccf22bb..978253f0 100644 --- a/pcl_recorder/launch/pcl_recorder.launch.py +++ b/pcl_recorder/launch/pcl_recorder.launch.py @@ -22,12 +22,12 @@ def generate_launch_description(): ), # launch_ros.actions.Node( # package='rostopic', - # node_executable='rostopic', + # executable='rostopic', # name='enable_autopilot_rostopic' # ), launch_ros.actions.Node( package='pcl_recorder', - node_executable='pcl_recorder_node', + executable='pcl_recorder_node', name='pcl_recorder_node', output='screen', parameters=[ From 8a2b1b08d602cf5116aff56fcc43d8ab4bdefa00 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 17 Dec 2020 13:47:10 +0100 Subject: [PATCH 437/627] Port spawning --- .../src/carla_ad_agent/basic_agent.py | 4 +- carla_common/src/carla_common/transforms.py | 11 ++-- .../launch/carla_manual_control.launch.py | 1 + .../carla_manual_control.py | 34 ++++++----- carla_msgs | 2 +- .../src/carla_ros_bridge/actor.py | 41 ++++--------- .../src/carla_ros_bridge/actor_control.py | 6 +- .../src/carla_ros_bridge/actor_list_sensor.py | 2 +- .../src/carla_ros_bridge/bridge.py | 27 +++++---- .../src/carla_ros_bridge/camera.py | 24 +------- .../src/carla_ros_bridge/ego_vehicle.py | 4 +- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 3 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 +- .../src/carla_ros_bridge/lidar.py | 2 +- .../src/carla_ros_bridge/odom_sensor.py | 3 +- .../src/carla_ros_bridge/opendrive_sensor.py | 6 +- .../src/carla_ros_bridge/sensor.py | 11 ++-- .../carla_ros_bridge/speedometer_sensor.py | 2 +- .../src/carla_ros_bridge/tf_sensor.py | 16 ++--- .../src/carla_ros_bridge/traffic.py | 2 +- .../carla_ros_bridge/traffic_participant.py | 15 ----- .../launch/carla_spawn_objects.launch.py | 1 + .../carla_spawn_objects.py | 58 ++++++++++++------- 23 files changed, 123 insertions(+), 154 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 9b349684..1d447cb5 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -85,12 +85,12 @@ def get_actor_waypoint(self, actor_id): Only used if risk should be avoided. """ try: + #TODO: have ros_compat get_service_request(GetActorWaypoint) if ROS_VERSION == 1: request = GetActorWaypointRequest() - request.id = actor_id elif ROS_VERSION == 2: request = GetActorWaypoint.Request() - request.id = actor_id + request.id = actor_id response = self.node.call_service(self._get_actor_waypoint_client, request) return response.waypoint except (ServiceException, ROSInterruptException, TypeError) as e: diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index e1fa738a..d29914bd 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -10,15 +10,12 @@ Tool functions to convert transforms from carla to ROS coordinate system """ -import os import math import numpy +import carla from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel # pylint: disable=import-error -from ros_compatibility import euler_matrix, quaternion_from_euler - -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - +from ros_compatibility import euler_matrix, quaternion_from_euler, euler_from_quaternion def carla_location_to_numpy_vector(carla_location): """ @@ -338,7 +335,7 @@ def carla_location_to_pose(carla_location): def RPY_to_ros_quaternion(roll, pitch, yaw): - quat = tf.transformations.quaternion_from_euler(roll, pitch, yaw) + quat = quaternion_from_euler(roll, pitch, yaw) return Quaternion(*quat) @@ -353,7 +350,7 @@ def ros_quaternion_to_RPY(ros_quaternion): ros_quaternion.z, ros_quaternion.w ) - return tf.transformations.euler_from_quaternion(quaternion) + return euler_from_quaternion(quaternion) def RPY_to_carla_rotation(roll, pitch, yaw): diff --git a/carla_manual_control/launch/carla_manual_control.launch.py b/carla_manual_control/launch/carla_manual_control.launch.py index 2f2f8615..a48ed671 100644 --- a/carla_manual_control/launch/carla_manual_control.launch.py +++ b/carla_manual_control/launch/carla_manual_control.launch.py @@ -16,6 +16,7 @@ def generate_launch_description(): executable='carla_manual_control', name=launch.substitutions.LaunchConfiguration('role_name'), output='screen', + emulate_tty=True, parameters=[ { 'role_name': launch.substitutions.LaunchConfiguration('role_name') diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index d43f6680..37c705a1 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -41,7 +41,8 @@ latch_on, euler_from_quaternion, ros_ok, - ros_init) + ros_init, + destroy_subscription) import os import datetime import math @@ -59,6 +60,7 @@ elif ROS_VERSION == 2: import rclpy + from rclpy.time import Time from rclpy.callback_groups import ReentrantCallbackGroup from tf2_ros import LookupException from tf2_ros import ConnectivityException @@ -177,14 +179,9 @@ def destroy(self): """ destroy all objects """ - if ROS_VERSION == 1: - self.image_subscriber.unregister() - self.collision_subscriber.unregister() - self.lane_invasion_subscriber.unregister() - elif ROS_VERSION == 2: - self.image_subscriber.destroy() - self.collision_subscriber.destroy() - self.lane_invasion_subscriber.destroy() + destroy_subscription(self.image_subscriber) + destroy_subscription(self.collision_subscriber) + destroy_subscription(self.lane_invasion_subscriber) # ============================================================================== @@ -368,8 +365,8 @@ def __init__(self, role_name, width, height): self.callback_group = None elif ROS_VERSION == 2: self.tf_listener_node = rclpy.create_node("tf_listener") - self.tfBuffer = tf2_ros.Buffer() - self.tf_listener = tf2_ros.TransformListener(self.tfBuffer, node=self.tf_listener_node) + self.tf_buffer = tf2_ros.Buffer() + self.tf_listener = tf2_ros.TransformListener(self.tf_buffer, node=self.tf_listener_node) self.time = Time() self.callback_group = ReentrantCallbackGroup() @@ -470,14 +467,21 @@ def update_info_text(self): if not self._show_info: return try: - (position, quaternion) = self.tf_listener.lookupTransform( - '/map', self.role_name, rospy.Time()) + + if ROS_VERSION == 1: + (position, quaternion) = self.tf_listener.lookupTransform( + 'map', self.role_name, Time()) + elif ROS_VERSION == 2: + (position, quaternion) = self.tf_buffer.lookup_transform( + target_frame='map', source_frame=self.role_name, time=Time()) + _, _, yaw = euler_from_quaternion(quaternion) yaw = -math.degrees(yaw) x = position[0] y = -position[1] z = position[2] - except (LookupException, ConnectivityException, ExtrapolationException): + except (LookupException, ConnectivityException, ExtrapolationException) as e: + print(e) x = 0 y = 0 z = 0 @@ -488,6 +492,7 @@ def update_info_text(self): heading += 'W' if -0.5 > yaw > -179.5 else '' fps = 0 + #TODO if ROS_VERSION == 1: time = str(datetime.timedelta(seconds=float(rospy.get_rostime().to_sec())))[:10] elif ROS_VERSION == 2: @@ -681,6 +686,7 @@ def main(args=None): main function """ ros_init(args) + #TODO if ROS_VERSION == 1: rospy.init_node('carla_manual_control', anonymous=True) role_name = rospy.get_param("~role_name", "ego_vehicle") diff --git a/carla_msgs b/carla_msgs index d2e8f131..3ca07f67 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit d2e8f1319769ed8231d7f4a9ed9d82fc8fb96d8e +Subproject commit 3ca07f679667642369edccd89332eae6b37b2bd2 diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 28f10bc6..48b7b929 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -65,6 +65,16 @@ def get_current_ros_pose(self): return trans.carla_transform_to_ros_pose( self.carla_actor.get_transform()) + def get_current_ros_transform(self): + """ + Function to provide the current ROS pose + + :return: the ROS pose of this actor + :rtype: geometry_msgs.msg.Pose + """ + return trans.carla_transform_to_ros_transform( + self.carla_actor.get_transform()) + def get_current_ros_twist_rotated(self): """ Function to provide the current ROS twist rotated @@ -105,34 +115,3 @@ def get_id(self): :rtype: int64 """ return self.carla_actor_id - - def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): - """ - Function to provide the current ROS transform - - :return: the ROS transfrom - :rtype: geometry_msgs.msg.TransformStamped - """ - tf_msg = TransformStamped() - if frame_id: - tf_msg.header = self.get_msg_header(frame_id) - else: - tf_msg.header = self.get_msg_header("map") - if child_frame_id: - tf_msg.child_frame_id = child_frame_id - else: - tf_msg.child_frame_id = self.get_prefix() - if transform: - tf_msg.transform = transform - else: - tf_msg.transform = trans.carla_transform_to_ros_transform( - self.carla_actor.get_transform()) - return tf_msg - - def publish_transform(self, ros_transform_msg): - """ - Helper function to send a ROS tf message of this child - - :return: - """ - self.node.publish_tf_message(ros_transform_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index 34b462ba..49e1c44c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -14,7 +14,7 @@ from carla_ros_bridge.pseudo_actor import PseudoActor from geometry_msgs.msg import Pose, Twist from carla import Vector3D - +from ros_compatibility import destroy_subscription class ActorControl(PseudoActor): @@ -58,9 +58,9 @@ def destroy(self): :return: """ - self.set_location_subscriber.unregister() + destroy_subscription(self.set_location_subscriber) self.set_location_subscriber = None - self.twist_control_subscriber.unregister() + destroy_subscription(self.twist_control_subscriber) self.twist_control_subscriber = None super(ActorControl, self).destroy() diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py index 155df619..e974eaed 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -42,7 +42,7 @@ def __init__(self, uid, name, parent, node, actor_list): parent=parent, node=node) self.actor_list = actor_list - self.actor_list_publisher = sel.new_publisher(CarlaActorList, self.get_topic_prefix()) + self.actor_list_publisher = node.new_publisher(CarlaActorList, self.get_topic_prefix()) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index aa7ae86b..358a89b0 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -45,6 +45,7 @@ from carla_msgs.msg import CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, DestroyObject, GetBlueprints +import carla_common.transforms as trans # to generate a random spawning position or vehicles secure_random = random.SystemRandom() @@ -220,20 +221,24 @@ def _spawn_pseudo_actor(self, req): actor = self.actor_factory.create(req.type, req.id, req.attach_to, req.transform) return actor.uid - def spawn_object(self, req): + def spawn_object(self, req, response=None): + if ROS_VERSION == 1: + response = SpawnObjectResponse() + else: + response = SpawnObject.Response() with self.actor_factory.spawn_lock: try: if "pseudo" in req.type: id_ = self._spawn_pseudo_actor(req) else: id_ = self._spawn_actor(req) - self._registered_actors.append(id_) - return SpawnObjectResponse(id_, "") - + response.id = id_ except Exception as e: - self.logwarn("Error spawning object '{}: {}".format(req.type, e)) - return SpawnObjectResponse(-1, str(e)) + self.logwarn("Error spawning object '{}': {}".format(req.type, e)) + response.id = -1 + response.error_string = str(e) + return response def _destroy_actor(self, uid): if uid not in self.actor_factory.actors: @@ -336,10 +341,12 @@ def _synchronous_mode_update(self): self.status_publisher.set_frame(frame) self.update_clock(world_snapshot.timestamp) - self.logdebug("Tick for frame {} returned. Waiting for sensor data...".format(frame)) - self._update(frame, world_snapshot.timestamp.elapsed_seconds) + self.logdebug("Tick for frame {} returned. Waiting for sensor data...".format( + frame)) + with self.actor_factory.lock: + self._update(frame, world_snapshot.timestamp.elapsed_seconds) self.logdebug("Waiting for sensor data finished.") - self._update_actors(set([x.id for x in world_snapshot])) + self.actor_factory.update() if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: # wait for all ego vehicles to send a vehicle control command @@ -425,6 +432,7 @@ def destroy(self): :return: """ + self.loginfo("Shutting down...") self.debug_helper.destroy() self.shutdown.set() destroy_subscription(self.carla_weather_subscriber) @@ -440,7 +448,6 @@ def destroy(self): self._destroy_actor(uid) self.actor_factory.clear() - self.loginfo("Exiting Bridge") super(CarlaRosBridge, self).destroy() diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 96e4b828..3ddfbbb5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -80,7 +80,7 @@ def _build_camera_info(self): """ camera_info = CameraInfo() # store info without header - camera_info.header = None + camera_info.header = self.get_msg_header() camera_info.width = int(self.carla_actor.attributes['image_size_x']) camera_info.height = int(self.carla_actor.attributes['image_size_y']) camera_info.distortion_model = 'plumb_bob' @@ -116,28 +116,6 @@ def sensor_data_updated(self, carla_camera_data): self.camera_info_publisher.publish(cam_info) self.camera_image_publisher.publish(img_msg) - def get_ros_transform(self, transform=None, frame_id=None, child_frame_id=None): - """ - Function (override) to modify the tf messages sent by this camera. - - The camera transformation has to be altered to look at the same axis - as the opencv projection in order to get easy depth cloud for RGBD camera - - :return: the filled tf message - :rtype: geometry_msgs.msg.TransformStamped - """ - tf_msg = super(Camera, self).get_ros_transform(transform, frame_id, child_frame_id) - rotation = tf_msg.transform.rotation - quat = [rotation.x, rotation.y, rotation.z, rotation.w] - - if ROS_VERSION == 1: - quat_swap = quaternion_from_matrix([[0, 0, 1, 0], [-1, 0, 0, 0], - [0, -1, 0, 0], [0, 0, 0, 1]]) - elif ROS_VERSION == 2: - quat_swap = quaternion_from_matrix( - numpy.asarray([numpy.asarray([0, 0, 1]), numpy.asarray([-1, 0, 0]), - numpy.asarray([0, -1, 0])])) - def get_ros_image(self, carla_camera_data): """ Function to transform the received carla camera data into a ROS image message diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 2464cfe1..5ef650d4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -76,7 +76,7 @@ def __init__(self, uid, name, parent, node, carla_actor, vehicle_control_applied self.vehicle_control_override = False self._vehicle_control_applied_callback = vehicle_control_applied_callback - self.vehicle_status_publisher = ( + self.vehicle_status_publisher = node.new_publisher( CarlaEgoVehicleStatus, self.get_topic_prefix() + "/vehicle_status") self.vehicle_info_publisher = node.new_publisher(CarlaEgoVehicleInfo, @@ -208,8 +208,6 @@ def destroy(self): self.control_subscriber = None destroy_subscription(self.enable_autopilot_subscriber) self.enable_autopilot_subscriber = None - self.twist_control_subscriber.unregister() - self.twist_control_subscriber = None destroy_subscription(self.control_override_subscriber) self.control_override_subscriber = None destroy_subscription(self.manual_control_subscriber) diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index 6e686dd7..c5e6d1f3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -49,8 +49,7 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy synchronous_mode=synchronous_mode) self.gnss_publisher = node.new_publisher(NavSatFix, - self.get_topic_prefix(), - queue_size=10) + self.get_topic_prefix()) self.listen() # pylint: disable=arguments-differ diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 829c479b..0176b7fe 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -48,7 +48,7 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy carla_actor=carla_actor, synchronous_mode=synchronous_mode) - self.imu_publisher = node.new_publisher(Imu, self.get_topic_prefix(), queue_size=10) + self.imu_publisher = node.new_publisher(Imu, self.get_topic_prefix()) self.listen() # pylint: disable=arguments-differ diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 6655067e..e3e096fc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -15,7 +15,7 @@ from sensor_msgs.msg import PointCloud2, PointField -from carla_ros_bridge.sensor import Sensor +from carla_ros_bridge.sensor import Sensor, create_cloud from ros_compatibility import quaternion_from_euler, euler_from_quaternion diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 1405641e..1bc73956 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -42,8 +42,7 @@ def __init__(self, uid, name, parent, node): node=node) self.odometry_publisher = node.new_publisher(Odometry, - self.get_topic_prefix(), - queue_size=10) + self.get_topic_prefix()) @staticmethod def get_blueprint_name(): diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 8278925c..09478e1f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -15,6 +15,7 @@ from std_msgs.msg import String +from ros_compatibility import QoSProfile, latch_on class OpenDriveSensor(PseudoActor): @@ -44,8 +45,7 @@ def __init__(self, uid, name, parent, node, carla_map): self.carla_map = carla_map self._map_published = False self.map_publisher = node.new_publisher(String, self.get_topic_prefix(), - queue_size=10, - latch=True) + qos_profile=QoSProfile(depth=10, durability=latch_on)) @staticmethod def get_blueprint_name(): @@ -60,5 +60,5 @@ def update(self, frame, timestamp): Function (override) to update this object. """ if not self._map_published: - self.map_publisher.publish(String(self.carla_map.to_opendrive())) + self.map_publisher.publish(String(data=self.carla_map.to_opendrive())) self._map_published = True diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index ac539ec2..62ffd206 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -17,9 +17,10 @@ except ImportError: import Queue as queue +import tf2_ros from carla_ros_bridge.actor import Actor import carla_common.transforms as trans -from ros_compatibility import ros_ok +from ros_compatibility import ros_ok, ros_timestamp from sensor_msgs.msg import PointCloud2, PointField _DATATYPES = {} @@ -51,7 +52,7 @@ def __init__(self, # pylint: disable=too-many-arguments # if a sensor only delivers data on special events, # do not wait for it. That means you might get data from a # sensor, that belongs to a different frame - prefix=None): + ): """ Constructor @@ -90,7 +91,7 @@ def __init__(self, # pylint: disable=too-many-arguments except (KeyError, ValueError): self.sensor_tick_time = None - self._tf_broadcaster = tf2_ros.TransformBroadcaster() + self._tf_broadcaster = tf2_ros.TransformBroadcaster(node) def publish_tf(self, pose=None): if self.synchronous_mode: @@ -106,8 +107,8 @@ def publish_tf(self, pose=None): frame_id = "map" if pose is not None: - transform = TransformStamped() - transform.header.stamp = ros_timestamp(sec=self.node.get_time, from_sec=True) + transform = tf2_ros.TransformStamped() + transform.header.stamp = ros_timestamp(sec=self.node.get_time(), from_sec=True) transform.header.frame_id = frame_id transform.child_frame_id = child_frame_id diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 7056a9fe..721cf80b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -68,4 +68,4 @@ def update(self, frame, timestamp): ]) speed = np.dot(vel_np, orientation) - self.speedometer_publisher.publish(Float32(speed)) + self.speedometer_publisher.publish(Float32(data=speed)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index d66eeaf7..18bf941a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -11,6 +11,8 @@ import os from carla_ros_bridge.pseudo_actor import PseudoActor +from ros_compatibility import ros_timestamp +from geometry_msgs.msg import TransformStamped, Transform ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -46,7 +48,7 @@ def __init__(self, uid, name, parent, node): parent=parent, node=node) - self.tf_broadcaster = tf.TransformBroadcaster() + self.tf_broadcaster = tf2_ros.TransformBroadcaster(node) @staticmethod def get_blueprint_name(): @@ -60,10 +62,8 @@ def update(self, frame, timestamp): """ Function (override) to update this object. """ - pose = self.parent.get_current_ros_pose() - position = pose.position - orientation = pose.orientation - self.tf_broadcaster.sendTransform( - (position.x, position.y, position.z), - (orientation.x, orientation.y, orientation.z, orientation.w), - ros_timestamp(self.ros_node.get_time(), from_sec=True), self.parent.get_prefix(), "map") + self.parent.get_prefix() + self.tf_broadcaster.sendTransform(TransformStamped( + header=self.get_msg_header("map"), + child_frame_id=self.parent.get_prefix(), + transform=self.parent.get_current_ros_transform())) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 3dc3e96c..2a7317bf 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -97,7 +97,7 @@ def get_info(self): info = CarlaTrafficLightInfo() info.id = self.get_id() info.transform = self.get_current_ros_pose() - info.trigger_volume.center = trans.carla_location_to_ros_point( + info.trigger_volume.center = trans.carla_location_to_ros_vector3( self.carla_actor.trigger_volume.location) info.trigger_volume.size.x = self.carla_actor.trigger_volume.extent.x * 2.0 info.trigger_volume.size.y = self.carla_actor.trigger_volume.extent.y * 2.0 diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index 6f20598c..cb32b791 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -58,23 +58,8 @@ def update(self, frame, timestamp): :return: """ self.classification_age += 1 - self.publish_transform(self.get_ros_transform(None, None, str(self.get_id()))) - self.publish_marker() - self.send_odometry() - super(TrafficParticipant, self).update(frame, timestamp) - def send_odometry(self): - """ - Sends odometry - :return: - """ - odometry = Odometry(header=self.get_msg_header("map")) - odometry.child_frame_id = self.get_prefix() - odometry.pose.pose = self.get_current_ros_pose() - odometry.twist.twist = self.get_current_ros_twist_rotated() - self.odometry_publisher.publish(odometry) - def get_object_info(self): """ Function to send object messages of this traffic participant. diff --git a/carla_spawn_objects/launch/carla_spawn_objects.launch.py b/carla_spawn_objects/launch/carla_spawn_objects.launch.py index 9e9bd1a6..0778b1c2 100644 --- a/carla_spawn_objects/launch/carla_spawn_objects.launch.py +++ b/carla_spawn_objects/launch/carla_spawn_objects.launch.py @@ -25,6 +25,7 @@ def generate_launch_description(): executable='carla_spawn_objects', name='carla_spawn_objects', output='screen', + emulate_tty=True, parameters=[ { 'objects_definition_file': launch.substitutions.LaunchConfiguration('objects_definition_file') diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index ff7b18a1..698dc9bf 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -33,7 +33,8 @@ CompatibleNode, ROSInterruptException, ServiceException, - quaternion_from_euler + quaternion_from_euler, + ros_init ) ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -56,8 +57,8 @@ class CarlaSpawnObjects(CompatibleNode): def __init__(self): super(CarlaSpawnObjects, self).__init__('carla_spawn_objects') - self.objects_definition_file = self.get_param('~objects_definition_file') - self.spawn_sensors_only = self.get_param('~spawn_sensors_only', None) + self.objects_definition_file = self.get_param('objects_definition_file') + self.spawn_sensors_only = self.get_param('spawn_sensors_only', None) self.players = [] self.vehicles_sensors = [] @@ -75,10 +76,9 @@ def spawn_objects(self): :return: """ # Read sensors from file - if not os.path.exists(self.objects_definition_file): + if not self.objects_definition_file or not os.path.exists(self.objects_definition_file): raise RuntimeError( - "Could not read sensor-definition from {}".format(self.objects_definition_file)) - json_sensors = None + "Could not read object definitions from {}".format(self.objects_definition_file)) with open(self.objects_definition_file) as handle: json_actors = json.loads(handle.read()) @@ -138,7 +138,10 @@ def setup_vehicles(self, vehicles): raise Exception( "Setting up sensors of already spawned vehicle {} failed with error: {}".format(vehicle["id"], e)) else: - spawn_object_request = SpawnObjectRequest() + if ROS_VERSION == 1: + spawn_object_request = SpawnObjectRequest() + elif ROS_VERSION == 2: + spawn_object_request = SpawnObject.Request() spawn_object_request.type = vehicle["type"] spawn_object_request.id = vehicle["id"] spawn_object_request.attach_to = 0 @@ -180,11 +183,12 @@ def setup_vehicles(self, vehicles): self.loginfo("Spawn point selected at random") spawn_point = Pose() # empty pose spawn_object_request.random_pose = True - + player_spawned = False while not player_spawned: spawn_object_request.transform = spawn_point - response = self.spawn_object_service(spawn_object_request) + + response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id != -1: player_spawned = True players.append(response.id) @@ -243,7 +247,10 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): spawn_point.pop("pitch", 0.0), spawn_point.pop("yaw", 0.0)) - spawn_object_request = SpawnObjectRequest() + if ROS_VERSION == 1: + spawn_object_request = SpawnObjectRequest() + elif ROS_VERSION == 2: + spawn_object_request = SpawnObject.Request() spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id spawn_object_request.attach_to = attached_vehicle_id @@ -252,9 +259,9 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): for attribute, value in sensor_spec.items(): spawn_object_request.attributes.append( - KeyValue(str(attribute), str(value))) + KeyValue(key=str(attribute), value=str(value))) - response = self.spawn_object_service(spawn_object_request) + response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id == -1: raise Exception(response.error_string) @@ -276,7 +283,7 @@ def create_spawn_point(self, x, y, z, roll, pitch, yaw): spawn_point.position.x = x spawn_point.position.y = y spawn_point.position.z = z - quat = trans.quaternion_from_euler( + quat = quaternion_from_euler( math.radians(roll), math.radians(pitch), math.radians(yaw)) @@ -305,11 +312,15 @@ def destroy(self): """ destroy all the players and sensors """ + self.loginfo("Shutting down...") # destroy global sensors for actor_id in self.global_sensors: - destroy_object_request = DestroyObjectRequest(actor_id) + if ROS_VERSION == 1: + destroy_object_request = DestroyObjectRequest(actor_id) + elif ROS_VERSION == 2: + destroy_object_request = DestroyObject.Request(actor_id) try: - response = self.destroy_object_service(destroy_object_request) + self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: self.logwarn_once(str(e)) self.global_sensors = [] @@ -317,18 +328,24 @@ def destroy(self): # destroy vehicles sensors for vehicle_sensors_id in self.vehicles_sensors: for actor_id in vehicle_sensors_id: - destroy_object_request = DestroyObjectRequest(actor_id) + if ROS_VERSION == 1: + destroy_object_request = DestroyObjectRequest(actor_id) + elif ROS_VERSION == 2: + destroy_object_request = DestroyObject.Request(actor_id) try: - response = self.destroy_object_service(destroy_object_request) + self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: self.logwarn_once(str(e)) self.vehicles_sensors = [] # destroy player for player_id in self.players: - destroy_object_request = DestroyObjectRequest(player_id) + if ROS_VERSION == 1: + destroy_object_request = DestroyObjectRequest(player_id) + elif ROS_VERSION == 2: + destroy_object_request = DestroyObject.Request(player_id) try: - self.destroy_object_service(destroy_object_request) + self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: self.logwarn_once(str(e)) self.players = [] @@ -349,10 +366,11 @@ def run(self): # ============================================================================== -def main(): +def main(args=None): """ main function """ + ros_init(args) spawn_objects_node = None try: spawn_objects_node = CarlaSpawnObjects() From 6ab876e49120548b05ec5a1a6cd23d93c8965df9 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 17 Dec 2020 15:21:26 +0100 Subject: [PATCH 438/627] Fix ros1 issues --- .../src/carla_manual_control/carla_manual_control.py | 7 +++---- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 1 + .../src/carla_ros_bridge/pseudo_actor.py | 8 ++++---- carla_ros_bridge/src/carla_ros_bridge/sensor.py | 11 +++++++++-- carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py | 12 ++++++------ carla_ros_scenario_runner/CMakeLists.txt | 2 +- carla_spawn_objects/CMakeLists.txt | 3 ++- 7 files changed, 26 insertions(+), 18 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 37c705a1..de63a015 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -52,6 +52,7 @@ if ROS_VERSION == 1: import rospy + from rospy import Time from tf import LookupException from tf import ConnectivityException from tf import ExtrapolationException @@ -467,14 +468,12 @@ def update_info_text(self): if not self._show_info: return try: - if ROS_VERSION == 1: (position, quaternion) = self.tf_listener.lookupTransform( - 'map', self.role_name, Time()) + '/map', self.role_name, Time()) elif ROS_VERSION == 2: (position, quaternion) = self.tf_buffer.lookup_transform( - target_frame='map', source_frame=self.role_name, time=Time()) - + source_frame='map', target_frame=self.role_name, time=Time()) _, _, yaw = euler_from_quaternion(quaternion) yaw = -math.degrees(yaw) x = position[0] diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 358a89b0..cd1b9382 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -432,6 +432,7 @@ def destroy(self): :return: """ + #TODO fix if carla is not running self.loginfo("Shutting down...") self.debug_helper.destroy() self.shutdown.set() diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index b36c0cc4..02c229fe 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -78,10 +78,10 @@ def get_msg_header(self, frame_id=None, timestamp=None): header.frame_id = frame_id else: header.frame_id = self.get_prefix() - if timestamp: - header.stamp = ros_timestamp(sec=timestamp, from_sec=True) - else: - header.stamp = self.node.ros_timestamp + + if not timestamp: + timestamp = self.node.get_time() + header.stamp = ros_timestamp(sec=timestamp, from_sec=True) return header def get_prefix(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 62ffd206..9c15f636 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -8,8 +8,10 @@ """ Classes to handle Carla sensors """ +from __future__ import print_function from abc import abstractmethod import ctypes +import os import struct import sys try: @@ -23,6 +25,8 @@ from ros_compatibility import ros_ok, ros_timestamp from sensor_msgs.msg import PointCloud2, PointField +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + _DATATYPES = {} _DATATYPES[PointField.INT8] = ('b', 1) _DATATYPES[PointField.UINT8] = ('B', 1) @@ -91,7 +95,10 @@ def __init__(self, # pylint: disable=too-many-arguments except (KeyError, ValueError): self.sensor_tick_time = None - self._tf_broadcaster = tf2_ros.TransformBroadcaster(node) + if ROS_VERSION == 1: + self._tf_broadcaster = tf2_ros.TransformBroadcaster() + elif ROS_VERSION == 2: + self._tf_broadcaster = tf2_ros.TransformBroadcaster(node) def publish_tf(self, pose=None): if self.synchronous_mode: @@ -234,7 +241,7 @@ def _get_struct_fmt(is_bigendian, fields, field_names=None): fmt += 'x' * (field.offset - offset) offset = field.offset if field.datatype not in _DATATYPES: - print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr) + print('Skipping unknown PointField datatype [{}]' % field.datatype, file=sys.stderr) else: datatype_fmt, datatype_length = _DATATYPES[field.datatype] fmt += field.count * datatype_fmt diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 18bf941a..065c5c46 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -16,10 +16,7 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -if ROS_VERSION == 1: - import tf -elif ROS_VERSION == 2: - import tf2_ros +import tf2_ros @@ -48,7 +45,10 @@ def __init__(self, uid, name, parent, node): parent=parent, node=node) - self.tf_broadcaster = tf2_ros.TransformBroadcaster(node) + if ROS_VERSION == 1: + self._tf_broadcaster = tf2_ros.TransformBroadcaster() + elif ROS_VERSION == 2: + self._tf_broadcaster = tf2_ros.TransformBroadcaster(node) @staticmethod def get_blueprint_name(): @@ -63,7 +63,7 @@ def update(self, frame, timestamp): Function (override) to update this object. """ self.parent.get_prefix() - self.tf_broadcaster.sendTransform(TransformStamped( + self._tf_broadcaster.sendTransform(TransformStamped( header=self.get_msg_header("map"), child_frame_id=self.parent.get_prefix(), transform=self.parent.get_current_ros_transform())) diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt index feb890a4..b3bbe915 100644 --- a/carla_ros_scenario_runner/CMakeLists.txt +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -18,7 +18,7 @@ if(${ROS_VERSION} EQUAL 1) catkin_install_python( PROGRAMS - src/carla_ros_scenario_runner/carla_ros_scenario_runner.py + src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py src/carla_ros_scenario_runner/application_runner.py src/carla_ros_scenario_runner/scenario_runner_runner.py src/carla_ros_scenario_runner/ros_vehicle_control.py diff --git a/carla_spawn_objects/CMakeLists.txt b/carla_spawn_objects/CMakeLists.txt index 08715dd1..9b78f40b 100644 --- a/carla_spawn_objects/CMakeLists.txt +++ b/carla_spawn_objects/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(carla_ego_vehicle) +project(carla_spawn_objects) find_package(ros_environment REQUIRED) set(ROS_VERSION $ENV{ROS_VERSION}) @@ -28,6 +28,7 @@ if(${ROS_VERSION} EQUAL 1) DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) elseif(${ROS_VERSION} EQUAL 2) +#TODO: not needed? find_package(ament_cmake REQUIRED) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) From 00df48e3091ff9e01b59b831d818c829314bc33b Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 17 Dec 2020 18:34:40 +0100 Subject: [PATCH 439/627] manual_control: Fix gnss and map-location --- .../carla_manual_control.py | 24 ++++++++++++------- 1 file changed, 15 insertions(+), 9 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index de63a015..4e7d1c54 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -389,7 +389,7 @@ def __init__(self, role_name, width, height): self.manual_control = False self.gnss_subscriber = self.create_subscriber( - NavSatFix, "/carla/{}/gnss/gnss1/fix".format(self.role_name), self.gnss_updated, + NavSatFix, "/carla/{}/gnss".format(self.role_name), self.gnss_updated, callback_group=self.callback_group) self.manual_control_subscriber = self.create_subscriber( @@ -469,18 +469,24 @@ def update_info_text(self): return try: if ROS_VERSION == 1: - (position, quaternion) = self.tf_listener.lookupTransform( + (position, rotation) = self.tf_listener.lookupTransform( '/map', self.role_name, Time()) elif ROS_VERSION == 2: - (position, quaternion) = self.tf_buffer.lookup_transform( - source_frame='map', target_frame=self.role_name, time=Time()) - _, _, yaw = euler_from_quaternion(quaternion) - yaw = -math.degrees(yaw) + transform = self.tf_buffer.lookup_transform( + target_frame='map', source_frame=self.role_name, time=Time()) + position = [transform.transform.translation.x, + transform.transform.translation.y, + transform.transform.translation.z] + rotation = [transform.transform.rotation.x, + transform.transform.rotation.y, + transform.transform.rotation.z, + transform.transform.rotation.w] + _, _, yaw = euler_from_quaternion(rotation) + yaw = math.degrees(yaw) x = position[0] - y = -position[1] + y = position[1] z = position[2] - except (LookupException, ConnectivityException, ExtrapolationException) as e: - print(e) + except (LookupException, ConnectivityException, ExtrapolationException): x = 0 y = 0 z = 0 From f1a85a57b3d5eb59f1721cb49244dac7185a83c2 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 17 Dec 2020 19:31:45 +0100 Subject: [PATCH 440/627] Fix carla_ad_demo --- carla_ad_demo/launch/carla_ad_demo.launch.py | 6 ++--- .../carla_ad_demo_with_scenario.launch.py | 6 ++--- .../carla_spectator_camera.py | 12 ++++++++-- .../launch/carla_waypoint_publisher.launch.py | 6 ++--- .../carla_waypoint_publisher.py | 24 +++++++++---------- 5 files changed, 30 insertions(+), 24 deletions(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 4b9d84d6..eebdf290 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -80,11 +80,11 @@ def generate_launch_description(): launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( - 'carla_spawn_actors'), 'carla_example_ego_vehicle.launch.py') + 'carla_spawn_objects'), 'carla_example_ego_vehicle.launch.py') ), launch_arguments={ - 'object_definition_file': get_package_share_directory('carla_spawn_actors') + '/config/sensors.json', - 'role_name_' + launch.substitutions.LaunchConfiguration('role_name'): launch.substitutions.LaunchConfiguration('role_name'), + 'object_definition_file': get_package_share_directory('carla_spawn_objects') + '/config/sensors.json', + 'role_name_' + str(launch.substitutions.LaunchConfiguration('role_name')): launch.substitutions.LaunchConfiguration('role_name'), 'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point') }.items() ), diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index 1288a9ac..e7c053a6 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -109,11 +109,11 @@ def generate_launch_description(): launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( - 'carla_spawn_actors'), 'carla_example_ego_vehicle.launch.py') + 'carla_spawn_objects'), 'carla_example_ego_vehicle.launch.py') ), launch_arguments={ - 'object_definition_file': get_package_share_directory('carla_spawn_actors') + '/config/objects.json', - 'role_name_' + launch.substitutions.LaunchConfiguration('role_name'): launch.substitutions.LaunchConfiguration('role_name') + 'object_definition_file': get_package_share_directory('carla_spawn_objects') + '/config/objects.json', + 'role_name_' + str(launch.substitutions.LaunchConfiguration('role_name')): launch.substitutions.LaunchConfiguration('role_name') }.items() ), launch.actions.IncludeLaunchDescription( diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 314f39f9..bf3e4c36 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -10,7 +10,7 @@ The pose of the camera can be changed by publishing to /carla//spectator_position. """ - +import os import sys import carla @@ -30,6 +30,11 @@ ROSInterruptException, ros_init ) + +ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) + +if ROS_VERSION == 1: + from carla_msgs.srv import SpawnObjectRequest, DestroyObjectRequest # ============================================================================== # -- CarlaSpectatorCamera ------------------------------------------------------------ # ============================================================================== @@ -113,7 +118,10 @@ def create_camera(self, ego_actor): if not transform: transform = carla.Transform() - spawn_object_request = SpawnObjectRequest() + if ROS_VERSION == 1: + spawn_object_request = SpawnObjectRequest() + elif ROS_VERSION == 2: + spawn_object_request = SpawnObject.Request() spawn_object_request.type = "sensor.camera.rgb" spawn_object_request.id = "spectator_view" spawn_object_request.attach_to = ego_actor.id diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py index 4a334e6c..887af064 100644 --- a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py @@ -31,13 +31,13 @@ def generate_launch_description(): emulate_tty='True', parameters=[ { - '/carla/host': launch.substitutions.LaunchConfiguration('host') + 'host': launch.substitutions.LaunchConfiguration('host') }, { - '/carla/port': launch.substitutions.LaunchConfiguration('port') + 'port': launch.substitutions.LaunchConfiguration('port') }, { - '/carla/timeout': launch.substitutions.LaunchConfiguration('timeout') + 'timeout': launch.substitutions.LaunchConfiguration('timeout') }, { 'role_name': launch.substitutions.LaunchConfiguration('role_name') diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 207b43a9..61052475 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -28,7 +28,8 @@ QoSProfile, ROSException, ros_timestamp, - latch_on) + latch_on, + ros_init) from nav_msgs.msg import Path from geometry_msgs.msg import PoseStamped import carla_common.transforms as trans @@ -71,14 +72,14 @@ def __init__(self): Path, '/carla/{}/waypoints'.format(self.role_name), QoSProfile(depth=1, durability=True)) # initialize ros services - self.getWaypointService = self.new_service( + self.get_waypoint_service = self.new_service( GetWaypoint, '/carla_waypoint_publisher/{}/get_waypoint'.format(self.role_name), self.get_waypoint) - self.getActorWaypointService = self.new_service( + self.get_actor_waypoint_service = self.new_service( GetActorWaypoint, '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(self.role_name), - GetActorWaypoint, self.get_actor_waypoint) + self.get_actor_waypoint) # set initial goal self.goal = self.world.get_map().get_spawn_points()[0] @@ -133,11 +134,11 @@ def get_actor_waypoint(self, req, response=None): if ROS_VERSION == 1: response = GetActorWaypointResponse() + else: + response = GetActorWaypoint.Response() if actor: carla_waypoint = self.map.get_waypoint(actor.get_location()) - response.waypoint.pose.position.x = carla_waypoint.transform.location.x - response.waypoint.pose.position.y = -carla_waypoint.transform.location.y - response.waypoint.pose.position.z = carla_waypoint.transform.location.z + response.waypoint.pose = trans.carla_transform_to_ros_pose(carla_waypoint.transform) response.waypoint.is_junction = carla_waypoint.is_junction response.waypoint.road_id = carla_waypoint.road_id response.waypoint.section_id = carla_waypoint.section_id @@ -253,9 +254,9 @@ def connect_to_carla(self): self.logerr("Error while waiting for world info!") sys.exit(1) - host = self.get_param("carla/host", "127.0.0.1") - port = self.get_param("carla/port", 2000) - timeout = self.get_param("carla/timeout", 10) + host = self.get_param("host", "127.0.0.1") + port = self.get_param("port", 2000) + timeout = self.get_param("timeout", 10) self.loginfo("CARLA world available. Trying to connect to {host}:{port}".format( host=host, port=port)) @@ -266,9 +267,6 @@ def connect_to_carla(self): self.loginfo("Connected to Carla.") - waypointConverter = CarlaToRosWaypointConverter(carla_world) - - def main(args=None): """ main function From 015cbbbec33cad4566cce887a09939cb8602bda0 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 18 Dec 2020 08:34:44 +0100 Subject: [PATCH 441/627] Update to latest ci --- .github/workflows/ci.yml | 4 +-- .travis.yml | 53 ++++------------------------------------ 2 files changed, 7 insertions(+), 50 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 42da6094..3680f3ca 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -23,7 +23,7 @@ jobs: container: ros:${{ matrix.ros-version }}-robot strategy: matrix: - ros-version: [melodic, noetic] + ros-version: [melodic, noetic, foxy] env: SCENARIO_RUNNER_PATH: "" DEBIAN_FRONTEND: "noninteractive" @@ -62,7 +62,7 @@ jobs: container: ros:${{ matrix.ros-version }}-robot strategy: matrix: - ros-version: [melodic, noetic] + ros-version: [melodic, noetic, foxy] env: SCENARIO_RUNNER_PATH: "" DEBIAN_FRONTEND: "noninteractive" diff --git a/.travis.yml b/.travis.yml index 09cd8bb3..15e1bb1a 100644 --- a/.travis.yml +++ b/.travis.yml @@ -26,53 +26,10 @@ jobs: env: - ROS_DISTRO=noetic - PYTHON_SUFFIX="3.7" - addons: - apt: - packages: - - python3-pip - - python3-pygame - - name: "Docker Kinetic" - stage: docker - services: docker - before_install: skip - install: skip - script: cd docker && ./build.sh --build-arg ROS_VERSION=kinetic - - name: "Docker Melodic" - services: docker - before_install: skip - install: skip - script: cd docker && ./build.sh --build-arg ROS_VERSION=melodic - - name: "Docker Noetic" - services: docker - before_install: skip - install: skip - script: cd docker && ./build.sh --build-arg ROS_VERSION=noetic --build-arg PYTHON_VERSION=3.7 - - name: "Docker Eloquent" - services: docker - before_install: skip - install: skip - script: docker build -t carla-ros-bridge -f docker/Dockerfile.eloquent ./.. - -before_install: - - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list' - - sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654 - - sudo apt update - - sudo apt install -y ros-$ROS_DISTRO-desktop-full python$PYTHON_SUFFIX-osrf-pycommon python$PYTHON_SUFFIX-catkin-tools python$PYTHON_SUFFIX-catkin-pkg python$PYTHON_SUFFIX-catkin-pkg-modules python$PYTHON_SUFFIX-rosdep python$PYTHON_SUFFIX-wstool - -install: - - pip$PYTHON_SUFFIX install --user -r requirements.txt - - mkdir ros-bridge/ - - shopt -s dotglob - - shopt -s extglob - - mv !(ros-bridge) ros-bridge/ - - mkdir -p catkin_ws/src - - cd catkin_ws/src - - ln -s ../../ros-bridge - - cd .. - - source /opt/ros/$ROS_DISTRO/setup.bash - - sudo rosdep init - - rosdep update - - rosdep install --from-paths src --ignore-src -r + - name: "Docker Foxy" + env: + - ROS_DISTRO=foxy + - PYTHON_SUFFIX="3.7" script: cd docker && ./build.sh --build-arg ROS_VERSION=$ROS_DISTRO --build-arg PYTHON_VERSION=$PYTHON_SUFFIX @@ -80,4 +37,4 @@ after_failure: - tail --lines=2000 build.log notifications: - email: false + email: false \ No newline at end of file From 85f148a100379db47e55d89097ee705a7b572b02 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 18 Dec 2020 08:38:12 +0100 Subject: [PATCH 442/627] Fix formatting --- carla_ad_agent/src/carla_ad_agent/basic_agent.py | 2 +- carla_common/src/carla_common/transforms.py | 1 + .../carla_manual_control/carla_manual_control.py | 14 +++++++------- .../src/carla_ros_bridge/actor_control.py | 9 +++++---- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 14 +++++++------- .../src/carla_ros_bridge/marker_sensor.py | 2 +- .../src/carla_ros_bridge/odom_sensor.py | 2 +- .../src/carla_ros_bridge/opendrive_sensor.py | 3 ++- .../src/carla_ros_bridge/pseudo_actor.py | 2 +- .../src/carla_ros_bridge/speedometer_sensor.py | 3 ++- carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py | 4 +--- .../carla_ros_scenario_runner_node.py | 4 ++-- carla_spawn_objects/CMakeLists.txt | 2 +- .../src/carla_spawn_objects/carla_spawn_objects.py | 11 ++++++----- .../carla_twist_to_control.py | 6 +++--- .../src/carla_walker_agent/carla_walker_agent.py | 6 +++--- .../carla_waypoint_publisher.py | 2 ++ .../src/ros_compatibility/ros_compatible_node.py | 2 +- 18 files changed, 47 insertions(+), 42 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 1d447cb5..60234ee6 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -85,7 +85,7 @@ def get_actor_waypoint(self, actor_id): Only used if risk should be avoided. """ try: - #TODO: have ros_compat get_service_request(GetActorWaypoint) + # TODO: have ros_compat get_service_request(GetActorWaypoint) if ROS_VERSION == 1: request = GetActorWaypointRequest() elif ROS_VERSION == 2: diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index d29914bd..e9974a0a 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -17,6 +17,7 @@ from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel # pylint: disable=import-error from ros_compatibility import euler_matrix, quaternion_from_euler, euler_from_quaternion + def carla_location_to_numpy_vector(carla_location): """ Convert a carla location to a ROS vector3 diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 4e7d1c54..38babee2 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -475,12 +475,12 @@ def update_info_text(self): transform = self.tf_buffer.lookup_transform( target_frame='map', source_frame=self.role_name, time=Time()) position = [transform.transform.translation.x, - transform.transform.translation.y, - transform.transform.translation.z] + transform.transform.translation.y, + transform.transform.translation.z] rotation = [transform.transform.rotation.x, - transform.transform.rotation.y, - transform.transform.rotation.z, - transform.transform.rotation.w] + transform.transform.rotation.y, + transform.transform.rotation.z, + transform.transform.rotation.w] _, _, yaw = euler_from_quaternion(rotation) yaw = math.degrees(yaw) x = position[0] @@ -497,7 +497,7 @@ def update_info_text(self): heading += 'W' if -0.5 > yaw > -179.5 else '' fps = 0 - #TODO + # TODO if ROS_VERSION == 1: time = str(datetime.timedelta(seconds=float(rospy.get_rostime().to_sec())))[:10] elif ROS_VERSION == 2: @@ -691,7 +691,7 @@ def main(args=None): main function """ ros_init(args) - #TODO + # TODO if ROS_VERSION == 1: rospy.init_node('carla_manual_control', anonymous=True) role_name = rospy.get_param("~role_name", "ego_vehicle") diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index 49e1c44c..d622c22b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -16,6 +16,7 @@ from carla import Vector3D from ros_compatibility import destroy_subscription + class ActorControl(PseudoActor): """ @@ -42,12 +43,12 @@ def __init__(self, uid, name, parent, node): node=node) self.set_location_subscriber = self.node.create_subscriber(Pose, - self.get_topic_prefix() + "/set_transform", - self.on_pose) + self.get_topic_prefix() + "/set_transform", + self.on_pose) self.twist_control_subscriber = self.node.create_subscriber(Twist, - self.get_topic_prefix() + "/set_target_velocity", - self.on_twist) + self.get_topic_prefix() + "/set_target_velocity", + self.on_twist) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index cd1b9382..4ca6189f 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -177,13 +177,13 @@ def initialize_bridge(self, carla_world, params): # services configuration. self._registered_actors = [] - self.spawn_object_service = self.new_service(SpawnObject, "/carla/spawn_object", - self.spawn_object) - self.destroy_object_service = self.new_service(DestroyObject, "/carla/destroy_object", - self.destroy_object) + self.spawn_object_service = self.new_service(SpawnObject, "/carla/spawn_object", + self.spawn_object) + self.destroy_object_service = self.new_service(DestroyObject, "/carla/destroy_object", + self.destroy_object) - self.get_blueprints_service = self.new_service(GetBlueprints, "/carla/get_blueprints", - self.get_blueprints) + self.get_blueprints_service = self.new_service(GetBlueprints, "/carla/get_blueprints", + self.get_blueprints) self.carla_weather_subscriber = \ self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", @@ -432,7 +432,7 @@ def destroy(self): :return: """ - #TODO fix if carla is not running + # TODO fix if carla is not running self.loginfo("Shutting down...") self.debug_helper.destroy() self.shutdown.set() diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index 26698a57..3386850d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -46,7 +46,7 @@ def __init__(self, uid, name, parent, node, actor_list): self.actor_list = actor_list self.marker_publisher = node.new_publisher(MarkerArray, - self.get_topic_prefix()) + self.get_topic_prefix()) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 1bc73956..4116b309 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -42,7 +42,7 @@ def __init__(self, uid, name, parent, node): node=node) self.odometry_publisher = node.new_publisher(Odometry, - self.get_topic_prefix()) + self.get_topic_prefix()) @staticmethod def get_blueprint_name(): diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 09478e1f..3df1100f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -17,6 +17,7 @@ from ros_compatibility import QoSProfile, latch_on + class OpenDriveSensor(PseudoActor): """ @@ -45,7 +46,7 @@ def __init__(self, uid, name, parent, node, carla_map): self.carla_map = carla_map self._map_published = False self.map_publisher = node.new_publisher(String, self.get_topic_prefix(), - qos_profile=QoSProfile(depth=10, durability=latch_on)) + qos_profile=QoSProfile(depth=10, durability=latch_on)) @staticmethod def get_blueprint_name(): diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index 02c229fe..b3bc9338 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -80,7 +80,7 @@ def get_msg_header(self, frame_id=None, timestamp=None): header.frame_id = self.get_prefix() if not timestamp: - timestamp = self.node.get_time() + timestamp = self.node.get_time() header.stamp = ros_timestamp(sec=timestamp, from_sec=True) return header diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 721cf80b..7862f5fb 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -15,6 +15,7 @@ from std_msgs.msg import Float32 + class SpeedometerSensor(PseudoActor): """ @@ -41,7 +42,7 @@ def __init__(self, uid, name, parent, node): node=node) self.speedometer_publisher = node.new_publisher(Float32, - self.get_topic_prefix()) + self.get_topic_prefix()) @staticmethod def get_blueprint_name(): diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 065c5c46..499a6bd4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -9,6 +9,7 @@ handle a tf sensor """ +import tf2_ros import os from carla_ros_bridge.pseudo_actor import PseudoActor from ros_compatibility import ros_timestamp @@ -16,9 +17,6 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) -import tf2_ros - - class TFSensor(PseudoActor): diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py index a07c82ab..5d02784e 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py @@ -26,8 +26,8 @@ from carla_ros_scenario_runner.scenario_runner_runner import ScenarioRunnerRunner # pylint: disable=relative-import from ros_compatibility import ( - CompatibleNode, - QoSProfile, + CompatibleNode, + QoSProfile, ros_ok, ros_init) diff --git a/carla_spawn_objects/CMakeLists.txt b/carla_spawn_objects/CMakeLists.txt index 9b78f40b..d89b8724 100644 --- a/carla_spawn_objects/CMakeLists.txt +++ b/carla_spawn_objects/CMakeLists.txt @@ -28,7 +28,7 @@ if(${ROS_VERSION} EQUAL 1) DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) elseif(${ROS_VERSION} EQUAL 2) -#TODO: not needed? + # TODO: not needed? find_package(ament_cmake REQUIRED) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 698dc9bf..71a42e40 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -65,7 +65,8 @@ def __init__(self): self.global_sensors = [] self.spawn_object_service = self.create_service_client("/carla/spawn_object", SpawnObject) - self.destroy_object_service = self.create_service_client("/carla/destroy_object", DestroyObject) + self.destroy_object_service = self.create_service_client( + "/carla/destroy_object", DestroyObject) def spawn_objects(self): """ @@ -160,7 +161,7 @@ def setup_vehicles(self, vehicles): spawn_param_used = True except Exception as e: self.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"]) + - "the spawn point from config file will be used. Error is: {}".format(e)) + "the spawn point from config file will be used. Error is: {}".format(e)) if "spawn_point" in vehicle and spawn_param_used is False: # get spawn point from config file @@ -176,18 +177,18 @@ def setup_vehicles(self, vehicles): self.loginfo("Spawn point from configuration file") except KeyError as e: self.logerr("{}: Could not use the spawn point from config file, ".format(vehicle["id"]) + - "the mandatory attribute {} is missing, a random spawn point will be used".format(e)) + "the mandatory attribute {} is missing, a random spawn point will be used".format(e)) if spawn_point is None: # pose not specified, ask for a random one in the service call self.loginfo("Spawn point selected at random") spawn_point = Pose() # empty pose spawn_object_request.random_pose = True - + player_spawned = False while not player_spawned: spawn_object_request.transform = spawn_point - + response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id != -1: player_spawned = True diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index 34e44bee..b90eb14b 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -10,9 +10,9 @@ use max wheel steer angle """ from ros_compatibility import ( - CompatibleNode, - ros_ok, - ROSException, + CompatibleNode, + ros_ok, + ROSException, ROSInterruptException, ros_init) import sys diff --git a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py index ffd500ff..de2a5c99 100755 --- a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py +++ b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py @@ -14,9 +14,9 @@ from geometry_msgs.msg import Pose, Vector3 from carla_msgs.msg import CarlaWalkerControl from ros_compatibility import ( - CompatibleNode, - QoSProfile, - ros_ok, + CompatibleNode, + QoSProfile, + ros_ok, ROSInterruptException, ros_init) diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 61052475..950ae508 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -46,6 +46,7 @@ if ROS_VERSION == 1: from carla_waypoint_types.srv import GetWaypointResponse, GetActorWaypointResponse + class CarlaToRosWaypointConverter(CompatibleNode): """ @@ -267,6 +268,7 @@ def connect_to_carla(self): self.loginfo("Connected to Carla.") + def main(args=None): """ main function diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 42fb7bb3..e795c85a 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -11,7 +11,7 @@ def ros_init(args=None): pass - + def ros_timestamp(sec=0, nsec=0, from_sec=False): if from_sec: return rospy.Time.from_sec(sec) From ca07f4dabf8e66b698d60564ed0725791ce1724b Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 18 Dec 2020 09:11:34 +0100 Subject: [PATCH 443/627] Cleanup imports --- carla_ros_bridge/src/carla_ros_bridge/actor_factory.py | 9 --------- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 3 --- .../src/carla_ros_bridge/opendrive_sensor.py | 2 -- .../src/carla_spawn_objects/carla_spawn_objects.py | 5 +---- .../src/carla_spectator_camera/carla_spectator_camera.py | 2 -- .../carla_waypoint_publisher/carla_waypoint_publisher.py | 3 +-- 6 files changed, 2 insertions(+), 22 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 9630480f..ecea68fd 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -6,19 +6,10 @@ # For a copy, see . # -try: - import queue -except ImportError: - import Queue as queue - import time from threading import Thread, Lock import itertools -import carla - -import carla_common.transforms as trans - from carla_ros_bridge.actor import Actor from carla_ros_bridge.spectator import Spectator from carla_ros_bridge.traffic import Traffic, TrafficLight diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 5ef650d4..bd4488e8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -13,11 +13,8 @@ import os import numpy -from geometry_msgs.msg import Twist, Transform # pylint: disable=import-error from std_msgs.msg import Bool # pylint: disable=import-error from std_msgs.msg import ColorRGBA # pylint: disable=import-error -import carla_common.transforms as transforms -from carla import Vector3D from carla import VehicleControl from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleStatus # pylint: disable=import-error diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 3df1100f..22b1805d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -9,8 +9,6 @@ handle a opendrive sensor """ -import numpy as np - from carla_ros_bridge.pseudo_actor import PseudoActor from std_msgs.msg import String diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 71a42e40..5639281c 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -15,16 +15,13 @@ """ -from abc import abstractmethod - import os -import sys import math import json from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import Pose -from carla_msgs.msg import CarlaWorldInfo, CarlaActorList +from carla_msgs.msg import CarlaActorList from carla_msgs.srv import SpawnObject, DestroyObject diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index bf3e4c36..30f8db5a 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -11,11 +11,9 @@ to /carla//spectator_position. """ import os -import sys import carla from geometry_msgs.msg import PoseStamped -from carla_msgs.msg import CarlaWorldInfo from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest from diagnostic_msgs.msg import KeyValue diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 950ae508..49810e5b 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -22,8 +22,7 @@ import threading import os -from ros_compatibility import (euler_from_quaternion, - quaternion_from_euler, +from ros_compatibility import (quaternion_from_euler, CompatibleNode, QoSProfile, ROSException, From a1d701ce0fc42437a8eee5771f204deeb0c5cc5f Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 18 Dec 2020 09:33:54 +0100 Subject: [PATCH 444/627] carla_spectator_camera use ros_compatibility --- .../carla_spectator_camera.py | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 30f8db5a..ba3c0cca 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -14,7 +14,7 @@ import carla from geometry_msgs.msg import PoseStamped -from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest +from carla_msgs.srv import SpawnObject, DestroyObject from diagnostic_msgs.msg import KeyValue import carla @@ -26,7 +26,8 @@ QoSProfile, ROSException, ROSInterruptException, - ros_init + ros_init, + ServiceException ) ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -126,12 +127,12 @@ def create_camera(self, ego_actor): spawn_object_request.transform = trans.carla_transform_to_ros_pose(transform) spawn_object_request.random_pose = False spawn_object_request.attributes.extend([ - KeyValue("image_size_x", str(self.camera_resolution_x)), - KeyValue("image_size_y", str(self.camera_resolution_y)), - KeyValue("fov", str(self.camera_fov)) + KeyValue(key="image_size_x", value=str(self.camera_resolution_x)), + KeyValue(key="image_size_y", value=str(self.camera_resolution_y)), + KeyValue(key="fov", value=str(self.camera_fov)) ]) - response = self.spawn_object_service(spawn_object_request) + response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id == -1: raise Exception(response.error_string) @@ -171,9 +172,9 @@ def destroy(self): if self.camera_actor: destroy_object_request = DestroyObjectRequest(self.camera_actor.id) try: - self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) + self.call_service(self.destroy_object_service,destroy_object_request) + except ServiceException as e: + self.logwarn_once(str(e)) self.camera_actor = None From f52b918f536fcf6a4b6a2178cffb02ccb2860918 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 21 Dec 2020 10:38:57 -0500 Subject: [PATCH 445/627] actor_factory update thread waits for world tick from inside spawn_lock --- carla_ros_bridge/src/carla_ros_bridge/actor_factory.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 59e1a2bb..f780577c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -78,8 +78,9 @@ def _update_thread(self): while not self.node.shutdown.is_set(): time.sleep(ActorFactory.TIME_BETWEEN_UPDATES) - self.world.wait_for_tick() + # self.world.wait_for_tick() with self.spawn_lock: + self.world.wait_for_tick() self.update() def update(self): From 74efdcf420767899b779456b33620a85129f52e2 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 21 Dec 2020 14:15:37 -0500 Subject: [PATCH 446/627] formatting --- carla_ros_bridge/src/carla_ros_bridge/actor_factory.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index f780577c..5b0a8569 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -77,8 +77,6 @@ def _update_thread(self): """ while not self.node.shutdown.is_set(): time.sleep(ActorFactory.TIME_BETWEEN_UPDATES) - - # self.world.wait_for_tick() with self.spawn_lock: self.world.wait_for_tick() self.update() From 032198b4a6610868c81a3d7fe39f111a0a4205da Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 21 Dec 2020 14:19:04 -0500 Subject: [PATCH 447/627] cannot iterate thorough a dictionary while deleting entries --- carla_ros_bridge/src/carla_ros_bridge/actor_factory.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 5b0a8569..6e0ad2d2 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -100,7 +100,7 @@ def update(self): def clear(self): ids = self.actors.keys() - for id_ in ids: + for id_ in list(ids): self.destroy(id_) def _create_carla_actor(self, carla_actor): From 2103f44add9af1f550f26c8ee6f0030e0ea45b02 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 22 Dec 2020 10:55:16 +0100 Subject: [PATCH 448/627] Fix datatype --- carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 43a67aaf..bdd41759 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -36,7 +36,7 @@ def __init__(self, synchronous_mode, fixed_delta_seconds, node): self.synchronous_mode_running = True self.fixed_delta_seconds = fixed_delta_seconds if self.fixed_delta_seconds is None: - self.fixed_delta_seconds = 0 + self.fixed_delta_seconds = 0. self.frame = 0 if ROS_VERSION == 1: callback_group = None From b215f51c45ec76829515150a9df4dc3e7b9c1f42 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 22 Dec 2020 14:27:40 +0100 Subject: [PATCH 449/627] Update CI --- .github/workflows/ci.yml | 25 ++++++++++++++++++------- packaging/build-deb.sh | 3 ++- packaging/install_dependencies.sh | 18 ++++++++++++------ 3 files changed, 32 insertions(+), 14 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 3680f3ca..ced44e48 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -20,10 +20,10 @@ jobs: ros: runs-on: ubuntu-latest - container: ros:${{ matrix.ros-version }}-robot + container: ros:${{ matrix.ros-version }} strategy: matrix: - ros-version: [melodic, noetic, foxy] + ros-version: [melodic-robot, noetic-robot, foxy] env: SCENARIO_RUNNER_PATH: "" DEBIAN_FRONTEND: "noninteractive" @@ -35,10 +35,12 @@ jobs: - name: Setup run: | sudo apt-get update && sudo apt-get install wget unzip -y - rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/master.zip - unzip master.zip -d carla_msgs && rm master.zip + #TODO: replace ros2 with master + rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip + unzip ros2.zip -d carla_msgs && rm ros2.zip packaging/install_dependencies.sh - name: Init Workspace + if: matrix.ros-version != 'foxy' run: | mkdir -p $GITHUB_WORKSPACE/../catkin_ws/src cd $GITHUB_WORKSPACE/../catkin_ws/src @@ -46,9 +48,18 @@ jobs: cd .. catkin init - name: Build, Test, Lint + if: matrix.ros-version == 'foxy' shell: bash run: | - source /opt/ros/${{ matrix.ros-version }}/setup.bash + source /opt/ros/$(rosversion -d)/setup.bash + colcon build --continue-on-error + colcon test && colcon test-result + source install/setup.bash + - name: Build, Test, Lint + if: matrix.ros-version != 'foxy' + shell: bash + run: | + source /opt/ros/$(rosversion -d)/setup.bash cd $GITHUB_WORKSPACE/../catkin_ws && catkin build --summarize --no-status --force-color catkin run_tests --no-status --force-color && catkin_test_results @@ -59,10 +70,10 @@ jobs: debian: runs-on: ubuntu-latest - container: ros:${{ matrix.ros-version }}-robot + container: ros:${{ matrix.ros-version }} strategy: matrix: - ros-version: [melodic, noetic, foxy] + ros-version: [melodic-robot, noetic-robot, foxy] env: SCENARIO_RUNNER_PATH: "" DEBIAN_FRONTEND: "noninteractive" diff --git a/packaging/build-deb.sh b/packaging/build-deb.sh index d8aebe25..b50b70f3 100755 --- a/packaging/build-deb.sh +++ b/packaging/build-deb.sh @@ -5,7 +5,8 @@ set -e SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" BUILD_DIR=${SCRIPT_DIR}/build/$(rosversion -d) WORKSPACE_DIR=${BUILD_DIR}/catkin_ws -if [ "$(rosversion -d)" = "noetic" ]; then +ROS_VERSION=$(rosversion -d) +if [ "$ROS_VERSION" = "noetic" -o "$ROS_VERSION" = "foxy" ]; then PYTHON_SUFFIX=3 else PYTHON_SUFFIX="" diff --git a/packaging/install_dependencies.sh b/packaging/install_dependencies.sh index 586b1aed..4d2a82a9 100755 --- a/packaging/install_dependencies.sh +++ b/packaging/install_dependencies.sh @@ -2,12 +2,22 @@ SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" ROS_VERSION=$(rosversion -d) -if [ "$ROS_VERSION" = "noetic" ]; then +if [ "$ROS_VERSION" = "noetic" -o "$ROS_VERSION" = "foxy" ]; then PYTHON_SUFFIX=3 else PYTHON_SUFFIX="" fi +if [ "$ROS_VERSION" = "foxy" ]; then + ADDITIONAL_PACKAGES="ros-$ROS_VERSION-rviz2" +else + ADDITIONAL_PACKAGES="ros-$ROS_VERSION-rviz + ros-$ROS_VERSION-opencv-apps + ros-$ROS_VERSION-rospy-message-converter + ros-$ROS_VERSION-pcl-ros" +fi +echo ADDITIONAL PACKAGES $ADDITIONAL_PACKAGES + sudo apt update sudo apt-get install --no-install-recommends -y \ python$PYTHON_SUFFIX-pip \ @@ -17,18 +27,14 @@ sudo apt-get install --no-install-recommends -y \ python$PYTHON_SUFFIX-catkin-pkg-modules \ python$PYTHON_SUFFIX-rosdep \ python$PYTHON_SUFFIX-wstool \ - ros-$ROS_VERSION-opencv-apps \ ros-$ROS_VERSION-ackermann-msgs \ ros-$ROS_VERSION-derived-object-msgs \ ros-$ROS_VERSION-cv-bridge \ ros-$ROS_VERSION-vision-opencv \ - ros-$ROS_VERSION-rospy-message-converter \ - ros-$ROS_VERSION-rviz \ ros-$ROS_VERSION-rqt-image-view \ ros-$ROS_VERSION-rqt-gui-py \ - ros-$ROS_VERSION-rviz \ qt5-default \ ros-$ROS_VERSION-pcl-conversions \ - ros-$ROS_VERSION-pcl-ros + $ADDITIONAL_PACKAGES pip$PYTHON_SUFFIX install -r $SCRIPT_DIR/../requirements.txt From 0bf3b908a991fa94131d7fe7a3b13de02199aab5 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 22 Dec 2020 15:09:28 +0100 Subject: [PATCH 450/627] Update carla_msgs submodule --- carla_msgs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_msgs b/carla_msgs index 3ca07f67..f75637ce 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit 3ca07f679667642369edccd89332eae6b37b2bd2 +Subproject commit f75637ce83a0b4e8fbd9818980c9b11570ff477c From 708cb7406d4eeffd5a43d7de6340928e14c8e59d Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Wed, 23 Dec 2020 10:04:50 +0100 Subject: [PATCH 451/627] Ros2 transforms cleanup (#447) Cleanup transformation functions, use transforms3d --- .../carla_control_physics.py | 8 +-- carla_ad_agent/src/carla_ad_agent/agent.py | 9 ++- .../carla_ad_agent/vehicle_pid_controller.py | 8 +-- carla_common/src/carla_common/transforms.py | 66 +++---------------- .../carla_manual_control.py | 10 +-- .../src/carla_ros_bridge/camera.py | 1 - .../src/carla_ros_bridge/debug_helper.py | 10 +-- carla_ros_bridge/src/carla_ros_bridge/imu.py | 10 ++- .../src/carla_ros_bridge/lidar.py | 2 - .../carla_spawn_objects.py | 17 ++--- .../carla_spectator_camera.py | 10 +-- .../carla_waypoint_publisher.py | 3 +- .../ros_compatibility/ros_compatible_node.py | 38 ----------- 13 files changed, 51 insertions(+), 141 deletions(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py b/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py index c4bfc1e6..c93fa4d4 100644 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_control_physics.py @@ -11,7 +11,7 @@ import math -from ros_compatibility import euler_from_quaternion +from transforms3d.euler import quat2euler def get_vehicle_lay_off_engine_acceleration(vehicle_info): @@ -182,9 +182,9 @@ def get_slope_force(vehicle_info, vehicle_status): :return: slope force [N, >0 uphill, <0 downhill] :rtype: float64 """ - dummy_roll, pitch, dummy_yaw = euler_from_quaternion( - [vehicle_status.orientation.x, vehicle_status.orientation.y, - vehicle_status.orientation.z, vehicle_status.orientation.w]) + dummy_roll, pitch, dummy_yaw = quat2euler( + [vehicle_status.orientation.w, vehicle_status.orientation.x, + vehicle_status.orientation.y, vehicle_status.orientation.z]) slope_force = get_acceleration_of_gravity( vehicle_info) * get_vehicle_mass(vehicle_info) * math.sin(-pitch) return slope_force diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 96fa2710..30f41bf2 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -14,9 +14,8 @@ from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus # pylint: disable=import-error from enum import Enum import math - +from transforms3d.euler import quat2euler from ros_compatibility import ( - euler_from_quaternion, ros_ok, ServiceException, ROSInterruptException, @@ -90,12 +89,12 @@ def odometry_updated(self, odo): """ self._vehicle_location = odo.pose.pose.position quaternion = ( + odo.pose.pose.orientation.w, odo.pose.pose.orientation.x, odo.pose.pose.orientation.y, - odo.pose.pose.orientation.z, - odo.pose.pose.orientation.w + odo.pose.pose.orientation.z ) - _, _, self._vehicle_yaw = euler_from_quaternion(quaternion) + _, _, self._vehicle_yaw = quat2euler(quaternion) def _is_light_red(self, lights_list): """ diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index f7811c39..f1e43b1b 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -11,7 +11,7 @@ from collections import deque import math import numpy as np -from ros_compatibility import euler_from_quaternion # pylint: disable=import-error +from transforms3d.euler import quat2euler from geometry_msgs.msg import Point # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error @@ -137,12 +137,12 @@ def run_step(self, current_pose, waypoint, dt): """ v_begin = current_pose.position quaternion = ( + current_pose.orientation.w, current_pose.orientation.x, current_pose.orientation.y, - current_pose.orientation.z, - current_pose.orientation.w + current_pose.orientation.z ) - _, _, yaw = euler_from_quaternion(quaternion) + _, _, yaw = quat2euler(quaternion) v_end = Point() v_end.x = v_begin.x + math.cos(yaw) v_end.y = v_begin.y + math.sin(yaw) diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index e9974a0a..300616b6 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -15,7 +15,7 @@ import carla from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel # pylint: disable=import-error -from ros_compatibility import euler_matrix, quaternion_from_euler, euler_from_quaternion +from transforms3d.euler import euler2mat, quat2euler, euler2quat def carla_location_to_numpy_vector(carla_location): @@ -77,23 +77,6 @@ def carla_location_to_ros_point(carla_location): return ros_point -def numpy_quaternion_to_ros_quaternion(numpy_quaternion): - """ - Convert a quaternion from transforms to a ROS msg quaternion - - :param numpy_quaternion: a numpy quaternion - :type numpy_quaternion: numpy.array - :return: a ROS quaternion - :rtype: geometry_msgs.msg.Quaternion - """ - ros_quaternion = Quaternion() - ros_quaternion.x = numpy_quaternion[0] - ros_quaternion.y = numpy_quaternion[1] - ros_quaternion.z = numpy_quaternion[2] - ros_quaternion.w = numpy_quaternion[3] - return ros_quaternion - - def carla_rotation_to_RPY(carla_rotation): """ Convert a carla rotation to a roll, pitch, yaw tuple @@ -114,25 +97,6 @@ def carla_rotation_to_RPY(carla_rotation): return (roll, pitch, yaw) -def carla_rotation_to_numpy_quaternion(carla_rotation): - """ - Convert a carla rotation to a numpy quaternion - - Considers the conversion from left-handed system (unreal) to right-handed - system (ROS). - Considers the conversion from degrees (carla) to radians (ROS). - - :param carla_rotation: the carla rotation - :type carla_rotation: carla.Rotation - :return: a numpy.array with 4 elements (quaternion) - :rtype: numpy.array - """ - roll, pitch, yaw = carla_rotation_to_RPY(carla_rotation) - quat = quaternion_from_euler(roll, pitch, yaw) - - return quat - - def carla_rotation_to_ros_quaternion(carla_rotation): """ Convert a carla rotation to a ROS quaternion @@ -146,9 +110,9 @@ def carla_rotation_to_ros_quaternion(carla_rotation): :return: a ROS quaternion :rtype: geometry_msgs.msg.Quaternion """ - quat = carla_rotation_to_numpy_quaternion(carla_rotation) - ros_quaternion = numpy_quaternion_to_ros_quaternion(quat) - + roll, pitch, yaw = carla_rotation_to_RPY(carla_rotation) + quat = euler2quat(roll, pitch, yaw) + ros_quaternion = Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3]) return ros_quaternion @@ -166,7 +130,7 @@ def carla_rotation_to_numpy_rotation_matrix(carla_rotation): :rtype: numpy.array """ roll, pitch, yaw = carla_rotation_to_RPY(carla_rotation) - numpy_array = euler_matrix(roll, pitch, yaw) + numpy_array = euler2mat(roll, pitch, yaw) rotation_matrix = numpy_array[:3, :3] return rotation_matrix @@ -335,25 +299,10 @@ def carla_location_to_pose(carla_location): return ros_pose -def RPY_to_ros_quaternion(roll, pitch, yaw): - quat = quaternion_from_euler(roll, pitch, yaw) - return Quaternion(*quat) - - def ros_point_to_carla_location(ros_point): return carla.Location(ros_point.x, -ros_point.y, ros_point.z) -def ros_quaternion_to_RPY(ros_quaternion): - quaternion = ( - ros_quaternion.x, - ros_quaternion.y, - ros_quaternion.z, - ros_quaternion.w - ) - return euler_from_quaternion(quaternion) - - def RPY_to_carla_rotation(roll, pitch, yaw): return carla.Rotation(roll=math.degrees(roll), pitch=-math.degrees(pitch), @@ -361,7 +310,10 @@ def RPY_to_carla_rotation(roll, pitch, yaw): def ros_quaternion_to_carla_rotation(ros_quaternion): - roll, pitch, yaw = ros_quaternion_to_RPY(ros_quaternion) + roll, pitch, yaw = quat2euler([ros_quaternion.w, + ros_quaternion.x, + ros_quaternion.y, + ros_quaternion.z]) return RPY_to_carla_rotation(roll, pitch, yaw) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 38babee2..9f187b03 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -36,10 +36,10 @@ from sensor_msgs.msg import Image from sensor_msgs.msg import NavSatFix from std_msgs.msg import Bool +from transforms3d.euler import quat2euler from ros_compatibility import ( CompatibleNode, latch_on, - euler_from_quaternion, ros_ok, ros_init, destroy_subscription) @@ -477,11 +477,11 @@ def update_info_text(self): position = [transform.transform.translation.x, transform.transform.translation.y, transform.transform.translation.z] - rotation = [transform.transform.rotation.x, + rotation = [transform.transform.rotation.w, + transform.transform.rotation.x, transform.transform.rotation.y, - transform.transform.rotation.z, - transform.transform.rotation.w] - _, _, yaw = euler_from_quaternion(rotation) + transform.transform.rotation.z] + _, _, yaw = quat2euler(rotation) yaw = math.degrees(yaw) x = position[0] y = position[1] diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 3ddfbbb5..6f2238d1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -20,7 +20,6 @@ import carla from carla_ros_bridge.sensor import Sensor, create_cloud import carla_common.transforms as trans -from ros_compatibility import quaternion_from_matrix, quaternion_multiply ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 321fc789..28106cef 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -14,8 +14,8 @@ from visualization_msgs.msg import Marker, MarkerArray # pylint: disable=import-error import carla - -from ros_compatibility import CompatibleNode, destroy_subscription, euler_from_quaternion +from transforms3d.euler import quat2euler +from ros_compatibility import CompatibleNode, destroy_subscription ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -144,9 +144,9 @@ def draw_box(self, marker, lifetime, color): box.extent.y = marker.scale.y / 2 box.extent.z = marker.scale.z / 2 - roll, pitch, yaw = euler_from_quaternion([ - marker.pose.orientation.x, marker.pose.orientation.y, marker.pose.orientation.z, - marker.pose.orientation.w + roll, pitch, yaw = quat2euler([ + marker.pose.orientation.w, marker.pose.orientation.x, marker.pose.orientation.y, marker.pose.orientation.z + ]) rotation = carla.Rotation() rotation.roll = math.degrees(roll) diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 0176b7fe..7c0b307a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -12,6 +12,7 @@ from sensor_msgs.msg import Imu from carla_ros_bridge.sensor import Sensor +from transforms3d.euler import euler2quat import carla_common.transforms as trans @@ -73,8 +74,11 @@ def sensor_data_updated(self, carla_imu_measurement): imu_msg.linear_acceleration.y = -carla_imu_measurement.accelerometer.y imu_msg.linear_acceleration.z = carla_imu_measurement.accelerometer.z - imu_rotation = carla_imu_measurement.transform.rotation + roll, pitch, yaw = trans.carla_rotation_to_RPY(carla_imu_measurement.transform.rotation) + quat = euler2quat(roll, pitch, yaw) + imu_msg.orientation.w = quat[0] + imu_msg.orientation.x = quat[1] + imu_msg.orientation.y = quat[2] + imu_msg.orientation.z = quat[3] - quat = trans.carla_rotation_to_numpy_quaternion(imu_rotation) - imu_msg.orientation = trans.numpy_quaternion_to_ros_quaternion(quat) self.imu_publisher.publish(imu_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index e3e096fc..1f62dfa5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -17,8 +17,6 @@ from carla_ros_bridge.sensor import Sensor, create_cloud -from ros_compatibility import quaternion_from_euler, euler_from_quaternion - class Lidar(Sensor): diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 5639281c..17f01bc3 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -24,13 +24,13 @@ from carla_msgs.msg import CarlaActorList +from transforms3d.euler import euler2quat from carla_msgs.srv import SpawnObject, DestroyObject from ros_compatibility import ( CompatibleNode, ROSInterruptException, ServiceException, - quaternion_from_euler, ros_init ) @@ -281,15 +281,12 @@ def create_spawn_point(self, x, y, z, roll, pitch, yaw): spawn_point.position.x = x spawn_point.position.y = y spawn_point.position.z = z - quat = quaternion_from_euler( - math.radians(roll), - math.radians(pitch), - math.radians(yaw)) - - spawn_point.orientation.x = quat[0] - spawn_point.orientation.y = quat[1] - spawn_point.orientation.z = quat[2] - spawn_point.orientation.w = quat[3] + quat = euler2quat(math.radians(roll), math.radians(pitch), math.radians(yaw)) + + spawn_point.orientation.w = quat[0] + spawn_point.orientation.x = quat[1] + spawn_point.orientation.y = quat[2] + spawn_point.orientation.z = quat[3] return spawn_point def check_spawn_point_param(self, spawn_point_parameter): diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index ba3c0cca..7872aa4b 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -19,10 +19,10 @@ import carla import carla_common.transforms as trans +from transforms3d.euler import quat2euler from ros_compatibility import ( CompatibleNode, - euler_from_quaternion, QoSProfile, ROSException, ROSInterruptException, @@ -97,12 +97,12 @@ def get_camera_transform(self): y=-self.pose.pose.position.y, z=self.pose.pose.position.z) quaternion = ( + self.pose.pose.orientation.w, self.pose.pose.orientation.x, self.pose.pose.orientation.y, - self.pose.pose.orientation.z, - self.pose.pose.orientation.w + self.pose.pose.orientation.z ) - roll, pitch, yaw = euler_from_quaternion(quaternion) + roll, pitch, yaw = quat2euler(quaternion) # rotate to CARLA sensor_rotation = carla.Rotation(pitch=math.degrees(roll)-90, roll=math.degrees(pitch), @@ -172,7 +172,7 @@ def destroy(self): if self.camera_actor: destroy_object_request = DestroyObjectRequest(self.camera_actor.id) try: - self.call_service(self.destroy_object_service,destroy_object_request) + self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: self.logwarn_once(str(e)) diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 49810e5b..9bee1df4 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -22,8 +22,7 @@ import threading import os -from ros_compatibility import (quaternion_from_euler, - CompatibleNode, +from ros_compatibility import (CompatibleNode, QoSProfile, ROSException, ros_timestamp, diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index e795c85a..c254beba 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -26,21 +26,6 @@ def ros_shutdown(): def destroy_subscription(subscription): subscription.unregister() - def euler_matrix(roll, pitch, yaw): - return trans.euler_matrix(roll, pitch, yaw) - - def euler_from_quaternion(quaternion): - return trans.euler_from_quaternion(quaternion) - - def quaternion_from_euler(roll, pitch, yaw): - return trans.quaternion_from_euler(roll, pitch, yaw) - - def quaternion_from_matrix(matrix): - return trans.quaternion_from_matrix(matrix) - - def quaternion_multiply(q1, q2): - return trans.quaternion_multiply(q1, q2) - class ROSException(rospy.ROSException): pass @@ -149,9 +134,6 @@ def on_shutdown(self, handler): import rclpy from builtin_interfaces.msg import Time - from transforms3d.euler import euler2mat, euler2quat, quat2euler - from transforms3d.quaternions import mat2quat, qmult - latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL def ros_init(args=None): @@ -176,26 +158,6 @@ def ros_shutdown(): def destroy_subscription(subscription): subscription.destroy() - def euler_matrix(roll, pitch, yaw): - return euler2mat(roll, pitch, yaw) - - def euler_from_quaternion(quaternion): - quat = [quaternion[3], quaternion[0], quaternion[1], quaternion[2]] - return quat2euler(quat) - - def quaternion_from_euler(roll, pitch, yaw): - quat = euler2quat(roll, pitch, yaw) - return [quat[1], quat[2], quat[3], quat[0]] - - def quaternion_from_matrix(matrix): - return mat2quat(matrix) - - def quaternion_multiply(q1, q2): - q1 = [q1[3], q1[0], q1[1], q1[2]] - q2 = [q2[3], q2[0], q2[1], q2[2]] - quat = qmult(q1, q2) - return [quat[1], quat[2], quat[3], quat[0]] - class WaitForMessageHelper(object): def __init__(self): self.msg = None From 414db5918618b29fad828eea52db4e63e1224bdd Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 23 Dec 2020 09:28:28 +0100 Subject: [PATCH 452/627] fixes spawn bug --- .../src/carla_ros_bridge/actor_factory.py | 5 - .../src/carla_ros_bridge/bridge.py | 14 ++- .../carla_spawn_objects.py | 93 +++++++++---------- 3 files changed, 56 insertions(+), 56 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 6e0ad2d2..26e44358 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -146,11 +146,6 @@ def create(self, type_id, name, attach_to, spawn_pose, carla_actor=None): return actor def destroy(self, actor_id): - # remove actors that have the actor to be removed as parent. - for actor in self.actors.values(): - if actor.parent is not None and actor.parent.uid == actor_id: - self.destroy(actor.uid) - with self.lock: # check that the actor is not already removed. if actor_id not in self.actors: diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index ac49929c..ff2dc198 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -197,19 +197,27 @@ def _destroy_actor(self, uid): if uid not in self.actor_factory.actors: return False + # remove actors that have the actor to be removed as parent. + for actor in list(self.actor_factory.actors.values()): + if actor.parent is not None and actor.parent.uid == uid: + if actor.uid in self._registered_actors: + success = self._destroy_actor(actor.uid) + if not success: + return False + actor = self.actor_factory.actors[uid] if isinstance(actor, Actor): actor.carla_actor.destroy() self.actor_factory.destroy(uid) + if uid in self._registered_actors: + self._registered_actors.remove(uid) + return True def destroy_object(self, req): with self.actor_factory.spawn_lock: result = self._destroy_actor(req.id) - if result and req.id in self._registered_actors: - self._registered_actors.remove(req.id) - return DestroyObjectResponse(result) def get_blueprints(self, req): diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index ee0c34f7..47b5c109 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -70,7 +70,7 @@ def spawn_objects(self): if not os.path.exists(self.objects_definition_file): raise RuntimeError( "Could not read sensor-definition from {}".format(self.objects_definition_file)) - json_sensors = None + with open(self.objects_definition_file) as handle: json_actors = json.loads(handle.read()) @@ -91,13 +91,13 @@ def spawn_objects(self): rospy.logwarn( "Object with type {} is not a vehicle, a walker or a sensor, ignoring".format(actor["type"])) if self.spawn_sensors_only is True and found_sensor_actor_list is False: - raise Exception("Parameter 'spawn_sensors_only' enabled, " + - "but 'sensor.pseudo.actor_list' is not instantiated, add it to your config file.") + raise RuntimeError("Parameter 'spawn_sensors_only' enabled, " + + "but 'sensor.pseudo.actor_list' is not instantiated, add it to your config file.") try: - self.global_sensors = self.setup_sensors(global_sensors) - except Exception as e: - raise Exception("Setting up global sensors failed: {}".format(e)) + self.setup_sensors(global_sensors) + except RuntimeError as e: + raise RuntimeError("Setting up global sensors failed: {}".format(e)) if self.spawn_sensors_only is True: # get vehicle id from topic /carla/actor_list for all vehicles listed in config file @@ -108,12 +108,11 @@ def spawn_objects(self): vehicle["carla_id"] = actor_info.id try: - self.players = self.setup_vehicles(vehicles) - except Exception as e: - raise Exception("Setting up vehicles failed: {}".format(e)) + self.setup_vehicles(vehicles) + except RuntimeError as e: + raise RuntimeError("Setting up vehicles failed: {}".format(e)) def setup_vehicles(self, vehicles): - players = [] for vehicle in vehicles: if self.spawn_sensors_only is True: # spawn sensors of already spawned vehicles @@ -124,11 +123,7 @@ def setup_vehicles(self, vehicles): "Could not spawn sensors of vehicle {}, its carla ID is not known.".format(vehicle["id"])) break # spawn the vehicle's sensors - try: - self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], carla_id)) - except Exception as e: - raise Exception( - "Setting up sensors of already spawned vehicle {} failed with error: {}".format(vehicle["id"], e)) + self.setup_sensors(vehicle["sensors"], carla_id) else: spawn_object_request = SpawnObjectRequest() spawn_object_request.type = vehicle["type"] @@ -143,13 +138,13 @@ def setup_vehicles(self, vehicles): spawn_param_used = False if (spawn_point_param is not None): # try to use spawn_point from parameters - try: - spawn_point = self.check_spawn_point_param(spawn_point_param) + spawn_point = self.check_spawn_point_param(spawn_point_param) + if spawn_point is None: + rospy.logwarn("{}: Could not use spawn point from parameters, ".format(vehicle["id"]) + + "the spawn point from config file will be used.") + else: rospy.loginfo("Spawn point from ros parameters") spawn_param_used = True - except Exception as e: - rospy.logerr("{}: Could not use spawn point from parameters, ".format(vehicle["id"]) + - "the spawn point from config file will be used. Error is: {}".format(e)) if "spawn_point" in vehicle and spawn_param_used is False: # get spawn point from config file @@ -179,18 +174,15 @@ def setup_vehicles(self, vehicles): response = self.spawn_object_service(spawn_object_request) if response.id != -1: player_spawned = True - players.append(response.id) + self.players.append(response.id) # Set up the sensors try: - self.vehicles_sensors.append( - self.setup_sensors(vehicle["sensors"], response.id)) + self.setup_sensors(vehicle["sensors"], response.id) except KeyError: rospy.logwarn( "Vehicle {} have no 'sensors' field in his config file, none will be spawned") - return players - - def setup_sensors(self, sensors, attached_vehicle_id=0): + def setup_sensors(self, sensors, attached_vehicle_id=None): """ Create the sensors defined by the user and attach them to the vehicle (or not if global sensor) @@ -198,7 +190,6 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): :param attached_vehicle_id: id of vehicle to attach the sensors to :return actors: list of ids of objects created """ - actors = [] sensor_names = [] for sensor_spec in sensors: try: @@ -207,12 +198,10 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): sensor_name = sensor_type + "/" + sensor_id if sensor_name in sensor_names: - raise NameError( - "Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) + raise NameError sensor_names.append(sensor_name) - if attached_vehicle_id == 0 and "pseudo" not in sensor_type: + if attached_vehicle_id is None and "pseudo" not in sensor_type: spawn_point = sensor_spec.pop("spawn_point") sensor_transform = self.create_spawn_point( spawn_point.pop("x"), @@ -238,7 +227,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): spawn_object_request = SpawnObjectRequest() spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id - spawn_object_request.attach_to = attached_vehicle_id + spawn_object_request.attach_to = attached_vehicle_id if attached_vehicle_id is not None else 0 spawn_object_request.transform = sensor_transform spawn_object_request.random_pose = False # never set a random pose for a sensor @@ -248,20 +237,26 @@ def setup_sensors(self, sensors, attached_vehicle_id=0): response = self.spawn_object_service(spawn_object_request) if response.id == -1: - raise Exception(response.error_string) + raise RuntimeError(response.error_string) + if attached_vehicle_id is None: + self.global_sensors.append(response.id) + else: + self.vehicles_sensors.append(response.id) except KeyError as e: rospy.logerr( "Sensor {} will not be spawned, the mandatory attribute {} is missing".format(sensor_name, e)) continue - except Exception as e: + except RuntimeError as e: rospy.logerr( "Sensor {} will not be spawned: {}".format(sensor_name, e)) continue - actors.append(response.id) - return actors + except NameError: + rospy.logerr("Sensor rolename '{}' is only allowed to be used once.".format( + sensor_spec['id'])) + continue def create_spawn_point(self, x, y, z, roll, pitch, yaw): spawn_point = Pose() @@ -282,7 +277,8 @@ def create_spawn_point(self, x, y, z, roll, pitch, yaw): def check_spawn_point_param(self, spawn_point_parameter): components = spawn_point_parameter.split(',') if len(components) != 6: - raise ValueError("Invalid spawnpoint '{}'".format(spawn_point_parameter)) + rospy.logwarn("Invalid spawnpoint '{}'".format(spawn_point_parameter)) + return None spawn_point = self.create_spawn_point( float(components[0]), float(components[1]), @@ -307,13 +303,12 @@ def destroy(self): self.global_sensors = [] # destroy vehicles sensors - for vehicle_sensors_id in self.vehicles_sensors: - for actor_id in vehicle_sensors_id: - destroy_object_request = DestroyObjectRequest(actor_id) - try: - response = self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) + for actor_id in self.vehicles_sensors: + destroy_object_request = DestroyObjectRequest(actor_id) + try: + response = self.destroy_object_service(destroy_object_request) + except rospy.ServiceException as e: + rospy.logwarn_once(str(e)) self.vehicles_sensors = [] # destroy player @@ -330,11 +325,13 @@ def run(self): main loop """ rospy.on_shutdown(self.destroy) - self.spawn_objects() try: - rospy.spin() + self.spawn_objects() except rospy.ROSInterruptException: - pass + rospy.logwarn( + "Spawning process has been interrupted. There might be actors that has not been destroyed properly") + rospy.spin() + # ============================================================================== # -- main() -------------------------------------------------------------------- @@ -349,7 +346,7 @@ def main(): try: spawn_objects_node = CarlaSpawnObjects() spawn_objects_node.run() - except Exception as e: + except RuntimeError as e: rospy.logfatal( "Exception caught: {}".format(e)) finally: From 959039ad9d84d167fe9ef79e69da4a6cfaa3adef Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 23 Dec 2020 11:33:39 +0100 Subject: [PATCH 453/627] added exception for python3 --- .../src/carla_spawn_objects/carla_spawn_objects.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 47b5c109..9640d529 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -327,7 +327,7 @@ def run(self): rospy.on_shutdown(self.destroy) try: self.spawn_objects() - except rospy.ROSInterruptException: + except (rospy.ROSInterruptException, rospy.ServiceException): rospy.logwarn( "Spawning process has been interrupted. There might be actors that has not been destroyed properly") rospy.spin() From 85964345bf6ffbb7599b65a3ed7073be8aa4e06e Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 23 Dec 2020 13:46:31 +0100 Subject: [PATCH 454/627] Fix hybrid mode for spawning/destroying objects --- .../src/carla_ros_bridge/bridge.py | 15 ++++-- .../carla_spawn_objects.py | 53 ++++++++++++------- .../ros_compatibility/ros_compatible_node.py | 30 +++++++++++ 3 files changed, 76 insertions(+), 22 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index cbcc4665..6f336607 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -262,13 +262,20 @@ def _destroy_actor(self, uid): return True - def destroy_object(self, req): + def destroy_object(self, req, response=None): + if ROS_VERSION == 1: + response = DestroyObjectResponse() + else: + response = DestroyObject.Response() with self.actor_factory.spawn_lock: - result = self._destroy_actor(req.id) - return DestroyObjectResponse(result) + response.success = self._destroy_actor(req.id) + return response def get_blueprints(self, req): - response = GetBlueprintsResponse() + if ROS_VERSION == 1: + response = GetBlueprintsResponse() + else: + response = GetBlueprints.Response() if req.filter: bp_filter = req.filter else: diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 032a34cd..a2b8bebd 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -32,7 +32,11 @@ ROSInterruptException, ServiceException, ros_init, - logfatal + logfatal, + loginfo, + logwarn, + logerr, + ros_ok ) ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -118,9 +122,9 @@ def spawn_objects(self): self.setup_vehicles(vehicles) except RuntimeError as e: raise RuntimeError("Setting up vehicles failed: {}".format(e)) + self.loginfo("All objects spawned.") def setup_vehicles(self, vehicles): - players = [] for vehicle in vehicles: if self.spawn_sensors_only is True: # spawn sensors of already spawned vehicles @@ -189,6 +193,7 @@ def setup_vehicles(self, vehicles): response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id != -1: + self.loginfo("Object (type='{}', id='{}') spawned successfully.".format(spawn_object_request.type, spawn_object_request.id)) player_spawned = True self.players.append(response.id) # Set up the sensors @@ -196,7 +201,7 @@ def setup_vehicles(self, vehicles): self.setup_sensors(vehicle["sensors"], response.id) except KeyError: self.logwarn( - "Vehicle {} have no 'sensors' field in his config file, none will be spawned") + "Object (type='{}', id='{}') has no 'sensors' field in his config file, none will be spawned.".format(spawn_object_request.type, spawn_object_request.id)) def setup_sensors(self, sensors, attached_vehicle_id=None): """ @@ -256,7 +261,9 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id == -1: + self.logwarn("Error while spawning object (type='{}', id='{}').".format(spawn_object_request.type, spawn_object_request.id)) raise RuntimeError(response.error_string) + self.loginfo("Object (type='{}', id='{}') spawned successfully.".format(spawn_object_request.type, spawn_object_request.id)) if attached_vehicle_id is None: self.global_sensors.append(response.id) else: @@ -309,12 +316,14 @@ def destroy(self): """ destroy all the players and sensors """ + self.loginfo("Shutting down.") # destroy global sensors for actor_id in self.global_sensors: if ROS_VERSION == 1: - destroy_object_request = DestroyObjectRequest(actor_id) + destroy_object_request = DestroyObjectRequest() elif ROS_VERSION == 2: - destroy_object_request = DestroyObject.Request(actor_id) + destroy_object_request = DestroyObject.Request() + destroy_object_request.id=actor_id try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: @@ -323,23 +332,28 @@ def destroy(self): # destroy vehicles sensors for actor_id in self.vehicles_sensors: - destroy_object_request = DestroyObjectRequest(actor_id) + if ROS_VERSION == 1: + destroy_object_request = DestroyObjectRequest() + elif ROS_VERSION == 2: + destroy_object_request = DestroyObject.Request() + destroy_object_request.id=actor_id try: - self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - self.logwarn_once(str(e)) + self.call_service(self.destroy_object_service, destroy_object_request) + except ServiceException as e: + self.logwarn(str(e)) self.vehicles_sensors = [] # destroy player for player_id in self.players: if ROS_VERSION == 1: - destroy_object_request = DestroyObjectRequest(player_id) + destroy_object_request = DestroyObjectRequest() elif ROS_VERSION == 2: - destroy_object_request = DestroyObject.Request(player_id) + destroy_object_request = DestroyObject.Request() + destroy_object_request.id = player_id try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: - self.logwarn_once(str(e)) + self.logwarn(str(e)) self.players = [] def run(self): @@ -347,15 +361,18 @@ def run(self): main loop """ self.on_shutdown(self.destroy) + spin = True try: self.spawn_objects() - except (ROSInterruptException, ServiceException): - self.logwarn_once( + except (ROSInterruptException, ServiceException, KeyboardInterrupt): + spin = False + self.logwarn( "Spawning process has been interrupted. There might be actors that has not been destroyed properly") - try: - rospy.spin() - except ROSInterruptException: - pass + if spin: + try: + self.spin() + except (KeyboardInterrupt): + self.loginfo("Shutdown requested.") # ============================================================================== # -- main() -------------------------------------------------------------------- diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index c254beba..b4efd4c3 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -26,6 +26,21 @@ def ros_shutdown(): def destroy_subscription(subscription): subscription.unregister() + def logdebug(log): + rospy.logdebug(log) + + def loginfo(log): + rospy.loginfo(log) + + def logwarn(log): + rospy.logwarn(log) + + def logerr(log): + rospy.logerr(log) + + def logfatal(log): + rospy.logfatal(log) + class ROSException(rospy.ROSException): pass @@ -158,6 +173,21 @@ def ros_shutdown(): def destroy_subscription(subscription): subscription.destroy() + def logdebug(log): + rclpy.logging.get_logger("default").debug(log) + + def loginfo(log): + rclpy.logging.get_logger("default").info(log) + + def logwarn(log): + rclpy.logging.get_logger("default").warn(log) + + def logerr(log): + rclpy.logging.get_logger("default").error(log) + + def logfatal(log): + rclpy.logging.get_logger("default").fatal(log) + class WaitForMessageHelper(object): def __init__(self): self.msg = None From 6fa72f47e6a6b6288ab8af32a648546a4fba0ad0 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 23 Dec 2020 14:42:51 +0100 Subject: [PATCH 455/627] Add convenience calls for getting service types --- carla_ad_agent/src/carla_ad_agent/agent.py | 35 +++++------------- .../src/carla_ad_agent/basic_agent.py | 10 ++---- .../src/carla_ros_bridge/bridge.py | 18 +++------- .../carla_spawn_objects.py | 36 +++++-------------- .../carla_spectator_camera.py | 12 ++----- .../carla_waypoint_publisher.py | 17 +++------ .../ros_compatibility/ros_compatible_node.py | 18 ++++++++++ 7 files changed, 51 insertions(+), 95 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 30f41bf2..7ce91da7 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -20,13 +20,13 @@ ServiceException, ROSInterruptException, QoSProfile, - latch_on) + latch_on, + get_service_request) import os ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: - from carla_waypoint_types.srv import GetWaypointRequest from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import elif ROS_VERSION == 2: from carla_ad_agent.misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import @@ -125,10 +125,7 @@ def _is_light_red_europe_style(self, lights_list): red traffic light affecting us """ if self._vehicle_location is not None: - if ROS_VERSION == 2: - ego_vehicle_location = GetWaypoint.Request() - elif ROS_VERSION == 1: - ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location = get_service_request(GetWaypoint) ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location @@ -182,10 +179,7 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc red traffic light affecting us """ if self._vehicle_location is not None: - if ROS_VERSION == 2: - ego_vehicle_location = GetWaypoint.Request() - elif ROS_VERSION == 1: - ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location = get_service_request(GetWaypoint) ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location @@ -200,12 +194,8 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc return (False, None) if self._local_planner.target_route_point is not None: - if ROS_VERSION == 2: - request = GetWaypoint.Request() - request.location = self._local_planner.target_route_point.position - elif ROS_VERSION == 1: - request = GetWaypointRequest() - request.location = self._local_planner.target_route_point.position + request = get_service_request(GetWaypoint) + request.location = self._local_planner.target_route_point.position target_waypoint = self.get_waypoint(request) if not target_waypoint: if ros_ok(): @@ -269,10 +259,7 @@ def _is_vehicle_hazard(self, vehicle_list, objects): """ if self._vehicle_location is not None: - if ROS_VERSION == 2: - ego_vehicle_location = GetWaypoint.Request() - elif ROS_VERSION == 1: - ego_vehicle_location = GetWaypointRequest() + ego_vehicle_location = get_service_request(GetWaypoint) ego_vehicle_location.location = self._vehicle_location else: ego_vehicle_location = self._vehicle_location @@ -299,12 +286,8 @@ def _is_vehicle_hazard(self, vehicle_list, objects): continue # if the object is not in our lane it's not an obstacle - if ROS_VERSION == 2: - request = GetWaypoint.Request() - request.location = target_vehicle_location.position - elif ROS_VERSION == 1: - request = GetWaypointRequest() - request.location = target_vehicle_location.position + request = get_service_request(GetWaypoint) + request.location = target_vehicle_location.position target_vehicle_waypoint = self.get_waypoint(request) if not target_vehicle_waypoint: if ros_ok(): diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 60234ee6..581e8961 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -21,12 +21,12 @@ ServiceException, ROSInterruptException, QoSProfile, - latch_on) + latch_on, + get_service_request) import os ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: - from carla_waypoint_types.srv import GetActorWaypointRequest from local_planner import LocalPlanner # pylint: disable=relative-import from agent import Agent, AgentState # pylint: disable=relative-import elif ROS_VERSION == 2: @@ -85,11 +85,7 @@ def get_actor_waypoint(self, actor_id): Only used if risk should be avoided. """ try: - # TODO: have ros_compat get_service_request(GetActorWaypoint) - if ROS_VERSION == 1: - request = GetActorWaypointRequest() - elif ROS_VERSION == 2: - request = GetActorWaypoint.Request() + request = get_service_request(GetActorWaypoint) request.id = actor_id response = self.node.call_service(self._get_actor_waypoint_client, request) return response.waypoint diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 6f336607..ab1bbc91 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -18,7 +18,8 @@ ros_timestamp, QoSProfile, latch_on, - ros_init) + ros_init, + get_service_response) try: import queue @@ -222,10 +223,7 @@ def _spawn_pseudo_actor(self, req): return actor.uid def spawn_object(self, req, response=None): - if ROS_VERSION == 1: - response = SpawnObjectResponse() - else: - response = SpawnObject.Response() + response = get_service_response(SpawnObject) with self.actor_factory.spawn_lock: try: if "pseudo" in req.type: @@ -263,19 +261,13 @@ def _destroy_actor(self, uid): return True def destroy_object(self, req, response=None): - if ROS_VERSION == 1: - response = DestroyObjectResponse() - else: - response = DestroyObject.Response() + response = get_service_response(DestroyObject) with self.actor_factory.spawn_lock: response.success = self._destroy_actor(req.id) return response def get_blueprints(self, req): - if ROS_VERSION == 1: - response = GetBlueprintsResponse() - else: - response = GetBlueprints.Response() + response = get_service_response(GetBlueprints) if req.filter: bp_filter = req.filter else: diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index a2b8bebd..8c52d1a9 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -36,14 +36,10 @@ loginfo, logwarn, logerr, - ros_ok + ros_ok, + get_service_request ) -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION == 1: - from carla_msgs.srv import SpawnObjectRequest, DestroyObjectRequest - # ============================================================================== # -- CarlaSpawnObjects ------------------------------------------------------------ # ============================================================================== @@ -124,6 +120,7 @@ def spawn_objects(self): raise RuntimeError("Setting up vehicles failed: {}".format(e)) self.loginfo("All objects spawned.") + def setup_vehicles(self, vehicles): for vehicle in vehicles: if self.spawn_sensors_only is True: @@ -141,10 +138,7 @@ def setup_vehicles(self, vehicles): raise Exception( "Setting up sensors of already spawned vehicle {} failed with error: {}".format(vehicle["id"], e)) else: - if ROS_VERSION == 1: - spawn_object_request = SpawnObjectRequest() - elif ROS_VERSION == 2: - spawn_object_request = SpawnObject.Request() + spawn_object_request = get_service_request(SpawnObject) spawn_object_request.type = vehicle["type"] spawn_object_request.id = vehicle["id"] spawn_object_request.attach_to = 0 @@ -244,11 +238,8 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): spawn_point.pop("roll", 0.0), spawn_point.pop("pitch", 0.0), spawn_point.pop("yaw", 0.0)) - - if ROS_VERSION == 1: - spawn_object_request = SpawnObjectRequest() - elif ROS_VERSION == 2: - spawn_object_request = SpawnObject.Request() + + spawn_object_request = get_service_request(SpawnObject) spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id spawn_object_request.attach_to = attached_vehicle_id if attached_vehicle_id is not None else 0 @@ -319,10 +310,7 @@ def destroy(self): self.loginfo("Shutting down.") # destroy global sensors for actor_id in self.global_sensors: - if ROS_VERSION == 1: - destroy_object_request = DestroyObjectRequest() - elif ROS_VERSION == 2: - destroy_object_request = DestroyObject.Request() + destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id=actor_id try: self.call_service(self.destroy_object_service, destroy_object_request) @@ -332,10 +320,7 @@ def destroy(self): # destroy vehicles sensors for actor_id in self.vehicles_sensors: - if ROS_VERSION == 1: - destroy_object_request = DestroyObjectRequest() - elif ROS_VERSION == 2: - destroy_object_request = DestroyObject.Request() + destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id=actor_id try: self.call_service(self.destroy_object_service, destroy_object_request) @@ -345,10 +330,7 @@ def destroy(self): # destroy player for player_id in self.players: - if ROS_VERSION == 1: - destroy_object_request = DestroyObjectRequest() - elif ROS_VERSION == 2: - destroy_object_request = DestroyObject.Request() + destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = player_id try: self.call_service(self.destroy_object_service, destroy_object_request) diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 7872aa4b..337a8af7 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -27,13 +27,10 @@ ROSException, ROSInterruptException, ros_init, - ServiceException + ServiceException, + get_service_request ) -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION == 1: - from carla_msgs.srv import SpawnObjectRequest, DestroyObjectRequest # ============================================================================== # -- CarlaSpectatorCamera ------------------------------------------------------------ # ============================================================================== @@ -117,10 +114,7 @@ def create_camera(self, ego_actor): if not transform: transform = carla.Transform() - if ROS_VERSION == 1: - spawn_object_request = SpawnObjectRequest() - elif ROS_VERSION == 2: - spawn_object_request = SpawnObject.Request() + spawn_object_request = get_service_request(SpawnObject) spawn_object_request.type = "sensor.camera.rgb" spawn_object_request.id = "spectator_view" spawn_object_request.attach_to = ego_actor.id diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 9bee1df4..d5b9cddc 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -27,7 +27,8 @@ ROSException, ros_timestamp, latch_on, - ros_init) + ros_init, + get_service_response) from nav_msgs.msg import Path from geometry_msgs.msg import PoseStamped import carla_common.transforms as trans @@ -39,12 +40,6 @@ from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION == 1: - from carla_waypoint_types.srv import GetWaypointResponse, GetActorWaypointResponse - - class CarlaToRosWaypointConverter(CompatibleNode): """ @@ -112,8 +107,7 @@ def get_waypoint(self, req, response=None): carla_waypoint = self.map.get_waypoint(carla_position) - if ROS_VERSION == 1: - response = GetWaypointResponse() + response = get_service_response(GetWaypoint) response.waypoint.pose.position.x = carla_waypoint.transform.location.x response.waypoint.pose.position.y = -carla_waypoint.transform.location.y response.waypoint.pose.position.z = carla_waypoint.transform.location.z @@ -131,10 +125,7 @@ def get_actor_waypoint(self, req, response=None): # self.loginfo("get_actor_waypoint(): Get waypoint of actor {}".format(req.id)) actor = self.world.get_actors().find(req.id) - if ROS_VERSION == 1: - response = GetActorWaypointResponse() - else: - response = GetActorWaypoint.Response() + response = get_service_response(GetActorWaypoint) if actor: carla_waypoint = self.map.get_waypoint(actor.get_location()) response.waypoint.pose = trans.carla_transform_to_ros_pose(carla_waypoint.transform) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index b4efd4c3..1828be76 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -41,6 +41,18 @@ def logerr(log): def logfatal(log): rospy.logfatal(log) + def get_service_request(service_type): + ros1_classname = service_type.__name__ + "Request" + module = ".".join(service_type.__module__.split(".")[:-1]) + request_class = __import__(module, fromlist=[ros1_classname]) + return getattr(request_class, ros1_classname)() + + def get_service_response(service_type): + ros1_classname = service_type.__name__ + "Response" + module = ".".join(service_type.__module__.split(".")[:-1]) + request_class = __import__(module, fromlist=[ros1_classname]) + return getattr(request_class, ros1_classname)() + class ROSException(rospy.ROSException): pass @@ -196,6 +208,12 @@ def callback(self, msg): if self.msg is None: self.msg = msg + def get_service_request(service_type): + return service_type.Request() + + def get_service_response(service_type): + return service_type.Response() + class ROSException(Exception): pass From 2c7ee0efc2490600e1a18af896245d7699e374eb Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 23 Dec 2020 15:08:01 +0100 Subject: [PATCH 456/627] cleanup ci --- .github/workflows/ci.yml | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index ced44e48..775c7169 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -39,15 +39,7 @@ jobs: rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip unzip ros2.zip -d carla_msgs && rm ros2.zip packaging/install_dependencies.sh - - name: Init Workspace - if: matrix.ros-version != 'foxy' - run: | - mkdir -p $GITHUB_WORKSPACE/../catkin_ws/src - cd $GITHUB_WORKSPACE/../catkin_ws/src - ln -s $GITHUB_WORKSPACE - cd .. - catkin init - - name: Build, Test, Lint + - name: ROS2 Build, Test, Lint if: matrix.ros-version == 'foxy' shell: bash run: | @@ -55,10 +47,15 @@ jobs: colcon build --continue-on-error colcon test && colcon test-result source install/setup.bash - - name: Build, Test, Lint + - name: ROS1 Build, Test, Lint if: matrix.ros-version != 'foxy' shell: bash run: | + mkdir -p $GITHUB_WORKSPACE/../catkin_ws/src + cd $GITHUB_WORKSPACE/../catkin_ws/src + ln -s $GITHUB_WORKSPACE + cd .. + catkin init source /opt/ros/$(rosversion -d)/setup.bash cd $GITHUB_WORKSPACE/../catkin_ws && catkin build --summarize --no-status --force-color From 84ec90b41a36b19164a2d281ad943d90cdfd69c1 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 23 Dec 2020 15:13:55 +0100 Subject: [PATCH 457/627] Cleanup --- carla_ros_bridge/src/carla_ros_bridge/actor.py | 1 - .../src/carla_ros_bridge/actor_control.py | 2 +- .../src/carla_ros_bridge/ego_vehicle.py | 1 - .../carla_spawn_objects/carla_spawn_objects.py | 18 ++++++++++-------- .../carla_waypoint_publisher.py | 1 + .../ros_compatibility/ros_compatible_node.py | 4 ++-- 6 files changed, 14 insertions(+), 13 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 48b7b929..03169895 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -10,7 +10,6 @@ Base Classes to handle Actor objects """ -import numpy as np from geometry_msgs.msg import TransformStamped # pylint: disable=import-error from visualization_msgs.msg import Marker # pylint: disable=import-error from std_msgs.msg import ColorRGBA # pylint: disable=import-error diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index d622c22b..83e91cb9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -6,7 +6,7 @@ # For a copy, see . # """ -provide functions to control actors +provide functions to control actors """ import numpy diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index bd4488e8..12800e45 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -12,7 +12,6 @@ import math import os -import numpy from std_msgs.msg import Bool # pylint: disable=import-error from std_msgs.msg import ColorRGBA # pylint: disable=import-error from carla import VehicleControl diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 8c52d1a9..209f98fe 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -10,7 +10,7 @@ Gets config file from ros parameter ~objects_definition_file and spawns corresponding objects through ROS service /carla/spawn_object. -Looks for an initial spawn point first in the launchfile, then in the config file, and +Looks for an initial spawn point first in the launchfile, then in the config file, and finally ask for a random one to the spawn service. """ @@ -120,7 +120,6 @@ def spawn_objects(self): raise RuntimeError("Setting up vehicles failed: {}".format(e)) self.loginfo("All objects spawned.") - def setup_vehicles(self, vehicles): for vehicle in vehicles: if self.spawn_sensors_only is True: @@ -187,7 +186,8 @@ def setup_vehicles(self, vehicles): response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id != -1: - self.loginfo("Object (type='{}', id='{}') spawned successfully.".format(spawn_object_request.type, spawn_object_request.id)) + self.loginfo("Object (type='{}', id='{}') spawned successfully.".format( + spawn_object_request.type, spawn_object_request.id)) player_spawned = True self.players.append(response.id) # Set up the sensors @@ -238,7 +238,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): spawn_point.pop("roll", 0.0), spawn_point.pop("pitch", 0.0), spawn_point.pop("yaw", 0.0)) - + spawn_object_request = get_service_request(SpawnObject) spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id @@ -252,9 +252,11 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id == -1: - self.logwarn("Error while spawning object (type='{}', id='{}').".format(spawn_object_request.type, spawn_object_request.id)) + self.logwarn("Error while spawning object (type='{}', id='{}').".format( + spawn_object_request.type, spawn_object_request.id)) raise RuntimeError(response.error_string) - self.loginfo("Object (type='{}', id='{}') spawned successfully.".format(spawn_object_request.type, spawn_object_request.id)) + self.loginfo("Object (type='{}', id='{}') spawned successfully.".format( + spawn_object_request.type, spawn_object_request.id)) if attached_vehicle_id is None: self.global_sensors.append(response.id) else: @@ -311,7 +313,7 @@ def destroy(self): # destroy global sensors for actor_id in self.global_sensors: destroy_object_request = get_service_request(DestroyObject) - destroy_object_request.id=actor_id + destroy_object_request.id = actor_id try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: @@ -321,7 +323,7 @@ def destroy(self): # destroy vehicles sensors for actor_id in self.vehicles_sensors: destroy_object_request = get_service_request(DestroyObject) - destroy_object_request.id=actor_id + destroy_object_request.id = actor_id try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index d5b9cddc..17ede2de 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -40,6 +40,7 @@ from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO + class CarlaToRosWaypointConverter(CompatibleNode): """ diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 1828be76..37da703e 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -44,13 +44,13 @@ def logfatal(log): def get_service_request(service_type): ros1_classname = service_type.__name__ + "Request" module = ".".join(service_type.__module__.split(".")[:-1]) - request_class = __import__(module, fromlist=[ros1_classname]) + request_class = __import__(module, fromlist=[ros1_classname]) return getattr(request_class, ros1_classname)() def get_service_response(service_type): ros1_classname = service_type.__name__ + "Response" module = ".".join(service_type.__module__.split(".")[:-1]) - request_class = __import__(module, fromlist=[ros1_classname]) + request_class = __import__(module, fromlist=[ros1_classname]) return getattr(request_class, ros1_classname)() class ROSException(rospy.ROSException): From be75596901fdae377f0bcaa5df89c2ce224cced0 Mon Sep 17 00:00:00 2001 From: Jean-Baptiste Magnin <47941074+jbmag@users.noreply.github.com> Date: Mon, 4 Jan 2021 10:01:35 +0100 Subject: [PATCH 458/627] Removed carla_spectator_camera node (#450) * removed carla_spectator_camera node, replaced it by actor_control snesor attached to cameras * Update README.md --- carla_ad_demo/config/carla_ad_demo.rviz | 2 +- .../launch/carla_ad_demo_with_scenario.launch | 20 +- carla_ad_demo/package.xml | 1 - carla_spawn_objects/config/objects.json | 9 +- .../carla_spawn_objects.py | 22 +- carla_spectator_camera/CMakeLists.txt | 19 -- carla_spectator_camera/README.md | 17 -- .../launch/carla_spectator_camera.launch | 22 -- carla_spectator_camera/package.xml | 17 -- carla_spectator_camera/setup.py | 13 -- .../src/carla_spectator_camera/__init__.py | 0 .../carla_spectator_camera.py | 206 ------------------ docker/Dockerfile | 1 - rviz_carla_plugin/README.md | 4 +- rviz_carla_plugin/src/carla_control_panel.cpp | 26 +-- 15 files changed, 42 insertions(+), 337 deletions(-) delete mode 100644 carla_spectator_camera/CMakeLists.txt delete mode 100644 carla_spectator_camera/README.md delete mode 100644 carla_spectator_camera/launch/carla_spectator_camera.launch delete mode 100644 carla_spectator_camera/package.xml delete mode 100644 carla_spectator_camera/setup.py delete mode 100644 carla_spectator_camera/src/carla_spectator_camera/__init__.py delete mode 100755 carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index 1121ee30..1451cd95 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -68,7 +68,7 @@ Visualization Manager: - Class: rviz/Camera Enabled: true Image Rendering: background and overlay - Image Topic: /carla/ego_vehicle/spectator_view/image + Image Topic: /carla/ego_vehicle/rgb_view/image Name: RGB Camera Overlay Alpha: 0.5 Queue Size: 2 diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index 873aea77..0a4830a9 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -18,11 +18,6 @@ - - - - - @@ -52,17 +47,6 @@ - - - - - - - - - - - @@ -88,6 +72,8 @@ - + + + diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 94e2453f..04af2523 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -13,7 +13,6 @@ carla_manual_control rviz_carla_plugin carla_twist_to_control - carla_spectator_camera carla_ros_scenario_runner rostopic rviz diff --git a/carla_spawn_objects/config/objects.json b/carla_spawn_objects/config/objects.json index 717a7981..8efcead7 100644 --- a/carla_spawn_objects/config/objects.json +++ b/carla_spawn_objects/config/objects.json @@ -42,7 +42,14 @@ "image_size_x": 800, "image_size_y": 600, "fov": 90.0, - "sensor_tick": 0.05 + "sensor_tick": 0.05, + "attached_objects": + [ + { + "type": "actor.pseudo.control", + "id": "control" + } + ] }, { "type": "sensor.lidar.ray_cast", diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 9640d529..edf8fb0b 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -231,13 +231,23 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): spawn_object_request.transform = sensor_transform spawn_object_request.random_pose = False # never set a random pose for a sensor + attached_objects = [] for attribute, value in sensor_spec.items(): + if attribute == "attached_objects": + for attached_object in sensor_spec["attached_objects"]: + attached_objects.append(attached_object) + continue spawn_object_request.attributes.append( KeyValue(str(attribute), str(value))) response = self.spawn_object_service(spawn_object_request) if response.id == -1: raise RuntimeError(response.error_string) + + if attached_objects: + # spawn the attached objects + self.setup_sensors(attached_objects, response.id) + if attached_vehicle_id is None: self.global_sensors.append(response.id) else: @@ -293,23 +303,23 @@ def destroy(self): """ destroy all the players and sensors """ - # destroy global sensors - for actor_id in self.global_sensors: + # destroy vehicles sensors + for actor_id in self.vehicles_sensors: destroy_object_request = DestroyObjectRequest(actor_id) try: response = self.destroy_object_service(destroy_object_request) except rospy.ServiceException as e: rospy.logwarn_once(str(e)) - self.global_sensors = [] + self.vehicles_sensors = [] - # destroy vehicles sensors - for actor_id in self.vehicles_sensors: + # destroy global sensors + for actor_id in self.global_sensors: destroy_object_request = DestroyObjectRequest(actor_id) try: response = self.destroy_object_service(destroy_object_request) except rospy.ServiceException as e: rospy.logwarn_once(str(e)) - self.vehicles_sensors = [] + self.global_sensors = [] # destroy player for player_id in self.players: diff --git a/carla_spectator_camera/CMakeLists.txt b/carla_spectator_camera/CMakeLists.txt deleted file mode 100644 index aef4b66a..00000000 --- a/carla_spectator_camera/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(carla_spectator_camera) - -find_package(catkin REQUIRED COMPONENTS rospy roslaunch geometry_msgs) - -catkin_python_setup() - -if(CATKIN_ENABLE_TESTING) - roslaunch_add_file_check(launch) -endif() - -catkin_package(CATKIN_DEPENDS rospy) - -catkin_install_python( - PROGRAMS src/carla_spectator_camera/carla_spectator_camera.py DESTINATION - ${CATKIN_PACKAGE_BIN_DESTINATION}) - -install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_spectator_camera/README.md b/carla_spectator_camera/README.md deleted file mode 100644 index 356370f2..00000000 --- a/carla_spectator_camera/README.md +++ /dev/null @@ -1,17 +0,0 @@ -# Carla Spectator Camera - -This node allows to spawn a camera, attached to an ego vehicle and move its pose via a ros topic. - -## Startup - -To run it: - - roslaunch carla_spectator_camera carla_spectator_camera.launch - -## Set the camera pose - -The camera pose can be set by publishing to: - -| Topic | Type | -| ------------------------------------------ | -------------------------------------------------------------------------------------------- | -| `/carla//spectator_pose` | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | diff --git a/carla_spectator_camera/launch/carla_spectator_camera.launch b/carla_spectator_camera/launch/carla_spectator_camera.launch deleted file mode 100644 index 4da884a4..00000000 --- a/carla_spectator_camera/launch/carla_spectator_camera.launch +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/carla_spectator_camera/package.xml b/carla_spectator_camera/package.xml deleted file mode 100644 index c30a4490..00000000 --- a/carla_spectator_camera/package.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - carla_spectator_camera - 0.0.0 - The carla_spectator_camera package - CARLA Simulator Team - MIT - catkin - rospy - roslaunch - rospy - rospy - topic_tools - geometry_msgs - - - diff --git a/carla_spectator_camera/setup.py b/carla_spectator_camera/setup.py deleted file mode 100644 index b0dae9aa..00000000 --- a/carla_spectator_camera/setup.py +++ /dev/null @@ -1,13 +0,0 @@ -""" -Setup for carla_spectator_camera -""" - -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup - -d = generate_distutils_setup( - packages=['carla_spectator_camera'], - package_dir={'': 'src'} -) - -setup(**d) diff --git a/carla_spectator_camera/src/carla_spectator_camera/__init__.py b/carla_spectator_camera/src/carla_spectator_camera/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py deleted file mode 100755 index a892afc8..00000000 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ /dev/null @@ -1,206 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -""" -Spawns a camera, attached to an ego vehicle. - -The pose of the camera can be changed by publishing -to /carla//spectator_position. -""" - -import math -import sys - -import carla -import rospy - -from tf.transformations import euler_from_quaternion - -from carla_msgs.msg import CarlaWorldInfo -from carla_msgs.srv import SpawnObject, SpawnObjectRequest, DestroyObject, DestroyObjectRequest -from diagnostic_msgs.msg import KeyValue -from geometry_msgs.msg import PoseStamped - -import carla_common.transforms as trans - -# ============================================================================== -# -- CarlaSpectatorCamera ------------------------------------------------------------ -# ============================================================================== - - -class CarlaSpectatorCamera(object): - """ - Spawns a camera, attached to an ego vehicle. - - The pose of the camera can be changed by publishing - to /carla//spectator_position. - """ - - def __init__(self): - """ - Constructor - """ - rospy.init_node('spectator_camera', anonymous=True) - self.role_name = rospy.get_param("/role_name", "ego_vehicle") - self.camera_resolution_x = rospy.get_param("~resolution_x", 800) - self.camera_resolution_y = rospy.get_param("~resolution_y", 600) - self.camera_fov = rospy.get_param("~fov", 50) - self.host = rospy.get_param('/carla/host', '127.0.0.1') - self.port = rospy.get_param('/carla/port', 2000) - self.timeout = rospy.get_param("/carla/timeout", 10) - self.world = None - self.pose = None - self.camera_actor = None - self.ego_vehicle = None - - rospy.wait_for_service('/carla/spawn_object') - rospy.wait_for_service('/carla/destroy_object') - - self.spawn_object_service = rospy.ServiceProxy("/carla/spawn_object", SpawnObject) - self.destroy_object_service = rospy.ServiceProxy("/carla/destroy_object", DestroyObject) - - rospy.Subscriber("/carla/{}/spectator_pose".format(self.role_name), - PoseStamped, self.pose_received) - - def pose_received(self, pose): - """ - Move the camera - """ - if self.pose != pose: - rospy.logdebug("Camera pose changed. Updating carla camera") - self.pose = pose - transform = self.get_camera_transform() - if transform and self.camera_actor: - self.camera_actor.set_transform(transform) - - def get_camera_transform(self): - """ - Calculate the CARLA camera transform - """ - if not self.pose: - rospy.loginfo("no pose!") - return None - if self.pose.header.frame_id != self.role_name: - rospy.logwarn("Unsupported frame received. Supported {}, received {}".format( - self.role_name, self.pose.header.frame_id)) - return None - sensor_location = carla.Location(x=self.pose.pose.position.x, - y=-self.pose.pose.position.y, - z=self.pose.pose.position.z) - quaternion = ( - self.pose.pose.orientation.x, - self.pose.pose.orientation.y, - self.pose.pose.orientation.z, - self.pose.pose.orientation.w - ) - roll, pitch, yaw = euler_from_quaternion(quaternion) - # rotate to CARLA - sensor_rotation = carla.Rotation(pitch=math.degrees(roll)-90, - roll=math.degrees(pitch), - yaw=-math.degrees(yaw)-90) - return carla.Transform(sensor_location, sensor_rotation) - - def create_camera(self, ego_actor): - """ - Attach the camera to the ego vehicle - """ - transform = self.get_camera_transform() - if not transform: - transform = carla.Transform() - - spawn_object_request = SpawnObjectRequest() - spawn_object_request.type = "sensor.camera.rgb" - spawn_object_request.id = "spectator_view" - spawn_object_request.attach_to = ego_actor.id - spawn_object_request.transform = trans.carla_transform_to_ros_pose(transform) - spawn_object_request.random_pose = False - spawn_object_request.attributes.extend([ - KeyValue("image_size_x", str(self.camera_resolution_x)), - KeyValue("image_size_y", str(self.camera_resolution_y)), - KeyValue("fov", str(self.camera_fov)) - ]) - - response = self.spawn_object_service(spawn_object_request) - if response.id == -1: - raise Exception(response.error_string) - - self.camera_actor = self.world.get_actor(response.id) - - def find_ego_vehicle_actor(self): - """ - Look for an carla actor with role name - """ - hero = None - for actor in self.world.get_actors(): - if actor.attributes.get('role_name') == self.role_name: - hero = actor - break - ego_vehicle_changed = False - if hero is None and self.ego_vehicle is not None: - ego_vehicle_changed = True - - if not ego_vehicle_changed and hero is not None and self.ego_vehicle is None: - ego_vehicle_changed = True - - if not ego_vehicle_changed and hero is not None and \ - self.ego_vehicle is not None and hero.id != self.ego_vehicle.id: - ego_vehicle_changed = True - - if ego_vehicle_changed: - self.destroy() - rospy.loginfo("Ego vehicle changed.") - self.ego_vehicle = hero - if self.ego_vehicle: - self.create_camera(self.ego_vehicle) - - def destroy(self): - """ - destroy the camera - """ - if self.camera_actor: - destroy_object_request = DestroyObjectRequest(self.camera_actor.id) - try: - self.destroy_object_service(destroy_object_request) - except rospy.ServiceException as e: - rospy.logwarn_once(str(e)) - - self.camera_actor = None - - def run(self): - """ - main loop - """ - client = carla.Client(self.host, self.port) - client.set_timeout(self.timeout) - self.world = client.get_world() - - try: - r = rospy.Rate(10) # 10hz - while not rospy.is_shutdown(): - self.find_ego_vehicle_actor() - r.sleep() - except rospy.ROSInterruptException: - pass - -# ============================================================================== -# -- main() -------------------------------------------------------------------- -# ============================================================================== - - -def main(): - """ - main function - """ - carla_spectator_camera = CarlaSpectatorCamera() - try: - carla_spectator_camera.run() - finally: - if carla_spectator_camera is not None: - carla_spectator_camera.destroy() - - -if __name__ == '__main__': - main() diff --git a/docker/Dockerfile b/docker/Dockerfile index 4c13d726..2c44d892 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -37,7 +37,6 @@ COPY carla_msgs /opt/carla-ros-bridge/src/carla_msgs COPY carla_ros_bridge /opt/carla-ros-bridge/src/carla_ros_bridge COPY carla_ros_scenario_runner /opt/carla-ros-bridge/src/carla_ros_scenario_runner COPY carla_ros_scenario_runner_types /opt/carla-ros-bridge/src/carla_ros_scenario_runner_types -COPY carla_spectator_camera /opt/carla-ros-bridge/src/carla_spectator_camera COPY carla_twist_to_control /opt/carla-ros-bridge/src/carla_twist_to_control COPY carla_walker_agent /opt/carla-ros-bridge/src/carla_walker_agent COPY carla_waypoint_publisher /opt/carla-ros-bridge/src/carla_waypoint_publisher diff --git a/rviz_carla_plugin/README.md b/rviz_carla_plugin/README.md index 0a54dc75..911b9816 100644 --- a/rviz_carla_plugin/README.md +++ b/rviz_carla_plugin/README.md @@ -10,9 +10,7 @@ This plugin is expecting a ego vehicle named `ego_vehicle`. ### Provide the RVIZ view pose to other nodes -In combination with [carla_spectator_camera](../carla_spectator_camera), this allows visually moving around in the CARLA world. - -Currently, it is limited to a camera attached to the ego-vehicle. Please set the target frame of the "Current View" to `ego_vehicle`. +When a `actor.pseudo.control` is attached to a camera (using the [carla_spawn_objects](../carla_spawn_objects) node), it allows to move the camera around in the CARLA world, by publishing a Pose message. ### Visualize the current ego vehicle state diff --git a/rviz_carla_plugin/src/carla_control_panel.cpp b/rviz_carla_plugin/src/carla_control_panel.cpp index ce436946..8dea95e4 100644 --- a/rviz_carla_plugin/src/carla_control_panel.cpp +++ b/rviz_carla_plugin/src/carla_control_panel.cpp @@ -21,7 +21,7 @@ #include #include -#include +#include #include #include #include @@ -138,7 +138,7 @@ CarlaControlPanel::CarlaControlPanel(QWidget *parent) = mNodeHandle.subscribe("/carla/ego_vehicle/odometry", 1000, &CarlaControlPanel::egoVehicleOdometryChanged, this); mCameraPosePublisher - = mNodeHandle.advertise("carla/ego_vehicle/spectator_pose", 10, true); + = mNodeHandle.advertise("carla/ego_vehicle/spectator_pose", 10, true); mEgoVehicleControlManualOverridePublisher = mNodeHandle.advertise("/carla/ego_vehicle/vehicle_control_manual_override", 1, true); @@ -177,17 +177,17 @@ void CarlaControlPanel::cameraPreRenderScene(Ogre::Camera *cam) void CarlaControlPanel::updateCameraPos() { auto frame = mViewController->subProp("Target Frame")->getValue(); - - geometry_msgs::PoseStamped pose; - pose.header.frame_id = frame.toString().toStdString(); - pose.header.stamp = ros::Time::now(); - pose.pose.position.x = mCameraCurrentPosition.x; - pose.pose.position.y = mCameraCurrentPosition.y; - pose.pose.position.z = mCameraCurrentPosition.z; - pose.pose.orientation.x = mCameraCurrentOrientation.x; - pose.pose.orientation.y = mCameraCurrentOrientation.y; - pose.pose.orientation.z = mCameraCurrentOrientation.z; - pose.pose.orientation.w = mCameraCurrentOrientation.w; + geometry_msgs::Pose pose; + pose.position.x = mCameraCurrentPosition.x; + pose.position.y = mCameraCurrentPosition.y; + pose.position.z = mCameraCurrentPosition.z; + + mCameraCurrentOrientation = mCameraCurrentOrientation * Ogre::Quaternion(Ogre::Degree(90), Ogre::Vector3::UNIT_Y); + mCameraCurrentOrientation = mCameraCurrentOrientation * Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_X); + pose.orientation.x = mCameraCurrentOrientation.x; + pose.orientation.y = mCameraCurrentOrientation.y; + pose.orientation.z = mCameraCurrentOrientation.z; + pose.orientation.w = mCameraCurrentOrientation.w; mCameraPosePublisher.publish(pose); } From 090d9e17142107831d18ec461f984d52c612f550 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 4 Jan 2021 08:20:43 -0500 Subject: [PATCH 459/627] fix merge master --- carla_ad_demo/config/carla_ad_demo_ros2.rviz | 8 +- .../carla_ad_demo_with_scenario.launch.py | 41 +--- .../launch/carla_infrastructure.launch.py | 51 ----- .../resource/carla_infrastructure | 0 carla_infrastructure/setup.cfg | 4 - .../carla_spawn_objects.py | 15 +- carla_spectator_camera/CMakeLists.txt | 36 --- .../launch/carla_spectator_camera.launch.py | 73 ------ carla_spectator_camera/package.xml | 27 --- .../resource/carla_spectator_camera | 0 carla_spectator_camera/setup.cfg | 4 - carla_spectator_camera/setup.py | 42 ---- .../carla_spectator_camera.py | 210 ------------------ .../src/carla_control_panel_ROS2.cpp | 23 +- .../src/carla_control_panel_ROS2.h | 4 +- 15 files changed, 26 insertions(+), 512 deletions(-) delete mode 100644 carla_infrastructure/launch/carla_infrastructure.launch.py delete mode 100644 carla_infrastructure/resource/carla_infrastructure delete mode 100644 carla_infrastructure/setup.cfg delete mode 100644 carla_spectator_camera/CMakeLists.txt delete mode 100644 carla_spectator_camera/launch/carla_spectator_camera.launch.py delete mode 100644 carla_spectator_camera/package.xml delete mode 100644 carla_spectator_camera/resource/carla_spectator_camera delete mode 100644 carla_spectator_camera/setup.cfg delete mode 100644 carla_spectator_camera/setup.py delete mode 100755 carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py diff --git a/carla_ad_demo/config/carla_ad_demo_ros2.rviz b/carla_ad_demo/config/carla_ad_demo_ros2.rviz index b4dd8017..dbf347a6 100644 --- a/carla_ad_demo/config/carla_ad_demo_ros2.rviz +++ b/carla_ad_demo/config/carla_ad_demo_ros2.rviz @@ -79,7 +79,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /carla/ego_vehicle/camera/rgb/spectator_view/image_color + Value: /carla/ego_vehicle/rgb_view/image Value: true Visibility: DVS Camera: true @@ -150,7 +150,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /carla/ego_vehicle/camera/depth/front/image_depth + Value: /carla/ego_vehicle/depth_front/image Value: true - Class: rviz_default_plugins/Image Enabled: true @@ -164,7 +164,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /carla/ego_vehicle/camera/semantic_segmentation/front/image_segmentation + Value: /carla/ego_vehicle/semantic_segmentation_front/image Value: true - Class: rviz_default_plugins/Image Enabled: true @@ -178,7 +178,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /carla/ego_vehicle/camera/dvs/front/image_events + Value: /carla/ego_vehicle/dvs_front/image Value: true - Alpha: 1 Autocompute Intensity Bounds: true diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index e7c053a6..b2a5c9a4 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -48,26 +48,6 @@ def generate_launch_description(): name='role_name', default_value='ego_vehicle' ), - launch.actions.DeclareLaunchArgument( - name='vehicle_filter', - default_value='vehicle.tesla.model3' - ), - launch.actions.DeclareLaunchArgument( - name='avoid_risk', - default_value='True' - ), - launch.actions.DeclareLaunchArgument( - name='resolution_x', - default_value='800' - ), - launch.actions.DeclareLaunchArgument( - name='resolution_y', - default_value='600' - ), - launch.actions.DeclareLaunchArgument( - name='fov', - default_value='50' - ), launch_ros.actions.Node( package='carla_twist_to_control', executable='carla_twist_to_control', @@ -128,21 +108,6 @@ def generate_launch_description(): 'role_name': launch.substitutions.LaunchConfiguration('role_name') }.items() ), - launch.actions.IncludeLaunchDescription( - launch.launch_description_sources.PythonLaunchDescriptionSource( - os.path.join(get_package_share_directory( - 'carla_spectator_camera'), 'carla_spectator_camera.launch.py') - ), - launch_arguments={ - 'host': launch.substitutions.LaunchConfiguration('host'), - 'port': launch.substitutions.LaunchConfiguration('port'), - 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'role_name': launch.substitutions.LaunchConfiguration('role_name'), - 'resolution_x': launch.substitutions.LaunchConfiguration('resolution_x'), - 'resolution_y': launch.substitutions.LaunchConfiguration('resolution_y'), - 'fov': launch.substitutions.LaunchConfiguration('fov') - }.items() - ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( @@ -161,6 +126,12 @@ def generate_launch_description(): executable='rviz2', name='rviz2', output='screen', + remappings=[ + ( + "carla/ego_vehicle/spectator_pose", + "/carla/ego_vehicle/rgb_view/control/set_transform" + ) + ], arguments=[ '-d', os.path.join(get_package_share_directory('carla_ad_demo'), 'config/carla_ad_demo_ros2.rviz')], on_exit=launch.actions.Shutdown() diff --git a/carla_infrastructure/launch/carla_infrastructure.launch.py b/carla_infrastructure/launch/carla_infrastructure.launch.py deleted file mode 100644 index 18aa56dd..00000000 --- a/carla_infrastructure/launch/carla_infrastructure.launch.py +++ /dev/null @@ -1,51 +0,0 @@ -import os -import sys - -import launch -import launch_ros.actions - - -def generate_launch_description(): - ld = launch.LaunchDescription([ - launch.actions.DeclareLaunchArgument( - name='host', - default_value='localhost' - ), - launch.actions.DeclareLaunchArgument( - name='port', - default_value='2000' - ), - launch.actions.DeclareLaunchArgument( - name='timeout', - default_value='2' - ), - launch.actions.DeclareLaunchArgument( - name='infrastructure_sensor_definition_file' - ), - launch_ros.actions.Node( - package='carla_infrastructure', - executable='carla_infrastructure', - name='carla_infrastructure', - output='screen', - emulate_tty='True', - parameters=[ - { - 'carla/host': launch.substitutions.LaunchConfiguration('host') - }, - { - 'carla/port': launch.substitutions.LaunchConfiguration('port') - }, - { - 'carla/timeout': launch.substitutions.LaunchConfiguration('timeout') - }, - { - 'infrastructure_sensor_definition_file': launch.substitutions.LaunchConfiguration('infrastructure_sensor_definition_file') - } - ] - ) - ]) - return ld - - -if __name__ == '__main__': - generate_launch_description() diff --git a/carla_infrastructure/resource/carla_infrastructure b/carla_infrastructure/resource/carla_infrastructure deleted file mode 100644 index e69de29b..00000000 diff --git a/carla_infrastructure/setup.cfg b/carla_infrastructure/setup.cfg deleted file mode 100644 index ac855152..00000000 --- a/carla_infrastructure/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script-dir=$base/lib/carla_infrastructure -[install] -install-scripts=$base/lib/carla_infrastructure \ No newline at end of file diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 19e393e4..b77b6604 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -131,11 +131,7 @@ def setup_vehicles(self, vehicles): "Could not spawn sensors of vehicle {}, its carla ID is not known.".format(vehicle["id"])) break # spawn the vehicle's sensors - try: - self.vehicles_sensors.append(self.setup_sensors(vehicle["sensors"], carla_id)) - except Exception as e: - raise Exception( - "Setting up sensors of already spawned vehicle {} failed with error: {}".format(vehicle["id"], e)) + self.setup_sensors(vehicle["sensors"], carla_id) else: spawn_object_request = get_service_request(SpawnObject) spawn_object_request.type = vehicle["type"] @@ -183,11 +179,8 @@ def setup_vehicles(self, vehicles): player_spawned = False while not player_spawned: spawn_object_request.transform = spawn_point - response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id != -1: - self.loginfo("Object (type='{}', id='{}') spawned successfully.".format( - spawn_object_request.type, spawn_object_request.id)) player_spawned = True self.players.append(response.id) # Set up the sensors @@ -257,11 +250,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): response = self.call_service(self.spawn_object_service, spawn_object_request) if response.id == -1: - self.logwarn("Error while spawning object (type='{}', id='{}').".format( - spawn_object_request.type, spawn_object_request.id)) raise RuntimeError(response.error_string) - self.loginfo("Object (type='{}', id='{}') spawned successfully.".format( - spawn_object_request.type, spawn_object_request.id)) if attached_objects: # spawn the attached objects @@ -330,7 +319,7 @@ def destroy(self): except ServiceException as e: self.logwarn(str(e)) self.vehicles_sensors = [] - + # destroy global sensors for actor_id in self.global_sensors: destroy_object_request = get_service_request(DestroyObject) diff --git a/carla_spectator_camera/CMakeLists.txt b/carla_spectator_camera/CMakeLists.txt deleted file mode 100644 index d646eee0..00000000 --- a/carla_spectator_camera/CMakeLists.txt +++ /dev/null @@ -1,36 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(carla_spectator_camera) - -find_package(ros_environment REQUIRED) -set(ROS_VERSION $ENV{ROS_VERSION}) - -if(${ROS_VERSION} EQUAL 1) - - find_package(catkin REQUIRED COMPONENTS rospy roslaunch geometry_msgs) - - catkin_python_setup() - - if(CATKIN_ENABLE_TESTING) - roslaunch_add_file_check(launch) - endif() - - catkin_package(CATKIN_DEPENDS rospy) - - catkin_install_python( - PROGRAMS src/carla_spectator_camera/carla_spectator_camera.py DESTINATION - ${CATKIN_PACKAGE_BIN_DESTINATION}) - - install(DIRECTORY launch/ - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) - -elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) - - ament_package() - -endif() diff --git a/carla_spectator_camera/launch/carla_spectator_camera.launch.py b/carla_spectator_camera/launch/carla_spectator_camera.launch.py deleted file mode 100644 index 6e44769d..00000000 --- a/carla_spectator_camera/launch/carla_spectator_camera.launch.py +++ /dev/null @@ -1,73 +0,0 @@ -import os -import sys - -import launch -import launch_ros.actions - - -def generate_launch_description(): - ld = launch.LaunchDescription([ - launch.actions.DeclareLaunchArgument( - name='host', - default_value='localhost' - ), - launch.actions.DeclareLaunchArgument( - name='port', - default_value='2000' - ), - launch.actions.DeclareLaunchArgument( - name='timeout', - default_value='2' - ), - launch.actions.DeclareLaunchArgument( - name='role_name', - default_value='ego_vehicle' - ), - launch.actions.DeclareLaunchArgument( - name='resolution_x', - default_value='800' - ), - launch.actions.DeclareLaunchArgument( - name='resolution_y', - default_value='600' - ), - launch.actions.DeclareLaunchArgument( - name='fov', - default_value='50' - ), - launch_ros.actions.Node( - package='carla_spectator_camera', - executable='carla_spectator_camera', - name='carla_spectator_camera', - output='screen', - emulate_tty='True', - parameters=[ - { - 'carla/host': launch.substitutions.LaunchConfiguration('host') - }, - { - 'carla/port': launch.substitutions.LaunchConfiguration('port') - }, - { - 'carla/timeout': launch.substitutions.LaunchConfiguration('timeout') - }, - { - 'role_name': launch.substitutions.LaunchConfiguration('role_name') - }, - { - 'resolution_x': launch.substitutions.LaunchConfiguration('resolution_x') - }, - { - 'resolution_y': launch.substitutions.LaunchConfiguration('resolution_y') - }, - { - 'fov': launch.substitutions.LaunchConfiguration('fov') - } - ] - ) - ]) - return ld - - -if __name__ == '__main__': - generate_launch_description() diff --git a/carla_spectator_camera/package.xml b/carla_spectator_camera/package.xml deleted file mode 100644 index 5643395b..00000000 --- a/carla_spectator_camera/package.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - carla_spectator_camera - 0.0.0 - The carla_spectator_camera package - CARLA Simulator Team - MIT - - geometry_msgs - - - catkin - rospy - roslaunch - rospy - rospy - topic_tools - - - rclpy - ament_python - - - catkin - ament_python - - diff --git a/carla_spectator_camera/resource/carla_spectator_camera b/carla_spectator_camera/resource/carla_spectator_camera deleted file mode 100644 index e69de29b..00000000 diff --git a/carla_spectator_camera/setup.cfg b/carla_spectator_camera/setup.cfg deleted file mode 100644 index 5dfa44b9..00000000 --- a/carla_spectator_camera/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script-dir=$base/lib/carla_spectator_camera -[install] -install-scripts=$base/lib/carla_spectator_camera \ No newline at end of file diff --git a/carla_spectator_camera/setup.py b/carla_spectator_camera/setup.py deleted file mode 100644 index 806f8284..00000000 --- a/carla_spectator_camera/setup.py +++ /dev/null @@ -1,42 +0,0 @@ -""" -Setup for carla_spectator_camera -""" -import os -from glob import glob -ROS_VERSION = int(os.environ['ROS_VERSION']) - -if ROS_VERSION == 1: - from distutils.core import setup - from catkin_pkg.python_setup import generate_distutils_setup - - d = generate_distutils_setup( - packages=['carla_spectator_camera'], - package_dir={'': 'src'} - ) - - setup(**d) - -elif ROS_VERSION == 2: - from setuptools import setup - - package_name = 'carla_spectator_camera' - setup( - name=package_name, - version='0.0.0', - packages=[package_name], - data_files=[ - ('share/ament_index/resource_index/packages', ['resource/' + package_name]), - (os.path.join('share', package_name), ['package.xml']), - (os.path.join('share', package_name), glob('launch/*.launch.py')) - ], - install_requires=['setuptools'], - zip_safe=True, - maintainer='CARLA Simulator Team', - maintainer_email='carla.simulator@gmail.com', - description='CARLA ROS2 Spectator Camera', - license='MIT', - entry_points={ - 'console_scripts': ['carla_spectator_camera = carla_spectator_camera.carla_spectator_camera:main'], - }, - package_dir={'': 'src'}, - ) diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py deleted file mode 100755 index 337a8af7..00000000 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ /dev/null @@ -1,210 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -""" -Spawns a camera, attached to an ego vehicle. - -The pose of the camera can be changed by publishing -to /carla//spectator_position. -""" -import os - -import carla -from geometry_msgs.msg import PoseStamped -from carla_msgs.srv import SpawnObject, DestroyObject -from diagnostic_msgs.msg import KeyValue - -import carla -import carla_common.transforms as trans -from transforms3d.euler import quat2euler - -from ros_compatibility import ( - CompatibleNode, - QoSProfile, - ROSException, - ROSInterruptException, - ros_init, - ServiceException, - get_service_request -) - -# ============================================================================== -# -- CarlaSpectatorCamera ------------------------------------------------------------ -# ============================================================================== - - -class CarlaSpectatorCamera(CompatibleNode): - """ - Spawns a camera, attached to an ego vehicle. - - The pose of the camera can be changed by publishing - to /carla//spectator_position. - """ - - def __init__(self): - """ - Constructor - """ - super(CarlaSpectatorCamera, self).__init__('spectator_camera') - self.role_name = self.get_param("role_name", "ego_vehicle") - self.camera_resolution_x = self.get_param("resolution_x", 800) - self.camera_resolution_y = self.get_param("resolution_y", 600) - self.camera_fov = self.get_param("fov", 50) - self.host = self.get_param('carla/host', '127.0.0.1') - self.port = self.get_param('carla/port', 2000) - self.timeout = self.get_param("carla/timeout", 10) - self.world = None - self.pose = None - self.camera_actor = None - self.ego_vehicle = None - - self.spawn_object_service = self.create_service_client("/carla/spawn_object", SpawnObject) - self.destroy_object_service = self.create_service_client( - "/carla/destroy_object", DestroyObject) - - self.create_subscriber(PoseStamped, "/carla/{}/spectator_pose".format(self.role_name), - self.pose_received) - - def pose_received(self, pose): - """ - Move the camera - """ - if self.pose != pose: - self.logdebug("Camera pose changed. Updating carla camera") - self.pose = pose - transform = self.get_camera_transform() - if transform and self.camera_actor: - self.camera_actor.set_transform(transform) - - def get_camera_transform(self): - """ - Calculate the CARLA camera transform - """ - if not self.pose: - self.loginfo("no pose!") - return None - if self.pose.header.frame_id != self.role_name: - self.logwarn("Unsupported frame received. Supported {}, received {}".format( - self.role_name, self.pose.header.frame_id)) - return None - sensor_location = carla.Location(x=self.pose.pose.position.x, - y=-self.pose.pose.position.y, - z=self.pose.pose.position.z) - quaternion = ( - self.pose.pose.orientation.w, - self.pose.pose.orientation.x, - self.pose.pose.orientation.y, - self.pose.pose.orientation.z - ) - roll, pitch, yaw = quat2euler(quaternion) - # rotate to CARLA - sensor_rotation = carla.Rotation(pitch=math.degrees(roll)-90, - roll=math.degrees(pitch), - yaw=-math.degrees(yaw)-90) - return carla.Transform(sensor_location, sensor_rotation) - - def create_camera(self, ego_actor): - """ - Attach the camera to the ego vehicle - """ - transform = self.get_camera_transform() - if not transform: - transform = carla.Transform() - - spawn_object_request = get_service_request(SpawnObject) - spawn_object_request.type = "sensor.camera.rgb" - spawn_object_request.id = "spectator_view" - spawn_object_request.attach_to = ego_actor.id - spawn_object_request.transform = trans.carla_transform_to_ros_pose(transform) - spawn_object_request.random_pose = False - spawn_object_request.attributes.extend([ - KeyValue(key="image_size_x", value=str(self.camera_resolution_x)), - KeyValue(key="image_size_y", value=str(self.camera_resolution_y)), - KeyValue(key="fov", value=str(self.camera_fov)) - ]) - - response = self.call_service(self.spawn_object_service, spawn_object_request) - if response.id == -1: - raise Exception(response.error_string) - - self.camera_actor = self.world.get_actor(response.id) - - def find_ego_vehicle_actor(self): - """ - Look for an carla actor with role name - """ - hero = None - for actor in self.world.get_actors(): - if actor.attributes.get('role_name') == self.role_name: - hero = actor - break - ego_vehicle_changed = False - if hero is None and self.ego_vehicle is not None: - ego_vehicle_changed = True - - if not ego_vehicle_changed and hero is not None and self.ego_vehicle is None: - ego_vehicle_changed = True - - if not ego_vehicle_changed and hero is not None and \ - self.ego_vehicle is not None and hero.id != self.ego_vehicle.id: - ego_vehicle_changed = True - - if ego_vehicle_changed: - self.destroy() - self.loginfo("Ego vehicle changed.") - self.ego_vehicle = hero - if self.ego_vehicle: - self.create_camera(self.ego_vehicle) - - def destroy(self): - """ - destroy the camera - """ - if self.camera_actor: - destroy_object_request = DestroyObjectRequest(self.camera_actor.id) - try: - self.call_service(self.destroy_object_service, destroy_object_request) - except ServiceException as e: - self.logwarn_once(str(e)) - - self.camera_actor = None - - def run(self): - """ - main loop - """ - client = carla.Client(self.host, self.port) - client.set_timeout(self.timeout) - self.world = client.get_world() - - period = 0.1 - try: - self.new_timer(period, lambda timer_event=None: self.find_ego_vehicle_actor()) - self.spin() - except ROSInterruptException: - pass - -# ============================================================================== -# -- main() -------------------------------------------------------------------- -# ============================================================================== - - -def main(args=None): - """ - main function - """ - ros_init(args) - - carla_spectator_camera = CarlaSpectatorCamera() - try: - carla_spectator_camera.run() - finally: - if carla_spectator_camera is not None: - carla_spectator_camera.destroy() - - -if __name__ == '__main__': - main() diff --git a/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp b/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp index d1f2efdd..238cef8a 100644 --- a/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp +++ b/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp @@ -154,16 +154,17 @@ void CarlaControlPanel::cameraPreRenderScene(Ogre::Camera *cam) void CarlaControlPanel::updateCameraPos() { auto frame = mViewController->subProp("Target Frame")->getValue(); - geometry_msgs::msg::PoseStamped pose; - pose.header.frame_id = frame.toString().toStdString(); - pose.header.stamp = _node->now(); - pose.pose.position.x = mCameraCurrentPosition.x; - pose.pose.position.y = mCameraCurrentPosition.y; - pose.pose.position.z = mCameraCurrentPosition.z; - pose.pose.orientation.x = mCameraCurrentOrientation.x; - pose.pose.orientation.y = mCameraCurrentOrientation.y; - pose.pose.orientation.z = mCameraCurrentOrientation.z; - pose.pose.orientation.w = mCameraCurrentOrientation.w; + geometry_msgs::msg::Pose pose; + pose.position.x = mCameraCurrentPosition.x; + pose.position.y = mCameraCurrentPosition.y; + pose.position.z = mCameraCurrentPosition.z; + + mCameraCurrentOrientation = mCameraCurrentOrientation * Ogre::Quaternion(Ogre::Degree(90), Ogre::Vector3::UNIT_Y); + mCameraCurrentOrientation = mCameraCurrentOrientation * Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_X); + pose.orientation.x = mCameraCurrentOrientation.x; + pose.orientation.y = mCameraCurrentOrientation.y; + pose.orientation.z = mCameraCurrentOrientation.z; + pose.orientation.w = mCameraCurrentOrientation.w; mCameraPosePublisher->publish(pose); } @@ -185,7 +186,7 @@ void CarlaControlPanel::onInitialize() auto qos_latch_10 = rclcpp::QoS( rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, 10)); qos_latch_10.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); mCameraPosePublisher - = _node->create_publisher("/carla/ego_vehicle/spectator_pose", qos_latch_10); + = _node->create_publisher("/carla/ego_vehicle/spectator_pose", qos_latch_10); auto qos_latch_1 = rclcpp::QoS( rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_LAST, 1)); qos_latch_1.durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); diff --git a/rviz_carla_plugin/src/carla_control_panel_ROS2.h b/rviz_carla_plugin/src/carla_control_panel_ROS2.h index 4f544d0b..38fd1954 100644 --- a/rviz_carla_plugin/src/carla_control_panel_ROS2.h +++ b/rviz_carla_plugin/src/carla_control_panel_ROS2.h @@ -17,7 +17,7 @@ #include #include #include -#include +#include #include #include "rviz_common/ros_integration/ros_node_abstraction_iface.hpp" #include @@ -96,7 +96,7 @@ protected Q_SLOTS: rclcpp::Client::SharedPtr mExecuteScenarioClient; rclcpp::Subscription::SharedPtr mScenarioSubscriber; rclcpp::Subscription::SharedPtr mScenarioRunnerStatusSubscriber; - rclcpp::Publisher::SharedPtr mCameraPosePublisher; + rclcpp::Publisher::SharedPtr mCameraPosePublisher; carla_ros_scenario_runner_types::msg::CarlaScenarioList::SharedPtr mCarlaScenarios; From 35e9083ec6c40275beda87b68403678471e01213 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 4 Jan 2021 11:20:03 -0500 Subject: [PATCH 460/627] fix bug with rviz plugin definition file --- rviz_carla_plugin/package.xml | 3 +-- rviz_carla_plugin/src/carla_control_panel_ROS2.cpp | 1 - 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/rviz_carla_plugin/package.xml b/rviz_carla_plugin/package.xml index ec2d88c9..32f993ac 100644 --- a/rviz_carla_plugin/package.xml +++ b/rviz_carla_plugin/package.xml @@ -29,8 +29,7 @@ libqt5-widgets - - + --> catkin ament_cmake diff --git a/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp b/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp index 238cef8a..a9dc0b98 100644 --- a/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp +++ b/rviz_carla_plugin/src/carla_control_panel_ROS2.cpp @@ -153,7 +153,6 @@ void CarlaControlPanel::cameraPreRenderScene(Ogre::Camera *cam) void CarlaControlPanel::updateCameraPos() { - auto frame = mViewController->subProp("Target Frame")->getValue(); geometry_msgs::msg::Pose pose; pose.position.x = mCameraCurrentPosition.x; pose.position.y = mCameraCurrentPosition.y; From 18857af405ef42826f8fd7f60b8d832a39ed957b Mon Sep 17 00:00:00 2001 From: Jean-Baptiste Magnin <47941074+jbmag@users.noreply.github.com> Date: Mon, 4 Jan 2021 16:52:59 +0100 Subject: [PATCH 461/627] error in rviz2 config file to show markers (#453) * error in rviz2 config file to show markers --- carla_ad_demo/config/carla_ad_demo_ros2.rviz | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/carla_ad_demo/config/carla_ad_demo_ros2.rviz b/carla_ad_demo/config/carla_ad_demo_ros2.rviz index dbf347a6..84bcbf2a 100644 --- a/carla_ad_demo/config/carla_ad_demo_ros2.rviz +++ b/carla_ad_demo/config/carla_ad_demo_ros2.rviz @@ -126,17 +126,13 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: true - - Class: rviz_default_plugins/Marker + - Class: rviz_default_plugins/MarkerArray Enabled: true - Name: Marker + Topic: /carla/markers + Name: MarkerArray Namespaces: "": true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /carla/marker + Queue Size: 100 Value: true - Class: rviz_default_plugins/Image Enabled: true From 75f3a54f2c857a7ad3676a3420ad1ef84f8637a8 Mon Sep 17 00:00:00 2001 From: Jean-Baptiste Magnin <47941074+jbmag@users.noreply.github.com> Date: Thu, 7 Jan 2021 13:00:05 +0100 Subject: [PATCH 462/627] Fix tests (#454) * fix bug object_sensor adding only parent to list of actors * fix tests --- carla_ros_bridge/src/carla_ros_bridge/object_sensor.py | 2 +- carla_ros_bridge/test/ros_bridge_client.py | 10 +++++----- carla_ros_bridge/test/test_objects.json | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index c04c77a0..f7683580 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -74,7 +74,7 @@ def update(self, frame, timestamp): ros_objects = ObjectArray(header=self.get_msg_header("map")) for actor_id in self.actor_list.keys(): # currently only Vehicles and Walkers are added to the object array - if self.parent is None or self.parent.uid == actor_id: + if self.parent is None or self.parent.uid != actor_id: actor = self.actor_list[actor_id] if isinstance(actor, Vehicle): ros_objects.objects.append(actor.get_object_info()) diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 0a89d800..27077a6d 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -20,7 +20,7 @@ from geometry_msgs.msg import Quaternion, Vector3, Pose from nav_msgs.msg import Odometry from derived_object_msgs.msg import ObjectArray -from visualization_msgs.msg import Marker +from visualization_msgs.msg import Marker, MarkerArray from carla_msgs.msg import (CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, CarlaActorList, CarlaTrafficLightStatusList, CarlaTrafficLightInfoList) @@ -142,8 +142,8 @@ def test_dvs_camera_info(self): msg = rospy.wait_for_message( "/carla/ego_vehicle/dvs_front/camera_info", CameraInfo, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") - self.assertEqual(msg.height, 600) - self.assertEqual(msg.width, 800) + self.assertEqual(msg.height, 70) + self.assertEqual(msg.width, 400) def test_dvs_camera_image(self): """ @@ -153,8 +153,8 @@ def test_dvs_camera_image(self): msg = rospy.wait_for_message( "/carla/ego_vehicle/dvs_front/image", Image, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") - self.assertEqual(msg.height, 600) - self.assertEqual(msg.width, 800) + self.assertEqual(msg.height, 70) + self.assertEqual(msg.width, 400) self.assertEqual(msg.encoding, "bgr8") def test_dvs_camera_events(self): diff --git a/carla_ros_bridge/test/test_objects.json b/carla_ros_bridge/test/test_objects.json index cf461ce6..b426c5da 100644 --- a/carla_ros_bridge/test/test_objects.json +++ b/carla_ros_bridge/test/test_objects.json @@ -22,7 +22,7 @@ "id": "map" }, { - "type": "vehicle.audi.tt", + "type": "vehicle.tesla.model3", "id": "ego_vehicle", "sensors": [ From 601bc50a1dfbb8f1ec55363fd7e3182ec61b493e Mon Sep 17 00:00:00 2001 From: Jean-Baptiste Magnin <47941074+jbmag@users.noreply.github.com> Date: Fri, 8 Jan 2021 11:27:30 +0100 Subject: [PATCH 463/627] improved wait_for_one_message ros2 function (#455) * improved wait_for_one_message ros2 function, inspired by the rospy equivalent --- .../ros_compatibility/ros_compatible_node.py | 21 +++++++++++-------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 37da703e..6d70e13e 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -154,6 +154,7 @@ def on_shutdown(self, handler): rospy.on_shutdown(handler) elif ROS_VERSION == 2: + import time from rclpy import Parameter from rclpy.exceptions import ROSInterruptException from rclpy.node import Node @@ -288,18 +289,20 @@ def new_timer(self, timer_period_sec, callback): def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None): s = None - spin_timeout = 0.5 - loop_reps = -1 - if timeout is not None: - loop_reps = timeout // spin_timeout + 1 wfm = WaitForMessageHelper() try: s = self.create_subscriber(topic_type, topic, wfm.callback, qos_profile=qos_profile) - while ros_ok() and wfm.msg is None: - rclpy.spin_once(self, timeout_sec=spin_timeout) - loop_reps = loop_reps - 1 - if loop_reps == 0: - raise ROSException + if timeout is not None: + timeout_t = time.time() + timeout + while ros_ok() and wfm.msg is None: + time.sleep(0.01) + rclpy.spin_once(self, timeout_sec=0) + if time.time() >= timeout_t: + raise ROSException + else: + while ros_ok() and wfm.msg is None: + time.sleep(0.01) + rclpy.spin_once(self, timeout_sec=0) finally: if s is not None: self.destroy_subscription(s) From bcfda3c98c1ca2ebfe02312d7d9f7a6a5b86a24c Mon Sep 17 00:00:00 2001 From: Jean-Baptiste Magnin <47941074+jbmag@users.noreply.github.com> Date: Mon, 11 Jan 2021 11:19:37 +0100 Subject: [PATCH 464/627] Add/Fix tests ros2 branch (#456) * Fix tests (#454) * fix bug object_sensor adding only parent to list of actors * fix tests * moved carla_ros_bridge settings.yaml file to test directory * added ros2 launch_test * removed leftover debug function * fixed ros2 test timeout * added info on tests in readme * typo README.md * Disable ci tests for foxy Co-authored-by: Pasch, Frederik --- .github/workflows/ci.yml | 2 +- README.md | 20 + carla_ros_bridge/setup.py | 3 +- .../src/carla_ros_bridge/object_sensor.py | 2 +- carla_ros_bridge/test/ros_bridge_client.py | 10 +- carla_ros_bridge/test/ros_bridge_client.test | 2 +- .../test/ros_bridge_client_ros2_test.py | 522 ++++++++++++++++++ .../test}/settings.yaml | 0 carla_ros_bridge/test/test_objects.json | 2 +- carla_spawn_objects/setup.py | 2 +- 10 files changed, 554 insertions(+), 11 deletions(-) create mode 100644 carla_ros_bridge/test/ros_bridge_client_ros2_test.py rename {carla_spawn_objects/config => carla_ros_bridge/test}/settings.yaml (100%) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 775c7169..793bd522 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -45,7 +45,7 @@ jobs: run: | source /opt/ros/$(rosversion -d)/setup.bash colcon build --continue-on-error - colcon test && colcon test-result + # colcon test && colcon test-result source install/setup.bash - name: ROS1 Build, Test, Lint if: matrix.ros-version != 'foxy' diff --git a/README.md b/README.md index 1b33b4e2..c211f6f0 100644 --- a/README.md +++ b/README.md @@ -381,6 +381,26 @@ The following markers are supported in 'map'-frame: | ---------------------------------- | ------------------------------------------------------------------------------------------------------ | --------------------------- | | `/carla/debug_marker` (subscriber) | [visualization_msgs.MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) | draw markers in CARLA world | +## Testing + +### ROS1 and catkin + +To execute the tests, using catkin and ROS1, use the following commands: + + # build + catkin_make -DCATKIN_ENABLE_TESTING=0 + # run + rostest carla_ros_bridge ros_bridge_client.test + +### ROS2 and colcon + +To execute the tests using colcon and ROS2, use the following commands: + + # build + colcon build --packages-up-to carla_ros_bridge + # run + launch_test ros-bridge/carla_ros_bridge/test/ros_bridge_client_ros2_test.py + ## Troubleshooting ### ImportError: No module named carla diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index 91691d43..d107c657 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -23,7 +23,8 @@ packages=[package_name], data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - (os.path.join('share', package_name), glob('launch/*.launch.py'))], + (os.path.join('share', package_name), glob('launch/*.launch.py')), + (os.path.join('share', package_name + '/test'), glob('test/test_objects.json'))], install_requires=['setuptools'], zip_safe=True, maintainer='CARLA Simulator Team', diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index b87767d4..790c8c1f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -71,7 +71,7 @@ def update(self, frame, timestamp): ros_objects = ObjectArray(header=self.get_msg_header("map")) for actor_id in self.actor_list.keys(): # currently only Vehicles and Walkers are added to the object array - if self.parent is None or self.parent.uid == actor_id: + if self.parent is None or self.parent.uid != actor_id: actor = self.actor_list[actor_id] if isinstance(actor, Vehicle): ros_objects.objects.append(actor.get_object_info()) diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 0a89d800..27077a6d 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -20,7 +20,7 @@ from geometry_msgs.msg import Quaternion, Vector3, Pose from nav_msgs.msg import Odometry from derived_object_msgs.msg import ObjectArray -from visualization_msgs.msg import Marker +from visualization_msgs.msg import Marker, MarkerArray from carla_msgs.msg import (CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, CarlaActorList, CarlaTrafficLightStatusList, CarlaTrafficLightInfoList) @@ -142,8 +142,8 @@ def test_dvs_camera_info(self): msg = rospy.wait_for_message( "/carla/ego_vehicle/dvs_front/camera_info", CameraInfo, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") - self.assertEqual(msg.height, 600) - self.assertEqual(msg.width, 800) + self.assertEqual(msg.height, 70) + self.assertEqual(msg.width, 400) def test_dvs_camera_image(self): """ @@ -153,8 +153,8 @@ def test_dvs_camera_image(self): msg = rospy.wait_for_message( "/carla/ego_vehicle/dvs_front/image", Image, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") - self.assertEqual(msg.height, 600) - self.assertEqual(msg.width, 800) + self.assertEqual(msg.height, 70) + self.assertEqual(msg.width, 400) self.assertEqual(msg.encoding, "bgr8") def test_dvs_camera_events(self): diff --git a/carla_ros_bridge/test/ros_bridge_client.test b/carla_ros_bridge/test/ros_bridge_client.test index abc0e5ce..a4b3a71d 100644 --- a/carla_ros_bridge/test/ros_bridge_client.test +++ b/carla_ros_bridge/test/ros_bridge_client.test @@ -2,7 +2,7 @@ - + diff --git a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py new file mode 100644 index 00000000..4a254234 --- /dev/null +++ b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py @@ -0,0 +1,522 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +import os +import sys +import unittest + +import ament_index_python + +import launch +import launch.actions + +import launch_testing +import launch_testing.actions + +from ament_index_python.packages import get_package_share_directory +from ros_compatibility import CompatibleNode, ros_init, ros_shutdown, QoSProfile, latch_on + +from std_msgs.msg import Header, String +from rosgraph_msgs.msg import Clock +from sensor_msgs.msg import CameraInfo, NavSatFix, Image, PointCloud2, Imu +from geometry_msgs.msg import Quaternion, Vector3, Pose +from nav_msgs.msg import Odometry +from derived_object_msgs.msg import ObjectArray +from visualization_msgs.msg import Marker, MarkerArray +from carla_msgs.msg import (CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, + CarlaActorList, CarlaTrafficLightStatusList, + CarlaTrafficLightInfoList) + + + +def generate_test_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='host', + default_value='localhost' + ), + launch.actions.DeclareLaunchArgument( + name='port', + default_value='2000' + ), + launch.actions.DeclareLaunchArgument( + name='timeout', + default_value='2' + ), + launch.actions.DeclareLaunchArgument( + name='passive', + default_value='False' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode', + default_value='False' + ), + launch.actions.DeclareLaunchArgument( + name='synchronous_mode_wait_for_vehicle_control_command', + default_value='True' + ), + launch.actions.DeclareLaunchArgument( + name='fixed_delta_seconds', + default_value='0.05' + ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='vehicle_filter', + default_value='vehicle.tesla.model3' + ), + launch.actions.DeclareLaunchArgument( + name='ego_vehicle_role_names', + default_value=["hero", "ego_vehicle", "hero0", "hero1", "hero2", + "hero3", "hero4", "hero5", "hero6", "hero7", "hero8", "hero9"] + ), + launch.actions.DeclareLaunchArgument( + name='spawn_point', + default_value='' + ), + launch.actions.DeclareLaunchArgument( + name='objects_definition_file', + default_value=get_package_share_directory( + 'carla_ros_bridge') + '/test/test_objects.json' + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_ros_bridge'), 'carla_ros_bridge.launch.py') + ), + launch_arguments={ + 'host': launch.substitutions.LaunchConfiguration('host'), + 'port': launch.substitutions.LaunchConfiguration('port'), + 'timeout': launch.substitutions.LaunchConfiguration('timeout'), + 'passive': launch.substitutions.LaunchConfiguration('passive'), + 'synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode'), + 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), + 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') + }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_spawn_objects'), 'carla_spawn_objects.launch.py') + ), + launch_arguments={ + 'objects_definition_file': launch.substitutions.LaunchConfiguration('objects_definition_file') + }.items() + ), + # Start tests + launch_testing.actions.ReadyToTest() + ]) + return ld + +TIMEOUT = 30 + +class TestClock(unittest.TestCase): + + """ + Handles testing of the all nodes + """ + def test_clock(self): + """ + Tests clock + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message("/clock", Clock, timeout=TIMEOUT) + self.assertNotEqual(Clock(), msg) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_vehicle_status(self, proc_output): + """ + Tests vehicle_status + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message("/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus) + self.assertNotEqual(msg.header, Header()) # todo: check frame-id + self.assertNotEqual(msg.orientation, Quaternion()) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_vehicle_info(self): + """ + Tests vehicle_info + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/vehicle_info", CarlaEgoVehicleInfo, timeout=TIMEOUT, + qos_profile=QoSProfile(depth=1, durability=latch_on)) + self.assertNotEqual(msg.id, 0) + self.assertEqual(msg.type, "vehicle.tesla.model3") + self.assertEqual(msg.rolename, "ego_vehicle") + self.assertEqual(len(msg.wheels), 4) + self.assertNotEqual(msg.max_rpm, 0.0) + self.assertNotEqual(msg.moi, 0.0) + self.assertNotEqual(msg.damping_rate_full_throttle, 0.0) + self.assertNotEqual(msg.damping_rate_zero_throttle_clutch_engaged, 0.0) + self.assertNotEqual( + msg.damping_rate_zero_throttle_clutch_disengaged, 0.0) + self.assertTrue(msg.use_gear_autobox) + self.assertNotEqual(msg.gear_switch_time, 0.0) + self.assertNotEqual(msg.mass, 0.0) + self.assertNotEqual(msg.clutch_strength, 0.0) + self.assertNotEqual(msg.drag_coefficient, 0.0) + self.assertNotEqual(msg.center_of_mass, Vector3()) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_odometry(self): + """ + Tests Odometry + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/odometry", Odometry, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "map") + self.assertEqual(msg.child_frame_id, "ego_vehicle") + self.assertNotEqual(msg.pose, Pose()) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_gnss(self): + """ + Tests Gnss + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/gnss", NavSatFix, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/gnss") + self.assertNotEqual(msg.latitude, 0.0) + self.assertNotEqual(msg.longitude, 0.0) + self.assertNotEqual(msg.altitude, 0.0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_imu(self): + """ + Tests IMU sensor node + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message("/carla/ego_vehicle/imu", Imu, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/imu") + self.assertNotEqual(msg.linear_acceleration, 0.0) + self.assertNotEqual(msg.angular_velocity, 0.0) + self.assertNotEqual(msg.orientation, 0.0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_camera_info(self): + """ + Tests camera_info + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/rgb_front/camera_info", CameraInfo, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/rgb_front") + self.assertEqual(msg.height, 600) + self.assertEqual(msg.width, 800) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_camera_image(self): + """ + Tests camera_images + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/rgb_front/image", Image, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/rgb_front") + self.assertEqual(msg.height, 600) + self.assertEqual(msg.width, 800) + self.assertEqual(msg.encoding, "bgra8") + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_dvs_camera_info(self): + """ + Tests dvs camera info + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/dvs_front/camera_info", CameraInfo, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") + self.assertEqual(msg.height, 70) + self.assertEqual(msg.width, 400) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_dvs_camera_image(self): + """ + Tests dvs camera images + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/dvs_front/image", Image, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") + self.assertEqual(msg.height, 70) + self.assertEqual(msg.width, 400) + self.assertEqual(msg.encoding, "bgr8") + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_dvs_camera_events(self): + """ + Tests dvs camera events + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/dvs_front/events", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_lidar(self): + """ + Tests Lidar sensor node + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/lidar", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/lidar") + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_semantic_lidar(self): + """ + Tests semantic_lidar sensor node + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/semantic_lidar", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/semantic_lidar") + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_radar(self): + """ + Tests Radar sensor node + """ + try: + node = None + ros_init() + node = None + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/radar_front", PointCloud2, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "ego_vehicle/radar_front") + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_ego_vehicle_objects(self): + """ + Tests objects node for ego_vehicle + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/ego_vehicle/objects", ObjectArray, timeout=15) + self.assertEqual(msg.header.frame_id, "map") + self.assertEqual(len(msg.objects), 0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_objects(self): + """ + Tests carla objects + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message("/carla/objects", ObjectArray, timeout=TIMEOUT) + self.assertEqual(msg.header.frame_id, "map") + self.assertEqual(len(msg.objects), 1) # only ego vehicle exists + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_marker(self): + """ + Tests marker + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message("/carla/markers", MarkerArray, timeout=TIMEOUT) + self.assertEqual(len(msg.markers), 1) # only ego vehicle exists + + ego_marker = msg.markers[0] + self.assertEqual(ego_marker.header.frame_id, "map") + self.assertNotEqual(ego_marker.id, 0) + self.assertEqual(ego_marker.type, 1) + self.assertNotEqual(ego_marker.pose, Pose()) + self.assertNotEqual(ego_marker.scale, Vector3()) + self.assertEqual(ego_marker.color.r, 0.0) + self.assertEqual(ego_marker.color.g, 255.0) + self.assertEqual(ego_marker.color.b, 0.0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_map(self): + """ + Tests map + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/map", String, timeout=TIMEOUT, + qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.assertNotEqual(len(msg.data), 0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_world_info(self): + """ + Tests world_info + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/world_info", CarlaWorldInfo, timeout=TIMEOUT, + qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.assertNotEqual(len(msg.map_name), 0) + self.assertNotEqual(len(msg.opendrive), 0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_actor_list(self): + """ + Tests actor_list + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/actor_list", CarlaActorList, timeout=TIMEOUT) + self.assertNotEqual(len(msg.actors), 0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_traffic_lights(self): + """ + Tests traffic_lights + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/traffic_lights/status", CarlaTrafficLightStatusList, timeout=TIMEOUT, + qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.assertNotEqual(len(msg.traffic_lights), 0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() + + def test_traffic_lights_info(self): + """ + Tests traffic_lights + """ + try: + node = None + ros_init() + node = CompatibleNode('test_node') + msg = node.wait_for_one_message( + "/carla/traffic_lights/info", CarlaTrafficLightInfoList, timeout=TIMEOUT, + qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.assertNotEqual(len(msg.traffic_lights), 0) + finally: + if node is not None: + node.destroy_node() + ros_shutdown() \ No newline at end of file diff --git a/carla_spawn_objects/config/settings.yaml b/carla_ros_bridge/test/settings.yaml similarity index 100% rename from carla_spawn_objects/config/settings.yaml rename to carla_ros_bridge/test/settings.yaml diff --git a/carla_ros_bridge/test/test_objects.json b/carla_ros_bridge/test/test_objects.json index cf461ce6..b426c5da 100644 --- a/carla_ros_bridge/test/test_objects.json +++ b/carla_ros_bridge/test/test_objects.json @@ -22,7 +22,7 @@ "id": "map" }, { - "type": "vehicle.audi.tt", + "type": "vehicle.tesla.model3", "id": "ego_vehicle", "sensors": [ diff --git a/carla_spawn_objects/setup.py b/carla_spawn_objects/setup.py index 17213b88..fe09fcd3 100644 --- a/carla_spawn_objects/setup.py +++ b/carla_spawn_objects/setup.py @@ -29,7 +29,7 @@ ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ('share/' + package_name + '/config', - ['config/settings.yaml', 'config/objects.json']), + ['config/objects.json']), (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], From f205f57e60f16c215f78be9f091bff5578b21d75 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 4 Jan 2021 13:13:28 +0100 Subject: [PATCH 465/627] Update service calling --- .../carla_ros_bridge/traffic_participant.py | 6 +- .../carla_spawn_objects.py | 102 +++++++++++------- .../ros_compatibility/ros_compatible_node.py | 19 ++-- 3 files changed, 75 insertions(+), 52 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index cb32b791..d906a0a1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -107,9 +107,9 @@ def get_marker_color(self): # pylint: disable=no-self-use :rtpye : std_msgs.msg.ColorRGBA """ color = ColorRGBA() - color.r = 0 - color.g = 0 - color.b = 255 + color.r = 0. + color.g = 0. + color.b = 255. return color def get_marker_pose(self): diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index b77b6604..4f9f1682 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -18,6 +18,7 @@ import os import math import json +from threading import Thread from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import Pose @@ -37,7 +38,9 @@ logwarn, logerr, ros_ok, - get_service_request + get_service_request, + ros_shutdown, + ROS_VERSION ) # ============================================================================== @@ -66,6 +69,22 @@ def __init__(self): self.destroy_object_service = self.create_service_client( "/carla/destroy_object", DestroyObject) + def spawn_object(self, spawn_object_request): + response_id= -1 + try: + response = self.call_service(self.spawn_object_service, spawn_object_request) + response_id = response.id + if response_id != -1: + self.loginfo("Object (type='{}', id='{}') spawned successfully as {}.".format( + spawn_object_request.type, spawn_object_request.id, response_id)) + else: + self.logwarn("Error while spawning object (type='{}', id='{}').".format( + spawn_object_request.type, spawn_object_request.id)) + raise RuntimeError(response.error_string) + except ServiceException as e: + self.logwarn("Error while calling spawn_object(type='{}', id='{}'): {}".format(spawn_object_request.type, spawn_object_request.id, e)) + return response_id + def spawn_objects(self): """ Spawns the objects @@ -177,15 +196,16 @@ def setup_vehicles(self, vehicles): spawn_object_request.random_pose = True player_spawned = False - while not player_spawned: + while not player_spawned and ros_ok(): spawn_object_request.transform = spawn_point - response = self.call_service(self.spawn_object_service, spawn_object_request) - if response.id != -1: + + response_id = self.spawn_object(spawn_object_request) + if response_id != -1: player_spawned = True - self.players.append(response.id) + self.players.append(response_id) # Set up the sensors try: - self.setup_sensors(vehicle["sensors"], response.id) + self.setup_sensors(vehicle["sensors"], response_id) except KeyError: self.logwarn( "Object (type='{}', id='{}') has no 'sensors' field in his config file, none will be spawned.".format(spawn_object_request.type, spawn_object_request.id)) @@ -200,6 +220,8 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): """ sensor_names = [] for sensor_spec in sensors: + if not ros_ok(): + break try: sensor_type = str(sensor_spec.pop("type")) sensor_id = str(sensor_spec.pop("id")) @@ -248,18 +270,19 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): spawn_object_request.attributes.append( KeyValue(key=str(attribute), value=str(value))) - response = self.call_service(self.spawn_object_service, spawn_object_request) - if response.id == -1: + response_id = self.spawn_object(spawn_object_request) + + if response_id == -1: raise RuntimeError(response.error_string) if attached_objects: # spawn the attached objects - self.setup_sensors(attached_objects, response.id) + self.setup_sensors(attached_objects, response_id) if attached_vehicle_id is None: - self.global_sensors.append(response.id) + self.global_sensors.append(response_id) else: - self.vehicles_sensors.append(response.id) + self.vehicles_sensors.append(response_id) except KeyError as e: self.logerr( @@ -308,7 +331,7 @@ def destroy(self): """ destroy all the players and sensors """ - self.loginfo("Shutting down.") + self.loginfo("Destroying spawned objects...") # destroy vehicles sensors for actor_id in self.vehicles_sensors: @@ -318,6 +341,7 @@ def destroy(self): self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: self.logwarn(str(e)) + self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.vehicles_sensors = [] # destroy global sensors @@ -327,7 +351,8 @@ def destroy(self): try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: - self.logwarn_once(str(e)) + self.logwarn(str(e)) + self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.global_sensors = [] # destroy player @@ -338,26 +363,9 @@ def destroy(self): self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: self.logwarn(str(e)) + self.loginfo("Object {} successfully destroyed.".format(player_id)) self.players = [] - def run(self): - """ - main loop - """ - self.on_shutdown(self.destroy) - spin = True - try: - self.spawn_objects() - except (ROSInterruptException, ServiceException, KeyboardInterrupt): - spin = False - self.logwarn( - "Spawning process has been interrupted. There might be actors that has not been destroyed properly") - if spin: - try: - self.spin() - except (KeyboardInterrupt): - self.loginfo("Shutdown requested.") - # ============================================================================== # -- main() -------------------------------------------------------------------- # ============================================================================== @@ -371,14 +379,30 @@ def main(args=None): spawn_objects_node = None try: spawn_objects_node = CarlaSpawnObjects() - spawn_objects_node.run() - except RuntimeError as e: - logfatal( - "Exception caught: {}".format(e)) - finally: - if spawn_objects_node is not None: - spawn_objects_node.destroy() - + except KeyboardInterrupt: + logerr("Could not initialize CarlaSpawnObjects. Shutting down.") + + if spawn_objects_node: + if ROS_VERSION == 1: + spawn_objects_node.on_shutdown(spawn_objects_node.destroy) + try: + spawn_objects_node.spawn_objects() + except (ROSInterruptException, ServiceException, KeyboardInterrupt): + spawn_objects_node.logwarn("Spawning process has been interrupted. There might be actors that has not been destroyed properly") + except RuntimeError as e: + logfatal("Exception caught: {}".format(e)) + spawn_objects_node.spin() + else: + spin_thread = Thread(target=spawn_objects_node.spin) + try: + spin_thread.start() + spawn_objects_node.spawn_objects() + spin_thread.join() + except (ROSInterruptException, ServiceException, KeyboardInterrupt): + loginfo("Shutting down.") + spawn_objects_node.destroy() + + ros_shutdown() if __name__ == '__main__': main() diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 6d70e13e..4730ad67 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -1,10 +1,17 @@ # pylint: disable=import-error import os +from threading import Thread, currentThread ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) if ROS_VERSION == 1: import rospy +elif ROS_VERSION == 2: + import rclpy +else: + raise NotImplementedError('Make sure you have valid ROS_VERSION env variable.') + +if ROS_VERSION == 1: import tf.transformations as trans latch_on = True @@ -139,7 +146,7 @@ def call_service(self, client, req): try: return client(req) except rospy.ServiceException as e: - print("Service call failed: %s" % e) + raise ServiceException(e) def spin(self, executor=None): rospy.spin() @@ -159,7 +166,6 @@ def on_shutdown(self, handler): from rclpy.exceptions import ROSInterruptException from rclpy.node import Node from rclpy.qos import QoSProfile, QoSDurabilityPolicy - import rclpy from builtin_interfaces.msg import Time latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL @@ -318,14 +324,7 @@ def create_service_client(self, service_name, service, callback_group=None): return client def call_service(self, client, req): - resp = client.call_async(req) - rclpy.spin_until_future_complete(self, resp) - try: - result = resp.result() - except Exception as e: - node.get_logger().info('Service call failed %r' % (e,)) - else: - return result + return client.call(req) def spin(self, executor=None): rclpy.spin(self, executor) From 07a04f17395ec1fa3ffceb2865f3561bc4ded947 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 4 Jan 2021 16:38:29 +0100 Subject: [PATCH 466/627] Codeformatting --- .../src/carla_spawn_objects/carla_spawn_objects.py | 13 ++++++++----- .../src/ros_compatibility/ros_compatible_node.py | 2 +- 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 4f9f1682..10938966 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -70,7 +70,7 @@ def __init__(self): "/carla/destroy_object", DestroyObject) def spawn_object(self, spawn_object_request): - response_id= -1 + response_id = -1 try: response = self.call_service(self.spawn_object_service, spawn_object_request) response_id = response.id @@ -82,7 +82,8 @@ def spawn_object(self, spawn_object_request): spawn_object_request.type, spawn_object_request.id)) raise RuntimeError(response.error_string) except ServiceException as e: - self.logwarn("Error while calling spawn_object(type='{}', id='{}'): {}".format(spawn_object_request.type, spawn_object_request.id, e)) + self.logwarn("Error while calling spawn_object(type='{}', id='{}'): {}".format( + spawn_object_request.type, spawn_object_request.id, e)) return response_id def spawn_objects(self): @@ -271,7 +272,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): KeyValue(key=str(attribute), value=str(value))) response_id = self.spawn_object(spawn_object_request) - + if response_id == -1: raise RuntimeError(response.error_string) @@ -381,14 +382,15 @@ def main(args=None): spawn_objects_node = CarlaSpawnObjects() except KeyboardInterrupt: logerr("Could not initialize CarlaSpawnObjects. Shutting down.") - + if spawn_objects_node: if ROS_VERSION == 1: spawn_objects_node.on_shutdown(spawn_objects_node.destroy) try: spawn_objects_node.spawn_objects() except (ROSInterruptException, ServiceException, KeyboardInterrupt): - spawn_objects_node.logwarn("Spawning process has been interrupted. There might be actors that has not been destroyed properly") + spawn_objects_node.logwarn( + "Spawning process has been interrupted. There might be actors that has not been destroyed properly") except RuntimeError as e: logfatal("Exception caught: {}".format(e)) spawn_objects_node.spin() @@ -404,5 +406,6 @@ def main(args=None): ros_shutdown() + if __name__ == '__main__': main() diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 4730ad67..9a923237 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -10,7 +10,7 @@ import rclpy else: raise NotImplementedError('Make sure you have valid ROS_VERSION env variable.') - + if ROS_VERSION == 1: import tf.transformations as trans From 7023ca3bf5802cac27cb76d0da2b714ccd4a8e17 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 5 Jan 2021 17:15:25 +0100 Subject: [PATCH 467/627] Fix issues when creating objects attached to actors --- carla_ad_agent/CMakeLists.txt | 1 + .../carla_manual_control.py | 144 ++++++------------ .../src/carla_ros_bridge/actor_factory.py | 27 +++- .../src/carla_ros_bridge/bridge.py | 27 ++-- .../src/carla_ros_bridge/sensor.py | 37 ++--- .../src/carla_ros_bridge/tf_sensor.py | 2 +- .../ros_compatibility/ros_compatible_node.py | 2 +- 7 files changed, 107 insertions(+), 133 deletions(-) diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index a343c226..cb1d900a 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -25,6 +25,7 @@ if(${ROS_VERSION} EQUAL 1) DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) elseif(${ROS_VERSION} EQUAL 2) +#TODO: remove find_package(ament_cmake REQUIRED) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 9f187b03..09b61430 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -42,14 +42,16 @@ latch_on, ros_ok, ros_init, - destroy_subscription) + destroy_subscription, + ros_shutdown, + loginfo, + logwarn, + ROS_VERSION) import os import datetime import math import numpy -ROS_VERSION = int(os.environ['ROS_VERSION']) - if ROS_VERSION == 1: import rospy from rospy import Time @@ -105,16 +107,17 @@ # ============================================================================== -class World(CompatibleNode): +class ManualControl(CompatibleNode): """ Handle the rendering """ - def __init__(self, role_name, hud): - super(World, self).__init__("World", rospy_init=False) + def __init__(self, resolution): + super(ManualControl, self).__init__("ManualControl") self._surface = None - self.hud = hud - self.role_name = role_name + self.role_name = self.get_param("role_name", "ego_vehicle") + self.hud = HUD(self.role_name, resolution['width'], resolution['height'], self) + self.controller = KeyboardControl(self.role_name, self.hud, self) if ROS_VERSION == 1: self.callback_group = None @@ -168,37 +171,34 @@ def on_view_image(self, image): array = array[:, :, ::-1] self._surface = pygame.surfarray.make_surface(array.swapaxes(0, 1)) - def render(self, display): + def render(self, game_clock, display): """ render the current image """ + + do_quit = self.controller.parse_events(game_clock) + if do_quit: + return + self.hud.tick(game_clock) + if self._surface is not None: display.blit(self._surface, (0, 0)) self.hud.render(display) - def destroy(self): - """ - destroy all objects - """ - destroy_subscription(self.image_subscriber) - destroy_subscription(self.collision_subscriber) - destroy_subscription(self.lane_invasion_subscriber) - - # ============================================================================== # -- KeyboardControl ----------------------------------------------------------- # ============================================================================== -class KeyboardControl(CompatibleNode): +class KeyboardControl(object): """ Handle input events """ - def __init__(self, role_name, hud): - super(KeyboardControl, self).__init__("keyboard_control", rospy_init=False) + def __init__(self, role_name, hud, node): self.role_name = role_name self.hud = hud + self.node = node self._autopilot_enabled = False self._control = CarlaEgoVehicleControl() @@ -213,23 +213,23 @@ def __init__(self, role_name, hud): fast_latched_qos = QoSProfile(depth=10, durability=latch_on) # imported from ros_compat. self.vehicle_control_manual_override_publisher = \ - self.new_publisher(Bool, + self.node.new_publisher(Bool, "/carla/{}/vehicle_control_manual_override".format(self.role_name), qos_profile=fast_latched_qos, callback_group=self.callback_group) self.vehicle_control_manual_override = False self.auto_pilot_enable_publisher = \ - self.new_publisher(Bool, + self.node.new_publisher(Bool, "/carla/{}/enable_autopilot".format(self.role_name), qos_profile=fast_qos, callback_group=self.callback_group) self.vehicle_control_publisher = \ - self.new_publisher(CarlaEgoVehicleControl, + self.node.new_publisher(CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), qos_profile=fast_qos, callback_group=self.callback_group) - self.carla_status_subscriber = self.create_subscriber(CarlaStatus, "/carla/status", + self.carla_status_subscriber = self.node.create_subscriber(CarlaStatus, "/carla/status", self._on_new_carla_frame, callback_group=self.callback_group) @@ -238,16 +238,6 @@ def __init__(self, role_name, hud): self.set_vehicle_control_manual_override( self.vehicle_control_manual_override) # disable manual override - def __del__(self): - if ROS_VERSION == 1: - self.auto_pilot_enable_publisher.unregister() - self.vehicle_control_publisher.unregister() - self.vehicle_control_manual_override_publisher.unregister() - elif ROS_VERSION == 2: - self.auto_pilot_enable_publisher.destroy() - self.vehicle_control_publisher.destroy() - self.vehicle_control_manual_override_publisher.destroy() - def set_vehicle_control_manual_override(self, enable): """ Set the manual control override @@ -311,7 +301,7 @@ def _on_new_carla_frame(self, data): try: self.vehicle_control_publisher.publish(self._control) except Exception as error: - self.logwarn("Could not send vehicle control: {}".format(error)) + self.node.logwarn("Could not send vehicle control: {}".format(error)) def _parse_vehicle_keys(self, keys, milliseconds): """ @@ -340,15 +330,15 @@ def _is_quit_shortcut(key): # ============================================================================== -class HUD(CompatibleNode): +class HUD(object): """ Handle the info display """ - def __init__(self, role_name, width, height): - super(HUD, self).__init__(role_name, rospy_init=False) + def __init__(self, role_name, width, height, node): self.role_name = role_name self.dim = (width, height) + self.node = node font = pygame.font.Font(pygame.font.get_default_font(), 20) fonts = [x for x in pygame.font.get_fonts() if 'mono' in x] default_font = 'ubuntumono' @@ -365,22 +355,17 @@ def __init__(self, role_name, width, height): self.tf_listener = tf.TransformListener() self.callback_group = None elif ROS_VERSION == 2: - self.tf_listener_node = rclpy.create_node("tf_listener") self.tf_buffer = tf2_ros.Buffer() - self.tf_listener = tf2_ros.TransformListener(self.tf_buffer, node=self.tf_listener_node) + self.tf_listener = tf2_ros.TransformListener(self.tf_buffer, node=self.node) self.time = Time() self.callback_group = ReentrantCallbackGroup() - self.vehicle_status_subscriber = self.create_subscriber( - CarlaEgoVehicleStatus, "/carla/{}/vehicle_status".format(self.role_name), - self.vehicle_status_updated, callback_group=self.callback_group) - - self.vehicle_status_subscriber = self.create_subscriber( + self.vehicle_status_subscriber = node.create_subscriber( CarlaEgoVehicleStatus, "/carla/{}/vehicle_status".format(self.role_name), self.vehicle_status_updated, callback_group=self.callback_group) self.vehicle_info = CarlaEgoVehicleInfo() - self.vehicle_info_subscriber = self.create_subscriber( + self.vehicle_info_subscriber = node.create_subscriber( CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(self.role_name), self.vehicle_info_updated, callback_group=self.callback_group) @@ -388,34 +373,23 @@ def __init__(self, role_name, width, height): self.longitude = 0 self.manual_control = False - self.gnss_subscriber = self.create_subscriber( + self.gnss_subscriber = node.create_subscriber( NavSatFix, "/carla/{}/gnss".format(self.role_name), self.gnss_updated, callback_group=self.callback_group) - self.manual_control_subscriber = self.create_subscriber( + self.manual_control_subscriber = node.create_subscriber( Bool, "/carla/{}/vehicle_control_manual_override".format(self.role_name), self.manual_control_override_updated, callback_group=self.callback_group) self.carla_status = CarlaStatus() - self.status_subscriber = self.create_subscriber(CarlaStatus, "/carla/status", + self.status_subscriber = node.create_subscriber(CarlaStatus, "/carla/status", self.carla_status_updated, callback_group=self.callback_group) if ROS_VERSION == 2: - self.clock_subscriber = self.create_subscriber(Time, "/clock", + self.clock_subscriber = node.create_subscriber(Time, "/clock", self.clock_status_updated, callback_group=self.callback_group) - def __del__(self): - if ROS_VERSION == 1: - self.gnss_subscriber.unregister() - self.vehicle_status_subscriber.unregister() - self.vehicle_info_subscriber.unregister() - elif ROS_VERSION == 2: - self.gnss_subscriber.destroy() - self.vehicle_status_subscriber.destroy() - self.vehicle_info_subscriber.destroy() - self.clock_subscriber.destroy() - def tick(self, clock): """ tick method @@ -502,7 +476,7 @@ def update_info_text(self): time = str(datetime.timedelta(seconds=float(rospy.get_rostime().to_sec())))[:10] elif ROS_VERSION == 2: time = str(datetime.timedelta(seconds=float( - self.get_clock().now().nanoseconds)/10**9))[:10] + self.node.get_clock().now().nanoseconds)/10**9))[:10] if self.carla_status.fixed_delta_seconds: fps = 1 / self.carla_status.fixed_delta_seconds @@ -681,24 +655,11 @@ def render(self, display): # -- main() -------------------------------------------------------------------- # ============================================================================== - -def run(executer): - executer.spin() - - def main(args=None): """ main function """ ros_init(args) - # TODO - if ROS_VERSION == 1: - rospy.init_node('carla_manual_control', anonymous=True) - role_name = rospy.get_param("~role_name", "ego_vehicle") - elif ROS_VERSION == 2: - node = rclpy.create_node('carla_manual_control') - role_name = rclpy.Parameter("~role_name", value="ego_vehicle").value - thread = Thread() # resolution should be similar to spawned camera with role-name 'view' resolution = {"width": 800, "height": 600} @@ -706,38 +667,31 @@ def main(args=None): pygame.init() pygame.font.init() pygame.display.set_caption("CARLA ROS manual control") - world = None + try: display = pygame.display.set_mode((resolution['width'], resolution['height']), pygame.HWSURFACE | pygame.DOUBLEBUF) - hud = HUD(role_name, resolution['width'], resolution['height']) - world = World(role_name, hud) - controller = KeyboardControl(role_name, hud) + manual_control_node = ManualControl(resolution) clock = pygame.time.Clock() if ROS_VERSION == 2: - executer = rclpy.executors.MultiThreadedExecutor(num_threads=12) - executer.add_node(hud.tf_listener_node) - executer.add_node(hud) - executer.add_node(world) - executer.add_node(controller) - thread = Thread(target=run, args=(executer,)) - thread.start() + executer = rclpy.executors.MultiThreadedExecutor() + executer.add_node(manual_control_node) + spin_thread = Thread(target=executer.spin) + spin_thread.start() while ros_ok(): clock.tick_busy_loop(60) - if controller.parse_events(clock): + if manual_control_node.render(clock, display): return - hud.tick(clock) - world.render(display) pygame.display.flip() - + except KeyboardInterrupt: + loginfo("User requested shut down.") finally: - if world is not None: - world.destroy() - if ROS_VERSION == 2: - thread.join() + ros_shutdown() + if ROS_VERSION == 2: + spin_thread.join() pygame.quit() diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 53f368d9..1a282202 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -34,6 +34,7 @@ from carla_ros_bridge.actor_list_sensor import ActorListSensor from carla_ros_bridge.opendrive_sensor import OpenDriveSensor from carla_ros_bridge.actor_control import ActorControl +from carla_ros_bridge.sensor import Sensor class ActorFactory(object): @@ -46,6 +47,7 @@ def __init__(self, node, world, sync_mode=False): self.sync_mode = sync_mode self.actors = {} + self._newly_spawned_actors = [] # actors that were spawned but are not yet available via world.get_actors() self.lock = Lock() self.spawn_lock = Lock() @@ -53,11 +55,11 @@ def __init__(self, node, world, sync_mode=False): # id generator for pseudo sensors self.id_gen = itertools.count(10000) + self.thread = Thread(target=self._update_thread) + def start(self): # create initially existing actors self.update() - - self.thread = Thread(target=self._update_thread) self.thread.start() def _update_thread(self): @@ -78,14 +80,33 @@ def update(self): previous_actors = set([x.uid for x in self.actors.values() if isinstance(x, Actor)]) current_actors = set([x.id for x in self.world.get_actors()]) + # create bridge objects for actors that were created from outside the bridge new_actors = current_actors - previous_actors for actor_id in new_actors: carla_actor = self.world.get_actor(actor_id) self._create_carla_actor(carla_actor) + # remove bridge objects for actors that were deleted from outside the bridge deleted_actors = previous_actors - current_actors + # world.get_actors() does not report the newly created actors until the next tick, + # therefore use newly_spawned_actors list to remove all actors from list, that were just created + if deleted_actors: + deleted_actors = [x for x in deleted_actors if x not in self._newly_spawned_actors] for actor_id in deleted_actors: self.destroy(actor_id) + self._newly_spawned_actors.clear() + + def update_actor_states(self, frame_id, timestamp): + """ + update the state of all known actors + """ + for actor_id in self.actors: + try: + self.actors[actor_id].update(frame_id, timestamp) + except RuntimeError as e: + self.node.logwarn("Update actor {}({}) failed: {}".format( + self.actors[actor_id].__class__.__name__, actor_id, e)) + continue def clear(self): ids = self.actors.keys() @@ -111,6 +132,8 @@ def _create_carla_actor(self, carla_actor): def create(self, type_id, name, attach_to, spawn_pose, carla_actor=None): with self.lock: + if carla_actor: + self._newly_spawned_actors.append(carla_actor.id) # check that the actor is not already created. if carla_actor is not None and carla_actor.id in self.actors: return None diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index ab1bbc91..12cac0eb 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -73,6 +73,10 @@ class CarlaRosBridge(CompatibleNode): CARLA_VERSION = "0.9.10" + # in synchronous mode, if synchronous_mode_wait_for_vehicle_control_command is True, + # wait for this time until a next tick is triggered. + VEHICLE_CONTROL_TIMEOUT = 1. + def __init__(self, rospy_init=True, executor=None): """ Constructor @@ -184,7 +188,7 @@ def initialize_bridge(self, carla_world, params): self.destroy_object) self.get_blueprints_service = self.new_service(GetBlueprints, "/carla/get_blueprints", - self.get_blueprints) + self.get_blueprints, callback_group=self.callback_group) self.carla_weather_subscriber = \ self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", @@ -342,7 +346,6 @@ def _synchronous_mode_update(self): if isinstance(actor, EgoVehicle): self._expected_ego_vehicle_control_command_ids.append( actor_id) - frame = self.carla_world.tick() world_snapshot = self.carla_world.get_snapshot() @@ -358,9 +361,9 @@ def _synchronous_mode_update(self): if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: # wait for all ego vehicles to send a vehicle control command if self._expected_ego_vehicle_control_command_ids: - if not self._all_vehicle_control_commands_received.wait(1): - self.logwarn("Timeout (1s) while waiting for vehicle control commands. " - "Missing command from actor ids {}".format( + if not self._all_vehicle_control_commands_received.wait(CarlaRosBridge.VEHICLE_CONTROL_TIMEOUT): + self.logwarn("Timeout ({}s) while waiting for vehicle control commands. " + "Missing command from actor ids {}".format(CarlaRosBridge.VEHICLE_CONTROL_TIMEOUT, self._expected_ego_vehicle_control_command_ids)) self._all_vehicle_control_commands_received.clear() @@ -393,17 +396,8 @@ def _update(self, frame_id, timestamp): update all actors :return: """ - # update world info self.world_info.update(frame_id, timestamp) - - # update all carla actors - for actor_id in self.actor_factory.actors: - try: - self.actor_factory.actors[actor_id].update(frame_id, timestamp) - except RuntimeError as e: - self.logwarn("Update actor {}({}) failed: {}".format( - self.actor_factory.actors[actor_id].__class__.__name__, actor_id, e)) - continue + self.actor_factory.update_actor_states(frame_id, timestamp) def _ego_vehicle_control_applied_callback(self, ego_vehicle_id): if not self.sync_mode or \ @@ -475,9 +469,8 @@ def main(args=None): # rospy.init_node('carla_ros_bridge', anonymous=True) elif ROS_VERSION == 2: - executor = rclpy.executors.MultiThreadedExecutor(num_threads=12) + executor = rclpy.executors.MultiThreadedExecutor() carla_bridge = CarlaRosBridge(executor=executor) - # init_node = rclpy.create_node("init_ros_bridge") executor.add_node(carla_bridge) parameters['host'] = carla_bridge.get_param('host', 'localhost') diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 9c15f636..601fd0b2 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -100,8 +100,11 @@ def __init__(self, # pylint: disable=too-many-arguments elif ROS_VERSION == 2: self._tf_broadcaster = tf2_ros.TransformBroadcaster(node) - def publish_tf(self, pose=None): + def publish_tf(self, pose, timestamp): if self.synchronous_mode: + if not self.relative_spawn_pose: + self.node.loginfo("SKIP {}".format(self.get_prefix())) + return pose = self.relative_spawn_pose child_frame_id = self.get_prefix() if self.parent is not None: @@ -112,23 +115,23 @@ def publish_tf(self, pose=None): else: child_frame_id = self.get_prefix() frame_id = "map" + #self.node.logwarn("TF {} {} pose {}".format(self.get_prefix(), timestamp, pose)) - if pose is not None: - transform = tf2_ros.TransformStamped() - transform.header.stamp = ros_timestamp(sec=self.node.get_time(), from_sec=True) - transform.header.frame_id = frame_id - transform.child_frame_id = child_frame_id + transform = tf2_ros.TransformStamped() + transform.header.stamp = ros_timestamp(sec=timestamp, from_sec=True) + transform.header.frame_id = frame_id + transform.child_frame_id = child_frame_id - transform.transform.translation.x = pose.position.x - transform.transform.translation.y = pose.position.y - transform.transform.translation.z = pose.position.z + transform.transform.translation.x = pose.position.x + transform.transform.translation.y = pose.position.y + transform.transform.translation.z = pose.position.z - transform.transform.rotation.x = pose.orientation.x - transform.transform.rotation.y = pose.orientation.y - transform.transform.rotation.z = pose.orientation.z - transform.transform.rotation.w = pose.orientation.w + transform.transform.rotation.x = pose.orientation.x + transform.transform.rotation.y = pose.orientation.y + transform.transform.rotation.z = pose.orientation.z + transform.transform.rotation.w = pose.orientation.w - self._tf_broadcaster.sendTransform(transform) + self._tf_broadcaster.sendTransform(transform) def listen(self): self.carla_actor.listen(self._callback_sensor_data) @@ -161,7 +164,7 @@ def _callback_sensor_data(self, carla_sensor_data): float(self.sensor_tick_time) self.queue.put(carla_sensor_data) else: - self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform)) + self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform), carla_sensor_data.timestamp) self.sensor_data_updated(carla_sensor_data) @abstractmethod @@ -187,7 +190,7 @@ def _update_synchronous_event_sensor(self, frame): carla_sensor_data.frame, frame)) self.node.logdebug("{}({}): process {}".format( self.__class__.__name__, self.get_id(), frame)) - self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform)) + self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform), frame) self.sensor_data_updated(carla_sensor_data) except queue.Empty: return @@ -204,7 +207,7 @@ def _update_synchronous_sensor(self, frame, timestamp): self.node.logdebug("{}({}): process {}".format(self.__class__.__name__, self.get_id(), frame)) self.publish_tf(trans.carla_transform_to_ros_pose( - carla_sensor_data.transform)) + carla_sensor_data.transform), timestamp) self.sensor_data_updated(carla_sensor_data) return elif carla_sensor_data.frame < frame: diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 499a6bd4..10ddf812 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -62,6 +62,6 @@ def update(self, frame, timestamp): """ self.parent.get_prefix() self._tf_broadcaster.sendTransform(TransformStamped( - header=self.get_msg_header("map"), + header=self.get_msg_header("map", timestamp=timestamp), child_frame_id=self.parent.get_prefix(), transform=self.parent.get_current_ros_transform())) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 9a923237..d25a8820 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -315,7 +315,7 @@ def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None return wfm.msg def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): - return self.create_service(srv_type, srv_name, callback) + return self.create_service(srv_type, srv_name, callback, callback_group=callback_group) def create_service_client(self, service_name, service, callback_group=None): client = self.create_client(service, service_name, callback_group=callback_group) From 846a8118bc43ead47a4622818db7b1ddc93237f8 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 8 Jan 2021 17:54:20 +0100 Subject: [PATCH 468/627] Update actor factory and cleanup --- carla_common/src/carla_common/transforms.py | 20 ++ .../src/carla_ros_bridge/actor_factory.py | 259 +++++++++++++----- .../src/carla_ros_bridge/actor_list_sensor.py | 3 +- .../src/carla_ros_bridge/bridge.py | 140 +++------- .../src/carla_ros_bridge/camera.py | 10 +- .../carla_status_publisher.py | 6 +- .../src/carla_ros_bridge/collision_sensor.py | 4 + .../src/carla_ros_bridge/ego_vehicle.py | 14 +- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 4 + carla_ros_bridge/src/carla_ros_bridge/imu.py | 4 + .../carla_ros_bridge/lane_invasion_sensor.py | 4 + .../src/carla_ros_bridge/lidar.py | 8 + .../src/carla_ros_bridge/marker_sensor.py | 1 + .../src/carla_ros_bridge/object_sensor.py | 3 +- .../src/carla_ros_bridge/odom_sensor.py | 13 +- .../src/carla_ros_bridge/opendrive_sensor.py | 4 + .../src/carla_ros_bridge/radar.py | 4 + .../src/carla_ros_bridge/sensor.py | 26 +- .../carla_ros_bridge/speedometer_sensor.py | 13 +- .../src/carla_ros_bridge/tf_sensor.py | 11 +- .../carla_ros_bridge/traffic_lights_sensor.py | 4 +- .../src/carla_ros_bridge/walker.py | 4 +- .../src/carla_ros_bridge/world_info.py | 1 - .../ros_compatibility/ros_compatible_node.py | 12 +- 24 files changed, 361 insertions(+), 211 deletions(-) diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index 300616b6..5146e3b6 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -16,6 +16,7 @@ from geometry_msgs.msg import Vector3, Quaternion, Transform, Pose, Point, Twist, Accel # pylint: disable=import-error from transforms3d.euler import euler2mat, quat2euler, euler2quat +from transforms3d.quaternions import quat2mat, mat2quat def carla_location_to_numpy_vector(carla_location): @@ -324,3 +325,22 @@ def ros_pose_to_carla_transform(ros_pose): return carla.Transform( ros_point_to_carla_location(ros_pose.position), ros_quaternion_to_carla_rotation(ros_pose.orientation)) + +def transform_matrix_to_ros_pose(mat): + """ + Convert a transform matrix to a ROS pose. + """ + quat = mat2quat(mat[:3,:3]) + msg = Pose() + msg.position=Point(x=mat[0, 3], y=mat[1, 3], z=mat[2, 3]) + msg.orientation=Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3]) + return msg + +def ros_pose_to_transform_matrix(msg): + """ + Convert a ROS pose to a transform matrix + """ + mat44 = numpy.eye(4) + mat44[:3,:3] = quat2mat([msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z]) + mat44[0:3, -1] = [msg.position.x, msg.position.y, msg.position.z] + return mat44 \ No newline at end of file diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 1a282202..0228c51e 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -9,7 +9,13 @@ import time from threading import Thread, Lock import itertools +from enum import Enum +try: + import queue +except ImportError: + import Queue as queue + from carla_ros_bridge.actor import Actor from carla_ros_bridge.spectator import Spectator from carla_ros_bridge.traffic import Traffic, TrafficLight @@ -35,19 +41,38 @@ from carla_ros_bridge.opendrive_sensor import OpenDriveSensor from carla_ros_bridge.actor_control import ActorControl from carla_ros_bridge.sensor import Sensor +import carla_common.transforms as trans +import carla +import numpy as np +from geometry_msgs.msg import Pose, Quaternion, Point + +# to generate a random spawning position or vehicles +import random +secure_random = random.SystemRandom() class ActorFactory(object): TIME_BETWEEN_UPDATES = 0.1 + class TaskType(Enum): + SPAWN_PSEUDO_ACTOR = 0 + DESTROY_ACTOR = 1 + SYNC = 2 + def __init__(self, node, world, sync_mode=False): self.node = node self.world = world + self.blueprint_lib = self.world.get_blueprint_library() + self.spawn_points = self.world.get_map().get_spawn_points() self.sync_mode = sync_mode + self._previous_actor_ids = [] self.actors = {} - self._newly_spawned_actors = [] # actors that were spawned but are not yet available via world.get_actors() + + self._task_queue = queue.Queue() + self._last_task = None + self._known_actor_ids = [] # used to immediately reply to spawn_actor/destroy_actor calls self.lock = Lock() self.spawn_lock = Lock() @@ -59,7 +84,7 @@ def __init__(self, node, world, sync_mode=False): def start(self): # create initially existing actors - self.update() + self.update_available_objects() self.thread.start() def _update_thread(self): @@ -68,58 +93,156 @@ def _update_thread(self): """ while not self.node.shutdown.is_set(): time.sleep(ActorFactory.TIME_BETWEEN_UPDATES) - with self.spawn_lock: - self.world.wait_for_tick() - self.update() + self.world.wait_for_tick() + self.update_available_objects() - def update(self): + def add_task(self, task): + if self._last_task != ActorFactory.TaskType.SYNC or task[0] != ActorFactory.TaskType.SYNC: + self._task_queue.put(task) + self._last_task = task[0] + + def update_available_objects(self): """ update the available actors """ # get only carla actors - previous_actors = set([x.uid for x in self.actors.values() if isinstance(x, Actor)]) - current_actors = set([x.id for x in self.world.get_actors()]) + previous_actors = self._previous_actor_ids + current_actors = [x.id for x in self.world.get_actors()] + self._previous_actor_ids = current_actors + + new_actors = [x for x in current_actors if x not in previous_actors] + deleted_actors = [x for x in previous_actors if x not in current_actors] - # create bridge objects for actors that were created from outside the bridge - new_actors = current_actors - previous_actors + # Actual creation/removal of objects + self.lock.acquire() for actor_id in new_actors: carla_actor = self.world.get_actor(actor_id) - self._create_carla_actor(carla_actor) - - # remove bridge objects for actors that were deleted from outside the bridge - deleted_actors = previous_actors - current_actors - # world.get_actors() does not report the newly created actors until the next tick, - # therefore use newly_spawned_actors list to remove all actors from list, that were just created - if deleted_actors: - deleted_actors = [x for x in deleted_actors if x not in self._newly_spawned_actors] + self._create_object_from_actor(carla_actor) + for actor_id in deleted_actors: - self.destroy(actor_id) - self._newly_spawned_actors.clear() + self._destroy_object(actor_id, delete_actor=False) + + # update objects for pseudo actors here as they might have an carla actor as parent ###### + with self.spawn_lock: + while not self._task_queue.empty(): + task = self._task_queue.get() + if task[0] == ActorFactory.TaskType.SPAWN_PSEUDO_ACTOR: + pseudo_object = task[1] + self._create_object(pseudo_object[0], pseudo_object[1].type, pseudo_object[1].id, pseudo_object[1].attach_to, pseudo_object[1].transform) + elif task[0] == ActorFactory.TaskType.DESTROY_ACTOR: + actor_id = task[1] + self._destroy_object(actor_id, delete_actor=True) + elif task[0] == ActorFactory.TaskType.SYNC: + break + self.lock.release() + def update_actor_states(self, frame_id, timestamp): """ update the state of all known actors """ - for actor_id in self.actors: - try: - self.actors[actor_id].update(frame_id, timestamp) - except RuntimeError as e: - self.node.logwarn("Update actor {}({}) failed: {}".format( - self.actors[actor_id].__class__.__name__, actor_id, e)) - continue + with self.lock: + for actor_id in self.actors: + try: + self.actors[actor_id].update(frame_id, timestamp) + except RuntimeError as e: + self.node.logwarn("Update actor {}({}) failed: {}".format( + self.actors[actor_id].__class__.__name__, actor_id, e)) + continue def clear(self): - ids = self.actors.keys() - for id_ in list(ids): - self.destroy(id_) + for _, actor in self.actors.items(): + actor.destroy() + self.actors.clear() + + def spawn_actor(self, req): + """ + spawns an object + + No object instances are created here. Instead carla-actors are created, + and pseudo objects are appended to a list to get created later. + """ + with self.spawn_lock: + if "pseudo" in req.type: + #only allow spawning pseudo objects if parent actor already exists in carla + if req.attach_to != 0: + carla_actor = self.world.get_actor(req.attach_to) + if carla_actor is None: + raise IndexError("Parent actor {} not found".format(req.attach_to)) + id_ = next(self.id_gen) + self.add_task((ActorFactory.TaskType.SPAWN_PSEUDO_ACTOR, (id_, req))) + else: + id_ = self._spawn_carla_actor(req) + self.add_task((ActorFactory.TaskType.SYNC, None)) + self._known_actor_ids.append(id_) + return id_ + + def destroy_actor(self, uid): + with self.spawn_lock: + objects_to_destroy = set(self._destroy_actor(uid)) + for obj in objects_to_destroy: + self.add_task((ActorFactory.TaskType.DESTROY_ACTOR, obj)) + return objects_to_destroy + + def _destroy_actor(self, uid): + objects_to_destroy = [] + if uid in self._known_actor_ids: + objects_to_destroy.append(uid) + self._known_actor_ids.remove(uid) + + # remove actors that have the actor to be removed as parent. + for actor in list(self.actors.values()): + if actor.parent is not None and actor.parent.uid == uid: + objects_to_destroy.extend(self._destroy_actor(actor.uid)) + + return objects_to_destroy + + def _spawn_carla_actor(self, req): + """ + spawns an actor in carla + """ + if "*" in req.type: + blueprint = secure_random.choice( + self.blueprint_lib.filter(req.type)) + else: + blueprint = self.blueprint_lib.find(req.type) + blueprint.set_attribute('role_name', req.id) + for attribute in req.attributes: + blueprint.set_attribute(attribute.key, attribute.value) + if req.random_pose is False: + transform = trans.ros_pose_to_carla_transform(req.transform) + else: + # get a random pose + transform = secure_random.choice( + self.spawn_points) if self.spawn_points else carla.Transform() + + attach_to = None + if req.attach_to != 0: + attach_to = self.world.get_actor(req.attach_to) + if attach_to is None: + raise IndexError("Parent actor {} not found".format(req.attach_to)) + + carla_actor = self.world.spawn_actor(blueprint, transform, attach_to) + return carla_actor.id - def _create_carla_actor(self, carla_actor): + + def _create_object_from_actor(self, carla_actor): + """ + create a object for a given carla actor + Creates also the object for its parent, if not yet existing + """ parent = None + relative_transform = None if carla_actor.parent: if carla_actor.parent.id in self.actors: parent = self.actors[carla_actor.parent.id] else: - parent = self._create_carla_actor(carla_actor.parent) + parent = self._create_object_from_actor(carla_actor.parent) + # calculate relative transform + actor_transform_matrix = trans.ros_pose_to_transform_matrix(trans.carla_transform_to_ros_pose(carla_actor.get_transform())) + parent_transform_matrix = trans.ros_pose_to_transform_matrix(trans.carla_transform_to_ros_pose(carla_actor.parent.get_transform())) + relative_transform_matrix = np.matrix(parent_transform_matrix).getI() * np.matrix(actor_transform_matrix) + relative_transform = trans.transform_matrix_to_ros_pose(relative_transform_matrix) parent_id = 0 if parent is not None: @@ -128,45 +251,22 @@ def _create_carla_actor(self, carla_actor): name = carla_actor.attributes.get("role_name", "") if not name: name = str(carla_actor.id) - return self.create(carla_actor.type_id, name, parent_id, None, carla_actor) - - def create(self, type_id, name, attach_to, spawn_pose, carla_actor=None): - with self.lock: - if carla_actor: - self._newly_spawned_actors.append(carla_actor.id) - # check that the actor is not already created. - if carla_actor is not None and carla_actor.id in self.actors: - return None - - if attach_to != 0: - if attach_to not in self.actors: - raise IndexError("Parent object {} not found".format(attach_to)) - parent = self.actors[attach_to] - else: - parent = None - - if carla_actor is not None: - uid = carla_actor.id - else: - uid = next(self.id_gen) - - actor = self._create_object(uid, type_id, name, parent, spawn_pose, carla_actor) - self.actors[actor.uid] = actor - - self.node.loginfo("Created {}(id={})".format(actor.__class__.__name__, actor.uid)) - - return actor - - def destroy(self, actor_id): - with self.lock: - # check that the actor is not already removed. - if actor_id not in self.actors: - return - - actor = self.actors.pop(actor_id) - actor.destroy() - - self.node.loginfo("Removed {}(id={})".format(actor.__class__.__name__, actor.uid)) + obj = self._create_object(carla_actor.id, carla_actor.type_id, name, parent_id, relative_transform, carla_actor) + return obj + + + def _destroy_object(self, actor_id, delete_actor): + if actor_id not in self.actors: + return + actor = self.actors[actor_id] + del self.actors[actor_id] + carla_actor = None + if isinstance(actor, Actor): + carla_actor = actor.carla_actor + actor.destroy() + if carla_actor and delete_actor: + carla_actor.destroy() + self.node.loginfo("Removed {}(id={})".format(actor.__class__.__name__, actor.uid)) def get_pseudo_sensor_types(self): pseudo_sensors = [] @@ -175,7 +275,19 @@ def get_pseudo_sensor_types(self): pseudo_sensors.append(cls.get_blueprint_name()) return pseudo_sensors - def _create_object(self, uid, type_id, name, parent, spawn_pose, carla_actor=None): + def _create_object(self, uid, type_id, name, attach_to, spawn_pose, carla_actor=None): + # check that the actor is not already created. + if carla_actor is not None and carla_actor.id in self.actors: + return None + + if attach_to != 0: + if attach_to not in self.actors: + raise IndexError("Parent object {} not found".format(attach_to)) + + parent = self.actors[attach_to] + else: + parent = None + if type_id == TFSensor.get_blueprint_name(): actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) @@ -308,4 +420,7 @@ def _create_object(self, uid, type_id, name, parent, spawn_pose, carla_actor=Non else: actor = Actor(uid, name, parent, self.node, carla_actor) + self.actors[actor.uid] = actor + self.node.loginfo("Created {}(id={})".format(actor.__class__.__name__, actor.uid)) + return actor diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py index e974eaed..9331ce49 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -49,8 +49,9 @@ def destroy(self): Function to destroy this object. :return: """ - self.actor_list = None super(ActorListSensor, self).destroy() + self.actor_list = None + self.node.destroy_publisher(self.actor_list_publisher) @staticmethod def get_blueprint_name(): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 12cac0eb..7f25fb29 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -31,7 +31,6 @@ from distutils.version import LooseVersion from threading import Thread, Lock, Event import pkg_resources -import random from rosgraph_msgs.msg import Clock import carla @@ -46,11 +45,6 @@ from carla_msgs.msg import CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, DestroyObject, GetBlueprints -import carla_common.transforms as trans - -# to generate a random spawning position or vehicles -secure_random = random.SystemRandom() - ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -106,6 +100,7 @@ def initialize_bridge(self, carla_world, params): self.synchronous_mode_update_thread = None self.shutdown = Event() + self.synchronous_update_finished_event = Event() self.carla_settings = carla_world.get_settings() if not self.parameters["passive"]: @@ -144,10 +139,7 @@ def initialize_bridge(self, carla_world, params): self.debug_helper = DebugHelper(carla_world.debug, self) # Communication topics - if ROS_VERSION == 1: - self.clock_publisher = self.new_publisher(Clock, 'clock') - elif ROS_VERSION == 2: - self.clock_publisher = self.new_publisher(Clock, 'clock') + self.clock_publisher = self.new_publisher(Clock, 'clock') self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode, @@ -194,81 +186,25 @@ def initialize_bridge(self, carla_world, params): self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", self.on_weather_changed, callback_group=self.callback_group) - def _spawn_actor(self, req): - if "*" in req.type: - blueprint = secure_random.choice( - self.carla_world.get_blueprint_library().filter(req.type)) - else: - blueprint = self.carla_world.get_blueprint_library().find(req.type) - blueprint.set_attribute('role_name', req.id) - for attribute in req.attributes: - blueprint.set_attribute(attribute.key, attribute.value) - if req.random_pose is False: - transform = trans.ros_pose_to_carla_transform(req.transform) - else: - # get a random pose - spawn_points = self.carla_world.get_map().get_spawn_points() - transform = secure_random.choice( - spawn_points) if spawn_points else carla.Transform() - - attach_to = None - if req.attach_to != 0: - attach_to = self.carla_world.get_actor(req.attach_to) - if attach_to is None: - raise IndexError("Parent actor {} not found".format(req.attach_to)) - - carla_actor = self.carla_world.spawn_actor(blueprint, transform, attach_to) - actor = self.actor_factory.create( - req.type, req.id, req.attach_to, req.transform, carla_actor) - return actor.uid - - def _spawn_pseudo_actor(self, req): - actor = self.actor_factory.create(req.type, req.id, req.attach_to, req.transform) - return actor.uid - def spawn_object(self, req, response=None): response = get_service_response(SpawnObject) - with self.actor_factory.spawn_lock: - try: - if "pseudo" in req.type: - id_ = self._spawn_pseudo_actor(req) - else: - id_ = self._spawn_actor(req) - self._registered_actors.append(id_) - response.id = id_ - except Exception as e: - self.logwarn("Error spawning object '{}': {}".format(req.type, e)) - response.id = -1 - response.error_string = str(e) + try: + id_ = self.actor_factory.spawn_actor(req) + self._registered_actors.append(id_) + response.id = id_ + except Exception as e: + self.logwarn("Error spawning object '{}': {}".format(req.type, e)) + response.id = -1 + response.error_string = str(e) return response - def _destroy_actor(self, uid): - if uid not in self.actor_factory.actors: - return False - - # remove actors that have the actor to be removed as parent. - for actor in list(self.actor_factory.actors.values()): - if actor.parent is not None and actor.parent.uid == uid: - if actor.uid in self._registered_actors: - success = self._destroy_actor(actor.uid) - if not success: - return False - - actor = self.actor_factory.actors[uid] - if isinstance(actor, Actor): - actor.carla_actor.destroy() - - self.actor_factory.destroy(uid) - if uid in self._registered_actors: - self._registered_actors.remove(uid) - - return True - def destroy_object(self, req, response=None): response = get_service_response(DestroyObject) - with self.actor_factory.spawn_lock: - response.success = self._destroy_actor(req.id) - return response + destroyed_actors = self.actor_factory.destroy_actor(req.id) + response.success = bool(destroyed_actors) + for actor in destroyed_actors: + if actor in self._registered_actors: self._registered_actors.remove(actor) + return response def get_blueprints(self, req): response = get_service_response(GetBlueprints) @@ -336,6 +272,7 @@ def _synchronous_mode_update(self): execution loop for synchronous mode """ while not self.shutdown.is_set(): + self.synchronous_update_finished_event.clear() self.process_run_state() if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: @@ -353,10 +290,9 @@ def _synchronous_mode_update(self): self.update_clock(world_snapshot.timestamp) self.logdebug("Tick for frame {} returned. Waiting for sensor data...".format( frame)) - with self.actor_factory.lock: - self._update(frame, world_snapshot.timestamp.elapsed_seconds) + self._update(frame, world_snapshot.timestamp.elapsed_seconds) self.logdebug("Waiting for sensor data finished.") - self.actor_factory.update() + self.actor_factory.update_available_objects() if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: # wait for all ego vehicles to send a vehicle control command @@ -366,6 +302,7 @@ def _synchronous_mode_update(self): "Missing command from actor ids {}".format(CarlaRosBridge.VEHICLE_CONTROL_TIMEOUT, self._expected_ego_vehicle_control_command_ids)) self._all_vehicle_control_commands_received.clear() + self.synchronous_update_finished_event.set() def _carla_time_tick(self, carla_snapshot): """ @@ -382,14 +319,12 @@ def _carla_time_tick(self, carla_snapshot): :return: """ if not self.shutdown.is_set(): - if self.actor_factory.lock.acquire(False): - if self.timestamp_last_run < carla_snapshot.timestamp.elapsed_seconds: - self.timestamp_last_run = carla_snapshot.timestamp.elapsed_seconds - self.update_clock(carla_snapshot.timestamp) - self.status_publisher.set_frame(carla_snapshot.frame) - self._update(carla_snapshot.frame, - carla_snapshot.timestamp.elapsed_seconds) - self.actor_factory.lock.release() + if self.timestamp_last_run < carla_snapshot.timestamp.elapsed_seconds: + self.timestamp_last_run = carla_snapshot.timestamp.elapsed_seconds + self.update_clock(carla_snapshot.timestamp) + self.status_publisher.set_frame(carla_snapshot.frame) + self._update(carla_snapshot.frame, + carla_snapshot.timestamp.elapsed_seconds) def _update(self, frame_id, timestamp): """ @@ -422,10 +357,7 @@ def update_clock(self, carla_timestamp): :return: """ self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) - if ROS_VERSION == 1: - self.clock_publisher.publish(Clock(self.ros_timestamp)) - elif ROS_VERSION == 2: - self.clock_publisher.publish(Clock(clock=self.ros_timestamp)) + self.clock_publisher.publish(Clock(clock=self.ros_timestamp)) def destroy(self): """ @@ -435,21 +367,25 @@ def destroy(self): """ # TODO fix if carla is not running self.loginfo("Shutting down...") - self.debug_helper.destroy() self.shutdown.set() - destroy_subscription(self.carla_weather_subscriber) - self.carla_control_queue.put(CarlaControl.STEP_ONCE) if not self.sync_mode: if self.on_tick_id: self.carla_world.remove_on_tick(self.on_tick_id) self.actor_factory.thread.join() + else: + self.synchronous_update_finished_event.wait() + self.loginfo("Object update finished.") + self.debug_helper.destroy() + self.status_publisher.destroy() + self.destroy_service(self.spawn_object_service) + self.destroy_service(self.destroy_object_service) + self.destroy_subscription(self.carla_weather_subscriber) + self.carla_control_queue.put(CarlaControl.STEP_ONCE) - with self.actor_factory.spawn_lock: - # remove actors in reverse order to destroy parent actors first. - for uid in self._registered_actors[::-1]: - self._destroy_actor(uid) + for uid in self._registered_actors: + self.actor_factory.destroy_actor(uid) + self.actor_factory.update_available_objects() self.actor_factory.clear() - super(CarlaRosBridge, self).destroy() diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 6f2238d1..bff237c2 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -71,6 +71,11 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.camera_image_publisher = node.new_publisher(Image, self.get_topic_prefix() + '/' + 'image') + def destroy(self): + super(Camera, self).destroy() + self.node.destroy_publisher(self.camera_info_publisher) + self.node.destroy_publisher(self.camera_image_publisher) + def _build_camera_info(self): """ Private function to compute camera info @@ -111,7 +116,6 @@ def sensor_data_updated(self, carla_camera_data): cam_info = self._camera_info cam_info.header = img_msg.header - self.camera_info_publisher.publish(cam_info) self.camera_image_publisher.publish(img_msg) @@ -373,6 +377,10 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.listen() + def destroy(self): + super(DVSCamera, self).destroy() + self.node.destroy_publisher(self.dvs_camera_publisher) + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_dvs_event_array): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index bdd41759..6416ae85 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -35,6 +35,7 @@ def __init__(self, synchronous_mode, fixed_delta_seconds, node): self.synchronous_mode = synchronous_mode self.synchronous_mode_running = True self.fixed_delta_seconds = fixed_delta_seconds + self.node = node if self.fixed_delta_seconds is None: self.fixed_delta_seconds = 0. self.frame = 0 @@ -42,10 +43,13 @@ def __init__(self, synchronous_mode, fixed_delta_seconds, node): callback_group = None elif ROS_VERSION == 2: callback_group = ReentrantCallbackGroup() - self.carla_status_publisher = node.new_publisher(CarlaStatus, "/carla/status", + self.carla_status_publisher = self.node.new_publisher(CarlaStatus, "/carla/status", callback_group=callback_group) self.publish() + def destroy(self): + self.node.destroy_publisher(self.carla_status_publisher) + def publish(self): """ publish the current status diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index ed5c69fd..1eca28fa 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -52,6 +52,10 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.get_topic_prefix()) self.listen() + def destroy(self): + super(CollisionSensor, self).destroy() + self.node.destroy_publisher(self.collision_publisher) + # pylint: disable=arguments-differ def sensor_data_updated(self, collision_event): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 12800e45..68023a82 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -200,14 +200,12 @@ def destroy(self): :return: """ self.node.logdebug("Destroy Vehicle(id={})".format(self.get_id())) - destroy_subscription(self.control_subscriber) - self.control_subscriber = None - destroy_subscription(self.enable_autopilot_subscriber) - self.enable_autopilot_subscriber = None - destroy_subscription(self.control_override_subscriber) - self.control_override_subscriber = None - destroy_subscription(self.manual_control_subscriber) - self.manual_control_subscriber = None + self.node.destroy_subscription(self.control_subscriber) + self.node.destroy_subscription(self.enable_autopilot_subscriber) + self.node.destroy_subscription(self.control_override_subscriber) + self.node.destroy_subscription(self.manual_control_subscriber) + self.node.destroy_publisher(self.vehicle_status_publisher) + self.node.destroy_publisher(self.vehicle_info_publisher) Vehicle.destroy(self) def control_command_override(self, enable): diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index c5e6d1f3..9506bb81 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -52,6 +52,10 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.get_topic_prefix()) self.listen() + def destroy(self): + super(Gnss, self).destroy() + self.node.destroy_publisher(self.gnss_publisher) + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_gnss_measurement): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 7c0b307a..32e68af3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -52,6 +52,10 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.imu_publisher = node.new_publisher(Imu, self.get_topic_prefix()) self.listen() + def destroy(self): + super(ImuSensor, self).destroy() + self.node.destroy_publisher(self.imu_publisher) + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_imu_measurement): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index c64d8f0a..92e052f3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -52,6 +52,10 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.get_topic_prefix()) self.listen() + def destroy(self): + super(LaneInvasionSensor, self).destroy() + self.node.destroy_publisher(self.lane_invasion_publisher) + # pylint: disable=arguments-differ def sensor_data_updated(self, lane_invasion_event): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 1f62dfa5..946d500c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -55,6 +55,10 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.get_topic_prefix()) self.listen() + def destroy(self): + super(Lidar, self).destroy() + self.node.destroy_publisher(self.lidar_publisher) + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_lidar_measurement): """ @@ -120,6 +124,10 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.get_topic_prefix()) self.listen() + def destroy(self): + super(SemanticLidar, self).destroy() + self.node.destroy_publisher(self.semantic_lidar_publisher) + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_lidar_measurement): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index 3386850d..c2b030da 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -54,6 +54,7 @@ def destroy(self): :return: """ self.actor_list = None + self.node.destroy_publisher(self.marker_publisher) super(MarkerSensor, self).destroy() @staticmethod diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 790c8c1f..1f6b8a6e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -50,8 +50,9 @@ def destroy(self): Function to destroy this object. :return: """ - self.actor_list = None super(ObjectSensor, self).destroy() + self.actor_list = None + self.node.destroy_publisher(self.object_publisher) @staticmethod def get_blueprint_name(): diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 4116b309..7ea98970 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -44,6 +44,10 @@ def __init__(self, uid, name, parent, node): self.odometry_publisher = node.new_publisher(Odometry, self.get_topic_prefix()) + def destroy(self): + super(OdometrySensor, self).destroy() + self.node.destroy_publisher(self.odometry_publisher) + @staticmethod def get_blueprint_name(): """ @@ -58,6 +62,11 @@ def update(self, frame, timestamp): """ odometry = Odometry(header=self.parent.get_msg_header("map")) odometry.child_frame_id = self.parent.get_prefix() - odometry.pose.pose = self.parent.get_current_ros_pose() - odometry.twist.twist = self.parent.get_current_ros_twist_rotated() + try: + odometry.pose.pose = self.parent.get_current_ros_pose() + odometry.twist.twist = self.parent.get_current_ros_twist_rotated() + except AttributeError: + # parent actor disappeared, do not send tf + self.node.logwarn("OdometrySensor could not publish. parent actor {} not found".format(self.parent.uid)) + return self.odometry_publisher.publish(odometry) diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index 22b1805d..fbdc1830 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -46,6 +46,10 @@ def __init__(self, uid, name, parent, node, carla_map): self.map_publisher = node.new_publisher(String, self.get_topic_prefix(), qos_profile=QoSProfile(depth=10, durability=latch_on)) + def destroy(self): + super(OpenDriveSensor, self).destroy() + self.node.destroy_publisher(self.map_publisher) + @staticmethod def get_blueprint_name(): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index e42e05de..8f16b493 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -53,6 +53,10 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.radar_publisher = node.new_publisher(PointCloud2, self.get_topic_prefix()) self.listen() + def destroy(self): + super(Radar, self).destroy() + self.node.destroy_publisher(self.radar_publisher) + # pylint: disable=arguments-differ def sensor_data_updated(self, carla_radar_measurement): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 601fd0b2..4f3d56ba 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -14,6 +14,7 @@ import os import struct import sys +from threading import Lock try: import queue except ImportError: @@ -89,6 +90,7 @@ def __init__(self, # pylint: disable=too-many-arguments self.next_data_expected_time = None self.sensor_tick_time = None self.is_event_sensor = is_event_sensor + self._callback_active = Lock() try: self.sensor_tick_time = float(carla_actor.attributes["sensor_tick"]) node.logdebug("Sensor tick time is {}".format(self.sensor_tick_time)) @@ -103,7 +105,7 @@ def __init__(self, # pylint: disable=too-many-arguments def publish_tf(self, pose, timestamp): if self.synchronous_mode: if not self.relative_spawn_pose: - self.node.loginfo("SKIP {}".format(self.get_prefix())) + self.node.logwarn("{}: No relative spawn pose defined".format(self.get_prefix())) return pose = self.relative_spawn_pose child_frame_id = self.get_prefix() @@ -115,7 +117,6 @@ def publish_tf(self, pose, timestamp): else: child_frame_id = self.get_prefix() frame_id = "map" - #self.node.logwarn("TF {} {} pose {}".format(self.get_prefix(), timestamp, pose)) transform = tf2_ros.TransformStamped() transform.header.stamp = ros_timestamp(sec=timestamp, from_sec=True) @@ -145,7 +146,7 @@ def destroy(self): :return: """ - self.node.logdebug("Destroy Sensor(id={})".format(self.get_id())) + self._callback_active.acquire() if self.carla_actor.is_listening: self.carla_actor.stop() super(Sensor, self).destroy() @@ -157,15 +158,16 @@ def _callback_sensor_data(self, carla_sensor_data): :param carla_sensor_data: carla sensor data object :type carla_sensor_data: carla.SensorData """ - if ros_ok(): - if self.synchronous_mode: - if self.sensor_tick_time: - self.next_data_expected_time = carla_sensor_data.timestamp + \ - float(self.sensor_tick_time) - self.queue.put(carla_sensor_data) - else: - self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform), carla_sensor_data.timestamp) - self.sensor_data_updated(carla_sensor_data) + self._callback_active.acquire() + if self.synchronous_mode: + if self.sensor_tick_time: + self.next_data_expected_time = carla_sensor_data.timestamp + \ + float(self.sensor_tick_time) + self.queue.put(carla_sensor_data) + else: + self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform), carla_sensor_data.timestamp) + self.sensor_data_updated(carla_sensor_data) + self._callback_active.release() @abstractmethod def sensor_data_updated(self, carla_sensor_data): diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 7862f5fb..6accf5ef 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -44,6 +44,10 @@ def __init__(self, uid, name, parent, node): self.speedometer_publisher = node.new_publisher(Float32, self.get_topic_prefix()) + def destroy(self): + super(SpeedometerSensor, self).destroy() + self.node.destroy_publisher(self.speedometer_publisher) + @staticmethod def get_blueprint_name(): """ @@ -56,8 +60,13 @@ def update(self, frame, timestamp): """ Function (override) to update this object. """ - velocity = self.parent.carla_actor.get_velocity() - transform = self.parent.carla_actor.get_transform() + try: + velocity = self.parent.carla_actor.get_velocity() + transform = self.parent.carla_actor.get_transform() + except AttributeError: + # parent actor disappeared, do not send tf + self.node.logwarn("SpeedometerSensor could not publish. Parent actor {} not found".format(self.parent.uid)) + return vel_np = np.array([velocity.x, velocity.y, velocity.z]) pitch = np.deg2rad(transform.rotation.pitch) diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 10ddf812..97f1e441 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -61,7 +61,16 @@ def update(self, frame, timestamp): Function (override) to update this object. """ self.parent.get_prefix() + + transform = None + try: + transform = self.parent.get_current_ros_transform() + except AttributeError: + # parent actor disappeared, do not send tf + self.node.logwarn("TFSensor could not publish transform. Actor {} not found".format(self.parent.uid)) + return + self._tf_broadcaster.sendTransform(TransformStamped( header=self.get_msg_header("map", timestamp=timestamp), child_frame_id=self.parent.get_prefix(), - transform=self.parent.get_current_ros_transform())) + transform=transform)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index b7635d9b..e2f4a70a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -61,8 +61,10 @@ def destroy(self): Function to destroy this object. :return: """ - self.actor_list = None super(TrafficLightsSensor, self).destroy() + self.actor_list = None + self.node.destroy_publisher(self.traffic_lights_info_publisher) + self.node.destroy_publisher(self.traffic_lights_status_publisher) @staticmethod def get_blueprint_name(): diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index 592d2f3f..35d6dfa4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -60,10 +60,8 @@ def destroy(self): :return: """ - self.node.logdebug("Destroy Walker(id={})".format(self.get_id())) - destroy_subscription(self.control_subscriber) - self.control_subscriber = None super(Walker, self).destroy() + self.node.destroy_subscription(self.control_subscriber) def control_command_updated(self, ros_walker_control): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index 97917439..94f8fdce 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -47,7 +47,6 @@ def destroy(self): :return: """ - self.logdebug("Destroying WorldInfo()") self.node.destroy_publisher(self.world_info_publisher) self.carla_map = None diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index d25a8820..1350b4a1 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -84,6 +84,15 @@ def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwa def destroy(self): pass + def destroy_service(self, service): + service.shutdown() + + def destroy_subscription(self, subscription): + subscription.unregister() + + def destroy_publisher(self, publisher): + publisher.unregister() + def get_param(self, name, alternative_value=None, alternative_name=None): if name.startswith('/'): raise RuntimeError("Only private parameters are supported.") @@ -189,9 +198,6 @@ def ros_ok(): def ros_shutdown(): rclpy.shutdown() - def destroy_subscription(subscription): - subscription.destroy() - def logdebug(log): rclpy.logging.get_logger("default").debug(log) From ffebe4f0153da2d4dffa70174144a6f4b3f659e6 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 8 Jan 2021 17:56:36 +0100 Subject: [PATCH 469/627] Code formatting --- carla_ad_agent/CMakeLists.txt | 2 +- carla_common/src/carla_common/transforms.py | 13 ++++--- .../carla_manual_control.py | 19 +++++----- .../src/carla_ros_bridge/actor_factory.py | 35 ++++++++++--------- .../src/carla_ros_bridge/bridge.py | 7 ++-- .../carla_status_publisher.py | 2 +- .../src/carla_ros_bridge/odom_sensor.py | 3 +- .../src/carla_ros_bridge/sensor.py | 8 +++-- .../carla_ros_bridge/speedometer_sensor.py | 3 +- .../src/carla_ros_bridge/tf_sensor.py | 7 ++-- 10 files changed, 55 insertions(+), 44 deletions(-) diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index cb1d900a..690fd0e9 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -25,7 +25,7 @@ if(${ROS_VERSION} EQUAL 1) DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) elseif(${ROS_VERSION} EQUAL 2) -#TODO: remove + # TODO: remove find_package(ament_cmake REQUIRED) find_package(rclpy REQUIRED) ament_export_dependencies(rclpy) diff --git a/carla_common/src/carla_common/transforms.py b/carla_common/src/carla_common/transforms.py index 5146e3b6..723f38da 100644 --- a/carla_common/src/carla_common/transforms.py +++ b/carla_common/src/carla_common/transforms.py @@ -326,21 +326,24 @@ def ros_pose_to_carla_transform(ros_pose): ros_point_to_carla_location(ros_pose.position), ros_quaternion_to_carla_rotation(ros_pose.orientation)) + def transform_matrix_to_ros_pose(mat): """ Convert a transform matrix to a ROS pose. """ - quat = mat2quat(mat[:3,:3]) + quat = mat2quat(mat[:3, :3]) msg = Pose() - msg.position=Point(x=mat[0, 3], y=mat[1, 3], z=mat[2, 3]) - msg.orientation=Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3]) + msg.position = Point(x=mat[0, 3], y=mat[1, 3], z=mat[2, 3]) + msg.orientation = Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3]) return msg + def ros_pose_to_transform_matrix(msg): """ Convert a ROS pose to a transform matrix """ mat44 = numpy.eye(4) - mat44[:3,:3] = quat2mat([msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z]) + mat44[:3, :3] = quat2mat([msg.orientation.w, msg.orientation.x, + msg.orientation.y, msg.orientation.z]) mat44[0:3, -1] = [msg.position.x, msg.position.y, msg.position.z] - return mat44 \ No newline at end of file + return mat44 diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 09b61430..ae406d7b 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -175,7 +175,7 @@ def render(self, game_clock, display): """ render the current image """ - + do_quit = self.controller.parse_events(game_clock) if do_quit: return @@ -214,24 +214,25 @@ def __init__(self, role_name, hud, node): self.vehicle_control_manual_override_publisher = \ self.node.new_publisher(Bool, - "/carla/{}/vehicle_control_manual_override".format(self.role_name), - qos_profile=fast_latched_qos, callback_group=self.callback_group) + "/carla/{}/vehicle_control_manual_override".format( + self.role_name), + qos_profile=fast_latched_qos, callback_group=self.callback_group) self.vehicle_control_manual_override = False self.auto_pilot_enable_publisher = \ self.node.new_publisher(Bool, - "/carla/{}/enable_autopilot".format(self.role_name), - qos_profile=fast_qos, callback_group=self.callback_group) + "/carla/{}/enable_autopilot".format(self.role_name), + qos_profile=fast_qos, callback_group=self.callback_group) self.vehicle_control_publisher = \ self.node.new_publisher(CarlaEgoVehicleControl, - "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), - qos_profile=fast_qos, callback_group=self.callback_group) + "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), + qos_profile=fast_qos, callback_group=self.callback_group) self.carla_status_subscriber = self.node.create_subscriber(CarlaStatus, "/carla/status", - self._on_new_carla_frame, - callback_group=self.callback_group) + self._on_new_carla_frame, + callback_group=self.callback_group) self.set_autopilot(self._autopilot_enabled) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 0228c51e..c68e8e49 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -12,10 +12,10 @@ from enum import Enum try: - import queue + import queue except ImportError: - import Queue as queue - + import Queue as queue + from carla_ros_bridge.actor import Actor from carla_ros_bridge.spectator import Spectator from carla_ros_bridge.traffic import Traffic, TrafficLight @@ -72,7 +72,7 @@ def __init__(self, node, world, sync_mode=False): self._task_queue = queue.Queue() self._last_task = None - self._known_actor_ids = [] # used to immediately reply to spawn_actor/destroy_actor calls + self._known_actor_ids = [] # used to immediately reply to spawn_actor/destroy_actor calls self.lock = Lock() self.spawn_lock = Lock() @@ -128,7 +128,8 @@ def update_available_objects(self): task = self._task_queue.get() if task[0] == ActorFactory.TaskType.SPAWN_PSEUDO_ACTOR: pseudo_object = task[1] - self._create_object(pseudo_object[0], pseudo_object[1].type, pseudo_object[1].id, pseudo_object[1].attach_to, pseudo_object[1].transform) + self._create_object(pseudo_object[0], pseudo_object[1].type, pseudo_object[1].id, + pseudo_object[1].attach_to, pseudo_object[1].transform) elif task[0] == ActorFactory.TaskType.DESTROY_ACTOR: actor_id = task[1] self._destroy_object(actor_id, delete_actor=True) @@ -136,7 +137,6 @@ def update_available_objects(self): break self.lock.release() - def update_actor_states(self, frame_id, timestamp): """ update the state of all known actors @@ -152,7 +152,7 @@ def update_actor_states(self, frame_id, timestamp): def clear(self): for _, actor in self.actors.items(): - actor.destroy() + actor.destroy() self.actors.clear() def spawn_actor(self, req): @@ -164,7 +164,7 @@ def spawn_actor(self, req): """ with self.spawn_lock: if "pseudo" in req.type: - #only allow spawning pseudo objects if parent actor already exists in carla + # only allow spawning pseudo objects if parent actor already exists in carla if req.attach_to != 0: carla_actor = self.world.get_actor(req.attach_to) if carla_actor is None: @@ -189,7 +189,7 @@ def _destroy_actor(self, uid): if uid in self._known_actor_ids: objects_to_destroy.append(uid) self._known_actor_ids.remove(uid) - + # remove actors that have the actor to be removed as parent. for actor in list(self.actors.values()): if actor.parent is not None and actor.parent.uid == uid: @@ -225,7 +225,6 @@ def _spawn_carla_actor(self, req): carla_actor = self.world.spawn_actor(blueprint, transform, attach_to) return carla_actor.id - def _create_object_from_actor(self, carla_actor): """ create a object for a given carla actor @@ -239,9 +238,12 @@ def _create_object_from_actor(self, carla_actor): else: parent = self._create_object_from_actor(carla_actor.parent) # calculate relative transform - actor_transform_matrix = trans.ros_pose_to_transform_matrix(trans.carla_transform_to_ros_pose(carla_actor.get_transform())) - parent_transform_matrix = trans.ros_pose_to_transform_matrix(trans.carla_transform_to_ros_pose(carla_actor.parent.get_transform())) - relative_transform_matrix = np.matrix(parent_transform_matrix).getI() * np.matrix(actor_transform_matrix) + actor_transform_matrix = trans.ros_pose_to_transform_matrix( + trans.carla_transform_to_ros_pose(carla_actor.get_transform())) + parent_transform_matrix = trans.ros_pose_to_transform_matrix( + trans.carla_transform_to_ros_pose(carla_actor.parent.get_transform())) + relative_transform_matrix = np.matrix( + parent_transform_matrix).getI() * np.matrix(actor_transform_matrix) relative_transform = trans.transform_matrix_to_ros_pose(relative_transform_matrix) parent_id = 0 @@ -251,10 +253,10 @@ def _create_object_from_actor(self, carla_actor): name = carla_actor.attributes.get("role_name", "") if not name: name = str(carla_actor.id) - obj = self._create_object(carla_actor.id, carla_actor.type_id, name, parent_id, relative_transform, carla_actor) + obj = self._create_object(carla_actor.id, carla_actor.type_id, name, + parent_id, relative_transform, carla_actor) return obj - def _destroy_object(self, actor_id, delete_actor): if actor_id not in self.actors: return @@ -283,12 +285,11 @@ def _create_object(self, uid, type_id, name, attach_to, spawn_pose, carla_actor= if attach_to != 0: if attach_to not in self.actors: raise IndexError("Parent object {} not found".format(attach_to)) - + parent = self.actors[attach_to] else: parent = None - if type_id == TFSensor.get_blueprint_name(): actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 7f25fb29..782999a3 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -203,7 +203,8 @@ def destroy_object(self, req, response=None): destroyed_actors = self.actor_factory.destroy_actor(req.id) response.success = bool(destroyed_actors) for actor in destroyed_actors: - if actor in self._registered_actors: self._registered_actors.remove(actor) + if actor in self._registered_actors: + self._registered_actors.remove(actor) return response def get_blueprints(self, req): @@ -300,7 +301,7 @@ def _synchronous_mode_update(self): if not self._all_vehicle_control_commands_received.wait(CarlaRosBridge.VEHICLE_CONTROL_TIMEOUT): self.logwarn("Timeout ({}s) while waiting for vehicle control commands. " "Missing command from actor ids {}".format(CarlaRosBridge.VEHICLE_CONTROL_TIMEOUT, - self._expected_ego_vehicle_control_command_ids)) + self._expected_ego_vehicle_control_command_ids)) self._all_vehicle_control_commands_received.clear() self.synchronous_update_finished_event.set() @@ -324,7 +325,7 @@ def _carla_time_tick(self, carla_snapshot): self.update_clock(carla_snapshot.timestamp) self.status_publisher.set_frame(carla_snapshot.frame) self._update(carla_snapshot.frame, - carla_snapshot.timestamp.elapsed_seconds) + carla_snapshot.timestamp.elapsed_seconds) def _update(self, frame_id, timestamp): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 6416ae85..20f9be3b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -44,7 +44,7 @@ def __init__(self, synchronous_mode, fixed_delta_seconds, node): elif ROS_VERSION == 2: callback_group = ReentrantCallbackGroup() self.carla_status_publisher = self.node.new_publisher(CarlaStatus, "/carla/status", - callback_group=callback_group) + callback_group=callback_group) self.publish() def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 7ea98970..143ee645 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -67,6 +67,7 @@ def update(self, frame, timestamp): odometry.twist.twist = self.parent.get_current_ros_twist_rotated() except AttributeError: # parent actor disappeared, do not send tf - self.node.logwarn("OdometrySensor could not publish. parent actor {} not found".format(self.parent.uid)) + self.node.logwarn( + "OdometrySensor could not publish. parent actor {} not found".format(self.parent.uid)) return self.odometry_publisher.publish(odometry) diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 4f3d56ba..82897a46 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -158,14 +158,15 @@ def _callback_sensor_data(self, carla_sensor_data): :param carla_sensor_data: carla sensor data object :type carla_sensor_data: carla.SensorData """ - self._callback_active.acquire() + self._callback_active.acquire() if self.synchronous_mode: if self.sensor_tick_time: self.next_data_expected_time = carla_sensor_data.timestamp + \ float(self.sensor_tick_time) self.queue.put(carla_sensor_data) else: - self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform), carla_sensor_data.timestamp) + self.publish_tf(trans.carla_transform_to_ros_pose( + carla_sensor_data.transform), carla_sensor_data.timestamp) self.sensor_data_updated(carla_sensor_data) self._callback_active.release() @@ -192,7 +193,8 @@ def _update_synchronous_event_sensor(self, frame): carla_sensor_data.frame, frame)) self.node.logdebug("{}({}): process {}".format( self.__class__.__name__, self.get_id(), frame)) - self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform), frame) + self.publish_tf(trans.carla_transform_to_ros_pose( + carla_sensor_data.transform), frame) self.sensor_data_updated(carla_sensor_data) except queue.Empty: return diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 6accf5ef..213cfc6f 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -65,7 +65,8 @@ def update(self, frame, timestamp): transform = self.parent.carla_actor.get_transform() except AttributeError: # parent actor disappeared, do not send tf - self.node.logwarn("SpeedometerSensor could not publish. Parent actor {} not found".format(self.parent.uid)) + self.node.logwarn( + "SpeedometerSensor could not publish. Parent actor {} not found".format(self.parent.uid)) return vel_np = np.array([velocity.x, velocity.y, velocity.z]) diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 97f1e441..ad35b086 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -61,15 +61,16 @@ def update(self, frame, timestamp): Function (override) to update this object. """ self.parent.get_prefix() - + transform = None try: transform = self.parent.get_current_ros_transform() except AttributeError: # parent actor disappeared, do not send tf - self.node.logwarn("TFSensor could not publish transform. Actor {} not found".format(self.parent.uid)) + self.node.logwarn( + "TFSensor could not publish transform. Actor {} not found".format(self.parent.uid)) return - + self._tf_broadcaster.sendTransform(TransformStamped( header=self.get_msg_header("map", timestamp=timestamp), child_frame_id=self.parent.get_prefix(), From 865cfbf851f50d10de667a36ba61ec7c0fe30428 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 11 Jan 2021 11:05:00 +0100 Subject: [PATCH 470/627] Fix publish exception in sensor callback. Test all modes --- .../src/carla_ros_bridge/actor_factory.py | 8 ++++++-- .../src/carla_ros_bridge/sensor.py | 19 +++++++++++++++---- 2 files changed, 21 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index c68e8e49..1b426de3 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -6,6 +6,7 @@ # For a copy, see . # +from ros_compatibility import ROS_VERSION import time from threading import Thread, Lock import itertools @@ -97,9 +98,12 @@ def _update_thread(self): self.update_available_objects() def add_task(self, task): - if self._last_task != ActorFactory.TaskType.SYNC or task[0] != ActorFactory.TaskType.SYNC: + if ROS_VERSION == 1: self._task_queue.put(task) - self._last_task = task[0] + else: + if self._last_task != ActorFactory.TaskType.SYNC or task[0] != ActorFactory.TaskType.SYNC: + self._task_queue.put(task) + self._last_task = task[0] def update_available_objects(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 82897a46..c785fdd6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -23,7 +23,7 @@ import tf2_ros from carla_ros_bridge.actor import Actor import carla_common.transforms as trans -from ros_compatibility import ros_ok, ros_timestamp +from ros_compatibility import ros_ok, ros_timestamp, ROSException from sensor_msgs.msg import PointCloud2, PointField ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -132,7 +132,11 @@ def publish_tf(self, pose, timestamp): transform.transform.rotation.z = pose.orientation.z transform.transform.rotation.w = pose.orientation.w - self._tf_broadcaster.sendTransform(transform) + try: + self._tf_broadcaster.sendTransform(transform) + except ROSException: + if ros_ok(): + self.node.logwarn("Sensor {} failed to send transform.".format(self.uid)) def listen(self): self.carla_actor.listen(self._callback_sensor_data) @@ -158,7 +162,9 @@ def _callback_sensor_data(self, carla_sensor_data): :param carla_sensor_data: carla sensor data object :type carla_sensor_data: carla.SensorData """ - self._callback_active.acquire() + if not self._callback_active.acquire(False): + # if acquire fails, sensor is currently getting destroyed + return if self.synchronous_mode: if self.sensor_tick_time: self.next_data_expected_time = carla_sensor_data.timestamp + \ @@ -167,7 +173,12 @@ def _callback_sensor_data(self, carla_sensor_data): else: self.publish_tf(trans.carla_transform_to_ros_pose( carla_sensor_data.transform), carla_sensor_data.timestamp) - self.sensor_data_updated(carla_sensor_data) + try: + self.sensor_data_updated(carla_sensor_data) + except ROSException: + if ros_ok(): + self.node.logwarn( + "Sensor {}: Error while executing sensor_data_updated().".format(self.uid)) self._callback_active.release() @abstractmethod From ddc8e9a0dab8286e9d256aa5de257947ec6b7a59 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 11 Jan 2021 15:56:46 +0100 Subject: [PATCH 471/627] Fix ros1 launch for carla_waypoint_publisher --- .../launch/carla_waypoint_publisher.launch | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch index 2f7a9614..1fdbedf3 100644 --- a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch @@ -5,13 +5,11 @@ - - - - + + + - From 9b2a57d87258984dc37a9cc140cef2077ae3f958 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 11 Jan 2021 17:21:15 +0100 Subject: [PATCH 472/627] Cleanup destroy_subscription + startup --- carla_ad_agent/src/carla_ad_agent/agent.py | 2 +- .../src/carla_ad_agent/basic_agent.py | 2 +- .../carla_manual_control.py | 8 +++---- .../src/carla_ros_bridge/actor_control.py | 7 ++---- .../src/carla_ros_bridge/bridge.py | 1 - .../src/carla_ros_bridge/debug_helper.py | 5 ++--- .../src/carla_ros_bridge/ego_vehicle.py | 9 ++------ .../src/carla_ros_bridge/walker.py | 3 --- .../ros_vehicle_control.py | 6 ++--- .../carla_spawn_objects.py | 6 ++--- .../carla_waypoint_publisher.py | 22 ++++++++++++++----- .../ros_compatibility/ros_compatible_node.py | 6 ++--- 12 files changed, 36 insertions(+), 41 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 7ce91da7..e99ef225 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -163,7 +163,7 @@ def get_waypoint(self, location): try: response = self.node.call_service(self._get_waypoint_client, location) return response.waypoint - except (ServiceException, ROSInterruptException, TypeError) as e: + except (ServiceException, ROSInterruptException, KeyboardInterrupt, TypeError) as e: if ros_ok(): self.node.logwarn("Service call 'get_waypoint' failed: {}".format(e)) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 581e8961..aaeb8aa9 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -89,7 +89,7 @@ def get_actor_waypoint(self, actor_id): request.id = actor_id response = self.node.call_service(self._get_actor_waypoint_client, request) return response.waypoint - except (ServiceException, ROSInterruptException, TypeError) as e: + except (ServiceException, ROSInterruptException, KeyboardInterrupt, TypeError) as e: if ros_ok(): self.node.logwarn("Service call failed: {}".format(e)) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index ae406d7b..1b1ccaf6 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -42,7 +42,6 @@ latch_on, ros_ok, ros_init, - destroy_subscription, ros_shutdown, loginfo, logwarn, @@ -555,13 +554,12 @@ def render(self, display): else: rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6)) pygame.draw.rect(display, (255, 255, 255), rect_border, 1) - f = (item[1] - item[2]) / (item[3] - item[2]) if item[2] < 0.0: - rect = pygame.Rect((bar_h_offset + f * (bar_width - 6), v_offset + 8), + f = (item[1] - item[2]) / (item[3] - item[2]) + rect = pygame.Rect((bar_h_offset + int(f * (bar_width - 6)), v_offset + 8), (6, 6)) else: - f = 0.0 - rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6)) + rect = pygame.Rect((bar_h_offset, v_offset + 8), (0, 6)) pygame.draw.rect(display, (255, 255, 255), rect) item = item[0] if item: # At this point has to be a str. diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index 83e91cb9..b55829a8 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -14,7 +14,6 @@ from carla_ros_bridge.pseudo_actor import PseudoActor from geometry_msgs.msg import Pose, Twist from carla import Vector3D -from ros_compatibility import destroy_subscription class ActorControl(PseudoActor): @@ -59,10 +58,8 @@ def destroy(self): :return: """ - destroy_subscription(self.set_location_subscriber) - self.set_location_subscriber = None - destroy_subscription(self.twist_control_subscriber) - self.twist_control_subscriber = None + self.node.destroy_subscription(self.set_location_subscriber) + self.node.destroy_subscription(self.twist_control_subscriber) super(ActorControl, self).destroy() @staticmethod diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 782999a3..bdc78880 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -13,7 +13,6 @@ from ros_compatibility import ( CompatibleNode, ros_ok, - destroy_subscription, ros_shutdown, ros_timestamp, QoSProfile, diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 28106cef..48e9b048 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -15,7 +15,7 @@ import carla from transforms3d.euler import quat2euler -from ros_compatibility import CompatibleNode, destroy_subscription +from ros_compatibility import CompatibleNode ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -47,8 +47,7 @@ def destroy(self): """ self.node.logdebug("Destroy DebugHelper") self.debug = None - destroy_subscription(self.marker_subscriber) - self.marker_subscriber = None + self.node.destroy_subscription(self.marker_subscriber) def on_marker(self, marker_array): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 68023a82..b4297859 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -27,16 +27,11 @@ ) from ros_compatibility import ( - destroy_subscription, QoSProfile, - latch_on + latch_on, + ROS_VERSION ) -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION not in (1, 2): - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") - if ROS_VERSION == 2: from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index 35d6dfa4..015d39c6 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -16,9 +16,6 @@ from carla_msgs.msg import CarlaWalkerControl from carla import WalkerControl -from ros_compatibility import destroy_subscription - - class Walker(TrafficParticipant): """ diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 87d4277b..a5225ca7 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -15,7 +15,7 @@ import carla_common.transforms as trans from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error -from ros_compatibility import CompatibleNode, QoSProfile, ros_timestamp, destroy_subscription +from ros_compatibility import CompatibleNode, QoSProfile, ros_timestamp import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -134,10 +134,10 @@ def reset(self): if self._carla_actor and self._carla_actor.is_alive: self._carla_actor = None if self._target_speed_publisher: - destroy_subscription(self._target_speed_publisher) + self.node.destroy_subscription(self._target_speed_publisher) self._target_speed_publisher = None if self._path_publisher: - destroy_subscription(self._path_publisher) + self.node.destroy_subscription(self._path_publisher) self._path_publisher = None def run_step(self): diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 10938966..a4ff12ee 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -341,7 +341,7 @@ def destroy(self): try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: - self.logwarn(str(e)) + self.logwarn(str(e))#TODO: use logwarn_once self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.vehicles_sensors = [] @@ -352,7 +352,7 @@ def destroy(self): try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: - self.logwarn(str(e)) + self.logwarn(str(e))#TODO: use logwarn_once self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.global_sensors = [] @@ -363,7 +363,7 @@ def destroy(self): try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: - self.logwarn(str(e)) + self.logwarn(str(e))#TODO: use logwarn_once self.loginfo("Object {} successfully destroyed.".format(player_id)) self.players = [] diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 17ede2de..2125f10c 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -28,7 +28,10 @@ ros_timestamp, latch_on, ros_init, - get_service_response) + get_service_response, + loginfo, + ROS_VERSION, + ros_shutdown) from nav_msgs.msg import Path from geometry_msgs.msg import PoseStamped import carla_common.transforms as trans @@ -266,12 +269,19 @@ def main(args=None): ros_init(args) try: - waypointConverter = CarlaToRosWaypointConverter() - waypointConverter.spin() - del waypointConverter - + waypoint_converter = CarlaToRosWaypointConverter() + if ROS_VERSION == 1: + waypoint_converter.spin() + else: + spin_thread = threading.Thread(target=waypoint_converter.spin) + spin_thread.start() + spin_thread.join() + except KeyboardInterrupt: + loginfo("User requested shut down.") finally: - print("Done") + loginfo("Shutting down.") + waypoint_converter.destroy() + ros_shutdown() if __name__ == "__main__": diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 1350b4a1..800bfca7 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -4,6 +4,9 @@ ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +if ROS_VERSION not in (1, 2): + raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") + if ROS_VERSION == 1: import rospy elif ROS_VERSION == 2: @@ -30,9 +33,6 @@ def ros_ok(): def ros_shutdown(): pass - def destroy_subscription(subscription): - subscription.unregister() - def logdebug(log): rospy.logdebug(log) From 15595e340088cb4c9352b082ea7e2676b6b5045e Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 12 Jan 2021 12:41:06 +0100 Subject: [PATCH 473/627] Cleanup --- .../carla_ackermann_control_node.py | 5 +---- carla_ad_agent/src/carla_ad_agent/agent.py | 8 +++---- .../src/carla_ad_agent/basic_agent.py | 5 ++--- .../src/carla_ad_agent/carla_ad_agent.py | 22 +++++++++++-------- .../src/carla_ros_bridge/actor_factory.py | 15 +++---------- .../src/carla_ros_bridge/bridge.py | 5 ++--- .../src/carla_ros_bridge/walker.py | 1 + .../test/ros_bridge_client_ros2_test.py | 11 ++++++---- .../carla_ros_scenario_runner_node.py | 22 ++++++++++--------- .../carla_spawn_objects.py | 6 ++--- .../carla_waypoint_publisher.py | 18 ++++++++++----- pcl_recorder/src/PclRecorder.cpp | 2 +- pcl_recorder/src/PclRecorderROS2.cpp | 2 +- .../ros_compatibility/ros_compatible_node.py | 5 ++++- 14 files changed, 66 insertions(+), 61 deletions(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index 680672c7..ba2bd364 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -20,14 +20,11 @@ from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module,import-error from carla_ackermann_msgs.msg import EgoVehicleControlInfo # pylint: disable=no-name-in-module,import-error -from ros_compatibility import CompatibleNode, QoSProfile, ros_init +from ros_compatibility import CompatibleNode, QoSProfile, ros_init, ROS_VERSION from carla_ackermann_control import carla_control_physics as phys from simple_pid import PID # pylint: disable=import-error,wrong-import-order - -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - if ROS_VERSION == 1: from carla_ackermann_control.cfg import EgoVehicleControlParameterConfig from dynamic_reconfigure.server import Server diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index e99ef225..65cf13ad 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -21,10 +21,8 @@ ROSInterruptException, QoSProfile, latch_on, - get_service_request) - -import os -ROS_VERSION = int(os.environ['ROS_VERSION']) + get_service_request, + ROS_VERSION) if ROS_VERSION == 1: from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import @@ -165,7 +163,7 @@ def get_waypoint(self, location): return response.waypoint except (ServiceException, ROSInterruptException, KeyboardInterrupt, TypeError) as e: if ros_ok(): - self.node.logwarn("Service call 'get_waypoint' failed: {}".format(e)) + self.node.logwarn("Service call 'get_waypoint' failed: {}".format(str(e))) def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branches """ diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index aaeb8aa9..d5735634 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -22,10 +22,9 @@ ROSInterruptException, QoSProfile, latch_on, - get_service_request) + get_service_request, + ROS_VERSION) -import os -ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: from local_planner import LocalPlanner # pylint: disable=relative-import from agent import Agent, AgentState # pylint: disable=relative-import diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 177a1e17..47e8aaef 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -20,10 +20,11 @@ QoSProfile, ROSException, latch_on, - ros_init) - -import os -ROS_VERSION = int(os.environ['ROS_VERSION']) + ros_init, + ROS_VERSION, + logwarn, + loginfo, + ros_shutdown) if ROS_VERSION == 1: import rospy @@ -61,7 +62,7 @@ def __init__(self): vehicle_info = self.wait_for_one_message( "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) - self.loginfo("Vehicle info recieved.") + self.loginfo("Vehicle info received.") except ROSException: self.logerr("Timeout while waiting for vehicle info!") sys.exit(1) @@ -172,13 +173,16 @@ def main(args=None): """ ros_init(args) - controller = CarlaAdAgent() try: + controller = CarlaAdAgent() controller.run() - + except ROSInterruptException as e: + if ros_ok(): + logwarn("ROS Error during exection: {}".format(e)) + except KeyboardInterrupt: + loginfo("User requested shut down.") finally: - del controller - print("Done") + ros_shutdown() if __name__ == "__main__": diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 1b426de3..89c454dd 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -72,7 +72,6 @@ def __init__(self, node, world, sync_mode=False): self.actors = {} self._task_queue = queue.Queue() - self._last_task = None self._known_actor_ids = [] # used to immediately reply to spawn_actor/destroy_actor calls self.lock = Lock() @@ -97,14 +96,6 @@ def _update_thread(self): self.world.wait_for_tick() self.update_available_objects() - def add_task(self, task): - if ROS_VERSION == 1: - self._task_queue.put(task) - else: - if self._last_task != ActorFactory.TaskType.SYNC or task[0] != ActorFactory.TaskType.SYNC: - self._task_queue.put(task) - self._last_task = task[0] - def update_available_objects(self): """ update the available actors @@ -174,10 +165,10 @@ def spawn_actor(self, req): if carla_actor is None: raise IndexError("Parent actor {} not found".format(req.attach_to)) id_ = next(self.id_gen) - self.add_task((ActorFactory.TaskType.SPAWN_PSEUDO_ACTOR, (id_, req))) + self._task_queue.put((ActorFactory.TaskType.SPAWN_PSEUDO_ACTOR, (id_, req))) else: id_ = self._spawn_carla_actor(req) - self.add_task((ActorFactory.TaskType.SYNC, None)) + self._task_queue.put((ActorFactory.TaskType.SYNC, None)) self._known_actor_ids.append(id_) return id_ @@ -185,7 +176,7 @@ def destroy_actor(self, uid): with self.spawn_lock: objects_to_destroy = set(self._destroy_actor(uid)) for obj in objects_to_destroy: - self.add_task((ActorFactory.TaskType.DESTROY_ACTOR, obj)) + self._task_queue.put((ActorFactory.TaskType.DESTROY_ACTOR, obj)) return objects_to_destroy def _destroy_actor(self, uid): diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index bdc78880..d5aee0b2 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -18,7 +18,8 @@ QoSProfile, latch_on, ros_init, - get_service_response) + get_service_response, + ROS_VERSION) try: import queue @@ -45,8 +46,6 @@ from carla_msgs.msg import CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, DestroyObject, GetBlueprints -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - if ROS_VERSION == 1: import rospy # pylint: disable=import-error from carla_msgs.srv import SpawnObjectResponse, DestroyObjectResponse, GetBlueprintsResponse diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index 015d39c6..b9adc276 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -16,6 +16,7 @@ from carla_msgs.msg import CarlaWalkerControl from carla import WalkerControl + class Walker(TrafficParticipant): """ diff --git a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py index 4a254234..562bb291 100644 --- a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py +++ b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py @@ -32,7 +32,6 @@ CarlaTrafficLightInfoList) - def generate_test_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( @@ -114,13 +113,16 @@ def generate_test_description(): ]) return ld + TIMEOUT = 30 + class TestClock(unittest.TestCase): """ Handles testing of the all nodes """ + def test_clock(self): """ Tests clock @@ -144,7 +146,8 @@ def test_vehicle_status(self, proc_output): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message("/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus) + msg = node.wait_for_one_message( + "/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus) self.assertNotEqual(msg.header, Header()) # todo: check frame-id self.assertNotEqual(msg.orientation, Quaternion()) finally: @@ -514,9 +517,9 @@ def test_traffic_lights_info(self): node = CompatibleNode('test_node') msg = node.wait_for_one_message( "/carla/traffic_lights/info", CarlaTrafficLightInfoList, timeout=TIMEOUT, - qos_profile=QoSProfile(depth=10, durability=latch_on)) + qos_profile=QoSProfile(depth=10, durability=latch_on)) self.assertNotEqual(len(msg.traffic_lights), 0) finally: if node is not None: node.destroy_node() - ros_shutdown() \ No newline at end of file + ros_shutdown() diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py index 5d02784e..16f90afd 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py @@ -12,7 +12,6 @@ """ import sys import os -import logging try: import queue except ImportError: @@ -29,7 +28,11 @@ CompatibleNode, QoSProfile, ros_ok, - ros_init) + ros_init, + get_service_response, + ros_shutdown, + loginfo, + ROS_VERSION) # Check Python dependencies of scenario runner try: @@ -47,11 +50,7 @@ Please add /PythonAPI/carla to your PYTHONPATH.") sys.exit(1) -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION == 1: - from carla_ros_scenario_runner_types.srv import ExecuteScenarioResponse -elif ROS_VERSION == 2: +if ROS_VERSION == 2: import rclpy import threading @@ -120,8 +119,7 @@ def execute_scenario(self, req, response=None): """ self.loginfo("Scenario Execution requested...") - if ROS_VERSION == 1: - response = ExecuteScenarioResponse() + response = get_service_response(ExecuteScenario) response.result = True if not os.path.isfile(req.scenario.scenario_file): self.logwarn("Requested scenario file not existing {}".format( @@ -181,12 +179,16 @@ def main(args=None): try: scenario_runner.run() + except KeyboardInterrupt: + loginfo("User requested shut down.") finally: if scenario_runner._scenario_runner.is_running(): scenario_runner.loginfo("Scenario Runner still running. Shutting down.") scenario_runner._scenario_runner.shutdown() del scenario_runner - logging.info("Done.") + ros_shutdown() + if ROS_VERSION == 2: + spin_thread.join() if __name__ == "__main__": diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index a4ff12ee..8139eaed 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -341,7 +341,7 @@ def destroy(self): try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: - self.logwarn(str(e))#TODO: use logwarn_once + self.logwarn(str(e)) # TODO: use logwarn_once self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.vehicles_sensors = [] @@ -352,7 +352,7 @@ def destroy(self): try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: - self.logwarn(str(e))#TODO: use logwarn_once + self.logwarn(str(e)) # TODO: use logwarn_once self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.global_sensors = [] @@ -363,7 +363,7 @@ def destroy(self): try: self.call_service(self.destroy_object_service, destroy_object_request) except ServiceException as e: - self.logwarn(str(e))#TODO: use logwarn_once + self.logwarn(str(e)) # TODO: use logwarn_once self.loginfo("Object {} successfully destroyed.".format(player_id)) self.players = [] diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 2125f10c..454286b5 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -244,9 +244,9 @@ def connect_to_carla(self): try: self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on), timeout=10.0) - except ROSException: - self.logerr("Error while waiting for world info!") - sys.exit(1) + except ROSException as e: + self.logerr("Error while waiting for world info: {}".format(e)) + raise e host = self.get_param("host", "127.0.0.1") port = self.get_param("port", 2000) @@ -257,7 +257,11 @@ def connect_to_carla(self): carla_client = carla.Client(host=host, port=port) carla_client.set_timeout(timeout) - self.world = carla_client.get_world() + try: + self.world = carla_client.get_world() + except RuntimeError as e: + self.logerr("Error while connecting to Carla: {}".format(e)) + raise e self.loginfo("Connected to Carla.") @@ -268,6 +272,7 @@ def main(args=None): """ ros_init(args) + waypoint_converter = None try: waypoint_converter = CarlaToRosWaypointConverter() if ROS_VERSION == 1: @@ -276,11 +281,14 @@ def main(args=None): spin_thread = threading.Thread(target=waypoint_converter.spin) spin_thread.start() spin_thread.join() + except (RuntimeError, ROSException): + pass except KeyboardInterrupt: loginfo("User requested shut down.") finally: loginfo("Shutting down.") - waypoint_converter.destroy() + if waypoint_converter: + waypoint_converter.destroy() ros_shutdown() diff --git a/pcl_recorder/src/PclRecorder.cpp b/pcl_recorder/src/PclRecorder.cpp index 601fade4..af9af938 100644 --- a/pcl_recorder/src/PclRecorder.cpp +++ b/pcl_recorder/src/PclRecorder.cpp @@ -23,7 +23,7 @@ PclRecorder::PclRecorder() if (!ros::param::get("~role_name", roleName)) { roleName = "ego_vehicle"; } - sub = nh.subscribe("/carla/" + roleName + "/lidar/lidar1/point_cloud", 1000000, &PclRecorder::callback, this); + sub = nh.subscribe("/carla/" + roleName + "/lidar", 1000000, &PclRecorder::callback, this); } void PclRecorder::callback(const pcl::PCLPointCloud2::ConstPtr& cloud) diff --git a/pcl_recorder/src/PclRecorderROS2.cpp b/pcl_recorder/src/PclRecorderROS2.cpp index 075a2f6c..42a4ab69 100644 --- a/pcl_recorder/src/PclRecorderROS2.cpp +++ b/pcl_recorder/src/PclRecorderROS2.cpp @@ -28,7 +28,7 @@ PclRecorderROS2::PclRecorderROS2() : Node("pcl_recorder") if (!this->get_parameter("role_name", roleName)) { roleName = "ego_vehicle"; } - sub = this->create_subscription("/carla/" + roleName + "/lidar/lidar1/point_cloud", 100, std::bind(&PclRecorderROS2::callback, this, std::placeholders::_1)); + sub = this->create_subscription("/carla/" + roleName + "/lidar", 100, std::bind(&PclRecorderROS2::callback, this, std::placeholders::_1)); } void PclRecorderROS2::callback(const sensor_msgs::msg::PointCloud2::SharedPtr cloud) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 800bfca7..7530cb33 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -138,7 +138,10 @@ def new_timer(self, timer_period_sec, callback): return rospy.Timer(rospy.Duration(timer_period_sec), callback) def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None): - return rospy.wait_for_message(topic, topic_type, timeout) + try: + return rospy.wait_for_message(topic, topic_type, timeout) + except rospy.ROSException as e: + raise ROSException(e) def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): return rospy.Service(srv_name, srv_type, callback) From 1eebfcdd2fe065b0c747f2702a4c269d1532c505 Mon Sep 17 00:00:00 2001 From: Jean-Baptiste Magnin <47941074+jbmag@users.noreply.github.com> Date: Tue, 12 Jan 2021 15:50:16 +0100 Subject: [PATCH 474/627] Spawn object shutdown (#460) * fixed carla_spawn_object shutdown, ros2 call service back to using async call * format * removed forgotten import * format * remove threading import --- .../carla_spawn_objects.py | 41 ++++--------------- .../ros_compatibility/ros_compatible_node.py | 18 ++++++-- 2 files changed, 24 insertions(+), 35 deletions(-) diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 8139eaed..0714276b 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -18,13 +18,10 @@ import os import math import json -from threading import Thread from diagnostic_msgs.msg import KeyValue from geometry_msgs.msg import Pose from carla_msgs.msg import CarlaActorList - - from transforms3d.euler import euler2quat from carla_msgs.srv import SpawnObject, DestroyObject @@ -338,10 +335,7 @@ def destroy(self): for actor_id in self.vehicles_sensors: destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = actor_id - try: - self.call_service(self.destroy_object_service, destroy_object_request) - except ServiceException as e: - self.logwarn(str(e)) # TODO: use logwarn_once + self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.vehicles_sensors = [] @@ -349,10 +343,7 @@ def destroy(self): for actor_id in self.global_sensors: destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = actor_id - try: - self.call_service(self.destroy_object_service, destroy_object_request) - except ServiceException as e: - self.logwarn(str(e)) # TODO: use logwarn_once + self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.global_sensors = [] @@ -360,10 +351,7 @@ def destroy(self): for player_id in self.players: destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = player_id - try: - self.call_service(self.destroy_object_service, destroy_object_request) - except ServiceException as e: - self.logwarn(str(e)) # TODO: use logwarn_once + self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) self.loginfo("Object {} successfully destroyed.".format(player_id)) self.players = [] @@ -384,26 +372,15 @@ def main(args=None): logerr("Could not initialize CarlaSpawnObjects. Shutting down.") if spawn_objects_node: - if ROS_VERSION == 1: - spawn_objects_node.on_shutdown(spawn_objects_node.destroy) - try: - spawn_objects_node.spawn_objects() - except (ROSInterruptException, ServiceException, KeyboardInterrupt): - spawn_objects_node.logwarn( - "Spawning process has been interrupted. There might be actors that has not been destroyed properly") - except RuntimeError as e: - logfatal("Exception caught: {}".format(e)) + try: + spawn_objects_node.spawn_objects() spawn_objects_node.spin() - else: - spin_thread = Thread(target=spawn_objects_node.spin) + except (ROSInterruptException, ServiceException, KeyboardInterrupt): try: - spin_thread.start() - spawn_objects_node.spawn_objects() - spin_thread.join() - except (ROSInterruptException, ServiceException, KeyboardInterrupt): - loginfo("Shutting down.") spawn_objects_node.destroy() - + except ServiceException: + spawn_objects_node.logwarn( + 'Could not call destroy service on objects, the ros bridge is probably already shutdown') ros_shutdown() diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 7530cb33..2620d483 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -154,7 +154,7 @@ def create_service_client(self, service_name, service, callback_group=None): print("Service call failed: %s" % e) return client - def call_service(self, client, req): + def call_service(self, client, req, timeout_ros2=None): try: return client(req) except rospy.ServiceException as e: @@ -332,8 +332,20 @@ def create_service_client(self, service_name, service, callback_group=None): self.get_logger().info('service not available, waiting again...') return client - def call_service(self, client, req): - return client.call(req) + def call_service(self, client, req, timeout_ros2=None): + # uses the asynchronous call function but behaves like the synchronous call + # this is done because the basic synchronous call function doesn't raise + # an error when trying to call a service that is not alive anymore + future = client.call_async(req) + rclpy.spin_until_future_complete(self, future, timeout_sec=timeout_ros2) + if future.done(): + return future.result() + else: + if timeout_ros2 is not None: + raise ServiceException( + 'Service did not return a response before timeout {}'.format(timeout_ros2)) + else: + raise ServiceException('Service did not return a response') def spin(self, executor=None): rclpy.spin(self, executor) From 52340d66f870f9b8532c343b2882fea83ee2b3ec Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 13 Jan 2021 05:28:56 -0500 Subject: [PATCH 475/627] fix carla_ad_agent shutdown bug --- carla_ad_agent/src/carla_ad_agent/agent.py | 40 +++++++++---------- .../src/carla_ad_agent/basic_agent.py | 2 +- .../src/carla_ad_agent/carla_ad_agent.py | 24 ++++------- 3 files changed, 28 insertions(+), 38 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 65cf13ad..2a43c7be 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -122,15 +122,16 @@ def _is_light_red_europe_style(self, lights_list): - traffic_light is the object itself or None if there is no red traffic light affecting us """ - if self._vehicle_location is not None: - ego_vehicle_location = get_service_request(GetWaypoint) - ego_vehicle_location.location = self._vehicle_location - else: - ego_vehicle_location = self._vehicle_location + if self._vehicle_location is None: + # no available self location yet + return (False, None) + + ego_vehicle_location = get_service_request(GetWaypoint) + ego_vehicle_location.location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) if not ego_vehicle_waypoint: if ros_ok(): - self.node.logwarn("Could not get waypoint for ego vehicle.1") + self.node.logwarn("Could not get waypoint for ego vehicle.") return (False, None) for traffic_light in lights_list: @@ -161,7 +162,7 @@ def get_waypoint(self, location): try: response = self.node.call_service(self._get_waypoint_client, location) return response.waypoint - except (ServiceException, ROSInterruptException, KeyboardInterrupt, TypeError) as e: + except ServiceException as e: if ros_ok(): self.node.logwarn("Service call 'get_waypoint' failed: {}".format(str(e))) @@ -176,11 +177,12 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc - traffic_light is the object itself or None if there is no red traffic light affecting us """ - if self._vehicle_location is not None: - ego_vehicle_location = get_service_request(GetWaypoint) - ego_vehicle_location.location = self._vehicle_location - else: - ego_vehicle_location = self._vehicle_location + if self._vehicle_location is None: + # no available self location yet + return (False, None) + + ego_vehicle_location = get_service_request(GetWaypoint) + ego_vehicle_location.location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) if not ego_vehicle_waypoint: if ros_ok(): @@ -255,17 +257,16 @@ def _is_vehicle_hazard(self, vehicle_list, objects): and False otherwise - vehicle is the blocker object itself """ + if self._vehicle_location is None: + # no available self location yet + return (False, None) - if self._vehicle_location is not None: - ego_vehicle_location = get_service_request(GetWaypoint) - ego_vehicle_location.location = self._vehicle_location - else: - ego_vehicle_location = self._vehicle_location - + ego_vehicle_location = get_service_request(GetWaypoint) + ego_vehicle_location.location = self._vehicle_location ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) if not ego_vehicle_waypoint: if ros_ok(): - self.node.logwarn("Could not get waypoint for ego vehicle.3") + self.node.logwarn("Could not get waypoint for ego vehicle.") return (False, None) for target_vehicle_id in vehicle_list: @@ -312,5 +313,4 @@ def emergency_stop(self): # pylint: disable=no-self-use control.throttle = 0.0 control.brake = 1.0 control.hand_brake = False - return control diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index d5735634..db2e9a91 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -88,7 +88,7 @@ def get_actor_waypoint(self, actor_id): request.id = actor_id response = self.node.call_service(self._get_actor_waypoint_client, request) return response.waypoint - except (ServiceException, ROSInterruptException, KeyboardInterrupt, TypeError) as e: + except ServiceException as e: if ros_ok(): self.node.logwarn("Service call failed: {}".format(e)) diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 47e8aaef..80e704fc 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -53,7 +53,6 @@ def __init__(self): self._route_assigned = False self._global_plan = None self._agent = None - self.on_shutdown(self._on_shutdown) # wait for ego vehicle vehicle_info = None @@ -81,14 +80,6 @@ def __init__(self): self._agent = BasicAgent(role_name, vehicle_info.id, # pylint: disable=no-member self, avoid_risk) - def _on_shutdown(self): - """ - callback on shutdown - """ - self.loginfo("Shutting down, stopping ego vehicle...") - if self._agent: - self.vehicle_control_publisher.publish(self._agent.emergency_stop()) - def target_speed_updated(self, target_speed): """ callback on new target speed @@ -154,14 +145,11 @@ def run(self): control.steer = -control.steer self.vehicle_control_publisher.publish(control) else: - try: - if ROS_VERSION == 1: - r.sleep() - elif ROS_VERSION == 2: - # TODO: use rclpy.Rate, not working yet - time.sleep(1 / loop_frequency) - except ROSInterruptException: - pass + if ROS_VERSION == 1: + r.sleep() + elif ROS_VERSION == 2: + # TODO: use rclpy.Rate, not working yet + time.sleep(1 / loop_frequency) def main(args=None): @@ -182,6 +170,8 @@ def main(args=None): except KeyboardInterrupt: loginfo("User requested shut down.") finally: + if controller._agent: + controller.vehicle_control_publisher.publish(controller._agent.emergency_stop()) ros_shutdown() From 804a4fc5963e4c56a4f979f1f5acb1c6d5d03c7f Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 13 Jan 2021 07:25:43 -0500 Subject: [PATCH 476/627] fix same node name for manual_control and carla_ad_agent in ros2 launchfiles --- .../launch/carla_ad_agent.launch.py | 48 ++++++++++++------- .../launch/carla_manual_control.launch.py | 34 ++++++++----- 2 files changed, 53 insertions(+), 29 deletions(-) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 0bd5672f..6927f28b 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -5,12 +5,42 @@ import launch_ros.actions +def launch_setup(context, *args, **kwargs): + # workaround to use launch argument 'role_name' as a part of the string used for the node's name + node_name = 'carla_ad_agent_' + \ + launch.substitutions.LaunchConfiguration('role_name').perform(context) + + carla_ad_demo = launch_ros.actions.Node( + package='carla_ad_agent', + executable='carla_ad_agent', + name=node_name, + output='screen', + parameters=[ + { + 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'avoid_risk': launch.substitutions.LaunchConfiguration('avoid_risk') + } + ] + ) + + return [carla_ad_demo] + + def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( name='role_name', default_value='ego_vehicle' ), + launch.actions.SetLaunchConfiguration( + name='test', + value='jb' + ), launch.actions.DeclareLaunchArgument( name='target_speed', default_value='20' @@ -19,23 +49,7 @@ def generate_launch_description(): name='avoid_risk', default_value='True' ), - launch_ros.actions.Node( - package='carla_ad_agent', - executable='carla_ad_agent', - name=launch.substitutions.LaunchConfiguration('role_name'), - output='screen', - parameters=[ - { - 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') - }, - { - 'role_name': launch.substitutions.LaunchConfiguration('role_name') - }, - { - 'avoid_risk': launch.substitutions.LaunchConfiguration('avoid_risk') - } - ] - ) + launch.actions.OpaqueFunction(function=launch_setup) ]) return ld diff --git a/carla_manual_control/launch/carla_manual_control.launch.py b/carla_manual_control/launch/carla_manual_control.launch.py index a48ed671..c940a596 100644 --- a/carla_manual_control/launch/carla_manual_control.launch.py +++ b/carla_manual_control/launch/carla_manual_control.launch.py @@ -5,24 +5,34 @@ import launch_ros.actions +def launch_setup(context, *args, **kwargs): + # workaround to use launch argument 'role_name' as a part of the string used for the node's name + node_name = 'carla_manual_control_' + \ + launch.substitutions.LaunchConfiguration('role_name').perform(context) + + carla_manual_control = launch_ros.actions.Node( + package='carla_manual_control', + executable='carla_manual_control', + name=node_name, + output='screen', + emulate_tty=True, + parameters=[ + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] + ) + + return [carla_manual_control] + + def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( name='role_name', default_value='ego_vehicle' ), - launch_ros.actions.Node( - package='carla_manual_control', - executable='carla_manual_control', - name=launch.substitutions.LaunchConfiguration('role_name'), - output='screen', - emulate_tty=True, - parameters=[ - { - 'role_name': launch.substitutions.LaunchConfiguration('role_name') - } - ] - ) + launch.actions.OpaqueFunction(function=launch_setup) ]) return ld From e998c162ad06e5e83c68e2c373e684676448733d Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 13 Jan 2021 10:24:07 -0500 Subject: [PATCH 477/627] fix bug spawn_point parameter in ros carla_ad_demo launchfile --- carla_ad_demo/launch/carla_ad_demo.launch.py | 37 +++++++++++-------- .../carla_ad_demo_with_scenario.launch.py | 2 +- .../carla_spawn_objects.py | 2 +- 3 files changed, 23 insertions(+), 18 deletions(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index eebdf290..35b30401 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -6,6 +6,25 @@ from ament_index_python.packages import get_package_share_directory +def launch_carla_spawn_object(context, *args, **kwargs): + # workaround to use launch argument 'role_name' as a part of the string used for the spawn_point param name + spawn_point_param_name = 'spawn_point_' + \ + launch.substitutions.LaunchConfiguration('role_name').perform(context) + + carla_spawn_objects_launch = launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_spawn_objects'), 'carla_example_ego_vehicle.launch.py') + ), + launch_arguments={ + 'object_definition_file': get_package_share_directory('carla_spawn_objects') + '/config/sensors.json', + spawn_point_param_name: launch.substitutions.LaunchConfiguration('spawn_point') + }.items() + ) + + return [carla_spawn_objects_launch] + + def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( @@ -40,13 +59,9 @@ def generate_launch_description(): name='role_name', default_value='ego_vehicle' ), - launch.actions.DeclareLaunchArgument( - name='vehicle_filter', - default_value='vehicle.tesla.model3' - ), launch.actions.DeclareLaunchArgument( name='spawn_point', - default_value='127.4,195.4,0,0,0,180' + default_value='127.4,-195.4,2,0,0,180' ), launch.actions.DeclareLaunchArgument( name='target_speed', @@ -77,17 +92,7 @@ def generate_launch_description(): 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') }.items() ), - launch.actions.IncludeLaunchDescription( - launch.launch_description_sources.PythonLaunchDescriptionSource( - os.path.join(get_package_share_directory( - 'carla_spawn_objects'), 'carla_example_ego_vehicle.launch.py') - ), - launch_arguments={ - 'object_definition_file': get_package_share_directory('carla_spawn_objects') + '/config/sensors.json', - 'role_name_' + str(launch.substitutions.LaunchConfiguration('role_name')): launch.substitutions.LaunchConfiguration('role_name'), - 'spawn_point': launch.substitutions.LaunchConfiguration('spawn_point') - }.items() - ), + launch.actions.OpaqueFunction(function=launch_carla_spawn_object), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index b2a5c9a4..cd8c4009 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -93,7 +93,7 @@ def generate_launch_description(): ), launch_arguments={ 'object_definition_file': get_package_share_directory('carla_spawn_objects') + '/config/objects.json', - 'role_name_' + str(launch.substitutions.LaunchConfiguration('role_name')): launch.substitutions.LaunchConfiguration('role_name') + 'role_name': launch.substitutions.LaunchConfiguration('role_name') }.items() ), launch.actions.IncludeLaunchDescription( diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 0714276b..4f83626c 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -159,7 +159,7 @@ def setup_vehicles(self, vehicles): spawn_point = None # check if there's a spawn_point corresponding to this vehicle - spawn_point_param = self.get_param("~spawn_point_" + vehicle["id"], None) + spawn_point_param = self.get_param("spawn_point_" + vehicle["id"], None) spawn_param_used = False if (spawn_point_param is not None): # try to use spawn_point from parameters From 3af200f22df702bf74d7f90e614e2f243dc66204 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 13 Jan 2021 11:14:30 -0500 Subject: [PATCH 478/627] fixed ad_agent traffic light bug --- carla_ad_agent/src/carla_ad_agent/agent.py | 3 ++- carla_ad_agent/src/carla_ad_agent/basic_agent.py | 5 +---- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 2a43c7be..79d2f2ec 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -62,7 +62,8 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): self._traffic_lights = [] self._traffic_light_status_subscriber = node.create_subscriber(CarlaTrafficLightStatusList, - "/carla/traffic_lights", self.traffic_lights_updated) + "/carla/traffic_lights/status", self.traffic_lights_updated, + qos_profile=QoSProfile(depth=10, durability=latch_on)) node.create_subscriber(CarlaWorldInfo, "/carla/world_info", self.world_info_updated, qos_profile=QoSProfile(depth=1, durability=latch_on)) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index db2e9a91..1975bdf8 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -66,7 +66,7 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): self._vehicle_id_list = [] self._lights_id_list = [] self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", - self.actors_updated, qos_profile=QoSProfile(depth=1, durability=latch_on), callback_group=cb_group) + self.actors_updated, callback_group=cb_group) self._objects = [] self._objects_subscriber = self.node.create_subscriber(ObjectArray, @@ -140,7 +140,6 @@ def run_step(self, target_speed): vehicle_state, vehicle = self._is_vehicle_hazard( # pylint: disable=unused-variable self._vehicle_id_list, self._objects) if vehicle_state: - #rospy.loginfo('=== Vehicle blocking ahead [{}])'.format(vehicle)) self._state = AgentState.BLOCKED_BY_VEHICLE hazard_detected = True @@ -148,8 +147,6 @@ def run_step(self, target_speed): light_state, traffic_light = self._is_light_red( # pylint: disable=unused-variable self._lights_id_list) if light_state: - #rospy.loginfo('=== Red Light ahead [{}])'.format(traffic_light)) - self._state = AgentState.BLOCKED_RED_LIGHT hazard_detected = True From 3e28c49130cdef03e94bd144297524d2a1a56bd6 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 13 Jan 2021 12:33:48 -0500 Subject: [PATCH 479/627] fixed throttle and brake status bar in pyagmes --- .../src/carla_manual_control/carla_manual_control.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 1b1ccaf6..074e3a52 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -367,7 +367,7 @@ def __init__(self, role_name, width, height, node): self.vehicle_info = CarlaEgoVehicleInfo() self.vehicle_info_subscriber = node.create_subscriber( CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(self.role_name), - self.vehicle_info_updated, callback_group=self.callback_group) + self.vehicle_info_updated, callback_group=self.callback_group, qos_profile=QoSProfile(depth=10, durability=latch_on)) self.latitude = 0 self.longitude = 0 @@ -554,7 +554,7 @@ def render(self, display): else: rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6)) pygame.draw.rect(display, (255, 255, 255), rect_border, 1) - if item[2] < 0.0: + if item[2] <= 0.0: f = (item[1] - item[2]) / (item[3] - item[2]) rect = pygame.Rect((bar_h_offset + int(f * (bar_width - 6)), v_offset + 8), (6, 6)) From e64bc1f5d7de7e8060692d5a963bbdd13b048a4d Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Mon, 18 Jan 2021 09:20:47 +0100 Subject: [PATCH 480/627] carla_manual_control: fix throttle/brake display --- .../src/carla_manual_control/carla_manual_control.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 074e3a52..76856d1b 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -554,12 +554,12 @@ def render(self, display): else: rect_border = pygame.Rect((bar_h_offset, v_offset + 8), (bar_width, 6)) pygame.draw.rect(display, (255, 255, 255), rect_border, 1) - if item[2] <= 0.0: - f = (item[1] - item[2]) / (item[3] - item[2]) + f = (item[1] - item[2]) / (item[3] - item[2]) + if item[2] < 0.0: rect = pygame.Rect((bar_h_offset + int(f * (bar_width - 6)), v_offset + 8), (6, 6)) else: - rect = pygame.Rect((bar_h_offset, v_offset + 8), (0, 6)) + rect = pygame.Rect((bar_h_offset, v_offset + 8), (int(f * bar_width), 6)) pygame.draw.rect(display, (255, 255, 255), rect) item = item[0] if item: # At this point has to be a str. From 57caef8017a849ad0ce668a30da74f18065a061f Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 18 Jan 2021 07:06:22 -0500 Subject: [PATCH 481/627] clean up of create_service_client in ros_compatibility_node --- .../ros_compatibility/ros_compatible_node.py | 22 +++++++++++++------ 1 file changed, 15 insertions(+), 7 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 2620d483..785d809b 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -146,12 +146,18 @@ def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): return rospy.Service(srv_name, srv_type, callback) - def create_service_client(self, service_name, service, callback_group=None): - rospy.wait_for_service(service_name) + def create_service_client(self, service_name, service, timeout_sec=None, callback_group=None): + if timeout_sec is not None: + timeout = timeout_sec * 1000 + else: + timeout = timeout_sec try: + rospy.wait_for_service(service_name, timeout=timeout) client = rospy.ServiceProxy(service_name, service) except rospy.ServiceException as e: - print("Service call failed: %s" % e) + raise ServiceException(e) + except rospy.ROSException as e: + raise ROSException(e) return client def call_service(self, client, req, timeout_ros2=None): @@ -326,11 +332,13 @@ def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): return self.create_service(srv_type, srv_name, callback, callback_group=callback_group) - def create_service_client(self, service_name, service, callback_group=None): + def create_service_client(self, service_name, service, timeout_sec=None, callback_group=None): client = self.create_client(service, service_name, callback_group=callback_group) - while not client.wait_for_service(timeout_sec=1.0): - self.get_logger().info('service not available, waiting again...') - return client + status = client.wait_for_service(timeout_sec=timeout_sec) + if status is True: + return client + else: + raise ROSException("Timeout of {}sec while waiting for service".format(timeout_sec)) def call_service(self, client, req, timeout_ros2=None): # uses the asynchronous call function but behaves like the synchronous call From ba163ab303f79e09ea535e7fddb12e1489f95dce Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 15 Jan 2021 14:29:18 -0500 Subject: [PATCH 482/627] more cleanup in bridge, spawn_object and agent --- .../src/carla_ad_agent/basic_agent.py | 5 + .../src/carla_ad_agent/carla_ad_agent.py | 25 ++--- carla_ad_demo/launch/carla_ad_demo.launch.py | 2 +- .../src/carla_ros_bridge/actor_factory.py | 4 +- .../src/carla_ros_bridge/bridge.py | 36 ++++--- .../carla_spawn_objects.py | 102 +++++++++--------- .../carla_waypoint_publisher.py | 66 ++++++------ 7 files changed, 122 insertions(+), 118 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 1975bdf8..d558b8a2 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -65,6 +65,11 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): if self._avoid_risk: self._vehicle_id_list = [] self._lights_id_list = [] + + # the agent shouldn't start if it has no info about other actors and objects + self.node.wait_for_one_message("/carla/actor_list", CarlaActorList, timeout=15.0) + self.node.wait_for_one_message("/carla/{}/objects".format(role_name), ObjectArray, timeout=15.0) + self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", self.actors_updated, callback_group=cb_group) self._objects = [] diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 80e704fc..3fb8838e 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -56,15 +56,14 @@ def __init__(self): # wait for ego vehicle vehicle_info = None - try: - self.loginfo("Wait for vehicle info ...") - vehicle_info = self.wait_for_one_message( - "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, - qos_profile=QoSProfile(depth=1, durability=latch_on)) - self.loginfo("Vehicle info received.") - except ROSException: - self.logerr("Timeout while waiting for vehicle info!") - sys.exit(1) + self.loginfo("Wait for vehicle info ...") + vehicle_info = self.wait_for_one_message( + "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, + qos_profile=QoSProfile(depth=1, durability=latch_on)) + self.loginfo("Vehicle info received.") + + self._agent = BasicAgent(role_name, vehicle_info.id, # pylint: disable=no-member + self, avoid_risk) self._route_subscriber = self.create_subscriber( Path, "/carla/{}/waypoints".format(role_name), self.path_updated, @@ -77,8 +76,6 @@ def __init__(self): self.vehicle_control_publisher = self.new_publisher( CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), QoSProfile(depth=1, durability=False)) - self._agent = BasicAgent(role_name, vehicle_info.id, # pylint: disable=no-member - self, avoid_risk) def target_speed_updated(self, target_speed): """ @@ -160,17 +157,17 @@ def main(args=None): :return: """ ros_init(args) - + controller = None try: controller = CarlaAdAgent() controller.run() - except ROSInterruptException as e: + except (ROSInterruptException, ROSException) as e: if ros_ok(): logwarn("ROS Error during exection: {}".format(e)) except KeyboardInterrupt: loginfo("User requested shut down.") finally: - if controller._agent: + if controller is not None and controller._agent: controller.vehicle_control_publisher.publish(controller._agent.emergency_stop()) ros_shutdown() diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 35b30401..0c211018 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -41,7 +41,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='timeout', - default_value='2' + default_value='10' ), launch.actions.DeclareLaunchArgument( name='synchronous_mode', diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 89c454dd..082a8160 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -121,14 +121,14 @@ def update_available_objects(self): with self.spawn_lock: while not self._task_queue.empty(): task = self._task_queue.get() - if task[0] == ActorFactory.TaskType.SPAWN_PSEUDO_ACTOR: + if task[0] == ActorFactory.TaskType.SPAWN_PSEUDO_ACTOR and not self.node.shutdown.is_set(): pseudo_object = task[1] self._create_object(pseudo_object[0], pseudo_object[1].type, pseudo_object[1].id, pseudo_object[1].attach_to, pseudo_object[1].transform) elif task[0] == ActorFactory.TaskType.DESTROY_ACTOR: actor_id = task[1] self._destroy_object(actor_id, delete_actor=True) - elif task[0] == ActorFactory.TaskType.SYNC: + elif task[0] == ActorFactory.TaskType.SYNC and not self.node.shutdown.is_set(): break self.lock.release() diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index d5aee0b2..f9fa7b4c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -80,6 +80,7 @@ def __init__(self, rospy_init=True, executor=None): """ super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) self.executor = executor + self.bridge_is_initialized = Event() # pylint: disable=attribute-defined-outside-init def initialize_bridge(self, carla_world, params): @@ -98,7 +99,6 @@ def initialize_bridge(self, carla_world, params): self.synchronous_mode_update_thread = None self.shutdown = Event() - self.synchronous_update_finished_event = Event() self.carla_settings = carla_world.get_settings() if not self.parameters["passive"]: @@ -183,17 +183,22 @@ def initialize_bridge(self, carla_world, params): self.carla_weather_subscriber = \ self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", self.on_weather_changed, callback_group=self.callback_group) + self.bridge_is_initialized.set() def spawn_object(self, req, response=None): response = get_service_response(SpawnObject) - try: - id_ = self.actor_factory.spawn_actor(req) - self._registered_actors.append(id_) - response.id = id_ - except Exception as e: - self.logwarn("Error spawning object '{}': {}".format(req.type, e)) + if not self.shutdown.is_set(): + try: + id_ = self.actor_factory.spawn_actor(req) + self._registered_actors.append(id_) + response.id = id_ + except Exception as e: + self.logwarn("Error spawning object '{}': {}".format(req.type, e)) + response.id = -1 + response.error_string = str(e) + else: response.id = -1 - response.error_string = str(e) + response.error_string = 'Bridge is shutting down, object will not be spawned.' return response def destroy_object(self, req, response=None): @@ -270,8 +275,7 @@ def _synchronous_mode_update(self): """ execution loop for synchronous mode """ - while not self.shutdown.is_set(): - self.synchronous_update_finished_event.clear() + while not self.shutdown.is_set() and ros_ok(): self.process_run_state() if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: @@ -301,7 +305,6 @@ def _synchronous_mode_update(self): "Missing command from actor ids {}".format(CarlaRosBridge.VEHICLE_CONTROL_TIMEOUT, self._expected_ego_vehicle_control_command_ids)) self._all_vehicle_control_commands_received.clear() - self.synchronous_update_finished_event.set() def _carla_time_tick(self, carla_snapshot): """ @@ -355,8 +358,9 @@ def update_clock(self, carla_timestamp): :type carla_timestamp: carla.Timestamp :return: """ - self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) - self.clock_publisher.publish(Clock(clock=self.ros_timestamp)) + if ros_ok(): + self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) + self.clock_publisher.publish(Clock(clock=self.ros_timestamp)) def destroy(self): """ @@ -364,7 +368,6 @@ def destroy(self): :return: """ - # TODO fix if carla is not running self.loginfo("Shutting down...") self.shutdown.set() if not self.sync_mode: @@ -372,7 +375,7 @@ def destroy(self): self.carla_world.remove_on_tick(self.on_tick_id) self.actor_factory.thread.join() else: - self.synchronous_update_finished_event.wait() + self.synchronous_mode_update_thread.join() self.loginfo("Object update finished.") self.debug_helper.destroy() self.status_publisher.destroy() @@ -472,7 +475,8 @@ def main(args=None): except KeyboardInterrupt: pass finally: - carla_bridge.destroy() + if carla_bridge.bridge_is_initialized.is_set(): + carla_bridge.destroy() ros_shutdown() del carla_world del carla_client diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 4f83626c..367567f3 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -68,19 +68,15 @@ def __init__(self): def spawn_object(self, spawn_object_request): response_id = -1 - try: - response = self.call_service(self.spawn_object_service, spawn_object_request) - response_id = response.id - if response_id != -1: - self.loginfo("Object (type='{}', id='{}') spawned successfully as {}.".format( - spawn_object_request.type, spawn_object_request.id, response_id)) - else: - self.logwarn("Error while spawning object (type='{}', id='{}').".format( - spawn_object_request.type, spawn_object_request.id)) - raise RuntimeError(response.error_string) - except ServiceException as e: - self.logwarn("Error while calling spawn_object(type='{}', id='{}'): {}".format( - spawn_object_request.type, spawn_object_request.id, e)) + response = self.call_service(self.spawn_object_service, spawn_object_request) + response_id = response.id + if response_id != -1: + self.loginfo("Object (type='{}', id='{}') spawned successfully as {}.".format( + spawn_object_request.type, spawn_object_request.id, response_id)) + else: + self.logwarn("Error while spawning object (type='{}', id='{}').".format( + spawn_object_request.type, spawn_object_request.id)) + raise RuntimeError(response.error_string) return response_id def spawn_objects(self): @@ -118,10 +114,7 @@ def spawn_objects(self): raise RuntimeError("Parameter 'spawn_sensors_only' enabled, " + "but 'sensor.pseudo.actor_list' is not instantiated, add it to your config file.") - try: - self.setup_sensors(global_sensors) - except RuntimeError as e: - raise RuntimeError("Setting up global sensors failed: {}".format(e)) + self.setup_sensors(global_sensors) if self.spawn_sensors_only is True: # get vehicle id from topic /carla/actor_list for all vehicles listed in config file @@ -131,10 +124,7 @@ def spawn_objects(self): if actor_info.type == vehicle["type"] and actor_info.rolename == vehicle["id"]: vehicle["carla_id"] = actor_info.id - try: - self.setup_vehicles(vehicles) - except RuntimeError as e: - raise RuntimeError("Setting up vehicles failed: {}".format(e)) + self.setup_vehicles(vehicles) self.loginfo("All objects spawned.") def setup_vehicles(self, vehicles): @@ -330,30 +320,33 @@ def destroy(self): destroy all the players and sensors """ self.loginfo("Destroying spawned objects...") - - # destroy vehicles sensors - for actor_id in self.vehicles_sensors: - destroy_object_request = get_service_request(DestroyObject) - destroy_object_request.id = actor_id - self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) - self.loginfo("Object {} successfully destroyed.".format(actor_id)) - self.vehicles_sensors = [] - - # destroy global sensors - for actor_id in self.global_sensors: - destroy_object_request = get_service_request(DestroyObject) - destroy_object_request.id = actor_id - self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) - self.loginfo("Object {} successfully destroyed.".format(actor_id)) - self.global_sensors = [] - - # destroy player - for player_id in self.players: - destroy_object_request = get_service_request(DestroyObject) - destroy_object_request.id = player_id - self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) - self.loginfo("Object {} successfully destroyed.".format(player_id)) - self.players = [] + try: + # destroy vehicles sensors + for actor_id in self.vehicles_sensors: + destroy_object_request = get_service_request(DestroyObject) + destroy_object_request.id = actor_id + self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) + self.loginfo("Object {} successfully destroyed.".format(actor_id)) + self.vehicles_sensors = [] + + # destroy global sensors + for actor_id in self.global_sensors: + destroy_object_request = get_service_request(DestroyObject) + destroy_object_request.id = actor_id + self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) + self.loginfo("Object {} successfully destroyed.".format(actor_id)) + self.global_sensors = [] + + # destroy player + for player_id in self.players: + destroy_object_request = get_service_request(DestroyObject) + destroy_object_request.id = player_id + self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) + self.loginfo("Object {} successfully destroyed.".format(player_id)) + self.players = [] + except ServiceException: + self.logwarn( + 'Could not call destroy service on objects, the ros bridge is probably already shutdown') # ============================================================================== # -- main() -------------------------------------------------------------------- @@ -372,15 +365,22 @@ def main(args=None): logerr("Could not initialize CarlaSpawnObjects. Shutting down.") if spawn_objects_node: - try: + if ROS_VERSION == 1: + spawn_objects_node.on_shutdown(spawn_objects_node.destroy) + try: spawn_objects_node.spawn_objects() - spawn_objects_node.spin() - except (ROSInterruptException, ServiceException, KeyboardInterrupt): try: + spawn_objects_node.spin() + except (ROSInterruptException, ServiceException, KeyboardInterrupt): + pass + except (ROSInterruptException, ServiceException, KeyboardInterrupt): + spawn_objects_node.logwarn( + "Spawning process has been interrupted. There might be actors that have not been destroyed properly") + except RuntimeError as e: + logfatal("Exception caught: {}".format(e)) + finally: + if ROS_VERSION == 2: spawn_objects_node.destroy() - except ServiceException: - spawn_objects_node.logwarn( - 'Could not call destroy service on objects, the ros bridge is probably already shutdown') ros_shutdown() diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 454286b5..390a45b9 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -86,7 +86,6 @@ def __init__(self): self.goal_subscriber = self.create_subscriber( PoseStamped, "/carla/{}/goal".format(self.role_name), self.on_goal) - self._update_lock = threading.Lock() # use callback to wait for ego vehicle self.loginfo("Waiting for ego vehicle...") @@ -170,38 +169,37 @@ def find_ego_vehicle_actor(self, _): """ Look for an carla actor with name 'ego_vehicle' """ - with self._update_lock: - hero = None - for actor in self.world.get_actors(): - if actor.attributes.get('role_name') == self.role_name: - hero = actor - break - - ego_vehicle_changed = False - if hero is None and self.ego_vehicle is not None: - ego_vehicle_changed = True - - if not ego_vehicle_changed and hero is not None and self.ego_vehicle is None: - ego_vehicle_changed = True - - if not ego_vehicle_changed and hero is not None and \ - self.ego_vehicle is not None and hero.id != self.ego_vehicle.id: - ego_vehicle_changed = True - - if ego_vehicle_changed: - self.loginfo("Ego vehicle changed.") - self.ego_vehicle = hero - self.reroute() - elif self.ego_vehicle: - current_location = self.ego_vehicle.get_location() - if self.ego_vehicle_location: - dx = self.ego_vehicle_location.x - current_location.x - dy = self.ego_vehicle_location.y - current_location.y - distance = math.sqrt(dx * dx + dy * dy) - if distance > self.WAYPOINT_DISTANCE: - self.loginfo("Ego vehicle was repositioned.") - self.reroute() - self.ego_vehicle_location = current_location + hero = None + for actor in self.world.get_actors(): + if actor.attributes.get('role_name') == self.role_name: + hero = actor + break + + ego_vehicle_changed = False + if hero is None and self.ego_vehicle is not None: + ego_vehicle_changed = True + + if not ego_vehicle_changed and hero is not None and self.ego_vehicle is None: + ego_vehicle_changed = True + + if not ego_vehicle_changed and hero is not None and \ + self.ego_vehicle is not None and hero.id != self.ego_vehicle.id: + ego_vehicle_changed = True + + if ego_vehicle_changed: + self.loginfo("Ego vehicle changed.") + self.ego_vehicle = hero + self.reroute() + elif self.ego_vehicle: + current_location = self.ego_vehicle.get_location() + if self.ego_vehicle_location: + dx = self.ego_vehicle_location.x - current_location.x + dy = self.ego_vehicle_location.y - current_location.y + distance = math.sqrt(dx * dx + dy * dy) + if distance > self.WAYPOINT_DISTANCE: + self.loginfo("Ego vehicle was repositioned.") + self.reroute() + self.ego_vehicle_location = current_location def calculate_route(self, goal): """ @@ -243,7 +241,7 @@ def connect_to_carla(self): self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, - qos_profile=QoSProfile(depth=1, durability=latch_on), timeout=10.0) + qos_profile=QoSProfile(depth=1, durability=latch_on), timeout=15.0) except ROSException as e: self.logerr("Error while waiting for world info: {}".format(e)) raise e From ea86c450b461a9e00fc8c53d29918613a8ec68c9 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 18 Jan 2021 05:30:54 -0500 Subject: [PATCH 483/627] use a bool instead of an event to say that bridge is initialized --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index f9fa7b4c..987edd2c 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -80,7 +80,7 @@ def __init__(self, rospy_init=True, executor=None): """ super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) self.executor = executor - self.bridge_is_initialized = Event() + self.bridge_is_initialized = False # pylint: disable=attribute-defined-outside-init def initialize_bridge(self, carla_world, params): @@ -183,7 +183,7 @@ def initialize_bridge(self, carla_world, params): self.carla_weather_subscriber = \ self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", self.on_weather_changed, callback_group=self.callback_group) - self.bridge_is_initialized.set() + self.bridge_is_initialized = True def spawn_object(self, req, response=None): response = get_service_response(SpawnObject) @@ -475,7 +475,7 @@ def main(args=None): except KeyboardInterrupt: pass finally: - if carla_bridge.bridge_is_initialized.is_set(): + if carla_bridge.bridge_is_initialized is True: carla_bridge.destroy() ros_shutdown() del carla_world From 80d6e4239cc17eace8981db8bbf67d9e74e2a64d Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 18 Jan 2021 14:10:22 -0500 Subject: [PATCH 484/627] increased sigterm timeout in launchfile, and fixed bug in carla_spawn_objects error handling --- carla_ad_demo/launch/carla_ad_demo.launch.py | 4 ++++ .../src/carla_spawn_objects/carla_spawn_objects.py | 4 ++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 0c211018..0870cb6f 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -71,6 +71,10 @@ def generate_launch_description(): name='avoid_risk', default_value='True' ), + launch.actions.DeclareLaunchArgument( + name='sigterm_timeout', + default_value='15' + ), # TODO: adapt this to ROS2 # launch_ros.actions.Node( # package='rostopic', diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 367567f3..b2b5068c 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -283,8 +283,8 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): continue except NameError: - self.logerr("Sensor rolename '{}' is only allowed to be used once.".format( - sensor_spec['id'])) + self.logerr("Sensor rolename '{}' is only allowed to be used once. The second one will be ignored.".format( + sensor_id)) continue def create_spawn_point(self, x, y, z, roll, pitch, yaw): From d64a13fb723c3c795b6423884b455043fd4ee44b Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 18 Jan 2021 14:12:39 -0500 Subject: [PATCH 485/627] fix format --- .../src/carla_ad_agent/basic_agent.py | 3 ++- .../carla_manual_control.py | 3 ++- .../carla_spawn_objects/carla_spawn_objects.py | 17 ++++++++++------- .../carla_waypoint_publisher.py | 1 - .../ros_compatibility/ros_compatible_node.py | 2 +- 5 files changed, 15 insertions(+), 11 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index d558b8a2..eb4a10f8 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -68,7 +68,8 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): # the agent shouldn't start if it has no info about other actors and objects self.node.wait_for_one_message("/carla/actor_list", CarlaActorList, timeout=15.0) - self.node.wait_for_one_message("/carla/{}/objects".format(role_name), ObjectArray, timeout=15.0) + self.node.wait_for_one_message( + "/carla/{}/objects".format(role_name), ObjectArray, timeout=15.0) self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", self.actors_updated, callback_group=cb_group) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 76856d1b..f49a57f8 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -559,7 +559,8 @@ def render(self, display): rect = pygame.Rect((bar_h_offset + int(f * (bar_width - 6)), v_offset + 8), (6, 6)) else: - rect = pygame.Rect((bar_h_offset, v_offset + 8), (int(f * bar_width), 6)) + rect = pygame.Rect((bar_h_offset, v_offset + 8), + (int(f * bar_width), 6)) pygame.draw.rect(display, (255, 255, 255), rect) item = item[0] if item: # At this point has to be a str. diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index b2b5068c..27f06532 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -325,7 +325,8 @@ def destroy(self): for actor_id in self.vehicles_sensors: destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = actor_id - self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) + self.call_service(self.destroy_object_service, + destroy_object_request, timeout_ros2=0.2) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.vehicles_sensors = [] @@ -333,7 +334,8 @@ def destroy(self): for actor_id in self.global_sensors: destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = actor_id - self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) + self.call_service(self.destroy_object_service, + destroy_object_request, timeout_ros2=0.2) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.global_sensors = [] @@ -341,7 +343,8 @@ def destroy(self): for player_id in self.players: destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = player_id - self.call_service(self.destroy_object_service, destroy_object_request, timeout_ros2=0.2) + self.call_service(self.destroy_object_service, + destroy_object_request, timeout_ros2=0.2) self.loginfo("Object {} successfully destroyed.".format(player_id)) self.players = [] except ServiceException: @@ -367,16 +370,16 @@ def main(args=None): if spawn_objects_node: if ROS_VERSION == 1: spawn_objects_node.on_shutdown(spawn_objects_node.destroy) - try: + try: spawn_objects_node.spawn_objects() try: spawn_objects_node.spin() except (ROSInterruptException, ServiceException, KeyboardInterrupt): pass - except (ROSInterruptException, ServiceException, KeyboardInterrupt): - spawn_objects_node.logwarn( + except (ROSInterruptException, ServiceException, KeyboardInterrupt): + spawn_objects_node.logwarn( "Spawning process has been interrupted. There might be actors that have not been destroyed properly") - except RuntimeError as e: + except RuntimeError as e: logfatal("Exception caught: {}".format(e)) finally: if ROS_VERSION == 2: diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 390a45b9..bff4b888 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -86,7 +86,6 @@ def __init__(self): self.goal_subscriber = self.create_subscriber( PoseStamped, "/carla/{}/goal".format(self.role_name), self.on_goal) - # use callback to wait for ego vehicle self.loginfo("Waiting for ego vehicle...") self.on_tick = self.world.on_tick(self.find_ego_vehicle_actor) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 785d809b..455bc0dd 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -152,7 +152,7 @@ def create_service_client(self, service_name, service, timeout_sec=None, callbac else: timeout = timeout_sec try: - rospy.wait_for_service(service_name, timeout=timeout) + rospy.wait_for_service(service_name, timeout=timeout) client = rospy.ServiceProxy(service_name, service) except rospy.ServiceException as e: raise ServiceException(e) From e7eb9f75fa43628cf48a6a3b72e15e4f70960a89 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 27 Jan 2021 06:16:56 -0500 Subject: [PATCH 486/627] removed unnecessary clock subcriber in manual control --- .../src/carla_manual_control/carla_manual_control.py | 7 ------- 1 file changed, 7 deletions(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index f49a57f8..a52bfe5c 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -385,10 +385,6 @@ def __init__(self, role_name, width, height, node): self.status_subscriber = node.create_subscriber(CarlaStatus, "/carla/status", self.carla_status_updated, callback_group=self.callback_group) - if ROS_VERSION == 2: - self.clock_subscriber = node.create_subscriber(Time, "/clock", - self.clock_status_updated, - callback_group=self.callback_group) def tick(self, clock): """ @@ -396,9 +392,6 @@ def tick(self, clock): """ self._notifications.tick(clock) - def clock_status_updated(self, clock_time): - self.time = clock_time - def carla_status_updated(self, data): """ Callback on carla status From 794208647afa9106ab62b4f277606cb93f14034d Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 27 Jan 2021 06:20:38 -0500 Subject: [PATCH 487/627] removed self.time in manual control --- .../src/carla_manual_control/carla_manual_control.py | 1 - 1 file changed, 1 deletion(-) diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index a52bfe5c..d3e84893 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -357,7 +357,6 @@ def __init__(self, role_name, width, height, node): elif ROS_VERSION == 2: self.tf_buffer = tf2_ros.Buffer() self.tf_listener = tf2_ros.TransformListener(self.tf_buffer, node=self.node) - self.time = Time() self.callback_group = ReentrantCallbackGroup() self.vehicle_status_subscriber = node.create_subscriber( From e02c8646ea7201e15fdf1a5ccd0e0b6797baaf3c Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 29 Jan 2021 08:01:19 -0500 Subject: [PATCH 488/627] removed useless workaround to have a composed node name in ros2 launchfile --- .../launch/carla_ad_agent.launch.py | 45 +++++++------------ .../launch/carla_manual_control.launch.py | 34 +++++--------- 2 files changed, 29 insertions(+), 50 deletions(-) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 6927f28b..2446126f 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -4,33 +4,6 @@ import launch import launch_ros.actions - -def launch_setup(context, *args, **kwargs): - # workaround to use launch argument 'role_name' as a part of the string used for the node's name - node_name = 'carla_ad_agent_' + \ - launch.substitutions.LaunchConfiguration('role_name').perform(context) - - carla_ad_demo = launch_ros.actions.Node( - package='carla_ad_agent', - executable='carla_ad_agent', - name=node_name, - output='screen', - parameters=[ - { - 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') - }, - { - 'role_name': launch.substitutions.LaunchConfiguration('role_name') - }, - { - 'avoid_risk': launch.substitutions.LaunchConfiguration('avoid_risk') - } - ] - ) - - return [carla_ad_demo] - - def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( @@ -49,7 +22,23 @@ def generate_launch_description(): name='avoid_risk', default_value='True' ), - launch.actions.OpaqueFunction(function=launch_setup) + launch_ros.actions.Node( + package='carla_ad_agent', + executable='carla_ad_agent', + name=['carla_ad_agent_', launch.substitutions.LaunchConfiguration('role_name')], + output='screen', + parameters=[ + { + 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'avoid_risk': launch.substitutions.LaunchConfiguration('avoid_risk') + } + ] + ) ]) return ld diff --git a/carla_manual_control/launch/carla_manual_control.launch.py b/carla_manual_control/launch/carla_manual_control.launch.py index c940a596..6dc74f6a 100644 --- a/carla_manual_control/launch/carla_manual_control.launch.py +++ b/carla_manual_control/launch/carla_manual_control.launch.py @@ -5,34 +5,24 @@ import launch_ros.actions -def launch_setup(context, *args, **kwargs): - # workaround to use launch argument 'role_name' as a part of the string used for the node's name - node_name = 'carla_manual_control_' + \ - launch.substitutions.LaunchConfiguration('role_name').perform(context) - - carla_manual_control = launch_ros.actions.Node( - package='carla_manual_control', - executable='carla_manual_control', - name=node_name, - output='screen', - emulate_tty=True, - parameters=[ - { - 'role_name': launch.substitutions.LaunchConfiguration('role_name') - } - ] - ) - - return [carla_manual_control] - - def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( name='role_name', default_value='ego_vehicle' ), - launch.actions.OpaqueFunction(function=launch_setup) + launch_ros.actions.Node( + package='carla_manual_control', + executable='carla_manual_control', + name=['carla_manual_control_', launch.substitutions.LaunchConfiguration('role_name')], + output='screen', + emulate_tty=True, + parameters=[ + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] + ) ]) return ld From 34b53599d1aea2fa68a282400cad2286d3173844 Mon Sep 17 00:00:00 2001 From: Jean-Baptiste Magnin <47941074+jbmag@users.noreply.github.com> Date: Mon, 1 Feb 2021 11:19:56 +0100 Subject: [PATCH 489/627] Update carla_ad_demo.launch.py ad demo launch file uses old name of sensor setup file, and wrong param name --- carla_ad_demo/launch/carla_ad_demo.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 0870cb6f..fbb46633 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -17,7 +17,7 @@ def launch_carla_spawn_object(context, *args, **kwargs): 'carla_spawn_objects'), 'carla_example_ego_vehicle.launch.py') ), launch_arguments={ - 'object_definition_file': get_package_share_directory('carla_spawn_objects') + '/config/sensors.json', + 'objects_definition_file': get_package_share_directory('carla_spawn_objects') + '/config/objects.json', spawn_point_param_name: launch.substitutions.LaunchConfiguration('spawn_point') }.items() ) From 2dd1247f52ea081e06434312fc5b45c30b7af751 Mon Sep 17 00:00:00 2001 From: ksuszka Date: Mon, 1 Feb 2021 16:12:52 +0100 Subject: [PATCH 490/627] Fixed rosdep installation errors for missing ros2 packages --- carla_ackermann_control/package.xml | 1 - carla_ad_agent/package.xml | 1 - carla_ad_demo/package.xml | 1 - carla_common/package.xml | 2 -- carla_manual_control/package.xml | 1 - carla_ros_bridge/package.xml | 1 - carla_ros_scenario_runner/package.xml | 1 - carla_ros_scenario_runner_types/package.xml | 1 - carla_spawn_objects/package.xml | 1 - carla_walker_agent/package.xml | 1 - carla_waypoint_publisher/package.xml | 1 - 11 files changed, 12 deletions(-) diff --git a/carla_ackermann_control/package.xml b/carla_ackermann_control/package.xml index 823eed0b..35cc1cbd 100644 --- a/carla_ackermann_control/package.xml +++ b/carla_ackermann_control/package.xml @@ -15,7 +15,6 @@ rclpy - ament_python tf2_ros diff --git a/carla_ad_agent/package.xml b/carla_ad_agent/package.xml index 503f5bea..4541a632 100644 --- a/carla_ad_agent/package.xml +++ b/carla_ad_agent/package.xml @@ -20,7 +20,6 @@ rclpy - ament_python catkin diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml index 74cb7ae0..1edf5af5 100644 --- a/carla_ad_demo/package.xml +++ b/carla_ad_demo/package.xml @@ -18,7 +18,6 @@ - ament_python rviz2 diff --git a/carla_common/package.xml b/carla_common/package.xml index ed331092..65294f80 100644 --- a/carla_common/package.xml +++ b/carla_common/package.xml @@ -8,8 +8,6 @@ catkin - ament_python - catkin ament_python diff --git a/carla_manual_control/package.xml b/carla_manual_control/package.xml index 89327e55..70a0e3e9 100644 --- a/carla_manual_control/package.xml +++ b/carla_manual_control/package.xml @@ -13,7 +13,6 @@ rclpy - ament_python tf2_ros diff --git a/carla_ros_bridge/package.xml b/carla_ros_bridge/package.xml index 1d4fc2d6..30dd3ef1 100644 --- a/carla_ros_bridge/package.xml +++ b/carla_ros_bridge/package.xml @@ -25,7 +25,6 @@ rclpy - ament_python tf2_ros rviz2 diff --git a/carla_ros_scenario_runner/package.xml b/carla_ros_scenario_runner/package.xml index c337ed80..b7d6ae48 100644 --- a/carla_ros_scenario_runner/package.xml +++ b/carla_ros_scenario_runner/package.xml @@ -21,7 +21,6 @@ rclpy - ament_python catkin diff --git a/carla_ros_scenario_runner_types/package.xml b/carla_ros_scenario_runner_types/package.xml index d87561d9..07d9dc4f 100644 --- a/carla_ros_scenario_runner_types/package.xml +++ b/carla_ros_scenario_runner_types/package.xml @@ -16,7 +16,6 @@ builtin_interfaces - message_runtime geometry_msgs message_runtime diff --git a/carla_spawn_objects/package.xml b/carla_spawn_objects/package.xml index c3c41ec4..aaf7d480 100644 --- a/carla_spawn_objects/package.xml +++ b/carla_spawn_objects/package.xml @@ -12,7 +12,6 @@ rclpy - ament_python catkin diff --git a/carla_walker_agent/package.xml b/carla_walker_agent/package.xml index e8e538d4..53b24768 100644 --- a/carla_walker_agent/package.xml +++ b/carla_walker_agent/package.xml @@ -19,7 +19,6 @@ rclpy - ament_python catkin diff --git a/carla_waypoint_publisher/package.xml b/carla_waypoint_publisher/package.xml index 6ce6b3ef..095ede8b 100644 --- a/carla_waypoint_publisher/package.xml +++ b/carla_waypoint_publisher/package.xml @@ -18,7 +18,6 @@ rclpy - ament_python From 487356c0835ae5231a8055d69bffd94cf884249d Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 3 Feb 2021 15:53:02 +0100 Subject: [PATCH 491/627] Fix orientation of radar meassurement --- carla_ad_demo/config/carla_ad_demo_ros2.rviz | 52 ++++++++++--------- .../src/carla_ros_bridge/radar.py | 5 +- carla_spawn_objects/config/objects.json | 2 +- 3 files changed, 31 insertions(+), 28 deletions(-) diff --git a/carla_ad_demo/config/carla_ad_demo_ros2.rviz b/carla_ad_demo/config/carla_ad_demo_ros2.rviz index 84bcbf2a..490024e7 100644 --- a/carla_ad_demo/config/carla_ad_demo_ros2.rviz +++ b/carla_ad_demo/config/carla_ad_demo_ros2.rviz @@ -5,7 +5,7 @@ Panels: Property Tree Widget: Expanded: ~ Splitter Ratio: 0.5 - Tree Height: 468 + Tree Height: 467 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -86,7 +86,7 @@ Visualization Manager: Depth Camera: true Grid: true Lidar: true - Marker: true + MarkerArray: true Path: true Radar: true Semantic Camera: true @@ -128,11 +128,15 @@ Visualization Manager: Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true - Topic: /carla/markers Name: MarkerArray Namespaces: "": true - Queue Size: 100 + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/markers Value: true - Class: rviz_default_plugins/Image Enabled: true @@ -179,47 +183,47 @@ Visualization Manager: - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 + Max Value: 4.606257438659668 + Min Value: -5.983916759490967 Value: true Axis: Z - Channel Name: intensity + Channel Name: ObjTag Class: rviz_default_plugins/PointCloud2 Color: 255; 255; 255 Color Transformer: Intensity Decay Time: 0 - Enabled: false + Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 + Max Intensity: 19 Min Color: 0; 0; 0 Min Intensity: 0 Name: Semantic Lidar Position Transformer: XYZ Selectable: true - Size (Pixels): 3 + Size (Pixels): 2 Size (m): 0.009999999776482582 - Style: Flat Squares + Style: Points Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /carla/ego_vehicle/semantic_lidar/lidar1/point_cloud + Value: /carla/ego_vehicle/semantic_lidar Use Fixed Frame: true Use rainbow: true - Value: false + Value: true - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 + Max Value: 11.679780006408691 + Min Value: -1.10270357131958 Value: true Axis: Z Channel Name: intensity Class: rviz_default_plugins/PointCloud2 Color: 255; 255; 255 - Color Transformer: Intensity + Color Transformer: AxisColor Decay Time: 0 Enabled: true Invert Rainbow: false @@ -230,15 +234,15 @@ Visualization Manager: Name: Radar Position Transformer: XYZ Selectable: true - Size (Pixels): 3 + Size (Pixels): 1.5 Size (m): 0.009999999776482582 - Style: Flat Squares + Style: Points Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /carla/ego_vehicle/radar/front/radar + Value: /carla/ego_vehicle/radar_front Use Fixed Frame: true Use rainbow: true Value: true @@ -300,10 +304,10 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.49539870023727417 + Pitch: 0.33539873361587524 Target Frame: ego_vehicle Value: ThirdPersonFollower (rviz_default_plugins) - Yaw: 3.1504008769989014 + Yaw: 3.110400676727295 Saved: ~ Window Geometry: CarlaControl: @@ -314,10 +318,10 @@ Window Geometry: collapsed: false Displays: collapsed: false - Height: 1090 + Height: 1089 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 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 + QMainWindow State: 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 RGB Camera: collapsed: false Selection: @@ -328,6 +332,6 @@ Window Geometry: collapsed: false Views: collapsed: false - Width: 1920 + Width: 1918 X: 0 Y: 24 diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index 8f16b493..a63346a9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -74,9 +74,8 @@ def sensor_data_updated(self, carla_radar_measurement): PointField(name='ElevationAngle', offset=28, datatype=PointField.FLOAT32, count=1)] points = [] for detection in carla_radar_measurement: - points.append([detection.depth * np.cos(-detection.azimuth) * np.cos(detection.altitude), - detection.depth * np.sin(-detection.azimuth) * - np.cos(detection.altitude), + points.append([detection.depth * np.cos(detection.azimuth) * np.cos(-detection.altitude), + detection.depth * np.sin(-detection.azimuth) * np.cos(detection.altitude), detection.depth * np.sin(detection.altitude), detection.depth, detection.velocity, detection.azimuth, detection.altitude]) radar_msg = create_cloud(self.get_msg_header( diff --git a/carla_spawn_objects/config/objects.json b/carla_spawn_objects/config/objects.json index 8efcead7..0588c5c0 100644 --- a/carla_spawn_objects/config/objects.json +++ b/carla_spawn_objects/config/objects.json @@ -79,7 +79,7 @@ { "type": "sensor.other.radar", "id": "radar_front", - "spawn_point": {"x": 2.0, "y": 0.0, "z": 1.5, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "horizontal_fov": 30.0, "vertical_fov": 10.0, "points_per_second": 1500, From 6bb073435d60a94f562dd291154c8c6b8271efb1 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 12 Feb 2021 13:06:27 -0500 Subject: [PATCH 492/627] in passive mode the bridge deos not set the map --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 987edd2c..73b043a1 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -450,7 +450,7 @@ def main(args=None): carla_world = carla_client.get_world() - if "town" in parameters: + if "town" in parameters and not parameters['passive']: if parameters["town"].endswith(".xodr"): carla_bridge.loginfo( "Loading opendrive world from file '{}'".format(parameters["town"])) From 389acb4ef3db87206c7cbfe338b3bedb3c5c774e Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 12 Feb 2021 13:07:20 -0500 Subject: [PATCH 493/627] application runner logs from pexpect in utf-8 --- .../src/carla_ros_scenario_runner/application_runner.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py index 7de9f973..8eb9e0a9 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -102,7 +102,7 @@ def start_process(self, argument_list, log_fct, env=None, cwd=None): # pylint: raise KeyError("No arguments given!") executable = argument_list[0] log_fct("Executing: {}".format(" ".join(argument_list))) - process = pexpect.spawn(" ".join(argument_list), env=env, cwd=cwd) + process = pexpect.spawn(" ".join(argument_list), env=env, cwd=cwd, encoding='utf-8') #process.logfile_read = sys.stdout return process From c17f8dc8ef1b0231543c0c0f48655698a404011f Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 12 Feb 2021 13:11:41 -0500 Subject: [PATCH 494/627] option to use an executor to spin in call_service and wait_for_on_message --- .../ros_compatibility/ros_compatible_node.py | 23 +++++++++++++------ 1 file changed, 16 insertions(+), 7 deletions(-) diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 455bc0dd..a45abcdd 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -137,7 +137,7 @@ def new_rate(self, rate): def new_timer(self, timer_period_sec, callback): return rospy.Timer(rospy.Duration(timer_period_sec), callback) - def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None): + def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None, executor=None): try: return rospy.wait_for_message(topic, topic_type, timeout) except rospy.ROSException as e: @@ -160,7 +160,7 @@ def create_service_client(self, service_name, service, timeout_sec=None, callbac raise ROSException(e) return client - def call_service(self, client, req, timeout_ros2=None): + def call_service(self, client, req, timeout_ros2=None, executor=None): try: return client(req) except rospy.ServiceException as e: @@ -308,7 +308,7 @@ def new_rate(self, rate): def new_timer(self, timer_period_sec, callback): return self.create_timer(timer_period_sec, callback) - def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None): + def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None, executor=None): s = None wfm = WaitForMessageHelper() try: @@ -317,13 +317,19 @@ def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None timeout_t = time.time() + timeout while ros_ok() and wfm.msg is None: time.sleep(0.01) - rclpy.spin_once(self, timeout_sec=0) + if executor is None: + rclpy.spin_once(self, timeout_sec=0) + else: + executor.spin_once(timeout_sec=0) if time.time() >= timeout_t: raise ROSException else: while ros_ok() and wfm.msg is None: time.sleep(0.01) - rclpy.spin_once(self, timeout_sec=0) + if executor is None: + rclpy.spin_once(self, timeout_sec=0) + else: + executor.spin_once(timeout_sec=0) finally: if s is not None: self.destroy_subscription(s) @@ -340,12 +346,15 @@ def create_service_client(self, service_name, service, timeout_sec=None, callbac else: raise ROSException("Timeout of {}sec while waiting for service".format(timeout_sec)) - def call_service(self, client, req, timeout_ros2=None): + def call_service(self, client, req, timeout_ros2=None, executor=None): # uses the asynchronous call function but behaves like the synchronous call # this is done because the basic synchronous call function doesn't raise # an error when trying to call a service that is not alive anymore future = client.call_async(req) - rclpy.spin_until_future_complete(self, future, timeout_sec=timeout_ros2) + if executor is None: + rclpy.spin_until_future_complete(self, future, timeout_sec=timeout_ros2) + else: + executor.spin_until_future_complete(future, timeout_sec=timeout_ros2) if future.done(): return future.result() else: From 8a7355f9a72b0bc58c9697ab8c7d1e3fef73e564 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 12 Feb 2021 13:32:40 -0500 Subject: [PATCH 495/627] changed ackermann_control loop rate to 20hz --- .../src/carla_ackermann_control/carla_ackermann_control_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index ba2bd364..d572b408 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -105,7 +105,7 @@ def __init__(self): # ] # ) - self.control_loop_rate = 1.0 / 10 # 10Hz + self.control_loop_rate = 1.0 / 20 # 20Hz self.lastAckermannMsgReceived = datetime.datetime(datetime.MINYEAR, 1, 1) self.vehicle_status = CarlaEgoVehicleStatus() self.vehicle_info = CarlaEgoVehicleInfo() From c4ae993d80b8939a1a842d225ff1497917fd452f Mon Sep 17 00:00:00 2001 From: jmagnin Date: Mon, 15 Feb 2021 06:02:58 -0500 Subject: [PATCH 496/627] add ackermann control loop rate as ros parameter --- .../launch/carla_ackermann_control.launch | 4 +++- .../launch/carla_ackermann_control.launch.py | 7 ++++++- .../carla_ackermann_control_node.py | 2 +- 3 files changed, 10 insertions(+), 3 deletions(-) diff --git a/carla_ackermann_control/launch/carla_ackermann_control.launch b/carla_ackermann_control/launch/carla_ackermann_control.launch index 491ff7e6..de92a4b9 100644 --- a/carla_ackermann_control/launch/carla_ackermann_control.launch +++ b/carla_ackermann_control/launch/carla_ackermann_control.launch @@ -1,9 +1,11 @@ - + + + diff --git a/carla_ackermann_control/launch/carla_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ackermann_control.launch.py index 97b822d6..de1b0d0f 100644 --- a/carla_ackermann_control/launch/carla_ackermann_control.launch.py +++ b/carla_ackermann_control/launch/carla_ackermann_control.launch.py @@ -11,6 +11,10 @@ def generate_launch_description(): name='role_name', default_value='ego_vehicle' ), + launch.actions.DeclareLaunchArgument( + name='control_loop_rate', + default_value='0.05' + ), launch_ros.actions.Node( package='carla_ackermann_control', executable='carla_ackermann_control_node', @@ -19,7 +23,8 @@ def generate_launch_description(): parameters=[ Path(get_package_share_directory('carla_ackermann_control'), "settings.yaml"), { - 'role_name': launch.substitutions.LaunchConfiguration('role_name') + 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'control_loop_rate': launch.substitutions.LaunchConfiguration('control_loop_rate') } ] ) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index d572b408..9589dab3 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -105,7 +105,7 @@ def __init__(self): # ] # ) - self.control_loop_rate = 1.0 / 20 # 20Hz + self.control_loop_rate = self.get_param("control_loop_rate", 0.05) self.lastAckermannMsgReceived = datetime.datetime(datetime.MINYEAR, 1, 1) self.vehicle_status = CarlaEgoVehicleStatus() self.vehicle_info = CarlaEgoVehicleInfo() From aaf5366416c9eda157a0b1fcdd2412356f6b9f36 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 16 Feb 2021 11:57:50 -0500 Subject: [PATCH 497/627] application runner can take simple string as argumetn list --- .../carla_ros_scenario_runner/application_runner.py | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py index 8eb9e0a9..bc03b27f 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -100,10 +100,15 @@ def start_process(self, argument_list, log_fct, env=None, cwd=None): # pylint: """ if not argument_list: raise KeyError("No arguments given!") - executable = argument_list[0] - log_fct("Executing: {}".format(" ".join(argument_list))) - process = pexpect.spawn(" ".join(argument_list), env=env, cwd=cwd, encoding='utf-8') + if not isinstance(argument_list, str): + executable = " ".join(argument_list) + else: + executable = argument_list + + log_fct("Executing: " + executable) + process = pexpect.spawn(executable, env=env, cwd=cwd, encoding='utf-8') #process.logfile_read = sys.stdout + return process def run(self, process, shutdown_requested_event, ready_string, status_updated_fct, log_fct): # pylint: disable=no-self-use,too-many-arguments From 5719e56bd714474b899a18c646378013eaa953ab Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 16 Feb 2021 12:16:02 -0500 Subject: [PATCH 498/627] ego_vehicle does not subscribe to cmd topics when bridge in passive mode, useful for leaderboard --- .../src/carla_ros_bridge/ego_vehicle.py | 40 ++++++++++--------- 1 file changed, 21 insertions(+), 19 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index b4297859..28a82576 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -75,25 +75,27 @@ def __init__(self, uid, name, parent, node, carla_actor, vehicle_control_applied "/vehicle_info", qos_profile=QoSProfile(depth=10, durability=latch_on)) - self.control_subscriber = node.create_subscriber( - CarlaEgoVehicleControl, - self.get_topic_prefix() + "/vehicle_control_cmd", - lambda data: self.control_command_updated(data, manual_override=False)) - - self.manual_control_subscriber = node.create_subscriber( - CarlaEgoVehicleControl, - self.get_topic_prefix() + "/vehicle_control_cmd_manual", - lambda data: self.control_command_updated(data, manual_override=True)) - - self.control_override_subscriber = node.create_subscriber( - Bool, - self.get_topic_prefix() + "/vehicle_control_manual_override", - self.control_command_override, QoSProfile(depth=1, durability=True)) - - self.enable_autopilot_subscriber = node.create_subscriber( - Bool, - self.get_topic_prefix() + "/enable_autopilot", - self.enable_autopilot_updated) + # only subscribe to control topics if passive mode is not activated + if not node.parameters["passive"]: + self.control_subscriber = node.create_subscriber( + CarlaEgoVehicleControl, + self.get_topic_prefix() + "/vehicle_control_cmd", + lambda data: self.control_command_updated(data, manual_override=False)) + + self.manual_control_subscriber = node.create_subscriber( + CarlaEgoVehicleControl, + self.get_topic_prefix() + "/vehicle_control_cmd_manual", + lambda data: self.control_command_updated(data, manual_override=True)) + + self.control_override_subscriber = node.create_subscriber( + Bool, + self.get_topic_prefix() + "/vehicle_control_manual_override", + self.control_command_override, QoSProfile(depth=1, durability=True)) + + self.enable_autopilot_subscriber = node.create_subscriber( + Bool, + self.get_topic_prefix() + "/enable_autopilot", + self.enable_autopilot_updated) def get_marker_color(self): """ From 0ee086ce467d92349ad63beb9c00e9257d9d0543 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 22 Jan 2021 08:06:37 -0500 Subject: [PATCH 499/627] new carla_ad_agent structure and tuned longitudinal controller --- carla_ad_agent/CMakeLists.txt | 4 +- carla_ad_agent/launch/carla_ad_agent.launch | 5 + .../launch/carla_ad_agent.launch.py | 16 +- carla_ad_agent/setup.py | 4 +- carla_ad_agent/src/carla_ad_agent/agent.py | 1 + .../src/carla_ad_agent/basic_agent.py | 22 +- .../src/carla_ad_agent/carla_ad_agent.py | 95 ++------- .../src/carla_ad_agent/local_planner.py | 201 ++++++++++++------ .../carla_ad_agent/vehicle_pid_controller.py | 58 +++-- 9 files changed, 218 insertions(+), 188 deletions(-) mode change 100644 => 100755 carla_ad_agent/src/carla_ad_agent/local_planner.py diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index 690fd0e9..86c611c8 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -18,9 +18,9 @@ if(${ROS_VERSION} EQUAL 1) include_directories(${catkin_INCLUDE_DIRS}) - install(PROGRAMS src/carla_ad_agent/carla_ad_agent.py + install(PROGRAMS src/carla_ad_agent/carla_ad_agent.py src/carla_ad_agent/local_planner.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - + message(${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch b/carla_ad_agent/launch/carla_ad_agent.launch index 209de6b8..34ca6906 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch +++ b/carla_ad_agent/launch/carla_ad_agent.launch @@ -9,5 +9,10 @@ + + + + + diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 2446126f..8a28ec47 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -16,7 +16,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='target_speed', - default_value='20' + default_value='30' ), launch.actions.DeclareLaunchArgument( name='avoid_risk', @@ -38,6 +38,20 @@ def generate_launch_description(): 'avoid_risk': launch.substitutions.LaunchConfiguration('avoid_risk') } ] + ), + launch_ros.actions.Node( + package='carla_ad_agent', + executable='local_planner', + name=['local_planner_', launch.substitutions.LaunchConfiguration('role_name')], + output='screen', + parameters=[ + { + 'use_sim_time': True + }, + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + } + ] ) ]) return ld diff --git a/carla_ad_agent/setup.py b/carla_ad_agent/setup.py index 85f414fc..e64d76dd 100644 --- a/carla_ad_agent/setup.py +++ b/carla_ad_agent/setup.py @@ -33,7 +33,9 @@ description='CARLA ROS2 AD agent', license='MIT', entry_points={ - 'console_scripts': ['carla_ad_agent = carla_ad_agent.carla_ad_agent:main'], + 'console_scripts': ['carla_ad_agent = carla_ad_agent.carla_ad_agent:main', + 'local_planner = carla_ad_agent.local_planner:main', + 'testing_waypoints = carla_ad_agent.testing_waypoints:main'], }, package_dir={'': 'src'}, ) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 79d2f2ec..e5c11bcf 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -28,6 +28,7 @@ from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import elif ROS_VERSION == 2: from carla_ad_agent.misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import + from rclpy.callback_groups import ReentrantCallbackGroup class AgentState(Enum): diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index eb4a10f8..8bd538c0 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -50,13 +50,7 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): self._current_pose = Pose() self._proximity_threshold = 10.0 # meters self._state = AgentState.NAVIGATING - args_lateral_dict = { - 'K_P': 0.9, - 'K_D': 0.0, - 'K_I': 0.1} - self._local_planner = LocalPlanner(node=self.node, opt_dict={ - 'lateral_control_dict': args_lateral_dict}) - + if ROS_VERSION == 1: cb_group = None elif ROS_VERSION == 2: @@ -68,8 +62,7 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): # the agent shouldn't start if it has no info about other actors and objects self.node.wait_for_one_message("/carla/actor_list", CarlaActorList, timeout=15.0) - self.node.wait_for_one_message( - "/carla/{}/objects".format(role_name), ObjectArray, timeout=15.0) + self.node.wait_for_one_message("/carla/{}/objects".format(role_name), ObjectArray, timeout=15.0) self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", self.actors_updated, callback_group=cb_group) @@ -131,7 +124,7 @@ def objects_updated(self, objects): """ self._objects = objects.objects - def run_step(self, target_speed): + def run_step(self): """ Execute one step of navigation. :return: carla.VehicleControl @@ -156,12 +149,7 @@ def run_step(self, target_speed): self._state = AgentState.BLOCKED_RED_LIGHT hazard_detected = True - if hazard_detected: - control = self.emergency_stop() - else: + if hazard_detected is False: self._state = AgentState.NAVIGATING - # standard local planner behavior - control, finished = self._local_planner.run_step( - target_speed, self._current_speed, self._current_pose) - return control, finished + return hazard_detected diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 3fb8838e..51cb0263 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -49,9 +49,8 @@ def __init__(self): role_name = self.get_param("role_name", "ego_vehicle") avoid_risk = self.get_param("avoid_risk", True) - self._target_speed = self.get_param("target_speed", 20) - self._route_assigned = False - self._global_plan = None + self._target_speed = Float64() + self._target_speed.data = float(self.get_param("target_speed", 20)) self._agent = None # wait for ego vehicle @@ -62,91 +61,37 @@ def __init__(self): qos_profile=QoSProfile(depth=1, durability=latch_on)) self.loginfo("Vehicle info received.") - self._agent = BasicAgent(role_name, vehicle_info.id, # pylint: disable=no-member - self, avoid_risk) - - self._route_subscriber = self.create_subscriber( - Path, "/carla/{}/waypoints".format(role_name), self.path_updated, - QoSProfile(depth=1, durability=True)) + self._agent = BasicAgent(role_name, vehicle_info.id, self, avoid_risk) self._target_speed_subscriber = self.create_subscriber( Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) - - self.vehicle_control_publisher = self.new_publisher( - CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), - QoSProfile(depth=1, durability=False)) + + self.speed_to_pid = self.new_publisher( Float64, "/carla/{}/target_speed_to_pid".format(role_name), + QoSProfile(depth=1, durability=True)) def target_speed_updated(self, target_speed): """ callback on new target speed """ self.loginfo("New target speed received: {}".format(target_speed.data)) - self._target_speed = target_speed.data - - def path_updated(self, path): - """ - callback on new route - """ - self.loginfo("New plan with {} waypoints received.".format(len(path.poses))) - if self._agent: - self.vehicle_control_publisher.publish(self._agent.emergency_stop()) - self._global_plan = path - self._route_assigned = False + self._target_speed = target_speed def run_step(self): """ Execute one step of navigation. """ - control = CarlaEgoVehicleControl() - control.steer = 0.0 - control.throttle = 0.0 - control.brake = 0.0 - control.hand_brake = False - if not self._agent: self.loginfo("Waiting for ego vehicle...") - return control - - if not self._route_assigned and self._global_plan: - self.loginfo("Assigning plan...") - self._agent._local_planner.set_global_plan( # pylint: disable=protected-access - self._global_plan.poses) - self._route_assigned = True else: - control, finished = self._agent.run_step(self._target_speed) - if finished: - self._global_plan = None - self._route_assigned = False - - return control - - def run(self): - """ - - Control loop - - :return: - """ - loop_frequency = 10 - - if ROS_VERSION == 1: - r = rospy.Rate(loop_frequency) - - while ros_ok(): - if ROS_VERSION == 2: - rclpy.spin_once(self) - if self._global_plan: - control = self.run_step() - if control: - control.steer = -control.steer - self.vehicle_control_publisher.publish(control) + hazard_detected = self._agent.run_step() + if hazard_detected: + stopping_speed = Float64() + stopping_speed.data = 0.0 + self.speed_to_pid.publish(stopping_speed) else: - if ROS_VERSION == 1: - r.sleep() - elif ROS_VERSION == 2: - # TODO: use rclpy.Rate, not working yet - time.sleep(1 / loop_frequency) + self.speed_to_pid.publish(self._target_speed) + return def main(args=None): @@ -160,15 +105,21 @@ def main(args=None): controller = None try: controller = CarlaAdAgent() - controller.run() + while True: + time.sleep(0.05) + if ROS_VERSION == 2: + rclpy.spin_once(controller) + controller.run_step() except (ROSInterruptException, ROSException) as e: if ros_ok(): logwarn("ROS Error during exection: {}".format(e)) except KeyboardInterrupt: loginfo("User requested shut down.") finally: - if controller is not None and controller._agent: - controller.vehicle_control_publisher.publish(controller._agent.emergency_stop()) + if controller is not None: + stopping_speed = Float64() + stopping_speed.data = 0.0 + controller.speed_to_pid.publish(stopping_speed) ros_shutdown() diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py old mode 100644 new mode 100755 index 1599382a..f098d5fb --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -11,9 +11,16 @@ """ from collections import deque -from geometry_msgs.msg import PointStamped # pylint: disable=import-error +from geometry_msgs.msg import PointStamped, Pose # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error -from ros_compatibility import QoSProfile +from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION +from nav_msgs.msg import Path +from nav_msgs.msg import Odometry +from std_msgs.msg import Float64 +from threading import Thread +import time +import math +from visualization_msgs.msg import Marker import os ROS_VERSION = int(os.environ['ROS_VERSION']) @@ -24,9 +31,10 @@ elif ROS_VERSION == 2: from carla_ad_agent.vehicle_pid_controller import VehiclePIDController from carla_ad_agent.misc import distance_vehicle + import rclpy -class LocalPlanner(object): +class LocalPlanner(CompatibleNode): """ LocalPlanner implements the basic behavior of following a trajectory of waypoints that is generated on-the-fly. The low-level motion of the vehicle is computed by using two PID @@ -40,77 +48,83 @@ class LocalPlanner(object): # total distance) MIN_DISTANCE_PERCENTAGE = 0.9 - def __init__(self, node, opt_dict=None): - """ - :param vehicle: actor to apply to local planner logic onto - :param opt_dict: dictionary of arguments with the following semantics: - - target_speed -- desired cruise speed in Km/h + def __init__(self): + super(LocalPlanner, self).__init__('local_planner') - sampling_radius -- search radius for next waypoints in seconds: e.g. 0.5 seconds ahead + # ros parameters + role_name = self.get_param("role_name", "ego_vehicle") + args_lateral_dict = {} + args_lateral_dict['K_P'] = self.get_param("Kp_lateral", 0.9) + args_lateral_dict['K_I'] = self.get_param("Ki_lateral", 0.0) + args_lateral_dict['K_D'] = self.get_param("Kd_lateral", 0.0) + args_longitudinal_dict = {} + args_longitudinal_dict['K_P'] = self.get_param("Kp_longitudinal", 0.206) + args_longitudinal_dict['K_I'] = self.get_param("Ki_longitudinal", 0.0206) + args_longitudinal_dict['K_D'] = self.get_param("Kd_longitudinal", 0.9) - lateral_control_dict -- dictionary of arguments to setup the lateral PID controller - {'K_P':, 'K_D':, 'K_I'} - - longitudinal_control_dict -- dictionary of arguments to setup the longitudinal - PID controller - {'K_P':, 'K_D':, 'K_I'} - """ self.target_route_point = None self._vehicle_controller = None self._waypoints_queue = deque(maxlen=20000) self._buffer_size = 5 self._waypoint_buffer = deque(maxlen=self._buffer_size) - self.node = node + self.path_received = False + self._current_speed = None + self._current_pose = None + self._target_speed = 30.0 - self._target_point_publisher = self.node.new_publisher( - PointStamped, "/next_target", QoSProfile(depth=1, durability=False)) + # subscribers + self._odometry_subscriber = self.create_subscriber(Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) + self._path_subscriber = self.create_subscriber(Path, "/carla/{}/waypoints".format(role_name), self.path_updated, QoSProfile(depth=1, durability=True)) + self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) + + # publishers + self._target_point_publisher = self.new_publisher(Marker, "/next_target", QoSProfile(depth=10, durability=False)) + self._control_cmd_publisher = self.new_publisher(CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), QoSProfile(depth=1, durability=False)) # initializing controller - self._init_controller(opt_dict) + self._vehicle_controller = VehiclePIDController(self, args_lateral=args_lateral_dict, args_longitudinal=args_longitudinal_dict) - def _init_controller(self, opt_dict): - """ - Controller initialization. + # wait for required messages + self.loginfo('Local planner waiting for a path and target speed...') + while self._current_pose is None or self._target_speed is None or self.path_received is False: + time.sleep(0.05) + if ROS_VERSION == 2: + rclpy.spin_once(self, timeout_sec=0) + + self.f = open('data.txt', 'w') - :param opt_dict: dictionary of arguments. - :return: + def odometry_updated(self, new_pose): """ - # default params - args_lateral_dict = { - 'K_P': 1.95, - 'K_D': 0.01, - 'K_I': 1.4} - args_longitudinal_dict = { - 'K_P': 0.2, - 'K_D': 0.05, - 'K_I': 0.1} - - # parameters overload - if opt_dict: - if 'lateral_control_dict' in opt_dict: - args_lateral_dict = opt_dict['lateral_control_dict'] - if 'longitudinal_control_dict' in opt_dict: - args_longitudinal_dict = opt_dict['longitudinal_control_dict'] - - self._vehicle_controller = VehiclePIDController(self.node, args_lateral=args_lateral_dict, - args_longitudinal=args_longitudinal_dict) - - def set_global_plan(self, current_plan): + callback on new odometry + """ + self._current_speed = math.sqrt(new_pose.twist.twist.linear.x ** 2 + + new_pose.twist.twist.linear.y ** 2 + + new_pose.twist.twist.linear.z ** 2) * 3.6 + self._current_pose = new_pose.pose.pose + + def target_speed_updated(self, new_target_speed): + self._target_speed = new_target_speed.data + + def path_updated(self, new_path): """ set a global plan to follow """ + self.loginfo('New path to follow received.') + self.path_received = True self.target_route_point = None self._waypoint_buffer.clear() self._waypoints_queue.clear() - for elem in current_plan: + for elem in new_path.poses: self._waypoints_queue.append(elem.pose) - def run_step(self, target_speed, current_speed, current_pose): + def run_step(self): """ Execute one step of local planning which involves running the longitudinal and lateral PID controllers to follow the waypoints trajectory. """ + if self.path_received is False: + return + if not self._waypoint_buffer and not self._waypoints_queue: control = CarlaEgoVehicleControl() control.steer = 0.0 @@ -118,9 +132,21 @@ def run_step(self, target_speed, current_speed, current_pose): control.brake = 1.0 control.hand_brake = False control.manual_gear_shift = False - - self.node.loginfo("Route finished.") - return control, True + self._control_cmd_publisher.publish(control) + self.loginfo("Route finished. Waiting for a new one.") + self.path_received = False + return + + # When target speed is 0, brake + if self._target_speed == 0.0: + control = CarlaEgoVehicleControl() + control.steer = 0.0 + control.throttle = 0.0 + control.brake = 1.0 + control.hand_brake = False + control.manual_gear_shift = False + self._control_cmd_publisher.publish(control) + return # Buffering the waypoints if not self._waypoint_buffer: @@ -133,29 +159,82 @@ def run_step(self, target_speed, current_speed, current_pose): # target waypoint self.target_route_point = self._waypoint_buffer[0] - - target_point = PointStamped() + target_point = Marker() + target_point.type = 0 target_point.header.frame_id = "map" - target_point.point.x = self.target_route_point.position.x - target_point.point.y = self.target_route_point.position.y - target_point.point.z = self.target_route_point.position.z + target_point.pose = self.target_route_point + target_point.scale.x = 1.0 + target_point.scale.y = 0.2 + target_point.scale.z = 0.2 + target_point.color.r = 255.0 + target_point.color.a = 1.0 self._target_point_publisher.publish(target_point) + # move using PID controllers control = self._vehicle_controller.run_step( - target_speed, current_speed, current_pose, self.target_route_point) + self._target_speed, self._current_speed, self._current_pose, self.target_route_point) + + self.f.write('{}, {}, {}, {}, {}, \n'.format(self.get_time(), self._target_speed, self._current_speed, control.throttle, self._vehicle_controller._lat_controller.error)) # purge the queue of obsolete waypoints max_index = -1 - sampling_radius = target_speed * 1 / 3.6 # 1 seconds horizon + sampling_radius = self._target_speed * 1 / 3.6 # search radius for next waypoints in seconds min_distance = sampling_radius * self.MIN_DISTANCE_PERCENTAGE for i, route_point in enumerate(self._waypoint_buffer): if distance_vehicle( - route_point, current_pose.position) < min_distance: + route_point, self._current_pose.position) < min_distance: max_index = i if max_index >= 0: for i in range(max_index + 1): self._waypoint_buffer.popleft() - return control, False + self._control_cmd_publisher.publish(control) + return + + def emergency_stop(self): + control = CarlaEgoVehicleControl() + control.steer = 0.0 + control.throttle = 0.0 + control.brake = 1.0 + control.hand_brake = False + control.manual_gear_shift = False + self._control_cmd_publisher.publish(control) + + +def main(args=None): + """ + + main function + + :return: + """ + ros_init(args) + local_planner = None + update_timer = None + try: + local_planner = LocalPlanner() + if ROS_VERSION == 1: + local_planner.on_shutdown(local_planner.emergency_stop) + local_planner.loginfo('Local planner is starting.') + update_timer = local_planner.new_timer(0.05, lambda timer_event=None: local_planner.run_step()) + local_planner.spin() + except KeyboardInterrupt: + pass + finally: + loginfo('Local planner shutting down.') + if update_timer: + if ROS_VERSION == 1: + update_timer.shutdown() + else: + update_timer.destroy() + local_planner.f.close() + if ROS_VERSION == 2: + local_planner.emergency_stop() + local_planner.shutdown() + + + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index f1e43b1b..956d7a1d 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -44,7 +44,6 @@ def __init__(self, node, args_lateral=None, args_longitudinal=None): self.node = node self._lon_controller = PIDLongitudinalController(**args_longitudinal) self._lat_controller = PIDLateralController(**args_lateral) - self._last_control_time = self.node.get_time() def run_step(self, target_speed, current_speed, current_pose, waypoint): """ @@ -53,17 +52,12 @@ def run_step(self, target_speed, current_speed, current_pose, waypoint): :param target_speed: desired vehicle speed :param waypoint: target location encoded as a waypoint - :return: distance (in meters) to the waypoint + :return: control signal (throttle and steering) """ - current_time = self.node.get_time() - dt = current_time-self._last_control_time - if dt == 0.0: - dt = 0.000001 control = CarlaEgoVehicleControl() - throttle = self._lon_controller.run_step(target_speed, current_speed, dt) - steering = self._lat_controller.run_step(current_pose, waypoint, dt) - self._last_control_time = current_time - control.steer = steering + throttle = self._lon_controller.run_step(target_speed, current_speed) + steering = self._lat_controller.run_step(current_pose, waypoint) + control.steer = -steering control.throttle = throttle control.brake = 0.0 control.hand_brake = False @@ -87,9 +81,11 @@ def __init__(self, K_P=1.0, K_D=0.0, K_I=0.0): self._K_P = K_P self._K_D = K_D self._K_I = K_I - self._e_buffer = deque(maxlen=30) + self.error = 0.0 + self.error_integral = 0.0 + self.error_derivative = 0.0 - def run_step(self, target_speed, current_speed, dt): + def run_step(self, target_speed, current_speed): """ Estimate the throttle of the vehicle based on the PID equations @@ -97,17 +93,12 @@ def run_step(self, target_speed, current_speed, dt): :param current_speed: current speed of the vehicle in Km/h :return: throttle control in the range [0, 1] """ - _e = (target_speed - current_speed) - self._e_buffer.append(_e) - - if len(self._e_buffer) >= 2: - _de = (self._e_buffer[-1] - self._e_buffer[-2]) / dt - _ie = sum(self._e_buffer) * dt - else: - _de = 0.0 - _ie = 0.0 - - return np.clip((self._K_P * _e) + (self._K_D * _de / dt) + (self._K_I * _ie * dt), 0.0, 1.0) + previous_error = self.error + self.error = target_speed - current_speed + self.error_integral = np.clip(self.error_integral + self.error, -40.0, 40.0) # restrict integral term to avoid integral windup + self.error_derivative = self.error - previous_error + output = self._K_P * self.error + self._K_I * self.error_integral + self._K_D * self.error_derivative + return np.clip(output, 0.0, 1.0) class PIDLateralController(object): # pylint: disable=too-few-public-methods @@ -126,8 +117,11 @@ def __init__(self, K_P=1.0, K_D=0.0, K_I=0.0): self._K_D = K_D self._K_I = K_I self._e_buffer = deque(maxlen=10) + self.error = 0.0 + self.error_integral = 0.0 + self.error_derivative = 0.0 - def run_step(self, current_pose, waypoint, dt): + def run_step(self, current_pose, waypoint): """ Estimate the steering angle of the vehicle based on the PID equations @@ -158,13 +152,9 @@ def run_step(self, current_pose, waypoint, dt): if _cross[2] < 0: _dot *= -1.0 - self._e_buffer.append(_dot) - if len(self._e_buffer) >= 2: - _de = (self._e_buffer[-1] - self._e_buffer[-2]) / dt - _ie = sum(self._e_buffer) * dt - else: - _de = 0.0 - _ie = 0.0 - - return np.clip((self._K_P * _dot) + (self._K_D * _de / - dt) + (self._K_I * _ie * dt), -1.0, 1.0) + previous_error = self.error + self.error = _dot + self.error_integral = np.clip(self.error_integral + self.error, -40.0, 40.0) # restrict integral term to avoid integral windup + self.error_derivative = self.error - previous_error + output = self._K_P * self.error + self._K_I * self.error_integral + self._K_D * self.error_derivative + return np.clip(output, -1.0, 1.0) From 4a57ff90697a1c42d2cf0ee6dd702c43fe204e13 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 26 Jan 2021 11:56:50 -0500 Subject: [PATCH 500/627] to debug --- .../launch/carla_ad_agent.launch.py | 3 ++ carla_ad_agent/src/carla_ad_agent/agent.py | 25 ++++++----- .../src/carla_ad_agent/basic_agent.py | 26 +---------- .../src/carla_ad_agent/carla_ad_agent.py | 17 +++---- .../src/carla_ad_agent/local_planner.py | 45 ++++++++++--------- .../carla_ad_agent/vehicle_pid_controller.py | 2 +- 6 files changed, 48 insertions(+), 70 deletions(-) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 8a28ec47..22333a23 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -28,6 +28,9 @@ def generate_launch_description(): name=['carla_ad_agent_', launch.substitutions.LaunchConfiguration('role_name')], output='screen', parameters=[ + { + 'use_sim_time': True + }, { 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') }, diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index e5c11bcf..90cef1b4 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -12,8 +12,10 @@ from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error from carla_msgs.msg import CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus # pylint: disable=import-error +from nav_msgs.msg import Odometry from enum import Enum import math +import time from transforms3d.euler import quat2euler from ros_compatibility import ( ros_ok, @@ -28,7 +30,7 @@ from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import elif ROS_VERSION == 2: from carla_ad_agent.misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import - from rclpy.callback_groups import ReentrantCallbackGroup + from rclpy import spin_once class AgentState(Enum): @@ -57,6 +59,15 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): self._vehicle_id = vehicle_id self._last_traffic_light = None + self._odometry_subscriber = self.node.create_subscriber(Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) + # wait for first odometry update + self.node.logwarn('waiting for odo') + while self._vehicle_location is None: + time.sleep(0.05) + if ROS_VERSION == 2: + spin_once(node, timeout_sec=0) + self.node.logwarn('odo received') + if avoid_risk: self._get_waypoint_client = node.create_service_client( '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) @@ -65,9 +76,8 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): self._traffic_light_status_subscriber = node.create_subscriber(CarlaTrafficLightStatusList, "/carla/traffic_lights/status", self.traffic_lights_updated, qos_profile=QoSProfile(depth=10, durability=latch_on)) - - node.create_subscriber(CarlaWorldInfo, - "/carla/world_info", self.world_info_updated, qos_profile=QoSProfile(depth=1, durability=latch_on)) + world_info = node.wait_for_one_message("/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) + self._map_name = world_info.map_name def traffic_lights_updated(self, traffic_lights): """ @@ -76,13 +86,6 @@ def traffic_lights_updated(self, traffic_lights): """ self._traffic_lights = traffic_lights.traffic_lights - def world_info_updated(self, world_info): - """ - callback on new world info - Only used if risk should be avoided. - """ - self._map_name = world_info.map_name - def odometry_updated(self, odo): """ callback on new odometry diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index 8bd538c0..ee95e7a2 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -14,7 +14,6 @@ from carla_msgs.msg import CarlaActorList # pylint: disable=import-error from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error from geometry_msgs.msg import Pose # pylint: disable=import-error -from nav_msgs.msg import Odometry # pylint: disable=import-error import math from ros_compatibility import ( ros_ok, @@ -26,11 +25,9 @@ ROS_VERSION) if ROS_VERSION == 1: - from local_planner import LocalPlanner # pylint: disable=relative-import from agent import Agent, AgentState # pylint: disable=relative-import elif ROS_VERSION == 2: from rclpy.callback_groups import ReentrantCallbackGroup - from carla_ad_agent.local_planner import LocalPlanner # pylint: disable=relative-import from carla_ad_agent.agent import Agent, AgentState # pylint: disable=relative-import @@ -46,8 +43,6 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): super(BasicAgent, self).__init__(role_name, ego_vehicle_id, avoid_risk, node) self.node = node self._avoid_risk = avoid_risk - self._current_speed = 0.0 # Km/h - self._current_pose = Pose() self._proximity_threshold = 10.0 # meters self._state = AgentState.NAVIGATING @@ -59,24 +54,15 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): if self._avoid_risk: self._vehicle_id_list = [] self._lights_id_list = [] - - # the agent shouldn't start if it has no info about other actors and objects - self.node.wait_for_one_message("/carla/actor_list", CarlaActorList, timeout=15.0) - self.node.wait_for_one_message("/carla/{}/objects".format(role_name), ObjectArray, timeout=15.0) - + self._objects = [] self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", self.actors_updated, callback_group=cb_group) - self._objects = [] - self._objects_subscriber = self.node.create_subscriber(ObjectArray, "/carla/{}/objects".format(role_name), self.objects_updated) self._get_actor_waypoint_client = self.node.create_service_client( '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), GetActorWaypoint, callback_group=cb_group) - self._odometry_subscriber = self.node.create_subscriber(Odometry, - "/carla/{}/odometry".format(role_name), self.odometry_updated) - def get_actor_waypoint(self, actor_id): """ helper method to get waypoint for actor via ros service @@ -91,16 +77,6 @@ def get_actor_waypoint(self, actor_id): if ros_ok(): self.node.logwarn("Service call failed: {}".format(e)) - def odometry_updated(self, odo): - """ - callback on new odometry - """ - self._current_speed = math.sqrt(odo.twist.twist.linear.x ** 2 + - odo.twist.twist.linear.y ** 2 + - odo.twist.twist.linear.z ** 2) * 3.6 - self._current_pose = odo.pose.pose - super(BasicAgent, self).odometry_updated(odo) - def actors_updated(self, actors): """ callback on new actor list diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 51cb0263..502e5790 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -10,9 +10,8 @@ """ import sys import time -from nav_msgs.msg import Path # pylint: disable=import-error from std_msgs.msg import Float64 # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=import-error from ros_compatibility import ( CompatibleNode, ROSInterruptException, @@ -56,19 +55,14 @@ def __init__(self): # wait for ego vehicle vehicle_info = None self.loginfo("Wait for vehicle info ...") - vehicle_info = self.wait_for_one_message( - "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, - qos_profile=QoSProfile(depth=1, durability=latch_on)) + vehicle_info = self.wait_for_one_message("/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) self.loginfo("Vehicle info received.") self._agent = BasicAgent(role_name, vehicle_info.id, self, avoid_risk) - self._target_speed_subscriber = self.create_subscriber( - Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, - QoSProfile(depth=1, durability=True)) + self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) - self.speed_to_pid = self.new_publisher( Float64, "/carla/{}/target_speed_to_pid".format(role_name), - QoSProfile(depth=1, durability=True)) + self.speed_to_pid = self.new_publisher( Float64, "/carla/{}/target_speed_to_pid".format(role_name), QoSProfile(depth=1, durability=True)) def target_speed_updated(self, target_speed): """ @@ -86,6 +80,7 @@ def run_step(self): else: hazard_detected = self._agent.run_step() if hazard_detected: + # stop, publish speed 0.0km/h stopping_speed = Float64() stopping_speed.data = 0.0 self.speed_to_pid.publish(stopping_speed) @@ -106,7 +101,7 @@ def main(args=None): try: controller = CarlaAdAgent() while True: - time.sleep(0.05) + # time.sleep(0.01) if ROS_VERSION == 2: rclpy.spin_once(controller) controller.run_step() diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index f098d5fb..618c3192 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -13,7 +13,7 @@ from collections import deque from geometry_msgs.msg import PointStamped, Pose # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error -from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION +from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION, ros_ok from nav_msgs.msg import Path from nav_msgs.msg import Odometry from std_msgs.msg import Float64 @@ -53,6 +53,7 @@ def __init__(self): # ros parameters role_name = self.get_param("role_name", "ego_vehicle") + self.control_time_step = self.get_param("control_time_step", 0.05) args_lateral_dict = {} args_lateral_dict['K_P'] = self.get_param("Kp_lateral", 0.9) args_lateral_dict['K_I'] = self.get_param("Ki_lateral", 0.0) @@ -60,7 +61,7 @@ def __init__(self): args_longitudinal_dict = {} args_longitudinal_dict['K_P'] = self.get_param("Kp_longitudinal", 0.206) args_longitudinal_dict['K_I'] = self.get_param("Ki_longitudinal", 0.0206) - args_longitudinal_dict['K_D'] = self.get_param("Kd_longitudinal", 0.9) + args_longitudinal_dict['K_D'] = self.get_param("Kd_longitudinal", 0.515) self.target_route_point = None self._vehicle_controller = None @@ -75,7 +76,7 @@ def __init__(self): # subscribers self._odometry_subscriber = self.create_subscriber(Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) self._path_subscriber = self.create_subscriber(Path, "/carla/{}/waypoints".format(role_name), self.path_updated, QoSProfile(depth=1, durability=True)) - self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) + # self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) # publishers self._target_point_publisher = self.new_publisher(Marker, "/next_target", QoSProfile(depth=10, durability=False)) @@ -101,6 +102,7 @@ def odometry_updated(self, new_pose): new_pose.twist.twist.linear.y ** 2 + new_pose.twist.twist.linear.z ** 2) * 3.6 self._current_pose = new_pose.pose.pose + self.logwarn(f'odo update: {new_pose.header.stamp}, speed: {self._current_speed}') def target_speed_updated(self, new_target_speed): self._target_speed = new_target_speed.data @@ -126,26 +128,14 @@ def run_step(self): return if not self._waypoint_buffer and not self._waypoints_queue: - control = CarlaEgoVehicleControl() - control.steer = 0.0 - control.throttle = 0.0 - control.brake = 1.0 - control.hand_brake = False - control.manual_gear_shift = False - self._control_cmd_publisher.publish(control) + self.emergency_stop() self.loginfo("Route finished. Waiting for a new one.") self.path_received = False return # When target speed is 0, brake if self._target_speed == 0.0: - control = CarlaEgoVehicleControl() - control.steer = 0.0 - control.throttle = 0.0 - control.brake = 1.0 - control.hand_brake = False - control.manual_gear_shift = False - self._control_cmd_publisher.publish(control) + self.emergency_stop() return # Buffering the waypoints @@ -168,11 +158,23 @@ def run_step(self): target_point.scale.z = 0.2 target_point.color.r = 255.0 target_point.color.a = 1.0 + target_point.id =232 + self._target_point_publisher.publish(target_point) + # publish current pose as marker + target_point = Marker() + target_point.type = 0 + target_point.header.frame_id = "map" + target_point.pose = self._current_pose + target_point.scale.x = 1.0 + target_point.scale.y = 0.2 + target_point.scale.z = 0.2 + target_point.color.b = 255.0 + target_point.color.a = 1.0 + target_point.id =231 self._target_point_publisher.publish(target_point) # move using PID controllers - control = self._vehicle_controller.run_step( - self._target_speed, self._current_speed, self._current_pose, self.target_route_point) + control = self._vehicle_controller.run_step(self._target_speed, self._current_speed, self._current_pose, self.target_route_point) self.f.write('{}, {}, {}, {}, {}, \n'.format(self.get_time(), self._target_speed, self._current_speed, control.throttle, self._vehicle_controller._lat_controller.error)) @@ -183,8 +185,7 @@ def run_step(self): min_distance = sampling_radius * self.MIN_DISTANCE_PERCENTAGE for i, route_point in enumerate(self._waypoint_buffer): - if distance_vehicle( - route_point, self._current_pose.position) < min_distance: + if distance_vehicle(route_point, self._current_pose.position) < min_distance: max_index = i if max_index >= 0: for i in range(max_index + 1): @@ -218,7 +219,7 @@ def main(args=None): if ROS_VERSION == 1: local_planner.on_shutdown(local_planner.emergency_stop) local_planner.loginfo('Local planner is starting.') - update_timer = local_planner.new_timer(0.05, lambda timer_event=None: local_planner.run_step()) + update_timer = local_planner.new_timer(local_planner.control_time_step, lambda timer_event=None: local_planner.run_step()) local_planner.spin() except KeyboardInterrupt: pass diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index 956d7a1d..d797f043 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -154,7 +154,7 @@ def run_step(self, current_pose, waypoint): previous_error = self.error self.error = _dot - self.error_integral = np.clip(self.error_integral + self.error, -40.0, 40.0) # restrict integral term to avoid integral windup + self.error_integral = np.clip(self.error_integral + self.error, -400.0, 400.0) # restrict integral term to avoid integral windup self.error_derivative = self.error - previous_error output = self._K_P * self.error + self._K_I * self.error_integral + self._K_D * self.error_derivative return np.clip(output, -1.0, 1.0) From e162f3d2f88ecade5a56b102422a352996ceab42 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 29 Jan 2021 11:40:13 +0100 Subject: [PATCH 501/627] clean up carla_ad_agent --- .../launch/carla_ad_agent.launch.py | 37 +++++++++++++++---- .../src/carla_ad_agent/carla_ad_agent.py | 30 +++++++-------- .../src/carla_ad_agent/local_planner.py | 24 +++--------- carla_ad_demo/launch/carla_ad_demo.launch.py | 2 +- 4 files changed, 50 insertions(+), 43 deletions(-) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 22333a23..86f4b48a 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -10,27 +10,48 @@ def generate_launch_description(): name='role_name', default_value='ego_vehicle' ), - launch.actions.SetLaunchConfiguration( - name='test', - value='jb' - ), launch.actions.DeclareLaunchArgument( name='target_speed', - default_value='30' + default_value='30.0' ), launch.actions.DeclareLaunchArgument( name='avoid_risk', default_value='True' ), + launch.actions.DeclareLaunchArgument( + name='Kp_lateral', + default_value='0.9' + ), + launch.actions.DeclareLaunchArgument( + name='Ki_lateral', + default_value='0.0' + ), + launch.actions.DeclareLaunchArgument( + name='Kd_lateral', + default_value='0.0' + ), + launch.actions.DeclareLaunchArgument( + name='Kp_longitudinal', + default_value='0.206' + ), + launch.actions.DeclareLaunchArgument( + name='Ki_longitudinal', + default_value='0.0206' + ), + launch.actions.DeclareLaunchArgument( + name='Kd_longitudinal', + default_value='0.515' + ), + launch.actions.DeclareLaunchArgument( + name='control_time_step', + default_value='0.05' + ), launch_ros.actions.Node( package='carla_ad_agent', executable='carla_ad_agent', name=['carla_ad_agent_', launch.substitutions.LaunchConfiguration('role_name')], output='screen', parameters=[ - { - 'use_sim_time': True - }, { 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') }, diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index 502e5790..aa6e722d 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -48,9 +48,8 @@ def __init__(self): role_name = self.get_param("role_name", "ego_vehicle") avoid_risk = self.get_param("avoid_risk", True) - self._target_speed = Float64() - self._target_speed.data = float(self.get_param("target_speed", 20)) - self._agent = None + self.target_speed = self.get_param("target_speed", 30.0) + self.agent = None # wait for ego vehicle vehicle_info = None @@ -58,34 +57,35 @@ def __init__(self): vehicle_info = self.wait_for_one_message("/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) self.loginfo("Vehicle info received.") - self._agent = BasicAgent(role_name, vehicle_info.id, self, avoid_risk) + self.agent = BasicAgent(role_name, vehicle_info.id, self, avoid_risk) - self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) + self.target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) - self.speed_to_pid = self.new_publisher( Float64, "/carla/{}/target_speed_to_pid".format(role_name), QoSProfile(depth=1, durability=True)) + self.speed_command_publisher = self.new_publisher( Float64, "/carla/{}/speed_command".format(role_name), QoSProfile(depth=1, durability=True)) def target_speed_updated(self, target_speed): """ callback on new target speed """ self.loginfo("New target speed received: {}".format(target_speed.data)) - self._target_speed = target_speed + self.target_speed = target_speed.data def run_step(self): """ Execute one step of navigation. """ - if not self._agent: + if not self.agent: self.loginfo("Waiting for ego vehicle...") else: - hazard_detected = self._agent.run_step() + hazard_detected = self.agent.run_step() + speed_command = Float64() if hazard_detected: # stop, publish speed 0.0km/h - stopping_speed = Float64() - stopping_speed.data = 0.0 - self.speed_to_pid.publish(stopping_speed) + speed_command.data = 0.0 + self.speed_command_publisher.publish(speed_command) else: - self.speed_to_pid.publish(self._target_speed) + speed_command.data = self.target_speed + self.speed_command_publisher.publish(speed_command) return @@ -101,7 +101,7 @@ def main(args=None): try: controller = CarlaAdAgent() while True: - # time.sleep(0.01) + time.sleep(0.01) if ROS_VERSION == 2: rclpy.spin_once(controller) controller.run_step() @@ -114,7 +114,7 @@ def main(args=None): if controller is not None: stopping_speed = Float64() stopping_speed.data = 0.0 - controller.speed_to_pid.publish(stopping_speed) + controller.speed_command_publisher.publish(stopping_speed) ros_shutdown() diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 618c3192..8f885dbc 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -71,12 +71,12 @@ def __init__(self): self.path_received = False self._current_speed = None self._current_pose = None - self._target_speed = 30.0 + self._target_speed = 0.0 # subscribers self._odometry_subscriber = self.create_subscriber(Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) self._path_subscriber = self.create_subscriber(Path, "/carla/{}/waypoints".format(role_name), self.path_updated, QoSProfile(depth=1, durability=True)) - # self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) + self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/speed_command".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) # publishers self._target_point_publisher = self.new_publisher(Marker, "/next_target", QoSProfile(depth=10, durability=False)) @@ -92,7 +92,7 @@ def __init__(self): if ROS_VERSION == 2: rclpy.spin_once(self, timeout_sec=0) - self.f = open('data.txt', 'w') + # self.f = open('data.txt', 'w') def odometry_updated(self, new_pose): """ @@ -102,7 +102,6 @@ def odometry_updated(self, new_pose): new_pose.twist.twist.linear.y ** 2 + new_pose.twist.twist.linear.z ** 2) * 3.6 self._current_pose = new_pose.pose.pose - self.logwarn(f'odo update: {new_pose.header.stamp}, speed: {self._current_speed}') def target_speed_updated(self, new_target_speed): self._target_speed = new_target_speed.data @@ -158,25 +157,12 @@ def run_step(self): target_point.scale.z = 0.2 target_point.color.r = 255.0 target_point.color.a = 1.0 - target_point.id =232 - self._target_point_publisher.publish(target_point) - # publish current pose as marker - target_point = Marker() - target_point.type = 0 - target_point.header.frame_id = "map" - target_point.pose = self._current_pose - target_point.scale.x = 1.0 - target_point.scale.y = 0.2 - target_point.scale.z = 0.2 - target_point.color.b = 255.0 - target_point.color.a = 1.0 - target_point.id =231 self._target_point_publisher.publish(target_point) # move using PID controllers control = self._vehicle_controller.run_step(self._target_speed, self._current_speed, self._current_pose, self.target_route_point) - self.f.write('{}, {}, {}, {}, {}, \n'.format(self.get_time(), self._target_speed, self._current_speed, control.throttle, self._vehicle_controller._lat_controller.error)) + # self.f.write('{}, {}, {}, {}, {}, \n'.format(self.get_time(), self._target_speed, self._current_speed, control.throttle, self._vehicle_controller._lat_controller.error)) # purge the queue of obsolete waypoints max_index = -1 @@ -230,7 +216,7 @@ def main(args=None): update_timer.shutdown() else: update_timer.destroy() - local_planner.f.close() + # local_planner.f.close() if ROS_VERSION == 2: local_planner.emergency_stop() local_planner.shutdown() diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index fbb46633..cc03505c 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -65,7 +65,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='target_speed', - default_value='30' + default_value='30.0' ), launch.actions.DeclareLaunchArgument( name='avoid_risk', From be6a8f0089cbf90bf83f208847f0b3e29d176b43 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 23 Feb 2021 14:37:02 -0500 Subject: [PATCH 502/627] fix us-style traffic light case in carla_ad_agent --- carla_ad_agent/src/carla_ad_agent/agent.py | 16 +++++++++++----- .../src/carla_ad_agent/local_planner.py | 2 +- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 90cef1b4..5aa20dfa 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -13,6 +13,8 @@ from carla_msgs.msg import CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus # pylint: disable=import-error from nav_msgs.msg import Odometry +from geometry_msgs.msg import Point +from visualization_msgs.msg import Marker from enum import Enum import math import time @@ -52,21 +54,21 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): """ self.node = node self._proximity_threshold = 10.0 # meters - self._local_planner = None self._map_name = None self._vehicle_location = None self._vehicle_yaw = None self._vehicle_id = vehicle_id self._last_traffic_light = None + self._target_route_point = None self._odometry_subscriber = self.node.create_subscriber(Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) # wait for first odometry update - self.node.logwarn('waiting for odo') + self.node.logwarn('Agent waiting for odometry message') while self._vehicle_location is None: time.sleep(0.05) if ROS_VERSION == 2: spin_once(node, timeout_sec=0) - self.node.logwarn('odo received') + self.node.logwarn('Odometry message received') if avoid_risk: self._get_waypoint_client = node.create_service_client( @@ -76,6 +78,7 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): self._traffic_light_status_subscriber = node.create_subscriber(CarlaTrafficLightStatusList, "/carla/traffic_lights/status", self.traffic_lights_updated, qos_profile=QoSProfile(depth=10, durability=latch_on)) + self._target_point_subscriber = node.create_subscriber(Marker,"/carla/{}/next_target".format(role_name), self.target_point_updated) world_info = node.wait_for_one_message("/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) self._map_name = world_info.map_name @@ -86,6 +89,9 @@ def traffic_lights_updated(self, traffic_lights): """ self._traffic_lights = traffic_lights.traffic_lights + def target_point_updated(self, new_target_point): + self._target_route_point = new_target_point.pose.position + def odometry_updated(self, odo): """ callback on new odometry @@ -198,9 +204,9 @@ def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branc # It is too late. Do not block the intersection! Keep going! return (False, None) - if self._local_planner.target_route_point is not None: + if self._target_route_point is not None: request = get_service_request(GetWaypoint) - request.location = self._local_planner.target_route_point.position + request.location = self._target_route_point target_waypoint = self.get_waypoint(request) if not target_waypoint: if ros_ok(): diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 8f885dbc..13364854 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -79,7 +79,7 @@ def __init__(self): self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/speed_command".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) # publishers - self._target_point_publisher = self.new_publisher(Marker, "/next_target", QoSProfile(depth=10, durability=False)) + self._target_point_publisher = self.new_publisher(Marker, "/carla/{}/next_target".format(role_name), QoSProfile(depth=10, durability=False)) self._control_cmd_publisher = self.new_publisher(CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), QoSProfile(depth=1, durability=False)) # initializing controller From 273a3d8d64f2eb82b886fa8f761f5bb02ad5d126 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 23 Feb 2021 14:40:31 -0500 Subject: [PATCH 503/627] fix format --- .../launch/carla_ad_agent.launch.py | 1 + carla_ad_agent/src/carla_ad_agent/agent.py | 9 ++++-- .../src/carla_ad_agent/basic_agent.py | 2 +- .../src/carla_ad_agent/carla_ad_agent.py | 13 +++++---- .../src/carla_ad_agent/local_planner.py | 29 ++++++++++++------- .../carla_ad_agent/vehicle_pid_controller.py | 6 ++-- .../application_runner.py | 2 +- 7 files changed, 39 insertions(+), 23 deletions(-) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 86f4b48a..3a2d81f6 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -4,6 +4,7 @@ import launch import launch_ros.actions + def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 5aa20dfa..bcaf4616 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -61,7 +61,8 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): self._last_traffic_light = None self._target_route_point = None - self._odometry_subscriber = self.node.create_subscriber(Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) + self._odometry_subscriber = self.node.create_subscriber( + Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) # wait for first odometry update self.node.logwarn('Agent waiting for odometry message') while self._vehicle_location is None: @@ -78,8 +79,10 @@ def __init__(self, role_name, vehicle_id, avoid_risk, node): self._traffic_light_status_subscriber = node.create_subscriber(CarlaTrafficLightStatusList, "/carla/traffic_lights/status", self.traffic_lights_updated, qos_profile=QoSProfile(depth=10, durability=latch_on)) - self._target_point_subscriber = node.create_subscriber(Marker,"/carla/{}/next_target".format(role_name), self.target_point_updated) - world_info = node.wait_for_one_message("/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) + self._target_point_subscriber = node.create_subscriber( + Marker, "/carla/{}/next_target".format(role_name), self.target_point_updated) + world_info = node.wait_for_one_message( + "/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) self._map_name = world_info.map_name def traffic_lights_updated(self, traffic_lights): diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index ee95e7a2..f725da40 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -45,7 +45,7 @@ def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): self._avoid_risk = avoid_risk self._proximity_threshold = 10.0 # meters self._state = AgentState.NAVIGATING - + if ROS_VERSION == 1: cb_group = None elif ROS_VERSION == 2: diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index aa6e722d..ef26abb8 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -11,7 +11,7 @@ import sys import time from std_msgs.msg import Float64 # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=import-error from ros_compatibility import ( CompatibleNode, ROSInterruptException, @@ -54,14 +54,17 @@ def __init__(self): # wait for ego vehicle vehicle_info = None self.loginfo("Wait for vehicle info ...") - vehicle_info = self.wait_for_one_message("/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) + vehicle_info = self.wait_for_one_message("/carla/{}/vehicle_info".format( + role_name), CarlaEgoVehicleInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) self.loginfo("Vehicle info received.") self.agent = BasicAgent(role_name, vehicle_info.id, self, avoid_risk) - self.target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) - - self.speed_command_publisher = self.new_publisher( Float64, "/carla/{}/speed_command".format(role_name), QoSProfile(depth=1, durability=True)) + self.target_speed_subscriber = self.create_subscriber( + Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) + + self.speed_command_publisher = self.new_publisher( + Float64, "/carla/{}/speed_command".format(role_name), QoSProfile(depth=1, durability=True)) def target_speed_updated(self, target_speed): """ diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 13364854..c989c747 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -74,16 +74,22 @@ def __init__(self): self._target_speed = 0.0 # subscribers - self._odometry_subscriber = self.create_subscriber(Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) - self._path_subscriber = self.create_subscriber(Path, "/carla/{}/waypoints".format(role_name), self.path_updated, QoSProfile(depth=1, durability=True)) - self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/speed_command".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) + self._odometry_subscriber = self.create_subscriber( + Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) + self._path_subscriber = self.create_subscriber( + Path, "/carla/{}/waypoints".format(role_name), self.path_updated, QoSProfile(depth=1, durability=True)) + self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/speed_command".format( + role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) # publishers - self._target_point_publisher = self.new_publisher(Marker, "/carla/{}/next_target".format(role_name), QoSProfile(depth=10, durability=False)) - self._control_cmd_publisher = self.new_publisher(CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), QoSProfile(depth=1, durability=False)) + self._target_point_publisher = self.new_publisher( + Marker, "/carla/{}/next_target".format(role_name), QoSProfile(depth=10, durability=False)) + self._control_cmd_publisher = self.new_publisher( + CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), QoSProfile(depth=1, durability=False)) # initializing controller - self._vehicle_controller = VehiclePIDController(self, args_lateral=args_lateral_dict, args_longitudinal=args_longitudinal_dict) + self._vehicle_controller = VehiclePIDController( + self, args_lateral=args_lateral_dict, args_longitudinal=args_longitudinal_dict) # wait for required messages self.loginfo('Local planner waiting for a path and target speed...') @@ -131,7 +137,7 @@ def run_step(self): self.loginfo("Route finished. Waiting for a new one.") self.path_received = False return - + # When target speed is 0, brake if self._target_speed == 0.0: self.emergency_stop() @@ -160,7 +166,8 @@ def run_step(self): self._target_point_publisher.publish(target_point) # move using PID controllers - control = self._vehicle_controller.run_step(self._target_speed, self._current_speed, self._current_pose, self.target_route_point) + control = self._vehicle_controller.run_step( + self._target_speed, self._current_speed, self._current_pose, self.target_route_point) # self.f.write('{}, {}, {}, {}, {}, \n'.format(self.get_time(), self._target_speed, self._current_speed, control.throttle, self._vehicle_controller._lat_controller.error)) @@ -205,7 +212,8 @@ def main(args=None): if ROS_VERSION == 1: local_planner.on_shutdown(local_planner.emergency_stop) local_planner.loginfo('Local planner is starting.') - update_timer = local_planner.new_timer(local_planner.control_time_step, lambda timer_event=None: local_planner.run_step()) + update_timer = local_planner.new_timer( + local_planner.control_time_step, lambda timer_event=None: local_planner.run_step()) local_planner.spin() except KeyboardInterrupt: pass @@ -220,8 +228,7 @@ def main(args=None): if ROS_VERSION == 2: local_planner.emergency_stop() local_planner.shutdown() - if __name__ == "__main__": - main() \ No newline at end of file + main() diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py index d797f043..d2229935 100644 --- a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -95,7 +95,8 @@ def run_step(self, target_speed, current_speed): """ previous_error = self.error self.error = target_speed - current_speed - self.error_integral = np.clip(self.error_integral + self.error, -40.0, 40.0) # restrict integral term to avoid integral windup + # restrict integral term to avoid integral windup + self.error_integral = np.clip(self.error_integral + self.error, -40.0, 40.0) self.error_derivative = self.error - previous_error output = self._K_P * self.error + self._K_I * self.error_integral + self._K_D * self.error_derivative return np.clip(output, 0.0, 1.0) @@ -154,7 +155,8 @@ def run_step(self, current_pose, waypoint): previous_error = self.error self.error = _dot - self.error_integral = np.clip(self.error_integral + self.error, -400.0, 400.0) # restrict integral term to avoid integral windup + # restrict integral term to avoid integral windup + self.error_integral = np.clip(self.error_integral + self.error, -400.0, 400.0) self.error_derivative = self.error - previous_error output = self._K_P * self.error + self._K_I * self.error_integral + self._K_D * self.error_derivative return np.clip(output, -1.0, 1.0) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py index bc03b27f..1a1f84d4 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -104,7 +104,7 @@ def start_process(self, argument_list, log_fct, env=None, cwd=None): # pylint: executable = " ".join(argument_list) else: executable = argument_list - + log_fct("Executing: " + executable) process = pexpect.spawn(executable, env=env, cwd=cwd, encoding='utf-8') #process.logfile_read = sys.stdout From dda25c1c49ecca5cad4bfaa893a4b8785b28b4d5 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Tue, 23 Feb 2021 14:56:08 -0500 Subject: [PATCH 504/627] other fix format --- carla_ros_bridge/src/carla_ros_bridge/radar.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index a63346a9..a5c465fd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -75,7 +75,8 @@ def sensor_data_updated(self, carla_radar_measurement): points = [] for detection in carla_radar_measurement: points.append([detection.depth * np.cos(detection.azimuth) * np.cos(-detection.altitude), - detection.depth * np.sin(-detection.azimuth) * np.cos(detection.altitude), + detection.depth * np.sin(-detection.azimuth) * + np.cos(detection.altitude), detection.depth * np.sin(detection.altitude), detection.depth, detection.velocity, detection.azimuth, detection.altitude]) radar_msg = create_cloud(self.get_msg_header( From d20a5f8a9e4dc9338d38f92532c9dbaf760a8f11 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Tue, 23 Feb 2021 15:50:27 -0500 Subject: [PATCH 505/627] Update docs, fix bugs --- README.md | 106 +++--------------- README.ros.md | 73 ++++++++++++ README.ros2.md | 43 +++++++ carla_ad_agent/README.md | 17 ++- carla_ad_demo/README.md | 17 ++- carla_ad_demo/launch/carla_ad_demo.launch | 3 +- carla_ad_demo/launch/carla_ad_demo.launch.py | 19 ++-- .../launch/carla_ad_demo_with_scenario.launch | 3 +- .../carla_ad_demo_with_scenario.launch.py | 6 +- .../ros_vehicle_control.py | 2 +- 10 files changed, 170 insertions(+), 119 deletions(-) create mode 100644 README.ros.md create mode 100644 README.ros2.md diff --git a/README.md b/README.md index c211f6f0..9dfc49a3 100644 --- a/README.md +++ b/README.md @@ -1,11 +1,11 @@ -# ROS bridge for CARLA simulator +# ROS/ROS2 bridge for CARLA simulator [![Actions Status](https://github.com/carla-simulator/ros-bridge/workflows/CI/badge.svg)](https://github.com/carla-simulator/ros-bridge) [![Build Status](https://travis-ci.com/carla-simulator/ros-bridge.svg?branch=master)](https://travis-ci.com/carla-simulator/ros-bridge) [![GitHub](https://img.shields.io/github/license/carla-simulator/ros-bridge)](https://github.com/carla-simulator/ros-bridge/blob/master/LICENSE) [![GitHub release (latest by date)](https://img.shields.io/github/v/release/carla-simulator/ros-bridge)](https://github.com/carla-simulator/ros-bridge/releases/latest) -This ROS package aims at providing a simple ROS bridge for CARLA simulator. +This ROS package aims at providing a simple ROS/ROS2 bridge for CARLA simulator. ![rviz setup](./docs/images/ad_demo.png "AD Demo") @@ -16,7 +16,7 @@ This ROS package aims at providing a simple ROS bridge for CARLA simulator. - Provide Sensor Data (Lidar, Semantic lidar, Cameras (depth, segmentation, rgb, dvs), GNSS, Radar, IMU) - Provide Object Data (Transforms (via [tf](http://wiki.ros.org/tf)), Traffic light status, Visualization markers, Collision, Lane invasion) - Control AD Agents (Steer/Throttle/Brake) -- Control CARLA (Support synchronous mode, Play/pause simulation, Set simulation parameters) +- Control CARLA (Play/pause simulation, Set simulation parameters) ### Additional Functionality @@ -38,108 +38,30 @@ For a quick overview, after following the [Setup section](#setup), please run th ## Setup -### For Users +ROS and ROS2 are supported by using separate implementations with a [common interface](ros_compatibility). -First add the apt repository: +Please follow the instructions: - sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 1AF1527DE64CB8D9 - sudo add-apt-repository "deb [arch=amd64] http://dist.carla.org/carla $(lsb_release -sc) main" - -Then simply install the ROS bridge: - - sudo apt-get update - sudo apt-get install carla-ros-bridge - -This will install carla-ros-bridge in /opt/carla-ros-bridge - -### For Developers - - Create a catkin workspace and install carla_ros_bridge package - - #setup folder structure - mkdir -p ~/carla-ros-bridge/catkin_ws/src - cd ~/carla-ros-bridge - git clone https://github.com/carla-simulator/ros-bridge.git - cd ros-bridge - git submodule update --init - cd ../catkin_ws/src - ln -s ../../ros-bridge - source /opt/ros//setup.bash - cd .. - - #install required ros-dependencies - rosdep update - rosdep install --from-paths src --ignore-src -r - - #build - catkin_make - -For more information about configuring a ROS environment see - - -#### Using ROS2 - -In development - -To test the ROS2 implementation, the rmw_fasrtps_cpp RMW implementation should be used. (default with ROS2 standard installation). - -## Start the ROS bridge - -First run the simulator (see carla documentation: ) - - # run carla in background - SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl - -Wait a few seconds - - export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg - -##### For Users - - source /opt/carla-ros-bridge//setup.bash - -##### For Developers - - source ~/carla-ros-bridge/catkin_ws/devel/setup.bash - -Start the ros bridge (choose one option): - - # Option 1: start the ros bridge - roslaunch carla_ros_bridge carla_ros_bridge.launch - - # Option 2: start the ros bridge together with an example ego vehicle - roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch +* [ROS](README.ros.md) +* [ROS2](README.ros2.md) ## Configuration -### Settings file - -You can modify the ros bridge configuration by editing [carla_ros_bridge/config/settings.yaml](carla_ros_bridge/config/settings.yaml). - -If the rolename is within the list specified by ROS parameter `/carla/ego_vehicle/rolename`, the client is interpreted as an controllable ego vehicle and all relevant ROS topics are created. - -### Launch file - Certain parameters can be set within the launch file [carla_ros_bridge.launch](carla_ros_bridge/launch/carla_ros_bridge.launch). -#### Map +If the rolename is within the list specified by argument `ego_vehicle_role_name`, it is interpreted as an controllable ego vehicle and all relevant ROS topics are created. -The bridge is able to load a CARLA map by setting the launch-file parameter ```town```. Either specify an available CARLA Town (e.g. 'Town01') or a OpenDRIVE file (with ending '.xodr'). - -#### Mode +### Map -##### Default Mode - -In default mode (`synchronous_mode: false`) data is published: +The bridge is able to load a CARLA map by setting the launch-file parameter ```town```. Either specify an available CARLA Town (e.g. 'Town01') or a OpenDRIVE file (with ending '.xodr'). -- on every `world.on_tick()` callback -- on every `sensor.listen()` callback +### Mode -##### Synchronous Mode +The bridge should only be used in CARLA synchronous mode. -CAUTION: In synchronous mode, only the ros-bridge is allowed to tick. Other CARLA clients must passively wait. +CAUTION: Only the ros-bridge is allowed to tick. Other CARLA clients must passively wait. -In synchronous mode (`synchronous_mode: true`), the bridge waits for all sensor data that is expected within the current frame. This might slow down the overall simulation but ensures reproducible results. +The bridge waits for all sensor data that is expected within the current frame to ensures reproducible results. Additionally you might set `synchronous_mode_wait_for_vehicle_control_command` to `true` to wait for a vehicle control command before executing the next tick. diff --git a/README.ros.md b/README.ros.md new file mode 100644 index 00000000..34744464 --- /dev/null +++ b/README.ros.md @@ -0,0 +1,73 @@ +# ROS + +### For Users + +First add the apt repository: + + sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 1AF1527DE64CB8D9 + sudo add-apt-repository "deb [arch=amd64] http://dist.carla.org/carla $(lsb_release -sc) main" + +Then simply install the ROS bridge: + + sudo apt-get update + sudo apt-get install carla-ros-bridge + +This will install carla-ros-bridge in /opt/carla-ros-bridge + +### For Developers + + Create a catkin workspace and install carla_ros_bridge package + + #setup folder structure + mkdir -p ~/carla-ros-bridge/catkin_ws/src + cd ~/carla-ros-bridge + git clone https://github.com/carla-simulator/ros-bridge.git + cd ros-bridge + git submodule update --init + cd ../catkin_ws/src + ln -s ../../ros-bridge + source /opt/ros//setup.bash + cd .. + + #install required ros-dependencies + rosdep update + rosdep install --from-paths src --ignore-src -r + + #build + catkin_make + +For more information about configuring a ROS environment see + + +#### Using ROS2 + +In development + +To test the ROS2 implementation, the rmw_fasrtps_cpp RMW implementation should be used. (default with ROS2 standard installation). + +## Start the ROS bridge + +First run the simulator (see carla documentation: ) + + # run carla in background + SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl + +Wait a few seconds + + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg + +##### For Users + + source /opt/carla-ros-bridge//setup.bash + +##### For Developers + + source ~/carla-ros-bridge/catkin_ws/devel/setup.bash + +Start the ros bridge (choose one option): + + # Option 1: start the ros bridge + roslaunch carla_ros_bridge carla_ros_bridge.launch + + # Option 2: start the ros bridge together with an example ego vehicle + roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch diff --git a/README.ros2.md b/README.ros2.md new file mode 100644 index 00000000..1456645b --- /dev/null +++ b/README.ros2.md @@ -0,0 +1,43 @@ +# ROS2 + +Currently supported: [Foxy](https://index.ros.org/doc/ros2/Releases/Release-Foxy-Fitzroy/) + +# Setup + +Colcon and ROS2 Foxy needs to be installed on your system. + + git clone https://github.com/carla-simulator/ros-bridge.git + cd ros-bridge + git submodule update --init + source /opt/ros/foxy/setup.bash + colcon build + +For more information about configuring a ROS2 environment see + + +## Start the ROS bridge + +First run the simulator (see carla documentation: ) + + # run carla in background + SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl + + # Add the + export CARLA_ROOT= + export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla + +##### For Users + + source /opt/carla-ros-bridge//setup.bash + +##### For Developers + + source ~/carla-ros-bridge/catkin_ws/devel/setup.bash + +Start the ros bridge (choose one option): + + # Option 1: start the ros bridge + roslaunch carla_ros_bridge carla_ros_bridge.launch + + # Option 2: start the ros bridge together with an example ego vehicle + roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch diff --git a/carla_ad_agent/README.md b/carla_ad_agent/README.md index 15fa228e..8f251b7b 100644 --- a/carla_ad_agent/README.md +++ b/carla_ad_agent/README.md @@ -2,10 +2,25 @@ An AD agent that can follow a given route. -It avoids crashs with other vehicles and respects the state of the traffic lights. +It avoids crashs with other vehicles and respects the state of the traffic lights by accessing the ground truth data. For a more comprehensive solution, have a look at [Autoware](https://www.autoware.ai/). +## Subscriptions +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | +| `/carla//waypoints` | [nav_msgs.Path](http://docs.ros.org/api/nav_msgs/html/msg/Path.html) | Route to follow | +| `/carla//target_speed` | [std_msgs.Float64](http://docs.ros.org/api/std_msgs/html/msg/Float64.html) | Target speed | +| `/carla//odometry` | [nav_msgs.Odometry](http://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | localization of ego vehicle | + +For risk avoidance, more subscriptions are required: + +| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleInfo.msg) | Identify the carla actor id of the ego vehicle | +| `/carla//objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | Information about other actors | +| `/carla/actor_list` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaActorList.msg) | Actor list | +| `/carla/world_info` | [carla_msgs.CarlaWorldInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWorldInfo.msg) | Selects mode for traffic lights (US- or Europe-style) | +| `/carla/traffic_lights/status` | [carla_msgs.CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightStatusList.msg) | Get the current state of the traffic lights | + ## Publications | Topic | Type | Description | diff --git a/carla_ad_demo/README.md b/carla_ad_demo/README.md index c530e90c..75cae499 100644 --- a/carla_ad_demo/README.md +++ b/carla_ad_demo/README.md @@ -3,15 +3,19 @@ This meta package provides everything to launch a CARLA ROS environment with an AD vehicle. -![CARLA AD Demo](../docs/images/rviz_carla_plugin.png "rviz carla plugin") - -The Node setup is visualized [here](../docs/images/ad_demo.png "AD Demo Node Setup") +![CARLA AD Demo](../docs/images/ad_demo.png "AD Demo in Rviz") ## Startup export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ export SCENARIO_RUNNER_PATH= + + # ROS 1 roslaunch carla_ad_demo carla_ad_demo.launch + + # ROS 2 + ros2 launch carla_ad_demo carla_ad_demo.launch.py + ### Modes @@ -29,8 +33,12 @@ You can modify start position and goal within the [launch file](launch/carla_ad_ If you prefer to execute a predefined scenario, launch: + # ROS1 roslaunch carla_ad_demo carla_ad_demo_with_scenario.launch + # ROS2 + ros2 launch carla_ad_demo carla_ad_demo_with_scenario.launch.py + Select to example scenario "FollowLeadingVehicle" within the RVIZ Carla Plugin and press "Execute". The ego vehicle gets repositioned and the scenario is processed. You can specify your own scenarios by publishing to `/carla/available_scenarios`. See the [launch file](launch/carla_ad_demo_with_scenario.launch) for an example. @@ -38,4 +46,5 @@ You can specify your own scenarios by publishing to `/carla/available_scenarios` ##### Troubleshooting -If the example scenario fails, please analyze the ros log and follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working standalone. +- If the example scenario fails, please analyze the ros log and follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working standalone. + diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 258bec8b..5d8e4e34 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -8,7 +8,6 @@ - @@ -32,7 +31,7 @@ - + diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index cc03505c..0633b810 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -6,7 +6,7 @@ from ament_index_python.packages import get_package_share_directory -def launch_carla_spawn_object(context, *args, **kwargs): +def launch_carla_spawn_object(context, *args, **kwargs): #TODO find better solution # workaround to use launch argument 'role_name' as a part of the string used for the spawn_point param name spawn_point_param_name = 'spawn_point_' + \ launch.substitutions.LaunchConfiguration('role_name').perform(context) @@ -43,10 +43,6 @@ def generate_launch_description(): name='timeout', default_value='10' ), - launch.actions.DeclareLaunchArgument( - name='synchronous_mode', - default_value='True' - ), launch.actions.DeclareLaunchArgument( name='synchronous_mode_wait_for_vehicle_control_command', default_value='False' @@ -75,12 +71,11 @@ def generate_launch_description(): name='sigterm_timeout', default_value='15' ), - # TODO: adapt this to ROS2 - # launch_ros.actions.Node( - # package='rostopic', - # executable='rostopic', - # name='publish_goal' - # ), + launch.actions.ExecuteProcess( # TODO: required? + cmd=["ros2", "topic", "pub", "/carla/ego_vehicle/goal", + "geometry_msgs/PoseStamped", "--qos-durability transient_local", + "{ 'pose': { 'position': { 'x': 157.9, 'y': 29.8 }, 'orientation': { 'z': 0.70711, 'w': 0.70711 } } }'"] + ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( @@ -91,7 +86,7 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'town': launch.substitutions.LaunchConfiguration('town'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode'), + 'synchronous_mode': 'True', 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') }.items() diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index 0a4830a9..1dffed44 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -6,7 +6,6 @@ - @@ -27,7 +26,7 @@ - + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index cd8c4009..1b362b65 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -28,10 +28,6 @@ def generate_launch_description(): name='timeout', default_value='2' ), - launch.actions.DeclareLaunchArgument( - name='synchronous_mode', - default_value='True' - ), launch.actions.DeclareLaunchArgument( name='synchronous_mode_wait_for_vehicle_control_command', default_value='False' @@ -81,7 +77,7 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'town': launch.substitutions.LaunchConfiguration('town'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode'), + 'synchronous_mode': 'True', # only synchronous mode is supported 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') }.items() diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index a5225ca7..12da739b 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -15,7 +15,7 @@ import carla_common.transforms as trans from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error -from ros_compatibility import CompatibleNode, QoSProfile, ros_timestamp +from ros_compatibility import CompatibleNode, QoSProfile, ros_timestamp, ros_init import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) From f50b7eedc1e426b59d45713efd3c1c7ca4df92d4 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 24 Feb 2021 04:55:31 -0500 Subject: [PATCH 506/627] Cleanup --- README.ros.md | 6 ------ README.ros2.md | 20 +++++++------------ carla_ad_agent/CMakeLists.txt | 3 ++- carla_ad_demo/launch/carla_ad_demo.launch.py | 4 ++-- .../carla_ad_demo_with_scenario.launch.py | 2 +- 5 files changed, 12 insertions(+), 23 deletions(-) diff --git a/README.ros.md b/README.ros.md index 34744464..1d8772cd 100644 --- a/README.ros.md +++ b/README.ros.md @@ -39,12 +39,6 @@ This will install carla-ros-bridge in /opt/carla-ros-bridge For more information about configuring a ROS environment see -#### Using ROS2 - -In development - -To test the ROS2 implementation, the rmw_fasrtps_cpp RMW implementation should be used. (default with ROS2 standard installation). - ## Start the ROS bridge First run the simulator (see carla documentation: ) diff --git a/README.ros2.md b/README.ros2.md index 1456645b..66ae55ef 100644 --- a/README.ros2.md +++ b/README.ros2.md @@ -1,10 +1,10 @@ # ROS2 -Currently supported: [Foxy](https://index.ros.org/doc/ros2/Releases/Release-Foxy-Fitzroy/) +Currently supported: [ROS2 Foxy](https://index.ros.org/doc/ros2/Releases/Release-Foxy-Fitzroy/) # Setup -Colcon and ROS2 Foxy needs to be installed on your system. +Colcon and ROS2 Foxy need to be installed on your system. git clone https://github.com/carla-simulator/ros-bridge.git cd ros-bridge @@ -17,27 +17,21 @@ For more information about configuring a ROS2 environment see ## Start the ROS bridge -First run the simulator (see carla documentation: ) +First run the simulator (see CARLA documentation: ) # run carla in background SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl - # Add the + # Add the carla modules to your python environment export CARLA_ROOT= export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla -##### For Users - - source /opt/carla-ros-bridge//setup.bash - -##### For Developers - - source ~/carla-ros-bridge/catkin_ws/devel/setup.bash + source ./install/setup.bash Start the ros bridge (choose one option): # Option 1: start the ros bridge - roslaunch carla_ros_bridge carla_ros_bridge.launch + ros2 launch carla_ros_bridge carla_ros_bridge.launch.py # Option 2: start the ros bridge together with an example ego vehicle - roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch + ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index 86c611c8..5e106fa1 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -18,7 +18,8 @@ if(${ROS_VERSION} EQUAL 1) include_directories(${catkin_INCLUDE_DIRS}) - install(PROGRAMS src/carla_ad_agent/carla_ad_agent.py src/carla_ad_agent/local_planner.py + install(PROGRAMS src/carla_ad_agent/carla_ad_agent.py + src/carla_ad_agent/local_planner.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) message(${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 0633b810..3f61b442 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -6,7 +6,7 @@ from ament_index_python.packages import get_package_share_directory -def launch_carla_spawn_object(context, *args, **kwargs): #TODO find better solution +def launch_carla_spawn_object(context, *args, **kwargs): # TODO find better solution # workaround to use launch argument 'role_name' as a part of the string used for the spawn_point param name spawn_point_param_name = 'spawn_point_' + \ launch.substitutions.LaunchConfiguration('role_name').perform(context) @@ -71,7 +71,7 @@ def generate_launch_description(): name='sigterm_timeout', default_value='15' ), - launch.actions.ExecuteProcess( # TODO: required? + launch.actions.ExecuteProcess( # TODO: required? cmd=["ros2", "topic", "pub", "/carla/ego_vehicle/goal", "geometry_msgs/PoseStamped", "--qos-durability transient_local", "{ 'pose': { 'position': { 'x': 157.9, 'y': 29.8 }, 'orientation': { 'z': 0.70711, 'w': 0.70711 } } }'"] diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index 1b362b65..6421a2a8 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -77,7 +77,7 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'town': launch.substitutions.LaunchConfiguration('town'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'synchronous_mode': 'True', # only synchronous mode is supported + 'synchronous_mode': 'True', # only synchronous mode is supported 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') }.items() From 200bd83a5b953e87cc229b8f8cb825c605a369b8 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 24 Feb 2021 05:10:30 -0500 Subject: [PATCH 507/627] Update carla_ad_agent doc --- carla_ad_agent/README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/carla_ad_agent/README.md b/carla_ad_agent/README.md index 8f251b7b..fdcfe7dc 100644 --- a/carla_ad_agent/README.md +++ b/carla_ad_agent/README.md @@ -15,6 +15,8 @@ For a more comprehensive solution, have a look at [Autoware](https://www.autowar For risk avoidance, more subscriptions are required: +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | | `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleInfo.msg) | Identify the carla actor id of the ego vehicle | | `/carla//objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | Information about other actors | | `/carla/actor_list` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaActorList.msg) | Actor list | From 2d35bbacebede78c1a825a08afcef9b896f2401c Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 24 Feb 2021 05:26:58 -0500 Subject: [PATCH 508/627] Add doc for local planner node --- carla_ad_agent/README.md | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/carla_ad_agent/README.md b/carla_ad_agent/README.md index fdcfe7dc..e1fa08b9 100644 --- a/carla_ad_agent/README.md +++ b/carla_ad_agent/README.md @@ -28,3 +28,14 @@ For risk avoidance, more subscriptions are required: | Topic | Type | Description | | ---------------------------------- | ------------------- | --------------------------- | | `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | Vehicle control command | + + + +## Local Planner Node + +Internally, the CARLA AD Agent uses a separate node for [local planning](src/carla_ad_agent/local_planner.py). + +This is currently optimized for `vehicle.tesla.model3`, as it does not have any gear shift delays. + +The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedia.org/wiki/Ziegler%E2%80%93Nichols_method). + From 1380731431d60d9e6f3484fe75417a7e7c9d0b6a Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 24 Feb 2021 06:05:26 -0500 Subject: [PATCH 509/627] add comment and remove debug leftover --- carla_ad_agent/CMakeLists.txt | 1 - carla_ad_agent/src/carla_ad_agent/local_planner.py | 5 ----- carla_ad_demo/launch/carla_ad_demo.launch.py | 2 +- 3 files changed, 1 insertion(+), 7 deletions(-) diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index 5e106fa1..6e0a7ecb 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -21,7 +21,6 @@ if(${ROS_VERSION} EQUAL 1) install(PROGRAMS src/carla_ad_agent/carla_ad_agent.py src/carla_ad_agent/local_planner.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - message(${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index c989c747..d3e78eb0 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -98,8 +98,6 @@ def __init__(self): if ROS_VERSION == 2: rclpy.spin_once(self, timeout_sec=0) - # self.f = open('data.txt', 'w') - def odometry_updated(self, new_pose): """ callback on new odometry @@ -169,8 +167,6 @@ def run_step(self): control = self._vehicle_controller.run_step( self._target_speed, self._current_speed, self._current_pose, self.target_route_point) - # self.f.write('{}, {}, {}, {}, {}, \n'.format(self.get_time(), self._target_speed, self._current_speed, control.throttle, self._vehicle_controller._lat_controller.error)) - # purge the queue of obsolete waypoints max_index = -1 @@ -224,7 +220,6 @@ def main(args=None): update_timer.shutdown() else: update_timer.destroy() - # local_planner.f.close() if ROS_VERSION == 2: local_planner.emergency_stop() local_planner.shutdown() diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 3f61b442..7d6a70b1 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -86,7 +86,7 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'town': launch.substitutions.LaunchConfiguration('town'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'synchronous_mode': 'True', + 'synchronous_mode': 'True', # only synchronous mode is supported 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') }.items() From 29449bf7456998030f7bee7e04d38854c0862976 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 24 Feb 2021 06:13:30 -0500 Subject: [PATCH 510/627] passing some more parameters to node from launchfiles carla_ad_agent.launch --- carla_ad_agent/launch/carla_ad_agent.launch | 15 ++++++++++++- .../launch/carla_ad_agent.launch.py | 21 +++++++++++++++++++ 2 files changed, 35 insertions(+), 1 deletion(-) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch b/carla_ad_agent/launch/carla_ad_agent.launch index 34ca6906..cd6e688b 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch +++ b/carla_ad_agent/launch/carla_ad_agent.launch @@ -3,6 +3,13 @@ + + + + + + + @@ -12,7 +19,13 @@ - + + + + + + + diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 3a2d81f6..fe7179f7 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -75,6 +75,27 @@ def generate_launch_description(): }, { 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'Kp_lateral': launch.substitutions.LaunchConfiguration('Kp_lateral') + }, + { + 'Ki_lateral': launch.substitutions.LaunchConfiguration('Ki_lateral') + }, + { + 'Kd_lateral': launch.substitutions.LaunchConfiguration('Kd_lateral') + }, + { + 'Kp_longitudinal': launch.substitutions.LaunchConfiguration('Kp_longitudinal') + }, + { + 'Ki_longitudinal': launch.substitutions.LaunchConfiguration('Ki_longitudinal') + }, + { + 'Kd_longitudinal': launch.substitutions.LaunchConfiguration('Kd_longitudinal') + }, + { + 'control_time_step': launch.substitutions.LaunchConfiguration('control_time_step') } ] ) From 48db16ee21f2f1f9127c682cca6719e11f3ade1d Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 24 Feb 2021 06:41:04 -0500 Subject: [PATCH 511/627] fixes carla_ad_agent ros1 shutdown --- carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index ef26abb8..d98759c4 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -103,7 +103,7 @@ def main(args=None): controller = None try: controller = CarlaAdAgent() - while True: + while ros_ok(): time.sleep(0.01) if ROS_VERSION == 2: rclpy.spin_once(controller) From d215340e13e663137262bd26be85143552e56e7a Mon Sep 17 00:00:00 2001 From: jmagnin Date: Wed, 24 Feb 2021 06:43:23 -0500 Subject: [PATCH 512/627] removed unnecessary todo --- carla_ad_demo/launch/carla_ad_demo.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 7d6a70b1..d686c85e 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -6,7 +6,7 @@ from ament_index_python.packages import get_package_share_directory -def launch_carla_spawn_object(context, *args, **kwargs): # TODO find better solution +def launch_carla_spawn_object(context, *args, **kwargs): # workaround to use launch argument 'role_name' as a part of the string used for the spawn_point param name spawn_point_param_name = 'spawn_point_' + \ launch.substitutions.LaunchConfiguration('role_name').perform(context) From 4009f1d54eaf759916185d75654f4fd65fc5243f Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 25 Feb 2021 14:21:03 -0500 Subject: [PATCH 513/627] Remove astuff_sensor_msgs submodule --- .gitmodules | 4 ---- astuff_sensor_msgs | 1 - 2 files changed, 5 deletions(-) delete mode 160000 astuff_sensor_msgs diff --git a/.gitmodules b/.gitmodules index 3cef1f6a..720c0ea7 100644 --- a/.gitmodules +++ b/.gitmodules @@ -2,7 +2,3 @@ path = carla_msgs url = https://github.com/carla-simulator/ros-carla-msgs branch = master -[submodule "astuff_sensor_msgs"] - path = astuff_sensor_msgs - url = https://github.com/astuff/astuff_sensor_msgs.git - branch = maint/ros1_2_hybrid diff --git a/astuff_sensor_msgs b/astuff_sensor_msgs deleted file mode 160000 index 5a2c8979..00000000 --- a/astuff_sensor_msgs +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 5a2c89793aead8a1e52fd772606ef0bc41085fb6 From d08acf661bf4052bf69a7a0a4c5c9b89c07d9557 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 25 Feb 2021 14:37:10 -0500 Subject: [PATCH 514/627] Move test section to ros-version-specific readme --- README.md | 20 -------------------- README.ros.md | 19 +++++++++++++++++-- README.ros2.md | 9 +++++++++ 3 files changed, 26 insertions(+), 22 deletions(-) diff --git a/README.md b/README.md index 9dfc49a3..2cf19ebc 100644 --- a/README.md +++ b/README.md @@ -303,26 +303,6 @@ The following markers are supported in 'map'-frame: | ---------------------------------- | ------------------------------------------------------------------------------------------------------ | --------------------------- | | `/carla/debug_marker` (subscriber) | [visualization_msgs.MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) | draw markers in CARLA world | -## Testing - -### ROS1 and catkin - -To execute the tests, using catkin and ROS1, use the following commands: - - # build - catkin_make -DCATKIN_ENABLE_TESTING=0 - # run - rostest carla_ros_bridge ros_bridge_client.test - -### ROS2 and colcon - -To execute the tests using colcon and ROS2, use the following commands: - - # build - colcon build --packages-up-to carla_ros_bridge - # run - launch_test ros-bridge/carla_ros_bridge/test/ros_bridge_client_ros2_test.py - ## Troubleshooting ### ImportError: No module named carla diff --git a/README.ros.md b/README.ros.md index 1d8772cd..5a599f56 100644 --- a/README.ros.md +++ b/README.ros.md @@ -39,6 +39,12 @@ This will install carla-ros-bridge in /opt/carla-ros-bridge For more information about configuring a ROS environment see +#### Using ROS2 + +In development + +To test the ROS2 implementation, the rmw_fasrtps_cpp RMW implementation should be used. (default with ROS2 standard installation). + ## Start the ROS bridge First run the simulator (see carla documentation: ) @@ -46,8 +52,8 @@ First run the simulator (see carla documentation: export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg ##### For Users @@ -65,3 +71,12 @@ Start the ros bridge (choose one option): # Option 2: start the ros bridge together with an example ego vehicle roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch + +## Testing + +To execute the tests, using catkin, use the following commands: + + # build + catkin_make -DCATKIN_ENABLE_TESTING=0 + # run + rostest carla_ros_bridge ros_bridge_client.test diff --git a/README.ros2.md b/README.ros2.md index 66ae55ef..a63ca036 100644 --- a/README.ros2.md +++ b/README.ros2.md @@ -35,3 +35,12 @@ Start the ros bridge (choose one option): # Option 2: start the ros bridge together with an example ego vehicle ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py + +## Testing + +To execute the tests using colcon, use the following commands: + + # build + colcon build --packages-up-to carla_ros_bridge + # run + launch_test carla_ros_bridge/test/ros_bridge_client_ros2_test.py From 12fbe8f88eba8281b16e3d17c0c48de30d7e1f55 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Thu, 25 Feb 2021 12:43:30 -0500 Subject: [PATCH 515/627] removed useless ros2 part in cmakelists --- carla_ad_agent/CMakeLists.txt | 14 +------------- carla_ad_demo/CMakeLists.txt | 9 --------- carla_ros_bridge/CMakeLists.txt | 10 ---------- carla_spawn_objects/CMakeLists.txt | 11 ----------- carla_twist_to_control/CMakeLists.txt | 10 ---------- carla_walker_agent/CMakeLists.txt | 10 ---------- carla_waypoint_publisher/CMakeLists.txt | 10 ---------- ros_compatibility/CMakeLists.txt | 6 ------ 8 files changed, 1 insertion(+), 79 deletions(-) diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index 6e0a7ecb..bb3654fd 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -23,16 +23,4 @@ if(${ROS_VERSION} EQUAL 1) DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) - -elseif(${ROS_VERSION} EQUAL 2) - # TODO: remove - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) - - ament_package() - -endif() +endif() \ No newline at end of file diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 90f078ae..1bcdd94e 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -19,13 +19,4 @@ if(${ROS_VERSION} EQUAL 1) install(DIRECTORY config/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) - -elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) - - ament_package() - endif() diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index ae49ae7e..30ad3e11 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -36,14 +36,4 @@ if(${ROS_VERSION} EQUAL 1) add_rostest(test/ros_bridge_client.test) endif() -elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) - - ament_package() - endif() diff --git a/carla_spawn_objects/CMakeLists.txt b/carla_spawn_objects/CMakeLists.txt index d89b8724..59208126 100644 --- a/carla_spawn_objects/CMakeLists.txt +++ b/carla_spawn_objects/CMakeLists.txt @@ -27,15 +27,4 @@ if(${ROS_VERSION} EQUAL 1) install(DIRECTORY config/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config) -elseif(${ROS_VERSION} EQUAL 2) - # TODO: not needed? - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) - - ament_package() - endif() diff --git a/carla_twist_to_control/CMakeLists.txt b/carla_twist_to_control/CMakeLists.txt index 58be6bb9..2784baf2 100644 --- a/carla_twist_to_control/CMakeLists.txt +++ b/carla_twist_to_control/CMakeLists.txt @@ -23,14 +23,4 @@ if(${ROS_VERSION} EQUAL 1) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) -elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) - - ament_package() - endif() diff --git a/carla_walker_agent/CMakeLists.txt b/carla_walker_agent/CMakeLists.txt index 1fe9dde4..04714e33 100644 --- a/carla_walker_agent/CMakeLists.txt +++ b/carla_walker_agent/CMakeLists.txt @@ -22,14 +22,4 @@ if(${ROS_VERSION} EQUAL 1) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) -elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) - - ament_package() - endif() diff --git a/carla_waypoint_publisher/CMakeLists.txt b/carla_waypoint_publisher/CMakeLists.txt index 1e6a6fc0..cd266fca 100644 --- a/carla_waypoint_publisher/CMakeLists.txt +++ b/carla_waypoint_publisher/CMakeLists.txt @@ -24,14 +24,4 @@ if(${ROS_VERSION} EQUAL 1) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) -elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - - # Install launch files. - install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}/) - - ament_package() - endif() diff --git a/ros_compatibility/CMakeLists.txt b/ros_compatibility/CMakeLists.txt index c203d0f7..a249a699 100644 --- a/ros_compatibility/CMakeLists.txt +++ b/ros_compatibility/CMakeLists.txt @@ -23,10 +23,4 @@ if(${ROS_VERSION} EQUAL 1) catkin_install_python(PROGRAMS src/ros_compatibility/ros_compatible_node.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) -elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - ament_package() - endif() From 389d80d2084d2542c9a59ccabb47fd349c76e419 Mon Sep 17 00:00:00 2001 From: jmagnin Date: Thu, 25 Feb 2021 12:43:51 -0500 Subject: [PATCH 516/627] fix bug in actor_control --- .../src/carla_ros_bridge/actor_control.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index b55829a8..491096cc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -10,6 +10,7 @@ """ import numpy +import math import carla_common.transforms as trans from carla_ros_bridge.pseudo_actor import PseudoActor from geometry_msgs.msg import Pose, Twist @@ -48,6 +49,7 @@ def __init__(self, uid, name, parent, node): self.twist_control_subscriber = self.node.create_subscriber(Twist, self.get_topic_prefix() + "/set_target_velocity", self.on_twist) + self.parent = parent def destroy(self): """ @@ -78,12 +80,12 @@ def on_twist(self, twist): """ Set angular/linear velocity (this does not respect vehicle dynamics) """ - if not self.vehicle_control_override: + if not self.parent.vehicle_control_override: angular_velocity = Vector3D() angular_velocity.z = math.degrees(twist.angular.z) - rotation_matrix = transforms.carla_rotation_to_numpy_rotation_matrix( - self.carla_actor.get_transform().rotation) + rotation_matrix = trans.carla_rotation_to_numpy_rotation_matrix( + self.parent.carla_actor.get_transform().rotation) linear_vector = numpy.array([twist.linear.x, twist.linear.y, twist.linear.z]) rotated_linear_vector = rotation_matrix.dot(linear_vector) linear_velocity = Vector3D() @@ -93,5 +95,5 @@ def on_twist(self, twist): self.node.logdebug("Set velocity linear: {}, angular: {}".format( linear_velocity, angular_velocity)) - self.carla_actor.set_target_velocity(linear_velocity) - self.carla_actor.set_target_angular_velocity(angular_velocity) + self.parent.carla_actor.set_target_velocity(linear_velocity) + self.parent.carla_actor.set_target_angular_velocity(angular_velocity) From 7705a87e8bb1e0e61ac412c45237e5d8093035ff Mon Sep 17 00:00:00 2001 From: jmagnin Date: Thu, 25 Feb 2021 14:35:25 -0500 Subject: [PATCH 517/627] resolve some todo --- .../carla_ackermann_control_node.py | 19 ------------------- carla_ad_demo/launch/carla_ad_demo.launch | 5 ----- carla_ad_demo/launch/carla_ad_demo.launch.py | 5 ----- .../carla_manual_control.py | 7 +------ carla_ros_bridge/test/ros_bridge_client.py | 3 ++- .../test/ros_bridge_client_ros2_test.py | 3 ++- 6 files changed, 5 insertions(+), 37 deletions(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index 9589dab3..92432782 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -85,25 +85,6 @@ def __init__(self): # self.add_on_set_parameters_callback(self.reconfigure_pid_parameters) # works with ros2 foxy # for ros2 eloquent, deprecated in ros2 foxy self.set_parameters_callback(self.reconfigure_pid_parameters) - # TODO(hillekia@schaeffler.com): Enable stricter handling of node - # parameters, so they must be explicitly listed. This can be done by - # disabling the `automatically_declare_parameters_from_overrides` - # and `allow_undeclared_parameters` flags of `Node` and will prevent - # mistakes in the future. - # - # self.declare_parameters( - # namespace="", - # parameters=[ - # ("speed_Kp",), - # ("speed_Ki",), - # ("speed_Kd",), - # ("accel_Kp",), - # ("accel_Ki",), - # ("accel_Kd",), - # ("min_accel",), - # ("role_name",), - # ] - # ) self.control_loop_rate = self.get_param("control_loop_rate", 0.05) self.lastAckermannMsgReceived = datetime.datetime(datetime.MINYEAR, 1, 1) diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 5d8e4e34..b6233004 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -17,11 +17,6 @@ - - - - diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index d686c85e..f536a496 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -71,11 +71,6 @@ def generate_launch_description(): name='sigterm_timeout', default_value='15' ), - launch.actions.ExecuteProcess( # TODO: required? - cmd=["ros2", "topic", "pub", "/carla/ego_vehicle/goal", - "geometry_msgs/PoseStamped", "--qos-durability transient_local", - "{ 'pose': { 'position': { 'x': 157.9, 'y': 29.8 }, 'orientation': { 'z': 0.70711, 'w': 0.70711 } } }'"] - ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index d3e84893..32d78aae 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -463,12 +463,7 @@ def update_info_text(self): heading += 'W' if -0.5 > yaw > -179.5 else '' fps = 0 - # TODO - if ROS_VERSION == 1: - time = str(datetime.timedelta(seconds=float(rospy.get_rostime().to_sec())))[:10] - elif ROS_VERSION == 2: - time = str(datetime.timedelta(seconds=float( - self.node.get_clock().now().nanoseconds)/10**9))[:10] + time = str(datetime.timedelta(seconds=self.node.get_time()))[:10] if self.carla_status.fixed_delta_seconds: fps = 1 / self.carla_status.fixed_delta_seconds diff --git a/carla_ros_bridge/test/ros_bridge_client.py b/carla_ros_bridge/test/ros_bridge_client.py index 27077a6d..65cd4ecb 100755 --- a/carla_ros_bridge/test/ros_bridge_client.py +++ b/carla_ros_bridge/test/ros_bridge_client.py @@ -50,7 +50,8 @@ def test_vehicle_status(self): rospy.init_node('test_node', anonymous=True) msg = rospy.wait_for_message( "/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus, timeout=TIMEOUT) - self.assertNotEqual(msg.header, Header()) # todo: check frame-id + self.assertNotEqual(msg.header, Header()) + self.assertEqual(msg.header.frame_id, 'map') self.assertNotEqual(msg.orientation, Quaternion()) def test_vehicle_info(self): diff --git a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py index 562bb291..a681cf3b 100644 --- a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py +++ b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py @@ -148,7 +148,8 @@ def test_vehicle_status(self, proc_output): node = CompatibleNode('test_node') msg = node.wait_for_one_message( "/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus) - self.assertNotEqual(msg.header, Header()) # todo: check frame-id + self.assertNotEqual(msg.header, Header()) + self.assertEqual(msg.header.frame_id, 'map') self.assertNotEqual(msg.orientation, Quaternion()) finally: if node is not None: From 2917f3a932357d0bec17b1935a469a37facbca3e Mon Sep 17 00:00:00 2001 From: jmagnin Date: Thu, 25 Feb 2021 15:01:47 -0500 Subject: [PATCH 518/627] removed unnecessary comment and memebr variable --- .../src/carla_ackermann_control/carla_ackermann_control_node.py | 2 -- carla_ros_bridge/src/carla_ros_bridge/actor_control.py | 1 - 2 files changed, 3 deletions(-) diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index 92432782..cef8a2d0 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -82,8 +82,6 @@ def __init__(self): callback=self.reconfigure_pid_parameters, ) if ROS_VERSION == 2: - # self.add_on_set_parameters_callback(self.reconfigure_pid_parameters) # works with ros2 foxy - # for ros2 eloquent, deprecated in ros2 foxy self.set_parameters_callback(self.reconfigure_pid_parameters) self.control_loop_rate = self.get_param("control_loop_rate", 0.05) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index 491096cc..8c13655c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -49,7 +49,6 @@ def __init__(self, uid, name, parent, node): self.twist_control_subscriber = self.node.create_subscriber(Twist, self.get_topic_prefix() + "/set_target_velocity", self.on_twist) - self.parent = parent def destroy(self): """ From eaea59407837cee3a068b469e6fbe0cf9eacbfbd Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 25 Feb 2021 15:45:21 -0500 Subject: [PATCH 519/627] Fix code formatting --- carla_ad_agent/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index bb3654fd..5871b5c3 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -23,4 +23,4 @@ if(${ROS_VERSION} EQUAL 1) DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) -endif() \ No newline at end of file +endif() From b3d2008e95f6cd736c9ad01c9d8d26262d16c9bb Mon Sep 17 00:00:00 2001 From: jmagnin Date: Fri, 26 Feb 2021 08:07:41 -0500 Subject: [PATCH 520/627] some readme corrections --- README.md | 29 +++++++++++++++++------------ README.ros.md | 6 ------ ros_compatibility/README.md | 14 ++++++++++++++ 3 files changed, 31 insertions(+), 18 deletions(-) create mode 100644 ros_compatibility/README.md diff --git a/README.md b/README.md index 2cf19ebc..d42851bc 100644 --- a/README.md +++ b/README.md @@ -212,6 +212,17 @@ The tf data for the ego vehicle is published when this pseudo sensor is spawned. | ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | | `/carla/[]/` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaActorList.msg) | list of all carla actors | +##### Actor Control Sensor + +This pseudo-sensor allows to control the position and velocity of the actor it is attached to (e.g. an ego_vehicle) by publishing pose and velocity within Pose and Twist datatypes. +CAUTION: This control method does not respect the vehicle constraints. It allows movements impossible in the real world, like flying or rotating. +Currently this sensor applies the complete linear vector, but only the yaw from angular vector. + +| Topic | Type | Description | +| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | +| `/carla/[]//set_transform` | [geometry_msgs.Pose](https://docs.ros.org/en/api/geometry_msgs/html/msg/Pose.html) | transform to apply to the sensor's parent | +| `/carla/[]//set_target_velocity` | [geometry_msgs.Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | velocity (angular and linear) to apply to the sensor's parent | + ### Ego Vehicle #### Control @@ -239,27 +250,21 @@ Examples for a ego vehicle with role_name 'ego_vehicle': Max forward throttle: + # for ros1 rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 0.0}" -r 10 + # for ros2 + ros2 topic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 0.0}" -r 10 Max forward throttle with max steering to the right: + # for ros1 rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10 + # for ros2 + ros2 topic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10 The current status of the vehicle can be received via topic `/carla//vehicle_status`. Static information about the vehicle can be received via `/carla//vehicle_info` -##### Additional way of controlling - -| Topic | Type | -| ------------------------------------------- | -------------------------------------------------------------------------------- | -| `/carla//twist_cmd` (subscriber) | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | - -CAUTION: This control method does not respect the vehicle constraints. It allows movements impossible in the real world, like flying or rotating. - -You can also control the vehicle via publishing linear and angular velocity within a Twist datatype. - -Currently this method applies the complete linear vector, but only the yaw from angular vector. - ##### Carla Ackermann Control In certain cases, the [Carla Control Command](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) is not ideal to connect to an AD stack. diff --git a/README.ros.md b/README.ros.md index 5a599f56..687b643d 100644 --- a/README.ros.md +++ b/README.ros.md @@ -39,12 +39,6 @@ This will install carla-ros-bridge in /opt/carla-ros-bridge For more information about configuring a ROS environment see -#### Using ROS2 - -In development - -To test the ROS2 implementation, the rmw_fasrtps_cpp RMW implementation should be used. (default with ROS2 standard installation). - ## Start the ROS bridge First run the simulator (see carla documentation: ) diff --git a/ros_compatibility/README.md b/ros_compatibility/README.md new file mode 100644 index 00000000..eb2cc93a --- /dev/null +++ b/ros_compatibility/README.md @@ -0,0 +1,14 @@ +# ROS compatibility node +This acts as an interface over ROS1 and ROS2 to allow nodes to be used seamlessly with both versions. +Depending on the environment variable `ROS_VERSION`, the same api will call either ROS1 or ROS2 functions. +It is used by creating classes that inherit from the `CompatibleNode`. + +## ROS parameters + +By default in ROS2, parameters need to be declared before being set or accessed, which is not the case in ROS1. In order to keep both ROS1 and ROS2 modes working in a similar way, the parameter `allow_undeclared_parameters` is set to True in the ROS2 version of the `CompatibleNode`, allowing to use parameters without declaring them beforehand. + +## Services + +In ROS2 services can be called asynchronously, this is not the case in ROS1. Consequently, the `call_service()` method of the ROS2 version waits for the server's response after calling it asynchronously, in order to mimic the ROS1 synchronous behaviour. + +WARNING: While waiting for the response, the ROS2 `call_service()` methods spins the node. This can cause problems (erors or deadlocks) if another thread spins the same node in parallel. \ No newline at end of file From fc36cda089d7bb2208437663ae720608b07640ee Mon Sep 17 00:00:00 2001 From: Fabian Oboril Date: Mon, 1 Mar 2021 12:30:19 +0100 Subject: [PATCH 521/627] Removed redundant CXX-Standard in CARLA-RViz-Plugin --- rviz_carla_plugin/CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/rviz_carla_plugin/CMakeLists.txt b/rviz_carla_plugin/CMakeLists.txt index 8fe121f9..48c1e54f 100644 --- a/rviz_carla_plugin/CMakeLists.txt +++ b/rviz_carla_plugin/CMakeLists.txt @@ -31,8 +31,6 @@ if(${ROS_VERSION} EQUAL 1) target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) - target_compile_features(${PROJECT_NAME} PRIVATE cxx_std_14) - install( TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} From 2abe54df8fb9ab4dcd4112e3c7e1d529c4046698 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 3 Mar 2021 17:40:03 +0100 Subject: [PATCH 522/627] fixed shutdown bug ros1 --- carla_common/CMakeLists.txt | 6 ------ carla_ros_bridge/src/carla_ros_bridge/bridge.py | 9 ++++----- .../src/ros_compatibility/ros_compatible_node.py | 10 ++++++++++ 3 files changed, 14 insertions(+), 11 deletions(-) diff --git a/carla_common/CMakeLists.txt b/carla_common/CMakeLists.txt index a9ce1205..c3f2a5cc 100644 --- a/carla_common/CMakeLists.txt +++ b/carla_common/CMakeLists.txt @@ -15,10 +15,4 @@ if(${ROS_VERSION} EQUAL 1) catkin_install_python(PROGRAMS src/carla_common/transforms.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) -elseif(${ROS_VERSION} EQUAL 2) - find_package(ament_cmake REQUIRED) - find_package(rclpy REQUIRED) - ament_export_dependencies(rclpy) - ament_package() - endif() diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 73b043a1..60e4ad56 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -14,6 +14,7 @@ CompatibleNode, ros_ok, ros_shutdown, + ros_on_shutdown, ros_timestamp, QoSProfile, latch_on, @@ -63,7 +64,7 @@ class CarlaRosBridge(CompatibleNode): Carla Ros bridge """ - CARLA_VERSION = "0.9.10" + CARLA_VERSION = "0.9.11" # in synchronous mode, if synchronous_mode_wait_for_vehicle_control_command is True, # wait for this time until a next tick is triggered. @@ -80,13 +81,14 @@ def __init__(self, rospy_init=True, executor=None): """ super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) self.executor = executor - self.bridge_is_initialized = False # pylint: disable=attribute-defined-outside-init def initialize_bridge(self, carla_world, params): """ Initialize the bridge """ + ros_on_shutdown(self.destroy) + self.parameters = params self.carla_world = carla_world @@ -183,7 +185,6 @@ def initialize_bridge(self, carla_world, params): self.carla_weather_subscriber = \ self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", self.on_weather_changed, callback_group=self.callback_group) - self.bridge_is_initialized = True def spawn_object(self, req, response=None): response = get_service_response(SpawnObject) @@ -475,8 +476,6 @@ def main(args=None): except KeyboardInterrupt: pass finally: - if carla_bridge.bridge_is_initialized is True: - carla_bridge.destroy() ros_shutdown() del carla_world del carla_client diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index a45abcdd..e5d0e66d 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -33,6 +33,9 @@ def ros_ok(): def ros_shutdown(): pass + def ros_on_shutdown(handler): + rospy.on_shutdown(handler) + def logdebug(log): rospy.logdebug(log) @@ -187,6 +190,8 @@ def on_shutdown(self, handler): from builtin_interfaces.msg import Time latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL + def dummy_handler(): pass + shutdown_handler = dummy_handler def ros_init(args=None): rclpy.init(args=args) @@ -205,8 +210,13 @@ def ros_ok(): return rclpy.ok() def ros_shutdown(): + shutdown_handler() rclpy.shutdown() + def ros_on_shutdown(handler): + global shutdown_handler + shutdown_handler = handler + def logdebug(log): rclpy.logging.get_logger("default").debug(log) From 2a55d48a960f0788130431aa757d9c27ee68d2fb Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 3 Mar 2021 18:11:24 +0100 Subject: [PATCH 523/627] increased timeout destroy service --- .../src/carla_spawn_objects/carla_spawn_objects.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index 27f06532..bceafd20 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -326,7 +326,7 @@ def destroy(self): destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = actor_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.2) + destroy_object_request, timeout_ros2=0.5) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.vehicles_sensors = [] @@ -335,7 +335,7 @@ def destroy(self): destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = actor_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.2) + destroy_object_request, timeout_ros2=0.5) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.global_sensors = [] @@ -344,7 +344,7 @@ def destroy(self): destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = player_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.2) + destroy_object_request, timeout_ros2=0.5) self.loginfo("Object {} successfully destroyed.".format(player_id)) self.players = [] except ServiceException: From a3509d666972ef001c57259fd33703d1a529f2b3 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Wed, 3 Mar 2021 18:40:01 +0100 Subject: [PATCH 524/627] go back to 0.9.10 --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 60e4ad56..27550261 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -64,7 +64,7 @@ class CarlaRosBridge(CompatibleNode): Carla Ros bridge """ - CARLA_VERSION = "0.9.11" + CARLA_VERSION = "0.9.10" # in synchronous mode, if synchronous_mode_wait_for_vehicle_control_command is True, # wait for this time until a next tick is triggered. From 7dbd8da1602da516728db5534c7fe87ff0f48f2a Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 4 Mar 2021 12:17:57 +0100 Subject: [PATCH 525/627] fixed latched topic ros2 --- .../src/carla_twist_to_control/carla_twist_to_control.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index b90eb14b..f101fa49 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -11,6 +11,8 @@ """ from ros_compatibility import ( CompatibleNode, + QoSProfile, + latch_on, ros_ok, ROSException, ROSInterruptException, @@ -57,7 +59,8 @@ def initialize_twist_to_control(self, role_name): sys.exit(0) self.create_subscriber(CarlaEgoVehicleInfo, - "/carla/{}/vehicle_info".format(role_name), self.update_vehicle_info) + "/carla/{}/vehicle_info".format(role_name), self.update_vehicle_info, + qos_profile=QoSProfile(depth=1, durability=latch_on)) self.create_subscriber(Twist, "/carla/{}/twist".format(role_name), self.twist_received) From 00701d2037fe1ccef28d820a11f0f7fa5cfd5164 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 4 Mar 2021 15:27:16 +0100 Subject: [PATCH 526/627] using env variables to detect ros version --- packaging/build-deb.sh | 6 ++---- packaging/install_dependencies.sh | 32 +++++++++++++++---------------- 2 files changed, 17 insertions(+), 21 deletions(-) diff --git a/packaging/build-deb.sh b/packaging/build-deb.sh index b50b70f3..37901bb4 100755 --- a/packaging/build-deb.sh +++ b/packaging/build-deb.sh @@ -5,11 +5,9 @@ set -e SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" BUILD_DIR=${SCRIPT_DIR}/build/$(rosversion -d) WORKSPACE_DIR=${BUILD_DIR}/catkin_ws -ROS_VERSION=$(rosversion -d) -if [ "$ROS_VERSION" = "noetic" -o "$ROS_VERSION" = "foxy" ]; then +PYTHON_SUFFIX="" +if [ "$ROS_PYTHON_VERSION" = "3" ]; then PYTHON_SUFFIX=3 -else - PYTHON_SUFFIX="" fi sudo apt update diff --git a/packaging/install_dependencies.sh b/packaging/install_dependencies.sh index 4d2a82a9..7194e0bd 100755 --- a/packaging/install_dependencies.sh +++ b/packaging/install_dependencies.sh @@ -1,20 +1,18 @@ #!/usr/bin/env bash SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" -ROS_VERSION=$(rosversion -d) -if [ "$ROS_VERSION" = "noetic" -o "$ROS_VERSION" = "foxy" ]; then +PYTHON_SUFFIX="" +if [ "$ROS_PYTHON_VERSION" = "3" ]; then PYTHON_SUFFIX=3 -else - PYTHON_SUFFIX="" fi -if [ "$ROS_VERSION" = "foxy" ]; then - ADDITIONAL_PACKAGES="ros-$ROS_VERSION-rviz2" +if [ "$ROS_VERSION" = "2" ]; then + ADDITIONAL_PACKAGES="ros-$ROS_DISTRO-rviz2" else - ADDITIONAL_PACKAGES="ros-$ROS_VERSION-rviz - ros-$ROS_VERSION-opencv-apps - ros-$ROS_VERSION-rospy-message-converter - ros-$ROS_VERSION-pcl-ros" + ADDITIONAL_PACKAGES="ros-$ROS_DISTRO-rviz + ros-$ROS_DISTRO-opencv-apps + ros-$ROS_DISTRO-rospy-message-converter + ros-$ROS_DISTRO-pcl-ros" fi echo ADDITIONAL PACKAGES $ADDITIONAL_PACKAGES @@ -27,14 +25,14 @@ sudo apt-get install --no-install-recommends -y \ python$PYTHON_SUFFIX-catkin-pkg-modules \ python$PYTHON_SUFFIX-rosdep \ python$PYTHON_SUFFIX-wstool \ - ros-$ROS_VERSION-ackermann-msgs \ - ros-$ROS_VERSION-derived-object-msgs \ - ros-$ROS_VERSION-cv-bridge \ - ros-$ROS_VERSION-vision-opencv \ - ros-$ROS_VERSION-rqt-image-view \ - ros-$ROS_VERSION-rqt-gui-py \ + ros-$ROS_DISTRO-ackermann-msgs \ + ros-$ROS_DISTRO-derived-object-msgs \ + ros-$ROS_DISTRO-cv-bridge \ + ros-$ROS_DISTRO-vision-opencv \ + ros-$ROS_DISTRO-rqt-image-view \ + ros-$ROS_DISTRO-rqt-gui-py \ qt5-default \ - ros-$ROS_VERSION-pcl-conversions \ + ros-$ROS_DISTRO-pcl-conversions \ $ADDITIONAL_PACKAGES pip$PYTHON_SUFFIX install -r $SCRIPT_DIR/../requirements.txt From 9be4c1319cf94852b27e15e7f71b088dd9b5dc2d Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 4 Mar 2021 15:36:50 +0100 Subject: [PATCH 527/627] test ros env variables --- packaging/install_dependencies.sh | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/packaging/install_dependencies.sh b/packaging/install_dependencies.sh index 7194e0bd..a0df295b 100755 --- a/packaging/install_dependencies.sh +++ b/packaging/install_dependencies.sh @@ -1,5 +1,9 @@ #!/usr/bin/env bash +echo "$ROS_VERSION" +echo "$ROS_DISTRO" +echo "$ROS_PYTHON_VERSION" + SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" PYTHON_SUFFIX="" if [ "$ROS_PYTHON_VERSION" = "3" ]; then From bb9cb5d8406c2e85796d74867b1c6427921de6c4 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Thu, 4 Mar 2021 15:42:54 +0100 Subject: [PATCH 528/627] setup updated --- .github/workflows/ci.yml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 793bd522..7d5ac0dc 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -38,12 +38,13 @@ jobs: #TODO: replace ros2 with master rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip unzip ros2.zip -d carla_msgs && rm ros2.zip + source /opt/ros/$(rosversion -d)/setup.bash packaging/install_dependencies.sh - name: ROS2 Build, Test, Lint if: matrix.ros-version == 'foxy' shell: bash run: | - source /opt/ros/$(rosversion -d)/setup.bash + #source /opt/ros/$(rosversion -d)/setup.bash colcon build --continue-on-error # colcon test && colcon test-result source install/setup.bash @@ -56,7 +57,7 @@ jobs: ln -s $GITHUB_WORKSPACE cd .. catkin init - source /opt/ros/$(rosversion -d)/setup.bash + #source /opt/ros/$(rosversion -d)/setup.bash cd $GITHUB_WORKSPACE/../catkin_ws && catkin build --summarize --no-status --force-color catkin run_tests --no-status --force-color && catkin_test_results From fbe59738175e8cfedff4786f4b313d96a179da9d Mon Sep 17 00:00:00 2001 From: joel-mb Date: Thu, 4 Mar 2021 17:23:03 +0100 Subject: [PATCH 529/627] [ROS2] Codacy errors (#493) * fixing codacy errors * removed not needed code --- README.ros.md | 6 ++++-- README.ros2.md | 2 +- .../carla_ros_bridge_with_ackermann_control.launch.py | 2 -- .../carla_ackermann_control_node.py | 4 ---- carla_ad_agent/launch/carla_ad_agent.launch.py | 3 --- carla_ad_agent/src/carla_ad_agent/agent.py | 2 -- carla_ad_agent/src/carla_ad_agent/basic_agent.py | 2 -- carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py | 1 - carla_ad_agent/src/carla_ad_agent/local_planner.py | 4 +--- .../launch/carla_ad_demo_with_scenario.launch.py | 1 - .../src/carla_manual_control/carla_manual_control.py | 6 ++---- carla_ros_bridge/launch/carla_ros_bridge.launch.py | 4 ---- ...arla_ros_bridge_with_example_ego_vehicle.launch.py | 2 -- .../launch/carla_ros_bridge_with_rviz.launch.py | 1 - carla_ros_bridge/src/carla_ros_bridge/actor.py | 2 -- .../src/carla_ros_bridge/actor_factory.py | 4 +--- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 -- carla_ros_bridge/src/carla_ros_bridge/debug_helper.py | 1 - carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 5 ----- carla_ros_bridge/src/carla_ros_bridge/imu.py | 2 -- carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py | 1 - carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py | 3 +-- carla_ros_bridge/test/ros_bridge_client_ros2_test.py | 5 +---- .../launch/carla_ros_scenario_runner.launch.py | 3 --- .../carla_ros_scenario_runner_node.py | 4 ---- .../carla_ros_scenario_runner/ros_vehicle_control.py | 1 - .../launch/carla_example_ego_vehicle.launch.py | 2 -- .../carla_twist_to_control/carla_twist_to_control.py | 11 ----------- .../src/carla_walker_agent/carla_walker_agent.py | 1 - .../launch/carla_waypoint_publisher.launch.py | 3 --- .../carla_waypoint_publisher.py | 1 - packaging/install_dependencies.sh | 2 +- .../src/ros_compatibility/ros_compatible_node.py | 2 -- rqt_carla_control/setup.py | 1 - 34 files changed, 12 insertions(+), 84 deletions(-) diff --git a/README.ros.md b/README.ros.md index 687b643d..92361a3f 100644 --- a/README.ros.md +++ b/README.ros.md @@ -1,5 +1,7 @@ # ROS +## Setup + ### For Users First add the apt repository: @@ -50,11 +52,11 @@ First run the simulator (see carla documentation: export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg -##### For Users +### For Users source /opt/carla-ros-bridge//setup.bash -##### For Developers +### For Developers source ~/carla-ros-bridge/catkin_ws/devel/setup.bash diff --git a/README.ros2.md b/README.ros2.md index a63ca036..e2f480d8 100644 --- a/README.ros2.md +++ b/README.ros2.md @@ -2,7 +2,7 @@ Currently supported: [ROS2 Foxy](https://index.ros.org/doc/ros2/Releases/Release-Foxy-Fitzroy/) -# Setup +## Setup Colcon and ROS2 Foxy need to be installed on your system. diff --git a/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py index 60526c54..ab402129 100644 --- a/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py +++ b/carla_ackermann_control/launch/carla_ros_bridge_with_ackermann_control.launch.py @@ -1,8 +1,6 @@ import os -import sys import launch -import launch_ros.actions from ament_index_python.packages import get_package_share_directory diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index cef8a2d0..e14aee99 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -9,7 +9,6 @@ """ Control Carla ego vehicle by using AckermannDrive messages """ -import os import sys import datetime import numpy @@ -29,10 +28,7 @@ from carla_ackermann_control.cfg import EgoVehicleControlParameterConfig from dynamic_reconfigure.server import Server if ROS_VERSION == 2: - import rclpy - from rclpy.parameter import Parameter from rcl_interfaces.msg import SetParametersResult - from typing import Sequence class CarlaAckermannControl(CompatibleNode): diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index fe7179f7..2c8c0db4 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -1,6 +1,3 @@ -import os -import sys - import launch import launch_ros.actions diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index bcaf4616..a2f9b2f8 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -13,7 +13,6 @@ from carla_msgs.msg import CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus # pylint: disable=import-error from nav_msgs.msg import Odometry -from geometry_msgs.msg import Point from visualization_msgs.msg import Marker from enum import Enum import math @@ -22,7 +21,6 @@ from ros_compatibility import ( ros_ok, ServiceException, - ROSInterruptException, QoSProfile, latch_on, get_service_request, diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py index f725da40..009375e3 100644 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -13,12 +13,10 @@ from carla_waypoint_types.srv import GetActorWaypoint # pylint: disable=import-error from carla_msgs.msg import CarlaActorList # pylint: disable=import-error from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error -from geometry_msgs.msg import Pose # pylint: disable=import-error import math from ros_compatibility import ( ros_ok, ServiceException, - ROSInterruptException, QoSProfile, latch_on, get_service_request, diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py index d98759c4..f78ef18f 100755 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -26,7 +26,6 @@ ros_shutdown) if ROS_VERSION == 1: - import rospy # TODO: different ways to import the carla_ad_agent submodules (e.g. carla_ad_agent.basic_agent) between ros1 and ros2 shouldn't be necessary from basic_agent import BasicAgent elif ROS_VERSION == 2: diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index d3e78eb0..341edc6f 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -11,13 +11,11 @@ """ from collections import deque -from geometry_msgs.msg import PointStamped, Pose # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error -from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION, ros_ok +from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION from nav_msgs.msg import Path from nav_msgs.msg import Odometry from std_msgs.msg import Float64 -from threading import Thread import time import math from visualization_msgs.msg import Marker diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index 6421a2a8..eedac67d 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -1,5 +1,4 @@ import os -import sys import launch import launch_ros.actions diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 32d78aae..4b53a0bc 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -46,13 +46,11 @@ loginfo, logwarn, ROS_VERSION) -import os import datetime import math import numpy if ROS_VERSION == 1: - import rospy from rospy import Time from tf import LookupException from tf import ConnectivityException @@ -68,8 +66,8 @@ from tf2_ros import ConnectivityException from tf2_ros import ExtrapolationException import tf2_ros - from rclpy.qos import QoSProfile, QoSDurabilityPolicy - from threading import Thread, Lock, Event + from rclpy.qos import QoSProfile + from threading import Thread from builtin_interfaces.msg import Time else: raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch.py b/carla_ros_bridge/launch/carla_ros_bridge.launch.py index 6e2ae1f5..9a8e9891 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch.py @@ -1,9 +1,5 @@ -import os -import sys - import launch import launch_ros.actions -from ament_index_python.packages import get_package_share_directory def generate_launch_description(): diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py index 938d56a4..ca07156d 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py @@ -1,8 +1,6 @@ import os -import sys import launch -import launch_ros.actions from ament_index_python.packages import get_package_share_directory diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py index d1b092a0..25f248bf 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py @@ -1,5 +1,4 @@ import os -import sys import launch import launch_ros.actions diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 03169895..471b724e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -11,8 +11,6 @@ """ from geometry_msgs.msg import TransformStamped # pylint: disable=import-error -from visualization_msgs.msg import Marker # pylint: disable=import-error -from std_msgs.msg import ColorRGBA # pylint: disable=import-error from carla_ros_bridge.pseudo_actor import PseudoActor import carla_common.transforms as trans diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 082a8160..03a18321 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -6,7 +6,6 @@ # For a copy, see . # -from ros_compatibility import ROS_VERSION import time from threading import Thread, Lock import itertools @@ -45,7 +44,6 @@ import carla_common.transforms as trans import carla import numpy as np -from geometry_msgs.msg import Pose, Quaternion, Point # to generate a random spawning position or vehicles import random @@ -154,7 +152,7 @@ def spawn_actor(self, req): """ spawns an object - No object instances are created here. Instead carla-actors are created, + No object instances are created here. Instead carla-actors are created, and pseudo objects are appended to a list to get created later. """ with self.spawn_lock: diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 27550261..1065b89d 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -27,7 +27,6 @@ except ImportError: import Queue as queue -import os import sys from distutils.version import LooseVersion from threading import Thread, Lock, Event @@ -49,7 +48,6 @@ if ROS_VERSION == 1: import rospy # pylint: disable=import-error - from carla_msgs.srv import SpawnObjectResponse, DestroyObjectResponse, GetBlueprintsResponse elif ROS_VERSION == 2: import rclpy # pylint: disable=import-error from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 48e9b048..75e4860b 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -15,7 +15,6 @@ import carla from transforms3d.euler import quat2euler -from ros_compatibility import CompatibleNode ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 28a82576..2261c67e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -15,8 +15,6 @@ from std_msgs.msg import Bool # pylint: disable=import-error from std_msgs.msg import ColorRGBA # pylint: disable=import-error from carla import VehicleControl -from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleStatus # pylint: disable=import-error from carla_ros_bridge.vehicle import Vehicle from carla_msgs.msg import ( @@ -32,9 +30,6 @@ ROS_VERSION ) -if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error - class EgoVehicle(Vehicle): diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 32e68af3..4c90eef4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -7,8 +7,6 @@ Classes to handle Carla imu sensor """ -import math - from sensor_msgs.msg import Imu from carla_ros_bridge.sensor import Sensor diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index b3bc9338..c1aa6abc 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -12,7 +12,6 @@ from std_msgs.msg import Header from ros_compatibility import ( - CompatibleNode, ros_timestamp, QoSProfile, latch_on diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index ad35b086..7a4b7789 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -12,8 +12,7 @@ import tf2_ros import os from carla_ros_bridge.pseudo_actor import PseudoActor -from ros_compatibility import ros_timestamp -from geometry_msgs.msg import TransformStamped, Transform +from geometry_msgs.msg import TransformStamped ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) diff --git a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py index a681cf3b..5ce94562 100644 --- a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py +++ b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py @@ -6,11 +6,8 @@ # For a copy, see . # import os -import sys import unittest -import ament_index_python - import launch import launch.actions @@ -26,7 +23,7 @@ from geometry_msgs.msg import Quaternion, Vector3, Pose from nav_msgs.msg import Odometry from derived_object_msgs.msg import ObjectArray -from visualization_msgs.msg import Marker, MarkerArray +from visualization_msgs.msg import MarkerArray from carla_msgs.msg import (CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaWorldInfo, CarlaActorList, CarlaTrafficLightStatusList, CarlaTrafficLightInfoList) diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py index c9255fa7..21355532 100644 --- a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch.py @@ -1,6 +1,3 @@ -import os -import sys - import launch import launch_ros.actions diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py index 16f90afd..d1c1894b 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py @@ -16,9 +16,6 @@ import queue except ImportError: import Queue as queue -from geometry_msgs.msg import PoseStamped -from nav_msgs.msg import Path -from std_msgs.msg import Float64 from carla_ros_scenario_runner_types.srv import ExecuteScenario from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus from carla_ros_scenario_runner.application_runner import ApplicationStatus # pylint: disable=relative-import @@ -51,7 +48,6 @@ sys.exit(1) if ROS_VERSION == 2: - import rclpy import threading diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 12da739b..c89f0b00 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -25,7 +25,6 @@ import roslaunch elif ROS_VERSION == 2: from carla_ros_scenario_runner.application_runner import ApplicationRunner - import rclpy class RosVehicleControl(BasicControl): diff --git a/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py b/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py index 6c469a68..d5563b5d 100644 --- a/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py +++ b/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py @@ -1,8 +1,6 @@ import os -import sys import launch -import launch_ros.actions from ament_index_python.packages import get_package_share_directory diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index f101fa49..d35ae514 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -47,17 +47,6 @@ def __init__(self, rospy_init=True): self.max_steering_angle = None def initialize_twist_to_control(self, role_name): - if ROS_VERSION == 1: - self.loginfo("Wait for vehicle info...") - try: - vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), - CarlaEgoVehicleInfo) - except ROSInterruptException as e: - if ros_ok: - raise e - else: - sys.exit(0) - self.create_subscriber(CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(role_name), self.update_vehicle_info, qos_profile=QoSProfile(depth=1, durability=latch_on)) diff --git a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py index de2a5c99..7ad24620 100755 --- a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py +++ b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py @@ -27,7 +27,6 @@ import rospy elif ROS_VERSION == 2: import time - import rclpy import threading diff --git a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py index 887af064..02800af9 100644 --- a/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py +++ b/carla_waypoint_publisher/launch/carla_waypoint_publisher.launch.py @@ -1,6 +1,3 @@ -import os -import sys - import launch import launch_ros.actions diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index bff4b888..639aca8a 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -20,7 +20,6 @@ import math import sys import threading -import os from ros_compatibility import (CompatibleNode, QoSProfile, diff --git a/packaging/install_dependencies.sh b/packaging/install_dependencies.sh index 4d2a82a9..18c4c2c3 100755 --- a/packaging/install_dependencies.sh +++ b/packaging/install_dependencies.sh @@ -16,7 +16,7 @@ else ros-$ROS_VERSION-rospy-message-converter ros-$ROS_VERSION-pcl-ros" fi -echo ADDITIONAL PACKAGES $ADDITIONAL_PACKAGES +echo "ADDITIONAL PACKAGES $ADDITIONAL_PACKAGES" sudo apt update sudo apt-get install --no-install-recommends -y \ diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index e5d0e66d..18f6a8a9 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -1,6 +1,5 @@ # pylint: disable=import-error import os -from threading import Thread, currentThread ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -15,7 +14,6 @@ raise NotImplementedError('Make sure you have valid ROS_VERSION env variable.') if ROS_VERSION == 1: - import tf.transformations as trans latch_on = True diff --git a/rqt_carla_control/setup.py b/rqt_carla_control/setup.py index 3a9c2b47..3a5846ac 100755 --- a/rqt_carla_control/setup.py +++ b/rqt_carla_control/setup.py @@ -5,7 +5,6 @@ Setup for rqt_carla_control """ import os -from glob import glob ROS_VERSION = int(os.environ['ROS_VERSION']) if ROS_VERSION == 1: From 20c56800beb2032c7b8e79b835c53c7465633c1c Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 10:45:42 +0100 Subject: [PATCH 530/627] test env variables --- .github/workflows/ci.yml | 122 ++++++++++++++++++++++----------------- 1 file changed, 69 insertions(+), 53 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 7d5ac0dc..2d8c65c6 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -6,65 +6,81 @@ jobs: check: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 - - name: Set up Python 3.8 - uses: actions/setup-python@v1 - with: - python-version: 3.8 - - name: Install dependencies - run: | - python -m pip install --upgrade pip - pip install -r requirements.txt - - name: Check - run: make check_format + - uses: actions/checkout@v2 + - name: Set up Python 3.8 + uses: actions/setup-python@v1 + with: + python-version: 3.8 + - name: Install dependencies + run: | + python -m pip install --upgrade pip + pip install -r requirements.txt + - name: Check + run: make check_format ros: runs-on: ubuntu-latest - container: ros:${{ matrix.ros-version }} strategy: matrix: - ros-version: [melodic-robot, noetic-robot, foxy] + include: + - docker_image: melodic-robot + ros_distro: melodic + ros_python_version: 2 + ros_version: 1 + + - docker_image: noetic-robot + ros_distro: noetic + ros_python_version: 3 + ros_version: 1 + + - docker_image: foxy + ros_distro: melodic + ros_python_version: 3 + ros_version: 2 + container: + image: ros:${{ matrix.docker_image }} env: SCENARIO_RUNNER_PATH: "" DEBIAN_FRONTEND: "noninteractive" + ROS_DISTRO: ${{ matrix.ros_distro }} + ROS_VERSION: ${{ matrix.ros_version }} + ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} steps: - - uses: actions/checkout@v2 - # TODO cleaner solution but currently not working because git version is below 2.18 - # with: - # submodules: true - - name: Setup - run: | - sudo apt-get update && sudo apt-get install wget unzip -y - #TODO: replace ros2 with master - rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip - unzip ros2.zip -d carla_msgs && rm ros2.zip - source /opt/ros/$(rosversion -d)/setup.bash - packaging/install_dependencies.sh - - name: ROS2 Build, Test, Lint - if: matrix.ros-version == 'foxy' - shell: bash - run: | - #source /opt/ros/$(rosversion -d)/setup.bash - colcon build --continue-on-error - # colcon test && colcon test-result - source install/setup.bash - - name: ROS1 Build, Test, Lint - if: matrix.ros-version != 'foxy' - shell: bash - run: | - mkdir -p $GITHUB_WORKSPACE/../catkin_ws/src - cd $GITHUB_WORKSPACE/../catkin_ws/src - ln -s $GITHUB_WORKSPACE - cd .. - catkin init - #source /opt/ros/$(rosversion -d)/setup.bash - cd $GITHUB_WORKSPACE/../catkin_ws && - catkin build --summarize --no-status --force-color - catkin run_tests --no-status --force-color && catkin_test_results - source devel/setup.bash - cd $GITHUB_WORKSPACE - # make pylint - # TODO enable pylint + - uses: actions/checkout@v2 + with: + submodules: true + - name: Setup + run: | + #sudo apt-get update && sudo apt-get install wget unzip -y + #TODO: replace ros2 with master + #rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip + #unzip ros2.zip -d carla_msgs && rm ros2.zip + packaging/install_dependencies.sh + - name: ROS2 Build, Test, Lint + if: matrix.ros-version == 'foxy' + shell: bash + run: | + source /opt/ros/$(rosversion -d)/setup.bash + colcon build --continue-on-error + # colcon test && colcon test-result + source install/setup.bash + - name: ROS1 Build, Test, Lint + if: matrix.ros-version != 'foxy' + shell: bash + run: | + mkdir -p $GITHUB_WORKSPACE/../catkin_ws/src + cd $GITHUB_WORKSPACE/../catkin_ws/src + ln -s $GITHUB_WORKSPACE + cd .. + catkin init + source /opt/ros/$(rosversion -d)/setup.bash + cd $GITHUB_WORKSPACE/../catkin_ws && + catkin build --summarize --no-status --force-color + catkin run_tests --no-status --force-color && catkin_test_results + source devel/setup.bash + cd $GITHUB_WORKSPACE + # make pylint + # TODO enable pylint debian: runs-on: ubuntu-latest @@ -76,6 +92,6 @@ jobs: SCENARIO_RUNNER_PATH: "" DEBIAN_FRONTEND: "noninteractive" steps: - - uses: actions/checkout@v2 - - name: Build Debian Package - run: packaging/build-deb.sh + - uses: actions/checkout@v2 + - name: Build Debian Package + run: packaging/build-deb.sh From 069db53b394e83ad0884b63e4c8d7754dae960be Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 10:49:21 +0100 Subject: [PATCH 531/627] WIP: deb env variables --- .github/workflows/ci.yml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 2d8c65c6..ec83963d 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -47,14 +47,15 @@ jobs: ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} steps: - uses: actions/checkout@v2 - with: - submodules: true + #with: + # submodules: true - name: Setup run: | #sudo apt-get update && sudo apt-get install wget unzip -y #TODO: replace ros2 with master #rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip #unzip ros2.zip -d carla_msgs && rm ros2.zip + git submodule update --init packaging/install_dependencies.sh - name: ROS2 Build, Test, Lint if: matrix.ros-version == 'foxy' From 196e6422fb851870accecb709d3906f6ed2c6e35 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 10:51:04 +0100 Subject: [PATCH 532/627] WIP: deb env variables --- .github/workflows/ci.yml | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index ec83963d..e200fa16 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -51,11 +51,10 @@ jobs: # submodules: true - name: Setup run: | - #sudo apt-get update && sudo apt-get install wget unzip -y + sudo apt-get update && sudo apt-get install wget unzip -y #TODO: replace ros2 with master - #rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip - #unzip ros2.zip -d carla_msgs && rm ros2.zip - git submodule update --init + rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip + unzip ros2.zip -d carla_msgs && rm ros2.zip packaging/install_dependencies.sh - name: ROS2 Build, Test, Lint if: matrix.ros-version == 'foxy' From dbfcae262ae3fc9caf7b90a830a429301b098683 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 10:55:00 +0100 Subject: [PATCH 533/627] WIP: minor fixes --- .github/workflows/ci.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index e200fa16..9dd1ff9c 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -34,7 +34,7 @@ jobs: ros_version: 1 - docker_image: foxy - ros_distro: melodic + ros_distro: foxy ros_python_version: 3 ros_version: 2 container: @@ -57,7 +57,7 @@ jobs: unzip ros2.zip -d carla_msgs && rm ros2.zip packaging/install_dependencies.sh - name: ROS2 Build, Test, Lint - if: matrix.ros-version == 'foxy' + if: ${{ matrix.ros_version == 2 }} shell: bash run: | source /opt/ros/$(rosversion -d)/setup.bash @@ -65,7 +65,7 @@ jobs: # colcon test && colcon test-result source install/setup.bash - name: ROS1 Build, Test, Lint - if: matrix.ros-version != 'foxy' + if: ${{ matrix.ros_version == 1 }} shell: bash run: | mkdir -p $GITHUB_WORKSPACE/../catkin_ws/src From f41b6895871290f61f3f3ac90f9f27a04b38818e Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 12:53:37 +0100 Subject: [PATCH 534/627] only enabling melodic deb packages --- .github/workflows/ci.yml | 14 +++++++++++--- Makefile | 3 +++ packaging/build-deb.sh | 11 ++++++++--- packaging/install_dependencies.sh | 4 ---- 4 files changed, 22 insertions(+), 10 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 9dd1ff9c..0a6c1a35 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -84,14 +84,22 @@ jobs: debian: runs-on: ubuntu-latest - container: ros:${{ matrix.ros-version }} strategy: matrix: - ros-version: [melodic-robot, noetic-robot, foxy] + include: + - docker_image: melodic-robot + ros_distro: melodic + ros_python_version: 2 + ros_version: 1 + container: + image: ros:${{ matrix.docker_image }} env: SCENARIO_RUNNER_PATH: "" DEBIAN_FRONTEND: "noninteractive" + ROS_DISTRO: ${{ matrix.ros_distro }} + ROS_VERSION: ${{ matrix.ros_version }} + ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} steps: - uses: actions/checkout@v2 - name: Build Debian Package - run: packaging/build-deb.sh + run: make deb diff --git a/Makefile b/Makefile index 42258c95..45c8a962 100644 --- a/Makefile +++ b/Makefile @@ -15,3 +15,6 @@ check_format: pylint: $(PY_FILES) | xargs pylint --rcfile=.pylintrc + +deb: + ./packaging/build-deb.sh diff --git a/packaging/build-deb.sh b/packaging/build-deb.sh index 37901bb4..6da59b34 100755 --- a/packaging/build-deb.sh +++ b/packaging/build-deb.sh @@ -2,9 +2,14 @@ set -e +if [ "${ROS_VERSION}" != "1" ]; then + echo "Only ROS1 packages are supported" + exit 1 +fi + SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" -BUILD_DIR=${SCRIPT_DIR}/build/$(rosversion -d) -WORKSPACE_DIR=${BUILD_DIR}/catkin_ws +BUILD_DIR=${PWD}/build/$(rosversion -d) +WORKSPACE_DIR=${BUILD_DIR}/ws PYTHON_SUFFIX="" if [ "$ROS_PYTHON_VERSION" = "3" ]; then PYTHON_SUFFIX=3 @@ -25,7 +30,7 @@ mkdir -p ${BUILD_DIR} ${WORKSPACE_DIR} rsync -r ${SCRIPT_DIR}/../* ${WORKSPACE_DIR}/src --exclude packaging # init ros workspace source /opt/ros/$(rosversion -d)/setup.bash -cd ${WORKSPACE_DIR} && catkin init +cd ${WORKSPACE_DIR} && catkin_init_workspace # add debian files cp -r ${SCRIPT_DIR}/debian ${WORKSPACE_DIR} sed -i "s/{ROS_DIST}/$(rosversion -d)/g" ${WORKSPACE_DIR}/debian/control diff --git a/packaging/install_dependencies.sh b/packaging/install_dependencies.sh index a0df295b..7194e0bd 100755 --- a/packaging/install_dependencies.sh +++ b/packaging/install_dependencies.sh @@ -1,9 +1,5 @@ #!/usr/bin/env bash -echo "$ROS_VERSION" -echo "$ROS_DISTRO" -echo "$ROS_PYTHON_VERSION" - SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" PYTHON_SUFFIX="" if [ "$ROS_PYTHON_VERSION" = "3" ]; then From 51186d6ef32426ba86357c65963b575779e17f6d Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 13:04:34 +0100 Subject: [PATCH 535/627] disabled debian package on ci --- .github/workflows/ci.yml | 47 ++++++++++++++++++++-------------------- 1 file changed, 24 insertions(+), 23 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 0a6c1a35..20d41fed 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -47,8 +47,9 @@ jobs: ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} steps: - uses: actions/checkout@v2 - #with: - # submodules: true + # TODO cleaner solution but currently not working because git version is below 2.18 + # with: + # submodules: true - name: Setup run: | sudo apt-get update && sudo apt-get install wget unzip -y @@ -82,24 +83,24 @@ jobs: # make pylint # TODO enable pylint - debian: - runs-on: ubuntu-latest - strategy: - matrix: - include: - - docker_image: melodic-robot - ros_distro: melodic - ros_python_version: 2 - ros_version: 1 - container: - image: ros:${{ matrix.docker_image }} - env: - SCENARIO_RUNNER_PATH: "" - DEBIAN_FRONTEND: "noninteractive" - ROS_DISTRO: ${{ matrix.ros_distro }} - ROS_VERSION: ${{ matrix.ros_version }} - ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} - steps: - - uses: actions/checkout@v2 - - name: Build Debian Package - run: make deb + # debian: + # runs-on: ubuntu-latest + # strategy: + # matrix: + # include: + # - docker_image: melodic-robot + # ros_distro: melodic + # ros_python_version: 2 + # ros_version: 1 + # container: + # image: ros:${{ matrix.docker_image }} + # env: + # SCENARIO_RUNNER_PATH: "" + # DEBIAN_FRONTEND: "noninteractive" + # ROS_DISTRO: ${{ matrix.ros_distro }} + # ROS_VERSION: ${{ matrix.ros_version }} + # ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} + # steps: + # - uses: actions/checkout@v2 + # - name: Build Debian Package + # run: make deb From 3daca98ace807a56f1d77bb39f15733a12688da6 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 13:32:59 +0100 Subject: [PATCH 536/627] fixed package name rviz --- .../launch/carla_ros_bridge_with_rviz.launch.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py index 25f248bf..9f88c44b 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py @@ -8,9 +8,9 @@ def generate_launch_description(): ld = launch.LaunchDescription([ launch_ros.actions.Node( - package='rviz', - executable='rviz', - name='rviz' + package='rviz2', + executable='rviz2', + name='rviz2' ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( From 969e78c2d97cbdd3c1fe540baca03e09f344df3f Mon Sep 17 00:00:00 2001 From: Erkan Adali Date: Fri, 5 Mar 2021 15:41:34 +0200 Subject: [PATCH 537/627] added manual_gear_shift and gear field to ego control message --- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index d449afc3..1ed591ad 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -225,6 +225,8 @@ def control_command_updated(self, ros_vehicle_control, manual_override): vehicle_control.steer = ros_vehicle_control.steer vehicle_control.throttle = ros_vehicle_control.throttle vehicle_control.reverse = ros_vehicle_control.reverse + vehicle_control.manual_gear_shift = ros_vehicle_control.manual_gear_shift + vehicle_control.gear = ros_vehicle_control.gear self.carla_actor.apply_control(vehicle_control) self._vehicle_control_applied_callback(self.get_id()) From 864544fc074313f653314cbd1e28109b4ce971c6 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Fri, 5 Mar 2021 17:34:04 +0100 Subject: [PATCH 538/627] Added the initial files for ROS documentation as a sub project of CARLA --- .readthedocs.yml | 14 ++ docs/carla_ackermann_control.md | 69 ++++++ docs/carla_manual_control.md | 67 ++++++ docs/carla_spawn_objects.md | 142 ++++++++++++ docs/extra.css | 246 +++++++++++++++++++++ docs/images/docs_version_panel.jpg | Bin 0 -> 1654 bytes docs/images/ros_rviz.png | Bin 0 -> 86433 bytes docs/images/rqt_plugin.png | Bin 0 -> 4685 bytes docs/images/rviz_set_start_goal.png | Bin 14565 -> 6600 bytes docs/index.md | 35 +++ docs/requirements.txt | 1 + docs/ros_installation_ros1.md | 192 ++++++++++++++++ docs/ros_installation_ros2.md | 134 +++++++++++ docs/ros_msgs.md | 331 ++++++++++++++++++++++++++++ docs/ros_packages.md | 44 ++++ docs/ros_sensors.md | 138 ++++++++++++ docs/rqt_plugin.md | 11 + docs/run_ros.md | 174 +++++++++++++++ docs/rviz_plugin.md | 94 ++++++++ mkdocs.yml | 26 +++ 20 files changed, 1718 insertions(+) create mode 100644 .readthedocs.yml create mode 100644 docs/carla_ackermann_control.md create mode 100644 docs/carla_manual_control.md create mode 100644 docs/carla_spawn_objects.md create mode 100644 docs/extra.css create mode 100644 docs/images/docs_version_panel.jpg create mode 100644 docs/images/ros_rviz.png create mode 100644 docs/images/rqt_plugin.png mode change 100755 => 100644 docs/images/rviz_set_start_goal.png create mode 100644 docs/index.md create mode 100644 docs/requirements.txt create mode 100644 docs/ros_installation_ros1.md create mode 100644 docs/ros_installation_ros2.md create mode 100644 docs/ros_msgs.md create mode 100644 docs/ros_packages.md create mode 100644 docs/ros_sensors.md create mode 100644 docs/rqt_plugin.md create mode 100644 docs/run_ros.md create mode 100644 docs/rviz_plugin.md create mode 100644 mkdocs.yml diff --git a/.readthedocs.yml b/.readthedocs.yml new file mode 100644 index 00000000..a76d3307 --- /dev/null +++ b/.readthedocs.yml @@ -0,0 +1,14 @@ +# Read the Docs configuration file +# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details + +version: 2 + +mkdocs: + configuration: mkdocs.yml + +formats: all + +python: + version: 3.7 + install: + - requirements: docs/requirements.txt diff --git a/docs/carla_ackermann_control.md b/docs/carla_ackermann_control.md new file mode 100644 index 00000000..1ab8f130 --- /dev/null +++ b/docs/carla_ackermann_control.md @@ -0,0 +1,69 @@ +# Carla Ackermann Control + +The `carla_ackermann_control` package is used to control a CARLA vehicle with [Ackermann messages][ackermanncontrolmsg]. The package converts the Ackermann messages into [CarlaEgoVehicleControl][carlaegovehiclecontrolmsg] messages. It reads vehicle information from CARLA and passes that information to a Python based PID controller called `simple-pid` to control the acceleration and velocity. + +[ackermanncontrolmsg]: https://docs.ros.org/en/api/ackermann_msgs/html/msg/AckermannDrive.html +[carlaegovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#carlaegovehiclecontrolmsg + +- [__Install the PID controller library__](#install-the-pid-controller-library) +- [__Configuration__](#configuration) +- [__Available Topics__](#available-topics) +- [__Testing control messages__](#testing-control-messages) +--- + +### Install the PID controller library + +Install the PID controller: +``` +python3 -m pip install simple-pid +``` + +--- + +### Configuration + +Parameters can be set both initially in a [configuration file][ackermanconfig] and during runtime via ROS [dynamic reconfigure][rosdynamicreconfig]. + +[ackermanconfig]: https://github.com/carla-simulator/ros-bridge/blob/master/carla_ackermann_control/config/settings.yaml +[rosdynamicreconfig]: https://wiki.ros.org/dynamic_reconfigure + +--- + +### Available topics + +|Topic|Type|Description| +|--|--|--| +|`/carla//ackermann_cmd` | [ackermann_msgs.AckermannDrive][ackermanncontrolmsg] | __Subscriber__ for steering commands | +| `/carla//ackermann_control/control_info` | [carla_ackermann_control.EgoVehicleControlInfo][egovehiclecontrolmsg] | The current values used within the controller (useful for debugging) | + +[egovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#egovehiclecontrolinfomsg + +
+ +--- + +### Testing control messages + +Test the setup by sending commands to the car via the topic `/carla//ackermann_cmd`. For example, move an ego vehicle with the role name of `ego_vehicle` forward at a speed of 10 meters/sec by running this command: + +```bash + +# ROS 1 +rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0.0, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10 + +# ROS 2 +ros2 topic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0.0, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10 + +``` + +Or make the vehicle move forward while turning at an angle of 1.22 radians: + +```bash + +# ROS 1 +rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 1.22, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10 + +# ROS 2 +ros2 topic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 1.22, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10 + +``` diff --git a/docs/carla_manual_control.md b/docs/carla_manual_control.md new file mode 100644 index 00000000..aa944b80 --- /dev/null +++ b/docs/carla_manual_control.md @@ -0,0 +1,67 @@ +# Carla Manual Control + +This package is a ROS only version of the [`manual_control.py`][manualcontrol] script that comes packaged with CARLA. All data is received via ROS topics. + +[manualcontrol]: https://github.com/carla-simulator/carla/blob/master/PythonAPI/examples/manual_control.py + +- [__Requirements__](#requirements) +- [__Run the package__](#run-the-package) +--- + +## Requirements + +To be able to use `carla_manual_control`, some specific sensors need to be attached to the ego vehicle (see [Carla Spawn Objects](carla_spawn_objects.md) for information on how to attach sensors to vehicles): + +- __to display an image__: a camera with role-name 'view' and resolution 800x600 +- __to display the current GNSS position__: a GNSS sensor with role-name 'gnss1' +- __to get a notification on lane invasions__: a lane invasion sensor +- __to get a notification on collisons__: a collision sensor + +--- + +## Run the package + +To run the package: + +__ 1.__ Make sure you have CARLA runing. Start the ROS bridge: + +```sh + # ROS 1 + roslaunch carla_ros_bridge carla_ros_bridge.launch + + # ROS 2 + ros2 launch carla_ros_bridge carla_ros_bridge.launch.py +``` + +__2.__ Spawn objects: + +```sh + # ROS 1 + roslaunch carla_spawn_objects carla_spawn_objects.launch + + # ROS 2 + ros2 launch carla_spawn_objects carla_spawn_objects.launch.py +``` + +__3.__ Launch the `carla_manual_control` node: + +```sh + # ROS 1 + roslaunch carla_manual_control carla_manual_control.launch + + # ROS 2 + ros2 launch carla_manual_control carla_manual_control.launch.py +``` + +__4.__ To steer the vehicle manually, press 'B'. Press 'H' to see instructions. + +All of the above commands are also combined into one single launchfile and can be run at the same time by executing the following: + +```sh + # ROS 1 + roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch + + # ROS 2 + ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py +``` +--- \ No newline at end of file diff --git a/docs/carla_spawn_objects.md b/docs/carla_spawn_objects.md new file mode 100644 index 00000000..4b7b7266 --- /dev/null +++ b/docs/carla_spawn_objects.md @@ -0,0 +1,142 @@ +# Carla Spawn Objects + +The `carla_spawn_objects` package is used to spawn actors (vehicles, sensors, walkers) and to attach sensors to them. + +- [__Configuration and sensor setup__](#configuration-and-sensor-setup) + - [Create the configuration](#create-the-configuration) +- [__Spawning Vehicles__](#spawning-vehicles) + - [Respawning vehicles](#respawning-vehicles) +- [__Spawning Sensors__](#spawning-sensors) + - [Attach sensors to an existing vehicle](#attach-sensors-to-an-existing-vehicle) + +--- + +## Configuration and sensor setup + +Objects and their attached sensors are defined through a `.json` file. The default location of this file is within `carla_spawn_objects/config/objects.json`. To change the location, pass the path to the file via the private ROS parameter, `objects_definition_file`, when you launch the package: + +```sh + # ROS 1 + roslaunch carla_spawn_objects carla_spawn_objects.launch objects_definition_file:=path/to/objects.json + + # ROS 2 + ros2 launch carla_spawn_objects carla_spawn_objects.launch.py objects_definition_file:=path/to/objects.json +``` + + +### Create the configuration + +You can find an example in the [ros-bridge repository][objectsjson] as well as follow this outline to create your own configuration and sensor setup: + +```json +{ +"objects": + [ + { + "type": "", + "id": "", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + + }, + { + "type": "", + "id": "", + "spawn_point": {"x": -11.1, "y": 138.5, "z": 0.2, "roll": 0.0, "pitch": 0.0, "yaw": -178.7}, + "sensors": + [ + + ] + } + ... + ] +} +``` + + +!!! Note + Remember when directly defining positions that ROS uses a [right hand system](https://www.ros.org/reps/rep-0103.html#chirality) + +All sensor attributes are defined as described in the [blueprint library](https://carla.readthedocs.io/en/latest/bp_library/). + +[objectsjson]: https://github.com/carla-simulator/ros-bridge/blob/master/carla_spawn_objects/config/objects.json + +--- + +## Spawning vehicles + +- If no specific spawn point is defined, vehicles will be spawned at a random location. +- To define the position at which a vehicle will be spawned, there are two choices: + + - Pass the desired position to a ROS parameter `spawn_point_`. `` will be the `id` you gave the vehicle in the `.json` file: + + # ROS 1 + roslaunch carla_spawn_objects carla_spawn_objects.launch spawn_point_:=x,y,z,roll,pitch,yaw + + # ROS 2 + ros2 launch carla_spawn_objects carla_spawn_objects.launch.py spawn_point_:=x,y,z,roll,pitch,yaw + + - Define the initial position directly in the `.json` file: + + { + "type": "vehicle.*", + "id": "ego_vehicle", + "spawn_point": {"x": -11.1, "y": 138.5, "z": 0.2, "roll": 0.0, "pitch": 0.0, "yaw": -178.7}, + } + +### Respawning vehicles + +A vehicle can be respawned to a different location during a simulation by publishing to the topic `/carla///initialpose`. To use this functionality: + +1. Attach an `actor.pseudo.control` pseudo-actor to the vehicle in the `.json` file. It should have the same `id` value as the value passed as `` used to publish to the topic: + + { + "type": "vehicle.*", + "id": "ego_vehicle", + "sensors": + [ + { + "type": "actor.pseudo.control", + "id": "control" + } + ] + } + +2. Launch the `set_inital_pose` node, passing the `` as an argument to the ROS parameter `controller_id` (default = 'control'): + + roslaunch carla_spawn_objects set_initial_pose.launch controller_id:= + +3. The preferred way to publish the message to set the new position is by using the __2D Pose Estimate__ button available in the RVIZ interface. You can then click on the viewport of the map to respawn in that position. This will delete the current `ego_vehicle` and respawn it at the specified position. + +> ![rviz_set_start_goal](images/rviz_set_start_goal.png) + +--- + +## Spawning Sensors + +- The initial position for a sensor should be defined directly in the `.json` file, as shown above for vehicles. +- The spawn point for a sensor attached to a vehicle is considered relative to the vehicle. + +### Attach sensors to an existing vehicle + +Sensors can be attached to an already existing vehicle. To do so: + +1. Define the pseudo sensor `sensor.pseudo.actor_list` in the `.json` file. This will give access to a list of already existing actors. + + ... + { + "type": "sensor.pseudo.actor_list", + "id": "actor_list" + }, + +2. Define the rest of the sensors as required. +3. Launch the node with the `spawn_sensors_only` parameter set to True. This will check if an actor with the same `id` and `type` as the one specified in the `.json` file is already active and if so, attach the sensors to this actor. + + # ROS 1 + roslaunch carla_spawn_objects carla_spawn_objects.launch spawn_sensors_only:=True + + # ROS 2 + ros2 launch carla_spawn_objects carla_spawn_objects.launch.py spawn_sensors_only:=True + + +--- + diff --git a/docs/extra.css b/docs/extra.css new file mode 100644 index 00000000..d64c890d --- /dev/null +++ b/docs/extra.css @@ -0,0 +1,246 @@ +.build-buttons{ + text-align: center; +} + +.build-buttons > p { + display: inline-block; + vertical-align: top; + padding: 5px; +} + +.vector-zero { + text-align: center; +} + + +/************************* DEFAULT TABLES **************************/ + +table { + border: 1px solid #242424; + background-color: #f3f6f6; + text-align: left; + border-collapse: collapse; +} + +table thead { + background: #ffffff; + border-bottom: 1px solid #444444; +} + +table tr:nth-child(even) { + background: #ffffff; +} + +table thead th { + padding: 7px 13px; +} + +table tbody td{ + padding: 7px 13px; +} + +/************************* INHERITED PYTHON API LINE **************************/ + +.Inherited { + padding-left:30px; + margin-top:-20px +} + +/************************* TOWN SLIDER **************************/ + + * {box-sizing:border-box} + +/* Container */ +.townslider-container { + max-width: 1000px; + position: relative; + margin: auto; +} + +/* Hide the images by default */ +.townslide { + display: none; + text-align: center; + +} + +/* Fading animation for slides */ +.fade { + -webkit-animation-name: fade; + -webkit-animation-duration: 1.5s; + animation-name: fade; + animation-duration: 1.5s; +} + +@-webkit-keyframes fade { + from {opacity: .4} + to {opacity: 1} +} + +@keyframes fade { + from {opacity: .4} + to {opacity: 1} +} + +/* "next" and "previous" buttons */ +.prev, .next { + cursor: pointer; + position: absolute; + top: 50%; + width: auto; + margin-top: -22px; + padding: 16px; + color: white; + font-weight: bold; + font-size: 18px; + transition: 0.6s ease; + border-radius: 0 3px 3px 0; + user-select: none; +} + +/* Position the "next" button*/ +.next { + right: 0; + border-radius: 3px 0 0 3px; +} + +/* Black background color to buttons when hovering*/ +.prev:hover, .next:hover { + background-color: rgba(0,0,0,0.8); +} + +/* Caption text for towns */ +.text { + color: #f2f2f2; + font-size: 15px; + padding: 8px 12px; + position: absolute; + bottom: 8px; + width: 100%; + text-align: center; + /*background-color:rgba(0,0,0,0.5);*/ +} + +/* The dot indicators for slides */ +.dot { + cursor: pointer; + height: 15px; + width: 15px; + margin: 0 2px; + background-color: #bbb; + border-radius: 50%; + display: inline-block; + transition: background-color 0.6s ease; +} + +.active, .dot:hover { + background-color: #717171; +} + +/************************* COPY SCRIPT BUTTON **************************/ + +.CopyScript { + box-shadow:inset 0px 1px 0px 0px #ffffff; + background:linear-gradient(to bottom, #ffffff 5%, #f6f6f6 100%); + background-color:#ffffff; + border-radius:6px; + border:1px solid #dcdcdc; + display:inline-block; + cursor:pointer; + color:#666666; + font-family:Arial; + font-size:15px; + font-weight:bold; + padding:6px 6px; + text-decoration:none; + text-shadow:0px 1px 0px #ffffff; + margin-left: 2px; +} +.CopyScript:hover { + background:linear-gradient(to bottom, #f6f6f6 5%, #ffffff 100%); + background-color:#f6f6f6; +} +.CopyScript:active { + position:relative; + top:1px; +} + +/************************* CLOSE SNIPET BUTTON **************************/ + +.CloseSnipet { + box-shadow:inset 0px 1px 0px 0px #ffffff; + background:linear-gradient(to bottom, #ffffff 5%, #f6f6f6 100%); + background-color:#ffffff; + border-radius:6px; + border:1px solid #dcdcdc; + display:inline-block; + cursor:pointer; + color:#666666; + font-family:Arial; + font-size:15px; + font-weight:bold; + padding:6px 6px; + text-decoration:none; + text-shadow:0px 1px 0px #ffffff; + margin-left: 2px; +} +.CloseSnipet:hover { + background:linear-gradient(to bottom, #ffe6e6 5%, #ffffff 100%); + background-color:#ffffff; +} +.CloseSnipet:active { + position:relative; + top:1px; +} + +/************************* SNIPET TITLE **************************/ + +.SnipetFont { + font-family: Arial, Helvetica, sans-serif; + font-size: 16px; + letter-spacing: 0.4px; + margin-left: 10px; + margin-bottom: 0px; + word-spacing: -2.2px; + color: #4675B1; + font-weight: 700; + text-decoration: rgb(68, 68, 68); + font-style: normal; + font-variant: normal; + text-transform: none; +} + +/************************* SNIPET BUTTON **************************/ + +.SnipetButton { + background-color: #476e9e; + border-radius:42px; + border:0px; + display:inline-block; + cursor:pointer; + color:#ffffff; + font-family:Arial; + font-size:12px; + padding:2px 3px; + text-decoration:none; + text-shadow:0px 1px 0px #2f6627; +} + +/************************* SNIPET CONTENT **************************/ + +.SnipetContent { + width: calc(100vw - 1150px); + margin-left: 10px; +} + +/************************* SNIPET CONTAINER **************************/ + +.Container { + position: fixed; + margin-left: 0px; + overflow-y: auto; + padding-left: 10px; + height: 95%; + top: 70px; + left: 1100px; +} diff --git a/docs/images/docs_version_panel.jpg b/docs/images/docs_version_panel.jpg new file mode 100644 index 0000000000000000000000000000000000000000..0d16b0f96c8df93f2bac3b8c7089a0c9f3651a20 GIT binary patch literal 1654 zcmb7^c|4SB6vyA0cjlcjgN!AS?8$N|OOeV_Lm5%oS~Rw68|n_ql!}y56XBNT>Ix+^ z8f&S^5-LgdEHh@v(%>p}-Hfqyr`%UQxBK@!&*wRx=lPuHJm-7W# z`ID7YBpL+KI1GgO{^WnTr56AJ3#bD=Ac6oO2?&sYSb7Pl!H`HK2$TLW5RH<8FjyQM zRfYQiVeB6l@(mCUO7*1s4QRX!HsK6274!3_%{iDrhNco7zj^ls1_uyZJ{lVI(X}im(OV z$9@|!PbL4Mq9*OET1pFI=JW2_F z$hz4!TA2-QE>{h%9qu6=GV3l(syEY}8T}eBh%$-w^mC(bIwER_K*)`aEE84#8;F*E@(eE@wB8=(@6%u2F+~>JA8EH<;Xu^KpH5 zXRe<-xNXQW{=92<`m9Hbf&u4H`u#} zCkFI7uNwyl1=Qo$_E#zInD_CHt!{Xnsc!D%?qn{1*uZNrp3Y(6sR)u6C;GZxifY7m zpX2~>_!Fi1-qI2I0sZ9Yvng%aDo;HpRZ5&{bkf&n$OuJ7WBs3mF_=l*?G0T7n)0j> zzOvwo_YF!<1-X#I7k4HKEE3jaTOwGEYdz0iP&sDjVtDsctyfrdkZg{?zxT9+m+#$x z<+;{Il@cwK?K|~fO|z8ah_0kSMpBJ7m3J@1^GxC|9S$0*Q7B&r%l6X1`V$T>y@-|q+TL81x(-D`ZR&$?v9?M!lWac&cI-VNsq}C1B!gH!iSeeuR zWCWH5kbsg`(2`R$v)9zwWcqzNVFk1Whsp+59ZTb;R8|Nze2Xmha#Z0Od&aW z1w~DJB_03ogs|Az0@%oh&!?~>Cfibf3RR z?Qh#q8~K;S3&U%kd0AiT;e#p(bJ<+8-5W22;Ace5I(gw%c)R+r@tuo13u8N;Tlu{^ z!e~`jH2(a`qarA`-af3~uDATeMWwK)KH7GUml)G&krqBZo~W_c+KRF2ZJ}67c%!y# kVj=%cU}hhCqQuBG?zW0QZD+E0qUo>l;StM)(fTF9KfDF0w*UYD literal 0 HcmV?d00001 diff --git a/docs/images/ros_rviz.png b/docs/images/ros_rviz.png new file mode 100644 index 0000000000000000000000000000000000000000..6f2060750dc8c109e51d7df9a3d8d1455a93a10f GIT binary patch literal 86433 zcmX6^Wn5I<*QIml4uOH8q>+{oh8R*(KuWq(L`s^WVdxg=2I(%Tp`{y%p*y97m*@X} zxgXB&-m~Mbz3w{uo)e+2rhtb-je~@Qgr^9R)kH!<2O=S%{K7(g86jufp+-VNMN(JM zmgD8+Jv}{rett$qMs99yzP`Selasr@zsJP^1iT9{G5)l+x}u?>Wn*J|#k2=xU??vy zUzndWGqaEnsz+=i+B-TdENpxG`fO|*U0vKh>g!vufA;Y3BqbnlbaZob^RTyfG%)z| zLFa=L`)4ali-5#j8fxl&q-S=|fv=GnZlTG(aXDUIz7bjF4*sx=^fV_&M}79set!O? z^{pmG2Ei#s5s~3f4;Me1+ZT|YhetEF3kEmmHU7UIJ8u}muLpM!&gBN)<6OsvDxidgXpf7aDs9sg|(Wb%vOkB;7C)lCBFwEVzSbTo^KbsNrK1Ywax$KHv5| z|68ji+puc6XsJ%q)=xOyjoBy5g2*<^e$13-2RDsxq?@p1CVS`6*6br)((q_3 zC(7!BB_Y66PF?>b`5z&fL%;jG$PLQ8?DVn^_=o4W)xZ4k)8f%*=s*l++Z$;%M;Swm zJ)N`^+}?uL8iQ){ZAu%b(wre3ot7SS?HnE)3!;dE%%OL6XI6kSC8FH}`0S#di7R{L zM6OG&zr{Oz>7=ruTInuGyy9fT1Rd3eK)7%u(lb8BvtL+r6hj%?SMxuxs9!1*dlj`^ zzc|o?FGH&ATPJIuk&w1nueDvdBLBoO)TiU!zG3Z@B2wDDN1JkL|3S9W$txU5h=iqYy$G7#kM_C8EaUnb0n%15I3J{X6JQ+j#K-3AMTM4Q?> zjmA!va0$aaGU+v?7$uCcUXv~DhT!M3;_2j|xYv}{PjyeWoOu}R@}a}Q`9#eX`K9!b zJ{dP5A$9*jK}HIYA|*yb3PnSD2Si4Cas?inINSQ!c~$8nA-%aHos#65znqk~w_m$3 ztV2Sw`p8h&9Rev`ja6pg^f=f^&$yMa&;SyNFdxI0trdQZA%m}JRJFk9Z|=- zmGwr#FmY6Hsj686AHx!OIjN%*w?iUWllA`GX{0c-d|U8T%J3tV!Pv0Ol-y>(%j27u zw3=kKUned@1sFdc8f<=&{J7S>svUY|j1_^d%bEDEb)pX6cIGp@T>s@oj0$$ZrcZn< zcLs##+;edh2QU6P)^L)xcL|ok>^_iB`QUwBMEaD*{u0GDc}G)g=B&b(sS=r;{P>u| zd00LD$;vm+HO3m>TL$fai0t?IIHh9)nlW#qq=I>{k-FKma1?_LCkjpDFV$iM%3uPX zqxz2(?mCdu9t)V@5-0^zltmJ`Kr3{{szYYSb1NB)ge1?mk;x%zhKw}&xe}(5x43{d z7ISx;2SfVw`o-Vw9I6+GkgQ~Y{&gmUB3Qk=NOB#rRJ8@cJc$qV(XW%cOFvHb0QK&> z-b16$&h2B84#ASWLOrJ{2La6HzsBJ}=NChcN%+ zJFT?6R?X~qG{y*ENC51rMtxm6!Z|#pM50UFFpTma#=vIy@lQkoJhy4G{az@*^B!iA z(Ez@g9UUPk)}Oo%8eLDUPPntYaqR*-sVS*;wC`A_ANvR??(h-#pYf&f+*ENF#B<>I zyqaKfzu&U4u;C+BVwb@sH}Hjb-txXD2WeBQ7TB`ukq7h08T^DRampu!2ohvMe$?tj z4{Lg$3Q1Bfd{icNooxO6O~auvNz##`mB6g#Y9&WxQDwkAQ{E%h_w%mxX~&w+c+0Ne z_cwLxiGG!N6dP~0qkxwS=cR*he#oHjVii)q_M~>ruoTw&xyM%kI&WiCJ7;)}SKLfl ze*G7QlEK0v8D|zy6Z~`xapvUTY`C!x74R&RlHI4^9Jm>z3X@0%6X!Q5C-iweudn+N zWO2zq1?1)3)-hLiX*!eN`@l_{7)sp(J=Cqs%6340v&u@8{g@$bQVJ>Piqq~7ohVBHo4n2x^+ zlnJl0PM`i#G$RkaVomg8L$3wvyu#5|ciPi$WCuGL>65>2OZQp?uzwYkiqv+8w*Q`* zx*b@qE;-Z3Qqh!~tDD%nLo~$VnEt()VZnz@lx~ zJHna4i99+@0hRt89os7)nG4(S5AJbe4rY*|;|SPmncnCi3)IW8Fv5c_PGtjcnhzH^0&hs)C=y<7;oOA5zf zRi_JD_~2Fy(2x%YHcFelKF|Z&O=|fG(w_@YvSdM)$PGU%_XU$wpYON}Ki-6CFxFqTENfO)7X{J?PQ#uLH#9 zw$!@gN8|#*Y9LX@CkQf0K6!sINnd9=Xtm=_G%%`7(G?m!u=N)if9sqrKw3E)D9w-x z%ye+%m?p}v`_2j`?w99YT{c*5mbJhP#2LmmPg!LLf;&%K+PfqBDBbJ_xhq)^tCETt z>b$R8leJIWA$3bdvxo0TPMw!J{uF?QGU5JmrCIz1g{?*7@>EkFbhR9%p-1OBxlMy& zgHVQ_wq2dHYItD`jjcbgbHBxV+1OwvI1% zlMZnDM6`(I#GfFaqZz!N>$ww&3m=`tsl@Rs)i}e)TG4km!MXzmOmXt$k~hb&eyx~i z5A5g98qoB3?QJ)D(D5(#iy(3pSilVJOzhQ$qg6?!!?-BRVRQ-!i<@J<+%E{EDsbYq zdnHNkZ1)rbQ(y>)7LtLb!WizM&CpRB18uva4Pi6npYbKQz`kN$1%f%_bWtpOMV2<=)ekVC;^Yn-+l9BRQ zFnI_6^q+afg_tnICI@odXQ^L*oZA zVqt{iW7XlyGQFF-nG5Q{qlurzkxL;N;52X(F>YF18z+Bj4Ihnpue-9psv;Br)da`* zTA;z};8iLDW6<ox9NW)6C?csalTjm?8|WDD zq^@&lU4B%g_8%*1!lZB^2rmv8%y|NmIy3h9{X z%>arvC9^q-^>-_ZM-1*o@?>u0@h@~W$m*X3R5bepiU#b@IEawXp{on6s%i#Dyq6&9 zHmCzAs*Lv{2Z93(xzNFL_RGO0u26tyXAS#C%YMgS*BBA-%@5|=1SW7^A(=M0e-h!F z>kF!>95t&A;f1~eRC}T^{7}7{AZMj1c^3i)J5=ZDq*_w*6i4g6h5o2<809=++q77!g%a)1Z2gkivS&D~^Hgt_JwM^(>G$P3r1j-*V1P8-{%d7vc@&8-Z4;K2)NMG2IKiR7yx4xhmGO4jE@z znT~y#9kPyNaeB_I-7BJtX_|m=V7}8hriKIutqE&$?jCnm8)fb_rGU9y;}{|ngCD_E zGSWng4}*B%eaeMK#2at#J_%msc3^~?fiXpM^B@p32#Z;D2G~y z5EAWmpHiF1qkzeQfn*+MS;jW(l*BqehTUE$;|{FCm$II}`GLbq%WPhIA}ZohB- zgJjc;T7($~q~U`)*gDPF8R!ERJ1W?Kz-RI`H7a6ebNxk;S84v$HMr1rl|RgVrNk## zA1sywNauRtu-5I6s}+F7-{EV^GH?p8t_ZY)F}2454=aAvO(pl5Fg~+7!UeAvX+~0{ z;&Yp`t1%~1?myxZNnWEmK*Xr3V?cI`@o0(6cpYd_O7za=Sy)R^WTdF*^fv{ihtDZs zJXj1zSXyoFcUApcd$Jdl6WsRiF86Iwd?Nga1MSN#tz{fpTRNW$Q|Buq%T((%n6nfG z=fy??$F9Lp(4tkmEGsc*gwRv;UI4HAIt7Cuer7w-N;l&OUPF7KThcBYCD>!Jtd6Z4 zcCN4F>zD)_EdFZ)5FIdw7wo4}qW~V2V~{?-J0*+|vh)WIaz6>sWW4=GA~K$HCXqOu z+6$8qw<#dY!($8Iz(KEdfVTAHk46*b=17@FgD9tbd3{Mwfei|OUKm8d3y>Zo#3B(b z>%DkeqY@Oo%MW^XW~^siwn|f9i7~NrABoZ2|MI3;vjaj?3@FV^NHdJ%?SBf(KJ;>B zg#OC(Fb@qH|DE!^J+g@`iO#!By;_WIp==>jQ}0?^9E*{yq*c^L$vvVkfx3Us5H$5G}oaiN$aFYq*ar|D_r%3#pVe<=w{hE@P zQLV}Z=Sx(kHs@V5i=S}O+73lM=rGtd1-CeN{DL=FJdn4S+6haxlqB-Nfv zXsNGcYx6{Wo7+z%Qh)?0bQm%e<6HhDQRtu*)DRe@m^a~td7ZkQ^GW-x@vBE^`2EEg zZgw%|pGM*LU3#z1Z^XNNdE>l%P=3n(-!Ze7XvJqqp$dmf6!Y#e-AABtpH`Ubs_n(J|cNZW}{J0c+oRS zakm5u7+o>f@Yuv~63y>$f+ij_wqlWNxTF(K2^0>}6`;W~@*qfb_cB=9`BfYQ{N`c$ zVePzZYa)KSUjqa>kJ=lr4KFpm*#HY_lm+cH4iys&Rb9+dC*mqma#-wfIO+e2okBT& zm+vb~fH| zcc*55TVo9ozcBS_oK>i`_sMPSd}YBHa?WS*vx`&K%l{o!oeaw?Z?6bO%|a}rr>cRl zVh7pJ(0R>%3M$}GRE#tU4rsNGJm84ppz+q(t`-L<>}1}vk1cWAOw$pPn#=}4&rc?z zd`Q!!xY*R&vccUqG>yXjDu(xr|%t8yT}7iWuG&P$~`{&!)K9KOf}vLK*dI zs5!aNEwfc6#fz;KM$iM_F^d)qry5NxVu{*fiRKapbo?OXwB%Ptb}NgnEoRx zv+zs2w&)Bs`j0;8WwKd)vWN_q;!t9Fw#0}Is{nsty3xZg0I>lk*^zBy;`QjiN5R{H ztnYX+_JLyMAlE5MVqjZTZyyqsSPO#?8V-!=A+7zj!Za<5+k3I~QYw?)u9WPjTkVQs zO^=%lUe*00_pRxdw#4hFc*m-5rt&1V|0LoG$6K>@t{iL(ag&B>idkOWH8Tj1<~XS` z6#NT%mcl>9dz3;r-;7%cn^I!^lIUYK@!j|pvAh0{z5PkZel`r9vy4^ zlfRC)-}R9EUB5-S#i5gv6cUEG%%)v@4wF>Ez3U@gN5IGv`f^8qkWV=$0@S)(aqrL$ zBE90sYw46gJKDrY0Zl6PZsqvTe>}bsSHb9rOl zU{7%~BCu;V;RSa#6W8@-Q@bn6GnK}y@)@rE+C^bMkPQmL{WEo5$qSHSe$Ee!>Nn{$ zo3ZE$66e#Ye+ngF9(bdE*8pCo-VGyBgvE-VuC>b_b`I|(|G5lxX%FsjNOt^9t#4_t zt0Tmrw|@)fsv9GqUaL_c{hT3X5_&x6#6Kp31zb{5!~)7@4uufP)NA0~DME~R&`g~Y z`bJ!gbzkH|evQ_|-!4V}*EBG2Zsw}OR zCv~S6UkJ;~k$LhZE4kWFd>J>yM^`5Pryu9PaO~Y;=zQZ`tqD0FS-T4n!s~Z!H_*fr zS!CGb^0bq-*R5&9m#+WyfzaSO>9xDMI^*Y5I<#CY%|b@Ky`GT*ZCM_Y?B#days|i` zm-KlA_mEmp0YX|>HBZ=dk-8uA(Q2!E3N*U?_#m<=rSayjKVLtJjx zf~tc@KN*t?5NJBVJNBu4R)4|P;|zWO4!;_XG@#V{?FQ!N)&$>QZp%Yy51aPS{sp|o z&A?r*8$I%T6)_0` zqH_s>&{}SBf()-y11+%4=<%(M@_)f-{Gt?R_xmU6i^t?`7rw8q+T5xfi9Yyh zMwH2{_ificip(6SlH!TvP{Tj{U)v~L7AeTj-v3&1>ed~s2i5Mftl_;jnmA53{1 zl4q78@p@v1)KWwzBQ`Pp6TusV_~vJkP!R2s2 zPrX(EPX=^!)ZSSi#XpoF^?PUz+1aq3KXY_@ZJfuC*|YkTejZBv92K4SuH3(1K~i=Q zEVu3c*AQvg7CD#^tNOYdmfi<@|7Si?RH`L9eciwcPBC(?EuN`p7|geI@Ni4>Fa5m- z+Zdn)AE57jUL}>In1%ZRkDUnWW7!=hTIYJh9m)|CTa+@sr85-`C~45j z%9_q`pJzRLu}V(k)@TPe#+ovNv?>F|;!mz%a0&kyJPj~P-~K*!!mJ@}_N*-IL-33l zoFE#1B1{adghXOhC1a?DfIXmi4oY{e!P0x0^UlS;XAqsrF=0pWCItcQi$(rzW(o&} z0?{jlUb^+e!8&KAzK>vYa0&}=FD@~-_KraiVWy^4|5>`P!qciDx#gAIobU^oI^8C2HLTAY@1rDu7xxr*)P5A^HU{fOc9DSs%Zo)GkFlSV z%L$0r)n8Do39bqleJ%19pL)EOuaItrMe7N6j>d)YCW6y%QzxO~P=v$)mht|9 zm*uTkqrTN5gti)en~&L^4`jc{+ufJZZYK!x%eW(fR(#())AykHM3CQz4aN}~gY78c zb^RLmJ|!uL%FaAT$Pi{mojRuC@t^0cHy;m&@oWMvQR z{cF}@vermyY5e_Z#ow`@`ds6?emW!n-34Zy7yqGG*E%(n2@{3Nmxu^g-S1L-#{0?G zz9QMwiguJ^1^~sJ8;$SL{NUj$QU$3K5*vfy+cpR3L%`4?yQ0rR{BeY9t)|wy_76e4 z7HS9nG_pv8bqg*SfJn;)PR&tTBOe#G8wN7}FU_{%dv81V@b1XYwuv25wQ+#+75=H=SWqR*`LWFZLLXAHzCkB*a+Gf1mtqtO z;zgtkGCM{qnMCcM$UBa9cKCdgj8mvi4lt!$peBA}rXyYhD~85B;y4J&K#BO&DABt9 zINvVP^_k`BNl@~hdl%=S%f*w*MeVvx+VE$nuwX{@ms->_I8vHI0xtoJ%+Ab0tFToI z^U#3o#X1hR#oftoF!SiywA|i!E51-F+;=8om*!(JB{u5%rXdi#KuXdG6uyKYwGhPw zpLntW=oL00LZ$wPhO`~3=t8`RTa}(~b~OGc(!xmI0wjk7;Bpi3+ofkmj|S)BW_B7u zMCl*(eEr{V`WN(KD;T0e);;O4QDwqgO+()j`&oF)qWZGX)gnhRXqaPYfkqW#U9bSb z)I@3sCks4=HZ4L6;-C=hj%?A}cwQ~eaprtce!Vc>g6?f%=*lM4;q$XMzP^4nmAzj< zvV)CRuh83vG!U|D!8mEL4-7mo3aYhJ@StSc(@wbdxPlF55^`iwYB5po$ZJpCB2(lY z!?32xdqN}srbXTIDWZ!es*v;AX%zf7|2-?9w9M|ItB;)5;-Q+x?XUMWoL_D&@62d6 zHmj4~B5onKQj{3ouVC8YO;`vi9w?bM;hkANong6xR&2?2pA1MBVF#iaV(@CXo&0gV zK$>pG6gJbok2}O>S*AxTYs_9LN2$5)_U{YWSaVkSK-mG0+3U+q%cAIGi^I3;fs?id z^DwGfW>JgJtz#I}^%G^2LW*=6Hd^NC6^lr0#AwYVsC&66N27unOEc8WAt+pPAlomX z_aHApMsltUN{6qe&=U1T(lMV6!5lO57?zB_K7;sxqAyB1FPP(=HxVwludUb_ytKP3 zT!O<=tCz)C;<(pjm($){IM&DItUNp8EzVxQeX*ZLJceTTkhAI~TNtW6=W?TY+7pC< z`Nj@Kr@#v{VV&vI#1;HhVksi@5!lFPu1d)zYm=)wm^+WInoot`%Ny*Gu9bhIKwdL6 z6_XcV+NAvwHd=Kt{I7a zx2|TmtbtuYy-0GYPLXV}icoxM16#SX)~-QMDt!^WzIns&8>$8&T6))&!avkU$q6qf zH7B*|S@~4?iQO!plNRBx%RF1Xmsy`rBrqw+Fok{06e9lsq&0t2v$26 z-d?oqhdq}=9a@iSiw?{o&!ZpPG``N$dd+x~%GpWe5hEnx5m;n;nqLA^@^6WBh9*X+K4u5t}!IPGWfBpn0?PsghW^xjU z@187IP~V4qC_pS}R?P>;QP{Ny$3bb+@ynPB6DszvZ7x3a-~lmGjfQM@|1ki_<{-~6oh;={qoAB!VQz)?|fSY*{D_0wG_MC9BvUPkWo{nAlaR4CCiJnDf|{a@W<|Rp#nBdf)|a(t%Al%PEK+C z4zViSAySTqjZ9~EJMM)vQ>It5%<7&bj~*wZFdESfs~Hgu7-j4o=))U~Ce<5YiE68z zgOLYsIlvPeD~Q1-SA8%7)$zSPYN)+4;AX{ZD+!0qB=isxC49sJ9^Se*`}g*wc>}pn zX}oqHJDljfM5;H#?Ou$Q=T6-Vm!RXd2szrbbKcJuPMxqZMqk#NuuC;ED?Q%X?_>g7u_Shn)*SWmL2(CZ-o3|JPov;EleH(=ONAb zJg2?QDNm}AvaX+D6l!Yb6&uE|7^lXWl7n9|vpn#Uq@@_}LCcZzwV}`^SSd4}?Sb;* zx@PQ~$qH|scS=ViF!=9d)+?XtPQ0NY!)l;htd(X*BYg`O&&L=jom@i6$2hSN#DGc_ zdiF<}JHb&K{%)6Bn>`J%$)Ax6#++YME8@hCVY+vpB3TljJ=5kDmN=Kq)bm>$p08mN z6D#*YLZI5CALF&B(!1$2#Xs7qB(!?t{{DW%ry}kGjtn@;RkZ83z9s>%6m5QaoV~D(@gRzpx-Vghm#>kSPJ7~TzC{L*;quM z`KQl0u@mx?Gc65N>>BBaD{j=rn1m-;1nGalzDl-LpHJ3|joB6LJWcLO(fTmlPA-gh zE<2?K-jI7Vmw#(Lk)XBBDYQ)w+$HEuBT#j6cFIUd&p>pDYcW9|8RwgJizvR%R0F5E zm@_gnpKnA8_#}=`<>To03mTfCv^wX1&E=5v^Om`+&Ps61armVHgucgvZh=1lZc7p)%KCK$>QJ%GAaAMpXLZ8o{OF_)To$xL)H*W zsUDwob$z~A6Ptb!cTa{;YeEgbh|AvZvyxRnsb4vMjwY|H7rAu$VUkW)K2q}8*Btz< zyUq$#LADA^0ZFqGM}s=^p@)_dMRanoe+=oL+)({lAVWWKue?3N=j7D}FZBxtO&k%<}o~pAn~0r-q3P`>wmuJ$A}{tiAoj6mu`Ze-O+o8OsigoO=y4?1UA@v$SHjW8)6zTOdMmsZ*$s}9P}#GtAc^xKSn`8wuj#fSde{Q z)UDc=Pa}xIr+QYh`X(uy_3>eMZl_~!W z`*6k_ZGpJ=yLm8RDg!+3SS6;A_P_ZGuxh=*2V~-T{j~&_a4$!AR2BWVJcWAbs|Nby zR~(NExj1D+V#F2$hA7F8X(vj>ZAh)6TndsJOmcYAbh${xe(qV?uXRGGHC##IaUR^u zo7-Jh@aO*diLz*52g%H)4DFNF%u{fz_xKW~&7|Qy8#F0&!?K(nPueYivU)h2J~846 zq-lR)p79u7Zo!>ODjZ3r+-f0Be)c{0BN|nrj00XPDR;2_zq@D0WPfW+_#Pd^7*@fvEul~PvP-#`S^OhzoBX(EC- z*5|Ua&#~!7B=2pweYM}rv;BxtpB6y!mW`rO)MN}xFjIIT?}+$xl|l#o=W zmb&m)TnTmp(;hmW5pTf)(T{#cMOx)h2TqiqBc|&Y8>W^Js=!flFAtj8e(EV=EC)*P z)6+la*^^(tKObZ6BuCu6pUDN5Q-wVq`X#A+tlo&{=+TW`ncPDxIU8_y2>HrRm}KT0 zo4N_ymmsh}S=vJ$&aJ8Ogql|nKW)<5t8WliayIf+G@5dzS%7NDBbMUQzgjK~LEl4l zo5yd2L58Q?fH-rnVrjTmkzDOd^B!xfSIt)*-nRI#=N&jPL@u27}_}2O$=d-`~<7*-U=IsHokT zl={YJ^Z<6Z+c<&fEo(-UXGNw8_y4lrK0$##-y?kaT~5E2J`^9!z-FVt-rx2@<>0K@ z3d-By92KdHjq|)e<@4Qo)M}x1hqELO+Q^YJ({JDv?BB1t{boRgL3*PRzz}gIDi3MN zKp_HEa-B!W+gDa*|1nmSdRui4wrcR8TCZ((8}It1&8F;QTsC%R>^Dk$)gdx*MV!@F zz6f5kfo~_m-;9;U1jPx+2Rj(V)Pv)}EM&ZaIy< z+i8ffrbk!bfrFN703`_@Uo=S%H!Cm}K^#n<4cRe_WYEC9e2jstVUzbOnj))rpM0_5 zE7_oMw*MXYZbas4TN^hF;lkGQ+m8=D}>8@H2IHGA3{CHHT z?CiJU(HxX8iDhu3V4f$Hb_>epQjrJs3~+>dD*A~1$DNZib`;Ru(>V0^B0>v&6o*Tp z$i5Py9#^Q@x{1gpSvtB^z}c_vUpl#Q{M-+<7E(7>E30P=QjClMrNQz{5klv2)XI1| zpAj0>hvz1X(>;Y#u_0^Vo<{&W&7}Q{j+2YhY{3%UBT^5N5DxR3#3qWpl;=$TMXmTS zm)rjX%4f0V930&BPslTxXRZYowb^OH)Vl30{@oWL!5wXC{@WEqVD|eYfR|PakjZ@c z$z%&Q9J`z8XLzUVBp`Xkmi(e=jukFDs4V77>CT3TvH2ll)FNXFL@ou4l_q%Go z-fgDv^)VB2=WX>#c&*9u^--tyoBwKDa|6AIV4lu4>3!OebmeIQ;NxYvmE(?msP|wx zGEf@w2SDdVm@qGaV^rpzT)grz#s;lZ??aH`_nb@vI_@(H&V{(iZg&iWS4$oETr7gw zBk~y%BF(z@hpVB;>!s;FPQOkMcFK9iHxo-}~gr(=Vxyu4EW!YsE#ED)fb5zuz471MRgI3_{nek}$547{1Kt?LgvKOcmS^ z#NUu(y3WAZ9-|QhTj%*#u`#QMzc<0hb6~pZ%Z0<0(2d+_%#2eB@y5#CS%W`be(`2- zNly)!$x0>5WA2~D^iTp+<+xVhC4kqqYUt=9q%B&v{!RU}NVXeGwnjgrdQIvl2X>66C zOD?R~izVg^NCMiU8vo~3zoi1mX_ONOW|)Wj`%IVxDXcjX!BRB zK5b?V78BDGBmauBwv1A<-bOxLq#zjseeJS_G3UCXK|W&g@%0JTO8B0JPzQGlQ5XXs z2$xvH42=5GOBDmgh;A6pY$S~$V4;-A-Tk_d2rfz&=q}j<;y9u{=vWoG$4{TnK^ZL_t@!YirfEG!V7U90OgMd8p*y)i3$iu zixAC%n}{ufUM(60inxXBy+hwZ)mCS2k~bwT3!tSSFQDWniIUGxR}uGB5~qy|L%kcB zXt5dbY}IA4c~?m18ig{D5|NS;F*%8yq#+)z^a-a;y?aIQ5t2!(R-BbLUR8I-bSv`z zGVuQ$=z~>sBwx77>aTY&GHUC(W331(&a*DGq8 z6JtJTVAnD$^+6Kzq}@PzaLcF91Sr7~kci$~9F7 zQa()XF-yLC!~zQyPkUnEj3Wyb&?V5e@W(wnpWn_pie96(X-q1>=oMUPx#_zNQq6;Qlh`mjjzJwr#MO{5F3Y4iC%kEm0Lo8 zT>u?rV;5BIqI5&clNG5kWp2kL@ZO&m$fgKjnSc;I?ILhGA=<@I)8q1^AVk3nsC#TXwA&PUK#7xhk= zWXPyz7MOnAy5jrw=|tu$&{DtXr=kxgQp@g6%`Iq=qs(v zkBo?jRC!FWOg2Uxu3n7OXGPJASNmV}pQ|StQC790FJ7m(+x}dGrF@cRrMLZ&v(3?KdL*u1BU(5KD`9 zCDF)8zE`4#+YG9DObcVYbT;`iE9d~{5W>@`wGBVfP?GSQ+OCi%vZfkAhi(pv_QhE! z-7xuEi>F{K49al7GV&021@bROaxm#m-Qt8as1EZ~Ra zOD0%rj|;AEEVevC;;?|iMZj{(u=XD@!SAq9jq0%%%${|;jI@rq{!DEzqIr0 zHZ#zNFeAf^Cz+bue>B2?ri1SoIHfI~%A&YiOD@IIeq+kQNJvN`=CoFtH6BQgjJUBj z2Y>1J0IzqP6KK84*IGtc6%& zK0EPg0g+u|?HX#$522S33$G0qO<28my(Ot56)#h=OS>RUin&YJ)5zMom(#m=O zqtU7u(s%fWg9jzK$FfPqHh(~CkGOO@z8OuBGd0PRy~1}i1FwZiQWOp*3TFdSlIfYd z)Fuz#kV?ukPKpZ!jj70Ark>V1zxwD~GUN>*!Dhsc0|s}|{Yj^Gak)&SnT35?g@yn+ z++9Y%5i`5;eORm+0_Q*{hlAb7U*9bRTS4j&n4$*AKS>6}E)Y(w(c&6!8SBdUjOnvW zk)cjD=vw}TLTxgpQE+j|gOB~ANY*G(bKAgc7+-dfye2GM4lj=mv{XoklP_Q6t!HXp z1IHRIU{GeG$0<$wr+=+UC=g^E^gYP<;mL2;up0jXths#P_i|q3yN|Ut553>+goIR> znfdP+hM?#I(;j004eipGJI;UMG2Y@km3VjMzah|zO?|~EwmiASbz&Twk>Zm#R6Qe&BTDdlx-+c_= zwpCBSIrtSD{>pUV@r>|Nv_DSO{QjID2%m5X4<%O%>2-fsko=;MNq47V|IWHZTJmzd zAX>pChCk%B&CxTuQP&;=8IUt!TZ3$5D{b*%H}8^V;u!3V7wDa2%QsyhK zG(imk1EcA(cyE4LzJh&OJG~eO@Br0J7*czhupM>7M+Z|cD^x#_L@Pfbi0a}EdcOTR zFz?HKx}5NfsUjfe125vWNWn-wXfPf{IJFBcrrZ*ZoqDBN-3aExP@2c75zpjcg%p~v zkpGjVkkK|I#*T7I10-d)baUf@_Wr#%5@_DZ3; zY;)Tap?~t58vbH48Dj~LvV}|T0JToIy$yaFMsF}4g}q(lo8h}|j#j$;_oRLBZd95Z z9LDciP(SavZa?&iv^)Hm!7WiL&vdl9VzpqfBB;>e>Bxn-Md1^jW zyH}w%&TyC$lEab7)=VgEym1IY!G*`a?9)hGXe* zk5SRMonLLWtOr$CKC6Q7R~=L2M!qBu^P6B4$m_o&4fWZ1I+GJDFA1D^O*(`o9$$_U zD7W?iv5Jm_6Y+s`O9zoDHF&vu&_IN-7NeA!dqn6xAb=7c>^x-!^iZ?#F|+9T4ttK||C{R}q#`!4g4TS^KleyUH&eLMkkkV`7z zoatvq-zzE#W_!&8Cp;RM2{)q&rlQ*7s&!5Onbyw%ae8YXLy;P*WMF~9;4 z6&7u3X50nl%C@8qVlg3iiT^xYNwq5Q=m)%UZYcy7U`Z({GkSwE@a(yk^P=7eBT(N< z{kyuRe?ySP3jTh{3E+f3nZZj+YIEPpMO-m_4g4H$Br^mKEhkdNEnczWMn}o?RB>WS zVK)U*#L{c1hsTX6 z`o4~Df128BKtzlUzNKR!VOH-*HI;{HeLV{V+$~NESBh`=W$@xf)Vb|PWhngaxWLTH zco1sc;?a;M7pfSAu?VBW*5Ntz7Nj`3i!q(HR6YuI{ls? z(cWvlxEJ9o#P{TuDWxbr_RNS2roV)>=<&A@3vM^72v4VU#g(a?{aK9k{n!j3&gTV1 zhJ#!c&{yM`Mnyh3o$L#auN}!85M_R&6n|Z>NfH1upUuh&L%0fc$B5gafHy0V-_|ZJ zJc;LwY@FdB)6`Zf$j0eaup3%gUexaOr)T?NfS=Arz`4l;Sko}~vWa!w`HMiwiOw7N zHoe5eDVs!Z-QN*eA%f2Pm2LVC=-+TY`u;znMZSl@#dLkC%ULzZCSOKC_!q*@h5t+K zvQLYl7`d`PrR7TAKAwP$hXke#GIckqgBzp2KHScM=_dRQNQ1n<)j^~`@(Ouu@AUAT zPBt-|I+Rv!WcS{J4;x#PgUB^u;*7e9IJyZrG+_$%2yvNMwVQ>iN-0U8?8SeLq#%^o z_V(2Rr-1gKprkG%x*&u785ke4M*0{7)B=-j;I$kxG?)_kW$yMN@&tp%1e zvy6%%)>UF9GahUX7=Ce9E^o6D@LGN< zLB$P?p&<6l=d!e*BePOm55yjQbXB}x)S2}w*%VjG|6}5<0;2rB?_m+?L8OOf=#=he zh@l%P$)UR&rG|zX8YQGtx60>-DP^uHPtbDl@0lg|6k(ld}#r(|bR+?wEctP1pn(<=L`Z-s2PFhTC?EeN|CE z!49ag{WUvboQWMpWk@Dh(fU&kkfpxses9P!SMV?V^c9XHi}QPGKW}{TO>!wG58tou zR?ijW{2|UY){wI~qCkY?!u4I1swv6)Z2#x+G0%)X_ux_x%ImSNRNUbud*mnA?+K9K zA+vB^SieRj2sGfz#VGdIj}t{K88rUuF{+;X4<8;`P1>jvWG;%g zNbbD-3K~8IdX%ZPg)-rRcg+=NlQ`8ggNIAYH zs2PC~^^g~B=MZD^WW}}AiORs#1hdZjiP2I(OonUdI}sTFhfA7~-YG>u8-YscC3~9@ z7VK4z&O%4XNq}R5R$cYQ|miq zeIar$SYrBN)!N#kR(L$C+FI)Ok}VX1vCqq(^xI{ zerqTrxoS;f+4%hDGgAiq8ChI;cnS6NmoGl`43CQk5E2Fl(hxjW;y{_I!d%`oDU}hhQm{T9wU3`qKLG#sYPfEF)(MLp z*0|rZbP^S`es2tD$Hl7AIz(GL3D2$ji9s0O@5^-=NUbULaII4cVEype%3pN;pEZVD zg9kGM*fT~;J&P3@v_|pk7y!@0Qf6mn?Pyksk5Keqe|+Xdn6)k3#22;nR?fMFXsCN7|k_BC5v zg6!Qa#gIHYdX?qb1wMjE{Jw<1x1FFmf(!8xQa zC2odb&kN2(WA#nmI#)VA+W78EcA*{eP-Owx68e|_OoC%zmr@i!R@{))L7E>E>Ay|{ zq1=Fd%eMTAmOKg(V}*SkBc)zy9>0X02IpzxkFCJJO@ES-%9;i>LYej{6)_ z_U7cP3%a=ovvq%cYAlTVJ!Q3~Rlt+W>E$&@gg}o720n?3bmG| z>#oYmE$);Rl}=3MocH0ffw>Ea*h_uW`o@HQ->p~#Z3)*nxsoOBPt3+9Q`ijciXGe< zY*`G$dd1}ZkCKV*2FlAtNblm6R7REc?Z;~)W{iZ@-96)u-*h+x`Sh=4`&74Kc=$!> zwTw>7r&Qe|I#$y-N3T|KY><+c$aCi8@O;gxA5P!2R#eWKW_aK({aeG0B5BbSq!mHn z=~=4jja5Pw+Ct7ru2;Ou-M6LbsyH4Qit`sPB$u;ft%%mBt7wN>ve!650iD!`tWL6xy`mey64u{E(8;yT|;KM$m-9E9`Bryh+VNtpcjv zOpnZ;anRdQI7w+Oz@G;f>z*6RlA1Uq8_jU@=j2IPL*>V&h#*5EXUYygH#9IleqvQ> zT1*i={J3KtEop&kOeogz1zPZd!mFee@GMrx`JjucV&bJZgQng*LMx1~A{p0)*-aQq z-m|shBa!u5bpi|QabiRC0Gc;jkfbEYKJIFJQfkYh5EZ%q8y9|fZ@UyWx_f~IPG5?% z`nc(44q3L43Q>}br`9Dxa{Vn{ADK0JidrUe-$i^F!;Uz^5IlBP=5sL9?)soA zbRw>(HiRzC=-52^?#%;ebZ5C%{NCwk^?|MV>*nv}Yvy9&u13jSRw5^?JPoJ?+-Dng zx@vZkBf!$yqSYLBY(@Q?L^kdRA!T@r9!9(ZY`Ie50GWO=p%( zOV1*VKKbIc61zHlc?fhAWROo7y#17K(e%4;Ly0d)ZimjzDh-CI)049c+KU90?!BB1 zP{FbC+~#+`>Ypc^oh2lEXO^(mD7H`P;<~zGwQ`D5?~Ic|hja@Z5~i3r%FJZooEW%> z^=T5tcb7uHzM{rK||jv*Fagp`?uQ>up~o-CrG&ctyjhOP$BG{V}DmYhxPP!5MYeJk61Hu98?VYnv!=FoKrk~XP6uA-#Maaqrh zRX#8sa3JUE1a&%Qlbo>KSJ0z*o0e)OAq#grP5!wRTk-8>9@Sr)8VxTM_MP6zDQvrY6 zAe$;X=c!ZI_>QVVvGwQFWdOQF%HQHhBva<%iWkO7&z&+F1!v%^gtGU=q(XGCB72C* zn_`DCaKJD;me+AMwKBD`o_mu6lU*8@uY#P~y!LOfIsKn-R3TxG@n6ql$um)_pHf{o zPWi?Mt!s5j(Z#MBT7TIq*Ym0p@7^Sl1KYEo5k1Fd15Nnwe0%UC& zsTGmL`mftg0Y&YMfE%|>DS?8Ee?A<}D{7cEHQ#->>LPhP&BsfalNUwHF7W8sj)$lC z1v6waq4TGrKD9NDn09{A68Xt>o6#)Mq6bysag}GV;ISr1Ud)tDSr&Drf%Q{?4gY!p z`iI&j6LQHM*4`**=-b6fV|by(kbd7X-m_r7%#5_SwZ_z>d_`7BA8e4GA^ySMmjt$r zL20n5Zf5yC5|xcQWcvd=(xMg*yqUL+Nst?Vmom%%$by0g$76=(3mP~~ms~7!>TqJeIU;I5NE9ZZ2dfg&%`&!PMX%8G4 zmQBkyrlwHNMUD+>QLJ>G-&qeGKaO8l1*gAOumZE~_eAacse;>oKSrwPD4XSZLCx2v z>X66bKYmbk8;v&KO8gIRl>`vTl^EaKF`HN$ABv>6bxQr2>r@4#4f` z2PquzbN=nQX{u}(Dv-7PF&Wp;k$>cUs&b?(R;ro*`M`=DUl-Q8BHbq~ubZM0%GZm; z14`^X2zSdFZs_^#b}I?Z9+hP0KYYQWFpBFxUJbC9W2=(9FkLJRWG{T_i}Eajf2298 ziHF1L68jnmC|`O-PMjd>fX-7m9_bQBe#qE=ctz4(+s-1r-Z~&ght?5^%f68RoHR5f zK?iEfC8Bau&?$(6)1xuY&Jd9sijPd!yn9apG5?nSh5Q#xMX`MBG=cCQ3?&5e@Isji zX#qzCMb@dw+HZvtsU0QpX-XMP=Hjalr>9k!whZHY;e}cslxsf00I~??A?9Ca$5qqJ zkr$g3BlcpSZrrE)xbzdA;2%5SR+>5jU!=pYj~C}>U%?)-aRWPToyx8G!fr--Imj`$M(GXS0CHUDdjY7Ws))oh>ASr6{E{}Lv3-7ZFP z3{NAb&26S99feKt{$|COp1xkU(21{?_^N*{{7Zc44!+YG!-ZCtf}h4rhA;OCLGRlt zB*d3=?ecevEe0Re`CA<=F((q^pkSHOYN^g1oo73GD-}f8O8Nd0Zj|+Mcra${d##2K z{|^W5>b1-;lDk%j!_VhHhFdtw5Ey|@vnR>6OS1EFyybnNlhKI(Uga$8@yym@|Jlb0 zzw+zAE1|9IEW@>Y-lj7Y?x09Tb`A-X(OU?w;3HWso%XwrAvKHd3zNCAYvk2h$#b)5 zOfNW6f0~kzJU!Q42aDhtidFAi2qlJ>4e^N`)rE_*Ym-#WRk^2CO*b_ko(J@8_^ZnE zl5^mKWfP5FM#*p5A0J}fC)x~RQOvA=LZAQGUJC*YTR9f8GXB01!)|1nmD^@Hj+PNf zC@<~T+G=&4LfBQ00yw}%nc3et0O2>CV*z~xf;l9K39>a3vh*je9rfIBqK#3V|NAR? zSp4iTv63gXhvqSLsg@7?F?vukY)K+Xkx{&&nuTojGXt3Speu*;JD0b1jX)etd)MVH zGaGf&K;bc6QoUo^z&f&V);NcmEp4#?PS@>xLanQ{-IE9yfKy6|>KPSl4JQHr27ZxM z6b#iLX7jm++t>`ocz;d=5@gu@NlYUT*a??)W*igYEmC+D|C?^3kRPCPI}STjm-jTW zF(;ep-R`uuFwbQyl?k*&?699-6rXYcvR|Hi0q%ZH_D&6nZ%2tK>C=(%nrgtHq_C>M z-VJTRcnR3X($$rB6@FBoAua|h-F3ybClonqh^R}8;kAP_`y^gFHW7AtKL!^U9Eq}D zL?|vbt;b``8+rxgK#>lT-);60vD3fh&$kvA7m=8M##H##F%ZOIl+(nkxUd!CxU)N+7WPKvJy*rLiA+M*}y*hi>EJ-v_+g|M8T+L+*N$ql4vu$$boS zE|4Ly{d}I8t2`l_po9TcvM-ELfC_`M^(eUJt6wG=qXqAA`KS9xr{I z|CJe3j-irUlP39Y>cvmTNYrpcJ9F1McqR)E%*^HaWfKScq0qIXEV4R`zW4>1SR0v% zc)NBRFf&5WX@4x4`lLJD3~0(v6|*WSI82ogF&?FLon9GqF+4bTs*7TEkdP3OK75OW zf7Nc-acKLb#tYS%<>IRa*jxNh7aB0X`}h|y%n(-y_VPd@8ir9?fXTbze}-c@wJOYY z0034iq+f{pTO{lc4Ry&Pe7LKS%B`{My|`#dp{Nv@@zRh>UQSN?YD8WM=Wptb9`T}rPyoLYY)mvYBFs%I6vR50oil(2&V}K!S{uGy zI$b}22=FjmpVEM zg7hbKZZWgs+E>lZ9XD7Q;77DA6Y(-=x9T2U6_9}kTlScat$RQ0GlN6Ec`BW-EFPlD1TgTI}I8U!wUGH}o4p%^-are2Y~< zvHYv*gjl!}1S8+3fo!1M&KXRX^G;TVrM$|j<(9wO-?kI#c?GaxM5&6gzI7W;>Cq%- zzkq6rZK_teSxFKrIhe9ge#jYT>xg`6ca6n0oSYyfe27t&Kmi|qYD#yWj`^>;@y!x~ zP3v9ZNGT36R$#)1&69=;a%*=$?dEJ)Sc$X#f$damg#b zxdEG^K8`Grh5d?a=!c>WU#5>PUux2zWXEfX8S`u##$dlDEteo%u#GQH+F>fP*L;B> z^>9kRJ-l`zs&RjicRP|FYIX?+<@(84fM1u|uQDmXI5IFP-pk2a25u$%2)U02#E}22 z9uJHJ>6Girje&n8CJ$wtnfx{A1TN#qr2XD@5BW}A6A;Fa+|?2!8s^znW*}HH z_VZioqhbTHrUZj-OWdq(t~L5BfHSkwsfLSPef`g>`TW7)xp0vVdWZ%sn9Dt0W=C24 z;(iYQhyf73w}Xmm!-X%M5OOaJup-SNYv8QPaj_F_25z4RbC8%1ktlW#yhzc@R~BeZ z^HtZDu6==3VTn@ihl960gjMn7ui3HUMYv})?eO!QIxa7{1)&&ac>AXT<3IS|iC*}N zfC&1%ns()R%%o4OY3s^nvZcV8cN0i!%2<$=kU6qk?Au51z!0onp0Vn=UU*Yi&u!A# zbUga61cZ1?;j_&td42-r$l+I?`ua+u0yV|EO0g09L}|=ilv{W+5>%<=za~$f5-B_p zhJZbiS?{qt8GOQRBdu^AN_5PdVF^^fDQnb5wc`{^WZ@-<=BUPxa%N)IskN>MYjT>5 zUppUlI=OaK=eEcZ>0?i7d{B(t>EK=`YcEzW6|NE%TiyIT1 zv}3%3*wo#LAugfy{ra52`d;TN$aOg9PT7)PVvx!i1F4ImVi3iA9lofP4Q7sc6M4n$ zbw}_F&_1^e-yCCVvSo*=dA$WUKJrUPJH`P)d(8aD1I)??wxr|@{f9s zWiQOtLrBkJ(f9pzR+Wy`#6&d9=<5Mse*R`k22nm{zT85XLg`7&611roZus1g$pw)& zHJy0({jr`F3=0mb_!qwi6sNhUFc^8qi%EkotNoHH(`f1=K1H~8Innx*_cydQlX6wH z6X6<%rp-82qpvw6v)D*|-TBCqvX;8F5+DJbIxm98zWcsyt8>%x{KozplXk^sGPPL* zhfYW?6Y9MG&b7%YfJ{F5LLd<|4XHnlprW)RhEc5Nj9Y?Ten49tpHZL1!(tR%iu3cH z@H>8%EI0=;iLqzw(r=*3Et4?H#a02eS*NzDnKBB38?kqnXG5qCxU#Mwp6`Yc8Bdi# znkKt-`o=a(pYXrXT=Y7n^1qLwL(RS@k*M}nj{E{2Cej1^aDzm9ykEqrDC?eaVEn3W zT_Zdil6^GS4fn{|apskI$Lqr_9OL;PM#>>x^Y zaXeq&;?@xs@5s9%pa;C(j|##JiO(X}>SF-2jrajTbxe_NXsF;%nKoDdJ2vXKZPcQAg2utx!zTZQV24FYl>Qu;L|>*c^iv(bm0yOo>t=h0Rnp zT;JFW(5bFK1#5(ky_2=yg8v7=} zf7*{ z-EmNywCASJCD|BKWz3r=Z*zLHZrhZ}^{osJTJ;j0$}Q5Rq3K?MB-5{^2ApVhUzrUj z(SDUq6o6>!IjmOmGpH}(XBedr!h%?PtRa9FtgIq(r(QKm2V(T)42=4RuOq#RP^7P< z4S3TwB85VLEH~zmQ~dHRR%#8+uSKnt4gGf(i-j~ZcJ;5_8^&!s9pu{komp1|C&P4E zx?piZ1Eeot$DABVmXHqH&*>N`K1v9*C)*tDlgNYj!2;Z8nZ6||s>MVht^0WA63``= zACaXiO(14d_RO@;h3akL_rlf`J@jgCCe3$RNQn4a;p#LCvHq{=E|bJ>qDKxSZp&Zq#C(k_Y^2#e56bgh`GQZ8JymOGesoR{AqDku5eu+!(`cQ*9?E;i6F&i3+OhjW0^_%i zZZ6E5g#vfU$U`jBt8u_#f=XC{Fz>odLlBrexTC4|4ftA(5a#u20KWIP^$#CF1P1y% zQ6Qe5wxk~2V)E;XbCdGd$sTm{_3jn zhTSSFxsP>9cTIs8rUv-7j#Fp&9tuTnktWK0=k!o4MUUpyGYWLF`XsNP&0mW(3pk7y zaQMx)n*PLWec>W3CO>v_z;kA(cR^OZ=F8+s6nUPkjJN5A&1MVCit3em>o@zu(U}qc z$pAwwb|XnHBKSLeP7-YU4ea=!hqse6LD&n0Nwh%>;F&ezp~*U0*1kb`s-$urD3@>m zgW|>ea=sA32b1e+{qUQaPfoj4#LD2cq-#DRu=c=94yp6}l2kn5Y~6cEjfA5#3IowW z8v^uH2bFZNuSD?GmrgKbk1<^rw_#@-u6y|D>7up}pf7qp1_~D0(7`&nJBQ003YFD8 zrD6S{U1QwWbXJgf<99RI!~uHeN8Rv)MwV1;?~HT}Le_XQ9T;x?^z(qbKPyBK8c11< zJ1o@MAP9~1x}QVU=t&f&0s5klU7!F72=V~vX@vqYAi^J%F2v}mTtQE`MFSj)$rR-m zU)8{a0%QdNIL5G*|1-E3&!d>8hP)4BMoQorJno`5tOdAFS^y;qn0wVe=Nl0t!Un~# zV+~f=v37cwLLSMU%8Jq}jG#lp!)4(55uacw@*TmgrO~_kYUqZp7Nh^a8}sza2Ke%CkvLmfSX zczdg5yhE;_yNOxXZ(V}hHfk{Mu1H+)>Hk?;E$vOYH;WbWNBshy2uwVMr-)a-J5$?E zE?HOljoNgJ^B76Svws69B8IO7Ow*q~!MqHTwySs76D@~&#k}qoka=8EWbWnCOMOa* zoawT5c`JVGFgi(AJ9JHX>mG~1i_OAX3Wy@Cid{Ep_k6ED*^ZK;kG~#68~dXF`}T(y zQtL9f%m5`#`$gTa*F-n6+9(DfwC50P9(#}N`Sn#_=22YK=v%CFJm9re`cyBn!}{N` z&caB#YKOX$oFJxP)W`dPBJ?ob2weGV9&Oait0^y9ZMX5HOA(5T385!OvYC%cHPxp< zV(jhV_UI}8jm+UO)xM&QYrlm=y(&j4mk(4$b1tB=@3_Y`a;EJ*5hmFgK_MFzSHdvy zM6_YPVD-Wm1lq5dLo!KUs@;nORMeW%gFRx^_LkvXJ#co*zxBfZN8sy~+>dDBHMNes z&|ttFK-Rt&D{$9w27aTHj>{6E8$`pK?@ZV6rijjt4*JU*mp9Lu0u|J31+hm~&eQQ1 z&}uVHkES~}x_uQ1jP_bFYYsI+;p}kLx#64P)1#(hMLnlWnPq7PUH{1k2 ztCc3&8p2RKd*jA2Q$i`f;-uCeI9bnmz32*UE+TKaW%{+CV&_uJd&=aI>`b?=*?m)Zgze8MV;wD8JM{&v1PY0>BNMcEiToX( z5RKHPE5>9`COwFa`H%?Rclu`7g^yVuJ2C3u|7ZTwG#YFiWm^m@{gQ_-YSrX>!u-NX zompv{GPC$$L`uvx8nu-q<0P!;az8+7yOxi$6*r&ys}dj!uFMGQ%z>>iKW~4whoqPi zfphWKND}#|LMH%J5e*aEl-I?ipZil~<%%XhkOc+d%--@HxB8!(8*-&q6voBHVbBD* zHHK~p?uwY}{>vvsKMTb9#Ld+k!??8R$3r)fKb#POPlNvJpNTh5*P4s;AVb8#!~5ZwZGVG{2uDh~(ZQ1dfJli{ z(4kt=4+fZOv{D84ikj6@ExrH51tlHHCK?q`s;&puv~gnq818ye6h8TxKjzGNHVk*? zortq*T_z_+Jd3>TzV*wB9oR%yGA{b0iiWsW+48On5`L2EH1xh8cRuWrbB|B!1_V)V z$l!&Ef53{R+-&Ln2XSj;;(^MtUFA`DSV?Yg057JV9sV?)$d$`0n+H!GUWK4RpVStL z+K1Zp0r{eDhegwwwfCL8>m+a{IR&Yn@I&ZK<`>Yfqj*Y3F;Ght#%SaUVKKsD?W6OY z)@Wr;y&z5RY!!6!xy|{~{Mt%|73moZD)pnFQGRyLM~{23m5ScqldWeGrZJa?#=dIA z=sw$jVT~Mi=QcdO@to!xi%OJAgU&#^e(8^i;n8?CTDBH{HuHD>h~wej6Tdk9<6Y3k zt|8RYr+L=n(F7kQ7FE9^r_z)OP)k9iZ?9tIhiiXK@fk+yU&zi4IeS6w_W(EGL_QS6 zfAR;kTljP$azL^RL*$q4_LaJYiy$aR_EXAfA!d?w|lS%QhH<(`sU({bfVO( zTpoWgjI>AsUdS%PUYifPKt+tCD-f<;+Qw@>sF%*$zp5J4q&7vqC{#wFex*2W!)d;b zLRONK5p6tp z)0F#*8S13Cp+@ONh6=*ul)$Yg$IMkde~DgiyZtUrYC8=h(>n>c#c`PGDC%AC=M=12 z4#`uyLtQ%0#hdEoYkU1*NT&C9WNoPfq8(we@>7pgf#QeE@W(Ilp$}?XKbi0%LTOTZEW#?>n492j+t~N+z2FLmwUckA z-?~{J{l~}n=;;p!i5*FT|;TvdylCrjz)`VP1abql*s(q{> znc{g>v|JjBZq`lpbvv-WFeXj(Su=JHPr2g#{6sZs(;~i%lXWfD>ZypQ*A0^tFW$mj9dyruHO=d!fTzWAauNyuDb!GdoLm@paLMER6X z2G(qBE}R(FxR+L`kqDWQIiiAL*Z4nO9q!0PCjCPqSi+Fog4(`X`=oIacW1N&)z0p9 z57oq=_zfBLz6_u_V?2cvC>%>#{_a)$;u3}#txyXbZwI`R;Cq(&;oj*PNIRa_!!i)e z3KxZu-;cNr-&qt)w`El<)3!p_mcH?*V*2ARpV`#|UK^@dZk)M|7QhhwCW(Uzr)>Sw zmIHJ^7$)Y1OlYnyf9xMdenZ(5cN5;CWBms&-P=hk@kN4GG$yIP z(>TshP}%4G3J{rMK=ZfYb#*9h)YQ>xF(`w^WKsuc)DKrYL%!lAG@g=s#((f&9t&$2Z6efTTc`qK${ zB_5goJk~P37e)%D*W=?Y{H>iD_$?L5C^52)$;U{PGqc?`i$ya`qpJ~ctLZoZ{ETB` zKeBwz$dgR3rh|YYZse0?R-j7X&?Y2r#-c$YY%%4ht$a{LRCXWizQG%VU(XvKI_u7t z6p6v@m%usrBlEWmPWnvaV;i%!D4k{t$aUvACx!U*hWjdffx3V>vHVL%z4-o*_Uzs% zI#>iqFVRQ<zvUU9z(5_8fSH(k-HYlP#U3*5k71KPAkn?86FX$_y4lUPAR4CDu zVzZ~Ds59p|4qxM@UU;RXl&md_Ob+7^1N-nd7?pCHyWw{`@}~M>5ONWN>ArvP2wH<@ z`->2QJz|o?EH*&j`=!EhKysQwMcKsY{ueIgrrqBaEV+|bP&K4C9(9D zQ&nZcev8iOAl-@2k2lda2P8&r@U`XjO^D-H)=7#1l3%oG>F$I%D0-MmPV@}t?)WQvx2v{O^JupYX}MA-fUYa}XpwsmacvrIbtZtnf1O4yK? ztO)aZ4)prfw{iyp}&; z5hYEymtlUCsCsA_dJH#rg2O|bjb)J z38Hx>359uw33ZWGZpD%N^5IGZKk2G@q~6!UzB`0e${26DW69L_;MLNK;)ai|zVYO7 zfA0Qs&ZbVoBwfc-Y4i49`H52VEkJ;~6$8FaXm=5#@jv`;&5plxT>ZXH^y=UW2g%@o zZOA-al;FuMq)}f=*r|RbM-YdG`h_la#yiu#JF><}wXA~4GjBEXaP1Yq4F~B zhu5HI3G+_AglKE0W3~wtmtC;RUnopT*8|6=OA1Wl%MQh8cFN~TFlm@m3Rvs^6hPw) zM@9Lq=vku`>G>i3P8fIu$s39V5aIRAYoFl>^1w6#}d7Q?#$@j<#4)17ZMgeAuZb|hA|m5pdI{AZ!>$7O!pZ|SmFvSIjeE3H_qEH&V2wMR>5a=Aq zd~+i#>5#V=sK|4#&}0~qD()VKS=l7O^oL+!VX$NwuBJmY#DuEByqZjlUCLdK&gQjv z*emz5>x5t->?~%8A>9W&08j$w5$_{AB~d)%ES2cRotlPF#;S#3l=yCnvLtOw^rX~C%`hjO%c=!yxZl)|4R`$#*uG(2l)YKA7LCl8 z2ei%N$u7y`Yr+i&-?lKs)OoNaJH*4E!Y(X%l((MHjP%tY#9y_n+9@FfI0D;tVZ1+p z$$pjXqaP5y&<1Mf{(S~Af3e<}nTZ`Hd=I4qKmL+4k>ETxYO`2cOniyg7zINziy0Mp z#I(QuR26|b*6!P9d*P6DN0+`8KD}*f!P{~&?O&aLCBT0f%rFK_3!dF<0$BN$$UsxY zHziE&q@-EPNWK?QWixy5ZrV#!QCL9)|4gJp`qZSk^vi-T4*CEh(wl+Mi?@g@MoMqKJjIn-;fbj zF7KYaVs=dt0f1)8uGgzgnk9Gy(S#9U$*2%`WFNuAo5uh_(putgysaxtwDUM2K%&nC z)w?Fk@FLxKV#vr8_+WA&v)C8oA*~$;hQq*mtJOO-uxU&HZM(KmQ2~r-c6Bo!dodvj z<`u=f;!*n6?HwOglvn6plmoKm)`I`lY1WVKPtW#XNqONdY=J4!o5Z3O6$(Dy04u|7 z38W@?M08X)AW>JejMi*{yfe}M?Iz;GVUwUXOJ2Pj{62+>qzNuOWyd(G_q)M6&Sa!Q zyZe^L9#DUCMZHTF{G&Kd*A>5Hq^lLSGnEm{a`;>E&1OkyB&egiZmR~E9IGqCwmhH@ zHuaAH5+o#DOCtQVTDC=IsXQmWN?@`(ZpC~I|1zCFc3~{r*3_1iayQ0+qJn`0`k2KH zI(n zfzvhsvV+HXW<>?L;oK%hTi_TOv#@puF^u63htVe8j7k|x>@}I*P1J9zv+=jj%yqu2 z^Y8?sXNII%6@rGzS^ycV9xa_9q1-McJgC(-zIB$&BhDi=EHJ_9Z71UYlVsKXDjVD% z>6cbZs8B&*)YjtdrFU`i1f1%7d@e31oloi7f6j|20Aq-ymmDl#f%A5vX)r!>BEk=j zCI^2$e`0C=qOYRB!hvrARw5ikh`jTNB~6JhOhkG3Aw8A}-8%8*dvMf(1^<Pb0y9wmtpb*MYb7}-o*_L$Ak=Kr zXk>?k5vt^Kp^QjPCN0>`nY?)rUuettezi90J$^Qp<)3T2n;i%Xdb~zKb2cS|V;ZH> zlVAc6+v>#GjKX}GIay0Gro+QBU26E{q)okOtDYv|v*5|O6%M{W@l;g}mGjS}HWt7& zQ+X$^q@gW%(+da8K*1;*=0-(sJ}8@@!#GyX;w)W}+gX)Hl5F{odZ254nhSReG^Aw{ z`jYi$B0OgdWBj!9 zsKn@a@+W-wenAA2zXe5cYQjm#FcBVJa|IbgwYW9I?`_Y@mL$qs1u-v38fg1=eZ7PZ zQ@Pg5ZhiS9ak;^#L7R(P=nkTp0g`@FzCW}w>k_C*?_OU!83Bi?MBequ=XWH+ydl0B z;oXM6J1v21Yveabm(ng@a<^H3#-B!?n}!5sE_|@CVv2uwSL`#4;KhvsqY@oy85VJp z`c0*gw{vLkZA4tb=r?2X4vk~>Z&ANm{AT^-@hkWy=f-yblExpqkIoBeK}Rizrv0U= zBA0B~>jfCS2qq;0JXXFa)Miwpb|Z3pvzIj`Yrqk*%U_3Y?~{Ac9I>UZbF(Jq^5ncL zuM>!oG6nA8BJi|Gal;camJ=%dCBG5=Yhbec|R

vc)QbYQQgK2 zeOU2CP;ai6@|#abq0pp1wrzg;htvVW<=^n4BsqTuaTCb(B2_c{Sw-%)$DBlId-h(p zonZ^A@H>13#@bMigJN+xmT<|gggN;#)Rl7E#FFa{3hT;@%}`7Qq@Cmf%TlyP=SCLG z4gJO$id1{uNj23F)_^zc=4zA3y(Pn3lSE1o=`fbb%6Xv9{-fCZd zNN3c!k-Ec`uRk)WvoX{XE$YtH6<#GO9iAESX^wab)oIWGTHUHY`v zw`t)YFKffkjx9q$7-9s+A^aTg-C8f_7P?6En|VmJBaR>8IUHD^cY&^X#GG+|z)Xg3 z&Usp1TA%P}V3|rG^#5c;rl-tw#gdO01jiE;2w0SPyJO0t$p*;JRW;QlC{7{ynhFJx z$$IikTjs6m+*YnXAFw9wJs6I$x#l`K(Tp)iBcvFkJA||<{^U|~!H&`Egrc4*MTS^J zdcQha)$;xDv6N$~ug{2uzkf1ke*Xdaot9lCD&p02zYob5L1Z2A+7Lgwqo2w~1&HB| zcHqFiWxS2+G4LSO1KvMamzdGV|FdV>Sy({AlNJ>yoH4S`6>H-)t{p*d+q1sdQx2Y@ z5}8BEXj*7=nq(fEC%4VHwM#0@NfH1vv4TB401(!(PWE4cKegrh!tro!S)}XPGa}&c zzgjR;f&Rr-u}BpePT8a@AI#XZb%>&6CBx|mA6SguSB668P%Y0MQn3f=uf-Y`OJ2g8Zu33s@=doiWJimUaAmkIDnlF8 z-4&Px=8{r6n|@9r7Q5Y_iudJ2aWaZ?O|cCyaauB5%He<~!vCqszEzHjC%{DEmAqZ= zuJU&IvPGuAfa+Gd9)+g*$xXoWnpk2%q(kMC;44XwG`A7=iHY1bdnWTFy|eJTx8=Uk z{P75yQIjyuM`?U1K`ythadoj1BW`Z8CuWH^Q}4aT-(H2l1B)y{#>=ecRYV!}z90dr z%PRSgTcKh(t)6>P$IyK7?{cQeLSnLiL!Uu`R@Q!HKlZadIL6SBL=lNlT(hqsct1uW zyoU)1!Yr`csjFpSRKrvQn;GHrQ1!!=Ec6;|K0mJi49w$S;b-mbDYXPmw8G#i1tp25 z(XD`r%3-9%7qWwR<8$NndVYxX`_dp^O`36JYQC-_?0M=FZ7*QwqWS&ZMSfgSmFYQ87%USb zOyAiVSAl)A6q~L5w0V zsVc_?n^Hh{kM~EY|KdcUit8WVN!}6OZH|JG!QUTUo)|4gL|k)Q+A(7uon_Mn>kv7% zw!W_`bkhp-L2np#^=IX#t8nc3w}u8}S-^-w!VyPODe$ap`0~d_t+y2t=jTJSvDN*L zkTyo|-u8TF_bMM@;kVyWQnM4i<49~c>@Ee5)(f8{u>ak@V ztrj-k8bmvbw!=%TSC~9!n4TDxEF4xv?#|xSr~L1jR;tvs91)LyQ_ez~d`_`isx7V+ zJ(f2}Yu?JfRftmM5Tm@^PLb{nn)^mT(X=#@?l9P6*Qj9Uj3{5+3UWGdJQikE4rAs? z72%U61zaXc{k=uysm}bV1pYHI*f2|(6;o=?4_t&<&WUVA2?Hlw-r2{V25j~)ACe-8 z4?iMCYx1E%gJGUDTPM0s)kVY3rXA&en7RYMz1Nt?dxy}SFTR(7ed=FsSMD^_FZ|_{ zKINloCFnf8%D1Zi3Xh>YZ(=3Vht&Uk9qwD@gVoLYe!zR zfKLjZ%ho?6r0u`)@-SJ4I@)QlRHAQg#{{1B8?-wj!UnT{5$c-7h$jvfmiW{zmrWE9 z&a_>GS+Ndixfm*_g*UC56&U!~Qux+KL}Z&hB%xq!nJ%8MXB}1l#fexsX-+U*K6*@g z-TwQ}ydqNm0Inf^*Mp(49D7*aiB5`&od=fY zsIQc>P^yrUgM;(0%)1zU%1L&u(HOv!En`t~9nE7S^-2VbEUGVuLh@FHwP*3`3883j zcn#_4gqHS3$M@9E#P>Uq{oV@__qnUNl6I>@d0i|MW5Z%e-)wVQ5|{V)A8I5|kndK9 z_d>%bR=6qUAZsX5w7x)@Apex zx$j<+n3!nNS8dKtha~6>q+hsSN?te7&1)eVv%dDqB(1o-e4!i=Bt62&#eD))+u$jL zCrN6OOqri?wyey2FT>1XrL1cf7_TOmBczx$vX=~3E;TQyjP^PzZc@asA8Fp1T4=RT z9~?PdTpZRWAdsu>!DyQ-aR(0j{X5vWJ^uFDv~dC}>e~fB1kfNNo9nq9$=r3ZA&-D} zTxt|&;X1@kaid_7i6{8|(!|^Uh0YL2K>MMyF-{@H;LC!ea9ui7rlgg3$rB%DV zwCq7I0`%nB1PFO*(F4@j6FDR1^9`2u{YUy=D==~^rva{8%7E3ITiGu|e`m>X3OZ;Z zIlZXNsCWf5Ry;-}n6l29Ihso_?5T?^wToX`4u~?h^)YO{85nH(jr=0FnBaA6R(qQ5 z6@vWNA*}Y?@h;gv;CHKtm37=s8}>Auaa8rRBl(%5^YAGpDP*th&gV)b>KD+~GeZ32 z_esPc%U-U>hs^ih*W;yBA-`BjbHBw_9Y2dxF34Co`l`}($rmj~I$DN0ax80Y9!7YS zl2e25lv4FYC?DFpg#!kg>M}CfmF_q`Y*7u3UmYp4VQ&y>0ecD=OMadv%ok&!{=Gy2)sjQk1S(G@)K@fYh9rHX;cy2>F9g+sTbB-{rG`j z3N;y$tPQwR3RHN7nRBW$v0XG+5+ztVY5R;F<&zA{3TzH(1^rTy)B9PH-S)MWi0T!a zH&UZ5e8)=|>)mYx^urghwSdnl_c3kgX~&L1N$Htuvo;$izje`ADHzB3!Vyp3I^l&L za|88acg2qn`qwX|!;oAzOSX9$f@XbbNzTDM{B!I3IIKAnD!i?VhIY7S zEW+P`ndWxQ2vX9%?8Gg1b7bSeGK{t&lCg&A^QvdB?sOvdx)$%+k-N+?dyN6l%FD#fupq z#RwsJ*IVthg7r0mg)PBPf>ao3@nnNs0WA60(#3 zjx0$&=IscItkG^h?6VM^U?A)`Ce`<@jkG|*Jdk@{? z?W50gq$Xzj9CP#5q`+y$Y~ih3gfDrq)JqVmqU%9I1a=^u;SEl7zhy= zIb?&H*|x52)>KjBq?Z1Om(YOZEsSYxFf%>9YoY!>HPhI^(QI=zkKjukcZhB~?81z< zzeO49;19E#w@P;8pY(_MO@gTz%n;;G?o7O9XI85UJ3kZ_GPZu}9C7KAS;gJ8x#-xi zZ_7l8Y*}GxM56exKa`z4EJwrs(h#z%80=(O>$1Q9@>kTn_T7Wl-ROm9HeBcZ8`gdN zymOys_V}~wgxNY*zPa_fN1yS?Iqz+>?&J4`Shf-Q*}RN#fO-7otA>z^(jm*ys7$0c zVPQMt#~I_nTgS*67-p#*j#bvn3r9a(*$hJ&*x%H_@bG%RTnk$!*PInvaH+ z?ujev!mA4jU~(L<$#kZA@IvqVNWbC)$EgS={cS>d@1kO`?N0Cf;cd1aK08NeyAuGePXmUm+xNH>EZ-q)UNbQp0aEYw!&TrUB z*B|mP$coY->3)_2hQzJE%)A7iq;}Z#P#WQ)XM!fDwJLh{P%8zX+#X6FV}{Lu>kLBl z$eLq)2TsVDTIq|3mI~OXVOj)nZy=}a^g@#huJZL-6+5L|!bA=H1^y0(QF|=3OWA}< z0QvQ<0qgql0=panxi;N`Y-uTv6?ffe$X&PGf7>V3CmVrH{E%WJ+o(TW5<+%X^@^6~ z|I&3GA^(enTueSBILNRr1&)5`p^J(IE2U?}Ru67s0T4@-=mAI06%1`mXGH>boIoj) zmPM>=nCWzKr{PQ^5YGV2o&K|pV%_)?jYwzka0)Gut8`SkOm9+5SEed!tZd9X9wUY`A-aScGFBUIWkb7CSgA4btD4@;J0V>2H$Xpf^2&PXyMmqdr`u-HkbL;e+6QGUp#PiBkz zeG$wSCS`;gjTqC4Y$rX|dZ=Cf#B|A+x@@nNKQAA|UXls;;}8)k4pwqGelR^fHS5TA zwN1{NjB7Q%h$guuMX3aWEU2$Vt@uo6S+21bT%R-Pz>kxPs#sna^g{-z&s27wk~)rX z9k3_BK0rgpfyz+#(4aA?UbWN66+w6qxl=o*LuB$G;oCuwd3wy8@_2y|$Z#f_(uohqFZ>uea? zpa`7Ssg%D8Lm40BPEWuyp^gQa(_9%GhZ@5;p>I%F<(w?o**b=RkTE4gNCk>!B~0{D z4o+Yh3ua&WiHM)38-WknpNBV{r>+FU9G*m@n=NOlsT#Mu zL3>P6hrJ16L!c((EFM8o)q!K>OWNd~o|&G#qf*?)p%wWW*~f=z^;lJ)$0a!KndW}G zJ*Fy*0fV}jq3D=a;%p4i;Fweeq?KKC$D$Gl1?S4yo5j>7Cr+gaKP9QeMF(cMEy>)z z6#bKiK)$Pr$oNS-ARBVXZZt|pSldftWv{URC_7m}m|R7KymtFF_PY4&jRob4=S)5F zSHJ(<&ma2L(%a82oXZ8*QmP-?Q|7NbE}mvSn+!ivx&&drg&5sLW9IDEX2)r+mS@1)o`y z20ALqr)mipSB$|VY~wn&V$5aP?r`r;=bv9=u$yXlENvHuAh#143(>PqnJ7P!2(`wF zahs3@lT-(nGAemUN~IQaKiU-rGm$T{t_DsI2g>>>1%JrVnE_WSqQnhx3sy1{#h0A^ zm}Q~Nuh^bM_Ad4r83 z8$^7SQ7%iHD@DJg9anT$xex}aCT9qlY=wr0$&CUD>Cow58fu?0nz|o`6M)=r!XS(; zN(ks_Omv*AxS&Ewtm<4vI|gyDb)!lq&I}I}<<~H)#Q9u4(_X@*>RZ&$E1Zw8-xcUh zzXJ6+cR!ScT@tN9hJB_DTiFk`c2}3($-@7Gtu#Wev*#9DJWrkVmMC!ljzmH}K#}4f z64Jdh{x%_zH4~EQhWwr7d0sYrv<(deA)~_=4IFXRAv?GTX8W6vQ$I$ z4ug5hsIftdsQLy|ck0O}WpX=rC$|QP9>=LdkrkIz`<A`aVck{Nt`=qUb(ed zV^1W@y*70m9>tNZ5)6Cbz2xIb0~nE*4G9+f!m2ZrUqu;z@e$(%~gD=+X#4&Y>+%45mJ0275!v}XQ;$Whr!e`MHi8di`YL{u#{0h{5(gzRms z?xo50>0FMT%$FaQgOKblce}@+X}t(581SHl!uv_*Bjh^B7a zt+Q-8XMz-`&pgb^U^D! z=a`U7{=96M(DXAwLdLf1Y7#J!FkumdKoc!AO`~1X8zwAf0EV1Fkb|F6$gIl5wcIW~ zWHdW7^YJteL8mI_tYTG{n8DD~dF2(tc$=iiiGrgIwu#UuEfMgg3c}=y)hPK#{>7Nj zqj4`Os%-|)nLv!%RNBhc6-@l|fq6*~CRI!Z^r9NK%o8PghNmpZ57~DVyOjcs$z8(3 z(rG>;GJSLyVQEiv-OoCiFC8J*NJvLuOg5+eoc+|kpB*%hkTmZ7aNnmnsfY?c?b%I{ z>jk?t6A~oyS+vUMxNhT%ev^=|`g{B*mQRN~PQFESsUhz~Bosj!=Lt%ml3$X%AKB7F zg=?}h)asSGwCeZseg!n`)XNJ2sBn=BX^rslGbLG~r{G-XXHV->nS;wEqyK1X9D z(q!)EIXhU6w4$TpQc{k?{~1^rac}62Hm>nQ;)_HkHduE~Izo1`)>P#;KZA{41gwMyg!YuS77JVH|k5=|NV=FtPRz5HHWaQm^Lh_-pl^s8UzR7;M{E){g z{jX65kL=4ptP36R4sZdsQ8s1uIZ@VQ>aHGCO-1)FIhEfG7s;_4Qlx}1kU znUM*^#aRO@6=>(xii`>;Aqg?0GShP2Z*{8C*?z<6q3UUJQkX`x$;8fPiuOp}ID4mz zcTZvHWPz+;LK3Oj@BG7KaOQ)PUv;ErHztSP{oy*xDjUZL4Ey7++v5C39zOevJ$}|9 z;oLJ9nzk~-Sh+RKJjWEGuFdu?&=LkkEAg^ARB zaoAb6KceA&Tikmqf9Ia?cP`Rjyo~=TjCV`nhlCwcn`CV#%6AEdHES@^PCRVVR+cz{ zV6-zhDr*`{s&EhGFLyq6*$_aPrBB6-Tm5|d?YAFKKjCK#CY6KEHiR29QjFu20z3l; zx%0YEfsHu3O(saXdoOEg%GaWjGC)VQ9@)c?X5yyj;M|GgctW+Q8!pnoaZSQwuv0<1 z!H*F7b7VusqCl)XuC4D9-$o3Ix`RTqRQk51G(kVjsUw!8l zuWqOz$weyWiGOE4A=lAvDg2N_#c@SQfS^)jKnY|<5Twy6@ZjBN%T%~LkziJ58Ygaj zrhG$blB$xfW_OyMorZ3Mr2gQ8>6u-jBRqp;(g^zntcA$} zBvwqby6QPah=VYyO8~7id7yGpV{Geel8UxTL}Nw!M@3rF2IZ1zq8y}FilxKuZ5~_) z(v?TLzm}U88WqdN`{*pliN1!&1ruF9XNWpXZk)uB1^kIKd&0`te> zh{{4CAiY>O0I~69?d{`0E}Ppn;E4m5RN^roa-zAQZ5d__PDr@Zm!&=GyyN7qgPW*ed-9aFWgr5%GyO2o!{ys?0`l zq>bCC9JcIGnc4UQrI!@o9t~M?Nw(rPtCx`Tb--``lWh4NS%W&eQe|}z(h-=2@+V5P zuifjUSDxN_(V?V;&c|i&Ljpx!u);0CAck}+tj-HYaK)@tilDVfw+EXDZ6q7n+CWLA zdv0iP*X)zCyUx1Z`1A*OA!`hD;@I*x%F<4Su_l9*gJ5FA!rU&$Hs#CQj*^Tb6<@1? zZ=1Q*1s{i_*`RQ}HE+JtRf`4RMJPvxvv`Ox&X8U3f~KyXyIK^u>^# zD8&(yLP~valO_e9&7?0vR{@s4kcXI3*0!NqvT3;j)DK-;Ze=nn(IL&ovgD2PfOV$a z-H4Y~Cnf;pf0~d#{IDV|<4#s<_p?RIVfzNTY2os}{k&|sAz_31*eETZ3Ge_J zvQLLPV3RgbMidc3O~;Ha9VAV~H;}6{B`+i@Wi!0vV}yWB1rG~UIe`l>_8}&9F%D?E z)sG#LsFdNEV2Nt016R2q>ikx*w#-*z(P#TRsve!X9sA@-xqh%Fal% z+lCYTZWT@r6YiqdlyXCYbAjJ+d2DJxC{W^g9KlIqG$1iRa-@lL>whm&^T}6#k%uct zOIo?|$tP>AEa?cj%(D32K2Ra3QgXzB2?k1{<~ZzUn6!klao&02Lc|8n^q@^+6%y`@ zS}fWWJkHMCktz5sK+e`>qad~8B$-NIm}Ytam}4?j)WE$I-9QvWSYRcDf7?sUL>GXFc zfTC4WfIR^dg~VamgNd@aLFUASc4e0j`4fBR4(d!1#c>~?GVEdz z*++7-U-A3S`<&%K&V;<2ggn9zxfUCs;{YbLx6*SeLPg8Pc9Gw)hE!ynTGAQL2f@-H zV-B^+R3?c1#(Nvi1>0;lOgH3QaKHw0x&c+$&6APcxT7SgjS$j^$w;@H#Wd-bK}{_H zXYfuJG^>z>pTR3GOXq7)h&%*PEcSWYkGgEYQIifS&D7iDMh+~_aulconqu^(V3eEJ zu_*_VXK$&4(Vp~#z2sV4hNYCQ^{Er`bVCrANp_0mSL_bX{JNY8`74CH=cb>@J=dI; z99dHX7Uhc5wuF*hT@)zT0gp0*$s823L23{qg8{~-_)7{+PRcQE-UE?amG_118}HzU zoXtZyULq6C&=^N=(c{f)e~_bw2un z@1}*pM3{Gr(tk!9XV^Kh592Ln1g2YyapnbEc})=1r@G>;gmlWoq%tRr-UltG7AC%~ zKsiccFwZ`xT-nUJbsrsn0K zA?-n$%<+UgfZ_=f@~BvL*}36{!99^I2hfo`Y}4}sT~Zzel;maE(k-Q=C0E~orp4*y z9UxV;H^E2hYBGp}fvUNQtpy(h=1nHUB<4&%0Jp;RqdFKNJOHXuLhA zIa!V^1KNNYp0naKiv5VQQ#O6JZf`b5R8%17yo9te+gGu9Nn}evSKq&Qyh&bHYeOz9 z^}ro_JNf?-p}TQimtpX5_KDWioC$eC^2L8kNc9T)UEFyM^SiJ9uL*gKA2KUg0T0w4 zQ3-%W%OO>5J!;{lCNR^?cDa&?ms8W%W;+dXlSHM>8yl7y2ByUA6{yN>7R4Z+Vm`rL zh>?TVvXRyZxag0Dk~#aBEyF4o3dbe_V}Z{hMR#D%=0TsNv~g4UA_t+W2V}c7G_xcq zPg#JBCD$>^37NSiD5}(onP-IO8uU!^MOrLrsGKQQ{2|wRV8ED4t6W;ADKSfB%|Cx}-`5^}dCKR}>wdMh-KvQ`z3fUB~lAkIVCX`4v(goSJX0lx8t&1oX z?VUHa-@NgrL9%SY6}(*|9js+=CscVKpsc=SkZ_i&*J6;yiAdd37J0HfHCP826Etm; ze3CKcI5sn#4q{}CzQ_SvJd@sIQfMuXFfU`ULt<~TA&Bdn^XnQU>=PkDA*e4N$Yw7x z4qexH`qI%XwflDn`NbK8SAu-^pA(Y#3)gBa!Q<~fz+|ue5CaJ5ue;x(X!`A^AmsZG z_!I;u`osh@mLkbXz;YxMdtBqBX%Z?y{^D0Rk8{jlCM&v6wij;H6B!{bl2GWI# z?Kj(RHk(*;%&oSTJcHXnnn6yJA>=O`OHPZ7Y5DaxWHXblE6?7xlB zX(gPtG=+J^;dmSNxRM%$%(3M;Ng138;()={rXVfR`{J6xK7i}3&SSH{!93KEvrq{+ zg-gp(O!bjF7seOnZ*y(5G8$N|Wn=y>n;16u5dykf1QvhOUN2Jvht&>^vDbw zmtbv3lU#LRb1?VU704$vmJFm+VF(vrHUmu?EjOFibi=6HmOKTx6~i3dt=OtX7TD44 zv+B z8cTw{ljZtZiy#oAJ%`-`BwnRzH+g8jhFAiR>rtvKRk9Dot!-Z|I(_o_kY_nP`EI}a zPY8Jpy}+D-KMpbY(aQdm;RrW8=7jWWX5RASO;tm z+`Goq!~`Qli^WRn-qa`644MdIzXuhAnvT5$AK!TAy$~kII2szDHy;aAV;eciGBojW z9@*UzJgK~nrm*yCQV7TUl$(vKl||U<4c0Qud7A>;?#ayDJOOsQ zu*%5(3IA*zIT_EZj6Z_m_{OBkzo8LUi z=J4eIFid|mA@?)-U;70i_d^W!gnaGc8}Iq#p+iFMZ@SX0>?8b;3+fVeHSi$S?g=mA zh5)(t5RJT%zUv8vu*On^$W$h)DdmqCwSe!@g2Fl*m1DmHv|7yI(V7oO1X>}KY0PMh z7fFdYQRRZMVPKE^%6WLJW!caGQiBz|r*Bk+Vuqw?rMFsytx!$H)JeBD~ z-oE-xLLOdWdGKlYU=Ke-SN6wO7DkUHB=Q0_GQ`7NJ|N_Nh=J(1AGz=Cb##@@(^5Ni z(>a#?M;YUWwz#aT$ z&Gt=`S5P%KZfaYZq~OiMTCNI~%ob4>+mu_9Rh>r#uqRkIY2xgyv)MGW8ORpWBVMTBg80l=J^EPvMWH?~;$=GDu8YRwAlwBEd1?p!+WOl%W2 zc0w#9FD)AM@O_sKndFjO{%3^z;t*GCPEHOKO;(3&rF8IeC5;|WNV;#oc>9wd-#{DL zLqhI{7(Btm0ul0qho8OY5p+n!ai09#=T*PTt$x#$PRQf@kn8mV3x>XC0~2|%1r$l; z+PU>wx*Mo-8d+6uqi78>87B5-^Uj#OcMk?Oq9C_yc#p==kxEA7CT`P<%pT{dYHA>4ZE+hg9+L zBI9ycU}UYJab2uK41uxB+AKbz0X%YQ6kT>hrHi{A-+Ng(HM4!=fSlpy0KqV>r6Ps| zfWj<5T4~u5KgQ9-Ed*zvT!4xyMO0GI6f}ay=A!vDO;w7TzO@Qo7S3f;ue8KX3E0)K zOv&*%QV$I_ zH^qaPgBO;cvEOI(R2vo{J1Su>5j8sc2o;;p*J#aKwT1Vd?o9%n3l`*6*x0{#l zdh@-Oi>LZjQ}7u)!M&D(Cod|%GMQ--*R0NxkShkH@QNj?I>#bc+UN-OLPZeD#xu@y zT1^(b0o!PePv#&I`QdUdzE0L)UW3aM>zES18S2&4LMeiyd9>cU6|wWYM}M;FnUTB( z9+wLPxO7ThG9B`}bB_6ClQSWIO-{-W*?UKaf|83{o83uSGess|ekXdsjGk4I*JODI zf)#a29&UD@P5bad%{x`h17H)j@JdN~vFSLCF0$iU81!BCKS7 zrGss}!tl$&krmck5`SdKLMK)D)le$j3P5a3rnz6hX_T(WVj4NN8bd6cidomqOdTB? z@RS-DY~m+3h{%N?k7fb5ChIx|R;^_&DOg?&%<-p`O3t^Dba2YbhF$0;qaVsi&_YeH zKX>m`0VSn7@>I2kKDfrb;ATJ+zS2Ly3H0{)?gy3eEdPOg_bZzEnUI%}kjKQb7eo;3 zt}`j1yQEry;Q&5FksQOo3E0?+l?8UTQf_-wJu0@L#2&&&@R5+s1yuB*+ORHzGT~4g zuZJ!}sMyQMj3r&G%>rM=vR0F`!gcuJ)H-#8T= z@+>DIKaYNYaVF#?A|!GYA@g#bPp*=UNhG&=!Z>ObjG24QU0UQW2}XDcHO;rZ_YH_# zlFr6&5K<$>p=p=tZK3ouCykAPZ8qgu#F{vtRxR;bc@lb6X?FmK$$R#YF23STDcNWq zF83yDX##B6-UZ%`DZ|%6)3P&$`=mR^0Q`#SkA-3~eqCY-$f=524HLR!fcI$>i=&=6ZPerkvraQdV{RTW+o zP}jVFIh$Q^bcCAKs-`O##Ji}dmc;;GY8u9E7b{&bgpjuR^jQ(F1yh!}4Dw008MwPO zEydMMK9CP~C#1gD;O&6rv(}ErdQq_ zYQ8J*1j-=`z>pQzxnBiCi7uS(48b~z66eiItV2Pc`2?xZy%dH#@3{@f8gzQlel@vs z?#D(u)ML;FfSb-PvgeQOyai}JW2hDbHss6jD9Ryg?%@rDV9#=nD3Bb|YGuC)(2!s7 z@lOed%#;)&sx>*XdIoyg;3G7gi1#zIrG$9L8Cm__c}ma(fFAE~E7=uoPhH(LS9dF^ z#bBhD-2sL~a)e8yNschbA$f<3RgLiix1lb@V8|YCTQVi=?j=I(JPy{Zfvt5l0X$Ub z^+cbmhJ@q2f%~);gJDCu+Hn1cs{%(9NDf)Rl<+`)^+Nvvk7;Hir-r<&F=U4e7gspg zstE{){ny6ra<6L0m!2+Ku%TcLi6Dj)O>#%h49QNVm^SEt2mw%G=&GO45kj3$rnB5k8|0 z02ec$wHOQ;lIIoU0Aol;HG@MmS$Z6{IXE(5$VA-KV(y4*-+c}Z z2|zAr6Bb9&elA-Css)B>(PZgqz;F8WWMALpv=v=9%xB2_>GLffMH@k(3z{&Au-{ri z8n0JoKV7CT&kOO?MS?>^c8=NMbA&>=6rCXvR>qJUd?_|qO+x}1F{JfpALggkxFO?l zZWk+JPsxn$h}mRC{}~1?tI_FKc*ruo$Te}A;B#Y0K{({!l>YQc(HT;kL;3=NKxG8u zBZeG224fB$U!^FHc>*ZlcMsJ2TkJ3>F)CtSG}@uTsA!U=A*cJ2OdB%f3@_;-Q6U(R zMDQKD;3u8afofaMR_4jN5?{viYHy!nG9-dEWHhjI$GP$Vf*R7@K2?3IUs9?bd52M8 z!YL2BJ<*1TTU9ASroL+P+ry?I(=?>jItgx^oCHr!TCM3DGG4;jqQ$Q%6)Jh5!g)~0 zL6MoTk_Bnfb*Kr`kes2LLq=c!wh8Ap%`xOa6&yp-ios*;O%Mn*k0MtR9(fPes}08? zm5fx0{zjBvzC9~>6nNsZM!OVjf^Rw{NhVE-mdjZqha+Bpf+|F(7}V zeVITZ{{%2{rhOTwKjMUGNFLA~hm6L4ch>B9jbIFkMc7?CW?uoFY*%-!-_@Q<8AGV= zjd?M3U|d=OEtTq9PDnDhZ^*cTk}x5Vq*Au_lb#`w>XKdU!51y|@F-)*!Ov&yb}4B{XbIWo z@Sxj*@L)rdCPi;ZI#aWNA(xmU>nCRwMJ~w*bO1WThPjLFY^BLN5i3~}u z>q-TILqqE1koB0Rva(9OUbZ;ll~H1-G69jI2FEoz*^Y^WG^9*Fr-1YSq-^mSlH1 zB!zc1JUlU~mqS9LIkKzzRzNg!NMgv+Ib_z5bV?TF$PK51>Ld7z1ZE3Tp;BaJI6OCa z8oySu0lN8x9yACS)T3D?xLyG8q<+3lJ!r)A{n zN!ajbyHip~OIm=zxFK!(q?KG662ls@au-2o#W>cb2jztR7N^BB60H(3Kl;(~o`8Sc zX_3}NSVO{UAGE+HX-Lwfh;fw8!I3dTw(;Oa##h-+_o!Hvpz6>daVP{b4wX5;nIUOW zg@M>LH#iS@j}%?#JPv=p<*hy5r*+Fu3P<+78H4T6?%0)jfB(RB+>#VvFlxw^Wz}j5 z$)zE&Bh618W|yJzQik$*_x8z`iI@EA-4bmw3J+!^)ugX@8Q*bZNK#bcCb$n0%G=;Q zT66&tOtzQZ;kvB$vTu4%p_a4&gF!?7W$%1K<0|4fzJCl26c18^PzZP`1#fzY^mp)* zbNxp!3AneYSWB=d36|7MBbo{oE8-tSi$-X-c&JYOb76A)~B#@MN;M7 zAM%6_riY>p{kTESY9KnqdmkTCmrWiZ z@E&-d-k?@dgyf7%Ke~9DI~+10xv0XIIP9o1)Lex@N7=8(Zy*?nkSZQ0x5)(< zoC*0r9W7)@2^sbnFNxHGf-w_9Ub~jBX>2A=)*Q(}#$kvI;Ht-Q*mLy5iI5XxR)plD z3JYhSJo&dOI`hpbU35XcIC1jg()`>bCogU`&K`MAdC11uiSK5Sj_OD*z~G$AzW3?- z%Sy=pamad5aZ=MF(+K$&n-1^VP#zY#&u?VNK0SIsIXcj^qLij)WwYm5{{9K*-`%O=^Gq zaC_s$6aGCTgOS2$dn@ElJp3W?@z&0F6u0qM;5!NE7?OUCpTkgL%7na0jl9F}-anME zb44y<4;ctq4ke@P{SU^EdUJ$4v_W)CKhB+oqMvk%iuz9P`SXSFzo#NeQy~)M%vFp^ zcb&T%As^hIh_XkIkfm1ekmV7@NDRn>nvmWd=8ki2RyCp)UW8WEA6kB)$dnT*&)321IiNJQjFN7_$Rw7*Tn~a#F*;MBf(|K4=O4J!FWo^U~w@O!O%bvPf066627i+ACo+g3lZU z(3koVSvy%Jhw5=0a(?fs; z7Hc@mV)!h5GkT;3TG>+Ww}1lhLaH#}?i7U)l1o99QGt*pP$$N!;kxXmcQQ)wJ5WdN zP(!!ODIJixjVy3~U~l7LNb9n>3PX{Ez!C&VQ_ zxCbSUVqZS#=GNK8$#_(IX?b&Z5bb~ep9Rc`s{dP<1Rc69&$H|JmetlkcTOJ#))=@ zQAt+IcoqPUXBPJLfE{JdRT!w!!h0WmyhvL=S`=7tCnR44R(&{&)mzRnA(tM10gFkW zSw1%R=x5*WTVJ^R(+>-8EX}XH@Y5fb7v@gL>JSLoQMaJM+BwQ5)7W(X|1SNEDoTgY z+|7*@iQ&~*?u67ALAy>OnfnN-wE6M-%g0u0^o}Y7 zapL&w;k)87c*v1ZhICCzlLz^;pH&!onVR*v z#S0s!Y8C|++zH7SaR(uB@7_PAzh**yOVuH8i1g2+b06;5WAKo>RbB`Q?!5859GQ(> z!J~SDXG?b2wSs%k3CX1(8m|!{)tv}=TwT>A zO-PQe1$)zA(z5Lmqljo>V_r#6ZLms*9A*a?GKR^1}^JkVnfAYu;gz1h7 z9&(q;g^*?HwqZdtrqF`mt4E(N=gByC+?7+Er5_*g@Gz9C~tQClwE-ZcS7<- zy!Fe`@yCvyt6>96J-mET&FiT*nu{?ZX|_+}+Tzl0{x68O+2Egbd0J|tOu+x2lx0k2a|J}2Ihy_V zBkeyM2svVe3{iGo>X;vz3n4qh+v^be1`5kP$7g^iOinKc$o9>17RW%zbOl20Uil*= z$PAcp$W8NDpA#4PDtIwD4^wjLhMo`nn46N}xNVnUIm~O#RSFc2wU zk4@Xc8~x=M){dU9O?{0e5UxJ+(j>m9xOK)mAt{va?JmUa3#+v%1L9cixBm$Aph|jn^ z^~&|)4P@B4qEs>=Bt+JhB{HA&tzDxDb&(KlX#=g6Z1R^K=-}P*NG&xA1#Pk z2|0igBDxniW1Oon5Fs(BzVPwIMEQkv40mZ`oi7*OKxUzT{AA(0Z$grh#nWscl)1h9 z!=ZZPK=Jht%j6;Vy3zB) zo>Grd3NX7W5fw&AE`Sgdauau5Oq5^vs7FWy*LhV1@eDTdCM36?xPh+KR=bgq-O&%Q zy=Z4b+Rft;J>r44&BO^N+vX#g018L2Rm#Hsw@q-nU1@78YXnN55d|KbO-<&2H0n6x z@5pBr1|sCzi*N6%CCV?XCkTnWWDl8ll#NoZwQv*JBV@H$LIy-CRR@Y_XJ&SCDl8)b zF=Apz6&G7Q>OjldC(g`J6plS$gS0iHZoYUpA3Ih^S4LD+a&E*&LIAns5JPw&}rlxF!EIi5%gxuLf zg2nDy!t_Y9aN1}#GsGDaM3qRd{K53?a(iBkGv^38)T~d9oUek^_{uNhhAshKiCR=`9RcQ(f+iCKda_8HGnd zZ{@0Xi_RJkAW`G5arp%*51S-pKJy`` zZoH^wi7P_tHkO5$9KU+jq1J-eH8rC*A9BQmgzTn3GKG*X<+pgTur!D_Db!5qOtcO2 z*hs*3yB83*saHbc@I_{`!qK~t02CnwrNq-BZ}Y@{XK;py2b>LIDx%!iWm8T&xuzx# z!S~pz!{8xvS2qSF-IA}fvJg^AvvI`8a9(4YD40fKKw1dhgD3)~)lzhF6UNOQo$Rl#m+F>c?3GelxqZ`)8GP94pXU|)IUUmcg-B&Njs*K5WEu7Y+d%-wOSx# z(6D7sNGZLo_z*aTnCg-QC_GT(ZeXN%mc|whX+?Nz#n5Y2{+ZeNuvRjkLr`mT5RGsA zQ~C4?^`huWbf$qy19wSIaSPKw^fYb!VJmfnQWz${ptEBavLrj`CinJv>)*Y)w@)R?A``i$OVO&s1{0X9x=(iA;Z8Z}KjY&j8qj8BuEI}mhMXV(2P&&TfB*~_8%eb0NDS*~vu)a2-szag5T zX+YtYSw;K_5}8QR8ER!g^+SSb{LDTPvTCUt@(oR*v22L9=`dc2g$g$rb@)A~aR?>k6BGZZZn1kp zH6W_CsZ9J+`3=L;uZAAThNAQb0CGT$zpTNOy2sK;$Y8}4bpI-$-RB*5PPqt41L0HX zY;EAr+aK!5)Gl|=50vHy0om~aVQa0_Y?O@jV5L{o+gsrCb_J5SQJ zaDF@?_hP0WWfwzpDiSj4hwFpg4QV_f!xsxrQ+b%|9CS6+5DF@$^C0a=L^6afk&War z{tR-kFk7oj&4IckjFhDvF$V=UOh>BPKFlY^^fk?_b}@A@O{uG(qEqVW&3D$o2a7i+ z*)jQp2zdx|{C+zj&u{(x?_2n{))@cW#2EX#YT5Gof)BsLs#Ga5XRg#_(;?`BU!_}b zC<_1r#!9Vc@)Il%YcS5z53K7j(~mpV7)n)`hqZ((GqW)VNsTj}$l4x@`2x4+Y-f|Z z#Tl8Y+bg=wJx&b@xtAYA$h*szAOEd{0Q?GBsM3Rtv;R0r9gOK+&F1dqTLG zljj(i=eQi0Rl`qJ1p{-t%7)GWJ9M8o7;RpodJqbxmz19UU4h&X%mk{NPD2Kq5@xrNV5K%5g|`eV^nq zcbzwUl~fmsSe7r)1*326%oxl{IU@IEMoy-|T?ap#kf(P8gLkoLt|cVb^ZB&oxLFBp zkuhG$=EsT%Vsq}1b5e?*SMEw-iUX`yHYm3--! zCk)|?rNl^PLT%bhA~jcE-ryIboxkc1|nUJV+zgYhu5;As-|0=y3?;!*Fcvy2u$J@$*{y`Wgsc2E@qI3tYjUQ7z zJn;C3uAS5@15}mfLg(?m^EG6-^60VhqUk!xZuU`x2UZ=2{`GN0Jv5`=k4{02+d5fm^00?OU*ZC631;6uD&Mt zCDh*qVrx#9tab2Y%bC+mf_H4095YMw! zJmm9jOBQXv!)sdopM;Da^0&)FNMTv6@zbv>4fiNflW}z~A32jMw-y*>pKW>GUepH> zjoq{#0b3N}{v*j|1HU5;3g0J&k4G{~$h;ZOh(>!1Ww?!q5v}BpUb%u%c9{ORS%{7+CYAy3*B5=IkJ z#A8*NCh(cqMcof&;h##WG|e4cUPqbA6WBLfFYca8=EN9@m~93Mtr;}Cu}Ye4Mi3IT z4LbQn-REVBgv_TF<=vVNVsDA?fNM{{WG(hVY4?Oha#HRqf9<59oL-59loUPWKdZ2A zpOXaONNMNztTcoSQUN#?s_ei+6}FGNSGFcqK*$!1M4ydw;rjB-MLRHU2R|BYzMp`1 zo0H91bDL!<%q6L6C2=*$vDuuFn25^fLWrFq6{?i_`b2GtKC0-9+8m|o$JTWr)VZq? zXT|ajx4kn>UNQ}?s6|2wiiG@kTg(C*hq7A=Q zt6r>a+P8(g;*s27O$xEe!pR)mGXR92oXjW9E!n3F@RL}V2xS;cCOmD$*gR>x=zNaT z*jt$=u#9al=(z z?7u54O<$digbY*kkpHZlgtYG?bSZrm$VTfD%Tg{-%M%7WehUCW*I{2uD*9SNe#yN_ z0vb+i=FxJ~B5%inCc56YY~KXe?%T0;*;*WOXy1YbI5a4BxH~xA^%-D2q`7&{l=1b#928z zroG*TN@)L{&yB?@Fepg19xd-;hl4v3?rpJC^MuxjI0cfOUp>{1IghrNN?Q zDDMA+%zgNwzQpBZM@wldTF&;G0V&(F-jUo=DOq$7vZ@>{TiQ8GF}~~Yx600`iT#j& zg2whkrZkqp)fsIotX`>7m1V~q+0`UkIErnISz-z*d2X>|J8@WNLAaZIK{o(%pZP?b z*-^V&MsjXgHd(f7*{&5xN*O(by*HFl z7^h8NOLwWi&ymk0ZVh!djnq`iUuKp*t=Im18e%Q`w^?oCrIyZ`6LK5PJ>-8@J0T?F z?))6IX=`fh`4Qo&z|r_|SEw`*&@oAYVMGSbE2E&ftZ{Tebz%h&S_bkw&j_zI{KN?2 zHn204bHCxEA!NZgYiAmTC3yW`moxg7vrzS2?cU<_vE7K+9>0dn{>-5f~=DFW5&>pCb*F5YM^1zJO~VgP(!8uvD#i(Vzu!Uz&YEssA;4E52=OSP z&!c*lhgMXN>T=`*s!JF7&nx#l$w((<<2FB83ui20S>bmG*joU z$bMMhdzt7%O*BDlKaPGoHTh!KV-(5`HMe)Oa(1*kLf$iJ&0}t% z58}twr^i{?L6ae7UdC5vr$HlfOUKnXp~Xv~S0WihAtXa<@-OgvJzBzgy$ohO`R@E1Zo!x% z>17fUt$X1puX^{89{^YN(!WT^5rt<_^EJk2N4p_pT5D!ej~PQ}pJD_*34g8 z86SC#?lP4_yC(%ny3Rc!C(kD8l=lu3q||CFDHHo(b)kkoz+ic|_orG0F%+rUJn1b;~FX0?Tzkyq0(C zt#~S1BG0oN?-Kh~jOgtHE0w&sNX2&FuGp10-UpVt-PnZ&eLUiB*LAzyZd|uZgObgg z?HCWJIfw?aV^?h_t_~XgMt^`W+p=TJigDTZZ3_&<6L{AIMwU55JSVlF;|wt3L&`5N6+exo|O?kkUDQ_|pG$lszZp zKd+q-l6btQmRa_gH}sfJQo{+26B7NEQNQSvSqBa%C{i%|WY=++jaKpyIdhmVp-t@R zgtRAtvWytkMTns7HuF65a~F!V~Zy}ehZ}RJH>v#NJ+!SOjI@a1^5!QaTgD}ANS>cCz0K>?W9qPOM|*)0ku$U4+dda8icl`rstRgrK(;? z*GZa%@y4f_8k#VRrr6pxHAZC<@}2|B#_!>dL(|XHJUH}#!zlYT>AnG9_ts7C{Br-c zggk8c(*Jg*WmsTcP=iRZJxn;h^ZfM-CvP%!7+Mv6dgJJ#4U^wvJwaz z3CAR#T=G=*xxUF{OHfCLCa~eV^mUPRcqWP((qmj*a3qj!;CjFp@BqZ(q%>?Cn~@kv zKjM4%K&53h8Wt%!pzTzlKkR6=*Jl@Abf4QF6m9s|ZkKL1jDg&4zw1)Ry69A-gNwL9 znOq3>Cq~(GMrwB)$5JwW$-qkL$=wDuO%Iu$jUgnnY~-{E`TQA&u-XUAd;aXBUw&P1 z`T0dJelH&KOn68PG@b~GZbwM<(%n@1JUiRfKJyiHXF&&LDieyvCu`eQA93N#$+ za+!v4kAohi2I3t1R`QV5G4xUBQOgi44lVB)Mad0w-grEsCw?It<-OCbo`%Ul{hlU!$ zELw77Al5c2MN#0Z`8j;<%ArU5+gIe1;Z!!9eGb&RL=&>pcAV~@NVyJkH~M#t(C~oj z$+U0GCgj?B{xTNRuNX(k&T**n0RU0Iz4S0@eijywI0}*TgNsicye%QsOLtK*e$A{` zj4MJOG}o*tf0I$hXSKDgg|1UI;iREa-e;t&O*4t1N7qtqXhnI)fHuvlj~P>6Ljb^0QE*43xAHa^sxk@*_5D z%F)Km8{KC!UuzrszitLru6QjYN&UZ_mwnJ&v!)4tpg6{#<0#iMHuf`Pz*YUDJt}K) z9c3CxN97(tM_MkYp!FN-y+>8vQp?z{2WSbudhmOcW@R;2J%-kFiewlC25uvZV9u7` z1R;m+Qd}tcO6(HH&A143(wz1hyh1{v!YD%1vj;4|R5=-zpX+f+r>MPkLAa=TT$Oip z6~&~T@st=o_Z_RoP1Q2Av48xogEBN_LSA^zvrp1OYW+V6dCk0WEmd;*g4?gBEgqugm zRbBFD_(;z!j7AwjeQ`s`B<2lHQBuwl+=51gl8;RG zb}Cv^Bc!RuM`UH5=%b}?B-rE|P*|qz%bsi`BZ{A;< z6EauRuZKKju76GkWeUSi6Up=+=^xSbMB?%8tsUilBzRPH&NAZ_$)$ z?qefx&~akhiA#=%W!;dC$JW+9;B?Ej-MGJ14Xf@*Md}oJR&owhai3$QwQE9ZjQM_p z=^=*NVse{^`O&78L`$U1q^IgOA-iadR2x<9l*a}rH<8^=&uG$m zdhNhyd;Qm3LK2d5LhiA2#rT|%f45#f`Mfcm{PH1xO32iYPs%K&&ir_;IqJWPQl8c9 zIoU?CT2c?4r02MjjcJXTI8+p(7f2E(2(S!~OpEq06PiitBqzhvh!YEPK**iP$-F%2 zD5aHF1|bdJo?`IU=5cEat$0wa_T6LEeT~?b2{rw?;{>A#I^jOSZHy{%OUyKy9-5X{ zpjaTP(%VdRD?a<$9xsGx`ZLWAL zYI=pR#K<$~TBYS4kqHzw7?}EK&`%;ea#rmJ6I-vp{WMPL5?HFFNM&ytRFFeaf4$#TDgsgEn{~gLirMWy8ZO)1jZmVqwEByqJT(c}`1zcs3 z*HQ0i^JF7JsH%c!fui3O@95`w#NxJ>t=%E8X#KUzRbn2OiF#?HoN}41AOIwTAo~;s{QAgWj6kI9npp+ai{BLnF&bZ`YDWrrcg_U-jh~x6N zLp+8GluThb?y#CrWv7*-%+c2jn|hEFQddHPj(3BS29)2ws^gyJcbjzWx@j6zjC9(NAmknwSF}g74??bZ{s=riw{W{H zX0!o>Z2tWg>i1?(Lef+1%q(0rs+PmW0$T6P=78mKl?9;YLk#CkA2%VRsk~(z75fv6 zn6`>_V-y)TYB5@i?3_8UDu8<ZoswFC2b8>ZqeU2szbwNr3R%bdLWq6^~6E z>unC0W^MvDj~|JM`$19lK9PK z-#dP(NyuyG&AZhgq_`M*v}f7uFVSwnMo2z)$kNM?KX38;NAS8uXKnFy?CQ|dJue)( z;%?MXduiS_C^`AgA#3 z_Sl^W#bPB4GAc|)5HO!gt)JvLpGc%+ua~HausB1lv3&5CgN@&R4^DpH++2f@AFpEObxn0nsO#xbW)jLX-qo~g3V0l5j2-3Br`^^q%r7C zr^^NL_S};!^les2DuUnN!sU3Xq{foVKT9=shfAHVgk;e8stHHdc0hz|f>yqK6}!xI zJaOgH`xd^j>{gYKTUIU-cu(WZK}d8vjLltS5;BCD7cN-2`bq2J<@0xE(ef+wgd`a0 z@uuZy^u(dN=JC*Ukk*F$?A^b%4BfC#6(N@&h{xB$fZi)-#==jXwZ)2$y5I*}eFz8% zhuC({Eu4!Tj2BD`asj%aQD0-@!kim!dLwe1@j@DyocZIDaMS5WTT?bE9oO94d<)q4 z-FM&PfD?B@u7bHxTS>?AdZgrjX0O~eIV4copR%%zC&eZtoiwVum)OYRI(!)EF)pux z$7-*2q`gi=1whF92^!BCl{U)p&2T_4lW{C#V19dvv22t;%%>8WD9ISL@-o|7`%;9a zkSqaIMa8~OTR4_i&h`Wh$;R}{K5yQw7*rq_I%CZez-hw>2?O)=ujajIBV=gshckO# z_C-j#YF@f@`JM7T4gdD-p=lvKA=myj*m3x~h7>~5P`vVx=N7*4+x<8$Uhu|m_nsME z4MJYK-+l)^xA3Xo?p?Bos9V!@t%ZVDemm_0oGf0j{I`4Ohd=wxJXyK#^S5EnWEyf*LGjk9q znEn<$WyX7%Q&Sz5y-S-T3nmB?Gk8LJUyt{W5t6xr!A8c!BN)Eba9x3rKqKAUg~}h4 zR55D3KGk0_!n^wvHY!1?9$eG~y#`zTOf0J9LYj8mHCuvogA1*%#>_gcGFB_t1Ly#}@cZZ9leaHaW# zZI%6E54Ik02xBaSpnwB0*SPos-)D_6X$@Y4cal@K*pvi9DywXtgk!-ul44L z{VLYhl878@6={J5B=*>%3~n((qv645q2?F^5D{TLt-7%61LlZP#3?+x6R*4H9M0LL z#UTRH($A8RK@wPR!^U%IKr&-1U0KMB8g3|KR4I`LTGD|7KNnw*bfi)-Y8j6V|8cF! zS%(56BsTy}PtD>34}EUoB?cioo`8SmB@nW5F;vrrJk)MOesb2KcP)6tFgl6fYfq$u z=h3-9Egzo7gGESgInqfZ3Hc`6KhUfHzOP1aLw;qdeYdZ4ghUVk)I&lNl{P|Rs1Onh z=~y^s5pqoo&z=v&Hc=#`n6e2HQhI896Y|#yK+^6Mt>WRRqtCUr(e+S~W3}XCF)yNF zQ2DE$ZkkMg0t7HQF$PA!T>-#|qO|cT07zyWy5=12)UL}o-1TQgx`acSvsjUnwIrZ7 zAyr7G)AqfF2fyVhA(<@`gO!GgXq1>=*TPXLH6#r4BpB&lw|H6*QUvr2zQ}kUlJ3IK z(Tzcg_Ho~b{N&6q_R21*5c18gCPe@6A~S0k?IYo+5Rz=9$!WbO#!b|f|GpuqC*;x8 zS?%q6X;#_CFIcqOe*5ir?t!j^l&frMAg+ZECadX+Ru`ELZ z;kRgyun3O3BEgw(Qi=`v4IXp}hfYFjSv%(dhh3{`C%l2G*70^Y?OWNKvA57>rgqbh zV_4YHiffz7uZxIuq<&lw&M|cZSjR|x#U=d~$xQXL;N@LoTt@qtdINuhb)Fh9kx!Yc z?DH3$Tv!8&RfME136YT2lueP4o0}2ioBJf>DWkOm>xPF_KFW*TLz0j~ z-GHJ)sZ`!<;5zQOgk>h%y5NYj)^=J_Qv@I#AzlRaBBb%KSzzCRleIvsQ|s2HTglIK zZ~8b6{zylt2NUBwu3Hxoh;6q;|CG2PsVb?~+MTd7a(KkiZM%w*6Ti+7(o?}l`zVC` z?6ZrZc1RQLgGip0#~ghBGQ;8W*>N9*uLTd`vf0N@NWc)+4)}C648*-0Hss<3J)a$X z@4glxjVYU+4Y_%hyb0-%dre+y`8Y&A3Y9RH{i#H&Kl5Xp$)~LS$86MIqnoik*#gGB zW29ppCS=>cPRO>FDOjtOC8oW6SGFg`1RTYim&j5d@*11t7jUy%Kr&MAns=8_H z|5x4l@eCnrX-R_7v{6TDMuyb0MLBQu9T7TI`PYmWUK7)hVaabOsfR3e{= zn(sh^oP&Pb7UcS(7$&=iYS@vTwVK!w^9NNJOO&JhIVSqowOM7zqkYaj$nGJ@NSwO_A9RjXC*7}_@ziX5$qKse z)z4-KxiREU$hQ?E67i2pd^pn!wV$h`QW{rQn~{sYVpPB}kr5@b&GmIT3wMl4g}7V+ zyDQRQLNZ{y!G!cSbmNwlSwLNK=GvI%WE7d1B6hs3-5SvYRwZdVvhTL-mj|DXs}mb8 zn}N<5Li*QC1>OIfTvpi%4@p49f9={nue&&qbbbz#mHn}Nzo>1N$HLH#H?-JKS9~!aCo5oN3G0eh24NA~E1 zqqb*53CXy~2RvrX5OPMrD0o7Sj)0MFo$_oAq4=2_kmV_4nqd+*YyUBo7Y1aJOYzpk zIKd$6^rUGKR8w0jM|bn)k(+`ws4OUXG@5|bM6j#t5NZgO*8uUOl&-$(M)9Ty^V0{@jsMwLT#TcH6z=j ze60tYJOjoXPDpavGia$inKK>yy@szQo~v})PV^h*W29AeaEnKc1_o->Mk@`MlvPB~ zgdALh+P81Ke3d&PnVj83)oMAzte69L_;7;>DH3}qX6(3$Eg@I|!&AZAkTZn**X2dX ziCR4vMwGTEsDi6es+g?QHY~~=NO~7qBUXl;upena=F+V#LT$V7;NB;T2-W9fD{Zvg zIZMb2c@WYIZ;fRrJ4NKi81$1Xh##71PG-u9LfrIfB`V(RypqM_RCme!H|uDE9uy&I zmGyjf4m&oTaX^$@wbFlAX|&Ga|l@nXOWey%7wE8t(y3)C1gMh zjTh3^J|vE2000jeR7c~CJR?l$)~@{3O7*+6Wj%5E=cse|l5EO=>B!(Vn|obtthIaI!AkgxXJX+;ma;9w9w>f@ENvL9OYlO` zxxr4zju)30rYs2A#O`3IH)*`{<#-`7!kPEo^T<*piGz?vQ3$kaK>oM3$nJ~{`F~X{ zLRLAjdC(-P=@U1I%8JKeeX49O`PN(Q3K1!uHIfM#w?a+|_k)9f^=>jwd3kFF`WX6| zk2=m$Hbd3bpp`RRK^tjN<;GCa#;mtsg-gb>d?uT~4ATqN9~ETm)790LPnNnjdgTf> zh7qV-&Grc-q;aMXPJ9mU zjDK(T;`v6c$}7)%@2jg!LcTn2n>$eG+@sZ4;PH?%gbYf-6OvHW6Ol0@qk23}Ix}cw zXTA*jEbuIs=w~D(10d<2&6}==+y(;Ddv%K$^*L&oQd93LyM--ZDL2rfdPSQDXKgdq zjZ4n9rpNI}J=khyawbHWeyTX>jE)?x_-rPTWwVh93EW)5BO44F^>i-+A?1mE-AqEt zC+_QdAS9YHuzn;javq*Uvl+9@4|5MMlN z;&J_a33HM$@hH%r6hf;@it`GyzA)bi;$F< zQ+=mM8nS9@^A<26w>H1DgjD(1&rmvj_QemZ|Qn z5~4Tw)j&zTMkXfI`tbo&(7osE2gE8nBv#q-L{CU?irA8b6g<_gvLzw8R)%U4l9z6@ zCP+f^JxNG9+i`dS*Sr-xA;a2xSZ_m0dl2HnStX=9NsZT3fN8fO2}fcwU_#0_)(}!f zBZs_u&=S(jAUT5~WDO5ZsU-2492gnW=Cw)XQ}*tKbSET8u5X!B$gRh?|4{J28A|id zJ79de5VC6H0dZ1hG(e74Wj3w;J2LP`Dp|4ak*l4w$BDa^yc-QV9`c3-sLr+G^<`Jx z*t6Yi(>e3V-63(}YD2C))NVuGaKw4h}jQ4ULoY*Lnj`(rsoRG!Xy+^d=kNzbG;YY!S|`DX+rWrSx*Ww%14WWIzsYl z#fFq)2O()cl4C*Jkn*MyGF&AKb3A$=vKBmpCS-NX1zWzw05|+=s3`M;;W`j5Z06FW z(^*fp1&=>Hxq=~N;NOaO_&Womct8VjGiN()eJj=iyWk{bs$ceLpqIuP4-X`De;D~Y z9}Sd{pb{F68Z8n!)|df49dE+?6DL|i0;?az&97loTvK1^RWS~@hXyuvUku|c3!gKbE1PyQP4LaILN&Q8XN%Vx|@K+;B$efXksy+=i} z8Cp9JW(#!8c=(_jZbEWOfP`#3L|vv>F_KyMx(v=nt#}^{GKw|N5CfYTxqec=)E*gD zI=9VKt}u1sZNOyXHG6x7khSp02mj#E6B6PNy2+njmaJB_cNT$>TM#$i&#CtQ$)n+3f#!JD@ zj20|JM)SBTcZB68u{0ekW8N%{PKhS1?k>WvlDjZTJ z;K%`wJZNo5@@!++kSZPBfXJJA^t2%Z--lH9AmvyO%3>-dyBJnUP;#=|Ixec4)rGdm zW}fmjB^W{mLF<;b4V}XB6F;$V&M9vdBTvo!p2RWQ5aR(kn$!8xwVvUY=*<;0dl;vAZ4}r z2$6mM_aU7O6&D&uNES2DEy+r9oJ1D3T-2#`6UtV%88pf_8~>%hMVqQtHmkB^Z_nDM z?W`KS3EAR@kmjM`_)~H1pT#0tYAnvPEFJineu2pK3G*lthF4D@@Po)d2=AV*}P&RFf2?+!7zNCEC}h1NN-@u zH<$Kf%-e>nF)#tio91F*gj9ot)pJ(Il^$)`XCaxC%W7o{GFl!ho1<)c?-nbZ4}s5r zjAdIjc_xvFzO$-5zvMVwSJie!b0TD{A_v;06CsJe4St(KM*QtjJlvETbr z0*vT~s4L2p94cvl<*b`LGDFCXquHS?sb*?34^Or$3*}JU9if6D6Nq-J4M{Cf1%ctM zLxPMZ#sEk=Ax{>!sS%Py1SX|o4nE@MACK<)kika#ObicCI6a%P601hhVt1byrZVal zBuJUzAf2T<)-rp_Y-8xYfc9pRu79=EPGqdA>O{UdZjk-^7fVRXrZkN8Pe>Yw4W?+J zSA84&&_yy+K@c)uL1fBa2n`bc?NZVu(raRPhLCzSl8~D>Yxg0;a_Hf^<%7W#cAva=nZcZ;eMPMm)xJD{TLmY^s`uX9Bh%X)m~h{BVh_+qo*H z`Ye0VvEP*`SXK;zd<>T4axiB zMHNC4V#1KL3zNj*WURjZ>0~JrjbXk$`G_xf8eM;HXDPc$5GctWEo zM>Rq#TR4u|hQ{aHs^67M6Oi6yo3hc?QjcLLQ);|c*`mgpN0~L&op6V&GRMhSsW}eD z@<*G~*`kT88j#95#ttVN^J|3M0m64>=*KnnUrA})|^liF#H zhOw>Rj$1{4dO2s8cw9B(VMfYEU$SGYr_^xB&L9cN$ZmhS2Qz~tBzr4V&M*6lW4*3h zay#2JY&4OOv)T@VcAP~*>Lp?6Wm2hYZWWKJ4Jn6;Vz$I=gOGxZ^2SpTZ(DCfZnl|f zL*f?39byuYV;hopbs4Qiras(<=Ms+%sO_UJxRXPDx+ot2Qk<1jQ8neQkVwc9;@pI^ z5Cy=f9Q@+~~uiV78%c3vQIJ!@G=kDE4wbaZ6Gj>sUp zFl-V1P0~-|yXii&8z=RC`8}dIVQ;@+w?c>PORy0|RRzk+tbHo7uq}+?d zP>f5?zmdUrVc2pCglyXVsvrnS`648>@d*h;5|AWhE#pzrpw?Pj4IZ~sNAktphUCK6 z!lSSurB1H+YrF_aZD!h#Wm2jO zZH1VWlaZF!SzTq@hqVdG7$QMP3Xn9Z8@5bIhZHXAPu#pQ)l(JL;xQmXGOLsK%*p!r-00=4R*Qhs&i|p*Ng7QX*Y<2c$ z6q3I^XTUh~5#<^3@kcuw(S-qxx?YTdJLjDE-itjCR5~o6V#QfTM+R_g`P#b{fQ}VH zUh?MI4-i_iD}(VK%g~Lh7O+wWQP&Q?gGrmpM}T z83ZBKc)0Enn~9-oaTpy+=`BcML$(-tqG}skp~YOlB-`D zkqm|m9gan?9Drm8};Y(z7Tyfz|)4OoBjgW>33TP=^8NfAKcbCuSCmeHq6OyHJNyy5J z9eo}IA+G~6@4?i@O4^Xkns`Vl}fHW^Sw$zub4z$bUQyCHF zqXfGc;XeEj*Uh!S?93MbgnX>Qrk|WtPvB5GYaY_9B`G@pM8^^t&0jAaB;^plX0`PO zDH&WB21&@Ld$v3DlleMAp8e7`&>c2H!dP6m=lrW>R|bWU@0%SLrb0;ZVrQQRK}cA& ztU4L6ylqG|jYi#u^xT4UrKkR8KIqLzxepl=nKcd@lF}s?Itd9`0YoGu@u;;SUB2}H zp{{90kbU1a2ttlJlP<_aSr{_OEq^T_xx}_o4&#hbfhU0%%ISC=IVDh|C+P_}9lj^; zN!c+XGM6*?pBpQfh^+iBvMCM}6;n!iV7h^Z-&EH zi>?d`AqOutr)?-9`R?Myx;_tV(_lRL+)o$;EB|@fDgeBa4)s19oYev(ugFKC81JHZ zg(T$38XMB3-PismA?Ml&iMN?c2^*3(H)oA}&^u`4qiR-*$y9@C`y}mqkoJCt$x1)w zyvXy7Rsfl^YRi<_ZE8+i%lLQ;lpFiDwPkvkkToaCfbqZx+13)+r1qM7kkZo3@|4xk zM238x0|rKlKp+|Plhl+&mi`)dLjI>TYm5JqM2&IR)itEuhIId`apPStu87@iNL;J7 zA$P1&B!VX;A@Q=9`Hs?tlz?o~mprQ#9Vu;X{f2{~pd!X;KLu%V&sXy_;mS*Him&N>yFvYo=JDiy7RMs{;v|U&b4?vr~G@|(vX#YpkjhYn*H)O z*`M^8T(kL%HnKKz!y`|eG^n}I_N1g7ssg_pHY8=itx9@AZfzqZUyFBy4vDgO^dL-Quqk6zf8SVL9 z_)7UAmJEmVN64TI+m`xZ%e_Y(N3+?C2=&Q00udM?sSzvxNd4ytIlH;~HvJ`Q`#6JH zIP^|CREJa9hm<{GB_T;iJXRdqVQ`N&We@n2l$#^u#XoAto(@t8Nv5YL*mGauOO z;xTZC`1zan-n^lF6tnN>$Ll>If0Z6m5ORx0OtZhUZ(D(X81RUM4X7_b@2a8P*n%GN$;ezwzpCS(}BhSMzT zHF>Bs--aSHiO5+&YJPa39ol;$suluqbpN6q-rV677}BRt9?)p`9acAa8kx2 zn*yHu`+JU%Ldo?rA@7c6*(8^(6#Niht3xGSf4xWK?of{1KDeX(vj5;dBjR`&==OXS zl1mJsG#52I>1YOn!z*^?!|Z{@16JrCP4hFx!P3S(`UpXs0I+(+FXU)i?^=RPCc=*v z>B12#54*v28R4?JWecu3HZcu2-L(nA7$ESFJ-OVGO^OT9*7o@w1CBQ`zTT zmi!pJ<5IJH>YZe2-j)KbdjunGFXlKT(5MC?8${ALqyVO{kJ}sJA;Vvv2^j>>goFZ0 zNP);Z8i(W}k>-Yw2MiTgt*aJtzLVErfVd;_oRpAq6FnpW^duUM?0D6IQKls|W=m%t z#XH!W$SOo|qYV*^zKY-M_2T$8d^V5Ou5P@}w+G8d6CuThLwMic*ItKjOH3T{ingz? zFZTf)wO7_f3jZZmzR*lfb0+a904WF=2EmbsyxT%DxuYKP4!LYpi^D@IE)d5&H<8fh z)^2Z~!8IXKHB3(iFqR->U!+U9*|VHmmxZAe(x_J)<&==_N5v5fScyiVP49O_J7N!vp#)O(MKL9o{$%meoYOE0Ikb?ENXrLM#e-o*F!>z?|`HvWb+k%7K(-L z;zsvz5MRf4Y8+B{NC`-thcxb%jYFkxMXMfi#d--o_u0>Ke)f!xK4k~Yp(P=eMTah^ z7F)(g-Q>K}x=Np4*kqjsLi22`5OTQOAC6Z?NjNO1@`SvYm}(zdFiw$ZTkK=-l5zkf zroxTwYX}K89(%|j*b_4R{M$1ie~+PtkbE2xc^VRjG;F-U9{`ZlMvA9!O-StqUa%Ye zzL^T?yuzwsS5R}$(e?=$Mh^d#QEVh+Sx&@LPIe};zt5!gXG>`((F$!jq-zdw{Kv`@ z@=^-aWi&h*$qi1}))huRvK~^-vI!y4=SL7S5QKcj- z3yZr$@WmDn1lJHCNN{&uG{`^*1P>AjZowf0UxK~3Lx2T>2MH4F^4)uXOii7tsX1NU zJ!ks#>E~%EAty*}&d!S=t-$_(Nb|{Q$B3d=$kHrQVq7}@wb|O~(s_JcXg?-Oco+-n_rZDc9>2%~S=}a2m*$U@z=Al^>776#UUb|Oe$jRgJxBy9 zPe1tqnBLN6KPBX(p)a%S+KlfrYZzMwHkUFe>dh`BKYxTF`T5FMWZ~2D4nn5yENOVc ztV)+&KEx?jNj()|02rmu)A;BojbbY0dc`&H)Xqh?AlQswqR880WA7H^&x&VuB~a4P zqfp-lhN;%|!V>7N@HUymIS?f`wDP_7`j9ClX+h3H>lL2yms_28g{+a7rIO-K9I@n1 z5x^0VMrFKl@wm6lfqi30!`n&r5mkd5^UH071hk-HvZnZEV%oV~4Rc07&-@9K)5^>8 zC90F1;cQD7V&l<9WB{8AgnzG1`M#Ugqp0_-{R-GR4Hrm#WhM3o8APfkD^a*UW4duck9% z%@e8ae)g%7ll6HBq}GUx1cH%qYGOt$n=`N&w*r9wp{%r+v_;pSI9&Q`yg8{uku}*r zi2#_TCAwo$wXbaB50>!(-i^U#^5fger#@W_ zS>q+{Mj9S)!J%hNLn-j-#IjE|{KT_*zH{6K&5XZr3k)n%F{gL)Tdb-;;0wu;&euzL zMn;rATwNvp9*!0IG;!WyylxcAsYrXdYm>`uir<-ZTnBG8w`IwBV=7Gr_;^ZwM-A>T zaU{AhfMwIK0QqmeZ(NoL3`4z+A%a6O(Ms7d@vxn~yK78i+nnW+$+zEJ@Y`0WE-j#z_oGi0aQsZkVO934? zZ0915PcOD_?20$94lXTyg{#ljEAwX4nTMQRk#~1tMyW_S3)3Rvo74$18*ctrOfMQL zO!F6T1%V-S(f_gVKxzJIz_d|4Y)lmu=eo+K?jC+QF~8hD-X5BeI7ji-X`OB#)#1$}2OePG|?~mTqKv*leo= z=x8jc?R3+0!l?vI;WZ!ZxG^gNp}<)|Mh%rw{9&R(I~t?j@z_H*X62I&?sY9_j%; z>o5Q60%iB5inn^GuX`$-e0(+&x5|ac!q6d%@zHc!wlB;%186|?j{?IZf0MI%dtciT z7}yes?0(+ACR;9+L{-0Yn_ga%m2r88o}Zx4Hkp97=*(s$%((v|QI1aiEyxm!s<%r9`8}`JwOBfd&EMc5_8Mn0X%1+xBtiu+EvO>K9ETa+JpTQpmUr5Y9P$C zG`_IZN6Jo!y|kpR178gto{j=gq#l)D{=EOxJwS4_{V(C#BW1-9v?!~-0hu;^F=&~h z^1eI+ha~;x`iF8d712{{qyPGDC8#YU3kc@(;`sWtsz0BeSjb)=dYHlBFxUPVN2PE& z;@FWW{fvS1U}L)KM+Hqti+_51QBVy#ih92^)>-ip=LIcDO;r9vsHhAkjIAC7f0Hpr zricIS!~Ku{{{HwqMo3qVxTE=L>zkbLlrL7&rP3Y@t?d)OkYhp_ye}T>J?sowJj~Qm zAKFDPTRg1$%9q?SqnT1Y`ZdJ^nC#sEu5U8~9}_ryz+mna%O9tevQgfP6j+&Ti_Lx$^g&n4-GYBfX5SCSoBb zoqdqlp<+mW@~Y-DM6gjq_2uMlEm6zl`+|Lfb*GKi_hVz#HOj_tTb=wCVIf>AYZRg; zN8yYIH?_Qn@?!#JK46jhKNlc`l)Z`phS@4FvM|0~f%|d_~iFC8mS2GRl1fg3rkD?a0aU{hjW5`s-A_D;*1GO7~kUhC*?jvu2}sX0^N z{}97}dSAfHOkZJJs+rgI_NmpFh5jsStY6-A%H^acv*rV<0DB2{8#}5mDh5CXMFMJY zS$D?_!7=XfK}$LbK4IsP4JXtC$b)&B#JdvlIp-?n>@vCQ>W1KDMQe@r}%MMPrSu*i6Vk zR*6>KoEzB>-s&JNb@cw02dCMNH4seq@qK!7ZM}RT`N_43w&V!GZKk>~Pp?kdIftr7 z7{pelqW?ci9@~p&#&ZuZ5yAlL2ge4we7TLE5aszNwy(1PrwHLEMMQE(DDC2UQ)p* zNuUzD2=Q5YY@W*eS1A7_g6@lF>ZK%y)VrNK-`9bBmxopnckB6|XK=!52~B6};~%L( z<+e_g?<3et^8WX2jkBQ8*xxVWvWMB!TpEW1$l1gOb)nr&4llG&(9!r+!t*3xU!d1nWe3&5Fgpl2_zP2R!Je%HF`#SxGN$FIb>EGk_zd?Q{TZ63j#A zi$SLk&b9=1Iiz@v(86=%_17O2mkocW;dLGqr~AI#v}98)Z(t8ZGnWlSt$fFdg{t?W zTIXmczu8Ji(X&g_<7om?|4WILmC;p#R#b=kGvl&6&K=CPQ+Zmz}iEN+Lp( z@7!^16)8L37L`wXie_bZEm>-mHZ&E2CX0~iy1W+y2>n@E$#JLOOnn@^{hXlT?Bdta zo)LwxS@aPh2?tk~UrV?FE{)qlt4(jqpOgJh1^I@a5L-72$G<71_1}7Dp(U1nRZ|AF z?Au%xIXRhS(WPbL1d4p3Ti-3kKZ{GOpmixKBS{8LlQd$KcS3*O_9FT(4%2aAJ3mEG zbYwzY3E+UA7rt+M3P+c1Lc#G@S{W#({fhH@6|tmVl6R~)r4-R*q?L@W&aG|;_lL+` zr`6Z{(LJB3z_80g!8Z+w232~uwK|}9u#TyuJ(nY?bSXMT;HM<;-YY>!tfAX_=(EWq zw_6tIw{$Zf(gs3)0{wnx8lErQj*4^NcVxxSVIMHs+@b_z@?xaF{`9C25q+H-GiGU+ zwp{*2fSwkQ`a_D~47`HVKEj_aHn9W?BJ8DSg zdiVrHk$?h*zc=%#9mWATRIVFxa^|vk>n5J4d)gph=@lnpq0@OUSQu+CiKnAu_d&*@ zV>GFrR6tsZN1#ojpcsY{4K`JxGIPUkK|*x{;wdTvKev`H=a=FgzeEPB+Y1uV$3*BY z-XU$Tm{E9w5FA!w&-IPISpHi>2df-_v0Fm8J=lAI5luGu59Y)9Ey)Afzx%BCc$O~_4`&D#NBOM#={eqhG!4sYD6Z@aPsK&fRq5oZA3kXZ#Ddj z!9qp8zE(kZNb`PGV_E{UwaHi3AnLR19oMIplz4l3{P{^>$>$NkL9AQn#$qFp_zW8= zC@5vM{mW=PPUmh%2`#$nCeu97De)T(q$(Gq8vhlPZJU&bokHCRM zz`LctqSQ;5z59amH-OaJva|qBR&Q9Os5KFme%>0J*+6zLP}OK!_vItUxYc|C_Q+oMXwF1!2bpULxg zEn{&}j0M!&kDl_pXHU2crmYcr+3TLz5k?W-A%2?I_xe8wWJGj$!|Hc`-3#CC*A{GC z*_+uWt=B#Ma`KRMD`TV{$FdKrG(|T@5J!aI+2|Xb!idZ z{^}a434R=4HetnLmA@Eu_5I)O?Uh$>NNcd;PN56|5Yp{` zF|nEn3e=*@_PJ!z?h3n-X*@Z)e{-BPu>CiBi|oTuV*|G~QZZ}vaKS!oZB{}{>LKuS z&qNk5TbGmdfPVr~q)#IfEyueanN=IS(sK)}M(GPA`;Rt?z3{jj;`x;$0QhVxiZCv! z*{N0!7OC-tG>_isGh#(@fVrfL@<=m;q5fYX;s%PH z+w_h$^Le~W_e$+w`@dETtg*dQ$aSFCo`pxPVwwD2Z2>$I@imh|x8*tM8fj=tqL!`_7ZIHu3z8BvTppT>AU-q%L}da~?J%U_I=+Z}c~a z-4Jqy7{+j8{bs!y&&|B0m!Q8Rlnp^{b948z&Cd-%Fr0&*0Cc=SaTB%`@JFbmhiD9- zSHT@-sfT__vAgAznq>*wj0zZk1BN8YHtNZ9_i9L6dY3hAqcPAcYNX0+mfP3Rkp{;f zhY*Q1PzZmAL4_7Fg_c!v==S%*X@a#@VHWks zCudyP?5|f=M_!sN8f?9=-1Yi%z4^O;V0|h%pu=ns1W_(19=SDKBkPmVR9UPrdHk$~ z6nt9feje_>9HfF|W~{6)F_q+`>XoyKhAx?D+PY!bymbIm&!F@>Sb#)Hj5h4u3mtrm zX@~5=5|eBzuQqjI;z;#^r(bj0d{y5cAJkgeRpLF--^<00xN%>r<=E1(A3rt#?Mo4o&9iV|J&8hjyx(WxjtKiKy6H*B`n?AVEkf zNFz?h9CF;^0R(2z88Q0Xxx-X)9%9;%$GSD#Zf6`K4Ed;^4rJX)+$J_&S?ibJ2D7NO0^ zl9H~P#SDBx6>A;381^bD@_i{iXjl0Y_mtjPt$gazwdlWX1AC@l0#ei6fWZ|~3=ej6 z57=fL*29aJg$Xbr18%dOoG%>^2-Z|rVVmj?aTcM?)tOFi0f(ciY)(cddIMlNbsQzV zZy;*?1>=-nT{|66*1Sf57{+Y#84F-o@00ZX^<55rS;ojwCxejT`nOlG@msbMpc6yM z(c;JUKYbErXw9LIW1lbidMJ4=FtD@IhgbGW&&b6!uqvf1P_LG~1-ryjG|LP8EN$o+ z0Ss!{4{8%GicC=%I%J&=_{^zRhHWzE^)_~rUt4kCY`cLGHuz!yR~`O35Ng6bf#1pr-gZdwQvG)>fm0ijQKX3lsUIi^M2G(@;KT>Wp368Ne9H*mKq)v2(K zwEU@Dxvt3um0o`Z^d`e>!IXRv z8mxP7H5i1lYI~AvQFg@7zNEo4pF`9{_It1^zY92wT=<+-WHD*HEY8qtkdC@^$cV4d9}P|MSbsOuLWUbsE0*4t+AY}D@@J=A z>!9J0s#(BqMf6Uw3fZ2JF!&=kH-LJ>PPRSEHNd<3l0S;H4OfV}NjG22X%^3wW{VX@?9L%w(P zt#y*j!!#Xi$$!|`Tk9O?-@is!r#~*7V1=*hin%)rvkvUYZ@C!D73^%ViqL|h~%iTSgj z(ANw3&R=Egnu4kRL2gQRb3(jTxkAMc%Y9 z?bDWX|2QjqP0`yf>eZNYpT@%$oz!4zI{_l#ZPg#A0kXm zsSZiHMe|zW1J1FY__;yXlnJ5Z^JolA7L6p;=P@&Gp#;f2pIo&z)6~_On+z-Wzl=Re zA%2k44`2Q7Acr>L?IrL~K&f zoo&u1$0C(rDcF8{DQ7w10Rt?;aPGcuZ22j4TODP}{k0Bj-I`($E736{S`AtaZ+NNI z_5D+6D#Vrz?R(@|{i7K4G3}Exw?3>?UzOx^eDTe`q?VT|Hpnr%s)HHOh0T3P(%b(I zb&@asPA2r_zurHQSFZ#bVY15bc(kmQ5`#KS0`>Z@4a&hk0uF0)R{8g7VRew&o1>AP zyt2?oWRtD{?OC#yB}0k}@|A<)v+?=Yy(~iWAuP5r!~i4wWsIXD^ZwV0o-xs^xnKF)|ViN4;d+>AP`lFXgyz8<&RcE-ZF#++(K+rE0P8U~V_ z0CPIPN8vAO+3;!g^l|J-5Z)B~%$$jypRBfe;jOV3oZf`!Iqj$n0|ye!lc2eVcAobH z+z^8%!Mn5`g9aYC#cX|xiJ%yNoqh9}cY~^wdGN;c13uhZ{=Zl#ZcBuw^SRFxKg@SY zzGIK56ym9ET;hgV1ev?jerHaB&PA)z6K!mc)p79MuugjphF!__%*;&RdS~L0^mh#3 zoQ1vlJtd^(GsIyE0Vjw91jZuO!~hD3^=6W|zi;~4wRM95Q`F^fwn~oU$9#mof!2Zl z=)MyiT+Zyte#k#)jO@g0zV%fu%y1^?Rt2TSSSeqVkgp{JmA+YWC8<{C(}B((b%EnB-vCGa?x7ozFVLa$V~DqsS=;vRbp>3@He{zVVun+3j>AY)ZO=AgjbIa=1M0X+Q;7d`Gz*S z{4QHxzk6%HGp?njW$`)F+3;6JvDu4(D?zAjLIO$#r2_wx48kW%)Ah|qjAjU1IznQ$ zetC*}2WL8~HMfM=ZeVb6Y3gUWG<~%)+0$Tp7R7pRnkG7!2#gJ2qjIXGwOaz|D+|Gp zSNypH-VmQJ&LRJFwQIzMoHoSXIFkxhLGZr2Ei6u0K5P%qpT1?#*bBLuA&TzJkt=B1 zuMs}Ma{85n;4#L;9^)nsxa>7lupD2rh^R9EAY>*RR;ahwTPY)h1HR%_=hq*ve$lN& zozwTR6@Rwb{gnQr*FyY3bv&Mg0IOeLwc{HD8sDL>?^^U*YE-P-^dwm=cWhI3>I&pH z=sCQTrcXYR388p2ir6MNX!}1HIl=$?&r7!kG1KF?l>UrVf8IDM!lGRPHtv4kCm(8< zaKpJa6aFa0y>}ym2BFp)s}VuZ3m#8`o4N9H{btW+VJ>PIAkAjQLvw zSG2#5hS!19uhI0bEY3!&zA@`CCynEI(HiqaZpa=x3uM(~n@tYZn*gD<1PH94%{(&nYM>Fx$IL9%g1?4k6t%}8v z929*ANif@DmbGqqf4y`^Ef%Bw4^_LonNSZZcj2ZILH_qZuQaKUd{3vS?N_pfIZMAZ*!#2?B4zw; z17mHvB^tFUA-eyYgn;n)3n5yhw^^HDZeq2cLNx`EuKMaF28PF5JPvC~pZT!b+ z!-){d%oTRhMwke1daQZF*D$yw<$TSljTVw?l+hfIi%3B+ zLBzI*<|tMojx3^WZ2_P%!i6X!@l^h}(!^)WwzWhdyCFPOEVVl{${14PY#mnaUi0IA9Ptl7my#VrXCHZ`XkK zx#qFDp?=Zc?tiw{ki{<$vvgIO6$qQcQ|X+cF7sV}vKO1}3nK|qx^INl9Ath!M#rSI zGE3OsxI&u8S0p>2U>X;K4?G%l`UbIZUv!HRO(gOvdis1q<_-;OnqMdM->7134HzOP zd7i*xOMcA^@d$Ux%A!%M3ZS>EEwUBOCcBTGhS8A`cYG3~5mQPp&xmDUIYoPgNbfpz ztLghFVQF{7BFhxFIC()KqSd z4ikU--jtQSb^b_Y7oQb&7n~*!+do$k6k8>kC1?AYG5kgt1XCBM^3u^JeHE()_jLF2 zS}GrWIj!}h@m&cYv25V(FQ(Af1u^FPT(FA2!>ZNjvTTPPD}vsgsnnOheIB~44n#N{gQCr=@dj&w z*=BQ}qRh6YzG{%e$)+eldo=5N)`?)w{E`d2V6WP>J=6L6`xOu;6ZFws4$6Km85a#6 z&cy?njA&B4vI_~xv&Wcj7OEA9n+=!*;LHCq8Y^-T$C`iz@FrCIjiztQEq`e^OU!SR z=c%ik3u3S9otNbg*6Oo$kfQHbk85(u=fzpQx`Ld{Z5#jC`05$z|3^lXBKyw5hEVE5 zTvgNhHZpn?F=MqZcf-jSo__bM>&9xW^{j$lF1biNOv-E9U_FGaYOBaOL5Nx~bSOQ7 z^>b`XjMUpI{8pO=$S(qkC=Xe)-%29e?{-9zi|iyNQCU=WVh04y)jd(I`iR6sV|u@M zI*pDCV8_r206fhl#bNMy3Hn4{$mzh;w~^>lQag<%Id`LuiT)i>ZY~P6u%EHb$_8##Tl5fTxz@ajA1hZs8_VJW+VB&$n2;YBf8p>z zY9Fj`fAlNjX_JIp8Tc7mIsw9~1F`$Jdv8WXps)MA&gg%Y)eLb3kfpUKS>h(2HwZw= zXNcc+E!WuLYxb3AK|K)qlzEmkRQ8S?E< zW&ZW+7o@aN39G}UE@*!heI}ouWOUm-*rP!X(4F}|-|3|tRz)%(&lBtVMrb^rV}h~- zGwHXTlYs|4QX#33-#~}6^ERJ&%Tg~vA_XKG4uy7o`F0vD6-G_sITW6#|BS9AhG~CEz5r9F9W7hGA|BRAJr%=8tk?-GscrRc5*N(MdHBpY# zP<&<2e^>?4knuK?NirAFLv)~(#UAeXmSmWfpiu_X-6#HF)|M4&VEDGKuI>kwGW-!6 z3LOb?yH3(79JPwie6uC{E4|jbr5$%Y;imucIhmfOozoQPCUb#m=ZopUmDSCq;=dT_ z2XO??+RKurLgr;7f0z5af5$7>TnEmI=aMKs}W;wceI)OU2Pym-rsvRaZy(uqQkK%jtuF;>%?QtfUlN?HrQiggP$QmNv{G1l|! zv=;)6!=wAj8V^nHmg><2^p^&s%b7}yd zugO#*Rqs%@ZK7%)Qh}^}w5a9fwa9a~lUTqHRh7@>THW`~%UeBcff1+WkGL$Nb7)E8 ziL0H38LIhU8tluUZ!=20gSn5zJL^`Pvg)ZdTO zfw<(Kk7>QLyeJeZMk}hbs{|JT6Mg{ro@cVXI=Ubgv6X*uYvymyYh6xyugKvS+n?@&lmXtCf3gNI z{M@bZ_{D-^CF-{>z#ulJ`gQYA{`v++DioqA3kK6yCn*N>GCH;S!;r--HgM#7TH4Fi zXU$>N?Wc0AwhK-KeaI(fXh=CPrkAlX?2Q@7HU!cEe5W1`a>&-pec?kBRRmXFWiuPf z-S<_Pt&A{@omP;3?%f{c8Y1u#A)@A$nop;X>aKQN@#cb1o1Y^Fx9~xGV;!$^SwMS_ zAn4D_8ON3=gtJDsaKjsRgmfS+EewNij_)li^coJ6^@YJ7o#l2(oMPb%f5wFrVS$w< z@PD|Hvje~TB(iSF$)-;@BmT|ae`m4nrn(BGuM-gyly!mDTfN}zU>aF-N`+nek9YoC{ zdjIJ(rSET%X^%js?iGu*PQeVIFx{CqI2hVR$D@^pQRd&YKjYl>UHedqJA**CP|M~A zheJ;P7RQkxYVqBp^Z>!bzM7PbrgY~;r4_{^L!NQMJtG(_e8P)0tZK)B&RF?_1sotq z1v`5fi~t@!1)R_j3-y#!7!uQ0T)ZoV{1>=Z040NPZV?U;J9(A6i5TwQb(em9{=>1& zcI#g&ilWSeZi_2@i(qzd4|4P;=iQs&^7ZDH`5WTqQhM!Ya>LF42?|WEbe*U$jD&Sw zi4oBbwVJOvud#dFH_i@?*u8gXn9$%3#sa($c(5@Fvq5nlVVEFkTd5K18)?Y zU1I-43mTXC<7Slg;pJjLFr#sHnU$)y-7Uz{D3Q{-!nXsQCB@L9W3t>A+_bqx?{N0N z&7WjS?~AC>MD@IQA(%)uk@)uW=k*J3zk#z<;s*Dz{wAFI_*awLHf^L0fyA%}m(gA= zVZje1xi!a=#6o1uL`v|4#3}?zxW^I`62&#`gJQ)XFYx%e%67|mMIE*L^I0)Xj{ktv z@d}wZ*5*@ynT{aWnC)7u*~Z=a{+xzc@U(Jzaq&y2oMGR!-9mdqx#wurze)FU>Mh$n%Gbsc+RZS z0PR@h{K%}CZy~l+GfPNhp#b4kIqQoJ5qwcnXru&dmM&q0xP*veG2*E>Pi9tEj)bO# zLvI+FDOsqanW4RPK(*Y3R8svLCKE?@CP|&F_cQF!4UH;v2ItS_!k-mDoCNIA^Vyo| zD{OqdSO0d646aclCZoS0--|=?`(9G~*aJYfRYVZpdVy$o z09z~~QPGx5EBOdTgagsSC3-qTHzm@JNSUowf)6UDIZ!&TodFP#qar@jY#i#(pz!zt zg)@f$m%U{BVdXpPBk*Y&6)^R%;Fs=GpH<{JmGvmj;3ZKmk1KyT3e+PQ-DB9wr#3#2}agTc-|x zvVEWWoaf>jINfn9vi=Lb3*C@^84>|(ZqKV9qv`igF$)gAge$|P3ttImzIkIH}m} z#Y3J)b|?9=u0{+u}r9qLQlRa0GU5>G-ptKlM% z5pCsJ-VyRx7yFInt6;1*nDXq|Q-sAHp_EX^>M?sW_hS1CGC63ioO(vu0GSUx_a;Vy(e)E%q{5bOmZ^KP{# zJEgjZUg)p5<@pOs{=LZf+vVlCf86?t5K^!mvrA+t(eC;gmh5#DeUevxcPjP?*{(j; zI2v)bJA6LzLOq)}0S0hkurm$Fmpb!hauM;3N<&9-??UlY14WA+~-^GxM21B3`3Os z4jM-IwQaeq%1~hm@>3GkbY3h*?sJJ&Dn;xB)$sFzZt@z^Hfa?`Q0rqJi7OZS=-**j`TDsy0!WkBV(l%uJx`6DLFV!) zI@7B&*&^7{DrPIhAj{GSbKNHZIH(O4th#R*)YFhm5y%SJ)}7~?r_TwHX&K5%@CJcN z(1(r>_c9UEV&?mr?HwzRRl9vZ7N(kv+@#J<diIRVw%reE`Q}$wRXmk1lmD3X(a+x1|^Q648f7ktypO=58({ikZzZ^&Tj^xFGj zKkN`<6HCE2V8dG&v=kr50zJFP#j^$tgAj>tSs__zN}@Pgv0#w3T)Ws8kC|GOchhi4<;*BVz_B62@}ZnpFA#UKCPgoU z&+oj~m&Ya36QD<2)klv+G9@vX8Vj=DHO~gcim$<7mL3vMoLzn2U)F?!h_la1Moj#~ zdc@qmJ-v~@%SgmZ*R46~9Wi6&(GdxkXe2DrzKp zi3dgGf0aq0i-}(taBk)tGXZBlBHi{#K>t~0gaAEBO()CPCez*iOW4$ahqc!m8pg@^ zCMhn))m;Y+(y60MNlOxhd86NOzs>-)q2I&bNWX!Ip9y+8-G2bG=vec5FVmYkpEn~v z$5MW_%pjn#9Pb2OTZkxnt>PDM(PrCT>9@8O&}tLNKdLeaNxs-9f_?}WN%_rWSM{mL zd4o-YHok@g8#185PmsA?piP*Y<*dX#zcVQ!B5kGeftLIILZ=wSI7X6!gRUf=+AsEI z=o1@sgM>i{hC5}$6y=*ZUGa5BIxSB|2}#RY|4r7H@LR|UU4Ay(=Kg`C({&qsUFJ() z;hfhZ0jQihiDrnUuM8DRD4Z^$0T)PPu@xIxhQGj=i%~%1C-&?RvoVHY1T{#OQF3>X z<@?%#hVh7JwW&Yf6>N{TKX%~rPf$620}rbyEruPu+-0bYP-z;xJS7$~>>li^2cwmT z-Jrn3RPSE1>}^{ajM1>#R(}j;=zG3qnr4Kr2!EkvM|ty1rN@sr&5iz%@-zDTe!9Xd zx+GbMs)=GZ+;gA+;NEe2koU>XmNs$-fX4v!5g?v~D;_$xheQ+@d6S+&TluBs#Dl>K47r)&$hJ)$oG-pG zVnyLbLGe(6LIJ#2R8QzH|0Q?U&GDN-O|qKmbboW0Y9#O{DV~W#VJrUCXu%8uae==x zA?HNK581O-`?4_bVe)>c6*1#oqNJMYDSs@$1>qzRLQ*50sL+KZAn~!sh|G@uc0Y|( zLrt5VvY`~6*ngyrH}97p=t&?}-<>z%ZO5Z*jg?wz@CjsUA?Ps&76>saNnM5U|PjokCH{|r%3JKBYu>rh{7`n3QJAw2K(1W&}gSwonDJ|?`Aw% z@4L-zEVu%42UACQg_M0zX?Rir9RG5O34*Q=ibVb>F#c6o!cO(PSST{m5*FLaKd=!A z@ch>R_11MHP7?+kBJt&sH|MHZGj}&Gyn=|t1j2KhBIP!hM%Woq(ACM3(sP{Gxf*N2 z=#mmoSzaD-H9_MIATbg*_M6Q>;jjN#D<#^!-342{iRp2BzC=&WDGPbKrzIFykheU$ zf(;k^y0r`n`Eb6*rZpYdCe8RSM`Tz$BDP~~c|;(3rc(YNzZnBhx}T~g{N5~3s>V;p z+|@prE%Tr68;j+{imAR;1XoGLI#WskABuI)s93OZYF66MTN*>s8Pc8X&M0Yy7sB_b zIz39E$FRU)4e9VKY!}w=@rD?CTCK@^)XuJ z>~uP_E0>C!yZe@kbUrbb4vhnf_7a}RIidX>{gFOeNoB$Jgf?2~*-JRuX8_H81BQzx z{{k0`Mox-0K3^4MQK9uTD9b*NW;oZffQx^X&}MbVM$>$vWhe|ZL}Cx6NZ?_hvFRG8 z9cp(>I`|!?kq<`a{-yV8*U$E)4>N>Tg$CW2qsfm)a{)t1$of?SBzD-&TZpIEU`h*f z0R_u;`P_?WEFh=?$QvwA<|{dn-~t9XQj@n5kh@F^R>9<0MA&F3E8~WvW@noYUa7_A zqgEi|gt7?6Rl^u({LaxVBt2*mr*>o@scWd^r_>pHC63p2k_9@NBqoSE|A~`O%oHY$0DhP;6z`Ue#RcUN|v& zL6j@+wjC;axtP!bNKL^p6k8#<<%YN9BT_spH~_l=cVYIKRcs+zIC#dpn!)vhun}7L z-W`y8kB^2g5ykgpPqbDEO9DzX|1RhMSy3K>&J+Q|2nR=Fp^-hAkL}5rnooBBl&AxF zm!CsoIi@}|ijN$Xn3$z#$SAa*cDEY5^nKRFzvc0Tx|{!lgzz_R?h+#;@q~Kc|DOB3 zRe`%lDb(LIB_NC`Bs{JR$;v{{qGlsc%c2IdtYQCmD7oyE@4Gs5&S_h5qBB<&(V1mJ zJCgNy_}$>-CPeRVxT18WoLe{TP}XCEpKF&ImM)#2pVmr0j^OO|x7tDfpwq~`s1}D{ zPX)$wjg@|-nef2{a+f7}H5c4!k5_RdKuJ>M{|WI84)Q=7V#EZ+q!^+#wrQ$W`2b$N zgpZyxFbwFfphCUzkHukkTKVre=eIMn)A-M7ef^s@%KzdaSFfKW~GcIOwUY@$rQ-_ehPRO5roZmR9&1c_nOxK)) z-}G2f_w%5ZGp`!xxYD+Y^IpZi!x%sm@1wguwjDr zr81k3z2s3>m*)1qbz-_jJl%&5seC(SXu=;J>=jV)pC%;p44fDj(4D!vyZd?Goh}o^ znLBjorFS_!2ha))f6uo7!Qw}`)7fIU`JjSgBgF&fLx91ORJj58Z5x4*v5%WgC8>w? zu)`%dYm1K>BkoVn^NwMjUsxi%VL4FKzPR=9#Jn=uB7@9f@TUpM;zol??8{x2LuVF9}ZZ$}?JZrK1iZ z+dxQGs*TlJLV6(2V$Ly0yRi@sujDbfM-OvM0e8AGUwJo=!F5$;Il z#SxeVa^$@NlSq4SG_CD9MT&{wf}+xq4Dq1l^Niyvd;vocyW!Y~i1A_oA+}w_cElPs zXW{(J?jw={MyXRBg9T-Ul(|ccT`LnZ;JHKyNxJw}u^vc}9=r~oOMJpHNzwsW$Z~*) zwar=gaH|X=AvdvEwtq>2DKST~7Za97)n6(nvKf~MMxyEKmRXg0W^rRdg%Dz+;J(RR z>8L|UuGNHOrRsNi!cfsU7EoHB3rA$ZozzQe+8+oh2*MawkOgHZ+#DgH*CsO-1*x5A zcv|XGwFnt;ADEaIiU%KA;F}Wi+@7o))F&jQsTamlbLY>xNNo@$PlYGlWc3=Zvv6Sij5a z*>8)7xWdeM5ZqbAR}3rfL%j3|X?I!o4%n2ry^HcDjylych=hoK>V7NtFha&YCiw~> zjlin99)ajh>}SdBT$AG|Az2Ratc@TQlw9i!A|cnY``*BwfhBhuvUi)IB>O^@sM=l8 z0|PebKP?saJ{qqlB#m2LP=WvbtIQFwL0##oLr74&2#Mnz$N-fFl+`EJ?Os(csmuMP zAf(UGh7B*dg@Y>><*}v+X+EA;`pLhEia3VNSt&F3Sc8yOL~f8AGP~j`{m>e;z}grZ zt)POk+FzJ_1kCBY?EiaOOYh#Z^s(m@{(5)Z)9G9iswN3yO5 z&P2(&6OxrG2JtCYA`K|bS`uyjq$d6Cu6PJ%*_00PP-8+0pqXdnzDxw@37tT`W=5l%l4^uW=3yIEK!(>&Y&?F(L zQyqgbXZ$?wcA@A)ky$p3*}5UJUe*Knv5I_O^j&vW8mtnsngfN*WVQWf*D<&@!PXgM zghYa(L1%@KfbvRI6H=~nDd6}wgrsq+1{KnQH|`&pm&Ux*Rp(i@p4v-DSQokPyvtPs zO0!mnkk!+SkUrWu)g&Rgf|Mh>Vb0wt;cl4suMU_VSrCl+gyg2>;^~Q#Y3(O9#$EyC zgSYs^FimK2)gqtx0PndFetnOS z)Tx$1wqyERLc&A_@JTl6`n*IAP(soiKtfjA@A1habZV7B-0fomoex1&SNFQf z7?ODV;Eb!4sQO)w&89ogINbYndSd>oCp9!~wS)xInODhLS9yr3z3agB2Q3 znzcHFq^GNdH1|3l419_?hsYQba^*2sCoMvfieNjcp&=-jA9CL%B-wU7lSD%P!N084 z$RDm#lH#`K9g}t_3&?yJUhb1{Bgpk75w{1B?E>NyT;A*RP&ZR){BeJuhCqDGW^B5v=XQN4l?917tNkc7-o7zz0& zd;YJazhm6-83_b41C<7pX009}>1j$x%m8I*-TM(i+&C06FT!N8PMzP&ZX~?Y|DET5 z-{2Sa?$`!k5D0>xPwat117nDYvG<9Uzx&G7?mrdoOH@YzOlBF<(5ZDz>5Y?}?Vna*EG02C5HApsN; zpioGFjzR)-6!K;7eqP!J<2a79$)~2vmSWkjN_6vmsfLNe6po^m>lR8dV#j*0%viL0_!a^QqcUf;xNB|gg@|Di!+0kcbB^(P)%ho#U39Wv= zB2P1gxb#?*z6zO|_fSXxh?%K{g2zblZz1hZV|ryPH!;#SR^3vjklcCXvPfYeIc=%; znkMQ${b7}&lc#SkHxv>8Vxj10xf<&(WL8dWrKy`6+1jEt?lPsIkX%YFRg*&}o4FcS zphAXwC?o*HgZXv&Hdj*>a@$xj8;SET6{ZjtQl3LD6<*5>zT})9|J3(gZZ-^2rz(Db zZrHCp`bpF5ygU|H*#Hn5WoukrNSb@nHqt(eCJV^}RLBbFi_SPdG;U@Z##?@2zZqNh zxqLMK(YbPq&c3d@Jb*$1KunaaRaGG`XqU7ol+n5inVLGYcg=+ZmqrKfMsAIhjjBgq zIe$C2%0?jpATG=w6VrRQc0Q_*_RZuk=b%!WO^!Aac^0L+kQzB}@{*+qA+)qtw(Ofz znh%EAH53v6;^k?3T@x>wEV7XA1l>MlnBQgA=5MSnX1nhtt*{eGj4V^?PHpM zM#G10SV+bh3JCx)C$F;qWt0bn45}C0hb%f*uDOu*c*tBzd-Obz)LCO26~#x4@a?1OPRw=?Ur)`PL-OrcV=&L^f%nyi$m&h4Et35ERK-W{7D41{4A z<|BM?3mmCj#395%ES*w-jamKh>T4+c@$XNa*cF|zNHJxh#{ZA3^U zAw*fS8`}`+_5Aal@A=;Iz2|&?e7`@h`?`Mjb?$SW`V4HqNu44GIMaz6v8riK=`wzjrp;czOIdVG9*baeFU)vMpXe-nws-Q8UZg>rDP z&wu&y=GNxm;GmAS_So3i$B!TT`uZ|5GMbv2+S}V}Yikb<4k{}vBO)U9_V#vmcDlQ} z}UaXQehNIcZ~agR;H4xUeufI@;0EafJbDW^P8=SP+h#%FfPi zX=#DW>T4GLkde2LgDdLEOUue?JRjNJqf(LOOOhFL4tbN5^()(_HR&kNA9GKa5+?Nw*)YVVH$l^73Af6mv<7s zY_85viu!dF7Urv|sFt`OOyuOAU1vm9|CE1zHps7fnUnSP_4c?5wcxVN$^3xC+{nnt z?=PKRKhn##mGf1V&b@U-g_+4q1XMh--Sc_=SykW5+9o64q~Yhb^c?1GULuut7v}e< zOFuV)I@TX1*Fnv4S4LBA+{J=G&>U0N&)-%ttt+u@bNYpI_X#~Ixn=T}DYpJGn_VHY zimpG4Eh03oPM8XqannWgu9v-^TH6?hCyc|x2j)JJ)lh}LxU86%n4K3vV{vL7fzo%1 z=WZnqug#LLcs2QFzlM7k&yZ8AawB`o9x3X2q3ls1?k40&Js2k(qbI&J*nGX(rpe6>Ds+sivGc+crMk+4VKMef(&&XSAarFFL^1 z(obDeH%bStA<0uSwGmfdmt9)Hsh>DPs`xon=;!8PWbJ+fA)_S1l|{sIz%9Q3gXsVO zR;Zq~hDG4idX}pxhsOCZsw|d1Mxe>e%o8lq%ccz#VAQWI=uF_`tt%81M{h+tdOFoi z5YbyC>g@5vQ)#E;`L9EEQd~uu{V?{c$3ui{;_;)*;LBSFwE5x$99^clwF{cTA&!;5 z;0;7AOuDqYM^?W?QXpJ3oX&<#L=&ESo=bpEYmcowyn{It(g2W9XY#}`vBg@V@gDiK z9jr+}B8_{WGuR4pPYPlacHRnn9jWgFU4YdQ`cS4ou6S|AHc_Aw)DmZlL?RV5(P%Uc zegLpijReq43tD(HHpQJFs%X@SVELSxz(P+rep&bz2e*&sT-7R z6734Q5nyfzdp^(o9V?t$;SPyJYbrc1ql+x>v4C(PUwv8$<)$#b)kby=dxYlM0Fi6L)`3MRBJiAMstV0{>6TNInC`ZiC&Qn^>{ zhSzvg1$7*r-i9&i3b(Uq%;Wy7#Q#8%kE4Yvf!0~=FHQ|5p@r=of$6SfU{+$K+3O=+ zjD#LFe%VVT!X8D~FtDAad50enq(4%@!VFUZhZp3(U1;LQ)LrL$zm|k|mW+Wbf*Dep znL_TnCd>GHuy8p)+d3t}Y=1ZFf~yA{^%V$$<=Ww}TiorNe8lY}w%X9u2HTTPv! zqpdtSv?$HpuA3FwaqMx}Ir7BCyN@I%)6Gi?bQ8ZTH*3<|(Y~K6{`Q8Oj+Z?I)};Vu z*rCrFIH!^)kh0ZVr76gOpF5v4d@L zZ48qP!It^E!rJ`a@VzJ1=hVEW)B7y#p1Mh`UJZyG&a}68eOEox9C}Cot1wS_Wb^m3 z`GSuG-bZSRDQj15!(FB$OkPK@+6A^1^lb}c($73a(f^xfj-wKcpC%g`_Ics& zPA|uB$h0Nh6=3VW-VvGR=9ikMz2pSW0T_=*-`%a`yco3w{T~NWpipB zI#K^<#+io*8m{X~K*vEgtn_dGu2g3}Ipy-twub0`DEheOH^C$hS_~+Mofij1;x!7; zrjqL9d@CGYqmGdiiw?k{7m7>`;rMXT^Bn(;1USYQcm_FtZ4!!q9=-D?g?-*dSTlj{ zaidY31~b>gSw!G=?@$%j9c0>{v@}iqOz3@qmsO7!$*_jS>05w2Jf~V=G}T(b5g#g6E-}I!-mgHLokiC}(YBMhau8%H*yX<KA)1oQ1_J1J#fy9fgbR%f9LKbqT4x%&F^YFn4<7LJ<$_%CSc|RW~O8jBX zI3YY81;)zo2@KVXkm_Lf-VaM&N{(W@O$|cVwBIxNtNGx@j@60O0kfe%ak66!Q~dJrz`VZ68QB;MNuj5_SJ z_76i=VP8}wEQ=4mkvsn4pD2W$3%o7k(!fLFZBF?<;tTZ9ea&!LYMomK5EUXCbV*#l z>~Z(W?bhD7OLf~z?F9d8cW2sWG5nlZvN75aM~8(iJ-!u+8wmV#qkHTMx*@6?3|Fg4 zKt(9{vSR3q{xp)dy+oizm|x_US3ly=>kdkiA%76vxK2}jNK|%**f+k`mpkTffaGbr zsw>UxY>+!Rz5GKug-fNSXts4B5M1andvxdW=NB-~UI8Ohx%r%tcB_o(0kYEXZ(uUT99lm1Exs}BmKIJj38pbb!B)f1IlL7dC`sC!~ zj3vW4nnoGV^rae{2!ubFPxO8Z->8!vu+ll{RSH-aTr>-KDUO0w>6_B9T*~`N(Z~Eq zMa?g0J62Rw(7Kys^FSm;muOX_n`aG`y}kT-8p3Fl)IKdOHNc()L%BFPhq6O>?;#DJ z$=@8R=2U$l9zuCKlt%j4dsPxOAsMS2;1M3cD*PBQNh~@DSAKg5hNQX1-n(!vFo09Y z9vpC2>$@p?)XI2&7RL?sDGmXxGS|(M6x)Dc^OnzI5AvKYBTxXLy#^lw4_l>5V|yKa z3!5x);VyrMHxV>$7kL#DB}PLJ7GUTAV`;|i_H)6WV+pi$`Qu3l&oE|H;RL=KVODP$ zIKcTL&+go5Z#?yK4_%^hA&YfBUOA=|f3e2dnD~m$Bt9ndVr3VcDN2e>JMWQB&)QGT z95Z-pgvWWnM2XYIvlA&wJsNq0rt5gXCW%sU&8nX)h*)P5*F1*zZ!SGXSiWix+7Piz+~!sGY3` zlS1Z&P#O0R93@&$aP1wRrD92=Tvn__E;LE!Vrsbvz(V*J$s;%f9Oj2`7m$VnPlFCR zJP|u6Lf)|h3N|mb4fU3j_F9VCzK@WP(}Db;^&0dzp;CZ4YH`57MRDF-R*paRDXbLu zLN~%s7%)1IUj9E*k*N%&iiXA0w>9$BvUL82gV+Hp-UyVmBe2ksAteZAWbmD2@~j9tOWW^flm2O} zUVaiDRbh(#NgL4hK+GiV+%h+=MSUvlx_TCCQ5Dl?{MjI!Y%Pg`>PnjfU|UwPw?(O~~a0RP_r zr~i?#|2@_JF(m2c91FZ{tz+A3G!smd`3Uphd;d6~bK@a`#l3iiH6SjR|>Fb_XXeTlU2T`Ip z8Y1s}R$RSs)d1LWCV2znD)RUh8>p@S`F@(73VU|0uDy~?rrCCr5P~H9*v>ULKS>Wq z6uugaI z7C+g!FNU{&aDySZ*yi<(p?`@)Y L%UHWw(=p;-Adi>L literal 0 HcmV?d00001 diff --git a/docs/images/rviz_set_start_goal.png b/docs/images/rviz_set_start_goal.png old mode 100755 new mode 100644 index 7972988db17444420457bd82e620c11c0ce9f2ab..57220c0fde07a4d353f234b03fcbf5cc8c112355 GIT binary patch literal 6600 zcmV;(88_yMP)rIoY;0_to10{0WLa5R>gnjLtgE4+p_rJMh=_=8Zf=Z=i>9WgmX?*q z#>HY{V%62uo}QkEhK9SlyLx(hb#-;~^YZWQ?7qIf-QC>7!^3oRbn)@;nVFe&?y0!ok6_v$L+Qu9K6KfPsK_cX#CE+0(2>f+(y&(F`mz`(q`yo!p7@bK@ju(0|0__DFF{{H^o z-P_sK(#grm%*n>Iw6m?KqZz- z%DcF;=v6o8=H{}ls+5$JU0q$-+1bg(!l+3pn@1)A`6RWmt&otA-SXeu+uFy(!KI;{ z1^+O#ODq8EC5}WRferEW6)Q@{+-gZj)W?QOdtaxCWbX-WyTi|kA zKjvB0Z&on)Q9iy;EB8z#(mv=~J`?mf!&Eh6PcaPLDFxvqP_iEYoEls^7yzah0FD&x z?d|5guq2M2QUp035sZ`qESwz;XNszTF$2vvW4K zwKjL$r5$aZ<~DQa+EHp=61UN`+N?B$LJTS>Dl#f6=q4G_i%PBNPWSu$exnQZ4|UG= zIA?8AZIsaYAcDg4@bk+&n@XipsZ^@}-td_dC(fKh$sM_j>ESO7Id@`H0}|`XyvU+xHT0lf0b}o!w_hZ+AfG;z+@W&4ftE2>X#=nXwc@ z+_v8Q5nVGYqtS-wuSR@3Hg*@dJ2v(<8?i>x>E~h`!`iktYnp-DDws?jYm4CFXU#`p z4?Z4j*iFRVm=n=CABk=-en5%HB_LX3aEU;TP;Xv@HY4bnVusi^v1{ds^wN4R z20_~mpwEm9(bF7twn1to39YVh#9KS4TN4q<5=(zJ;syc8Msxt+bU<(=3fS{Ja^TAg zZ_2A=wSmB5i5X{hG7`@ zD&%+mWaRzDqbcO*o;442dtiXR5*6Or0D=p#CdgD`HpehCeL1g0!R59aXhh{Joo&7Y z$=Tr`)2RGJ&lEGn2w`TK%QSvzjS~ZXkX40&WWps1nj}zWL98bnyl4$SG4;G8Pr(4n-UA0s+e z0M$xF($o)T9duS2acQkV@~4o`vB<8+^_axqtP%vFSKgjn-egJTL{y%MeLfNjVF4dX zxYtO6Kj+;!PEajk&SFWL98vTlkQFtA}VT= zQD+}~4XCkB6%mh4$sXayh&?U{dL!T-6bV*XoHIN$VrnthoQU$JT-cBJEH~2$)Ht<+RXLv%d)$0S0uB72VRA&j-W}{}1ZiRe^h^;$l!zg# zY5Y=b)X+>Mz?5^gexy9y%z%V>gM3fLlo3~-mJR(BF=p0>T}J$l3m=YRTKES;Zh!i8 z8>-?Y-@QvhRiw?Ep;D<-DwRt0ogH)QX(9;2aP#W-&FrviQ=xRLwp*-HTBNqLDj*Ho zXf>ix#G--+FbWt?QITkjryCRX-uSotM>5;GDQZRCjaNL~-Fyq7Gdz7eJ2TsCv&}Z! zY_rY3vLjGJzXBdieQ2lmn!yY(<7cR?R`?g9W~)dh;hW*Cz7o0JNts1f!jJ%%!2eGo zF@QcBZKOt&um~^=Y{`M{XcQz5ARLYY(WrNX!`L{mQEF@Lbf*X|i3EI8z6X!`2uc}( zqSlA~Uz13LO^6BEX8?)>wq#*$Jh_mc&ern}rjg5z4JEVF)6<2aL}5l(g=93Dd@zA_ z29gAqTeskwy;J(i`lQGLSC#kw{AY>j8Q5rNN`xht1mVx%bq6^In^<38ch=!j*aLXj zc6YQ@9v_BpvRWcHvsXAtrEY!8fk?b}>3NGw_qLWeoINm#Hh6)0A|R%Y(nPE0f5zcg zn*M`A~BaO!FO0Cw|)kz}hrrBUb zPN&ke0TdgOhzHgnj4%uN`+1_mAJV^vLCO@m2^@9C%4`_YkhC`diQy3`EV4``fWbRJ za1sx$F3?F}52m%T5sGl;z9UKh_5L3X3G&Hzy)i zxLSs870Rl@H;ILaDTxJ0Q92JM5CDU;2Gtjx^;8|18*o<0&LBUv@yH0Rvex3K_Sz8o*DhuC?uYj5{ zCn`_i5x3e2o8&Wz?;Fcg#awaYIKNzb-%%n%!y=J49JgXLDM{0`ObK+*$b`S)YRrTS zgCsEAO$xdi8iH@~m%wOIz9dtu2mo6Wev|mR(KVk+9XVpB#=07>J4$RNkA|~FyL}D4 zzCuDZ{V4>%)k)#i#27mT(iL(!Vq$0X(f;Yvh2hb3dNhjP!2ojEyfd9m%(~ejk_2H8`%L1O<#^@Fi%@9kU_9RV@*9cNlor7{3G&83=RCk9!Gu64o!I1I zZh(bi7@P}rb?pvy#dlXi@k;#b&C2dBO*|g2><+~yPg$1H+hbaz6N`IpTo1+F-?dIn zv%Iameh*BGacL+fBEc;ECh<(A5~_qk8<)zN-zAZ_DXN@hNuD$_76J7LCdq=~pZYDd zP^822h{zHo!eVju-T4pK&)htDWO8Z8+|

H%`pHd-v`{Y<~Xc#ZV}I<6QjQp-R{8 z+p#0_lOJNU8?O!KW3k2g`C}($W5;5#*$Dt-5CA@WHk_2u5HZ-N#JPjuyp7Aj+J~L1Jz>gXwTr_ zpiwH6^ZAAG3>j8fh~CqEz}`f6syj1icH21v?Tb%c^gkUq&7_$0o&UA->$SVfn)s`i zI*6Smx{j)L$_CnY4^JD0VlcVU@vpHIf(IAu*sULSG9!CSLe{ zcM&Csq$KV+5Y3o?69F?5vlW30wK}NPjh3X*9ECWLP1&`FpIjcUb>2_(X4g|w&LeJn zh7^zK3|b^ekqRJ;qnF{q1{N=P*#WoNB!>Hgo}QlZC?;Nrg9|J#%$0wz!1xkU;f)sh$!B&3i~U=YDC^+SNislJnU2&yFvZo8gJ z21&|gdXJB%B==fiL4bBi-G)_V5JR6{PgyX*`{R)-#W`Yl{6C2Xp|t<7x5=(KI$}s6 zrK^t>d{a30t#@;4ild0)xOMPP>SG@ypm}pGC1by!6r-6Fix-WFafA@LCB@o2>A|#G zU#u(qpeL@@xpwW$3kN&f<4dcC>Vq>ttjK}{;3|+CGeaY0^F7eeG=m9|m4l%+5E4O7 zr!kYThVgwNh#|&UGGrnSjjf*QkAV4LBGIH2NRSv2Em+W)v_1Xe z_Qqdg;*D+EO*g!7S5ER@dg7(!>q8U=c3LVw@<^j0N+d|00zUbqFbCvyxf2ji-oQd4 z;3TX2`{%}!Cn5?tiE3rwBCr&N`j}+rd3byLquzpcQBz;(ZU_&|TRRPh1}&viAz3f41>CD{{OMI2!M= zA_9~sx=y(BGp#ZL+*}KjvpH_DNLrbF5EF(MSZP2Iv;IemyKlYM_lyno#A0y#*twDC zK0UrMEPx0}vrcTKLPV8B2nGjAcIn#jG0G4ndAzm{@!?y#TlPTrA*-`#URc&oUtJ=W z{gg+S%DRWJL}DM9+iq8#uhJ1PXz&qU=||dQh*TLA6H-7lBQ^oqvF)Cz>EY?G`x~nR zjmwwMow@VTh0(7!2+S-7M@R^{I%B`gBVJiiB`3K`E8xPGBvk-23 zZ0Zuy!CnX)f3CD3V9m$vEAdS0wjTk>N!z^Nu@W0WqaznYD5^-ny{JOyEvIeDIT3{tY6K z=TOvdTdZQDa7q)0o@X$UpZTQJo2gB^w7f5R@a)b?$Ss1(5z`|fV24%_qG`zHkKH-5 z_*i43v3Y$qTlhTkWO{|3=ObZWQZ1ZDxb zobA_^LOs=70nwxb5SRL>vZS}ApRYwVP6)-I24(3!ECQRV#vdI=p$>Yq}}R@9T7y9G@t2# zt~Xfnl=5XPu9T(v(pPgt+Ylc)a4$~J+%Fdc1esQa1Y9|EI@oj01UDgu%k?M}m2~&N zOjE5WA8btexdk0_oX<|jM*@)C&@!}qL-?EUqmj$RunqMD}ZiM9>#`3naU@5%4h zrduCeGz*Vgz35~tLJmo3(MW^90>p8KV_=}w0z;)pu3ps$YgY%JLhId*4x&n;cy;*w zNe5vE7IDzxip5wIUXmcV12OUT9Ky1S^xp5fPC=o7nZ&H6YHJz0Bs3;Kog=5j&NPj) z%a61N$pf4+YuQpFB$0oG4h5%9J5Z z&tQ?QBGEU71eCTFi><=3<{ats)zdRBOWah@nT6%`uReVB)sMgY>h(#^Xj`F ze)8pE3yV0Ah^|j|Evh%b3o(hk^|&uX!PU$dJFZQL!>K8ob33*2(vK&CZxx)9vu?|Y zm82^gO(4Q1(ljCj0XPRjQ6`^$7Qs@$#6!snurXsVRL;G3Vuf@|)ud#{zI}+_eD&ai z8REyUe|7uyAvz(X$I92QU2H9B$&NohQXlLQhUPx;;qL7IC&XTYsz@R^)cfN#2@LT} zWPt!c!K7jm9i&-^sAQ6@_fO9WHj6qlg|M)QMBxH?UFK*xuX%pyS{Foxf%M6weTd(_ zdwUDwiEpn9k=2q6NS~kXy_9CdRicQor|aT(Bjef~cWi#K+57wB=kH11o?m(V#79rx z(Yw-nW%HxW-nE>J{4cxwX>!-Ri^1o9S|c?{kdlF13TQ6D2|!2$9Hm``7>UnJS%{&c z(1emv5WoE4(7VEt6I<8J`Y=~l zmKlKdW@2X-XCGTUJ+S)oX#L!DOC_&bMmh)CfyN1=Zyg$uThThFB4E`oK&s<_juI}Gj-o4$cyYGeW?%l6?k`CENFwabW_jI~vMfc>RF28bG!-6qE(v~D>K{EOX z??bgnOW~p5EKc4-2TCIeD$dRwYZxrcUdi#1K&-BxVCCfISq>lykw}eb;<5hGc?rjk zg=iXnaaCUh88841^?I>YPRxFK{O=66`}%h8mfHn+q4&xiU7LN&xAt{E+?U*5A*4X# z^PiurBZV^!do2Wk)xCikg%Vd#9YnKKS)x}(LC|5L?SaG03Xv$>i3CseZ_4nC> zIIC2ui8&_q2D-cVwkZaqRfiu9MDY3Y>-=V1$(erv@{QWI*w zhsporXks42H7WBy$22V(@csXvqxmd25!e45|IZKD>r6?L;Vp^@k|MUs_`gs3KPUQs zPyPR$uFxUIWf9x5Xo5#pt}Ds+%wh89RkWdDc+Bk6KcAn*nw`3yl-uT~#yZ^W0)Dh3 z(*z;hAK<_JZ5Nn~TmCNb-0Ol~GiTsN!{hnKAC1$UZB>Nu`6p!YC(}jNPs$(VL}lL~ zZynloG4C%r=SZU6pJSW|Fr9PxxqfzjTHtg_}*KgwPU!+MVI3$Vcu^@PQ2(of5J~Lvg9E5t)`IJaG$e?WseBI z8WUj#Kl9ly|I)GVDBm^G z5qW8=FX*vu#1T9A6C+QTB<&+Dn>hPjZ)tv>H?3rcr)iDb=ho5Z;t}nIjVPwUJln}s z>0v_p-I~|K@%6P^n9&dv%G!Kekdcw$U?z*qQv-qGP!-*JTR369p_1U)ieB$QMxk0L zv6~gox~epII(?p1kKH=rUMiAJV)?c16T5|k&iPK_E~$1;^r^v!PFzN6u;dxv)3!`= z;bOo;kUT=dzWr*BCG{}$&2yb$cTcAM{aZgTuMIdc84ZmaXieLB=GyZ$R%hpw7w0l|ez^bq7iO);wIqGNyJXLcouKrn$jI0oeF66q z-A1n~p5EcL;c3n4Swytl=cjCUQtM01+~>O*f8W~;=~R8M!LJ*=uc#Ci6+=Tq*JgV# ze;g;9MPM7x*DWkN;!x54`l70qf4X!F@_Z3x~@OA29Muw`=)2dBP`zTvcb+zwRY3}n{ zbyG@e>U+&!j?k3%1(t1>iSh>rf38ji3>qFwBolZBY|*yH89&_zo@7GmuRA_fs~?)B z>PL>n#KeG8rrm4AZVe5|)jaKgXnJ0=J8iqLuPInDWE;-%JSgak3eHy!gf=>D{n^d+ zr@}^8S5teuJ%>VvV z#huZ%b?Ki#af+Ad`3=icL%=KS9wl#lAZM&~n+nqXlyqeQP%kj6LC>RrdVon;tB;h`~KdiZMaTht8 z>y+%-ICQvOxPkE9MRShcPFg&iD2@Db>UVMXUImpnWxhjW?OD_53QbAX_uB^5fZHkj zZ#}qBI!5^T2fW4I(=%wD`v-y3vNGN-#(r{dW?|Z-!O~n$x2Y1vHVBXJ{bj=_f09v} zhv4%quK!AdMO*;`eYVS{=WfnYCz`+^v)qplxMBrR{mTz_NnaK;FCdS!{L2P#_UsB; zT3X`0zprE6#0Kn|)`TstNo!Xl@lPEV+x9JZmb+Fx`%jS>8k!!Ybnejih&663*T2sIocg!b6sUba*+g!; z#p%`6=YQh(u))wd%wLg|Dfff%MEFYk}QVql1T9M64m+0AyZ z(rY^D#S)X$6LR!?Vac4o`9ZJ~cgtkvx& zi;Ci6v#SFo={Ry<8JMH?8}*`3<&lw*9Wld`lauM3N*@T(N&9`z2k9-cJ?Z+LK7am< zkB=|lcC=U1boDOZs;3Q0o;&G;c0UoKsq!WF&>w48qGs;l)c?hM^r*r6X~w>xe=DMm z)%|qUcVXGHvu%GT<>|qp`Hn8kXtqjAM?-_hcAhQF2qNf24CMewV&BwSS$Wv-!3Kru zb8>P>{Mc+25s$s@XS28cPMqe$^R-4MV*>il`(|(SUCu(^=six#v*LEZ`R1yFnR(UQDIIn0_!poMX7r}dfAY87rKjcdDhd__DmzKnmO-fr~Ykm=I}GywWo5}Y)*?&R)-eP zhwEeJUQ$i(_V(v*jQ#KZoShSR`z=Cfbt%j&}kD=TX*uMr$UH*7aS#A83TF&26mB}xIq zs^5bhOKK&>+QsRSJWmF>vT3oKO*aXm5F;D(+sLDY)t&5A{?>ns49@OmXsAN$e! zQ=ONe+%nsXi?>A%nXw)DNkifjXrx!~4_^Q_%?aJCYUrrixX+W&D`tqiME3d%1b6={ zq{!wx9M)12zMB?#KHFSwPGv`aV~GWAs5xwVoP-MJo@#Wqgznx+MiJZy?xN%z3kZBb z3f`EMXVC{EC<2%M^6b7)It~*l*v`&w>8D+%^Rv$tzEmvn9iUg_aiz7j$~AKW*$@@H z-h{7|C`iFngeZ7#-r$PCA=BR{NK<6;n++vvj9L)x%z+U&7Z^D6v==$1(VlvH*0kT*Hx?U$;QPJ-2dabXh$jHb5LpZt;qbK!$L}PuVNmpQs zoLrnuft1FbW9(iutyubf94vw?aXn9+r$#A;NAb|%M2M`q-b52k(L=IeoaEQyu@eVP zGcq$z{nte$6H1jt_T_74=XtHBc18dUL>9EYbR*X~wCmT5orV|Y&t32_&hc7J-eZus z9W9qL$T1~b+t?g>GHRu~l})6TRl(zpNu+({<*Q|7MVACC{KNmnPf`VM``yOy5zX=w|VR8_of#~eEtMMZJ(;3d7<^TK4`HeqOe5r5*sBt1fdZ^N-RAU8Bic<{+O*s-|{>J#TW^%Zqem`}4!-jrw zx4RVUx93&dbCB>BSLv%9&XWe0pPb6^e2rK3WCCSX>uBR<=oH7@v9ezmkP z_LE7Yr1Q9+OpOWBpaiYh=lXoL>_>c))oFQl@p2JmP&Ac(etvH7yy+i{#38iiIK}bQ zAIWn=a{5`M=FXbQY^GvnEzIPlr=8PY^ z{ih4!0C`YmP}9=76A|f5*!pG2c6p1dM2quE6x)0x*u(a18ydOG925wy_31BbN2j%B{<-u>#4N>N{K!s%XKzgN$6^Nvu|w8du%2A zr90XvTo7aw*>Tl4+m`<(XhAJ3BdU|>k-}hA}qoMZ8KdyUqx#dwdTv~{} zI0yzsW%*uf0X{fC()2iF%0VXJ=VPHkf5%ev#qW>ZQ-}YFNIh28W{wosJxc=j2Ls&p zmVe#btiqxw>34;97NZZI{(9;*K{W|dYg}fN`% zk&uw+=;+WZ;*OGN5B_%B_i`&j0 zcz8~in;Y`;^XuyBDk_*rF>7?2osZ`0`YCL?+5H}Gfz%txl_^ zJoC`dctch6-`C%7st|VK7?GDdqt6?eBj(xPZ_N1Y7P-U*fVSaAAyA^k-rL(7;5=cl z5L^4M(==+|M1md$)CTwE{*r-BgC_I7X9{MQWG=8vy?dV0VG@^En#P3?m(aK!-qYA_!m zzDf{c4gKk%nMWRnY>O^N(wvx>2xVzKlBam}zQ&|ZlOz3TX2=7O*=)$}x+Z5|U*AEA zr6!EEuMJ0f2_)O=sII@`b~9?LKknwvhlGdRGK*RE)2Z-97a3+46?1Pb^L}G~G3~p0 zF}&?ek3=f*FkaHw>+9=^ii%z%^Wg6B#l;M{V!+=JMZZc=llIFdev>Q4>{k;eZ1}z{4}p9ETkcb^4<bw8yG0r;{2@FzS`7&DxP5FHcFoSegS zAm1y31RY5>v1h|kko@IulG5bvN1GNU1>9`}I%dYFxxCt?sOsN=hc@V1Dr`^gpyJ0V1F0rbW^fEmg3Q{cU!Ju&Uuq?}It}zZzhw|wulrfZb}G!Z3UZr~BU&@pyG|tR!+Xs> zyzMO1jed2u{v9yR*;#ej#9G{#1zQMR5`XpygRl9Og1>MZZ&2xQ$3`G_s zU>7h9AyfF&dRhzU~Ke~h!2Qx~7I$zoHPc#vza2`T*f+)l-fPhDCt%Iig3asWI$9qE20014kwL-U< z7#P^n6%Y{-x3{+!Y*R30EG#T|N%cXSCH5}CIOfG-HaavptUaI6zne;rE?{WZwZGGW zB8rxM|4z>5Oxy32_-*T9KbAWaJOv95qP;N>L5NmUM~8mRod5IPF7Pjqg1b*|db8<5 z{s}s85jQN@(&FSl&Mq&bZzstW+j3|28H)xS?7cr0b{6aC(|w(@+uG8?8{42=ok(lO zkq+>hi-J=B>2Z}RY}QlsX?1nYO8B>12SOT2MPn9z@u zh8*b}fZiqd+}AA~fBei4^pU-`+ss@(v4DXY>gMW-2nU;D0{n`|1>3v-FTTW?f z&M#IwA1MR2XH@r%T#q+i8a9F`uHT{UOiFA(;IxesC5 z%AP;?rmO8pe;Mt@^f>5^&7s7E)#}@Fs+^Jg{A2C(=HV%m$3cn~+cU%37v&-AldrF@ zi3tsr1RfxiCUt}eY}3L-E-pLi76f>Bm)4A3f5UXqkb)`vAM4gmOUHTOY+uf*o%tf= z&|LtnC}5c6#f1^!edB_mkj49&{qg?(zRfNS9Vr;PUB7h9HcfSk^gTVBCbD3lzJOuS zG|_B9jb9e!H6lAf6fB`Cp;Y4imy;PQo*+s?cV26AFe@7t9#_3juP#x})y6YE*w88E zMDv+w&02Exe3dKywB~p)!1L2F-_V^W3`f+E_7Kz$YN!=Hb~r_QU*GNpH~;1jlJY zEvZuE|Hl&bDDY>G7ERUDGBVG_33IBFei;A68PZ%`1_tF?!`1Gp>9(1Ju{eWaLxqA9Bo znSe+PLoOY4JV`3?a0~&@KZAw+(P5&_-H2~w_{!_*R8+o-;guVtH){}pRyyr?_^w~G z1|GAM6T99w?Cb1$1$yMF0ZIWDQG zR*4q-mz`lgwG((>7}EGb)3Rw{HRB$jD?#tmE2P0J3lPUll8AQYhp5-geIeyhPER)? z%AGT5T)>kAzGXUkFQwDP{MiAEc83DbvHb(#v;A<7Kj6zIV9QbL_sQlq2_ zUADXxNC|=a-LzD#ZUgL3Kqn>N=zWu+U5ABDz>!obohqKP3Nr%r9^6f-!1Q}wGbJ>J z63U^ert-~}yOMw>KvF{G8|^EsUZ<=A2L9~t)zvX_cClN__D%f%jMxal2;wvyz|Mw* zOOHT{+0zy91bgw3m^jf2tma0^lISQ>3tQf(_OVG&p{ls>`yHlW6ih6iHvMtj9rOk~ zYk9fq5B-BBzOt(76yRLYZC#dBT3H61f+|4dFzN4{U{qLA-!U@o!;`~D`%lW!x8Ln# za`7SG4XzVNT!D$V-27!`SKocb6%c*yN>iqDIWcWEk+Q9UM|=t*#DczDCL?h8zlH zk8bpaJ1qUIZf;J;=J38g0<3Fs5p`^B-vtaAN$P~4Ah_V}c<8pawl?5OUb25*dAYK4 zei(oBdzr5@0b(XbipGaMjp;Ty!}(h-G85<0(dbF+ES5%_fbsNR;v|REXa3|Q=Ls2) zi$53<5(U4i&JW#EYK4vKG{FpI$0uA0H{QX2r#>DLAysHSPmm;0{ILGi=1zm{R=g*31Z23Qba$}>gp>MhHKl#1n2zjsi zzdU`UjCc29CYUwh^R&1eJESX5t7_pYaKDik1&Y~s++kc0|g zQ(y@E8N5DPz(oxOH(T}{o^^1gp3k zx1^McIE=e87SL7Iv|nQ)3F|z`oLUaD{cs5S(1M~=z+_-_K^cb;nkHJB<9NAQl}vL;{M;K~icRSJvVnhPz>qD=vFBAHZE|XAYI5>>gAPHgMYY_o zpLy~Q(}`NA%-mZ#(wE9FK29fm6q5m^$B~{T`+3OlT}Z9`LgJ45$C>%w#mbaOF!)q2@7Hf+C5FZbW% z1wspO`S4z&Ms2|3@(<%}qhzD|w}8jhwQ4yWy-5SKVzL}yPotxdoLzZ&d2dv*oZWr+ ztykVdF86LiHiC6O_Dpy_d?1REN`<;6qMQ8+^#r=2@{IK6f8XFnq zdwF@4L{WcO1OV_pW=N60-(`c`H{d`(EF2E*BKGXg$NT1FrPipopTZxVl1=HQ zEVbUt)|;$M@FF=f44Cs0)UP8XfZD-{>RYzw8M`oV-~&{Su1S;GvKWT;6JDPTE!={( znp)A^A!rKJ9Ux|b4#kiy>%|qi_*`xVJD5mcI3s%naLWw%v`Zjf7#~;G)vaQPoUjbJ z8<);~6_Xw}uB0Bf1Lj>{{n7o^;RMXOynq-N56@V}2dI71gHMMV)3zgT7Q})Q+tS9S z&|OsJ9sUJ;#=YfXvHA4u>?|-TV~IZuZJi;&!B)&pqh${v)?!HHv=EVmk~mV&d@ol+ zMM)`Ozzi>}s6Z9U6wAkU;Xnf2jv9m=)fX*A6Mt;V5kXDF#^=KTMh>+dv3uStvD@em z0S>x4-w!=tUObyG1JE35Je%jI8AG()8@xSz0fOm=8W z1y>42*Lr@#zx>Wkb8W=S`>Mf|jEWRoC>3+=)&7g_{11XC0}~URVBzQqIRZkKQgx8m z&*a9X;~+}liZw08$T9K{lxg%DK}tEZArDV}AM!rhdDOBuX6;`kU`LJxel)z?o3PB) z1nCGml9^W65gTz#0R!+5v+UUj3nt3?jGdZw&CJYD-1$gjfmHy&Oe@6-UTT^mb!+T*7@HO95 zgd&J`ovq(>9IhZ`Ek!fI@#1N28rtH;IFmM6jOA!D&rVJPUkE`ofX}*NK|%#Rymx&b zO!G+UTBjd80f*3wHik$?33jbSS}Nk`NiHURD)9syR;V*Ajwl?_CAXM*5M@{1*Z!^b zc`#cbrIi&G0nQ+XaC37L3lEOz9@NDD2j{3t`}$*sBPl=zY-f;~f{xaN`RWY-aGuoz z!i!j^dE~wJpiiCP@o?PK>B7EO0?B00(-`ch=s*@uiKsGhB`r1448ul3O!N|>A8fIu zt0r}|5y{zw<)*%mlc5vCqtEf6o+aR$&qG!?ac)MTDzj027Y-PJTJU;pP*9K~FM9Nk zxPaNNVjzbNJT^i(qfpqrtyaQ~;{?`UlHsq#t z?FsV_+;33^JTML2T7}5t{v&JOyxDc;i|hX~rO1<zNz>Nq2 z6p%r?S{?92)KKF(LS3hdBr07>0YkA~ul`&a(a${bhFY`6btpl~>gq_Z;qSg*Gg1;* zY26yKHQ-Ao(8~5-wCO8zRx`h=&zjnI$zq_xjVNqGi&v=N#En4ccLEb;>lX$I_pOic zj|#+bu?=i5mRg$t>Iusqt*x163xG1Y@MDnRAQuh_3{4?pXw1#d7VMBmA{sGWn&kUV z51U_GqV1hx2>^Nm||3{y3w1-fsIK_ue&@hkS>4$(h=9i*KNnOk1g)zV5IG_~YK zrGpQ_tExUZvDaJ-qP%^2w&h0STb-Ff)alxG2HNw0x$8%XC}WGc3x9T>u~v%1I}bC&-2p{FmMx7q-k8Fz3u%o<@OEqNRT@Dc&rD6gq0 z{i!?Vqu>*^J2gFx7u8p#{*IZQpIup5v;W^vKnk888lQ>JV{YxGf*=Jl{Fb7JN5M(z`2kPwJ%a9gw_Lh zP7XXY7yfE{&PWTl))in6DoJ*v-4?T?cgX|YWzLZfk{~0aLd0bLzXYhEM?`tWx2MaK9UL`hlnp#=)zeBHLALfW4noRYwQyfsG() z;(f{H8Sf`)-dMn^f&0WY!u`^<({QgisY0Efwoa`pfcAqB1*AKJrZ~56gF*$zfSi?7 zu`FWBh7{IQ6UP`wMSz-ECmO%S5KI{{e=A!+sSC)N*1Zc3s9O;4!F%U)APze-wJAFn zPVLv)VFz$U(<;~igr0V}BqT;39%e)Dzr3POq-}WmjiYw<2?3ZKM@vmLg@uJ>WhnS? zcv0#Wa%H|drW}K8(F~CRMrDin1FHJ zU?BzXJ%ua;_Wf{J>)6>buVqjWTt65f?6o!LAnMWp*3^i3h1zR+rQ%O}V&e4dtW)AE zYH4QR#HH%+dsWUWu5;PI_4y|U818;)Zimm^xjaiV0-X>QLaP!+PJ2ljt2*7^qAbW~ z@q){nKLnl~F|@J(L&U?-^R3{4PsN{-l2fsj8(9F_Tr*hn-GVJa=&$19;sx8;!z<#L zKLDf$O^l^{nHAz{g!8rHoYVlu0|dJBAscCdT_tc6Tqz{FFD*Du&I69gZ( zfHY1N8x;+0VjAP$64>*=jgav6epqa@0UW=pU8*o)^8#d)*^nuVl5+0@bVY0O;8z!N zPS~=e7uaV%rcYoJ6GzO2$gw`yS^o9J{*x}=-L_-R){a(l|tL)q(ny=_k<1I&Eo+?CIGuR#;}KgqwzzY`FmV5W~i9p z7!4aiT>s1mN9)uyzx4ip-zeYoY_J(GdK8+0btavk(dNDtfuB|=|NecSsTsS{ZX;my zZ8Pz_W?zacH3^%;W|moP5QeM|53b`6=I}R-a~lauR*CjbiSr1fts*R8SR zdp8E&9jK)~Or$-6^7*dhp*;Lm%(#{-_BS~t$_9)nU4=HHrVy_%t6r%^30J|>`a2-$ z%<>86LcQ-t9j0j!rvHHF<)F*4?mO*-p7;|~&jO)sRKV1$0(1mV4 zKb`u|O-~cXNM(*7AqF7leMdb$6r4|6IB|qzb3Yya;)vmfRSPNljR$;q;>GogF_C^R zI2|!tlcAZ8@h}V$^U)3n z?X?&Gh(_UOiUVC1EM8U_+O_0PE_&!`yNh@PiRjg%5DKxr_)+h`N6i-0J26jd= z-H+y-Ry}v~*_lY`iMQ#I(aiR$G}P4#q(zj~LFWS&04YtV$kynW9tc>Y$4FikdhK_` z19oG|)vOP5s#RqL3`O!p@z939FwWRvu}>e!8M>nW@DiM1gt^pZ`nLaV0^_F4SzYPf z=L*5GR$Z3+O5&{2XS~ll|1!PayOfr|`c8WY>g(&r3S|Mu6nF{V-U5yG3_c&Hrr8s# z{$xqRc$N19t7UO<5r{@z7K=u0D+@Z;T)P8SqkXU*c=R_ii;7ZTMr~N!i_x4rPj&_E zUYX1H-UVbh7k3JDQy}^ow}9UYfE6Vq7%9mA1+y`ErPzO;Ffzu8$kpg z4^KG_V4Nf6r&)$;Sb`u^jnnHA0tUgcU3^G+YfaDm=;3c5KjU8v*)+lBYH9I-By1~A zggl;Pv|vX;zes#)*dW~!iQ1eiX%Oc9T9ZRAL!``hH-Da}%+N-cTJ$2Ds?W9%q}fNp!Etx+@T8B_FtyJ&>hX5AxcY>HT}ebE`T{7k;uI2wd+MrBQ=m;(;LqmOen{;sUwyYX2%U?udw; z*FBBe+1TjX6Y>hkKbe*=IM6O2!KjaZuMK=cbpwM=uVWFjvacs*v=Q^ukSHg`<=i^xDXv25p>(st}Uo+vg5n}8u$3!Xnc3LM34x$>HE&HF`W-8L;*9~_?EWWPARvZAG~zrjS>hm$B*f-`uV5_1?CDK8Zx zyt7w>bqaJlWjTyIh;Mr*KI4Ie7cAmz5CV%&UjZn)J;cZFfU|N3`PR zAQ)PozgI4ua&>ddP@vQ9m6?)>e}6G5a5_CR^BJog1V)+McAK7H%|;Y{>DUbqA7s%c zRNY8cv;_={wm)NIF|EHA?4gQ2fLlim4MQiQjx=T?{GrKQz_2Nw4Us-9FfygO43IN# z^p>=hZ53IouiN;w z6?aa+)g$_4Q;$W1BVEFm6v0kj9u2PVM+*K`ogu_pv%ue)BOMPRKQHfN>6E7+xg}Oc zxWqdQUY3de)mZqTc(G_*hUokmYeY%}DY?=qpb#SqKrRmFjki^mqnR*c-RCiR{z(+u zN0_3D6;Ub=SB_@y5P;|DKHBg~9F3@6k{B$_zLW zluz>5A;8T}g8?yCFf0rj(qngk|L?szAsT-4US2(xnz^mxlLJFBLXOIblPgLYk&K{ls_f0@*U5VxU$j@FfW#6Qlo2CBmnuh-HY7N3cq#Z?r zPjojnZ4`D6{4LOdZ_!18K`ieg_l}jd6#Ml*L{}sk>I4{^FxY-6Yc5IVWI3P`%S1oi zV{C^V0uN+SfGTsu&BX=AI~W=nr3xdMEH`m)N}JN9Bem=6ijrjR^)^YiVIf*oLgjZK zfQILUY%!b8y-J|CKvKxyQ}ktXmiLWP5GK?7p*NeQxstp4cD!|VY?9Xsb-dBAx%|{g zwn_gC#fTpEK@lBBl|)_@GZZz*uwmi)c&QZAucBMZ)kKZC9smIf!a5JR_fcJ{fnPK5 zl8Ygr8jdR$Y*%Sngs#sy3nwh86C9g$%YI58w@z5v+S$ElX8vuCiQent?*8V@8WA*Vs6?%JaEU(>!9(=qF>FQl!x z)JXNQk4hnQqDKLnspDz=?q#qle6D8r6|(`P7n2 zPAPwqv@&S%`bYWKmT(q2w4X~P4sEa^zM-E=K13(DK@}((!FToZw8HXv*|98g@{!yAX zV*+l@C(irvp0=Q_4@Q(h$4*`l+Ae2tu z4GqBeHY57>w)>BIDNm($&g5&Up9JRx6_u4Be4BK@rntWI(LDM1mhw41rEv9$&{F`| ze{m!T#mX9JD)KxX`6_RxMOt)Oj)H?XE!gmflF!s!8jC(LHZ1|J64XuE_rod;RYU5F z+2RR>VGgY<(AImkMc1MQ3lQ9)XB;dfJJNh zf~^+r?&=B~obQ}^y$yvg-Y|1@aRCnSd);60kztCN+`j+1k@wE68Wucq92^{Y(iI}k z1k{gh*M2!|0YV&xNfxO`4311tXI0gt1>4bWXF$m#3qaNb;zh}Y4&T-hbFhsX{M>o? zy;b<`FRpWKdEX`2GW0Y@S}Idi&M=4=1BN#A0Z1;`!LndWM-H^9HYW z@(6gB2D4f&{j6QjH2jZ!mX(SH6|Uhc(u&D4v|x?JxjBm=61+|5#tMaVtP5=XypTDW zhvjpeTYi;_W1r9$r@-J5AV4&>71o& z((Yi#8wI6*%L#S8{1tc9;%PvM94!t*JP5VGB2n$qF-2ROvF(aNq^}`@Ww^MuM&8^Z zm~~VLZ?PQ%tZLvI%lc5tbpDw%$UH{2m*<7Nek>K)AgO&zx47X5!zZ4U1cp_bc@SkD zBivOr0}3)@fIX9o14alpWzIQV{KpEbSzyfp^8OXFAyGJyHiswrq$N*$XFWvZgf`4l zofFZ&1=a(kY;uA5*eS?KEPy$@T?V4;V{ z>nkm63qNc)oQil9HKDmC!d^9QjFhkN+G~wq@Ys`Rq+=x%5Iy1+uaxl+AM*3ju^&oB zC%c3C&a8b1Rn%MVfvb$D-mlMHCIX%M!=-`{_>P}=UH{nlqGpO3Sdn&w>&@+A*0B7pi)WCQuCg1r_5qkiZ}@D+%z^eg5Tx< z26}?bICE3mCWgz)RNCD;Wqoy_UnuQlujM}Dy(Nz`sUad&)z)T`#ks@}(4E&ti3C1| zVGeMTzvg|!{y1MqMCSSi_IOf4w*}5JN62?nhSr#i7`O>WM#hzOfPU}n>^SoNXJt!s zC0yx^zQ+bIlqga5+#(sUP{MmHKY^hpK{x~nsOLb3H&=H@DWDFEBtf?V-rUMBFQ8D0 zASiO0iNFW3k@2$Ot`#8O)=M1-3fofqQJip!+`zO z_^-0N7n}cM@;+Ri0bEFLY&;NzJz$}ONF?yaQo~#>esQ|1gi{_i6&J$WZOUQfV6Cf8 z)>;sQf%K0heob)u?VdP;@gSU)sg~PVj!+u+5xoM2d}R4}*zmk*RYL<9$@x|dkW%^L zPe92uD}t7>+s@kOf|7q!ojKRZ{;4>^>0CRDg@Q^TGzkFO&G(JYR@j*x)Mb~<(wSX5s;zSe7XD^F!zi3(47_7uzk8(fHm zI^%H!i*Y4N)QYI+5w-7U3{m!tlBcL0t$ij>#JGfXMj{Wy#DGP@U0T6IH&N1@z zNKzxWzTVNA{$?@(Ln@D$(o9@lpd`jQW+m==sR6hMFPWV8@nU1ZvXitfYz*?gRA}%| zzV10W6zz}Ng?I3avjOQqkXsvg<^T_@OR5{C1@NtGgbkGo!8MRCj+l>_g9WAkj4sWp z#>Ql(Reg7KwMv6;LP_G9>w;qdM2+SU3IEhHgS|D{6u+4!dwcuum6c!kv-jSiDiUIb z2afQPV&;w^(_{093DwfdlE;OcX?3o}ofLb>;L+{|1_coErihE@o}W8wrPL8Qa}kG1 zM>^4jbXAllnC7jG-*NdT4Ji&Rx8WF*nlvoz@yNvW#{_t&w!tF<8tKB%xPwru*p5cJ zB8U!y&zH6=g@H{xowvjD7q6wz@RH5tw!F9)R5~!QCp)PB8j62VpuTP`vRQwD4dA+& WBJyHa2fv~SBP$7!_%3D`^#1^H?~khh diff --git a/docs/index.md b/docs/index.md new file mode 100644 index 00000000..e34da583 --- /dev/null +++ b/docs/index.md @@ -0,0 +1,35 @@ +# ROS Bridge Documentation + +This is the documentation for the ROS bridge which enables two-way communication between ROS and CARLA. The information from the CARLA server is translated to ROS topics. In the same way, the messages sent between nodes in ROS get translated to commands to be applied in CARLA. + +The ROS bridge is compatible with both ROS 1 and ROS 2. + +The ROS bridge boasts the following features: + +- Provides sensor data for LIDAR, Semantic LIDAR, Cameras (depth, segmentation, rgb, dvs), GNSS, Radar and IMU. +- Provides object data such as transforms, traffic light status, visualisation markers, collision and lane invasion. +- Control of AD agents through steering, throttle and brake. +- Control of aspects of the CARLA simulation like synchronous mode, playing and pausing the simulation and setting simulation parameters. + +## Get started + +- [__Installing ROS bridge for ROS 1__](ros_installation_ros1.md) +- [__Installing ROS bridge for ROS 2__](ros_installation_ros2.md) + +## Learn about the main ROS bridge package + +- [__Carla ROS bridge__](run_ros.md) - The main package required to run the ROS bridge + +## Learn about the additional ROS bridge packages + +- [__Carla Spawn Objects__](carla_spawn_objects.md) - Provides a generic way to spawn actors +- [__Carla Manual Control__](carla_manual_control.md)- A ROS-based visualization and control tool for an ego vehicle (similar to carla_manual_control.py provided by CARLA) +- [__Carla Ackerman Control__](carla_ackermann_control.md) - A controller to convert ackermann commands to steer/throttle/brake +- [__RQT Plugin__](rqt_plugin.md) - A RQT plugin to control CARLA +- [__RVIZ plugin__](rviz_plugin.md) - An RVIZ plugin to visualize/control CARLA. + +## Explore the reference material + +- [__ROS Sensors__](ros_sensors.md) +- [__ROS messages__](ros_msgs.md) +- [__ROS launchfiles__](ros_launchfiles.md) \ No newline at end of file diff --git a/docs/requirements.txt b/docs/requirements.txt new file mode 100644 index 00000000..3c1138df --- /dev/null +++ b/docs/requirements.txt @@ -0,0 +1 @@ +mkdocs == 1.1 diff --git a/docs/ros_installation_ros1.md b/docs/ros_installation_ros1.md new file mode 100644 index 00000000..8dbf57a8 --- /dev/null +++ b/docs/ros_installation_ros1.md @@ -0,0 +1,192 @@ +# ROS bridge installation for ROS 1 + +This section is a guide on how to install the ROS bridge on Linux for use with ROS 1. You will find the prerequisites, installation steps, how to run a basic package to make sure everything is working well and commands to run tests. + +- [__Before you begin__](#before-you-begin) + - [__ROS bridge installation __](#ros-bridge-installation) + - [A. Using the Debian repository](#a-using-the-debian-repository) + - [B. Using the source repository](#b-using-the-source-repository) +- [__Run the ROS bridge__](#run-the-ros-bridge) +- [__Testing__](#testing) + +!!! Important + ROS is still [experimental](http://wiki.ros.org/noetic/Installation) for Windows. It has only been tested for Linux systems. + +--- +## Before you begin + +You will need to fulfill the following software requirements before using the ROS bridge: + +- Install ROS according to your operating system: + - [__ROS Kinetic__](https://wiki.ros.org/kinetic/Installation) — For Ubuntu 16.04 (Xenial) + - [__ROS Melodic__](https://wiki.ros.org/melodic/Installation/Ubuntu) — For Ubuntu 18.04 (Bionic) + - [__ROS Noetic__](https://wiki.ros.org/noetic#Installation) — For Ubuntu 20.04 (Focal) +- Additional ROS packages may be required depending on your needs. [rviz](https://wiki.ros.org/rviz) is highly recommended to visualize ROS data. +- CARLA 0.9.7 or later — Previous versions are not compatible with the ROS bridge. Follow the [quick start installation](https://carla.readthedocs.io/en/latest/start_quickstart/) or make the build for [Linux](https://carla.readthedocs.io/en/latest/build_linux/). It is recommended to match the ROS bridge version to the CARLA version when possible. +- Install the ROS command line tool __python3-rosdep2__ to install system dependencies in ROS: +```sh + sudo apt install python3-rosdep2 +``` + +--- +## ROS bridge installation + +There are two options available to install the ROS bridge, fetching via the __apt__ tool from the Debian repository or by cloning from the source repository on GitHub. Both methods are detailed below. + +!!! Important + To install ROS bridge versions prior to 0.9.10, you will find the instructions in the older versions of the CARLA documentation [here](https://carla.readthedocs.io/en/0.9.10/ros_installation/). Change to the appropriate version of the documentation using the panel in the bottom right corner of the window. ![docs_version_panel](images/docs_version_panel.jpg) + +### A. Using the Debian repository + +__1.__ Set up the Debian repository in your system: +```sh + sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 1AF1527DE64CB8D9 + sudo add-apt-repository "deb [arch=amd64] http://dist.carla.org/carla $(lsb_release -sc) main" +``` + +__2.__ Install the ROS bridge: + +> - Latest version: +```sh + sudo apt-get update # Update the Debian package index + sudo apt-get install carla-ros-bridge # Install the latest ROS bridge version, or update the current installation +``` + +> - Install a specific version by adding a version tag to the command: +```sh + apt-cache madison carla-ros-bridge # List the available versions of the ROS bridge + sudo apt-get install carla-ros-bridge=0.9.10-1 # In this case, "0.9.10" refers to the ROS bridge version, and "1" to the Debian revision +``` + +__3.__ Check the ROS bridge has been installed successfully in the `/opt/` folder. + +### B. Using the source repository + + +__1.__ Create a catkin workspace: +```sh + mkdir -p ~/carla-ros-bridge/catkin_ws/src +``` + +__2.__ Clone the ROS Bridge repository: +```sh + cd ~/carla-ros-bridge + git clone https://github.com/carla-simulator/ros-bridge.git +``` + + +__3.__ Pull the ROS messages submodule: +```sh + cd ros-bridge + git submodule update --init +``` + +__4.__ Create a symbolic link from your catkin workspace to the ROS bridge directory: +```sh + cd ../catkin_ws/src + ln -s ../../ros-bridge +``` + +__5.__ Set up the ROS environment according to the ROS version you have installed: +```sh + source /opt/ros//setup.bash +``` +__6.__ Install the required ros-dependencies: +```sh + cd .. + rosdep update + rosdep install --from-paths src --ignore-src -r +``` + +__7.__ Build the ROS bridge: +```sh + catkin_make +``` + + +--- + + +## Run the ROS bridge + +__1.__ Start a CARLA server according to the installation method used to install CARLA: +```sh + # Package version in carla root folder + ./CarlaUE4.sh + + # Debian installation in `opt/carla-simulator/` + ./CarlaUE4.sh + + # Build from source version in carla root folder + make launch +``` + +__2.__ Add the source path for the ROS bridge workspace according to the installation method of the ROS bridge. This should be done in every terminal each time you want to run the ROS bridge: + +```sh + # For debian installation of ROS bridge. Change the command according to your installed version of ROS. + source /opt/carla-ros-bridge//setup.bash + + # For GitHub repository installation of ROS bridge + source ~/carla-ros-bridge/catkin_ws/devel/setup.bash +``` + +!!! Important + The source path can be set permanently, but it will cause conflict when working with another workspace. + +__3.__ Start the ROS bridge. Use any of the different launch files available to check the installation: + +```sh + # Option 1: start the ros bridge + roslaunch carla_ros_bridge carla_ros_bridge.launch + + # Option 2: start the ros bridge together with RVIZ + roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch + + # Option 3: start the ros bridge together with an example ego vehicle + roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch +``` + + +!!! Note + + If you receive the error: `ImportError: no module named CARLA` then the path to the CARLA Python API is missing. The apt installation sets the path automatically, but it may be missing for other installations. + + You will need to add the appropriate `.egg` file to your Python path. You will find the file in either `/PythonAPI/` or `/PythonAPI/dist/` depending on the CARLA installation. Execute the following command with the complete path to the `.egg` file, using the file that corresponds to your installed version of Python: + + `export PYTHONPATH=$PYTHONPATH:path/to/carla/PythonAPI/` + + To check the CARLA library can be imported correctly, run the following command and wait for a success message: + + python3 -c 'import carla;print("Success")' # python3 + + or + + python -c 'import carla;print("Success")' # python2 + + + + +--- + +## Testing + +To execute tests using catkin: + +__1.__ Build the package: + +```sh + catkin_make -DCATKIN_ENABLE_TESTING=0 +``` + +__2.__ Run the tests: + +```sh + rostest carla_ros_bridge ros_bridge_client.test +``` + + +--- + + + diff --git a/docs/ros_installation_ros2.md b/docs/ros_installation_ros2.md new file mode 100644 index 00000000..b87d7fef --- /dev/null +++ b/docs/ros_installation_ros2.md @@ -0,0 +1,134 @@ +# ROS bridge installation for ROS 2 + +This section is a guide on how to install the ROS bridge on Linux for use with ROS 2. You will find the prerequisites, installation steps, how to run a basic package to make sure everything is working well and commands to run tests. + +- [__Before you begin__](#before-you-begin) +- [__ROS bridge installation __](#ros-bridge-installation) +- [__Run the ROS bridge__](#run-the-ros-bridge) +- [__Testing__](#testing) + +!!! Important + ROS is still [experimental](http://wiki.ros.org/noetic/Installation) for Windows. It has only been tested for Linux systems. + +--- + +## Before you begin + +You will need to fulfill the following software requirements before using the ROS bridge: + +- Install ROS: + - [__ROS 2 Foxy__](https://docs.ros.org/en/foxy/Installation.html) — For Ubuntu 20.04 (Focal) +- Additional ROS packages may be required depending on your needs. [rviz](https://wiki.ros.org/rviz) is highly recommended to visualize ROS data. +- CARLA 0.9.7 or later — Previous versions are not compatible with the ROS bridge. Follow the [quick start installation](https://carla.readthedocs.io/en/latest/start_quickstart/) or make the build for [Linux](https://carla.readthedocs.io/en/latest/build_linux/). It is recommended to match the ROS bridge version to the CARLA version when possible. +- Install the ROS command line tool __python3-rosdep2__ to install system dependencies in ROS: +```sh + sudo apt install python3-rosdep2 +``` + +--- + +## ROS bridge installation + +__1.__ Clone the ROS bridge repository: + +```sh + git clone https://github.com/carla-simulator/ros-bridge.git +``` + +__2.__ Move into the `ros-bridge` repository and pull the ROS messages submodule: + +```sh + cd ros-bridge + git submodule update --init +``` + +__3.__ Set up the ROS environment: + +```sh + source /opt/ros/foxy/setup.bash +``` + +__4.__ Build the ROS bridge workspace using colcon: + +```sh + colcon build +``` + +--- + +## Run the ROS bridge + +__1.__ Start a CARLA server according to the installation method used to install CARLA: + +```sh + # Package version in carla root folder + ./CarlaUE4.sh + + # Debian installation in `opt/carla-simulator/` + ./CarlaUE4.sh + + # Build from source version in carla root folder + make launch +``` + +__2.__ Add the correct CARLA modules to your Python path: + +```sh + export CARLA_ROOT= + export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla +``` +__3.__ Add the source path for the ROS bridge workspace: + +```sh + source ./install/setup.bash +``` + +__4.__ In another terminal, start the ROS 2 bridge. You can run one of the two options below: + +```sh + # Option 1, start the basic ROS bridge package + ros2 launch carla_ros_bridge carla_ros_bridge.launch.py + + # Option 2, start the ROS bridge with an example ego vehicle + ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py +``` + +!!! Note + + If you receive the error: `ImportError: no module named CARLA` then the path to the CARLA Python API is missing. The apt installation sets the path automatically, but it may be missing for other installations. + + You will need to add the appropriate `.egg` file to your Python path. You will find the file in either `/PythonAPI/` or `/PythonAPI/dist/` depending on the CARLA installation. Execute the following command with the complete path to the `.egg` file, using the file that corresponds to your installed version of Python: + + `export PYTHONPATH=$PYTHONPATH:path/to/carla/PythonAPI/` + + To check the CARLA library can be imported correctly, run the following command and wait for a success message: + + python3 -c 'import carla;print("Success")' # python3 + + or + + python -c 'import carla;print("Success")' # python2 + + + +--- + +## Testing + +To execute tests using colcon: + +__1.__ Build the package: + +```sh + colcon build --packages-up-to carla_ros_bridge +``` + +__2.__ Run the tests: + +```sh + launch_test carla_ros_bridge/test/ros_bridge_client_ros2_test.py +``` + +--- + + diff --git a/docs/ros_msgs.md b/docs/ros_msgs.md new file mode 100644 index 00000000..aaf694c4 --- /dev/null +++ b/docs/ros_msgs.md @@ -0,0 +1,331 @@ +# CARLA messages reference + +The following reference lists all the CARLA messages available in the ROS bridge. + +Any doubts regarding these messages or the CARLA-ROS bridge can be solved in the forum. + +

+ +--- +## CarlaActorInfo.msg + +Information shared between ROS and CARLA regarding an actor. + +| Field | Type | Description | +| ---------------------------------------------------------- | ---------------------------------------------------------- | ---------------------------------------------------------- | +| `id` | uint32 | The ID of the actor. | +| `parent_id` | uint32 | The ID of the parent actor. \`0\` if no parent available. | +| `type` | string | The identifier of the blueprint this actor was based on. | +| `rolename` | string | Role assigned to the actor when spawned. | + + + + +--- +## CarlaActorList.msg + +A list of messages with some basic information for CARLA actors. + +| Field | Type | Description | +| -------------------------------------------------------- | -------------------------------------------------------- | -------------------------------------------------------- | +| `actors` | [CarlaActorInfo](<#carlaactorinfomsg>) | List of messages with actors' information. | + + + +--- +## CarlaCollisionEvent.msg + +Data retrieved on a collision event detected by the collision sensor of an actor. + +| Field | Type | Description | +| ------------------------------------------------------------------------- | ------------------------------------------------------------------------- | ------------------------------------------------------------------------- | +| `header` | [Header](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/Header.html) | Time stamp and frame ID when the message is published. | +| `other_actor_id` | uint32 | ID of the actor against whom the collision was detected. | +| `normal_impulse` | geometry\_msgs/Vector3 | Vector representing resulting impulse from the collision. | + + + + +--- +## CarlaControl.msg + +These messages control the simulation while in synchronous, non-passive mode. The constant defined is translated as stepping commands. + +| Field | Type | Description | +| ----------------------------------------------------------- | ----------------------------------------------------------- | ----------------------------------------------------------- | +| `command` | int8 | **PLAY**=0
**PAUSE**=1
**STEP\_ONCE**=2 | + +--- + +## CarlaEgoVehicleControl.msg + +Messages sent to apply a control to a vehicle in both modes, autopilot and manual. These are published in a stack. + +| Field | Type | Description | +| ------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------- | +| `header` | [Header](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/Header.html) | Time stamp and frame ID when the message is published. | +| `throttle` | float32 | Scalar value to cotrol the vehicle throttle: **[0.0, 1.0]** | +| `steer` | float32 | Scalar value to control the vehicle steering direction: **[-1.0, 1.0]** to control the vehicle steering | +| `brake` | float32 | Scalar value to control the vehicle brakes: **[0.0, 1.0]** | +| `hand_brake` | bool | If **True**, the hand brake is enabled. | +| `reverse` | bool | If **True**, the vehicle will move reverse. | +| `gear` | int32 | Changes between the available gears in a vehicle. | +| `manual_gear_shift` | bool | If **True**, the gears will be shifted using `gear`. | + +--- + +## CarlaEgoVehicleInfo.msg + +Static information regarding a vehicle, mostly the attributes used to define the vehicle's physics. + +| Field | Type | Description | +| -------------------------------------------------------------- | -------------------------------------------------------------- | -------------------------------------------------------------- | +| `id` | uint32 | ID of the vehicle actor. | +| `type` | string | The identifier of the blueprint this vehicle was based on. | +| `type` | string | The identifier of the blueprint this vehicle was based on. | +| `rolename` | string | Role assigned to the vehicle. | +| `wheels` | [CarlaEgoVehicleInfoWheel](<#carlaegovehicleinfowheelmsg>) | List of messages with information regarding wheels. | +| `max_rpm` | float32 | Maximum RPM of the vehicle's engine. | +| `moi` | float32 | Moment of inertia of the vehicle's engine. | +| `damping_rate_full_throttle` | float32 | Damping rate when the throttle is at maximum. | +| `damping_rate_zero_throttle`
`_clutch_engaged` | float32 | Damping rate when the throttle is zero with clutch engaged. | +| `damping_rate_zero_throttle`
`_clutch_disengaged` | float32 | Damping rate when the throttle is zero with clutch disengaged. | +| `use_gear_autobox` | bool | If **True**, the vehicle will have an automatic transmission. | +| `gear_switch_time` | float32 | Switching time between gears. | +| `clutch_strength` | float32 | The clutch strength of the vehicle. Measured in **Kgm^2/s**. | +| `mass` | float32 | The mass of the vehicle measured in Kg. | +| `drag_coefficient` | float32 | Drag coefficient of the vehicle's chassis. | +| `center_of_mass` | geometry\_msgs/Vector3 | The center of mass of the vehicle. | + +--- + +## CarlaEgoVehicleInfoWheel.msg + +Static information regarding a wheel that will be part of a [CarlaEgoVehicleInfo.msg](#carlaegovehicleinfomsg) message. + +| Field | Type | Description | +| -------------------------------------------------------- | -------------------------------------------------------- | -------------------------------------------------------- | +| `tire_friction` | float32 | A scalar value that indicates the friction of the wheel. | +| `damping_rate` | float32 | The damping rate of the wheel. | +| `max_steer_angle` | float32 | The maximum angle in degrees that the wheel can steer. | +| `radius` | float32 | The radius of the wheel in centimeters. | +| `max_brake_torque` | float32 | The maximum brake torque in Nm. | +| `max_handbrake_torque` | float32 | The maximum handbrake torque in Nm. | +| `position` | geometry\_msgs/Vector3 | World position of the wheel. | + +--- + +## CarlaEgoVehicleStatus.msg + +Current status of the vehicle as an object in the world. + +| Field | Type | Description | +| ------------------------------------------------------------------------- | ------------------------------------------------------------------------- | ------------------------------------------------------------------------- | +| `header` | [Header](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/Header.html) | Time stamp and frame ID when the message is published. | +| `velocity` | float32 | Current speed of the vehicle. | +| `acceleration` | geometry\_msgs/Accel | Current acceleration of the vehicle. | +| `orientation` | geometry\_msgs/Quaternion | Current orientation of the vehicle. | +| `control` | [CarlaEgoVehicleControl](<#carlaegovehiclecontrolmsg>) | Current control values as reported by CARLA. | + +--- + +## CarlaLaneInvasionEvent.msg + +These messages publish lane invasions detected by a lane-invasion sensor attached to a vehicle. The invasions detected in the last step are passed as a list with a constant definition to identify the lane crossed. + + + +| Field | Type | Description | +| ---------------------------------------------------- | ---------------------------------------------------- | ---------------------------------------------------- | +| `header` | [header](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/Header.html) | Time stamp and frame ID when the message is published. | +| `crossed_lane_markings` | int32[] | **LANE\_MARKING\_OTHER**=0
**LANE\_MARKING\_BROKEN**=1
**LANE\_MARKING\_SOLID**=2 | + +--- + +## CarlaScenario.msg + +Details for a test scenario. + + +| Field | Type | Description | +| ---------------------------------- | ---------------------------------- | ---------------------------------- | +| `name` | string | Name of the scenario. | +| `scenario_file` | string | Test file for the scenario. | +| `destination` | geometry\_msgs/Pose | Goal location of the scenario. | +| `target_speed` | float64 | Desired speed during the scenario. | + +--- + +## CarlaScenarioList.msg + +List of test scenarios to run in ScenarioRunner. + + +| Field | Type | Description | +| -------------------------------------- | -------------------------------------- | -------------------------------------- | +| `scenarios` | [CarlaScenario[]](<#carlascenariomsg>) | List of scenarios. | + +--- + +## CarlaScenarioRunnerStatus.msg + +Current state of the ScenarioRunner. It is managed using a constant. + + +| Field | Type | Description | +| ------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------- | +| `status` | uint8 | Current state of the scenario as an enum:
**STOPPED**=0
**STARTING**=1
**RUNNING**=2
**SHUTTINGDOWN**=3
**ERROR**=4 | + +--- + +## CarlaStatus.msg + +Current world settings of the simulation. + + +| Field | Type | Description | +| -------------------------------------------------- | -------------------------------------------------- | -------------------------------------------------- | +| `frame` | uint64 | Current frame number. | +| `fixed_delta_seconds` | float32 | Simulation time between last and current step. | +| `synchronous_mode` | bool | If **True**, synchronous mode is enabled. | +| `synchronous_mode_running` | bool | **True** when the simulation is running. **False** when it is paused. | + +--- + +## CarlaTrafficLightStatus.msg + +Constant definition regarding the state of a traffic light. + +| Field | Type | Description | +| ---------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | +| `id` | uint32 | ID of the traffic light actor. | +| `state` | uint8 | **RED**=0
**YELLOW**=1
**GREEN**=2
**OFF**=3
**UNKNOWN**=4 | + +--- + +## CarlaTrafficLightStatusList.msg + +List of traffic lights with their status. + +| Field | Type | Description | +| ---------------------------------------------------------- | ---------------------------------------------------------- | ---------------------------------------------------------- | +| `scenarios` | [CarlaTrafficLightStatus[]](<#carlatrafficlightstatusmsg>) | A list of messages summarizing traffic light states. | + +--- + +## CarlaWalkerControl.msg + +Information needed to apply a movement controller to a walker. + +| Field | Type | Description | +| ------------------------------------------------- | ------------------------------------------------- | ------------------------------------------------- | +| `direction` | geometry\_msgs/Vector3 | Vector that controls the direction of the walker. | +| `speed` | float32 | A scalar value to control the walker's speed. | +| `jump` | bool | If **True**, the walker will jump. | + +--- + +## CarlaWaypoint.msg + +Data contained in a waypoint object. + +| Field | Type | Description | +| ---------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------------------------------------------------------------- | +| `road_id` | int32 | OpenDRIVE road's id. | +| `section_id` | int32 | OpenDRIVE section's id, based on the order that they are originally defined. | +| `lane_id` | int32 | OpenDRIVE lane's id, this value can be positive or negative which represents the direction of the current lane with respect to the road. | +| `is_junction` | bool | **True**, if the current Waypoint is on a junction as defined by OpenDRIVE. | +| `is_junction` | [geometry\_msgs/Pose](https://docs.ros.org/en/api/geometry_msgs/html/msg/Pose.html) | **True** when the simulation is running. **False** when it is paused. | + +--- + +## CarlaWorldInfo.msg + +Information about the current CARLA map. + +| Field | Type | Description | +| ---------------------------------------------------- | ---------------------------------------------------- | ---------------------------------------------------- | +| `map_name` | string | Name of the CARLA map loaded in the current world. | +| `opendrive` | string | .xodr OpenDRIVE file of the current map as a string. | + +--- + +## EgoVehicleControlCurrent.msg + +Current time, speed and acceleration values of the vehicle. Used by the controller. It is part of a `Carla_Ackermann_Control.EgoVehicleControlInfo.msg` message. + +| Field | Type | Description | +| ----------------------------------------------- | ----------------------------------------------- | ----------------------------------------------- | +| `time_sec` | float32 | Current time when the controller is applied. | +| `speed` | float32 | Current speed applied by the controller. | +| `speed_abs` | float32 | Speed as an absolute value. | +| `accel` | float32 | Current acceleration applied by the controller. | + +--- + +## EgoVehicleControlInfo.msg + +Current values within an Ackermann controller. These messages are useful for debugging. + +| Field | Type | Description | +| ------------------------------------------------------------------------- | ------------------------------------------------------------------------- | ------------------------------------------------------------------------- | +| `header` | [header](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/Header.html) | Time stamp and frame ID when the message is published. | +| `restrictions` | [EgoVehicleControlMaxima](<#egovehiclecontrolmaximamsg>) | Limits to the controller values. | +| `target` | [EgoVehicleControlTarget](<#egovehiclecontroltargetmsg>) | Limits to the controller values. | +| `current` | [EgoVehicleControlCurrent](<#egovehiclecontrolcurrentmsg>) | Limits to the controller values. | +| `status` | [EgoVehicleControlStatus](<#egovehiclecontrolstatusmsg>) | Limits to the controller values. | +| `output` | [CarlaEgoVehicleControl](<#carlaegovehiclecontrolmsg>) | Limits to the controller values. | + +--- + +## EgoVehicleControlMaxima.msg + +Controller restrictions (limit values). It is part of a `Carla_Ackermann_Control.EgoVehicleControlInfo.msg` message. + +| Field | Type | Description | +| -------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------- | +| `max_steering_angle` | float32 | Max. steering angle for a vehicle. | +| `max_speed` | float32 | Max. speed for a vehicle. | +| `max_accel` | float32 | Max. acceleration for a vehicle. | +| `max_decel` | float32 | Max. deceleration for a vehicle. Default: **8m/s^2** | +| `min_accel` | float32 | Min. acceleration for a vehicle. When the Ackermann taget accel. exceeds this value, the input accel. is controlled. | +| `max_pedal` | float32 | Min. pedal. | + +--- + +## EgoVehicleControlStatus.msg + +Current status of the ego vehicle controller. It is part of a `Carla_Ackermann_Control.EgoVehicleControlInfo.msg` message. + +| Field | Type | Description | +| -------------------------------- | -------------------------------- | -------------------------------- | +| `status` | string | Current control status. | +| `speed_control_activation_count` | uint8 | Speed controller. | +| `speed_control_accel_delta` | float32 | Speed controller. | +| `speed_control_accel_target` | float32 | Speed controller. | +| `accel_control_pedal_delta` | float32 | Acceleration controller. | +| `accel_control_pedal_target` | float32 | Acceleration controller. | +| `brake_upper_border` | float32 | Borders for lay off pedal. | +| `throttle_lower_border` | float32 | Borders for lay off pedal. | + +--- + +## EgoVehicleControlTarget.msg + +Target values of the ego vehicle controller. It is part of a `Carla_Ackermann_Control.EgoVehicleControlInfo.msg` message. + +| Field | Type | Description | +| ----------------------------------------- | ----------------------------------------- | ----------------------------------------- | +| `steering_angle` | float32 | Target steering angle for the controller. | +| `speed` | float32 | Target speed for the controller. | +| `speed_abs` | float32 | Speed as an absolute value. | +| `accel` | float32 | Target acceleration for the controller. | +| `jerk` | float32 | Target jerk for the controller. | + +
diff --git a/docs/ros_packages.md b/docs/ros_packages.md new file mode 100644 index 00000000..77edd0ee --- /dev/null +++ b/docs/ros_packages.md @@ -0,0 +1,44 @@ +# ROS packages + +Here you will find information about the different ROS bridge packages to use with CARLA. + +- [__Carla Waypoint Publisher__](https://github.com/carla-simulator/ros-bridge/blob/master/carla_waypoint_publisher/README.md) - Provide routes and access to the Carla waypoint API +- [__Carla ROS Scenario Runner__](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_scenario_runner/README.md) - ROS node that wraps the functionality of the CARLA scenario runner to execute scenarios. + +- [__Carla AD Agent__](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ad_agent/README.md) - A basic AD agent, that follows a route, avoids collisions with other vehicles and stops on red traffic lights. + + + + +- [__Carla Walker Agent__](https://github.com/carla-simulator/ros-bridge/blob/master/carla_walker_agent/README.md) - A basic walker agent, that follows a route. + + +--- + + + +## [Carla Waypoint Publisher](https://github.com/carla-simulator/ros-bridge/blob/master/carla_waypoint_publisher/README.md) + + + +--- + +## [Carla ROS Scenario Runner](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_scenario_runner/README.md) + +--- + +## [Carla AD Demo and Agent](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ad_agent/README.md) + + + +--- + +## [Carla Walker Agent](https://github.com/carla-simulator/ros-bridge/blob/master/carla_walker_agent/README.md) + +--- + +# +--- + + +--- \ No newline at end of file diff --git a/docs/ros_sensors.md b/docs/ros_sensors.md new file mode 100644 index 00000000..7bb44123 --- /dev/null +++ b/docs/ros_sensors.md @@ -0,0 +1,138 @@ +# ROS Bridge Sensors + +--- + +## Available Sensors + +###### RGB camera + +| Topic | Type | +|-------|------| +| `/carla/[]//image` | [sensor_msgs.Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | + +###### Depth camera + +| Topic | Type | +|-------|------| +| `/carla/[]//image` | [sensor_msgs.Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | + +###### Semantic segmentation camera + +| Topic | Type | +|-------|------| +| `/carla/[]//image` | [sensor_msgs.Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | + +###### DVS camera + +| Topic | Type | +|-------|------| +| `/carla/[]//events` | [sensor_msgs.PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]//image` | [sensor_msgs.Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | + +###### Lidar + +| Topic | Type | +|-------|------| +| `/carla/[]/` | [sensor_msgs.PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | + +###### Semantic lidar + +| Topic | Type | +|-------|------| +| `/carla/[]/` | [sensor_msgs.PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | + +###### Radar + +| Topic | Type | +|-------|------| +| `/carla/[]/` | [sensor_msgs.PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | + +###### IMU + +| Topic | Type | +|-------|------| +| `/carla/[]/` | [sensor_msgs.Imu](https://docs.ros.org/en/api/sensor_msgs/html/msg/Imu.html) | + +###### GNSS + +| Topic | Type | +|-------|------| +| `/carla/[]/` | [sensor_msgs.NavSatFix](https://docs.ros.org/en/api/sensor_msgs/html/msg/NavSatFix.html) | + +###### Collision Sensor + +| Topic | Type | +|-------|------| +| `/carla/[]/` | [carla_msgs.CarlaCollisionEvent](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaCollisionEvent.msg) | + +###### Lane Invasion Sensor + +| Topic | Type | +|-------|------| +| `/carla/[]/` | [carla_msgs.CarlaLaneInvasionEvent](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaLaneInvasionEvent.msg) | + +Pseudo sensors + +###### TF Sensor + + + +The tf data for the ego vehicle is published when this pseudo sensor is spawned. + +Note: Sensors publish the tf data when the measurement is done. The child_frame_id corresponds with the prefix of the sensor topics. + +###### Odometry Sensor + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//` | [nav_msgs.Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Odometry of the parent actor. | + +###### Speedometer Sensor + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//` | [std_msgs.Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html) | Speed of the parent actor. Units: m/s. | + +###### Map Sensor + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/[]/` | [std_msgs.String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html) | Provides the OpenDRIVE map as a string on a latched topic. | + +###### Object Sensor + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/[]/` | [derived_object_msgs.ObjectArray](https://docs.ros.org/en/melodic/api/derived_object_msgs/html/msg/ObjectArray.html) | Publishes all vehicles and walker. If attached to a parent, the parent is not contained. | + +###### Marker Sensor + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/[]/` | [visualization_msgs.Marker](https://docs.ros.org/en/api/visualization_msgs/html/msg/Marker.html) | Visualization of vehicles and walkers | + +###### Traffic Lights Sensor + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/[]//status` | [carla_msgs.CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaTrafficLightStatusList.msg) | List of all traffic lights with their status. | +| `/carla/[]//info` | [carla_msgs.CarlaTrafficLightInfoList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaTrafficLightInfoList.msg) | Static information for all traffic lights (e.g. position). | + +###### Actor List Sensor + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/[]/` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaActorList.msg) | List of all CARLA actors. | + +###### Actor Control Sensor + +This pseudo-sensor allows to control the position and velocity of the actor it is attached to (e.g. an ego_vehicle) by publishing pose and velocity within Pose and Twist datatypes. CAUTION: This control method does not respect the vehicle constraints. It allows movements impossible in the real world, like flying or rotating. Currently this sensor applies the complete linear vector, but only the yaw from angular vector. + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/[]//set_transform` | [geometry_msgs.Pose](https://docs.ros.org/en/api/geometry_msgs/html/msg/Pose.html) | Transform to apply to the sensor's parent. | +| `/carla/[]//set_target_velocity` | [geometry_msgs.Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | Velocity (angular and linear) to apply to the sensor's parent. | diff --git a/docs/rqt_plugin.md b/docs/rqt_plugin.md new file mode 100644 index 00000000..e80d0c14 --- /dev/null +++ b/docs/rqt_plugin.md @@ -0,0 +1,11 @@ +# RQT Carla Plugin + +The RQT plugin is a simple interface for pausing, playing and controlling the steps of a simulation. To use it, execute the following command with the ROS-bridge running in synchronous mode: + +``` + rqt --standalone rqt_carla_control +``` + +You will be able to control the steps via GUI: + +>>>![rqt_plugin](images/rqt_plugin.png) diff --git a/docs/run_ros.md b/docs/run_ros.md new file mode 100644 index 00000000..a2c76d65 --- /dev/null +++ b/docs/run_ros.md @@ -0,0 +1,174 @@ +# The ROS Bridge package + +The `carla_ros_bridge` package is the main package needed to run the basic ROS bridge functionality. In this section you will learn how to prepare the ROS environment, run the ROS bridge, how to configure the settings, usage of synchronous mode, controlling the ego vehicle and a summary of the subscriptions, publications and services available. + +- [__Setting the ROS environment__](#setting-the-ros-environment) + - [Prepare ROS 1 environment](#prepare-ros-1-environment) + - [Prepare ROS 2 environment](#prepare-ros-2-environment) +- [__Running the ROS bridge__](#running-the-ros-bridge) +- [__Configuring CARLA settings__](#configuring-carla-settings) +- [__Using the ROS bridge in synchronous mode__](#using-the-ros-bridge-in-synchronous-mode) +- [__Ego vehicle control__](#ego-vehicle-control) +- [__ROS bridge subscriptions, publications and services__](#ros-bridge-subscriptions-publications-and-services) + - [Subscriptions](#subscriptions) + - [Publications](#publications) + - [Services](#services) +--- + +## Setting the ROS environment + +The ROS bridge supports both ROS 1 and ROS 2 using separate implementations with a common interface. When you want to run the ROS bridge you will have to set your ROS environment according to your ROS version in every terminal that you use: + +#### Prepare ROS 1 environment: + +The command to run depends on whether you installed ROS via the Debian package or via the source build. You will also need to change the ROS version in the path for the Debian option: + +```sh + # For debian installation of ROS bridge. Change the command according to your installed version of ROS. + source /opt/carla-ros-bridge//setup.bash + + # For GitHub repository installation of ROS bridge + source ~/carla-ros-bridge/catkin_ws/devel/setup.bash +``` + +#### Prepare ROS 2 environment: + +```sh + source ./install/setup.bash +``` + +## Running the ROS bridge + +Once you have set your ROS environment and have a CARLA server running, you will need to start the `carla_ros_bridge` package before being able to use any of the other packages. To do that, run the following command: + +```sh + # ROS 1 + roslaunch carla_ros_bridge carla_ros_bridge.launch + + # ROS 2 + ros2 launch carla_ros_bridge carla_ros_bridge.launch.py +``` + +There are other launchfiles that combine the above functionality of starting the ROS bridge at the same time as starting other packges or plugins: + +- `carla_ros_bridge_with_example_ego_vehicle.launch` (ROS 1) and `carla_ros_bridge_with_example_ego_vehicle.launch.py` (ROS 2) start the ROS bridge along with the [`carla_spawn_objects`](carla_spawn_objects.md) and [`carla_manual_control`](carla_manual_control.md) packages. +- `carla_ros_bridge_with_rviz.launch` (ROS 1) and `carla_ros_bridge_with_rviz.launch.py` (ROS 2) start the ROS bridge along with the [RVIZ plugin](rviz_plugin.md). + +--- + +## Configuring CARLA settings + +Configuration settings can be modified in [`ros-bridge/carla_ros_bridge/config/settings.yaml`](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_bridge/config/settings.yaml). The following settings are available: + +* __use_sim_time__: This should be set to __True__ to ensure that ROS is using simulation time rather than system time. This parameter will synchronize the ROS [`/clock`][ros_clock] topic with CARLA simulation time. +* __host and port__: Network settings to connect to CARLA using a Python client. +* __timeout__: Time to wait for a successful connection to the server. +* __passive__: Passive mode is for use in scynchronous mode. When enabled, the ROS bridge will take a backseat and another client __must__ tick the world. ROS bridge will wait for all expected data from all sensors to be received. +* __synchronous_mode__: + * __If false (default)__: Data is published on every `world.on_tick()` and every `sensor.listen()` callback. + * __If true__: ROS bridge waits for all the sensor messages expected before the next tick. This might slow down the overall simulation but ensures reproducible results. +* __synchronous_mode_wait_for_vehicle_control_command__: In synchronous mode, pauses the tick until a vehicle control is completed. +* __fixed_delta_seconds__: Simulation time (delta seconds) between simulation steps. __It must be lower than 0.1__. Take a look at the [documentation](https://carla.readthedocs.io/en/latest/adv_synchrony_timestep/) to learn more about this. +* __ego_vehicle__: Role names to identify ego vehicles. Relevant topics will be created so these vehicles will be able to be controlled from ROS. + +[ros_clock]: https://wiki.ros.org/Clock + +Most of the above parameters as well as others such as `town` and `rosbag_fname` can also be set within the launchfile `carla_ros_bridge.launch` or passed as an argument when running the file from the command line. When specifying a town, either use an available CARLA town (eg. 'town01') or an OpenDRIVE file (ending in `.xodr`). + +--- + +## Using the ROS bridge in synchronous mode + +When running multiple clients in synchronous mode, only one client is allowed to tick the world. The ROS bridge will by default be the only client allowed to tick the world unless passive mode is enabled. Enabling passive mode in [`ros-bridge/carla_ros_bridge/config/settings.yaml`](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_bridge/config/settings.yaml) will make the ROS bridge step back and allow another client to tick the world. __Another client must tick the world, otherwise CARLA will freeze.__ + +If the ROS bridge is not in passive mode (ROS bridge is the one ticking the world), then there are two ways to send step controls to the server: + +- Send a message to the topic `/carla/control` with a [`carla_msgs.CarlaControl`](ros_msgs.md#carlacontrolmsg) message. +- Use the [Control rqt plugin](rqt_plugin.md). This plugin launches a new window with a simple interface. It is then used to manage the steps and publish in the `/carla/control` topic. To use it, run the following command with CARLA in synchronous mode: +```sh + rqt --standalone rqt_carla_control +``` + +--- + +## Ego vehicle control + +There are two modes to control the ego vehicle: + +1. Normal mode - reading commands from `/carla//vehicle_control_cmd` +2. Manual mode - reading commands from `/carla//vehicle_control_cmd_manual`. This allows to manually override Vehicle Control Commands published by a software stack. + +You can toggle between the two modes by publishing to `/carla//vehicle_control_manual_override`. For an example of this being used see [Carla Manual Control](carla_manual_control.md). + +To test steering from the command line: + +__1.__ Launch the ROS Bridge with an ego vehicle: + +```sh + # ROS 1 + roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch + + # ROS 2 + ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py +``` + +__2.__ In another terminal, publish to the topic `/carla//vehicle_control_cmd` + +```sh + # Max forward throttle with max steering to the right + + # for ros1 + rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10 + + # for ros2 + ros2 topic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10 + +``` + +The current status of the vehicle can be received via topic `/carla//vehicle_status`. Static information about the vehicle can be received via `/carla//vehicle_info`. + +It is possible to use [AckermannDrive](https://docs.ros.org/en/api/ackermann_msgs/html/msg/AckermannDrive.html) messages to control the ego vehicles. This can be achieved through the use of the [CARLA Ackermann Control](carla_ackermann_control.md) package. + +--- + +## ROS bridge subscriptions, publications and services + +#### Subscriptions + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/debug_marker` | [visualization_msgs.MarkerArray](https://docs.ros.org/en/api/visualization_msgs/html/msg/MarkerArray.html) | Draws markers in the CARLA world. | +| `/carla/weather_control` | [carla_msgs.CarlaWeatherParameters](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaWeatherParameters.msg) | Set the CARLA weather parameters | +| `/clock` | [rosgraph_msgs/Clock](https://docs.ros.org/en/melodic/api/rosgraph_msgs/html/msg/Clock.html) | Publishes simulated time in ROS. | + +
+ +#### Publications + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/status` | [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) | Read the current status of CARLA | +| `/carla/world_info` | [carla_msgs/CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) | Information about the current CARLA map. | +| `/clock` | [rosgraph_msgs/Clock](https://docs.ros.org/en/melodic/api/rosgraph_msgs/html/msg/Clock.html) | Publishes simulated time in ROS. | +| `/rosout` | [rosgraph_msgs/Log](https://docs.ros.org/en/melodic/api/rosgraph_msgs/html/msg/Log.html) | ROS logging. | + +
+ +#### Services + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/destroy_object` | [](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/DestroyObject.srv) | Destroys an object | +| `/carla/get_blueprints` | [](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/GetBlueprints.srv) | Gets blueprints | +| `/carla/spawn_object` | [](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/SpawnObject.srv) | Spawn an object | +| `/carla_ros_bridge/get_loggers` | []() | | +| `/carla_ros_bridge/set_logger_level` | []() | | + +--- + + + + + + + diff --git a/docs/rviz_plugin.md b/docs/rviz_plugin.md new file mode 100644 index 00000000..5e96c6f2 --- /dev/null +++ b/docs/rviz_plugin.md @@ -0,0 +1,94 @@ +# RVIZ Carla Plugin + +The RVIZ plugin provides a visualization tool based on the [RVIZ](https://wiki.ros.org/rviz) ROS package. + +- [__Run ROS bridge with RVIZ__](#run-ros-bridge-with-rviz) +- [__Features of the RVIZ plugin__](#features-of-the-rviz-plugin) +- [__RVIZ plugin subscriptions, publications and services__](#rviz-plugin-subscriptions-publications-and-services) + - [Subscriptions](#subscriptions) + - [Publications](#publications) + - [Services](#services) + +--- + +## Run ROS bridge with RVIZ + +![ros_rviz](images/ros_rviz.png) + +The RVIZ plugin expects an ego vehicle named `ego_vehicle`. To see an example of ROS-bridge working with RVIZ, execute the following the commands with a CARLA server running: + +__1.__ Start the ROS bridge with RVIZ enabled: + +```sh + # ROS 1 + roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch + + # ROS 2 + ros2 launch carla_ros_bridge carla_ros_bridge_with_rviz.launch.py +``` + +__2.__ Spawn an ego vehicle with the `carla_spawn_objects` package: + +```sh + # ROS 1 + roslaunch carla_spawn_objects carla_spawn_objects.launch + + # ROS 2 + ros2 launch carla_spawn_objects carla_spawn_objects.launch.py +``` + +__3.__ Control the ego vehicle with the `carla_manual_control` package (press `B` to enable manual steering): + +```sh + # ROS 1 + roslaunch carla_manual_control carla_manual_control.launch + + # ROS 2 + ros2 launch carla_manual_control carla_manual_control.launch.py +``` + +--- + +## Features of the RVIZ plugin + +- __Visualization of the ego vehicle state__ - Visualize the vehicle position and control. +- __Provide RVIZ view pose to other nodes__ - With an `actor.pseudo.control` attached to a camera, move the camera around in the CARLA world by publishing a Pose message. +- __Visualization of sensors__ - Visualize RGB, LIDAR, depth, DVS and semanatic segmentation camera information. +- __Execute scenarios__ - Use the [carla_ros_scenario_runner](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_scenario_runner) package to trigger scenarios. +- __Play/Pause the simulation__ - If started in synchronous mode, you can play and pause the simulation. +- __Manually override ego vehicle control__ - Steer the vehicle by mouse by using the drive-widget from the [RVIZ Visualization Tutorials](https://github.com/ros-visualization/visualization_tutorials) and a [node](https://github.com/carla-simulator/ros-bridge/blob/master/carla_twist_to_control) to convert from twist to vehicle control. + +--- + +## RVIZ plugin subscriptions, publications and services + +#### Subscriptions + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/status` | [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) | Read the current status of CARLA | +| `/carla/ego_vehicle/vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) | Display the current state of the ego vehicle | +| `/carla/ego_vehicle/odometry` | [nav_msgs.Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Display the current pose of the ego vehicle | +| `/scenario_runner/status` | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](ros_msgs.md#carlascenariorunnerstatusmsg) | Visualize the scenario runner status | +| `/carla/available_scenarios` | [carla_ros_scenario_runner_types.CarlaScenarioList](ros_msgs.md#carlascenariolistmsg) | Provides a list of scenarios to execute (disabled in combo box)| + +
+ +#### Publications + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla/control` | [carla_msgs.CarlaControl](ros_msgs.md#carlacontrolmsg) | Play/pause/step CARLA | +| `/carla/ego_vehicle/spectator_pose` | [geometry_msgs.PoseStamped](https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html) | Publish the current pose of the RVIZ camera view | +| `/carla/ego_vehicle/vehicle_control_manual_override` | [std_msgs.Bool](https://docs.ros.org/en/api/std_msgs/html/msg/Bool.html) | Enable/disable vehicle control override | +| `/carla/ego_vehicle/twist` | [geometry_msgs.Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | The twist command, created via mouse | + +
+ +#### Services + +| Topic | Type | Description | +|-------|------|-------------| +| `/scenario_runner/execute_scenario` | [carla_ros_scenario_runner_types.ExecuteScenario](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | Execute the selected scenario | + +
diff --git a/mkdocs.yml b/mkdocs.yml new file mode 100644 index 00000000..6bdda69a --- /dev/null +++ b/mkdocs.yml @@ -0,0 +1,26 @@ +site_name: CARLA Simulator +repo_url: https://github.com/carla-simulator/ros-bridge +docs_dir: docs +edit_uri: 'edit/master/docs/' +theme: readthedocs +extra_css: [extra.css] + +nav: +- Home: 'index.md' +- Getting started: + - Install ROS Bridge for ROS 1: 'ros_installation_ros1.md' + - Install ROS Bridge for ROS 2: 'ros_installation_ros2.md' + - The ROS bridge package: 'run_ros.md' +- ROS Bridge Packages: + - Carla Spawn Objects: 'carla_spawn_objects.md' + - Carla Manual Control: 'carla_manual_control.md' + - Carla Ackermann Control: 'carla_ackermann_control.md' + - RVIZ Plugin: 'rviz_plugin.md' + - RQT Plugin: 'rqt_plugin.md' +- References: + - CARLA messages reference: 'ros_msgs.md' + - Launchfiles reference: 'ros_launchfiles.md' + + +markdown_extensions: + - admonition From 661d1d0f363dbea2ced7c3f74638d0e7e4341742 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 18:38:43 +0100 Subject: [PATCH 539/627] using checkout v1 --- .github/workflows/ci.yml | 59 ++++++++++++++++++++-------------------- 1 file changed, 30 insertions(+), 29 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 20d41fed..a19526e0 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -46,16 +46,13 @@ jobs: ROS_VERSION: ${{ matrix.ros_version }} ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} steps: - - uses: actions/checkout@v2 - # TODO cleaner solution but currently not working because git version is below 2.18 - # with: - # submodules: true + # We currently cannot use checkout@v2 because git version on ros images is below 2.18 + - uses: actions/checkout@v1 + with: + fetch-depth: 1 + submodules: true - name: Setup run: | - sudo apt-get update && sudo apt-get install wget unzip -y - #TODO: replace ros2 with master - rm -rf carla_msgs && wget https://github.com/carla-simulator/ros-carla-msgs/archive/ros2.zip - unzip ros2.zip -d carla_msgs && rm ros2.zip packaging/install_dependencies.sh - name: ROS2 Build, Test, Lint if: ${{ matrix.ros_version == 2 }} @@ -83,24 +80,28 @@ jobs: # make pylint # TODO enable pylint - # debian: - # runs-on: ubuntu-latest - # strategy: - # matrix: - # include: - # - docker_image: melodic-robot - # ros_distro: melodic - # ros_python_version: 2 - # ros_version: 1 - # container: - # image: ros:${{ matrix.docker_image }} - # env: - # SCENARIO_RUNNER_PATH: "" - # DEBIAN_FRONTEND: "noninteractive" - # ROS_DISTRO: ${{ matrix.ros_distro }} - # ROS_VERSION: ${{ matrix.ros_version }} - # ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} - # steps: - # - uses: actions/checkout@v2 - # - name: Build Debian Package - # run: make deb + debian: + runs-on: ubuntu-latest + strategy: + matrix: + include: + - docker_image: melodic-robot + ros_distro: melodic + ros_python_version: 2 + ros_version: 1 + container: + image: ros:${{ matrix.docker_image }} + env: + SCENARIO_RUNNER_PATH: "" + DEBIAN_FRONTEND: "noninteractive" + ROS_DISTRO: ${{ matrix.ros_distro }} + ROS_VERSION: ${{ matrix.ros_version }} + ROS_PYTHON_VERSION: ${{ matrix.ros_python_version }} + steps: + # We currently cannot use checkout@v2 because git version on ros images is below 2.18 + - uses: actions/checkout@v1 + with: + fetch-depth: 1 + submodules: true + - name: Build Debian Package + run: make deb From af9b8ae92611d9d8395253ac448b2e40a3370574 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 18:51:20 +0100 Subject: [PATCH 540/627] installing debian dependencies and enbabling packaging ci --- .github/workflows/ci.yml | 5 +++++ packaging/build-deb.sh | 4 +--- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index a19526e0..f3591ae3 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -89,6 +89,11 @@ jobs: ros_distro: melodic ros_python_version: 2 ros_version: 1 + + - docker_image: noetic-robot + ros_distro: noetic + ros_python_version: 3 + ros_version: 1 container: image: ros:${{ matrix.docker_image }} env: diff --git a/packaging/build-deb.sh b/packaging/build-deb.sh index 6da59b34..9e2e2b0d 100755 --- a/packaging/build-deb.sh +++ b/packaging/build-deb.sh @@ -15,10 +15,8 @@ if [ "$ROS_PYTHON_VERSION" = "3" ]; then PYTHON_SUFFIX=3 fi -sudo apt update +${SCRIPT_DIR}/install_dependencies.sh sudo apt-get install --no-install-recommends -y \ - python$PYTHON_SUFFIX-osrf-pycommon \ - python$PYTHON_SUFFIX-catkin-tools \ rsync \ build-essential \ dh-make From c9873afaf6da37701aa3a39d5407c01c6da800c6 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 18:52:58 +0100 Subject: [PATCH 541/627] fixed indentation --- .github/workflows/ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index f3591ae3..315db411 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -90,7 +90,7 @@ jobs: ros_python_version: 2 ros_version: 1 - - docker_image: noetic-robot + - docker_image: noetic-robot ros_distro: noetic ros_python_version: 3 ros_version: 1 From b9ee408b6d37060b2bf6aa23a3418bcee4258bab Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 5 Mar 2021 19:07:16 +0100 Subject: [PATCH 542/627] moved installation of dependencies to ci step --- .github/workflows/ci.yml | 5 +++-- packaging/build-deb.sh | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 315db411..32af906f 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -52,8 +52,7 @@ jobs: fetch-depth: 1 submodules: true - name: Setup - run: | - packaging/install_dependencies.sh + run: packaging/install_dependencies.sh - name: ROS2 Build, Test, Lint if: ${{ matrix.ros_version == 2 }} shell: bash @@ -108,5 +107,7 @@ jobs: with: fetch-depth: 1 submodules: true + - name: Setup + run: packaging/install_dependencies.sh - name: Build Debian Package run: make deb diff --git a/packaging/build-deb.sh b/packaging/build-deb.sh index 9e2e2b0d..72be6718 100755 --- a/packaging/build-deb.sh +++ b/packaging/build-deb.sh @@ -15,7 +15,7 @@ if [ "$ROS_PYTHON_VERSION" = "3" ]; then PYTHON_SUFFIX=3 fi -${SCRIPT_DIR}/install_dependencies.sh +sudo apt update sudo apt-get install --no-install-recommends -y \ rsync \ build-essential \ From 75cf4127a54d8a1607371f1d30a4a6a207dd9624 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 11:20:40 +0100 Subject: [PATCH 543/627] removed mixin folder --- mixin/index.yaml | 2 -- mixin/skip.mixin | 25 ------------------------- 2 files changed, 27 deletions(-) delete mode 100644 mixin/index.yaml delete mode 100644 mixin/skip.mixin diff --git a/mixin/index.yaml b/mixin/index.yaml deleted file mode 100644 index d8313acf..00000000 --- a/mixin/index.yaml +++ /dev/null @@ -1,2 +0,0 @@ -mixin: - - skip.mixin \ No newline at end of file diff --git a/mixin/skip.mixin b/mixin/skip.mixin deleted file mode 100644 index 2fe3f04d..00000000 --- a/mixin/skip.mixin +++ /dev/null @@ -1,25 +0,0 @@ -{ - "build": { - "skip": { - "packages-skip": [ - "carla_infrastructure", - "carla_ros_scenario_runner", - "carla_ros_scenario_runner_types", - "carla_spectator_camera", - "carla_walker_agent", - "pcl_recorder", - "rqt_carla_control", - "rviz_carla_plugin", - "astuff_sensor_msgs", - "delphi_esr_msgs", - "delphi_mrr_msgs", - "delphi_srr_msgs", - "ibeo_msgs", - "kartech_linear_actuator_msgs", - "mobileye_560_660_msgs", - "neobotix_usboard_msgs", - "pacmod_msgs", - ], - } - } -} From 803489ed96cc2f838415733af69007b62be801a3 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 11:21:04 +0100 Subject: [PATCH 544/627] removed travis file --- .travis.yml | 40 ---------------------------------------- 1 file changed, 40 deletions(-) delete mode 100644 .travis.yml diff --git a/.travis.yml b/.travis.yml deleted file mode 100644 index 15e1bb1a..00000000 --- a/.travis.yml +++ /dev/null @@ -1,40 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -os: linux -services: docker - -cache: - - apt - -addons: - apt: - packages: - - python-pip - -jobs: - include: - - name: "Docker Melodic" - env: - - ROS_DISTRO=melodic - - PYTHON_SUFFIX="2.7" - - name: "Docker Noetic" - env: - - ROS_DISTRO=noetic - - PYTHON_SUFFIX="3.7" - - name: "Docker Foxy" - env: - - ROS_DISTRO=foxy - - PYTHON_SUFFIX="3.7" - -script: cd docker && ./build.sh --build-arg ROS_VERSION=$ROS_DISTRO --build-arg PYTHON_VERSION=$PYTHON_SUFFIX - -after_failure: - - tail --lines=2000 build.log - -notifications: - email: false \ No newline at end of file From 7f6837c5ec9d4e330d7e958677325b8b9bd3ff2d Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 11:52:05 +0100 Subject: [PATCH 545/627] updated dockerfiles --- docker/Dockerfile | 70 +++++++++++-------------------- docker/Dockerfile.eloquent | 52 ----------------------- docker/build.sh | 18 +++++++- docker/content/ros_entrypoint.sh | 4 +- docker/run.sh | 6 ++- packaging/install_dependencies.sh | 11 ++++- 6 files changed, 59 insertions(+), 102 deletions(-) delete mode 100644 docker/Dockerfile.eloquent diff --git a/docker/Dockerfile b/docker/Dockerfile index 2c44d892..35476386 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -1,51 +1,29 @@ -ARG CARLA_VERSION='0.9.9' -ARG ROS_VERSION='melodic' -ARG CARLA_BUILD='' -ARG PYTHON_VERSION='2.7' - -FROM carlasim/carla:$CARLA_VERSION$CARLA_BUILD as carla - -FROM ros:$ROS_VERSION-ros-base - -ARG ROS_VERSION - -RUN apt-get update && \ - if [ "$ROS_VERSION" = "noetic" ] ; then export PYTHON_SUFFIX=3 ; else export PYTHON_SUFFIX="" ; fi && \ - apt-get install -y --no-install-recommends \ - libpng16-16 \ - ros-$ROS_VERSION-ackermann-msgs \ - ros-$ROS_VERSION-tf \ - ros-$ROS_VERSION-derived-object-msgs \ - ros-$ROS_VERSION-cv-bridge \ - ros-$ROS_VERSION-pcl-conversions \ - ros-$ROS_VERSION-pcl-ros \ - python$PYTHON_SUFFIX-osrf-pycommon \ - python$PYTHON_SUFFIX-catkin-tools \ - && rm -rf /var/lib/apt/lists/* +ARG CARLA_VERSION +ARG ROS_DISTRO + +FROM carlasim/carla:$CARLA_VERSION as carla + +FROM ros:$ROS_DISTRO-ros-base ARG CARLA_VERSION -ARG PYTHON_VERSION - -COPY --from=carla --chown=root /home/carla/PythonAPI /opt/carla/PythonAPI -ENV PYTHONPATH=/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py$PYTHON_VERSION-linux-x86_64.egg - -COPY carla_ackermann_control /opt/carla-ros-bridge/src/carla_ackermann_control -COPY carla_common /opt/carla-ros-bridge/src/carla_common -COPY carla_spawn_objects /opt/carla-ros-bridge/src/carla_spawn_objects -COPY carla_manual_control /opt/carla-ros-bridge/src/carla_manual_control -COPY carla_msgs /opt/carla-ros-bridge/src/carla_msgs -COPY carla_ros_bridge /opt/carla-ros-bridge/src/carla_ros_bridge -COPY carla_ros_scenario_runner /opt/carla-ros-bridge/src/carla_ros_scenario_runner -COPY carla_ros_scenario_runner_types /opt/carla-ros-bridge/src/carla_ros_scenario_runner_types -COPY carla_twist_to_control /opt/carla-ros-bridge/src/carla_twist_to_control -COPY carla_walker_agent /opt/carla-ros-bridge/src/carla_walker_agent -COPY carla_waypoint_publisher /opt/carla-ros-bridge/src/carla_waypoint_publisher -COPY carla_waypoint_types /opt/carla-ros-bridge/src/carla_waypoint_types -COPY pcl_recorder /opt/carla-ros-bridge/src/pcl_recorder - -RUN /bin/bash -c 'source /opt/ros/$ROS_VERSION/setup.bash; cd /opt/carla-ros-bridge; catkin config --install; catkin build --cmake-args -DCMAKE_BUILD_TYPE=Release' +ARG ROS_DISTRO + +ENV CARLA_VERSION=$CARLA_VERSION +ENV DEBIAN_FRONTEND=noninteractive + +RUN mkdir -p /opt/carla-ros-bridge/src +WORKDIR /opt/carla-ros-bridge + +COPY --from=carla /home/carla/PythonAPI /opt/carla/PythonAPI + +COPY . /opt/carla-ros-bridge/src/ + +RUN /bin/bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \ + bash /opt/carla-ros-bridge/src/packaging/install_dependencies.sh; \ + if [ "$CARLA_VERSION" = "0.9.10" ] || [ "$CARLA_VERSION" = "0.9.10.1" ]; then wget https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/carla-0.9.10-py2.7-linux-x86_64.egg -P /opt/carla/PythonAPI/carla/dist; fi; \ + echo "export PYTHONPATH=\$PYTHONPATH:/opt/carla/PythonAPI/carla/dist/$(ls /opt/carla/PythonAPI/carla/dist | grep py$ROS_PYTHON_VERSION.)" >> /opt/carla/setup.bash; \ + echo "export PYTHONPATH=\$PYTHONPATH:/opt/carla/PythonAPI/carla" >> /opt/carla/setup.bash; \ + if [ "$ROS_VERSION" == "2" ]; then colcon build; else catkin_make install; fi' # replace entrypoint COPY ./docker/content/ros_entrypoint.sh / - -CMD ["roslaunch", "carla_ros_bridge", "carla_ros_bridge.launch"] diff --git a/docker/Dockerfile.eloquent b/docker/Dockerfile.eloquent deleted file mode 100644 index 3bb4e158..00000000 --- a/docker/Dockerfile.eloquent +++ /dev/null @@ -1,52 +0,0 @@ -ARG CARLA_VERSION='0.9.9' -ARG ROS_VERSION='eloquent' -ARG CARLA_BUILD='' - -FROM carlasim/carla:$CARLA_VERSION$CARLA_BUILD as carla - -FROM ros:$ROS_VERSION-ros-base - -ARG ROS_VERSION - -RUN mkdir -p /carla_ws/src -WORKDIR /carla_ws - -RUN apt-get update \ - && apt-get install -y --no-install-recommends \ - libpng16-16 \ - # ros-$ROS_VERSION-ackermann-msgs \ - # ros-$ROS_VERSION-derived-object-msgs \ - # ros-$ROS_VERSION-tf \ - ros-$ROS_VERSION-cv-bridge \ - ros-$ROS_VERSION-pcl-conversions \ - # ros-$ROS_VERSION-pcl-ros \ - # ros-$ROS_VERSION-ainstein-radar \ - # python-catkin-tools \ - && rm -rf /var/lib/apt/lists/* - -ARG CARLA_VERSION - -COPY --from=carla --chown=root /home/carla/PythonAPI /opt/carla/PythonAPI -RUN sudo apt-get update && sudo apt-get install python-pip python3-pip -y --no-install-recommends -RUN python -m pip install setuptools -RUN python3 -m pip install setuptools -RUN easy_install --user --no-deps "/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py2.7-linux-x86_64.egg" -RUN easy_install --user --no-deps "/opt/carla/PythonAPI/carla/dist/carla-$CARLA_VERSION-py3.7-linux-x86_64.egg" - -COPY . src/ - -SHELL ["/bin/bash", "-c" , "-l"] - -RUN echo "source /opt/ros/$ROS_VERSION/setup.bash" >> /etc/profile - -RUN sudo apt-get update && sudo apt-get install ros-eloquent-ros-environment -#RUN rosdep install --from-paths src -r -y -RUN colcon info carla_msgs -# .bashrc does not seem to do the source -RUN colcon mixin add skip file:///carla_ws/src/ros-bridge/mixin/index.yaml -RUN colcon mixin update skip -RUN colcon build --mixin skip - -RUN echo "source /carla_ws/install/setup.bash" >> /etc/profile - -CMD ["ros2", "run", "carla_ros_bridge" , "carla_ros_bridge.py"] diff --git a/docker/build.sh b/docker/build.sh index 7b29057d..45c73a80 100755 --- a/docker/build.sh +++ b/docker/build.sh @@ -1,3 +1,19 @@ #!/bin/sh -docker build -t carla-ros-bridge -f Dockerfile ./.. "$@" +ROS_DISTRO="foxy" +CARLA_VERSION="0.9.10" + +while getopts r:c: flag +do + case "${flag}" in + r) ROS_DISTRO=${OPTARG};; + c) CARLA_VERSION=${OPTARG};; + *) error "Unexpected option ${flag}" ;; + esac +done + +docker build \ + -t carla-ros-bridge:$ROS_DISTRO \ + -f Dockerfile ./.. \ + --build-arg ROS_DISTRO=$ROS_DISTRO \ + --build-arg CARLA_VERSION=$CARLA_VERSION diff --git a/docker/content/ros_entrypoint.sh b/docker/content/ros_entrypoint.sh index f2b17898..473003b2 100755 --- a/docker/content/ros_entrypoint.sh +++ b/docker/content/ros_entrypoint.sh @@ -3,4 +3,6 @@ set -e # setup ros environment source "/opt/carla-ros-bridge/install/setup.bash" -exec "$@" \ No newline at end of file +source "/opt/carla/setup.bash" + +exec "$@" diff --git a/docker/run.sh b/docker/run.sh index 9fd597dc..3dc19b68 100755 --- a/docker/run.sh +++ b/docker/run.sh @@ -32,4 +32,8 @@ shift $((OPTIND-1)) echo "Using $DOCKER_IMAGE_NAME:$TAG" -docker run -it --rm "$DOCKER_IMAGE_NAME:$TAG" "$@" +docker run \ + -it --rm \ + --privileged \ + --net=host \ + "$DOCKER_IMAGE_NAME:$TAG" "$@" diff --git a/packaging/install_dependencies.sh b/packaging/install_dependencies.sh index 1dc0a2d7..caad04e8 100755 --- a/packaging/install_dependencies.sh +++ b/packaging/install_dependencies.sh @@ -14,7 +14,13 @@ else ros-$ROS_DISTRO-rospy-message-converter ros-$ROS_DISTRO-pcl-ros" fi -echo "ADDITIONAL PACKAGES $ADDITIONAL_PACKAGES" + +if [ "$(lsb_release -sc)" = "focal" ]; then + ADDITIONAL_PACKAGES="$ADDITIONAL_PACKAGES + python-is-python3" +fi + +echo ADDITIONAL PACKAGES $ADDITIONAL_PACKAGES sudo apt update sudo apt-get install --no-install-recommends -y \ @@ -25,14 +31,17 @@ sudo apt-get install --no-install-recommends -y \ python$PYTHON_SUFFIX-catkin-pkg-modules \ python$PYTHON_SUFFIX-rosdep \ python$PYTHON_SUFFIX-wstool \ + python$PYTHON_SUFFIX-opencv \ ros-$ROS_DISTRO-ackermann-msgs \ ros-$ROS_DISTRO-derived-object-msgs \ ros-$ROS_DISTRO-cv-bridge \ ros-$ROS_DISTRO-vision-opencv \ ros-$ROS_DISTRO-rqt-image-view \ ros-$ROS_DISTRO-rqt-gui-py \ + wget \ qt5-default \ ros-$ROS_DISTRO-pcl-conversions \ $ADDITIONAL_PACKAGES +pip$PYTHON_SUFFIX install --upgrade pip$PYTHON_SUFFIX pip$PYTHON_SUFFIX install -r $SCRIPT_DIR/../requirements.txt From 6736cac4a4654a94eda1a0ebef4ae19ece7f8bb6 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Mon, 8 Mar 2021 12:24:28 +0100 Subject: [PATCH 546/627] Added sections for the ad demo, ad agent and waypoints packages --- docs/carla_ad_agent.md | 41 +++++++++++++++++++++ docs/carla_ad_demo.md | 82 ++++++++++++++++++++++++++++++++++++++++++ docs/carla_waypoint.md | 69 +++++++++++++++++++++++++++++++++++ mkdocs.yml | 9 +++-- 4 files changed, 198 insertions(+), 3 deletions(-) create mode 100644 docs/carla_ad_agent.md create mode 100644 docs/carla_ad_demo.md create mode 100644 docs/carla_waypoint.md diff --git a/docs/carla_ad_agent.md b/docs/carla_ad_agent.md new file mode 100644 index 00000000..0cdc92de --- /dev/null +++ b/docs/carla_ad_agent.md @@ -0,0 +1,41 @@ +# CARLA AD Agent + +The CARLA AD agent is an AD agent that can follow a given route, avoids crashes with other vehicles and respects the state of traffic lights by accessing ground truth data. It is used by the [CARLA AD demo](carla_ad_demo.md) to provide an example of how the ROS bridge can be used. + +- [__Local Planner Node__](#local-planner-node) +- [__Publications and subscriptions__](#publications-and-subscriptions) + - [Subscriptions](#subscriptions) + - [Publications](#publications) + +--- + +## Local Planner Node + +Internally the CARLA AD Agent uses a separate node for [local planning](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_ad_agent/src/carla_ad_agent/local_planner.py). This node has been optimized for the `vehicle.tesla.model3`, as it does not have any gear shift delays. + +The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedia.org/wiki/Ziegler%E2%80%93Nichols_method). + +## Publications and subscriptions + +#### Subscriptions + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//waypoints` | [nav_msgs.Path](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | Route to follow | +| `/carla//target_speed` | [std_msgs.Float64](https://docs.ros.org/en/api/std_msgs/html/msg/Float64.html) | Target speed | +| `/carla//odometry` | [nav_msgs.Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Localization of ego vehicle | +| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) | Identify the carla actor id of the ego vehicle | +| `/carla//objects` | [derived_object_msgs.ObjectArray](https://docs.ros.org/en/melodic/api/derived_object_msgs/html/msg/ObjectArray.html) | Information about other actors | +| `/carla/actor_list` | [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) | Actor list | +| `/carla/world_info` | [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) | Selects mode for traffic lights (US- or European-style) | +| `/carla/traffic_lights/status` | [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) | Get the current state of the traffic lights | + +
+ +#### Publications + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) | Vehicle control command | + +
diff --git a/docs/carla_ad_demo.md b/docs/carla_ad_demo.md new file mode 100644 index 00000000..e414c8f5 --- /dev/null +++ b/docs/carla_ad_demo.md @@ -0,0 +1,82 @@ +# CARLA AD Demo + +The AD demo is an example package that provides everything needed to launch a CARLA ROS environment with an AD vehicle. + +- [__Before you begin__](#before-you-begin) +- [__Run the demo__](#run-the-demo) + - [Random route](#random-route) + - [Scenario execution](#scenario-execution) +--- + +## Before you begin + +Make sure your Python path is configured correctly to point to the correct version of CARLA: + +```sh +export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ +``` + +You will need to install [Scenario Runner ](https://carla-scenariorunner.readthedocs.io/en/latest/getting_scenariorunner/). Follow the +Scenario Runner ["Getting Started" tutorial](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working. Set an environment variable to find it: + +```sh +export SCENARIO_RUNNER_PATH= +``` + +--- + +## Run the demo + + +#### Random route + +To start a demo where the ego vehicle follows a randomly generated route, run the following command after you have started a CARLA server: + +```sh +# ROS 1 +roslaunch carla_ad_demo carla_ad_demo.launch + +# ROS 2 +ros2 launch carla_ad_demo carla_ad_demo.launch.py +``` + +You can also spawn additional vehicles or pedestrians by executing the following command in another terminal: + +```sh +cd /PythonAPI/examples/ + +python3 spawn_npc.py +``` + +#### Scenario execution + +To execute the demo with a predefined scenario, run the following command after you have started a CARLA server: + +```sh +# ROS1 +roslaunch carla_ad_demo carla_ad_demo_with_scenario.launch + +# ROS2 +ros2 launch carla_ad_demo carla_ad_demo_with_scenario.launch.py +``` + +Select the example scenario "FollowLeadingVehicle" within the RVIZ Carla Plugin and press "Execute". The ego vehicle gets repositioned and the scenario is processed. + +You can specify your own scenarios by publishing to `/carla/available_scenarios`. The [launchfile](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch) shows an example of how to do this: + +```launch + +``` + +--- + + + diff --git a/docs/carla_waypoint.md b/docs/carla_waypoint.md new file mode 100644 index 00000000..b0ee1e98 --- /dev/null +++ b/docs/carla_waypoint.md @@ -0,0 +1,69 @@ +# CARLA Waypoint Publisher + +The CARLA Waypoint Publisher makes waypoint calculations available to the ROS context and provides services to query CARLA waypoints. To find out more about waypoints, see the CARLA [documentation](https://carla.readthedocs.io/en/latest/core_map/#navigation-in-carla). + +- [__Before you begin__](#before-you-begin) +- [__Run the Waypoint Publisher__](#run-the-waypoint-publisher) + - [Set a goal](#set-a-goal) +- [__Using the Waypoint Publisher__](#using-the-waypoint-publisher) +- [__Publications and services__](#publications-and-services) + - [Publications](#publications) + - [Services](#services) +--- + +## Before you begin + +The Waypoint Publisher requires some functionality of the Python API that is not included in the Python `.egg` file. To include this functionality, extend your Python path with the following command: + +```sh +export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg:/PythonAPI/carla/ +``` + +--- + +## Run the Waypoint Publisher + +With a CARLA server running, execute the following command: + +```sh +# ROS 1 +roslaunch carla_waypoint_publisher carla_waypoint_publisher.launch + +# ROS 2 +ros2 launch carla_waypoint_publisher carla_waypoint_publisher.launch.py +``` + +### Set a goal + +If available a goal is read from the topic `/carla//goal`, otherwise a fixed spawn point is used. + +The preferred way of setting a goal is to click '2D Nav Goal` in RVIZ. + +![rviz_set_goal](images/rviz_set_start_goal.png) + +--- + +### Using the Waypoint Publisher + +The [CARLA AD demo](carla_ad_demo.md) uses the Waypoint Publisher to plan a route for the [CARLA AD agent](carla_ad_agent.md). See the CARLA AD demo [launchfile](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch) for an example on how it is used. + +--- + +## Publications and services + +#### Publications + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//waypoints` | [nav_msgs.Path](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | Publishes the calculated route | + +
+ +#### Services + +| Service | Type | Description | +|-------|------|-------------| +| `/carla_waypoint_publisher//get_waypoint` | [carla_waypoint_types.GetWaypoint](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_waypoint_types/srv/GetWaypoint.srv) | Get the waypoint for a specific location | +| `/carla_waypoint_publisher//get_actor_waypoint` | [carla_waypoint_types.GetActorWaypoint](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_waypoint_types/srv/GetActorWaypoint.srv) | Get the waypoint for an actor id | + +
diff --git a/mkdocs.yml b/mkdocs.yml index 6bdda69a..fa54b54c 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -12,9 +12,12 @@ nav: - Install ROS Bridge for ROS 2: 'ros_installation_ros2.md' - The ROS bridge package: 'run_ros.md' - ROS Bridge Packages: - - Carla Spawn Objects: 'carla_spawn_objects.md' - - Carla Manual Control: 'carla_manual_control.md' - - Carla Ackermann Control: 'carla_ackermann_control.md' + - CARLA Spawn Objects: 'carla_spawn_objects.md' + - CARLA Manual Control: 'carla_manual_control.md' + - CARLA Ackermann Control: 'carla_ackermann_control.md' + - CARLA Waypoint Publisher: 'carla_waypoint.md' + - CARLA AD Agent: 'carla_ad_agent.md' + - CARLA AD Demo: 'carla_ad_demo.md' - RVIZ Plugin: 'rviz_plugin.md' - RQT Plugin: 'rqt_plugin.md' - References: From 8737630ca7eb8d73ccb3a6d07bf3e367a6e83039 Mon Sep 17 00:00:00 2001 From: Bernd Gassmann Date: Mon, 8 Mar 2021 07:53:14 -0500 Subject: [PATCH 547/627] Fix RosVehicleControl.update_waypoints --- .../src/carla_ros_scenario_runner/ros_vehicle_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index c89f0b00..113d328e 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -117,7 +117,7 @@ def update_waypoints(self, waypoints, start_time=None): super(RosVehicleControl, self).update_waypoints(waypoints, start_time) self.node.loginfo("{}: Waypoints changed.".format(self._role_name)) path = Path() - path.header.stamp = ros_timestamp(sec=self.node.get_time, from_sec=True) + path.header.stamp = ros_timestamp(sec=self.node.get_time(), from_sec=True) path.header.frame_id = "map" for wpt in waypoints: print(wpt) From c3f510b0ce568c7678d0356f2d2a2138d30c5147 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 12:33:22 +0100 Subject: [PATCH 548/627] same ros1 behavior --- carla_spawn_objects/launch/carla_spawn_objects.launch.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/carla_spawn_objects/launch/carla_spawn_objects.launch.py b/carla_spawn_objects/launch/carla_spawn_objects.launch.py index 0778b1c2..9202acc8 100644 --- a/carla_spawn_objects/launch/carla_spawn_objects.launch.py +++ b/carla_spawn_objects/launch/carla_spawn_objects.launch.py @@ -3,13 +3,15 @@ import launch import launch_ros.actions +from ament_index_python.packages import get_package_share_directory def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( name='objects_definition_file', - default_value='' + default_value=get_package_share_directory( + 'carla_spawn_objects') + '/config/objects.json' ), launch.actions.DeclareLaunchArgument( name='spawn_point_ego_vehicle', From c38849b420eb391c90d8478480506648c087791f Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 13:25:09 +0100 Subject: [PATCH 549/627] added missing rviz configuration for ros2 --- .../config/carla_default_rviz2.cfg.rviz | 232 ++++++++++++++++++ .../carla_ros_bridge_with_rviz.launch.py | 3 +- carla_ros_bridge/setup.py | 1 + .../launch/carla_spawn_objects.launch.py | 4 +- 4 files changed, 237 insertions(+), 3 deletions(-) create mode 100644 carla_ros_bridge/config/carla_default_rviz2.cfg.rviz diff --git a/carla_ros_bridge/config/carla_default_rviz2.cfg.rviz b/carla_ros_bridge/config/carla_default_rviz2.cfg.rviz new file mode 100644 index 00000000..e2ee58c4 --- /dev/null +++ b/carla_ros_bridge/config/carla_default_rviz2.cfg.rviz @@ -0,0 +1,232 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 905 + - Class: rviz_common/Selection + Name: Selection + - Class: rviz_common/Tool Properties + Expanded: + - /2D Goal Pose1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: RGB Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/rgb_front/image + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: DVS Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/dvs_front/image + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Depth Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/depth_front/image + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Semantic Segmentation Camera + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/semantic_segmentation_front/image + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0.9790723323822021 + Min Color: 0; 0; 0 + Min Intensity: 0.8188661932945251 + Name: Lidar + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.05000000074505806 + Style: Squares + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/ego_vehicle/lidar + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: MarkerArray + Namespaces: + "": true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/markers + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + - Class: rviz_default_plugins/FocusCamera + - Class: rviz_default_plugins/Measure + Line color: 128; 128; 0 + - Class: rviz_default_plugins/SetInitialPose + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /initialpose + - Class: rviz_default_plugins/SetGoal + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /goal_pose + - Class: rviz_default_plugins/PublishPoint + Single click: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /clicked_point + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/ThirdPersonFollower + Distance: 29.307788848876953 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.0803985446691513 + Target Frame: ego_vehicle + Value: ThirdPersonFollower (rviz_default_plugins) + Yaw: 3.165407180786133 + Saved: ~ +Window Geometry: + DVS Camera: + collapsed: false + Depth Camera: + collapsed: false + Displays: + collapsed: false + Height: 1163 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000023800000431fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000014005200470042002000430061006d006500720061010000003d000001f10000002800fffffffb00000014004400560053002000430061006d0065007200610100000234000000cc0000002800fffffffb0000001800440065007000740068002000430061006d00650072006101000003060000008f0000002800fffffffb0000003800530065006d0061006e0074006900630020005300650067006d0065006e0074006100740069006f006e002000430061006d006500720061010000039b000000d30000002800ffffff000000010000019500000431fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fc0000003d00000431000000e60100001cfa000000000100000002fb000000100044006900730070006c0061007900730100000000ffffffff0000015600fffffffb0000000a00560069006500770073010000062a000001560000010000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000003a70000043100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + RGB Camera: + collapsed: false + Selection: + collapsed: false + Semantic Segmentation Camera: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1920 + X: 1920 + Y: 0 diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py index 9f88c44b..01629a5d 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py @@ -10,7 +10,8 @@ def generate_launch_description(): launch_ros.actions.Node( package='rviz2', executable='rviz2', - name='rviz2' + name='rviz2', + arguments=['-d', os.path.join(get_package_share_directory('carla_ros_bridge'), 'config', 'carla_default_rviz2.cfg.rviz')] ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index d107c657..7ce813a5 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -23,6 +23,7 @@ packages=[package_name], data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), + ('share/' + package_name + '/config', ['config/carla_default_rviz2.cfg.rviz']), (os.path.join('share', package_name), glob('launch/*.launch.py')), (os.path.join('share', package_name + '/test'), glob('test/test_objects.json'))], install_requires=['setuptools'], diff --git a/carla_spawn_objects/launch/carla_spawn_objects.launch.py b/carla_spawn_objects/launch/carla_spawn_objects.launch.py index 9202acc8..ba878484 100644 --- a/carla_spawn_objects/launch/carla_spawn_objects.launch.py +++ b/carla_spawn_objects/launch/carla_spawn_objects.launch.py @@ -10,8 +10,8 @@ def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( name='objects_definition_file', - default_value=get_package_share_directory( - 'carla_spawn_objects') + '/config/objects.json' + default_value=os.path.join(get_package_share_directory( + 'carla_spawn_objects'), 'config', 'objects.json') ), launch.actions.DeclareLaunchArgument( name='spawn_point_ego_vehicle', From 9593ae4aa1fdc2f0c88485639f6e79c5405088af Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 15:16:47 +0100 Subject: [PATCH 550/627] removed carla ros bridge with rviz example --- carla_ros_bridge/CMakeLists.txt | 2 - .../config/carla_default_rviz.cfg.rviz | 223 ----------------- .../config/carla_default_rviz2.cfg.rviz | 232 ------------------ .../launch/carla_ros_bridge_with_rviz.launch | 4 - .../carla_ros_bridge_with_rviz.launch.py | 27 -- carla_ros_bridge/setup.py | 1 - 6 files changed, 489 deletions(-) delete mode 100644 carla_ros_bridge/config/carla_default_rviz.cfg.rviz delete mode 100644 carla_ros_bridge/config/carla_default_rviz2.cfg.rviz delete mode 100644 carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch delete mode 100644 carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 30ad3e11..9d330e47 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -26,8 +26,6 @@ if(${ROS_VERSION} EQUAL 1) install(FILES test/ros_bridge_client.test DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) - install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) - install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch) diff --git a/carla_ros_bridge/config/carla_default_rviz.cfg.rviz b/carla_ros_bridge/config/carla_default_rviz.cfg.rviz deleted file mode 100644 index 3671fe6d..00000000 --- a/carla_ros_bridge/config/carla_default_rviz.cfg.rviz +++ /dev/null @@ -1,223 +0,0 @@ -Panels: - - Class: rviz/Displays - Help Height: 75 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 - - /Grid1 - Splitter Ratio: 0.6000000238418579 - Tree Height: 366 - - Class: rviz/Selection - Name: Selection - - Class: rviz/Tool Properties - Expanded: - - /2D Pose Estimate1 - - /2D Nav Goal1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: rviz/Time - Experimental: false - Name: Time - SyncMode: 0 - SyncSource: PointCloud2 - - Class: rviz/Displays - Help Height: 75 - Name: Displays - Property Tree Widget: - Expanded: - - /PointCloud21 - Splitter Ratio: 0.5 - Tree Height: 818 -Preferences: - PromptSaveOnExit: true -Toolbars: - toolButtonStyle: 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: ego_vehicle - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /carla/ego_vehicle/rgb_front/image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: RGB Camera - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /carla/ego_vehicle/dvs_front/image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: DVS Camera - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /carla/ego_vehicle/depth_front/image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Depth Camera - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Class: rviz/Image - Enabled: true - Image Topic: /carla/ego_vehicle/semantic_segmentation_front/image - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Semantic Segmentation Camera - Normalize Range: true - Queue Size: 2 - Transport Hint: raw - Unreliable: false - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 0.9799321889877319 - Min Color: 0; 0; 0 - Min Intensity: 0.8193743228912354 - Name: PointCloud2 - Position Transformer: XYZ - Queue Size: 10 - Selectable: true - Size (Pixels): 3 - Size (m): 0.05000000074505806 - Style: Squares - Topic: /carla/ego_vehicle/lidar - Unreliable: false - Use Fixed Frame: true - Use rainbow: true - Value: true - - Class: rviz/MarkerArray - Enabled: true - Marker Topic: /carla/markers - Name: Markers - Namespaces: - "": true - Queue Size: 100 - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Default Light: true - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz/Interact - Hide Inactive Objects: true - - Class: rviz/MoveCamera - - Class: rviz/Select - - Class: rviz/FocusCamera - - Class: rviz/Measure - - Class: rviz/SetInitialPose - Theta std deviation: 0.2617993950843811 - Topic: /initialpose - X std deviation: 0.5 - Y std deviation: 0.5 - - Class: rviz/SetGoal - Topic: /move_base_simple/goal - - Class: rviz/PublishPoint - Single click: true - Topic: /clicked_point - Value: true - Views: - Current: - Class: rviz/ThirdPersonFollower - Distance: 17.369640350341797 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: false - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.21539832651615143 - Target Frame: ego_vehicle - Value: ThirdPersonFollower (rviz) - Yaw: 3.180402994155884 - Saved: ~ -Window Geometry: - DVS Camera: - collapsed: false - Depth Camera: - collapsed: false - Displays: - collapsed: false - Height: 1145 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 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 - RGB Camera: - collapsed: false - Selection: - collapsed: false - Semantic Segmentation Camera: - collapsed: false - Time: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1871 - X: 49 - Y: 27 diff --git a/carla_ros_bridge/config/carla_default_rviz2.cfg.rviz b/carla_ros_bridge/config/carla_default_rviz2.cfg.rviz deleted file mode 100644 index e2ee58c4..00000000 --- a/carla_ros_bridge/config/carla_default_rviz2.cfg.rviz +++ /dev/null @@ -1,232 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 - Splitter Ratio: 0.5 - Tree Height: 905 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Goal Pose1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: RGB Camera - Normalize Range: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /carla/ego_vehicle/rgb_front/image - Value: true - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: DVS Camera - Normalize Range: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /carla/ego_vehicle/dvs_front/image - Value: true - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Depth Camera - Normalize Range: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /carla/ego_vehicle/depth_front/image - Value: true - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Semantic Segmentation Camera - Normalize Range: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /carla/ego_vehicle/semantic_segmentation_front/image - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 0.9790723323822021 - Min Color: 0; 0; 0 - Min Intensity: 0.8188661932945251 - Name: Lidar - Position Transformer: XYZ - Selectable: true - Size (Pixels): 3 - Size (m): 0.05000000074505806 - Style: Squares - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /carla/ego_vehicle/lidar - Use Fixed Frame: true - Use rainbow: true - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MarkerArray - Namespaces: - "": true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /carla/markers - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /goal_pose - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/ThirdPersonFollower - Distance: 29.307788848876953 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: false - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.0803985446691513 - Target Frame: ego_vehicle - Value: ThirdPersonFollower (rviz_default_plugins) - Yaw: 3.165407180786133 - Saved: ~ -Window Geometry: - DVS Camera: - collapsed: false - Depth Camera: - collapsed: false - Displays: - collapsed: false - Height: 1163 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd00000004000000000000023800000431fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000014005200470042002000430061006d006500720061010000003d000001f10000002800fffffffb00000014004400560053002000430061006d0065007200610100000234000000cc0000002800fffffffb0000001800440065007000740068002000430061006d00650072006101000003060000008f0000002800fffffffb0000003800530065006d0061006e0074006900630020005300650067006d0065006e0074006100740069006f006e002000430061006d006500720061010000039b000000d30000002800ffffff000000010000019500000431fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fc0000003d00000431000000e60100001cfa000000000100000002fb000000100044006900730070006c0061007900730100000000ffffffff0000015600fffffffb0000000a00560069006500770073010000062a000001560000010000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000003a70000043100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - RGB Camera: - collapsed: false - Selection: - collapsed: false - Semantic Segmentation Camera: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1920 - X: 1920 - Y: 0 diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch deleted file mode 100644 index 46cf2322..00000000 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py deleted file mode 100644 index 01629a5d..00000000 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_rviz.launch.py +++ /dev/null @@ -1,27 +0,0 @@ -import os - -import launch -import launch_ros.actions -from ament_index_python.packages import get_package_share_directory - - -def generate_launch_description(): - ld = launch.LaunchDescription([ - launch_ros.actions.Node( - package='rviz2', - executable='rviz2', - name='rviz2', - arguments=['-d', os.path.join(get_package_share_directory('carla_ros_bridge'), 'config', 'carla_default_rviz2.cfg.rviz')] - ), - launch.actions.IncludeLaunchDescription( - launch.launch_description_sources.PythonLaunchDescriptionSource( - os.path.join(get_package_share_directory( - 'carla_ros_bridge'), 'carla_ros_bridge.launch.py') - ) - ) - ]) - return ld - - -if __name__ == '__main__': - generate_launch_description() diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index 7ce813a5..d107c657 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -23,7 +23,6 @@ packages=[package_name], data_files=[('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - ('share/' + package_name + '/config', ['config/carla_default_rviz2.cfg.rviz']), (os.path.join('share', package_name), glob('launch/*.launch.py')), (os.path.join('share', package_name + '/test'), glob('test/test_objects.json'))], install_requires=['setuptools'], From 49ced6e0ef4d01b2f27287e188fa84d74828192f Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 16:17:26 +0100 Subject: [PATCH 551/627] moved install_dependencies to root folder --- .github/workflows/ci.yml | 4 ++-- docker/Dockerfile | 11 +++++++---- ...install_dependencies.sh => install_dependencies.sh | 2 +- 3 files changed, 10 insertions(+), 7 deletions(-) rename packaging/install_dependencies.sh => install_dependencies.sh (95%) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 32af906f..b1a55e80 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -52,7 +52,7 @@ jobs: fetch-depth: 1 submodules: true - name: Setup - run: packaging/install_dependencies.sh + run: install_dependencies.sh - name: ROS2 Build, Test, Lint if: ${{ matrix.ros_version == 2 }} shell: bash @@ -108,6 +108,6 @@ jobs: fetch-depth: 1 submodules: true - name: Setup - run: packaging/install_dependencies.sh + run: install_dependencies.sh - name: Build Debian Package run: make deb diff --git a/docker/Dockerfile b/docker/Dockerfile index 35476386..81f439a2 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -16,13 +16,16 @@ WORKDIR /opt/carla-ros-bridge COPY --from=carla /home/carla/PythonAPI /opt/carla/PythonAPI -COPY . /opt/carla-ros-bridge/src/ - +COPY requirements.txt /opt/carla-ros-bridge +COPY install_dependencies.sh /opt/carla-ros-bridge RUN /bin/bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \ - bash /opt/carla-ros-bridge/src/packaging/install_dependencies.sh; \ + bash /opt/carla-ros-bridge/install_dependencies.sh; \ if [ "$CARLA_VERSION" = "0.9.10" ] || [ "$CARLA_VERSION" = "0.9.10.1" ]; then wget https://carla-releases.s3.eu-west-3.amazonaws.com/Backup/carla-0.9.10-py2.7-linux-x86_64.egg -P /opt/carla/PythonAPI/carla/dist; fi; \ echo "export PYTHONPATH=\$PYTHONPATH:/opt/carla/PythonAPI/carla/dist/$(ls /opt/carla/PythonAPI/carla/dist | grep py$ROS_PYTHON_VERSION.)" >> /opt/carla/setup.bash; \ - echo "export PYTHONPATH=\$PYTHONPATH:/opt/carla/PythonAPI/carla" >> /opt/carla/setup.bash; \ + echo "export PYTHONPATH=\$PYTHONPATH:/opt/carla/PythonAPI/carla" >> /opt/carla/setup.bash' + +COPY . /opt/carla-ros-bridge/src/ +RUN /bin/bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \ if [ "$ROS_VERSION" == "2" ]; then colcon build; else catkin_make install; fi' # replace entrypoint diff --git a/packaging/install_dependencies.sh b/install_dependencies.sh similarity index 95% rename from packaging/install_dependencies.sh rename to install_dependencies.sh index caad04e8..c85c605f 100755 --- a/packaging/install_dependencies.sh +++ b/install_dependencies.sh @@ -44,4 +44,4 @@ sudo apt-get install --no-install-recommends -y \ $ADDITIONAL_PACKAGES pip$PYTHON_SUFFIX install --upgrade pip$PYTHON_SUFFIX -pip$PYTHON_SUFFIX install -r $SCRIPT_DIR/../requirements.txt +pip$PYTHON_SUFFIX install -r $SCRIPT_DIR/requirements.txt From e3cce2711b4b4ce23798f0ecfd8b8caf3e7e4908 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 18:00:00 +0100 Subject: [PATCH 552/627] added CARLA_VERSION file --- carla_ros_bridge/CMakeLists.txt | 3 +++ carla_ros_bridge/setup.py | 2 ++ carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION | 1 + carla_ros_bridge/src/carla_ros_bridge/bridge.py | 4 +++- docker/build.sh | 6 ++++-- docker/run.sh | 2 +- 6 files changed, 14 insertions(+), 4 deletions(-) create mode 100644 carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index 30ad3e11..d27f3e5a 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -23,6 +23,9 @@ if(${ROS_VERSION} EQUAL 1) install(PROGRAMS src/carla_ros_bridge/bridge.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(FILES src/carla_ros_bridge/CARLA_VERSION + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(FILES test/ros_bridge_client.test DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/carla_ros_bridge/setup.py b/carla_ros_bridge/setup.py index d107c657..18517fd9 100644 --- a/carla_ros_bridge/setup.py +++ b/carla_ros_bridge/setup.py @@ -36,4 +36,6 @@ 'console_scripts': ['bridge = carla_ros_bridge.bridge:main'], }, package_dir={'': 'src'}, + package_data={'': ['CARLA_VERSION']}, + include_package_data=True ) diff --git a/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION b/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION new file mode 100644 index 00000000..56f31511 --- /dev/null +++ b/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION @@ -0,0 +1 @@ +0.9.10 diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 1065b89d..0a67121b 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -27,6 +27,7 @@ except ImportError: import Queue as queue +import os import sys from distutils.version import LooseVersion from threading import Thread, Lock, Event @@ -62,7 +63,8 @@ class CarlaRosBridge(CompatibleNode): Carla Ros bridge """ - CARLA_VERSION = "0.9.10" + with open(os.path.join(os.path.dirname(__file__), "CARLA_VERSION")) as f: + CARLA_VERSION = f.read()[:-1] # in synchronous mode, if synchronous_mode_wait_for_vehicle_control_command is True, # wait for this time until a next tick is triggered. diff --git a/docker/build.sh b/docker/build.sh index 45c73a80..8dddc0cd 100755 --- a/docker/build.sh +++ b/docker/build.sh @@ -1,7 +1,9 @@ #!/bin/sh +SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" + ROS_DISTRO="foxy" -CARLA_VERSION="0.9.10" +CARLA_VERSION=$(cat ${SCRIPT_DIR}/../carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION) while getopts r:c: flag do @@ -14,6 +16,6 @@ done docker build \ -t carla-ros-bridge:$ROS_DISTRO \ - -f Dockerfile ./.. \ + -f Dockerfile ${SCRIPT_DIR}/.. \ --build-arg ROS_DISTRO=$ROS_DISTRO \ --build-arg CARLA_VERSION=$CARLA_VERSION diff --git a/docker/run.sh b/docker/run.sh index 3dc19b68..8b8635a6 100755 --- a/docker/run.sh +++ b/docker/run.sh @@ -4,7 +4,7 @@ usage() { echo "Usage: $0 [-t ] [-i ]" 1>&2; exit 1; } # Defaults DOCKER_IMAGE_NAME="carla-ros-bridge" -TAG="latest" +TAG="foxy" while getopts ":ht:i:" opt; do case $opt in From f77f3071b600c2beff30d58696f11e296ffd9cec Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 18:15:41 +0100 Subject: [PATCH 553/627] removed trailing space --- carla_ros_bridge/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/CMakeLists.txt b/carla_ros_bridge/CMakeLists.txt index d27f3e5a..717056a4 100644 --- a/carla_ros_bridge/CMakeLists.txt +++ b/carla_ros_bridge/CMakeLists.txt @@ -23,7 +23,7 @@ if(${ROS_VERSION} EQUAL 1) install(PROGRAMS src/carla_ros_bridge/bridge.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - install(FILES src/carla_ros_bridge/CARLA_VERSION + install(FILES src/carla_ros_bridge/CARLA_VERSION DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(FILES test/ros_bridge_client.test From f5630f678fa24ce7b0e9cffdfbd27dbd253d03d5 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 8 Mar 2021 18:18:51 +0100 Subject: [PATCH 554/627] fixing ci --- .github/workflows/ci.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index b1a55e80..6c627397 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -52,7 +52,7 @@ jobs: fetch-depth: 1 submodules: true - name: Setup - run: install_dependencies.sh + run: ./install_dependencies.sh - name: ROS2 Build, Test, Lint if: ${{ matrix.ros_version == 2 }} shell: bash @@ -108,6 +108,6 @@ jobs: fetch-depth: 1 submodules: true - name: Setup - run: install_dependencies.sh + run: ./install_dependencies.sh - name: Build Debian Package run: make deb From e3edd213367e13d9e6a982ef82b93cfd22ad973f Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Tue, 9 Mar 2021 10:02:45 +0100 Subject: [PATCH 555/627] removed unnecessary privileged parameter --- docker/run.sh | 1 - 1 file changed, 1 deletion(-) diff --git a/docker/run.sh b/docker/run.sh index 8b8635a6..381e45ef 100755 --- a/docker/run.sh +++ b/docker/run.sh @@ -34,6 +34,5 @@ echo "Using $DOCKER_IMAGE_NAME:$TAG" docker run \ -it --rm \ - --privileged \ --net=host \ "$DOCKER_IMAGE_NAME:$TAG" "$@" From 257d36a9b7d39da1f906ffc4b10f223e1a3ecbca Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Tue, 9 Mar 2021 10:51:07 +0100 Subject: [PATCH 556/627] Replaced '.' with '/' in all message types for consistency. Added links to ROS package services --- docs/carla_ad_agent.md | 18 +- docs/carla_waypoint.md | 6 +- docs/ros_launchfiles.md | 392 ++++++++++++++++++++++++++++++++++++++++ docs/ros_sensors.md | 52 +++--- docs/run_ros.md | 14 +- docs/rviz_plugin.md | 20 +- 6 files changed, 446 insertions(+), 56 deletions(-) create mode 100644 docs/ros_launchfiles.md diff --git a/docs/carla_ad_agent.md b/docs/carla_ad_agent.md index 0cdc92de..50253772 100644 --- a/docs/carla_ad_agent.md +++ b/docs/carla_ad_agent.md @@ -21,14 +21,14 @@ The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedi | Topic | Type | Description | |-------|------|-------------| -| `/carla//waypoints` | [nav_msgs.Path](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | Route to follow | -| `/carla//target_speed` | [std_msgs.Float64](https://docs.ros.org/en/api/std_msgs/html/msg/Float64.html) | Target speed | -| `/carla//odometry` | [nav_msgs.Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Localization of ego vehicle | -| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) | Identify the carla actor id of the ego vehicle | -| `/carla//objects` | [derived_object_msgs.ObjectArray](https://docs.ros.org/en/melodic/api/derived_object_msgs/html/msg/ObjectArray.html) | Information about other actors | -| `/carla/actor_list` | [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) | Actor list | -| `/carla/world_info` | [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) | Selects mode for traffic lights (US- or European-style) | -| `/carla/traffic_lights/status` | [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) | Get the current state of the traffic lights | +| `/carla//waypoints` | [nav_msgs/Path](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | Route to follow | +| `/carla//target_speed` | [std_msgs/Float64](https://docs.ros.org/en/api/std_msgs/html/msg/Float64.html) | Target speed | +| `/carla//odometry` | [nav_msgs/Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Localization of ego vehicle | +| `/carla//vehicle_info` | [carla_msgs/CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) | Identify the carla actor id of the ego vehicle | +| `/carla//objects` | [derived_object_msgs/ObjectArray](https://docs.ros.org/en/melodic/api/derived_object_msgs/html/msg/ObjectArray.html) | Information about other actors | +| `/carla/actor_list` | [carla_msgs/CarlaActorList](ros_msgs.md#carlaactorlistmsg) | Actor list | +| `/carla/world_info` | [carla_msgs/CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) | Selects mode for traffic lights (US- or European-style) | +| `/carla/traffic_lights/status` | [carla_msgs/CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) | Get the current state of the traffic lights |
@@ -36,6 +36,6 @@ The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedi | Topic | Type | Description | |-------|------|-------------| -| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) | Vehicle control command | +| `/carla//vehicle_control_cmd` | [carla_msgs/CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) | Vehicle control command |
diff --git a/docs/carla_waypoint.md b/docs/carla_waypoint.md index b0ee1e98..e2457900 100644 --- a/docs/carla_waypoint.md +++ b/docs/carla_waypoint.md @@ -55,7 +55,7 @@ The [CARLA AD demo](carla_ad_demo.md) uses the Waypoint Publisher to plan a rout | Topic | Type | Description | |-------|------|-------------| -| `/carla//waypoints` | [nav_msgs.Path](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | Publishes the calculated route | +| `/carla//waypoints` | [nav_msgs/Path](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | Publishes the calculated route |
@@ -63,7 +63,7 @@ The [CARLA AD demo](carla_ad_demo.md) uses the Waypoint Publisher to plan a rout | Service | Type | Description | |-------|------|-------------| -| `/carla_waypoint_publisher//get_waypoint` | [carla_waypoint_types.GetWaypoint](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_waypoint_types/srv/GetWaypoint.srv) | Get the waypoint for a specific location | -| `/carla_waypoint_publisher//get_actor_waypoint` | [carla_waypoint_types.GetActorWaypoint](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_waypoint_types/srv/GetActorWaypoint.srv) | Get the waypoint for an actor id | +| `/carla_waypoint_publisher//get_waypoint` | [carla_waypoint_types/GetWaypoint](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_waypoint_types/srv/GetWaypoint.srv) | Get the waypoint for a specific location | +| `/carla_waypoint_publisher//get_actor_waypoint` | [carla_waypoint_types/GetActorWaypoint](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_waypoint_types/srv/GetActorWaypoint.srv) | Get the waypoint for an actor id |
diff --git a/docs/ros_launchfiles.md b/docs/ros_launchfiles.md new file mode 100644 index 00000000..84a9b7b9 --- /dev/null +++ b/docs/ros_launchfiles.md @@ -0,0 +1,392 @@ +# Launchfiles reference + +--- +## carla_ackermann_control.launch + +Creates a node to manage a vehicle using Ackermann controls instead of the CARLA control messages. The node reads the vehicle info from CARLA and uses it to define the controller. A simple Python PID is used to adjust acceleration/velocity. This is a Python dependency that can be easily installed with _pip_. +```sh +pip install --user simple-pid +``` +It is possible to modify the parameters in runtime via ROS dynamic reconfigure. Initial parameters can be set using a `settings.yaml`. The path to it depends on the bridge installation. + +* __Deb repository installation__, +`/opt/carla-ros-bridge/melodic/share/carla_ackermann_control/config/settings.yaml`. +* __Source repository installation__, +`/catkin_ws/src/ros-bridge/carla_ackermann_control/config/settings.yaml`. + + +

/carla_ackermann_control_ego_vehicle (Node)

+Converts [AckermannDrive messages](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html) to [CarlaEgoVehicleControl.msg](ros_msgs.md#carlaegovehiclecontrolmsg). Speed is in __m/s__, steering angle in __radians__ and refers to driving angle, not wheel angle. + +

Subscribed to:

+ +* /carla/ego_vehicle/ackermann_cmd — [ackermann_msgs.AckermannDrive](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html) +* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) +* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) + + +

Publishes in:

+ +* /carla/ego_vehicle/ackermann_control/parameter_descriptions — [dynamic_reconfigure/ConfigDescription](http://docs.ros.org/melodic/api/dynamic_reconfigure/html/msg/ConfigDescription.html) +* /carla/ego_vehicle/ackermann_control/control_info — [carla_ackermann_control.EgoVehicleControlInfo](ros_msgs.md#egovehiclecontrolinfomsg) +* /carla/ego_vehicle/ackermann_control/parameter_updates — [dynamic_reconfigure/Config](http://wiki.ros.org/dynamic_reconfigure) +* /carla/ego_vehicle/vehicle_control_cmd — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) + +--- +## carla_ego_vehicle.launch + +Spawns an ego vehicle (`role-name="ego_vehicle"`). The argument `sensor_definition_file` describes the sensors attached to the vehicle. It is the location of a __.json__ file. The format of this file is explained [here](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ego_vehicle). + +To spawn the vehicle at a specific location, publish in `/carla/ego_vehicle/initialpose`, or use __RVIZ__ and select a position with __2D Pose estimate__. + + +

carla_ego_vehicle_ego_vehicle (Node)

+Spawns an ego vehicle with sensors attached, and waits for world information. + +

Subscribed to:

+ +* /carla/ego_vehicle/initialpose — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html) +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) + +--- +## carla_example_ego_vehicle.launch +Based on carla_ego_vehicle.launch, spawns an ego vehicle (`role-name="ego_vehicle"`). The file `sensors.json` describes the sensors attached. The path to it depends on the bridge installation. + +* __Deb repository installation__, +`/opt/carla-ros-bridge/melodic/share/carla_ego_vehicle/config/sensors.json`. +* __Source repository installation__, +`/catkin_ws/src/ros-bridge/carla_ego_vehicle/config/sensors.json`. + + +

carla_ego_vehicle_ego_vehicle (Node)

+Spawns an ego vehicle with sensors attached and waits for world information. + +

Subscribed to:

+ +* /carla/ego_vehicle/initialpose — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html) +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) + +--- +## carla_infrastructure.launch +Spawns infrastructure sensors and requires the argument `infrastructure_sensor_definition_file` with the location of a __.json__ file describing these sensors. + + +

/carla_infrastructure (Node)

+Spawns the infrastructure sensors passed as arguments. + +

Subscribed to:

+ +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) + +--- +## carla_ros_bridge.launch +Creates a node with some basic communications between CARLA and ROS. + + +

carla_ros_bridge (Node)

+Publishes the data regarding the current state of the simulation. Reads the debug shapes being drawn. + +

Subscribed to:

+ +* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) + +

Publishes in:

+ +* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) +* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) +* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) +* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) + +--- +## carla_ros_bridge_with_ackermann_control.launch + +Launches two basic nodes. One retrieves simulation data, the other controls a vehicle using [AckermannDrive messages](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html). + + +

carla_ros_bridge (Node)

+Publishes data regarding the current state of the simulation. Reads the debug shapes being drawn. + +

Subscribed to:

+ +* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) + +

Publishes in:

+ +* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) +* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) +* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) +* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) + + +

/carla_ackermann_control_ego_vehicle (Node)

+Converts [AckermannDrive messages](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html) to [CarlaEgoVehicleControl.msg](ros_msgs.md#carlaegovehiclemsg). Speed is in __m/s__, steering angle is in __radians__ and refers to driving angle, not wheel angle. + +

Subscribed to:

+ +* /carla/ego_vehicle/ackermann_cmd — [ackermann_msgs.AckermannDrive](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html) +* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) +* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) + + +

Publishes in:

+ +* /carla/ego_vehicle/ackermann_control/parameter_descriptions — [dynamic_reconfigure/ConfigDescription](http://docs.ros.org/melodic/api/dynamic_reconfigure/html/msg/ConfigDescription.html) +* /carla/ego_vehicle/ackermann_control/control_info — [carla_ackermann_control.EgoVehicleControlInfo](ros_msgs.md#egovehiclecontrolinfomsg) +* /carla/ego_vehicle/ackermann_control/parameter_updates — [dynamic_reconfigure/Config](http://wiki.ros.org/dynamic_reconfigure) +* /carla/ego_vehicle/vehicle_control_cmd — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) + +--- +## carla_ros_bridge_with_example_ego_vehicle.launch + +Spawns an ego vehicle with sensors attached, and starts communications between CARLA and ROS. Both share current simulation state, sensor and ego vehicle data. The ego vehicle is set ready to be used in manual control. + + +

carla_ros_bridge (Node)

+In charge of the communications between CARLA and ROS. They share the current state of the simulation, traffic lights, vehicle controllers and sensor data. +

Subscribed to:

+ +* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) +* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) +* /carla/ego_vehicle/twist — [geometry_msgs.Twist](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/Twist.html) +* /carla/ego_vehicle/vehicle_control_cmd — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) +* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) +* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) + +

Publishes in:

+ +* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) +* /carla/ego_vehicle/camera/rgb/front/camera_info — [sensor_msgs.CameraInfo](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/CameraInfo.html) +* /carla/ego_vehicle/camera/rgb/front/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) +* /carla/ego_vehicle/camera/rgb/view/camera_info — [sensor_msgs.CameraInfo](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/CameraInfo.html) +* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) +* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) +* /carla/ego_vehicle/imu — [sensor_msgs.Imu](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Imu.html) +* /carla/ego_vehicle/lidar/lidar1/point_cloud — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html) +* /carla/ego_vehicle/objects — [derived_object_msgs.ObjectArray](http://docs.ros.org/kinetic/api/derived_object_msgs/html/msg/ObjectArray.html) +* /carla/ego_vehicle/odometry — [nav_msgs.Odometry](http://docs.ros.org/melodic/api/nav_msgs/html/msg/Odometry.html) +* /carla/ego_vehicle/radar/front/radar — [ainstein_radar_msgs.RadarTargetArray](http://wiki.ros.org/ainstein_radar_msgs) +* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) +* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) +* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) +* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) +* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) + + + +

/carla_manual_control_ego_vehicle (Node)

+Retrieves information from CARLA regarding the ego vehicle. Uses keyboard input to publish controller messages for the ego vehicle. The information retrieved includes static data, current state, sensor data, and simulation settings. + +

Subscribed to:

+ +* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) +* /carla/ego_vehicle/collision — [carla_msgs.CarlaCollisionEvent](ros_msgs.md#carlacollisioneventmsg) +* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) +* /carla/ego_vehicle/lane_invasion — [carla_msgs.CarlaLaneInvasionEvent](ros_msgs.md#carlalaneinvasioneventmsg) +* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) +* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) +* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) +* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) + + +

Publishes in:

+ +* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) +* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) +* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) + + +

/carla_ego_vehicle_ego_vehicle (Node)

+Spawns an ego vehicle with sensors attached. Reads world information. + +

Subscribed to:

+ +* /carla/ego_vehicle/initialpose — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html) + +--- +## carla_ros_bridge_with_rviz.launch + +Starts communications between CARLA and ROS, and launches RVIZ to retrieve Lidar data. + +

carla_ros_bridge (Node)

+Shares information between CARLA and ROS regarding the current simulation state. + +

Subscribed to:

+ +* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) + +

Publishes in:

+ +* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) +* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) +* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) +* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) + + +

/rviz (Node)

+Runs an instance of RVIZ, and waits for Lidar data. + +

Subscribed to:

+ +* /carla/vehicle_marker — [visualization_msgs/Marker](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/Marker.html) +* /carla/vehicle_marker_array — [visualization_msgs/MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) +* /carla/ego_vehicle/lidar/front/point_cloud — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html) + + +--- +## carla_manual_control.launch + +A ROS version of the CARLA script `manual_control.py`. It has some prequisites. + +* __To display an image__, a camera with role-name `view` and resolution 800x600. +* __To display the position__, a gnss sensor with role-name `gnss1`. +* __To detect other sensor data__, the corresponding sensor. + + + +

/carla_manual_control_ego_vehicle (Node)

+Retrieves information from CARLA regarding the ego vehicle. Uses keyboard input to publish controller messages for the ego vehicle. The information retrieved includes static data, current state, sensor data, and simulation settings. + +

Subscribed to:

+ +* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) +* /carla/ego_vehicle/collision — [carla_msgs.CarlaCollisionEvent](ros_msgs.md#carlacollisioneventmsg) +* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) +* /carla/ego_vehicle/lane_invasion — [carla_msgs.CarlaLaneInvasionEvent](ros_msgs.md#carlalaneinvasioneventmsg) +* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) +* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) +* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) +* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) + + +

Publishes in:

+ +* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) +* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) +* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) + +--- +## carla_pcl_recorder.launch +Creates a pointcloud map for the current CARLA level. An autopilot ego vehicle roams around the map with a LIDAR sensor attached. + +The point clouds are saved in the `/tmp/pcl_capture` directory. Once the capture is done, the overall size can be reduced. + +```sh +#create one point cloud file +pcl_concatenate_points_pcd /tmp/pcl_capture/*.pcd + +#filter duplicates +pcl_voxel_grid -leaf 0.1,0.1,0.1 output.pcd map.pcd + +#verify the result +pcl_viewer map.pcd +``` + +The launch file requires some functionality that is not part of the python egg-file. The PYTHONPATH has to be extended. + +```sh +export PYTHONPATH=/PythonAPI/carla/dist/carla-.egg:/PythonAPI/carla/ +``` + + +

carla_ros_bridge (Node)

+In charge of most of the communications between CARLA and ROS. Both share the current state of the simulation, traffic lights, vehicle controllers and sensor data. + +

Subscribed to:

+ +* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) +* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) +* /carla/ego_vehicle/twist — [geometry_msgs.Twist](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/Twist.html) +* /carla/ego_vehicle/vehicle_control_cmd — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) +* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) +* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) + +

Publishes in:

+ +* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) +* /carla/ego_vehicle/camera/rgb/front/camera_info — [sensor_msgs.CameraInfo](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/CameraInfo.html) +* /carla/ego_vehicle/camera/rgb/front/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) +* /carla/ego_vehicle/camera/rgb/view/camera_info — [sensor_msgs.CameraInfo](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/CameraInfo.html) +* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) +* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) +* /carla/ego_vehicle/imu — [sensor_msgs.Imu](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Imu.html) +* /carla/ego_vehicle/lidar/lidar1/point_cloud — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html) +* /carla/ego_vehicle/objects — [derived_object_msgs.ObjectArray](http://docs.ros.org/kinetic/api/derived_object_msgs/html/msg/ObjectArray.html) +* /carla/ego_vehicle/odometry — [nav_msgs.Odometry](http://docs.ros.org/melodic/api/nav_msgs/html/msg/Odometry.html) +* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) +* /carla/ego_vehicle/radar/front/radar — [ainstein_radar_msgs.RadarTargetArray](http://wiki.ros.org/ainstein_radar_msgs) +* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) +* /carla/marker — [visualization_msgs.Marker](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/Marker.html) +* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) +* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) +* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) + + +

/carla_manual_control_ego_vehicle (Node)

+Retrieves information from CARLA regarding the ego vehicle. Uses keyboard input to publish controller messages for the ego vehicle. The information retrieved includes static data, current state, sensor data, and simulation settings. + +

Subscribed to:

+ +* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) +* /carla/ego_vehicle/collision — [carla_msgs.CarlaCollisionEvent](ros_msgs.md#carlacollisioneventmsg) +* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) +* /carla/ego_vehicle/lane_invasion — [carla_msgs.CarlaLaneInvasionEvent](ros_msgs.md#carlalaneinvasioneventmsg) +* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) +* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) +* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) +* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) + + +

Publishes in:

+ +* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) +* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) +* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) + + +

/carla_ego_vehicle_ego_vehicle (Node)

+Spawns an ego vehicle with sensors attached. Waits for world information. + +

Subscribed to:

+ +* /carla/ego_vehicle/initialpose — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html) + + +

/enable_autopilot_rostopic (Node)

+Changes between autopilot and manual control modes. + +

Publishes in:

+ +* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) + + + +

/pcl_recorder_node (Node)

+Receives the cloud point data. + +

Subscribed to:

+ +* /carla/ego_vehicle/lidar/lidar1/point_cloud — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html) + +--- +## carla_waypoint_publisher.launch + +Calculates a waypoint route for an ego vehicle. The route is published in `/carla//waypoints`. The goal is either read from the ROS topic `/carla//goal`, or a fixed spawnpoint is used. +The prefered way of setting a goal is to click __2D Nav Goal__ in RVIZ. + +The launch file requires some functionality that is not part of the python egg-file. The PYTHONPATH has to be extended. +```sh +export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ +``` + + +

/carla_waypoint_publisher (Node)

+Uses the current pose of the ego vehicle as starting point. If the vehicle is respawned or moved, the route is calculated again. + +

Subscribed to:

+ +* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) diff --git a/docs/ros_sensors.md b/docs/ros_sensors.md index 7bb44123..f3c3fd47 100644 --- a/docs/ros_sensors.md +++ b/docs/ros_sensors.md @@ -8,72 +8,72 @@ | Topic | Type | |-------|------| -| `/carla/[]//image` | [sensor_msgs.Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | -| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | +| `/carla/[]//image` | [sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs/CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | ###### Depth camera | Topic | Type | |-------|------| -| `/carla/[]//image` | [sensor_msgs.Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | -| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | +| `/carla/[]//image` | [sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs/CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | ###### Semantic segmentation camera | Topic | Type | |-------|------| -| `/carla/[]//image` | [sensor_msgs.Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | -| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | +| `/carla/[]//image` | [sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs/CameraInfo](http://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | ###### DVS camera | Topic | Type | |-------|------| -| `/carla/[]//events` | [sensor_msgs.PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | -| `/carla/[]//image` | [sensor_msgs.Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | -| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | +| `/carla/[]//events` | [sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]//image` | [sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html) | +| `/carla/[]//camera_info` | [sensor_msgs/CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html) | ###### Lidar | Topic | Type | |-------|------| -| `/carla/[]/` | [sensor_msgs.PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]/` | [sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | ###### Semantic lidar | Topic | Type | |-------|------| -| `/carla/[]/` | [sensor_msgs.PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]/` | [sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | ###### Radar | Topic | Type | |-------|------| -| `/carla/[]/` | [sensor_msgs.PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | +| `/carla/[]/` | [sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | ###### IMU | Topic | Type | |-------|------| -| `/carla/[]/` | [sensor_msgs.Imu](https://docs.ros.org/en/api/sensor_msgs/html/msg/Imu.html) | +| `/carla/[]/` | [sensor_msgs/Imu](https://docs.ros.org/en/api/sensor_msgs/html/msg/Imu.html) | ###### GNSS | Topic | Type | |-------|------| -| `/carla/[]/` | [sensor_msgs.NavSatFix](https://docs.ros.org/en/api/sensor_msgs/html/msg/NavSatFix.html) | +| `/carla/[]/` | [sensor_msgs/NavSatFix](https://docs.ros.org/en/api/sensor_msgs/html/msg/NavSatFix.html) | ###### Collision Sensor | Topic | Type | |-------|------| -| `/carla/[]/` | [carla_msgs.CarlaCollisionEvent](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaCollisionEvent.msg) | +| `/carla/[]/` | [carla_msgs/CarlaCollisionEvent](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaCollisionEvent.msg) | ###### Lane Invasion Sensor | Topic | Type | |-------|------| -| `/carla/[]/` | [carla_msgs.CarlaLaneInvasionEvent](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaLaneInvasionEvent.msg) | +| `/carla/[]/` | [carla_msgs/CarlaLaneInvasionEvent](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaLaneInvasionEvent.msg) | Pseudo sensors @@ -89,44 +89,44 @@ Note: Sensors publish the tf data when the measurement is done. The child_frame_ | Topic | Type | Description | |-------|------|-------------| -| `/carla//` | [nav_msgs.Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Odometry of the parent actor. | +| `/carla//` | [nav_msgs/Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Odometry of the parent actor. | ###### Speedometer Sensor | Topic | Type | Description | |-------|------|-------------| -| `/carla//` | [std_msgs.Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html) | Speed of the parent actor. Units: m/s. | +| `/carla//` | [std_msgs/Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html) | Speed of the parent actor. Units: m/s. | ###### Map Sensor | Topic | Type | Description | |-------|------|-------------| -| `/carla/[]/` | [std_msgs.String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html) | Provides the OpenDRIVE map as a string on a latched topic. | +| `/carla/[]/` | [std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html) | Provides the OpenDRIVE map as a string on a latched topic. | ###### Object Sensor | Topic | Type | Description | |-------|------|-------------| -| `/carla/[]/` | [derived_object_msgs.ObjectArray](https://docs.ros.org/en/melodic/api/derived_object_msgs/html/msg/ObjectArray.html) | Publishes all vehicles and walker. If attached to a parent, the parent is not contained. | +| `/carla/[]/` | [derived_object_msgs/ObjectArray](https://docs.ros.org/en/melodic/api/derived_object_msgs/html/msg/ObjectArray.html) | Publishes all vehicles and walker. If attached to a parent, the parent is not contained. | ###### Marker Sensor | Topic | Type | Description | |-------|------|-------------| -| `/carla/[]/` | [visualization_msgs.Marker](https://docs.ros.org/en/api/visualization_msgs/html/msg/Marker.html) | Visualization of vehicles and walkers | +| `/carla/[]/` | [visualization_msgs/Marker](https://docs.ros.org/en/api/visualization_msgs/html/msg/Marker.html) | Visualization of vehicles and walkers | ###### Traffic Lights Sensor | Topic | Type | Description | |-------|------|-------------| -| `/carla/[]//status` | [carla_msgs.CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaTrafficLightStatusList.msg) | List of all traffic lights with their status. | -| `/carla/[]//info` | [carla_msgs.CarlaTrafficLightInfoList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaTrafficLightInfoList.msg) | Static information for all traffic lights (e.g. position). | +| `/carla/[]//status` | [carla_msgs/CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaTrafficLightStatusList.msg) | List of all traffic lights with their status. | +| `/carla/[]//info` | [carla_msgs/CarlaTrafficLightInfoList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaTrafficLightInfoList.msg) | Static information for all traffic lights (e.g. position). | ###### Actor List Sensor | Topic | Type | Description | |-------|------|-------------| -| `/carla/[]/` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaActorList.msg) | List of all CARLA actors. | +| `/carla/[]/` | [carla_msgs/CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaActorList.msg) | List of all CARLA actors. | ###### Actor Control Sensor @@ -134,5 +134,5 @@ This pseudo-sensor allows to control the position and velocity of the actor it i | Topic | Type | Description | |-------|------|-------------| -| `/carla/[]//set_transform` | [geometry_msgs.Pose](https://docs.ros.org/en/api/geometry_msgs/html/msg/Pose.html) | Transform to apply to the sensor's parent. | -| `/carla/[]//set_target_velocity` | [geometry_msgs.Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | Velocity (angular and linear) to apply to the sensor's parent. | +| `/carla/[]//set_transform` | [geometry_msgs/Pose](https://docs.ros.org/en/api/geometry_msgs/html/msg/Pose.html) | Transform to apply to the sensor's parent. | +| `/carla/[]//set_target_velocity` | [geometry_msgs/Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | Velocity (angular and linear) to apply to the sensor's parent. | diff --git a/docs/run_ros.md b/docs/run_ros.md index a2c76d65..d2f4677d 100644 --- a/docs/run_ros.md +++ b/docs/run_ros.md @@ -137,8 +137,8 @@ It is possible to use [AckermannDrive](https://docs.ros.org/en/api/ackermann_msg | Topic | Type | Description | |-------|------|-------------| -| `/carla/debug_marker` | [visualization_msgs.MarkerArray](https://docs.ros.org/en/api/visualization_msgs/html/msg/MarkerArray.html) | Draws markers in the CARLA world. | -| `/carla/weather_control` | [carla_msgs.CarlaWeatherParameters](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaWeatherParameters.msg) | Set the CARLA weather parameters | +| `/carla/debug_marker` | [visualization_msgs/MarkerArray](https://docs.ros.org/en/api/visualization_msgs/html/msg/MarkerArray.html) | Draws markers in the CARLA world. | +| `/carla/weather_control` | [carla_msgs/CarlaWeatherParameters](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaWeatherParameters.msg) | Set the CARLA weather parameters | | `/clock` | [rosgraph_msgs/Clock](https://docs.ros.org/en/melodic/api/rosgraph_msgs/html/msg/Clock.html) | Publishes simulated time in ROS. |
@@ -147,7 +147,7 @@ It is possible to use [AckermannDrive](https://docs.ros.org/en/api/ackermann_msg | Topic | Type | Description | |-------|------|-------------| -| `/carla/status` | [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) | Read the current status of CARLA | +| `/carla/status` | [carla_msgs/CarlaStatus](ros_msgs.md#carlastatusmsg) | Read the current status of CARLA | | `/carla/world_info` | [carla_msgs/CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) | Information about the current CARLA map. | | `/clock` | [rosgraph_msgs/Clock](https://docs.ros.org/en/melodic/api/rosgraph_msgs/html/msg/Clock.html) | Publishes simulated time in ROS. | | `/rosout` | [rosgraph_msgs/Log](https://docs.ros.org/en/melodic/api/rosgraph_msgs/html/msg/Log.html) | ROS logging. | @@ -158,11 +158,9 @@ It is possible to use [AckermannDrive](https://docs.ros.org/en/api/ackermann_msg | Topic | Type | Description | |-------|------|-------------| -| `/carla/destroy_object` | [](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/DestroyObject.srv) | Destroys an object | -| `/carla/get_blueprints` | [](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/GetBlueprints.srv) | Gets blueprints | -| `/carla/spawn_object` | [](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/SpawnObject.srv) | Spawn an object | -| `/carla_ros_bridge/get_loggers` | []() | | -| `/carla_ros_bridge/set_logger_level` | []() | | +| `/carla/destroy_object` | [carla_msgs/DestroyObject.srv](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/DestroyObject.srv) | Destroys an object | +| `/carla/get_blueprints` | [carla_msgs/GetBlueprints.srv](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/GetBlueprints.srv) | Gets blueprints | +| `/carla/spawn_object` | [carla_msgs/SpawnObject.srv](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/SpawnObject.srv) | Spawn an object | --- diff --git a/docs/rviz_plugin.md b/docs/rviz_plugin.md index 5e96c6f2..8d318a6d 100644 --- a/docs/rviz_plugin.md +++ b/docs/rviz_plugin.md @@ -66,11 +66,11 @@ __3.__ Control the ego vehicle with the `carla_manual_control` package (press `B | Topic | Type | Description | |-------|------|-------------| -| `/carla/status` | [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) | Read the current status of CARLA | -| `/carla/ego_vehicle/vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) | Display the current state of the ego vehicle | -| `/carla/ego_vehicle/odometry` | [nav_msgs.Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Display the current pose of the ego vehicle | -| `/scenario_runner/status` | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](ros_msgs.md#carlascenariorunnerstatusmsg) | Visualize the scenario runner status | -| `/carla/available_scenarios` | [carla_ros_scenario_runner_types.CarlaScenarioList](ros_msgs.md#carlascenariolistmsg) | Provides a list of scenarios to execute (disabled in combo box)| +| `/carla/status` | [carla_msgs/CarlaStatus](ros_msgs.md#carlastatusmsg) | Read the current status of CARLA | +| `/carla/ego_vehicle/vehicle_status` | [carla_msgs/CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) | Display the current state of the ego vehicle | +| `/carla/ego_vehicle/odometry` | [nav_msgs/Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Display the current pose of the ego vehicle | +| `/scenario_runner/status` | [carla_ros_scenario_runner_types/CarlaScenarioRunnerStatus](ros_msgs.md#carlascenariorunnerstatusmsg) | Visualize the scenario runner status | +| `/carla/available_scenarios` | [carla_ros_scenario_runner_types/CarlaScenarioList](ros_msgs.md#carlascenariolistmsg) | Provides a list of scenarios to execute (disabled in combo box)|
@@ -78,10 +78,10 @@ __3.__ Control the ego vehicle with the `carla_manual_control` package (press `B | Topic | Type | Description | |-------|------|-------------| -| `/carla/control` | [carla_msgs.CarlaControl](ros_msgs.md#carlacontrolmsg) | Play/pause/step CARLA | -| `/carla/ego_vehicle/spectator_pose` | [geometry_msgs.PoseStamped](https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html) | Publish the current pose of the RVIZ camera view | -| `/carla/ego_vehicle/vehicle_control_manual_override` | [std_msgs.Bool](https://docs.ros.org/en/api/std_msgs/html/msg/Bool.html) | Enable/disable vehicle control override | -| `/carla/ego_vehicle/twist` | [geometry_msgs.Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | The twist command, created via mouse | +| `/carla/control` | [carla_msgs/CarlaControl](ros_msgs.md#carlacontrolmsg) | Play/pause/step CARLA | +| `/carla/ego_vehicle/spectator_pose` | [geometry_msgs/PoseStamped](https://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html) | Publish the current pose of the RVIZ camera view | +| `/carla/ego_vehicle/vehicle_control_manual_override` | [std_msgs/Bool](https://docs.ros.org/en/api/std_msgs/html/msg/Bool.html) | Enable/disable vehicle control override | +| `/carla/ego_vehicle/twist` | [geometry_msgs/Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | The twist command, created via mouse |
@@ -89,6 +89,6 @@ __3.__ Control the ego vehicle with the `carla_manual_control` package (press `B | Topic | Type | Description | |-------|------|-------------| -| `/scenario_runner/execute_scenario` | [carla_ros_scenario_runner_types.ExecuteScenario](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | Execute the selected scenario | +| `/scenario_runner/execute_scenario` | [carla_ros_scenario_runner_types/ExecuteScenario](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | Execute the selected scenario |
From 86ff23be8d080d5b1154411b7b667b3d4831d92a Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Tue, 9 Mar 2021 10:56:48 +0100 Subject: [PATCH 557/627] Added information about debug_marker potentially affecting sensor data --- docs/ros_packages.md | 44 -------------------------------------------- docs/run_ros.md | 4 ++++ 2 files changed, 4 insertions(+), 44 deletions(-) delete mode 100644 docs/ros_packages.md diff --git a/docs/ros_packages.md b/docs/ros_packages.md deleted file mode 100644 index 77edd0ee..00000000 --- a/docs/ros_packages.md +++ /dev/null @@ -1,44 +0,0 @@ -# ROS packages - -Here you will find information about the different ROS bridge packages to use with CARLA. - -- [__Carla Waypoint Publisher__](https://github.com/carla-simulator/ros-bridge/blob/master/carla_waypoint_publisher/README.md) - Provide routes and access to the Carla waypoint API -- [__Carla ROS Scenario Runner__](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_scenario_runner/README.md) - ROS node that wraps the functionality of the CARLA scenario runner to execute scenarios. - -- [__Carla AD Agent__](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ad_agent/README.md) - A basic AD agent, that follows a route, avoids collisions with other vehicles and stops on red traffic lights. - - - - -- [__Carla Walker Agent__](https://github.com/carla-simulator/ros-bridge/blob/master/carla_walker_agent/README.md) - A basic walker agent, that follows a route. - - ---- - - - -## [Carla Waypoint Publisher](https://github.com/carla-simulator/ros-bridge/blob/master/carla_waypoint_publisher/README.md) - - - ---- - -## [Carla ROS Scenario Runner](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_scenario_runner/README.md) - ---- - -## [Carla AD Demo and Agent](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ad_agent/README.md) - - - ---- - -## [Carla Walker Agent](https://github.com/carla-simulator/ros-bridge/blob/master/carla_walker_agent/README.md) - ---- - -# ---- - - ---- \ No newline at end of file diff --git a/docs/run_ros.md b/docs/run_ros.md index d2f4677d..0956d737 100644 --- a/docs/run_ros.md +++ b/docs/run_ros.md @@ -143,6 +143,10 @@ It is possible to use [AckermannDrive](https://docs.ros.org/en/api/ackermann_msg
+!!! Note + When using `debug_marker`, be aware that markers may affect the data published by sensors. Supported markers include: arrow (specified by two points), points, cube and line strip. +
+ #### Publications | Topic | Type | Description | From 439601aef72a60b35e1f61d6d4883f379dbf3420 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 9 Mar 2021 11:29:54 +0100 Subject: [PATCH 558/627] [ROS2] Default sync mode (#497) * sync mode is the default mode * removed sync mode parameter * using sync mode by default --- README.md | 17 +++++++++++++---- carla_ad_demo/launch/carla_ad_demo.launch | 1 - carla_ad_demo/launch/carla_ad_demo.launch.py | 1 - .../launch/carla_ad_demo_with_scenario.launch | 1 - .../carla_ad_demo_with_scenario.launch.py | 1 - carla_ros_bridge/launch/carla_ros_bridge.launch | 4 ++-- .../launch/carla_ros_bridge.launch.py | 4 ++-- ...a_ros_bridge_with_example_ego_vehicle.launch | 2 -- ...os_bridge_with_example_ego_vehicle.launch.py | 5 ----- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- 10 files changed, 18 insertions(+), 20 deletions(-) diff --git a/README.md b/README.md index d42851bc..e87c3a47 100644 --- a/README.md +++ b/README.md @@ -57,14 +57,23 @@ The bridge is able to load a CARLA map by setting the launch-file parameter ```t ### Mode -The bridge should only be used in CARLA synchronous mode. +The bridge operates by default in CARLA synchronous mode, waiting for all sensor data that is expected within the current frame to ensure reproducible results. The bridge should only be used in this mode. -CAUTION: Only the ros-bridge is allowed to tick. Other CARLA clients must passively wait. - -The bridge waits for all sensor data that is expected within the current frame to ensures reproducible results. +**CAUTION**: In synchronous mode, only one CARLA client is allowed to tick. The ROS bridge will by default be the only client allowed to tick the CARLA server unless passive mode is enabled. Enabling passive mode will make the ROS bridge step back and allow another client to tick the CARLA server. Additionally you might set `synchronous_mode_wait_for_vehicle_control_command` to `true` to wait for a vehicle control command before executing the next tick. +The usage of the asynchronous mode is discouraged. Users may enable this mode running the bridge in the following way: + +```sh +# ROS1 +roslaunch carla_ros_bridge carla_ros_bridge.launch synchronous_mode:=False + +# ROS2 +ros2 launch carla_ros_bridge carla_ros_bridge.launch.py synchronous_mode:=False +``` + + ###### Control Synchronous Mode It is possible to control the simulation execution: diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index b6233004..3a230af0 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -26,7 +26,6 @@ - diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index f536a496..3c39b824 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -81,7 +81,6 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'town': launch.substitutions.LaunchConfiguration('town'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'synchronous_mode': 'True', # only synchronous mode is supported 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') }.items() diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch index 1dffed44..b1ade608 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch @@ -26,7 +26,6 @@ - diff --git a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py index eedac67d..2c62407b 100644 --- a/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo_with_scenario.launch.py @@ -76,7 +76,6 @@ def generate_launch_description(): 'port': launch.substitutions.LaunchConfiguration('port'), 'town': launch.substitutions.LaunchConfiguration('town'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), - 'synchronous_mode': 'True', # only synchronous mode is supported 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') }.items() diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index 2b80665d..73298f95 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -12,8 +12,8 @@ expected data is received for all sensors --> - - + + diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch.py b/carla_ros_bridge/launch/carla_ros_bridge.launch.py index 9a8e9891..9d15118d 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch.py @@ -22,11 +22,11 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='synchronous_mode', - default_value='False' + default_value='True' ), launch.actions.DeclareLaunchArgument( name='synchronous_mode_wait_for_vehicle_control_command', - default_value='True' + default_value='False' ), launch.actions.DeclareLaunchArgument( name='fixed_delta_seconds', diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch index a1eb9ba5..3ce9dedb 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch @@ -17,7 +17,6 @@ - @@ -28,7 +27,6 @@ - diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py index ca07156d..d396a799 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py @@ -38,10 +38,6 @@ def generate_launch_description(): name='passive', default_value='False' ), - launch.actions.DeclareLaunchArgument( - name='synchronous_mode', - default_value='False' - ), launch.actions.DeclareLaunchArgument( name='synchronous_mode_wait_for_vehicle_control_command', default_value='False' @@ -61,7 +57,6 @@ def generate_launch_description(): 'town': launch.substitutions.LaunchConfiguration('town'), 'timeout': launch.substitutions.LaunchConfiguration('timeout'), 'passive': launch.substitutions.LaunchConfiguration('passive'), - 'synchronous_mode': launch.substitutions.LaunchConfiguration('synchronous_mode'), 'synchronous_mode_wait_for_vehicle_control_command': launch.substitutions.LaunchConfiguration('synchronous_mode_wait_for_vehicle_control_command'), 'fixed_delta_seconds': launch.substitutions.LaunchConfiguration('fixed_delta_seconds') }.items() diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 0a67121b..5cdaaae3 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -416,7 +416,7 @@ def main(args=None): parameters['port'] = carla_bridge.get_param('port', 2000) parameters['timeout'] = carla_bridge.get_param('timeout', 2) parameters['passive'] = carla_bridge.get_param('passive', False) - parameters['synchronous_mode'] = carla_bridge.get_param('synchronous_mode', False) + parameters['synchronous_mode'] = carla_bridge.get_param('synchronous_mode', True) parameters['synchronous_mode_wait_for_vehicle_control_command'] = carla_bridge.get_param( 'synchronous_mode_wait_for_vehicle_control_command', False) parameters['fixed_delta_seconds'] = carla_bridge.get_param('fixed_delta_seconds', From fcec787a6799ebfa17c8bba6227a3a0bf834c8d2 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Tue, 16 Mar 2021 17:27:25 +0100 Subject: [PATCH 559/627] Added links in each package to the associated GitHub repos --- docs/carla_ackermann_control.md | 2 +- docs/carla_ad_agent.md | 2 +- docs/carla_ad_demo.md | 2 +- docs/carla_manual_control.md | 2 +- docs/carla_spawn_objects.md | 2 +- docs/carla_waypoint.md | 2 +- docs/rqt_plugin.md | 2 +- docs/rviz_plugin.md | 2 +- 8 files changed, 8 insertions(+), 8 deletions(-) diff --git a/docs/carla_ackermann_control.md b/docs/carla_ackermann_control.md index 1ab8f130..d423dfcf 100644 --- a/docs/carla_ackermann_control.md +++ b/docs/carla_ackermann_control.md @@ -1,6 +1,6 @@ # Carla Ackermann Control -The `carla_ackermann_control` package is used to control a CARLA vehicle with [Ackermann messages][ackermanncontrolmsg]. The package converts the Ackermann messages into [CarlaEgoVehicleControl][carlaegovehiclecontrolmsg] messages. It reads vehicle information from CARLA and passes that information to a Python based PID controller called `simple-pid` to control the acceleration and velocity. +The [`carla_ackermann_control` package](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ackermann_control) is used to control a CARLA vehicle with [Ackermann messages][ackermanncontrolmsg]. The package converts the Ackermann messages into [CarlaEgoVehicleControl][carlaegovehiclecontrolmsg] messages. It reads vehicle information from CARLA and passes that information to a Python based PID controller called `simple-pid` to control the acceleration and velocity. [ackermanncontrolmsg]: https://docs.ros.org/en/api/ackermann_msgs/html/msg/AckermannDrive.html [carlaegovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#carlaegovehiclecontrolmsg diff --git a/docs/carla_ad_agent.md b/docs/carla_ad_agent.md index 50253772..525fcf88 100644 --- a/docs/carla_ad_agent.md +++ b/docs/carla_ad_agent.md @@ -1,6 +1,6 @@ # CARLA AD Agent -The CARLA AD agent is an AD agent that can follow a given route, avoids crashes with other vehicles and respects the state of traffic lights by accessing ground truth data. It is used by the [CARLA AD demo](carla_ad_demo.md) to provide an example of how the ROS bridge can be used. +The [CARLA AD agent](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ad_agent) is an AD agent that can follow a given route, avoids crashes with other vehicles and respects the state of traffic lights by accessing ground truth data. It is used by the [CARLA AD demo](carla_ad_demo.md) to provide an example of how the ROS bridge can be used. - [__Local Planner Node__](#local-planner-node) - [__Publications and subscriptions__](#publications-and-subscriptions) diff --git a/docs/carla_ad_demo.md b/docs/carla_ad_demo.md index e414c8f5..82e4cd6e 100644 --- a/docs/carla_ad_demo.md +++ b/docs/carla_ad_demo.md @@ -1,6 +1,6 @@ # CARLA AD Demo -The AD demo is an example package that provides everything needed to launch a CARLA ROS environment with an AD vehicle. +The [AD demo](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ad_demo) is an example package that provides everything needed to launch a CARLA ROS environment with an AD vehicle. - [__Before you begin__](#before-you-begin) - [__Run the demo__](#run-the-demo) diff --git a/docs/carla_manual_control.md b/docs/carla_manual_control.md index aa944b80..6d51859f 100644 --- a/docs/carla_manual_control.md +++ b/docs/carla_manual_control.md @@ -1,6 +1,6 @@ # Carla Manual Control -This package is a ROS only version of the [`manual_control.py`][manualcontrol] script that comes packaged with CARLA. All data is received via ROS topics. +The [CARLA manual control package](https://github.com/carla-simulator/ros-bridge/tree/master/carla_manual_control) is a ROS only version of the [`manual_control.py`][manualcontrol] script that comes packaged with CARLA. All data is received via ROS topics. [manualcontrol]: https://github.com/carla-simulator/carla/blob/master/PythonAPI/examples/manual_control.py diff --git a/docs/carla_spawn_objects.md b/docs/carla_spawn_objects.md index 4b7b7266..1b57bb1c 100644 --- a/docs/carla_spawn_objects.md +++ b/docs/carla_spawn_objects.md @@ -1,6 +1,6 @@ # Carla Spawn Objects -The `carla_spawn_objects` package is used to spawn actors (vehicles, sensors, walkers) and to attach sensors to them. +The [`carla_spawn_objects` package](https://github.com/carla-simulator/ros-bridge/tree/master/carla_spawn_objects) is used to spawn actors (vehicles, sensors, walkers) and to attach sensors to them. - [__Configuration and sensor setup__](#configuration-and-sensor-setup) - [Create the configuration](#create-the-configuration) diff --git a/docs/carla_waypoint.md b/docs/carla_waypoint.md index e2457900..550c5e82 100644 --- a/docs/carla_waypoint.md +++ b/docs/carla_waypoint.md @@ -1,6 +1,6 @@ # CARLA Waypoint Publisher -The CARLA Waypoint Publisher makes waypoint calculations available to the ROS context and provides services to query CARLA waypoints. To find out more about waypoints, see the CARLA [documentation](https://carla.readthedocs.io/en/latest/core_map/#navigation-in-carla). +The [CARLA Waypoint Publisher](https://github.com/carla-simulator/ros-bridge/tree/master/carla_waypoint_publisher) makes waypoint calculations available to the ROS context and provides services to query CARLA waypoints. To find out more about waypoints, see the CARLA [documentation](https://carla.readthedocs.io/en/latest/core_map/#navigation-in-carla). - [__Before you begin__](#before-you-begin) - [__Run the Waypoint Publisher__](#run-the-waypoint-publisher) diff --git a/docs/rqt_plugin.md b/docs/rqt_plugin.md index e80d0c14..d85e4ceb 100644 --- a/docs/rqt_plugin.md +++ b/docs/rqt_plugin.md @@ -1,6 +1,6 @@ # RQT Carla Plugin -The RQT plugin is a simple interface for pausing, playing and controlling the steps of a simulation. To use it, execute the following command with the ROS-bridge running in synchronous mode: +The [RQT plugin](https://github.com/carla-simulator/ros-bridge/tree/master/rqt_carla_control) is a simple interface for pausing, playing and controlling the steps of a simulation. To use it, execute the following command with the ROS-bridge running in synchronous mode: ``` rqt --standalone rqt_carla_control diff --git a/docs/rviz_plugin.md b/docs/rviz_plugin.md index 8d318a6d..1c02a9eb 100644 --- a/docs/rviz_plugin.md +++ b/docs/rviz_plugin.md @@ -1,6 +1,6 @@ # RVIZ Carla Plugin -The RVIZ plugin provides a visualization tool based on the [RVIZ](https://wiki.ros.org/rviz) ROS package. +The [RVIZ plugin](https://github.com/carla-simulator/ros-bridge/tree/master/rviz_carla_plugin) provides a visualization tool based on the [RVIZ](https://wiki.ros.org/rviz) ROS package. - [__Run ROS bridge with RVIZ__](#run-ros-bridge-with-rviz) - [__Features of the RVIZ plugin__](#features-of-the-rviz-plugin) From aa97d34614e3f1c92577fe33347dada7321958b2 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 17 Mar 2021 12:59:51 +0100 Subject: [PATCH 560/627] Added ROS scenario runner package docs --- docs/carla_ros_scenario_runner.md | 93 +++++++++++++++++++++++++++++++ mkdocs.yml | 1 + 2 files changed, 94 insertions(+) create mode 100644 docs/carla_ros_scenario_runner.md diff --git a/docs/carla_ros_scenario_runner.md b/docs/carla_ros_scenario_runner.md new file mode 100644 index 00000000..45c68248 --- /dev/null +++ b/docs/carla_ros_scenario_runner.md @@ -0,0 +1,93 @@ +# Carla ROS Scenario Runner + +The [CARLA ROS Scenario Runner package](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ros_scenario_runner) is a wrapper to execute [OpenScenarios](https://www.asam.net/standards/detail/openscenario/) with the CARLA [Scenario Runner](https://github.com/carla-simulator/scenario_runner) via ROS. + +- [__Before you begin__](#before-you-begin) +- [__Using ROS Scenario Runner__](#using-ros-scenario-runner) +- [__Run ROS Scenario Runner__](#run-ros-scenario-runner) +- [__Services and topics__](#services-and-topics) + - [Services](#services) + - [Topics](#topics) + +--- + +## Before you begin + +- Follow the Scenario Runner ["Getting started'](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) tutorial to install Scenario Runner. +- Install the Python module __Pexpect__: + +```shell +sudo apt install python-pexpect +``` +--- + +## Using ROS Scenario Runner + +The ROS Scenario Runer is best used from within the [`rviz_carla_plugin`](rviz_plugin.md). + +!!! Note + It is currently not supported to change the map. Each scenario will need to use the currently active map. + +An example scenario is found [here](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ad_demo/config/FollowLeadingVehicle.xosc). Of particular importance is the setup of the [ROS controller](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ad_demo/config/FollowLeadingVehicle.xosc#L78): + +```xml + + + + + + + +``` + +The above code example shows an instance of [`carla_ad_agent`](carla_ad_agent.md) being launched. Any additional `` should be appended as a ROS parameter (name:=value). + +--- + +## Run ROS Scenario Runner + +__1.__ Export the environment variables: + +```sh +export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ +``` + +__2.__ Run the ROS Scenario Runner package: + +```sh +# ROS 1 +roslaunch carla_ros_scenario_runner carla_ros_scenario_runner.launch scenario_runner_path:= + +# ROS 2 +ros2 launch carla_ros_scenario_runner carla_ros_scenario_runner.launch.py scenario_runner_path:= +``` + +__3.__ Run a scenario: + +```sh +# ROS 1 +rosservice call /scenario_runner/execute_scenario "{ 'scenario': { 'scenario_file': '' } }" + +# ROS 2 +ros2 service call /scenario_runner/execute_scenario carla_ros_scenario_runner_types/srv/ExecuteScenario "{ 'scenario': { 'scenario_file': '' } }" +``` + +--- + +## Services and topics + +### Services + +| Service | Type | Description | +|---------|------|-------------| +| `/scenario_runner/execute_scenario` | [`carla_ros_scenario_runner_types.ExecuteScenario`](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | Execute a scenario. If another scenario is currently running, it gets stopped. | + +
+ +### Topics + +| Topic | Type | Description | +|-------|------|-------------| +| `/scenario_runner/status` | [`carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus`](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | The current status of the scenario runner execution (used by the [rviz_carla_plugin](rviz_plugin.md)) | + +
diff --git a/mkdocs.yml b/mkdocs.yml index fa54b54c..4a8d183e 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -18,6 +18,7 @@ nav: - CARLA Waypoint Publisher: 'carla_waypoint.md' - CARLA AD Agent: 'carla_ad_agent.md' - CARLA AD Demo: 'carla_ad_demo.md' + - CARLA ROS Scenario Runner: 'carla_ros_scenario_runner.md' - RVIZ Plugin: 'rviz_plugin.md' - RQT Plugin: 'rqt_plugin.md' - References: From c89e0a64c0c0ce33107c29089d85f4d8c273ad35 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 17 Mar 2021 15:47:13 +0100 Subject: [PATCH 561/627] Added twist to control package docs --- docs/carla_twist_to_control.md | 22 ++++++++++++++++++++++ mkdocs.yml | 1 + 2 files changed, 23 insertions(+) create mode 100644 docs/carla_twist_to_control.md diff --git a/docs/carla_twist_to_control.md b/docs/carla_twist_to_control.md new file mode 100644 index 00000000..0c156f19 --- /dev/null +++ b/docs/carla_twist_to_control.md @@ -0,0 +1,22 @@ +# Carla Twist to Control + +The [`carla_twist_to_control` package](https://github.com/carla-simulator/ros-bridge/tree/master/carla_twist_to_control) converts a [geometry_msgs.Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) to [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg). + +## Subscriptions and publications + +### Subscriptions + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//vehicle_info` | [`carla_msgs.CarlaEgoVehicleInfo`](ros_msgs.md#carlaegovehicleinfomsg) | Ego vehicle info, to receive max steering angle. | +| `/carla//twist` | [`geometry_msgs.Twist`](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | Twist to convert. | + +
+ +### Publications + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//vehicle_control_cmd` | [`carla_msgs.CarlaEgoVehicleControl`](ros_msgs.md#carlaegovehiclecontrolmsg) | Converted vehicle control command. | + +
diff --git a/mkdocs.yml b/mkdocs.yml index 4a8d183e..4b1215e1 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -19,6 +19,7 @@ nav: - CARLA AD Agent: 'carla_ad_agent.md' - CARLA AD Demo: 'carla_ad_demo.md' - CARLA ROS Scenario Runner: 'carla_ros_scenario_runner.md' + - Carla Twist to Control: 'carla_twist_to_control.md' - RVIZ Plugin: 'rviz_plugin.md' - RQT Plugin: 'rqt_plugin.md' - References: From 85ae4e345431e35dfc70b6d94ffad3f51dad402f Mon Sep 17 00:00:00 2001 From: joel-mb Date: Mon, 22 Mar 2021 11:01:55 +0100 Subject: [PATCH 562/627] [ROS2] Fixed bug passive mode ang ego vehicle role names argument (#507) * subscribing again to ego vehicle topics in passive mode * fix bug not using ego vehicle role names arguments * removed unecessary comment --- .../launch/carla_ros_bridge.launch | 1 + .../launch/carla_ros_bridge.launch.py | 4 +- .../src/carla_ros_bridge/ego_vehicle.py | 40 +++++++++---------- 3 files changed, 22 insertions(+), 23 deletions(-) diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index 73298f95..b4f47fab 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -33,6 +33,7 @@ +
diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch.py b/carla_ros_bridge/launch/carla_ros_bridge.launch.py index 9d15118d..e1d4627a 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch.py @@ -37,7 +37,7 @@ def generate_launch_description(): default_value='Town01' ), launch.actions.DeclareLaunchArgument( - name='ego_vehicle_role_names', + name='ego_vehicle_role_name', default_value=["hero", "ego_vehicle", "hero0", "hero1", "hero2", "hero3", "hero4", "hero5", "hero6", "hero7", "hero8", "hero9"] ), @@ -77,7 +77,7 @@ def generate_launch_description(): 'town': launch.substitutions.LaunchConfiguration('town') }, { - 'ego_vehicle_role_name': launch.substitutions.LaunchConfiguration('ego_vehicle_role_names') + 'ego_vehicle_role_name': launch.substitutions.LaunchConfiguration('ego_vehicle_role_name') } ] ) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 2261c67e..1b7c801d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -70,27 +70,25 @@ def __init__(self, uid, name, parent, node, carla_actor, vehicle_control_applied "/vehicle_info", qos_profile=QoSProfile(depth=10, durability=latch_on)) - # only subscribe to control topics if passive mode is not activated - if not node.parameters["passive"]: - self.control_subscriber = node.create_subscriber( - CarlaEgoVehicleControl, - self.get_topic_prefix() + "/vehicle_control_cmd", - lambda data: self.control_command_updated(data, manual_override=False)) - - self.manual_control_subscriber = node.create_subscriber( - CarlaEgoVehicleControl, - self.get_topic_prefix() + "/vehicle_control_cmd_manual", - lambda data: self.control_command_updated(data, manual_override=True)) - - self.control_override_subscriber = node.create_subscriber( - Bool, - self.get_topic_prefix() + "/vehicle_control_manual_override", - self.control_command_override, QoSProfile(depth=1, durability=True)) - - self.enable_autopilot_subscriber = node.create_subscriber( - Bool, - self.get_topic_prefix() + "/enable_autopilot", - self.enable_autopilot_updated) + self.control_subscriber = node.create_subscriber( + CarlaEgoVehicleControl, + self.get_topic_prefix() + "/vehicle_control_cmd", + lambda data: self.control_command_updated(data, manual_override=False)) + + self.manual_control_subscriber = node.create_subscriber( + CarlaEgoVehicleControl, + self.get_topic_prefix() + "/vehicle_control_cmd_manual", + lambda data: self.control_command_updated(data, manual_override=True)) + + self.control_override_subscriber = node.create_subscriber( + Bool, + self.get_topic_prefix() + "/vehicle_control_manual_override", + self.control_command_override, QoSProfile(depth=1, durability=True)) + + self.enable_autopilot_subscriber = node.create_subscriber( + Bool, + self.get_topic_prefix() + "/enable_autopilot", + self.enable_autopilot_updated) def get_marker_color(self): """ From bb367ae80a3d2105df83c96231515f01e91028f1 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Mon, 22 Mar 2021 11:07:11 +0100 Subject: [PATCH 563/627] [ROS2] Updated installation process (#508) * updated installation process ros2 --- README.ros2.md | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/README.ros2.md b/README.ros2.md index e2f480d8..15c80f24 100644 --- a/README.ros2.md +++ b/README.ros2.md @@ -6,10 +6,16 @@ Currently supported: [ROS2 Foxy](https://index.ros.org/doc/ros2/Releases/Release Colcon and ROS2 Foxy need to be installed on your system. - git clone https://github.com/carla-simulator/ros-bridge.git - cd ros-bridge - git submodule update --init + #setup folder structure + mkdir -p ~/carla-ros-bridge && cd ~/carla-ros-bridge + git clone --recurse-submodules https://github.com/carla-simulator/ros-bridge.git src/ros-bridge source /opt/ros/foxy/setup.bash + + #install required ros-dependencies + rosdep update + rosdep install --from-paths src --ignore-src -r + + #build colcon build For more information about configuring a ROS2 environment see From b979bf04078016af0104aa9c33a39505d6b61f92 Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 22 Mar 2021 12:12:54 +0100 Subject: [PATCH 564/627] updated messages submodule --- carla_msgs | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_msgs b/carla_msgs index f75637ce..081fdcdc 160000 --- a/carla_msgs +++ b/carla_msgs @@ -1 +1 @@ -Subproject commit f75637ce83a0b4e8fbd9818980c9b11570ff477c +Subproject commit 081fdcdc8a4f8d4ce936b792c4ef13aba3fd7478 From 65dcdb23813804cb8ea787c704864da0d5e446de Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 23 Mar 2021 16:03:28 +0100 Subject: [PATCH 565/627] Increase CARLA version to 0.9.11 (#510) * increase carla version to 0.9.11 --- README.md | 2 +- README.ros.md | 7 +++++++ carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION | 2 +- 3 files changed, 9 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index e87c3a47..60a39ecc 100644 --- a/README.md +++ b/README.md @@ -9,7 +9,7 @@ This ROS package aims at providing a simple ROS/ROS2 bridge for CARLA simulator. ![rviz setup](./docs/images/ad_demo.png "AD Demo") -**This version requires CARLA 0.9.10** +**This version requires CARLA 0.9.11** ## Features diff --git a/README.ros.md b/README.ros.md index 92361a3f..840a2769 100644 --- a/README.ros.md +++ b/README.ros.md @@ -16,6 +16,13 @@ Then simply install the ROS bridge: This will install carla-ros-bridge in /opt/carla-ros-bridge +#### Note +Currently, the debian package is only available for ROS melodic. Please, follow the Developer intructions if you want to use any other supported distribution. + +To check the different bridge versions available in the apt repository run: + + apt-cache madison carla-ros-bridge + ### For Developers Create a catkin workspace and install carla_ros_bridge package diff --git a/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION b/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION index 56f31511..8225a4ba 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION +++ b/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION @@ -1 +1 @@ -0.9.10 +0.9.11 From 10698cf6c86d7d05267df2a606fc03ca0a8dcbf0 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 23 Mar 2021 16:15:48 +0100 Subject: [PATCH 566/627] DVS Camera and sync mode bug fixes (#509) * updated README * DVS camera is an event sensor * fix bug tf publication for event sensors * sensor tick attribute removed * Merge branch 'master' into joel-mb/dvs_camera_fix --- carla_ackermann_control/README.md | 11 +---------- carla_ros_bridge/src/carla_ros_bridge/camera.py | 8 +++++--- carla_ros_bridge/src/carla_ros_bridge/sensor.py | 6 +++--- carla_spawn_objects/config/objects.json | 15 ++++----------- 4 files changed, 13 insertions(+), 27 deletions(-) diff --git a/carla_ackermann_control/README.md b/carla_ackermann_control/README.md index 777cbb51..a6479089 100644 --- a/carla_ackermann_control/README.md +++ b/carla_ackermann_control/README.md @@ -10,20 +10,11 @@ ROS Node to convert [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html #install python simple-pid pip install --user simple-pid -### Using with ROS2 -There is currently no package release of _ackeramnn_msgs_ for ROS2 eloquent. A simple solution is to clone the source from github into your ros workspace. The following commands can be used: - - # In your ros workspace do: - git clone https://github.com/ros-drivers/ackermann_msgs.git - git fetch - git checkout ros2 - - ### Configuration Initial parameters can be set via [configuration file](config/settings.yaml). -It is possible to modify the parameters during runtime via ROS dynamic reconfigure. +In ROS1, it is possible to modify the parameters during runtime via the `dynamic reconfigure` package. ## Available Topics diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index bff237c2..e81d0730 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -33,7 +33,7 @@ class Camera(Sensor): # global cv bridge to convert image between opencv and ros cv_bridge = CvBridge() - def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode): # pylint: disable=too-many-arguments + def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, synchronous_mode, is_event_sensor=False): # pylint: disable=too-many-arguments """ Constructor @@ -56,7 +56,8 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, - synchronous_mode=synchronous_mode) + synchronous_mode=synchronous_mode, + is_event_sensor=is_event_sensor) if self.__class__.__name__ == "Camera": self.node.logwarn("Created Unsupported Camera Actor" @@ -368,7 +369,8 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy relative_spawn_pose=relative_spawn_pose, node=node, carla_actor=carla_actor, - synchronous_mode=synchronous_mode) + synchronous_mode=synchronous_mode, + is_event_sensor=True) self._dvs_events = None self.dvs_camera_publisher = node.new_publisher(PointCloud2, diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index c785fdd6..e6a58625 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -193,7 +193,7 @@ def sensor_data_updated(self, carla_sensor_data): raise NotImplementedError( "This function has to be implemented by the derived classes") - def _update_synchronous_event_sensor(self, frame): + def _update_synchronous_event_sensor(self, frame, timestamp): while True: try: carla_sensor_data = self.queue.get(block=False) @@ -205,7 +205,7 @@ def _update_synchronous_event_sensor(self, frame): self.node.logdebug("{}({}): process {}".format( self.__class__.__name__, self.get_id(), frame)) self.publish_tf(trans.carla_transform_to_ros_pose( - carla_sensor_data.transform), frame) + carla_sensor_data.transform), timestamp) self.sensor_data_updated(carla_sensor_data) except queue.Empty: return @@ -240,7 +240,7 @@ def _update_synchronous_sensor(self, frame, timestamp): def update(self, frame, timestamp): if self.synchronous_mode: if self.is_event_sensor: - self._update_synchronous_event_sensor(frame) + self._update_synchronous_event_sensor(frame, timestamp) else: self._update_synchronous_sensor(frame, timestamp) diff --git a/carla_spawn_objects/config/objects.json b/carla_spawn_objects/config/objects.json index 0588c5c0..4b87671c 100644 --- a/carla_spawn_objects/config/objects.json +++ b/carla_spawn_objects/config/objects.json @@ -32,8 +32,7 @@ "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "image_size_x": 800, "image_size_y": 600, - "fov": 90.0, - "sensor_tick": 0.05 + "fov": 90.0 }, { "type": "sensor.camera.rgb", @@ -42,7 +41,6 @@ "image_size_x": 800, "image_size_y": 600, "fov": 90.0, - "sensor_tick": 0.05, "attached_objects": [ { @@ -61,7 +59,6 @@ "upper_fov": 2.0, "lower_fov": -26.8, "rotation_frequency": 20, - "sensor_tick": 0.05, "noise_stddev": 0.0 }, { @@ -73,8 +70,7 @@ "points_per_second": 320000, "upper_fov": 2.0, "lower_fov": -26.8, - "rotation_frequency": 20, - "sensor_tick": 0.05 + "rotation_frequency": 20 }, { "type": "sensor.other.radar", @@ -91,8 +87,7 @@ "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "fov": 90.0, "image_size_x": 400, - "image_size_y": 70, - "sensor_tick": 0.05 + "image_size_y": 70 }, { "type": "sensor.camera.depth", @@ -100,8 +95,7 @@ "spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, "fov": 90.0, "image_size_x": 400, - "image_size_y": 70, - "sensor_tick": 0.05 + "image_size_y": 70 }, { "type": "sensor.camera.dvs", @@ -110,7 +104,6 @@ "fov": 90.0, "image_size_x": 400, "image_size_y": 70, - "sensor_tick": 0.05, "positive_threshold": 0.3, "negative_threshold": 0.3, "sigma_positive_threshold": 0.0, From 93df82e4b63b435e418112d3fd32d07d088f3614 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Thu, 25 Mar 2021 10:55:02 +0100 Subject: [PATCH 567/627] Removed reference to installing pid control as it will no longer be needed --- docs/carla_ackermann_control.md | 9 --------- 1 file changed, 9 deletions(-) diff --git a/docs/carla_ackermann_control.md b/docs/carla_ackermann_control.md index d423dfcf..b7981647 100644 --- a/docs/carla_ackermann_control.md +++ b/docs/carla_ackermann_control.md @@ -5,18 +5,9 @@ The [`carla_ackermann_control` package](https://github.com/carla-simulator/ros-b [ackermanncontrolmsg]: https://docs.ros.org/en/api/ackermann_msgs/html/msg/AckermannDrive.html [carlaegovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#carlaegovehiclecontrolmsg -- [__Install the PID controller library__](#install-the-pid-controller-library) - [__Configuration__](#configuration) - [__Available Topics__](#available-topics) - [__Testing control messages__](#testing-control-messages) ---- - -### Install the PID controller library - -Install the PID controller: -``` -python3 -m pip install simple-pid -``` --- From 379d554e7e63c46af50148f20b2c5e1c3adf488d Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Thu, 25 Mar 2021 13:40:40 +0100 Subject: [PATCH 568/627] Use markdown codeblocks to get syntax highliting in readmes --- README.ros.md | 97 ++++++++++++++++++++++++++++++-------------------- README.ros2.md | 54 ++++++++++++++++------------ 2 files changed, 89 insertions(+), 62 deletions(-) diff --git a/README.ros.md b/README.ros.md index 840a2769..66d98cd9 100644 --- a/README.ros.md +++ b/README.ros.md @@ -6,44 +6,53 @@ First add the apt repository: - sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 1AF1527DE64CB8D9 - sudo add-apt-repository "deb [arch=amd64] http://dist.carla.org/carla $(lsb_release -sc) main" +```shell +sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 1AF1527DE64CB8D9 +sudo add-apt-repository "deb [arch=amd64] http://dist.carla.org/carla $(lsb_release -sc) main" +``` Then simply install the ROS bridge: - sudo apt-get update - sudo apt-get install carla-ros-bridge +```shell +sudo apt-get update +sudo apt-get install carla-ros-bridge +``` -This will install carla-ros-bridge in /opt/carla-ros-bridge +This will install carla-ros-bridge in `/opt/carla-ros-bridge` #### Note -Currently, the debian package is only available for ROS melodic. Please, follow the Developer intructions if you want to use any other supported distribution. + +Currently, the debian package is only available for ROS melodic. Please, follow the Developer instructions if you want to use any other supported distribution. To check the different bridge versions available in the apt repository run: - apt-cache madison carla-ros-bridge +```shell +apt-cache madison carla-ros-bridge +``` ### For Developers - Create a catkin workspace and install carla_ros_bridge package +Create a catkin workspace and install carla_ros_bridge package - #setup folder structure - mkdir -p ~/carla-ros-bridge/catkin_ws/src - cd ~/carla-ros-bridge - git clone https://github.com/carla-simulator/ros-bridge.git - cd ros-bridge - git submodule update --init - cd ../catkin_ws/src - ln -s ../../ros-bridge - source /opt/ros//setup.bash - cd .. +```shell +# setup folder structure +mkdir -p ~/carla-ros-bridge/catkin_ws/src +cd ~/carla-ros-bridge +git clone https://github.com/carla-simulator/ros-bridge.git +cd ros-bridge +git submodule update --init +cd ../catkin_ws/src +ln -s ../../ros-bridge +source /opt/ros//setup.bash +cd .. - #install required ros-dependencies - rosdep update - rosdep install --from-paths src --ignore-src -r +# install required ros-dependencies +rosdep update +rosdep install --from-paths src --ignore-src -r - #build - catkin_make +# build +catkin build # alternatively catkin_make +``` For more information about configuring a ROS environment see @@ -52,34 +61,44 @@ For more information about configuring a ROS environment see First run the simulator (see carla documentation: ) - # run carla in background - SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl +```shell +# run carla in background +SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl - # Add the carla modules to your python environment - export CARLA_ROOT= - export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg +# Add the carla modules to your python environment +export CARLA_ROOT= +export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg +``` ### For Users - source /opt/carla-ros-bridge//setup.bash +```shell +source /opt/carla-ros-bridge//setup.bash +``` ### For Developers - source ~/carla-ros-bridge/catkin_ws/devel/setup.bash +```shell +source ~/carla-ros-bridge/catkin_ws/devel/setup.bash +``` Start the ros bridge (choose one option): - # Option 1: start the ros bridge - roslaunch carla_ros_bridge carla_ros_bridge.launch +```shell +# Option 1: start the ros bridge +roslaunch carla_ros_bridge carla_ros_bridge.launch - # Option 2: start the ros bridge together with an example ego vehicle - roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch +# Option 2: start the ros bridge together with an example ego vehicle +roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch +``` ## Testing To execute the tests, using catkin, use the following commands: - - # build - catkin_make -DCATKIN_ENABLE_TESTING=0 - # run - rostest carla_ros_bridge ros_bridge_client.test + +```shell +# build +catkin build -DCATKIN_ENABLE_TESTING=0 +# run +rostest carla_ros_bridge ros_bridge_client.test +``` diff --git a/README.ros2.md b/README.ros2.md index 15c80f24..b9adca9c 100644 --- a/README.ros2.md +++ b/README.ros2.md @@ -6,17 +6,19 @@ Currently supported: [ROS2 Foxy](https://index.ros.org/doc/ros2/Releases/Release Colcon and ROS2 Foxy need to be installed on your system. - #setup folder structure - mkdir -p ~/carla-ros-bridge && cd ~/carla-ros-bridge - git clone --recurse-submodules https://github.com/carla-simulator/ros-bridge.git src/ros-bridge - source /opt/ros/foxy/setup.bash +```shell +# setup folder structure +mkdir -p ~/carla-ros-bridge && cd ~/carla-ros-bridge +git clone --recurse-submodules https://github.com/carla-simulator/ros-bridge.git src/ros-bridge +source /opt/ros/foxy/setup.bash - #install required ros-dependencies - rosdep update - rosdep install --from-paths src --ignore-src -r +# install required ros-dependencies +rosdep update +rosdep install --from-paths src --ignore-src -r - #build - colcon build +# build +colcon build +``` For more information about configuring a ROS2 environment see @@ -25,28 +27,34 @@ For more information about configuring a ROS2 environment see First run the simulator (see CARLA documentation: ) - # run carla in background - SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl +```shell +# run carla in background +SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl - # Add the carla modules to your python environment - export CARLA_ROOT= - export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla +# Add the carla modules to your python environment +export CARLA_ROOT= +export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla - source ./install/setup.bash +source ./install/setup.bash +``` Start the ros bridge (choose one option): - # Option 1: start the ros bridge - ros2 launch carla_ros_bridge carla_ros_bridge.launch.py +```shell +# Option 1: start the ros bridge +ros2 launch carla_ros_bridge carla_ros_bridge.launch.py - # Option 2: start the ros bridge together with an example ego vehicle - ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py +# Option 2: start the ros bridge together with an example ego vehicle +ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py +``` ## Testing To execute the tests using colcon, use the following commands: - # build - colcon build --packages-up-to carla_ros_bridge - # run - launch_test carla_ros_bridge/test/ros_bridge_client_ros2_test.py +```shell +# build +colcon build --packages-up-to carla_ros_bridge +# run +launch_test carla_ros_bridge/test/ros_bridge_client_ros2_test.py +``` From 2773bb79058dd387281b4c383d5f6082724663e0 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Thu, 25 Mar 2021 13:41:02 +0100 Subject: [PATCH 569/627] fix typos and remove dplicate blank lines --- carla_ad_agent/README.md | 4 +-- carla_ad_demo/README.md | 12 +++------ carla_manual_control/README.md | 2 +- carla_ros_scenario_runner/README.md | 15 ++++------- carla_spawn_objects/README.md | 40 +++++++++++++++-------------- carla_twist_to_control/README.md | 1 - carla_waypoint_publisher/README.md | 5 ++-- pcl_recorder/README.md | 2 +- ros_compatibility/README.md | 5 ++-- rviz_carla_plugin/README.md | 3 --- 10 files changed, 38 insertions(+), 51 deletions(-) diff --git a/carla_ad_agent/README.md b/carla_ad_agent/README.md index e1fa08b9..be79391d 100644 --- a/carla_ad_agent/README.md +++ b/carla_ad_agent/README.md @@ -7,6 +7,7 @@ It avoids crashs with other vehicles and respects the state of the traffic light For a more comprehensive solution, have a look at [Autoware](https://www.autoware.ai/). ## Subscriptions + | Topic | Type | Description | | ---------------------------------- | ------------------- | --------------------------- | | `/carla//waypoints` | [nav_msgs.Path](http://docs.ros.org/api/nav_msgs/html/msg/Path.html) | Route to follow | @@ -29,8 +30,6 @@ For risk avoidance, more subscriptions are required: | ---------------------------------- | ------------------- | --------------------------- | | `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | Vehicle control command | - - ## Local Planner Node Internally, the CARLA AD Agent uses a separate node for [local planning](src/carla_ad_agent/local_planner.py). @@ -38,4 +37,3 @@ Internally, the CARLA AD Agent uses a separate node for [local planning](src/car This is currently optimized for `vehicle.tesla.model3`, as it does not have any gear shift delays. The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedia.org/wiki/Ziegler%E2%80%93Nichols_method). - diff --git a/carla_ad_demo/README.md b/carla_ad_demo/README.md index 75cae499..a2b62ae0 100644 --- a/carla_ad_demo/README.md +++ b/carla_ad_demo/README.md @@ -2,20 +2,18 @@ This meta package provides everything to launch a CARLA ROS environment with an AD vehicle. - ![CARLA AD Demo](../docs/images/ad_demo.png "AD Demo in Rviz") ## Startup export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ export SCENARIO_RUNNER_PATH= - + # ROS 1 roslaunch carla_ad_demo carla_ad_demo.launch - + # ROS 2 ros2 launch carla_ad_demo carla_ad_demo.launch.py - ### Modes @@ -35,16 +33,14 @@ If you prefer to execute a predefined scenario, launch: # ROS1 roslaunch carla_ad_demo carla_ad_demo_with_scenario.launch - + # ROS2 ros2 launch carla_ad_demo carla_ad_demo_with_scenario.launch.py - + Select to example scenario "FollowLeadingVehicle" within the RVIZ Carla Plugin and press "Execute". The ego vehicle gets repositioned and the scenario is processed. You can specify your own scenarios by publishing to `/carla/available_scenarios`. See the [launch file](launch/carla_ad_demo_with_scenario.launch) for an example. - ##### Troubleshooting - If the example scenario fails, please analyze the ros log and follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working standalone. - diff --git a/carla_manual_control/README.md b/carla_manual_control/README.md index 83807f3b..71c67ee6 100644 --- a/carla_manual_control/README.md +++ b/carla_manual_control/README.md @@ -3,7 +3,7 @@ The node `carla_manual_control` is a ROS-only version of the Carla `manual_control.py`. All data is received via ROS topics. -## Prerequistes +## Prerequisites To be able to use `carla_manual_control`, some sensors need to be attached to the ego vehicle: diff --git a/carla_ros_scenario_runner/README.md b/carla_ros_scenario_runner/README.md index 137dcda1..eb50be5f 100644 --- a/carla_ros_scenario_runner/README.md +++ b/carla_ros_scenario_runner/README.md @@ -16,7 +16,7 @@ Please have a look at the [example scenario](https://github.com/carla-simulator/ -By this section within the openscenario definition, an instance of `carla_ad_agent` is launched (i.e. `roslaunch ..` is executed). Any aditional `` is appened as ros parameter (name:=value). +By this section within the openscenario definition, an instance of `carla_ad_agent` is launched (i.e. `roslaunch ..` is executed). Any additional `` is appened as ros parameter (name:=value). ## Setup @@ -33,38 +33,33 @@ The environment variables are forwarded to scenario_runner, therefore set them t export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ ### Using ROS1 + To run the ROS node: roslaunch carla_ros_scenario_runner carla_ros_scenario_runner.launch scenario_runner_path:= -To run a scenario from commandline: +To run a scenario from command line: rosservice call /scenario_runner/execute_scenario "{ 'scenario': { 'scenario_file': '' } }" ### Using ROS2 + To run the ROS node: ros2 launch carla_ros_scenario_runner carla_ros_scenario_runner.launch.py scenario_runner_path:= -To run a scenario from commandline: +To run a scenario from command line: ros2 service call /scenario_runner/execute_scenario carla_ros_scenario_runner_types/srv/ExecuteScenario "{ 'scenario': { 'scenario_file': '' } }" - - ## Available services | Service | Description | Type | | ----------------------------------------------------------- | ----------- | -------------------------------------------------------------------- | | `/scenario_runner/execute_scenario` | Execute a scenario. If another scenario is currently running, it gets stopped. | [carla_ros_scenario_runner_types.ExecuteScenario](../carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | - ## Available topics - | Topic | Description | Type | | ------------------------------------- | ----------- | -------------------------------------------------------------------- | | `/scenario_runner/status` | The current status of the scenario runner execution (e.g. used by the [rviz_carla_plugin](../rviz_carla_plugin)) | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | - - - diff --git a/carla_spawn_objects/README.md b/carla_spawn_objects/README.md index 00602cdd..73c65fbb 100644 --- a/carla_spawn_objects/README.md +++ b/carla_spawn_objects/README.md @@ -30,25 +30,27 @@ Sensors, attached to vehicles or not, can be defined via a json file. `carla_spa The format is defined like that: - { "actors" = [ - { - "type": "", - "id": "", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - - }, - { - "type": "", - "id": "", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - "sensors": - [ - - ] - } - ... - ] - } +```json +{ "actors" = [ + { + "type": "", + "id": "", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + + }, + { + "type": "", + "id": "", + "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, + "sensors": + [ + + ] + } + ... + ] +} +``` Define sensors with their attributes as described in the Carla Documentation about [Cameras and Sensors](https://github.com/carla-simulator/carla/blob/master/Docs/cameras_and_sensors.md). diff --git a/carla_twist_to_control/README.md b/carla_twist_to_control/README.md index 81b6aa4e..298c9f0c 100644 --- a/carla_twist_to_control/README.md +++ b/carla_twist_to_control/README.md @@ -2,7 +2,6 @@ This node converts a [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) to [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) - ## Subscriptions | Topic | Type | Description | diff --git a/carla_waypoint_publisher/README.md b/carla_waypoint_publisher/README.md index a2b756dc..24190c98 100644 --- a/carla_waypoint_publisher/README.md +++ b/carla_waypoint_publisher/README.md @@ -21,9 +21,9 @@ To run it: ## Set a goal -The goal is either read from the ROS topic `/carla//goal`, if available, or a fixed spawnpoint is used. +The goal is either read from the ROS topic `/carla//goal`, if available, or a fixed spawn point is used. -The prefered way of setting a goal is to click '2D Nav Goal' in RVIZ. +The preferred way of setting a goal is to click '2D Nav Goal' in RVIZ. ![set goal](../docs/images/rviz_set_start_goal.png) @@ -35,7 +35,6 @@ The calculated route is published: | ------------------------------------- | -------------------------------------------------------------------- | | `/carla//waypoints` | [nav_msgs.Path](http://docs.ros.org/api/nav_msgs/html/msg/Path.html) | - ## Available services | Service | Description | Type | diff --git a/pcl_recorder/README.md b/pcl_recorder/README.md index 5334b7bd..a60ffee6 100644 --- a/pcl_recorder/README.md +++ b/pcl_recorder/README.md @@ -1,6 +1,6 @@ # Point Cloud Map Creation -Create pointcloud maps for Carla Levels. +Create point cloud maps for Carla Levels. The point clouds are created by driving around with an ego vehicle, using the autopilot functionality within the Carla PythonAPI. diff --git a/ros_compatibility/README.md b/ros_compatibility/README.md index eb2cc93a..276ed9bc 100644 --- a/ros_compatibility/README.md +++ b/ros_compatibility/README.md @@ -1,4 +1,5 @@ # ROS compatibility node + This acts as an interface over ROS1 and ROS2 to allow nodes to be used seamlessly with both versions. Depending on the environment variable `ROS_VERSION`, the same api will call either ROS1 or ROS2 functions. It is used by creating classes that inherit from the `CompatibleNode`. @@ -9,6 +10,6 @@ By default in ROS2, parameters need to be declared before being set or accessed, ## Services -In ROS2 services can be called asynchronously, this is not the case in ROS1. Consequently, the `call_service()` method of the ROS2 version waits for the server's response after calling it asynchronously, in order to mimic the ROS1 synchronous behaviour. +In ROS2 services can be called asynchronously, this is not the case in ROS1. Consequently, the `call_service()` method of the ROS2 version waits for the server's response after calling it asynchronously, in order to mimic the ROS1 synchronous behavior. -WARNING: While waiting for the response, the ROS2 `call_service()` methods spins the node. This can cause problems (erors or deadlocks) if another thread spins the same node in parallel. \ No newline at end of file +WARNING: While waiting for the response, the ROS2 `call_service()` methods spins the node. This can cause problems (errors or deadlocks) if another thread spins the same node in parallel. diff --git a/rviz_carla_plugin/README.md b/rviz_carla_plugin/README.md index 911b9816..80bd1692 100644 --- a/rviz_carla_plugin/README.md +++ b/rviz_carla_plugin/README.md @@ -27,13 +27,10 @@ By using the drive-widget from the [RVIZ Visualization Tutorials](https://github By using [carla_ros_scenario_runner](../carla_ros_scenario_runner), it is possible to trigger scenarios from within RVIZ. - ### Play/Pause the simulation (if started in synchronous mode) Similar to the [rqt CARLA plugin](../rqt_carla_plugin), it's possible to control the CARLA world, if synchronous mode is active. - - ## Topics ### Subscriptions From 53d87ba7c8c2cd8b0b1877f1b879adf5c27539d7 Mon Sep 17 00:00:00 2001 From: Markus Hofbauer Date: Thu, 25 Mar 2021 13:23:52 +0100 Subject: [PATCH 570/627] include submodules in clone instructions for ROS 1 --- README.ros.md | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/README.ros.md b/README.ros.md index 66d98cd9..2102b34b 100644 --- a/README.ros.md +++ b/README.ros.md @@ -36,15 +36,10 @@ Create a catkin workspace and install carla_ros_bridge package ```shell # setup folder structure -mkdir -p ~/carla-ros-bridge/catkin_ws/src -cd ~/carla-ros-bridge -git clone https://github.com/carla-simulator/ros-bridge.git -cd ros-bridge -git submodule update --init -cd ../catkin_ws/src -ln -s ../../ros-bridge +mkdir -p ~/carla-ros-bridge/catkin_ws/src && cd ~/carla-ros-bridge +git clone --recurse-submodules https://github.com/carla-simulator/ros-bridge.git catkin_ws/src/ros-bridge source /opt/ros//setup.bash -cd .. +cd catkin_ws # install required ros-dependencies rosdep update From ca6cc10a4bb31ac0ac3ff73a9a8dcb7a0c30671b Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Mon, 29 Mar 2021 11:08:12 +0200 Subject: [PATCH 571/627] fix camera transform --- .../src/carla_ros_bridge/camera.py | 26 +++++++++++++++++++ .../src/carla_ros_bridge/sensor.py | 6 ++++- 2 files changed, 31 insertions(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index e81d0730..1b5b7d9c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -13,6 +13,7 @@ import math import numpy +import transforms3d import os from cv_bridge import CvBridge from sensor_msgs.msg import CameraInfo, Image, PointCloud2, PointField @@ -120,6 +121,31 @@ def sensor_data_updated(self, carla_camera_data): self.camera_info_publisher.publish(cam_info) self.camera_image_publisher.publish(img_msg) + def get_ros_transform(self, pose, timestamp): + """ + Function (override) to modify the tf messages sent by this camera. + The camera transformation has to be altered to look at the same axis + as the opencv projection in order to get easy depth cloud for RGBD camera + :return: the filled tf message + :rtype: geometry_msgs.msg.TransformStamped + """ + tf_msg = super(Camera, self).get_ros_transform(pose, timestamp) + rotation = tf_msg.transform.rotation + + quat = [rotation.w, rotation.x, rotation.y, rotation.z] + quat_swap = transforms3d.quaternions.mat2quat(numpy.matrix( + [[0, 0, 1], + [-1, 0, 0], + [0, -1, 0]])) + quat = transforms3d.quaternions.qmult(quat, quat_swap) + + tf_msg.transform.rotation.w = quat[0] + tf_msg.transform.rotation.x = quat[1] + tf_msg.transform.rotation.y = quat[2] + tf_msg.transform.rotation.z = quat[3] + + return tf_msg + def get_ros_image(self, carla_camera_data): """ Function to transform the received carla camera data into a ROS image message diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index e6a58625..47334648 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -102,7 +102,7 @@ def __init__(self, # pylint: disable=too-many-arguments elif ROS_VERSION == 2: self._tf_broadcaster = tf2_ros.TransformBroadcaster(node) - def publish_tf(self, pose, timestamp): + def get_ros_transform(self, pose, timestamp): if self.synchronous_mode: if not self.relative_spawn_pose: self.node.logwarn("{}: No relative spawn pose defined".format(self.get_prefix())) @@ -132,6 +132,10 @@ def publish_tf(self, pose, timestamp): transform.transform.rotation.z = pose.orientation.z transform.transform.rotation.w = pose.orientation.w + return transform + + def publish_tf(self, pose, timestamp): + transform = self.get_ros_transform(pose, timestamp) try: self._tf_broadcaster.sendTransform(transform) except ROSException: From e68c6d2a9c2b16fd995610d92ebe26b59ba13893 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 16:27:54 +0200 Subject: [PATCH 572/627] Changed ROS API headings --- docs/carla_ackermann_control.md | 39 ++++++++++++++++++++----------- docs/carla_ad_agent.md | 4 ++-- docs/carla_ros_scenario_runner.md | 8 +++---- docs/carla_twist_to_control.md | 3 ++- docs/carla_waypoint.md | 4 ++-- docs/rviz_plugin.md | 4 ++-- 6 files changed, 37 insertions(+), 25 deletions(-) diff --git a/docs/carla_ackermann_control.md b/docs/carla_ackermann_control.md index b7981647..abe305b9 100644 --- a/docs/carla_ackermann_control.md +++ b/docs/carla_ackermann_control.md @@ -6,8 +6,10 @@ The [`carla_ackermann_control` package](https://github.com/carla-simulator/ros-b [carlaegovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#carlaegovehiclecontrolmsg - [__Configuration__](#configuration) -- [__Available Topics__](#available-topics) - [__Testing control messages__](#testing-control-messages) +- [__ROS API__](#ros-api) + - [Subscriptions](#subscriptions) + - [Publications](#publications) --- @@ -20,19 +22,6 @@ Parameters can be set both initially in a [configuration file][ackermanconfig] a --- -### Available topics - -|Topic|Type|Description| -|--|--|--| -|`/carla//ackermann_cmd` | [ackermann_msgs.AckermannDrive][ackermanncontrolmsg] | __Subscriber__ for steering commands | -| `/carla//ackermann_control/control_info` | [carla_ackermann_control.EgoVehicleControlInfo][egovehiclecontrolmsg] | The current values used within the controller (useful for debugging) | - -[egovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#egovehiclecontrolinfomsg - -
- ---- - ### Testing control messages Test the setup by sending commands to the car via the topic `/carla//ackermann_cmd`. For example, move an ego vehicle with the role name of `ego_vehicle` forward at a speed of 10 meters/sec by running this command: @@ -58,3 +47,25 @@ rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{st ros2 topic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 1.22, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10 ``` + +--- + +### ROS API + +#### Subscriptions + +|Topic|Type|Description| +|--|--|--| +|`/carla//ackermann_cmd` | [ackermann_msgs.AckermannDrive][ackermanncontrolmsg] | __Subscriber__ for steering commands | + +
+ +#### Publications + +|Topic|Type|Description| +|--|--|--| +| `/carla//ackermann_control/control_info` | [carla_ackermann_control.EgoVehicleControlInfo][egovehiclecontrolmsg] | The current values used within the controller (useful for debugging) | + +[egovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#egovehiclecontrolinfomsg + +
diff --git a/docs/carla_ad_agent.md b/docs/carla_ad_agent.md index 525fcf88..cd7d4993 100644 --- a/docs/carla_ad_agent.md +++ b/docs/carla_ad_agent.md @@ -3,7 +3,7 @@ The [CARLA AD agent](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ad_agent) is an AD agent that can follow a given route, avoids crashes with other vehicles and respects the state of traffic lights by accessing ground truth data. It is used by the [CARLA AD demo](carla_ad_demo.md) to provide an example of how the ROS bridge can be used. - [__Local Planner Node__](#local-planner-node) -- [__Publications and subscriptions__](#publications-and-subscriptions) +- [__ROS API__](#ros-api) - [Subscriptions](#subscriptions) - [Publications](#publications) @@ -15,7 +15,7 @@ Internally the CARLA AD Agent uses a separate node for [local planning](https:// The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedia.org/wiki/Ziegler%E2%80%93Nichols_method). -## Publications and subscriptions +## ROS API #### Subscriptions diff --git a/docs/carla_ros_scenario_runner.md b/docs/carla_ros_scenario_runner.md index 45c68248..9b4180af 100644 --- a/docs/carla_ros_scenario_runner.md +++ b/docs/carla_ros_scenario_runner.md @@ -5,9 +5,9 @@ The [CARLA ROS Scenario Runner package](https://github.com/carla-simulator/ros-b - [__Before you begin__](#before-you-begin) - [__Using ROS Scenario Runner__](#using-ros-scenario-runner) - [__Run ROS Scenario Runner__](#run-ros-scenario-runner) -- [__Services and topics__](#services-and-topics) +- [__ROS API__](#ros-api) - [Services](#services) - - [Topics](#topics) + - [Publications](#publications) --- @@ -74,7 +74,7 @@ ros2 service call /scenario_runner/execute_scenario carla_ros_scenario_runner_ty --- -## Services and topics +## ROS API ### Services @@ -84,7 +84,7 @@ ros2 service call /scenario_runner/execute_scenario carla_ros_scenario_runner_ty
-### Topics +### Publications | Topic | Type | Description | |-------|------|-------------| diff --git a/docs/carla_twist_to_control.md b/docs/carla_twist_to_control.md index 0c156f19..1bc8c097 100644 --- a/docs/carla_twist_to_control.md +++ b/docs/carla_twist_to_control.md @@ -2,7 +2,8 @@ The [`carla_twist_to_control` package](https://github.com/carla-simulator/ros-bridge/tree/master/carla_twist_to_control) converts a [geometry_msgs.Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) to [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg). -## Subscriptions and publications +--- +## ROS API ### Subscriptions diff --git a/docs/carla_waypoint.md b/docs/carla_waypoint.md index 550c5e82..9811700d 100644 --- a/docs/carla_waypoint.md +++ b/docs/carla_waypoint.md @@ -6,7 +6,7 @@ The [CARLA Waypoint Publisher](https://github.com/carla-simulator/ros-bridge/tre - [__Run the Waypoint Publisher__](#run-the-waypoint-publisher) - [Set a goal](#set-a-goal) - [__Using the Waypoint Publisher__](#using-the-waypoint-publisher) -- [__Publications and services__](#publications-and-services) +- [__ROS API__](#ros-api) - [Publications](#publications) - [Services](#services) --- @@ -49,7 +49,7 @@ The [CARLA AD demo](carla_ad_demo.md) uses the Waypoint Publisher to plan a rout --- -## Publications and services +## ROS API #### Publications diff --git a/docs/rviz_plugin.md b/docs/rviz_plugin.md index 1c02a9eb..6912e270 100644 --- a/docs/rviz_plugin.md +++ b/docs/rviz_plugin.md @@ -4,7 +4,7 @@ The [RVIZ plugin](https://github.com/carla-simulator/ros-bridge/tree/master/rviz - [__Run ROS bridge with RVIZ__](#run-ros-bridge-with-rviz) - [__Features of the RVIZ plugin__](#features-of-the-rviz-plugin) -- [__RVIZ plugin subscriptions, publications and services__](#rviz-plugin-subscriptions-publications-and-services) +- [__ROS API__](#ros-api) - [Subscriptions](#subscriptions) - [Publications](#publications) - [Services](#services) @@ -60,7 +60,7 @@ __3.__ Control the ego vehicle with the `carla_manual_control` package (press `B --- -## RVIZ plugin subscriptions, publications and services +## ROS API #### Subscriptions From 83b87708f48a8840c9dfb7484890799d695259fb Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 16:37:33 +0200 Subject: [PATCH 573/627] Removed setting the env var path to CARLA in the Carla AD demo package. It already existed in the ROS 2 installation so I added the same step to the ROS 1 installation guide. --- docs/carla_ad_demo.md | 9 ++------- docs/ros_installation_ros1.md | 11 +++++++++-- 2 files changed, 11 insertions(+), 9 deletions(-) diff --git a/docs/carla_ad_demo.md b/docs/carla_ad_demo.md index 82e4cd6e..67b3c751 100644 --- a/docs/carla_ad_demo.md +++ b/docs/carla_ad_demo.md @@ -10,14 +10,9 @@ The [AD demo](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ad ## Before you begin -Make sure your Python path is configured correctly to point to the correct version of CARLA: +Install [Scenario Runner](https://carla-scenariorunner.readthedocs.io/en/latest/getting_scenariorunner/) and follow the Scenario Runner ["Getting Started" tutorial](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working. -```sh -export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ -``` - -You will need to install [Scenario Runner ](https://carla-scenariorunner.readthedocs.io/en/latest/getting_scenariorunner/). Follow the -Scenario Runner ["Getting Started" tutorial](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working. Set an environment variable to find it: +Set an environment variable to find the Scenario Runner installation: ```sh export SCENARIO_RUNNER_PATH= diff --git a/docs/ros_installation_ros1.md b/docs/ros_installation_ros1.md index 8dbf57a8..2914459b 100644 --- a/docs/ros_installation_ros1.md +++ b/docs/ros_installation_ros1.md @@ -121,7 +121,14 @@ __1.__ Start a CARLA server according to the installation method used to install make launch ``` -__2.__ Add the source path for the ROS bridge workspace according to the installation method of the ROS bridge. This should be done in every terminal each time you want to run the ROS bridge: +__2.__ Add the correct CARLA modules to your Python path: + +```sh + export CARLA_ROOT= + export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla +``` + +__3.__ Add the source path for the ROS bridge workspace according to the installation method of the ROS bridge. This should be done in every terminal each time you want to run the ROS bridge: ```sh # For debian installation of ROS bridge. Change the command according to your installed version of ROS. @@ -134,7 +141,7 @@ __2.__ Add the source path for the ROS bridge workspace according to the install !!! Important The source path can be set permanently, but it will cause conflict when working with another workspace. -__3.__ Start the ROS bridge. Use any of the different launch files available to check the installation: +__4.__ Start the ROS bridge. Use any of the different launch files available to check the installation: ```sh # Option 1: start the ros bridge From 9c1de566d077ebc19dd723f1e5a6b8cbe8b30d9f Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 16:44:25 +0200 Subject: [PATCH 574/627] Changed sensor names and clarified section that demonstrates the different commands that can be launched in a single launchfile --- docs/carla_manual_control.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/carla_manual_control.md b/docs/carla_manual_control.md index 6d51859f..acabbbb9 100644 --- a/docs/carla_manual_control.md +++ b/docs/carla_manual_control.md @@ -12,10 +12,10 @@ The [CARLA manual control package](https://github.com/carla-simulator/ros-bridge To be able to use `carla_manual_control`, some specific sensors need to be attached to the ego vehicle (see [Carla Spawn Objects](carla_spawn_objects.md) for information on how to attach sensors to vehicles): -- __to display an image__: a camera with role-name 'view' and resolution 800x600 -- __to display the current GNSS position__: a GNSS sensor with role-name 'gnss1' -- __to get a notification on lane invasions__: a lane invasion sensor -- __to get a notification on collisons__: a collision sensor +- __to display an image__: a camera with role-name `rgb_view` and resolution 800x600. +- __to display the current GNSS position__: a GNSS sensor with role-name `gnss`. +- __to get a notification on lane invasions__: a lane invasion sensor with role-name `lane_invasion`. +- __to get a notification on collisons__: a collision sensor with role-name `collision`. --- @@ -55,7 +55,7 @@ __3.__ Launch the `carla_manual_control` node: __4.__ To steer the vehicle manually, press 'B'. Press 'H' to see instructions. -All of the above commands are also combined into one single launchfile and can be run at the same time by executing the following: +Alternatively, all of the above commands are combined into a separate, single launchfile and can be run at the same time by executing the following: ```sh # ROS 1 From a24e8f17714c57081b7f1bebef0fa4232286d6ec Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 16:47:16 +0200 Subject: [PATCH 575/627] Removed trailing spaces --- docs/carla_manual_control.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/carla_manual_control.md b/docs/carla_manual_control.md index acabbbb9..8bba5a3d 100644 --- a/docs/carla_manual_control.md +++ b/docs/carla_manual_control.md @@ -27,15 +27,15 @@ __ 1.__ Make sure you have CARLA runing. Start the ROS bridge: ```sh # ROS 1 - roslaunch carla_ros_bridge carla_ros_bridge.launch + roslaunch carla_ros_bridge carla_ros_bridge.launch # ROS 2 ros2 launch carla_ros_bridge carla_ros_bridge.launch.py ``` __2.__ Spawn objects: - -```sh + +```sh # ROS 1 roslaunch carla_spawn_objects carla_spawn_objects.launch @@ -64,4 +64,4 @@ Alternatively, all of the above commands are combined into a separate, single la # ROS 2 ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py ``` ---- \ No newline at end of file +--- From 4223e3414f2b28ca7fc88060b7403dbdb308c1a2 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 16:54:01 +0200 Subject: [PATCH 576/627] Typo fix. Removed export path step --- docs/carla_ros_scenario_runner.md | 14 ++++---------- 1 file changed, 4 insertions(+), 10 deletions(-) diff --git a/docs/carla_ros_scenario_runner.md b/docs/carla_ros_scenario_runner.md index 9b4180af..ab14050e 100644 --- a/docs/carla_ros_scenario_runner.md +++ b/docs/carla_ros_scenario_runner.md @@ -1,6 +1,6 @@ # Carla ROS Scenario Runner -The [CARLA ROS Scenario Runner package](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ros_scenario_runner) is a wrapper to execute [OpenScenarios](https://www.asam.net/standards/detail/openscenario/) with the CARLA [Scenario Runner](https://github.com/carla-simulator/scenario_runner) via ROS. +The [CARLA ROS Scenario Runner package](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ros_scenario_runner) is a wrapper to execute [OpenScenarios](https://www.asam.net/standards/detail/openscenario/) with the CARLA [Scenario Runner](https://github.com/carla-simulator/scenario_runner) via ROS. - [__Before you begin__](#before-you-begin) - [__Using ROS Scenario Runner__](#using-ros-scenario-runner) @@ -23,7 +23,7 @@ sudo apt install python-pexpect ## Using ROS Scenario Runner -The ROS Scenario Runer is best used from within the [`rviz_carla_plugin`](rviz_plugin.md). +The ROS Scenario Runner is best used from within the [`rviz_carla_plugin`](rviz_plugin.md). !!! Note It is currently not supported to change the map. Each scenario will need to use the currently active map. @@ -46,13 +46,7 @@ The above code example shows an instance of [`carla_ad_agent`](carla_ad_agent.md ## Run ROS Scenario Runner -__1.__ Export the environment variables: - -```sh -export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ -``` - -__2.__ Run the ROS Scenario Runner package: +__1.__ Run the ROS Scenario Runner package: ```sh # ROS 1 @@ -62,7 +56,7 @@ roslaunch carla_ros_scenario_runner carla_ros_scenario_runner.launch scenario_ru ros2 launch carla_ros_scenario_runner carla_ros_scenario_runner.launch.py scenario_runner_path:= ``` -__3.__ Run a scenario: +__2.__ Run a scenario: ```sh # ROS 1 From 4d5f3da6016a8be5028ebfc8466bf32cb9ef1d44 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 16:55:37 +0200 Subject: [PATCH 577/627] Trailing spaces removed --- docs/carla_spawn_objects.md | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/docs/carla_spawn_objects.md b/docs/carla_spawn_objects.md index 1b57bb1c..d6399f3b 100644 --- a/docs/carla_spawn_objects.md +++ b/docs/carla_spawn_objects.md @@ -29,22 +29,22 @@ Objects and their attached sensors are defined through a `.json` file. The defau You can find an example in the [ros-bridge repository][objectsjson] as well as follow this outline to create your own configuration and sensor setup: ```json -{ -"objects": +{ +"objects": [ { "type": "", "id": "", "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - }, + }, { "type": "", "id": "", "spawn_point": {"x": -11.1, "y": 138.5, "z": 0.2, "roll": 0.0, "pitch": 0.0, "yaw": -178.7}, - "sensors": + "sensors": [ - + ] } ... @@ -56,7 +56,7 @@ You can find an example in the [ros-bridge repository][objectsjson] as well as f !!! Note Remember when directly defining positions that ROS uses a [right hand system](https://www.ros.org/reps/rep-0103.html#chirality) -All sensor attributes are defined as described in the [blueprint library](https://carla.readthedocs.io/en/latest/bp_library/). +All sensor attributes are defined as described in the [blueprint library](https://carla.readthedocs.io/en/latest/bp_library/). [objectsjson]: https://github.com/carla-simulator/ros-bridge/blob/master/carla_spawn_objects/config/objects.json @@ -80,7 +80,7 @@ All sensor attributes are defined as described in the [blueprint library](https: { "type": "vehicle.*", "id": "ego_vehicle", - "spawn_point": {"x": -11.1, "y": 138.5, "z": 0.2, "roll": 0.0, "pitch": 0.0, "yaw": -178.7}, + "spawn_point": {"x": -11.1, "y": 138.5, "z": 0.2, "roll": 0.0, "pitch": 0.0, "yaw": -178.7}, } ### Respawning vehicles @@ -92,13 +92,13 @@ A vehicle can be respawned to a different location during a simulation by publis { "type": "vehicle.*", "id": "ego_vehicle", - "sensors": + "sensors": [ { "type": "actor.pseudo.control", "id": "control" } - ] + ] } 2. Launch the `set_inital_pose` node, passing the `` as an argument to the ROS parameter `controller_id` (default = 'control'): @@ -126,7 +126,7 @@ Sensors can be attached to an already existing vehicle. To do so: { "type": "sensor.pseudo.actor_list", "id": "actor_list" - }, + }, 2. Define the rest of the sensors as required. 3. Launch the node with the `spawn_sensors_only` parameter set to True. This will check if an actor with the same `id` and `type` as the one specified in the `.json` file is already active and if so, attach the sensors to this actor. From b6594034fb582bd9fc1bf03b3c1ae92cb2828af4 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 16:57:51 +0200 Subject: [PATCH 578/627] Removed export path step --- docs/carla_waypoint.md | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/docs/carla_waypoint.md b/docs/carla_waypoint.md index 9811700d..fc0d5dbe 100644 --- a/docs/carla_waypoint.md +++ b/docs/carla_waypoint.md @@ -2,22 +2,12 @@ The [CARLA Waypoint Publisher](https://github.com/carla-simulator/ros-bridge/tree/master/carla_waypoint_publisher) makes waypoint calculations available to the ROS context and provides services to query CARLA waypoints. To find out more about waypoints, see the CARLA [documentation](https://carla.readthedocs.io/en/latest/core_map/#navigation-in-carla). -- [__Before you begin__](#before-you-begin) - [__Run the Waypoint Publisher__](#run-the-waypoint-publisher) - [Set a goal](#set-a-goal) - [__Using the Waypoint Publisher__](#using-the-waypoint-publisher) - [__ROS API__](#ros-api) - [Publications](#publications) - [Services](#services) ---- - -## Before you begin - -The Waypoint Publisher requires some functionality of the Python API that is not included in the Python `.egg` file. To include this functionality, extend your Python path with the following command: - -```sh -export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg:/PythonAPI/carla/ -``` --- From d8755015febd6b3a4fea3edbf83a5c53188778ba Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 17:26:45 +0200 Subject: [PATCH 579/627] Updated installation guide for source build, removed kinetic support, specified that deb package only available on ubuntu 18.04, typo fixes, removed rviz launchfile reference --- docs/ros_installation_ros1.md | 92 ++++++++++++++--------------------- 1 file changed, 36 insertions(+), 56 deletions(-) diff --git a/docs/ros_installation_ros1.md b/docs/ros_installation_ros1.md index 2914459b..419b6dbc 100644 --- a/docs/ros_installation_ros1.md +++ b/docs/ros_installation_ros1.md @@ -1,16 +1,16 @@ # ROS bridge installation for ROS 1 -This section is a guide on how to install the ROS bridge on Linux for use with ROS 1. You will find the prerequisites, installation steps, how to run a basic package to make sure everything is working well and commands to run tests. +This section is a guide on how to install the ROS bridge on Linux for use with ROS 1. You will find the prerequisites, installation steps, how to run a basic package to make sure everything is working well and commands to run tests. -- [__Before you begin__](#before-you-begin) - - [__ROS bridge installation __](#ros-bridge-installation) - - [A. Using the Debian repository](#a-using-the-debian-repository) - - [B. Using the source repository](#b-using-the-source-repository) -- [__Run the ROS bridge__](#run-the-ros-bridge) -- [__Testing__](#testing) +- [__Before you begin__](#before-you-begin) + - [__ROS bridge installation __](#ros-bridge-installation) + - [A. Using the Debian repository](#a-using-the-debian-repository) + - [B. Using the source repository](#b-using-the-source-repository) +- [__Run the ROS bridge__](#run-the-ros-bridge) +- [__Testing__](#testing) !!! Important - ROS is still [experimental](http://wiki.ros.org/noetic/Installation) for Windows. It has only been tested for Linux systems. + ROS is still [experimental](http://wiki.ros.org/noetic/Installation) for Windows. It has only been tested for Linux systems. --- ## Before you begin @@ -18,26 +18,29 @@ This section is a guide on how to install the ROS bridge on Linux for use with R You will need to fulfill the following software requirements before using the ROS bridge: - Install ROS according to your operating system: - - [__ROS Kinetic__](https://wiki.ros.org/kinetic/Installation) — For Ubuntu 16.04 (Xenial) - [__ROS Melodic__](https://wiki.ros.org/melodic/Installation/Ubuntu) — For Ubuntu 18.04 (Bionic) - [__ROS Noetic__](https://wiki.ros.org/noetic#Installation) — For Ubuntu 20.04 (Focal) -- Additional ROS packages may be required depending on your needs. [rviz](https://wiki.ros.org/rviz) is highly recommended to visualize ROS data. -- CARLA 0.9.7 or later — Previous versions are not compatible with the ROS bridge. Follow the [quick start installation](https://carla.readthedocs.io/en/latest/start_quickstart/) or make the build for [Linux](https://carla.readthedocs.io/en/latest/build_linux/). It is recommended to match the ROS bridge version to the CARLA version when possible. -- Install the ROS command line tool __python3-rosdep2__ to install system dependencies in ROS: -```sh - sudo apt install python3-rosdep2 -``` +- Additional ROS packages may be required depending on your needs. [rviz](https://wiki.ros.org/rviz) is highly recommended to visualize ROS data. +- CARLA 0.9.7 or later — Previous versions are not compatible with the ROS bridge. Follow the [quick start installation](https://carla.readthedocs.io/en/latest/start_quickstart/) or make the build for [Linux](https://carla.readthedocs.io/en/latest/build_linux/). It is recommended to match the ROS bridge version to the CARLA version when possible. --- -## ROS bridge installation +## ROS bridge installation + +There are two options available to install the ROS bridge: -There are two options available to install the ROS bridge, fetching via the __apt__ tool from the Debian repository or by cloning from the source repository on GitHub. Both methods are detailed below. +- Install via the __apt__ tool from the Debian repository. Only available on Ubuntu 18.04. +- Cloning from the source repository on GitHub. + + Both methods are detailed below. !!! Important To install ROS bridge versions prior to 0.9.10, you will find the instructions in the older versions of the CARLA documentation [here](https://carla.readthedocs.io/en/0.9.10/ros_installation/). Change to the appropriate version of the documentation using the panel in the bottom right corner of the window. ![docs_version_panel](images/docs_version_panel.jpg) ### A. Using the Debian repository +!!! Note + This installation method is ony available on Ubuntu 18.04. For other supported distributions, see [Section B: Using the source repository](#b-using-the-source-repository). + __1.__ Set up the Debian repository in your system: ```sh sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 1AF1527DE64CB8D9 @@ -46,16 +49,16 @@ __1.__ Set up the Debian repository in your system: __2.__ Install the ROS bridge: -> - Latest version: +> - Latest version: ```sh sudo apt-get update # Update the Debian package index sudo apt-get install carla-ros-bridge # Install the latest ROS bridge version, or update the current installation ``` -> - Install a specific version by adding a version tag to the command: +> - Install a specific version by adding a version tag to the command: ```sh apt-cache madison carla-ros-bridge # List the available versions of the ROS bridge - sudo apt-get install carla-ros-bridge=0.9.10-1 # In this case, "0.9.10" refers to the ROS bridge version, and "1" to the Debian revision + sudo apt-get install carla-ros-bridge=0.9.10-1 # In this case, "0.9.10" refers to the ROS bridge version, and "1" to the Debian revision ``` __3.__ Check the ROS bridge has been installed successfully in the `/opt/` folder. @@ -68,45 +71,30 @@ __1.__ Create a catkin workspace: mkdir -p ~/carla-ros-bridge/catkin_ws/src ``` -__2.__ Clone the ROS Bridge repository: +__2.__ Clone the ROS Bridge repository and submodules: ```sh cd ~/carla-ros-bridge - git clone https://github.com/carla-simulator/ros-bridge.git -``` - - -__3.__ Pull the ROS messages submodule: -```sh - cd ros-bridge - git submodule update --init -``` - -__4.__ Create a symbolic link from your catkin workspace to the ROS bridge directory: -```sh - cd ../catkin_ws/src - ln -s ../../ros-bridge + git clone --recurse-submodules https://github.com/carla-simulator/ros-bridge.git catkin_ws/src/ros-bridge ``` __5.__ Set up the ROS environment according to the ROS version you have installed: ```sh - source /opt/ros//setup.bash + source /opt/ros//setup.bash ``` __6.__ Install the required ros-dependencies: ```sh - cd .. + cd catkin_ws rosdep update rosdep install --from-paths src --ignore-src -r ``` __7.__ Build the ROS bridge: ```sh - catkin_make + catkin build # alternatively catkin_make ``` - --- - ## Run the ROS bridge __1.__ Start a CARLA server according to the installation method used to install CARLA: @@ -128,28 +116,25 @@ __2.__ Add the correct CARLA modules to your Python path: export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla ``` -__3.__ Add the source path for the ROS bridge workspace according to the installation method of the ROS bridge. This should be done in every terminal each time you want to run the ROS bridge: +__3.__ Add the source path for the ROS bridge workspace according to the installation method of the ROS bridge. This should be done in every terminal each time you want to run the ROS bridge: ```sh # For debian installation of ROS bridge. Change the command according to your installed version of ROS. - source /opt/carla-ros-bridge//setup.bash + source /opt/carla-ros-bridge//setup.bash - # For GitHub repository installation of ROS bridge + # For GitHub repository installation of ROS bridge source ~/carla-ros-bridge/catkin_ws/devel/setup.bash ``` !!! Important - The source path can be set permanently, but it will cause conflict when working with another workspace. + The source path can be set permanently, but it may cause conflict when working with another workspace. -__4.__ Start the ROS bridge. Use any of the different launch files available to check the installation: +__4.__ Start the ROS bridge. Use any of the different launch files available to check the installation: ```sh # Option 1: start the ros bridge roslaunch carla_ros_bridge carla_ros_bridge.launch - # Option 2: start the ros bridge together with RVIZ - roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch - # Option 3: start the ros bridge together with an example ego vehicle roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch ``` @@ -157,12 +142,14 @@ __4.__ Start the ROS bridge. Use any of the different launch files available to !!! Note - If you receive the error: `ImportError: no module named CARLA` then the path to the CARLA Python API is missing. The apt installation sets the path automatically, but it may be missing for other installations. + If you receive the error: `ImportError: no module named CARLA` then the path to the CARLA Python API is missing. The apt installation sets the path automatically, but it may be missing for other installations. You will need to add the appropriate `.egg` file to your Python path. You will find the file in either `/PythonAPI/` or `/PythonAPI/dist/` depending on the CARLA installation. Execute the following command with the complete path to the `.egg` file, using the file that corresponds to your installed version of Python: `export PYTHONPATH=$PYTHONPATH:path/to/carla/PythonAPI/` + It is recommended to set this variable permanently by adding the previous line to your `.bashrc` file. + To check the CARLA library can be imported correctly, run the following command and wait for a success message: python3 -c 'import carla;print("Success")' # python3 @@ -171,9 +158,6 @@ __4.__ Start the ROS bridge. Use any of the different launch files available to python -c 'import carla;print("Success")' # python2 - - - --- ## Testing @@ -192,8 +176,4 @@ __2.__ Run the tests: rostest carla_ros_bridge ros_bridge_client.test ``` - --- - - - From afc2086883d6688e570efc20eee430580e86cd7c Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 17:27:11 +0200 Subject: [PATCH 580/627] Changed option 3 to 2 --- docs/ros_installation_ros1.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/ros_installation_ros1.md b/docs/ros_installation_ros1.md index 419b6dbc..30caeb95 100644 --- a/docs/ros_installation_ros1.md +++ b/docs/ros_installation_ros1.md @@ -135,7 +135,7 @@ __4.__ Start the ROS bridge. Use any of the different launch files available to # Option 1: start the ros bridge roslaunch carla_ros_bridge carla_ros_bridge.launch - # Option 3: start the ros bridge together with an example ego vehicle + # Option 2: start the ros bridge together with an example ego vehicle roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch ``` From 274b0c526b7f14b92b22dc57fcec0911c37a81ae Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 17:37:27 +0200 Subject: [PATCH 581/627] Updated installation instructions. Removed pytho3 rosdep2 installation --- docs/ros_installation_ros2.md | 64 +++++++++++++++++------------------ 1 file changed, 31 insertions(+), 33 deletions(-) diff --git a/docs/ros_installation_ros2.md b/docs/ros_installation_ros2.md index b87d7fef..22517390 100644 --- a/docs/ros_installation_ros2.md +++ b/docs/ros_installation_ros2.md @@ -1,14 +1,14 @@ # ROS bridge installation for ROS 2 -This section is a guide on how to install the ROS bridge on Linux for use with ROS 2. You will find the prerequisites, installation steps, how to run a basic package to make sure everything is working well and commands to run tests. +This section is a guide on how to install the ROS bridge on Linux for use with ROS 2. You will find the prerequisites, installation steps, how to run a basic package to make sure everything is working well and commands to run tests. - [__Before you begin__](#before-you-begin) -- [__ROS bridge installation __](#ros-bridge-installation) -- [__Run the ROS bridge__](#run-the-ros-bridge) +- [__ROS bridge installation __](#ros-bridge-installation) +- [__Run the ROS bridge__](#run-the-ros-bridge) - [__Testing__](#testing) !!! Important - ROS is still [experimental](http://wiki.ros.org/noetic/Installation) for Windows. It has only been tested for Linux systems. + ROS is still [experimental](http://wiki.ros.org/noetic/Installation) for Windows. It has only been tested for Linux systems. --- @@ -18,40 +18,40 @@ You will need to fulfill the following software requirements before using the RO - Install ROS: - [__ROS 2 Foxy__](https://docs.ros.org/en/foxy/Installation.html) — For Ubuntu 20.04 (Focal) -- Additional ROS packages may be required depending on your needs. [rviz](https://wiki.ros.org/rviz) is highly recommended to visualize ROS data. -- CARLA 0.9.7 or later — Previous versions are not compatible with the ROS bridge. Follow the [quick start installation](https://carla.readthedocs.io/en/latest/start_quickstart/) or make the build for [Linux](https://carla.readthedocs.io/en/latest/build_linux/). It is recommended to match the ROS bridge version to the CARLA version when possible. -- Install the ROS command line tool __python3-rosdep2__ to install system dependencies in ROS: -```sh - sudo apt install python3-rosdep2 -``` +- Additional ROS packages may be required depending on your needs. [rviz](https://wiki.ros.org/rviz) is highly recommended to visualize ROS data. +- CARLA 0.9.7 or later — Previous versions are not compatible with the ROS bridge. Follow the [quick start installation](https://carla.readthedocs.io/en/latest/start_quickstart/) or make the build for [Linux](https://carla.readthedocs.io/en/latest/build_linux/). It is recommended to match the ROS bridge version to the CARLA version when possible. --- -## ROS bridge installation +## ROS bridge installation -__1.__ Clone the ROS bridge repository: +!!! Note + The Debian package installation is not yet available for ROS 2. + +__1.__ Set up the project directory and clone the ROS bridge repository and submodules: ```sh - git clone https://github.com/carla-simulator/ros-bridge.git + mkdir -p ~/carla-ros-bridge && cd ~/carla-ros-bridge + git clone --recurse-submodules https://github.com/carla-simulator/ros-bridge.git src/ros-bridge ``` -__2.__ Move into the `ros-bridge` repository and pull the ROS messages submodule: +__2.__ Set up the ROS environment: ```sh - cd ros-bridge - git submodule update --init + source /opt/ros/foxy/setup.bash ``` -__3.__ Set up the ROS environment: +__3.__ Install the ROS dependencies: ```sh - source /opt/ros/foxy/setup.bash + rosdep update + rosdep install --from-paths src --ignore-src -r ``` __4.__ Build the ROS bridge workspace using colcon: ```sh - colcon build + colcon build ``` --- @@ -74,33 +74,35 @@ __1.__ Start a CARLA server according to the installation method used to install __2.__ Add the correct CARLA modules to your Python path: ```sh - export CARLA_ROOT= - export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla + export CARLA_ROOT= + export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla ``` __3.__ Add the source path for the ROS bridge workspace: ```sh - source ./install/setup.bash + source ./install/setup.bash ``` __4.__ In another terminal, start the ROS 2 bridge. You can run one of the two options below: ```sh - # Option 1, start the basic ROS bridge package - ros2 launch carla_ros_bridge carla_ros_bridge.launch.py + # Option 1, start the basic ROS bridge package + ros2 launch carla_ros_bridge carla_ros_bridge.launch.py - # Option 2, start the ROS bridge with an example ego vehicle - ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py + # Option 2, start the ROS bridge with an example ego vehicle + ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py ``` !!! Note - If you receive the error: `ImportError: no module named CARLA` then the path to the CARLA Python API is missing. The apt installation sets the path automatically, but it may be missing for other installations. + If you receive the error: `ImportError: no module named CARLA` then the path to the CARLA Python API is missing. The apt installation sets the path automatically, but it may be missing for other installations. You will need to add the appropriate `.egg` file to your Python path. You will find the file in either `/PythonAPI/` or `/PythonAPI/dist/` depending on the CARLA installation. Execute the following command with the complete path to the `.egg` file, using the file that corresponds to your installed version of Python: `export PYTHONPATH=$PYTHONPATH:path/to/carla/PythonAPI/` + It is recommended to set this variable permanently by adding the previous line to your `.bashrc` file. + To check the CARLA library can be imported correctly, run the following command and wait for a success message: python3 -c 'import carla;print("Success")' # python3 @@ -109,8 +111,6 @@ __4.__ In another terminal, start the ROS 2 bridge. You can run one of the two o python -c 'import carla;print("Success")' # python2 - - --- ## Testing @@ -120,15 +120,13 @@ To execute tests using colcon: __1.__ Build the package: ```sh - colcon build --packages-up-to carla_ros_bridge + colcon build --packages-up-to carla_ros_bridge ``` __2.__ Run the tests: ```sh - launch_test carla_ros_bridge/test/ros_bridge_client_ros2_test.py + launch_test carla_ros_bridge/test/ros_bridge_client_ros2_test.py ``` --- - - From 51aca1644f34c7fc2afe4d532eb1d76166e81d93 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 17:38:47 +0200 Subject: [PATCH 582/627] Removed kinetic --- docs/run_ros.md | 33 +++++++++++++-------------------- 1 file changed, 13 insertions(+), 20 deletions(-) diff --git a/docs/run_ros.md b/docs/run_ros.md index 0956d737..63583d1d 100644 --- a/docs/run_ros.md +++ b/docs/run_ros.md @@ -25,9 +25,9 @@ The command to run depends on whether you installed ROS via the Debian package o ```sh # For debian installation of ROS bridge. Change the command according to your installed version of ROS. - source /opt/carla-ros-bridge//setup.bash + source /opt/carla-ros-bridge//setup.bash - # For GitHub repository installation of ROS bridge + # For GitHub repository installation of ROS bridge source ~/carla-ros-bridge/catkin_ws/devel/setup.bash ``` @@ -60,16 +60,16 @@ There are other launchfiles that combine the above functionality of starting the Configuration settings can be modified in [`ros-bridge/carla_ros_bridge/config/settings.yaml`](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_bridge/config/settings.yaml). The following settings are available: -* __use_sim_time__: This should be set to __True__ to ensure that ROS is using simulation time rather than system time. This parameter will synchronize the ROS [`/clock`][ros_clock] topic with CARLA simulation time. -* __host and port__: Network settings to connect to CARLA using a Python client. +* __use_sim_time__: This should be set to __True__ to ensure that ROS is using simulation time rather than system time. This parameter will synchronize the ROS [`/clock`][ros_clock] topic with CARLA simulation time. +* __host and port__: Network settings to connect to CARLA using a Python client. * __timeout__: Time to wait for a successful connection to the server. -* __passive__: Passive mode is for use in scynchronous mode. When enabled, the ROS bridge will take a backseat and another client __must__ tick the world. ROS bridge will wait for all expected data from all sensors to be received. +* __passive__: Passive mode is for use in scynchronous mode. When enabled, the ROS bridge will take a backseat and another client __must__ tick the world. ROS bridge will wait for all expected data from all sensors to be received. * __synchronous_mode__: - * __If false (default)__: Data is published on every `world.on_tick()` and every `sensor.listen()` callback. - * __If true__: ROS bridge waits for all the sensor messages expected before the next tick. This might slow down the overall simulation but ensures reproducible results. -* __synchronous_mode_wait_for_vehicle_control_command__: In synchronous mode, pauses the tick until a vehicle control is completed. -* __fixed_delta_seconds__: Simulation time (delta seconds) between simulation steps. __It must be lower than 0.1__. Take a look at the [documentation](https://carla.readthedocs.io/en/latest/adv_synchrony_timestep/) to learn more about this. -* __ego_vehicle__: Role names to identify ego vehicles. Relevant topics will be created so these vehicles will be able to be controlled from ROS. + * __If false (default)__: Data is published on every `world.on_tick()` and every `sensor.listen()` callback. + * __If true__: ROS bridge waits for all the sensor messages expected before the next tick. This might slow down the overall simulation but ensures reproducible results. +* __synchronous_mode_wait_for_vehicle_control_command__: In synchronous mode, pauses the tick until a vehicle control is completed. +* __fixed_delta_seconds__: Simulation time (delta seconds) between simulation steps. __It must be lower than 0.1__. Take a look at the [documentation](https://carla.readthedocs.io/en/latest/adv_synchrony_timestep/) to learn more about this. +* __ego_vehicle__: Role names to identify ego vehicles. Relevant topics will be created so these vehicles will be able to be controlled from ROS. [ros_clock]: https://wiki.ros.org/Clock @@ -83,8 +83,8 @@ When running multiple clients in synchronous mode, only one client is allowed to If the ROS bridge is not in passive mode (ROS bridge is the one ticking the world), then there are two ways to send step controls to the server: -- Send a message to the topic `/carla/control` with a [`carla_msgs.CarlaControl`](ros_msgs.md#carlacontrolmsg) message. -- Use the [Control rqt plugin](rqt_plugin.md). This plugin launches a new window with a simple interface. It is then used to manage the steps and publish in the `/carla/control` topic. To use it, run the following command with CARLA in synchronous mode: +- Send a message to the topic `/carla/control` with a [`carla_msgs.CarlaControl`](ros_msgs.md#carlacontrolmsg) message. +- Use the [Control rqt plugin](rqt_plugin.md). This plugin launches a new window with a simple interface. It is then used to manage the steps and publish in the `/carla/control` topic. To use it, run the following command with CARLA in synchronous mode: ```sh rqt --standalone rqt_carla_control ``` @@ -122,7 +122,7 @@ __2.__ In another terminal, publish to the topic `/carla//vehicle_con # for ros2 ros2 topic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10 - + ``` The current status of the vehicle can be received via topic `/carla//vehicle_status`. Static information about the vehicle can be received via `/carla//vehicle_info`. @@ -167,10 +167,3 @@ It is possible to use [AckermannDrive](https://docs.ros.org/en/api/ackermann_msg | `/carla/spawn_object` | [carla_msgs/SpawnObject.srv](https://github.com/carla-simulator/ros-carla-msgs/blob/f75637ce83a0b4e8fbd9818980c9b11570ff477c/srv/SpawnObject.srv) | Spawn an object | --- - - - - - - - From 8e04bcc767f82344dd4c8a05613c1ce881301489 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 17:46:20 +0200 Subject: [PATCH 583/627] Typo fix --- docs/rviz_plugin.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/rviz_plugin.md b/docs/rviz_plugin.md index 6912e270..c0aa73ce 100644 --- a/docs/rviz_plugin.md +++ b/docs/rviz_plugin.md @@ -15,7 +15,7 @@ The [RVIZ plugin](https://github.com/carla-simulator/ros-bridge/tree/master/rviz ![ros_rviz](images/ros_rviz.png) -The RVIZ plugin expects an ego vehicle named `ego_vehicle`. To see an example of ROS-bridge working with RVIZ, execute the following the commands with a CARLA server running: +The RVIZ plugin expects an ego vehicle named `ego_vehicle`. To see an example of ROS-bridge working with RVIZ, execute the following commands with a CARLA server running: __1.__ Start the ROS bridge with RVIZ enabled: From 777a61573e6da4b9854778cea45ec9f23e424e1e Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 17:51:41 +0200 Subject: [PATCH 584/627] Removed launchfiles reference --- docs/ros_launchfiles.md | 392 ---------------------------------------- mkdocs.yml | 2 - 2 files changed, 394 deletions(-) delete mode 100644 docs/ros_launchfiles.md diff --git a/docs/ros_launchfiles.md b/docs/ros_launchfiles.md deleted file mode 100644 index 84a9b7b9..00000000 --- a/docs/ros_launchfiles.md +++ /dev/null @@ -1,392 +0,0 @@ -# Launchfiles reference - ---- -## carla_ackermann_control.launch - -Creates a node to manage a vehicle using Ackermann controls instead of the CARLA control messages. The node reads the vehicle info from CARLA and uses it to define the controller. A simple Python PID is used to adjust acceleration/velocity. This is a Python dependency that can be easily installed with _pip_. -```sh -pip install --user simple-pid -``` -It is possible to modify the parameters in runtime via ROS dynamic reconfigure. Initial parameters can be set using a `settings.yaml`. The path to it depends on the bridge installation. - -* __Deb repository installation__, -`/opt/carla-ros-bridge/melodic/share/carla_ackermann_control/config/settings.yaml`. -* __Source repository installation__, -`/catkin_ws/src/ros-bridge/carla_ackermann_control/config/settings.yaml`. - - -

/carla_ackermann_control_ego_vehicle (Node)

-Converts [AckermannDrive messages](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html) to [CarlaEgoVehicleControl.msg](ros_msgs.md#carlaegovehiclecontrolmsg). Speed is in __m/s__, steering angle in __radians__ and refers to driving angle, not wheel angle. - -

Subscribed to:

- -* /carla/ego_vehicle/ackermann_cmd — [ackermann_msgs.AckermannDrive](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html) -* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) -* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) - - -

Publishes in:

- -* /carla/ego_vehicle/ackermann_control/parameter_descriptions — [dynamic_reconfigure/ConfigDescription](http://docs.ros.org/melodic/api/dynamic_reconfigure/html/msg/ConfigDescription.html) -* /carla/ego_vehicle/ackermann_control/control_info — [carla_ackermann_control.EgoVehicleControlInfo](ros_msgs.md#egovehiclecontrolinfomsg) -* /carla/ego_vehicle/ackermann_control/parameter_updates — [dynamic_reconfigure/Config](http://wiki.ros.org/dynamic_reconfigure) -* /carla/ego_vehicle/vehicle_control_cmd — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) - ---- -## carla_ego_vehicle.launch - -Spawns an ego vehicle (`role-name="ego_vehicle"`). The argument `sensor_definition_file` describes the sensors attached to the vehicle. It is the location of a __.json__ file. The format of this file is explained [here](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ego_vehicle). - -To spawn the vehicle at a specific location, publish in `/carla/ego_vehicle/initialpose`, or use __RVIZ__ and select a position with __2D Pose estimate__. - - -

carla_ego_vehicle_ego_vehicle (Node)

-Spawns an ego vehicle with sensors attached, and waits for world information. - -

Subscribed to:

- -* /carla/ego_vehicle/initialpose — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html) -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) - ---- -## carla_example_ego_vehicle.launch -Based on carla_ego_vehicle.launch, spawns an ego vehicle (`role-name="ego_vehicle"`). The file `sensors.json` describes the sensors attached. The path to it depends on the bridge installation. - -* __Deb repository installation__, -`/opt/carla-ros-bridge/melodic/share/carla_ego_vehicle/config/sensors.json`. -* __Source repository installation__, -`/catkin_ws/src/ros-bridge/carla_ego_vehicle/config/sensors.json`. - - -

carla_ego_vehicle_ego_vehicle (Node)

-Spawns an ego vehicle with sensors attached and waits for world information. - -

Subscribed to:

- -* /carla/ego_vehicle/initialpose — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html) -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) - ---- -## carla_infrastructure.launch -Spawns infrastructure sensors and requires the argument `infrastructure_sensor_definition_file` with the location of a __.json__ file describing these sensors. - - -

/carla_infrastructure (Node)

-Spawns the infrastructure sensors passed as arguments. - -

Subscribed to:

- -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) - ---- -## carla_ros_bridge.launch -Creates a node with some basic communications between CARLA and ROS. - - -

carla_ros_bridge (Node)

-Publishes the data regarding the current state of the simulation. Reads the debug shapes being drawn. - -

Subscribed to:

- -* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) - -

Publishes in:

- -* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) -* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) -* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) -* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) - ---- -## carla_ros_bridge_with_ackermann_control.launch - -Launches two basic nodes. One retrieves simulation data, the other controls a vehicle using [AckermannDrive messages](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html). - - -

carla_ros_bridge (Node)

-Publishes data regarding the current state of the simulation. Reads the debug shapes being drawn. - -

Subscribed to:

- -* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) - -

Publishes in:

- -* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) -* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) -* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) -* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) - - -

/carla_ackermann_control_ego_vehicle (Node)

-Converts [AckermannDrive messages](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html) to [CarlaEgoVehicleControl.msg](ros_msgs.md#carlaegovehiclemsg). Speed is in __m/s__, steering angle is in __radians__ and refers to driving angle, not wheel angle. - -

Subscribed to:

- -* /carla/ego_vehicle/ackermann_cmd — [ackermann_msgs.AckermannDrive](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.html) -* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) -* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) - - -

Publishes in:

- -* /carla/ego_vehicle/ackermann_control/parameter_descriptions — [dynamic_reconfigure/ConfigDescription](http://docs.ros.org/melodic/api/dynamic_reconfigure/html/msg/ConfigDescription.html) -* /carla/ego_vehicle/ackermann_control/control_info — [carla_ackermann_control.EgoVehicleControlInfo](ros_msgs.md#egovehiclecontrolinfomsg) -* /carla/ego_vehicle/ackermann_control/parameter_updates — [dynamic_reconfigure/Config](http://wiki.ros.org/dynamic_reconfigure) -* /carla/ego_vehicle/vehicle_control_cmd — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) - ---- -## carla_ros_bridge_with_example_ego_vehicle.launch - -Spawns an ego vehicle with sensors attached, and starts communications between CARLA and ROS. Both share current simulation state, sensor and ego vehicle data. The ego vehicle is set ready to be used in manual control. - - -

carla_ros_bridge (Node)

-In charge of the communications between CARLA and ROS. They share the current state of the simulation, traffic lights, vehicle controllers and sensor data. -

Subscribed to:

- -* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) -* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) -* /carla/ego_vehicle/twist — [geometry_msgs.Twist](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/Twist.html) -* /carla/ego_vehicle/vehicle_control_cmd — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) -* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) -* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) - -

Publishes in:

- -* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) -* /carla/ego_vehicle/camera/rgb/front/camera_info — [sensor_msgs.CameraInfo](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/CameraInfo.html) -* /carla/ego_vehicle/camera/rgb/front/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) -* /carla/ego_vehicle/camera/rgb/view/camera_info — [sensor_msgs.CameraInfo](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/CameraInfo.html) -* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) -* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) -* /carla/ego_vehicle/imu — [sensor_msgs.Imu](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Imu.html) -* /carla/ego_vehicle/lidar/lidar1/point_cloud — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html) -* /carla/ego_vehicle/objects — [derived_object_msgs.ObjectArray](http://docs.ros.org/kinetic/api/derived_object_msgs/html/msg/ObjectArray.html) -* /carla/ego_vehicle/odometry — [nav_msgs.Odometry](http://docs.ros.org/melodic/api/nav_msgs/html/msg/Odometry.html) -* /carla/ego_vehicle/radar/front/radar — [ainstein_radar_msgs.RadarTargetArray](http://wiki.ros.org/ainstein_radar_msgs) -* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) -* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) -* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) -* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) -* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) - - - -

/carla_manual_control_ego_vehicle (Node)

-Retrieves information from CARLA regarding the ego vehicle. Uses keyboard input to publish controller messages for the ego vehicle. The information retrieved includes static data, current state, sensor data, and simulation settings. - -

Subscribed to:

- -* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) -* /carla/ego_vehicle/collision — [carla_msgs.CarlaCollisionEvent](ros_msgs.md#carlacollisioneventmsg) -* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) -* /carla/ego_vehicle/lane_invasion — [carla_msgs.CarlaLaneInvasionEvent](ros_msgs.md#carlalaneinvasioneventmsg) -* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) -* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) -* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) -* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) - - -

Publishes in:

- -* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) -* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) -* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) - - -

/carla_ego_vehicle_ego_vehicle (Node)

-Spawns an ego vehicle with sensors attached. Reads world information. - -

Subscribed to:

- -* /carla/ego_vehicle/initialpose — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html) - ---- -## carla_ros_bridge_with_rviz.launch - -Starts communications between CARLA and ROS, and launches RVIZ to retrieve Lidar data. - -

carla_ros_bridge (Node)

-Shares information between CARLA and ROS regarding the current simulation state. - -

Subscribed to:

- -* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) - -

Publishes in:

- -* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) -* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) -* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) -* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) - - -

/rviz (Node)

-Runs an instance of RVIZ, and waits for Lidar data. - -

Subscribed to:

- -* /carla/vehicle_marker — [visualization_msgs/Marker](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/Marker.html) -* /carla/vehicle_marker_array — [visualization_msgs/MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) -* /carla/ego_vehicle/lidar/front/point_cloud — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html) - - ---- -## carla_manual_control.launch - -A ROS version of the CARLA script `manual_control.py`. It has some prequisites. - -* __To display an image__, a camera with role-name `view` and resolution 800x600. -* __To display the position__, a gnss sensor with role-name `gnss1`. -* __To detect other sensor data__, the corresponding sensor. - - - -

/carla_manual_control_ego_vehicle (Node)

-Retrieves information from CARLA regarding the ego vehicle. Uses keyboard input to publish controller messages for the ego vehicle. The information retrieved includes static data, current state, sensor data, and simulation settings. - -

Subscribed to:

- -* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) -* /carla/ego_vehicle/collision — [carla_msgs.CarlaCollisionEvent](ros_msgs.md#carlacollisioneventmsg) -* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) -* /carla/ego_vehicle/lane_invasion — [carla_msgs.CarlaLaneInvasionEvent](ros_msgs.md#carlalaneinvasioneventmsg) -* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) -* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) -* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) -* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) - - -

Publishes in:

- -* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) -* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) -* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) - ---- -## carla_pcl_recorder.launch -Creates a pointcloud map for the current CARLA level. An autopilot ego vehicle roams around the map with a LIDAR sensor attached. - -The point clouds are saved in the `/tmp/pcl_capture` directory. Once the capture is done, the overall size can be reduced. - -```sh -#create one point cloud file -pcl_concatenate_points_pcd /tmp/pcl_capture/*.pcd - -#filter duplicates -pcl_voxel_grid -leaf 0.1,0.1,0.1 output.pcd map.pcd - -#verify the result -pcl_viewer map.pcd -``` - -The launch file requires some functionality that is not part of the python egg-file. The PYTHONPATH has to be extended. - -```sh -export PYTHONPATH=/PythonAPI/carla/dist/carla-.egg:/PythonAPI/carla/ -``` - - -

carla_ros_bridge (Node)

-In charge of most of the communications between CARLA and ROS. Both share the current state of the simulation, traffic lights, vehicle controllers and sensor data. - -

Subscribed to:

- -* /carla/debug_marker — [visualization_msgs.MarkerArray](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/MarkerArray.html) -* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) -* /carla/ego_vehicle/twist — [geometry_msgs.Twist](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/Twist.html) -* /carla/ego_vehicle/vehicle_control_cmd — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) -* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) -* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) - -

Publishes in:

- -* /carla/actor_list — [carla_msgs.CarlaActorList](ros_msgs.md#carlaactorlistmsg) -* /carla/ego_vehicle/camera/rgb/front/camera_info — [sensor_msgs.CameraInfo](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/CameraInfo.html) -* /carla/ego_vehicle/camera/rgb/front/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) -* /carla/ego_vehicle/camera/rgb/view/camera_info — [sensor_msgs.CameraInfo](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/CameraInfo.html) -* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) -* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) -* /carla/ego_vehicle/imu — [sensor_msgs.Imu](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Imu.html) -* /carla/ego_vehicle/lidar/lidar1/point_cloud — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html) -* /carla/ego_vehicle/objects — [derived_object_msgs.ObjectArray](http://docs.ros.org/kinetic/api/derived_object_msgs/html/msg/ObjectArray.html) -* /carla/ego_vehicle/odometry — [nav_msgs.Odometry](http://docs.ros.org/melodic/api/nav_msgs/html/msg/Odometry.html) -* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) -* /carla/ego_vehicle/radar/front/radar — [ainstein_radar_msgs.RadarTargetArray](http://wiki.ros.org/ainstein_radar_msgs) -* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) -* /carla/marker — [visualization_msgs.Marker](http://docs.ros.org/melodic/api/visualization_msgs/html/msg/Marker.html) -* /carla/objects — [derived_object_msgs.ObjectArrayring](http://wiki.ros.org/derived_object_msgs) -* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) -* /carla/traffic_lights — [carla_msgs.CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) - - -

/carla_manual_control_ego_vehicle (Node)

-Retrieves information from CARLA regarding the ego vehicle. Uses keyboard input to publish controller messages for the ego vehicle. The information retrieved includes static data, current state, sensor data, and simulation settings. - -

Subscribed to:

- -* /carla/ego_vehicle/camera/rgb/view/image_color — [sensor_msgs.Image](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/Image.html) -* /carla/ego_vehicle/collision — [carla_msgs.CarlaCollisionEvent](ros_msgs.md#carlacollisioneventmsg) -* /carla/ego_vehicle/gnss/gnss1/fix — [sensor_msgs.NavSatFix](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/NavSatFix.html) -* /carla/ego_vehicle/lane_invasion — [carla_msgs.CarlaLaneInvasionEvent](ros_msgs.md#carlalaneinvasioneventmsg) -* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) -* /carla/ego_vehicle/vehicle_info — [carla_msgs.CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) -* /carla/ego_vehicle/vehicle_status — [carla_msgs.CarlaEgoVehicleStatus](ros_msgs.md#carlaegovehiclestatusmsg) -* /carla/status — [carla_msgs.CarlaStatus](ros_msgs.md#carlastatusmsg) - - -

Publishes in:

- -* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) -* /carla/ego_vehicle/vehicle_control_cmd_manual — [carla_msgs.CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) -* /carla/ego_vehicle/vehicle_control_manual_override — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) - - -

/carla_ego_vehicle_ego_vehicle (Node)

-Spawns an ego vehicle with sensors attached. Waits for world information. - -

Subscribed to:

- -* /carla/ego_vehicle/initialpose — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html) - - -

/enable_autopilot_rostopic (Node)

-Changes between autopilot and manual control modes. - -

Publishes in:

- -* /carla/ego_vehicle/enable_autopilot — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html) - - - -

/pcl_recorder_node (Node)

-Receives the cloud point data. - -

Subscribed to:

- -* /carla/ego_vehicle/lidar/lidar1/point_cloud — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html) - ---- -## carla_waypoint_publisher.launch - -Calculates a waypoint route for an ego vehicle. The route is published in `/carla//waypoints`. The goal is either read from the ROS topic `/carla//goal`, or a fixed spawnpoint is used. -The prefered way of setting a goal is to click __2D Nav Goal__ in RVIZ. - -The launch file requires some functionality that is not part of the python egg-file. The PYTHONPATH has to be extended. -```sh -export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ -``` - - -

/carla_waypoint_publisher (Node)

-Uses the current pose of the ego vehicle as starting point. If the vehicle is respawned or moved, the route is calculated again. - -

Subscribed to:

- -* /carla/world_info — [carla_msgs.CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) diff --git a/mkdocs.yml b/mkdocs.yml index 4b1215e1..ddf3340d 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -24,8 +24,6 @@ nav: - RQT Plugin: 'rqt_plugin.md' - References: - CARLA messages reference: 'ros_msgs.md' - - Launchfiles reference: 'ros_launchfiles.md' - markdown_extensions: - admonition From 7aeabccf471111bcb7e774f81a352198cb0086d7 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 31 Mar 2021 17:53:02 +0200 Subject: [PATCH 585/627] Removed reference to launchfiles in index --- docs/index.md | 1 - 1 file changed, 1 deletion(-) diff --git a/docs/index.md b/docs/index.md index e34da583..eb621904 100644 --- a/docs/index.md +++ b/docs/index.md @@ -32,4 +32,3 @@ The ROS bridge boasts the following features: - [__ROS Sensors__](ros_sensors.md) - [__ROS messages__](ros_msgs.md) -- [__ROS launchfiles__](ros_launchfiles.md) \ No newline at end of file From 8e5fb99151d3652f33d12b6cd49ab7a83784cdb4 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Thu, 1 Apr 2021 10:58:25 +0200 Subject: [PATCH 586/627] Added step to launch RVIZ directly, replaces the deprecated launchfile --- docs/rviz_plugin.md | 34 ++++++++++++++++++++++------------ 1 file changed, 22 insertions(+), 12 deletions(-) diff --git a/docs/rviz_plugin.md b/docs/rviz_plugin.md index c0aa73ce..0910e3aa 100644 --- a/docs/rviz_plugin.md +++ b/docs/rviz_plugin.md @@ -20,31 +20,41 @@ The RVIZ plugin expects an ego vehicle named `ego_vehicle`. To see an example of __1.__ Start the ROS bridge with RVIZ enabled: ```sh - # ROS 1 - roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch +# ROS 1 +roslaunch carla_ros_bridge carla_ros_bridge.launch - # ROS 2 - ros2 launch carla_ros_bridge carla_ros_bridge_with_rviz.launch.py +# ROS 2 +ros2 launch carla_ros_bridge carla_ros_bridge.launch.py +``` + +__2.__ Start RVIZ: + +```sh +# ROS 1 +rosrun rviz rviz + +# ROS 2 +ros2 run rviz2 rviz2 ``` __2.__ Spawn an ego vehicle with the `carla_spawn_objects` package: ```sh - # ROS 1 - roslaunch carla_spawn_objects carla_spawn_objects.launch +# ROS 1 +roslaunch carla_spawn_objects carla_spawn_objects.launch - # ROS 2 - ros2 launch carla_spawn_objects carla_spawn_objects.launch.py +# ROS 2 +ros2 launch carla_spawn_objects carla_spawn_objects.launch.py ``` __3.__ Control the ego vehicle with the `carla_manual_control` package (press `B` to enable manual steering): ```sh - # ROS 1 - roslaunch carla_manual_control carla_manual_control.launch +# ROS 1 +roslaunch carla_manual_control carla_manual_control.launch - # ROS 2 - ros2 launch carla_manual_control carla_manual_control.launch.py +# ROS 2 +ros2 launch carla_manual_control carla_manual_control.launch.py ``` --- From 7474996f9b046947ba84f5fa72a2328f272b0f61 Mon Sep 17 00:00:00 2001 From: KevinLADLee Date: Fri, 9 Apr 2021 16:42:53 +0800 Subject: [PATCH 587/627] fixed wheels position transform in VehicleInfo --- .../src/carla_ros_bridge/ego_vehicle.py | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 3ff585cb..9f65f973 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -11,6 +11,7 @@ """ import math import os +import numpy from std_msgs.msg import Bool # pylint: disable=import-error from std_msgs.msg import ColorRGBA # pylint: disable=import-error @@ -142,12 +143,16 @@ def send_vehicle_msgs(self): wheel_info.radius = wheel.radius wheel_info.max_brake_torque = wheel.max_brake_torque wheel_info.max_handbrake_torque = wheel.max_handbrake_torque - wheel_info.position.x = (wheel.position.x/100.0) - \ - self.carla_actor.get_transform().location.x - wheel_info.position.y = -((wheel.position.y/100.0) - - self.carla_actor.get_transform().location.y) - wheel_info.position.z = (wheel.position.z/100.0) - \ - self.carla_actor.get_transform().location.z + + inv_T = numpy.array(self.carla_actor.get_transform().get_inverse_matrix(), dtype=float) + wheel_pos_in_map = numpy.array([[wheel.position.x/100.0], + [wheel.position.y/100.0], + [wheel.position.z/100.0], + [1.0]]) + wheel_pos_in_ego_vehicle = numpy.matmul(inv_T, wheel_pos_in_map) + wheel_info.position.x = wheel_pos_in_ego_vehicle[0] + wheel_info.position.y = -wheel_pos_in_ego_vehicle[1] + wheel_info.position.z = wheel_pos_in_ego_vehicle[2] vehicle_info.wheels.append(wheel_info) vehicle_info.max_rpm = vehicle_physics.max_rpm From 5c29a411448b75b29b12a99b9fa59ae87b095441 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Mon, 12 Apr 2021 16:48:53 +0200 Subject: [PATCH 588/627] Changes reflect that ROS bridge runs in sync mode by default, settings should be passed as paramters on command line or in launchfile, rviz launchfile no longer available, typo fix ROS -> ROS bridge, ROS bridge not tested in windows --- docs/ros_installation_ros1.md | 2 +- docs/run_ros.md | 25 ++++++++++++++++--------- 2 files changed, 17 insertions(+), 10 deletions(-) diff --git a/docs/ros_installation_ros1.md b/docs/ros_installation_ros1.md index 30caeb95..ad963992 100644 --- a/docs/ros_installation_ros1.md +++ b/docs/ros_installation_ros1.md @@ -10,7 +10,7 @@ This section is a guide on how to install the ROS bridge on Linux for use with R - [__Testing__](#testing) !!! Important - ROS is still [experimental](http://wiki.ros.org/noetic/Installation) for Windows. It has only been tested for Linux systems. + The ROS bridge has not yet been tested in Windows. --- ## Before you begin diff --git a/docs/run_ros.md b/docs/run_ros.md index 63583d1d..6a9b11fb 100644 --- a/docs/run_ros.md +++ b/docs/run_ros.md @@ -9,7 +9,7 @@ The `carla_ros_bridge` package is the main package needed to run the basic ROS b - [__Configuring CARLA settings__](#configuring-carla-settings) - [__Using the ROS bridge in synchronous mode__](#using-the-ros-bridge-in-synchronous-mode) - [__Ego vehicle control__](#ego-vehicle-control) -- [__ROS bridge subscriptions, publications and services__](#ros-bridge-subscriptions-publications-and-services) +- [__ROS API__](#ros-api) - [Subscriptions](#subscriptions) - [Publications](#publications) - [Services](#services) @@ -21,7 +21,7 @@ The ROS bridge supports both ROS 1 and ROS 2 using separate implementations with #### Prepare ROS 1 environment: -The command to run depends on whether you installed ROS via the Debian package or via the source build. You will also need to change the ROS version in the path for the Debian option: +The command to run depends on whether you installed the ROS bridge via the Debian package or via the source build. You will also need to change the ROS version in the path for the Debian option: ```sh # For debian installation of ROS bridge. Change the command according to your installed version of ROS. @@ -52,33 +52,40 @@ Once you have set your ROS environment and have a CARLA server running, you will There are other launchfiles that combine the above functionality of starting the ROS bridge at the same time as starting other packges or plugins: - `carla_ros_bridge_with_example_ego_vehicle.launch` (ROS 1) and `carla_ros_bridge_with_example_ego_vehicle.launch.py` (ROS 2) start the ROS bridge along with the [`carla_spawn_objects`](carla_spawn_objects.md) and [`carla_manual_control`](carla_manual_control.md) packages. -- `carla_ros_bridge_with_rviz.launch` (ROS 1) and `carla_ros_bridge_with_rviz.launch.py` (ROS 2) start the ROS bridge along with the [RVIZ plugin](rviz_plugin.md). --- ## Configuring CARLA settings -Configuration settings can be modified in [`ros-bridge/carla_ros_bridge/config/settings.yaml`](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_bridge/config/settings.yaml). The following settings are available: +Configurations should be set either within the launchfile or passed as an argument when running the file from the command line, for example: + + +```sh +roslaunch carla_ros_bridge carla_ros_bridge.launch passive:=True +``` + +The following settings are available: * __use_sim_time__: This should be set to __True__ to ensure that ROS is using simulation time rather than system time. This parameter will synchronize the ROS [`/clock`][ros_clock] topic with CARLA simulation time. * __host and port__: Network settings to connect to CARLA using a Python client. * __timeout__: Time to wait for a successful connection to the server. * __passive__: Passive mode is for use in scynchronous mode. When enabled, the ROS bridge will take a backseat and another client __must__ tick the world. ROS bridge will wait for all expected data from all sensors to be received. * __synchronous_mode__: - * __If false (default)__: Data is published on every `world.on_tick()` and every `sensor.listen()` callback. - * __If true__: ROS bridge waits for all the sensor messages expected before the next tick. This might slow down the overall simulation but ensures reproducible results. + * __If false__: Data is published on every `world.on_tick()` and every `sensor.listen()` callback. + * __If true (default)__: ROS bridge waits for all the sensor messages expected before the next tick. This might slow down the overall simulation but ensures reproducible results. * __synchronous_mode_wait_for_vehicle_control_command__: In synchronous mode, pauses the tick until a vehicle control is completed. * __fixed_delta_seconds__: Simulation time (delta seconds) between simulation steps. __It must be lower than 0.1__. Take a look at the [documentation](https://carla.readthedocs.io/en/latest/adv_synchrony_timestep/) to learn more about this. * __ego_vehicle__: Role names to identify ego vehicles. Relevant topics will be created so these vehicles will be able to be controlled from ROS. +* __town__: Either use an available CARLA town (eg. 'town01') or an OpenDRIVE file (ending in `.xodr`). [ros_clock]: https://wiki.ros.org/Clock -Most of the above parameters as well as others such as `town` and `rosbag_fname` can also be set within the launchfile `carla_ros_bridge.launch` or passed as an argument when running the file from the command line. When specifying a town, either use an available CARLA town (eg. 'town01') or an OpenDRIVE file (ending in `.xodr`). - --- ## Using the ROS bridge in synchronous mode +The ROS bridge operates in synchronous mode by default. It will wait for all sensor data that is expected within the current frame to ensure reproducible results. + When running multiple clients in synchronous mode, only one client is allowed to tick the world. The ROS bridge will by default be the only client allowed to tick the world unless passive mode is enabled. Enabling passive mode in [`ros-bridge/carla_ros_bridge/config/settings.yaml`](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_bridge/config/settings.yaml) will make the ROS bridge step back and allow another client to tick the world. __Another client must tick the world, otherwise CARLA will freeze.__ If the ROS bridge is not in passive mode (ROS bridge is the one ticking the world), then there are two ways to send step controls to the server: @@ -131,7 +138,7 @@ It is possible to use [AckermannDrive](https://docs.ros.org/en/api/ackermann_msg --- -## ROS bridge subscriptions, publications and services +## ROS API #### Subscriptions From dcd88c6972d5b74383dd2d63e286d8a1b9424996 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Tue, 13 Apr 2021 12:12:19 +0200 Subject: [PATCH 589/627] Clarified that dynamic reconfigure is only available for ROS 1 while the configuration file works in both 1 and 2 --- docs/carla_ackermann_control.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/carla_ackermann_control.md b/docs/carla_ackermann_control.md index abe305b9..c2cbd696 100644 --- a/docs/carla_ackermann_control.md +++ b/docs/carla_ackermann_control.md @@ -15,7 +15,7 @@ The [`carla_ackermann_control` package](https://github.com/carla-simulator/ros-b ### Configuration -Parameters can be set both initially in a [configuration file][ackermanconfig] and during runtime via ROS [dynamic reconfigure][rosdynamicreconfig]. +Parameters can be set both initially in a [configuration file][ackermanconfig] when using both ROS 1 and ROS 2 and during runtime via ROS [dynamic reconfigure][rosdynamicreconfig] in ROS 1. [ackermanconfig]: https://github.com/carla-simulator/ros-bridge/blob/master/carla_ackermann_control/config/settings.yaml [rosdynamicreconfig]: https://wiki.ros.org/dynamic_reconfigure From 917afde559049d8a9f70ebbf0ab82d973f98035f Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 14 Apr 2021 16:20:23 +0200 Subject: [PATCH 590/627] Update homepage with full contents. Typo fix in navbar and included sensor reference link --- docs/index.md | 21 ++++++++++++++------- mkdocs.yml | 3 ++- 2 files changed, 16 insertions(+), 8 deletions(-) diff --git a/docs/index.md b/docs/index.md index eb621904..aa42b149 100644 --- a/docs/index.md +++ b/docs/index.md @@ -11,6 +11,8 @@ The ROS bridge boasts the following features: - Control of AD agents through steering, throttle and brake. - Control of aspects of the CARLA simulation like synchronous mode, playing and pausing the simulation and setting simulation parameters. +--- + ## Get started - [__Installing ROS bridge for ROS 1__](ros_installation_ros1.md) @@ -18,17 +20,22 @@ The ROS bridge boasts the following features: ## Learn about the main ROS bridge package -- [__Carla ROS bridge__](run_ros.md) - The main package required to run the ROS bridge +- [__CARLA ROS bridge__](run_ros.md) - The main package required to run the ROS bridge ## Learn about the additional ROS bridge packages -- [__Carla Spawn Objects__](carla_spawn_objects.md) - Provides a generic way to spawn actors -- [__Carla Manual Control__](carla_manual_control.md)- A ROS-based visualization and control tool for an ego vehicle (similar to carla_manual_control.py provided by CARLA) -- [__Carla Ackerman Control__](carla_ackermann_control.md) - A controller to convert ackermann commands to steer/throttle/brake +- [__CARLA Spawn Objects__](carla_spawn_objects.md) - Provides a generic way to spawn actors +- [__CARLA Manual Control__](carla_manual_control.md)- A ROS-based visualization and control tool for an ego vehicle (similar to `carla_manual_control.py` provided by CARLA) +- [__CARLA Ackerman Control__](carla_ackermann_control.md) - A controller to convert ackermann commands to steer/throttle/brake +- [__CARLA Waypoint Publisher__](carla_waypoint.md) - Publish and query CARLA waypoints +- [__CARLA AD Agent__](carla_ad_agent.md) - An example agent that follows a route, avoids collisions and respects traffic lights +- [__CARLA AD Demo__](carla_ad_demo.md) - An example package that provides everything needed to launch a CARLA ROS environment with an AD vehicle +- [__CARLA ROS Scenario Runner__](carla_ros_scenario_runner.md) - A wrapper to execute OpenScenarios with the CARLA Scenario Runner via ROS +- [__CARLA Twist to Control__](carla_twist_to_control.md) - Convert twist controls to CARLA vehicle controls +- [__RVIZ plugin__](rviz_plugin.md) - An RVIZ plugin to visualize/control CARLA - [__RQT Plugin__](rqt_plugin.md) - A RQT plugin to control CARLA -- [__RVIZ plugin__](rviz_plugin.md) - An RVIZ plugin to visualize/control CARLA. ## Explore the reference material -- [__ROS Sensors__](ros_sensors.md) -- [__ROS messages__](ros_msgs.md) +- [__ROS Sensors__](ros_sensors.md) - Reference topics available in the different sensors +- [__ROS messages__](ros_msgs.md) - Reference parameters available in CARLA ROS messages diff --git a/mkdocs.yml b/mkdocs.yml index ddf3340d..794b1203 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -19,10 +19,11 @@ nav: - CARLA AD Agent: 'carla_ad_agent.md' - CARLA AD Demo: 'carla_ad_demo.md' - CARLA ROS Scenario Runner: 'carla_ros_scenario_runner.md' - - Carla Twist to Control: 'carla_twist_to_control.md' + - CARLA Twist to Control: 'carla_twist_to_control.md' - RVIZ Plugin: 'rviz_plugin.md' - RQT Plugin: 'rqt_plugin.md' - References: + - CARLA sensor reference: 'ros_sensors.md' - CARLA messages reference: 'ros_msgs.md' markdown_extensions: From a02565aacb0156c15be7798fa49830313702551d Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 14 Apr 2021 16:31:26 +0200 Subject: [PATCH 591/627] Removed READMEs for installation of ROS 1 and 2. Removed most info from main README and included link to documentation. --- README.md | 320 +------------------------------------------------ README.ros.md | 99 --------------- README.ros2.md | 60 ---------- 3 files changed, 3 insertions(+), 476 deletions(-) delete mode 100644 README.ros.md delete mode 100644 README.ros2.md diff --git a/README.md b/README.md index 60a39ecc..e0c0d4b4 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@ [![GitHub](https://img.shields.io/github/license/carla-simulator/ros-bridge)](https://github.com/carla-simulator/ros-bridge/blob/master/LICENSE) [![GitHub release (latest by date)](https://img.shields.io/github/v/release/carla-simulator/ros-bridge)](https://github.com/carla-simulator/ros-bridge/releases/latest) -This ROS package aims at providing a simple ROS/ROS2 bridge for CARLA simulator. + This ROS package is a bridge that enables two-way communication between ROS and CARLA. The information from the CARLA server is translated to ROS topics. In the same way, the messages sent between nodes in ROS get translated to commands to be applied in CARLA. ![rviz setup](./docs/images/ad_demo.png "AD Demo") @@ -18,320 +18,6 @@ This ROS package aims at providing a simple ROS/ROS2 bridge for CARLA simulator. - Control AD Agents (Steer/Throttle/Brake) - Control CARLA (Play/pause simulation, Set simulation parameters) -### Additional Functionality +## Getting started and documentation -Beside the bridging functionality, there are many more features provided in separate packages. - -| Name | Description | -| --------------------------------- | ------------------------------------------------------------------------------------------------------- | -| [Carla Spawn Actors](carla_spawn_objects/README.md) | Provides a generic way to spawn actors | -| [Carla Manual Control](carla_manual_control/README.md) | A ROS-based visualization and control tool for an ego vehicle (similar to carla_manual_control.py provided by CARLA) | -| [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API | -| [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. | -| [Carla Ackermann Control](carla_ackermann_control/README.md) | A controller to convert ackermann commands to steer/throttle/brake| -| [Carla AD Agent](carla_ad_agent/README.md) | A basic AD agent, that follows a route, avoids collisions with other vehicles and stops on red traffic lights. | -| [Carla Walker Agent](carla_walker_agent/README.md) | A basic walker agent, that follows a route. | -| [RVIZ Carla Plugin](rviz_carla_plugin/README.md) | A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. | -| [RQT Carla Plugin](rqt_carla_plugin/README.md) | A [RQT](http://wiki.ros.org/rqt) plugin to control CARLA. | - -For a quick overview, after following the [Setup section](#setup), please run the [CARLA AD Demo](carla_ad_demo/README.md). It provides a ready-to-use demonstrator of many of the features. - -## Setup - -ROS and ROS2 are supported by using separate implementations with a [common interface](ros_compatibility). - -Please follow the instructions: - -* [ROS](README.ros.md) -* [ROS2](README.ros2.md) - -## Configuration - -Certain parameters can be set within the launch file [carla_ros_bridge.launch](carla_ros_bridge/launch/carla_ros_bridge.launch). - -If the rolename is within the list specified by argument `ego_vehicle_role_name`, it is interpreted as an controllable ego vehicle and all relevant ROS topics are created. - -### Map - -The bridge is able to load a CARLA map by setting the launch-file parameter ```town```. Either specify an available CARLA Town (e.g. 'Town01') or a OpenDRIVE file (with ending '.xodr'). - -### Mode - -The bridge operates by default in CARLA synchronous mode, waiting for all sensor data that is expected within the current frame to ensure reproducible results. The bridge should only be used in this mode. - -**CAUTION**: In synchronous mode, only one CARLA client is allowed to tick. The ROS bridge will by default be the only client allowed to tick the CARLA server unless passive mode is enabled. Enabling passive mode will make the ROS bridge step back and allow another client to tick the CARLA server. - -Additionally you might set `synchronous_mode_wait_for_vehicle_control_command` to `true` to wait for a vehicle control command before executing the next tick. - -The usage of the asynchronous mode is discouraged. Users may enable this mode running the bridge in the following way: - -```sh -# ROS1 -roslaunch carla_ros_bridge carla_ros_bridge.launch synchronous_mode:=False - -# ROS2 -ros2 launch carla_ros_bridge carla_ros_bridge.launch.py synchronous_mode:=False -``` - - -###### Control Synchronous Mode - -It is possible to control the simulation execution: - -- Pause/Play -- Execute single step - -The following topic allows to control the stepping. - -| Topic | Type | -| ---------------- | ---------------------------------------------------------- | -| `/carla/control` | [carla_msgs.CarlaControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaControl.msg) | - -A [CARLA Control rqt plugin](rqt_carla_control/README.md) is available to publish to the topic. - -## Available ROS Topics - -### Sensors - -Sensor data is provided via topic with prefix `/carla/[]//[]` - -The following sensors are available: - -#### CARLA sensors - -##### RGB camera - -| Topic | Type | -| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla/[]//image` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | -| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | - -##### Depth camera - -| Topic | Type | -| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla/[]//image` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | -| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | - -##### Semantic segmentation camera - -| Topic | Type | -| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla/[]//image` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | -| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | - -##### DVS camera - -| Topic | Type | -| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla/[]//events` | [sensor_msgs.PointCloud2](http://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html) | -| `/carla/[]//image` | [sensor_msgs.Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) | -| `/carla/[]//camera_info` | [sensor_msgs.CameraInfo](http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html) | - -##### Lidar - -| Topic | Type | -| --------------------------------------------------------- | ---------------------------------------------------------------------------------------- | -| `/carla/[]/` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | - -##### Semantic lidar - -| Topic | Type | -| --------------------------------------------------------- | ---------------------------------------------------------------------------------------- | -| `/carla/[]/` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | - -##### Radar - -| Topic | Type | -| -------------------------------------------------------------- | -------------------------------------------------------------------------------------- | -| `/carla/[]/` | [sensor_msgs.PointCloud2](http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html) | - -##### IMU - -| Topic | Type | -| ------------------------ | --------------------------------------------------------------------------------- | -| `/carla/[]/` | [sensor_msgs.Imu](https://docs.ros.org/api/sensor_msgs/html/msg/Imu.html) | - -##### GNSS - -| Topic | Type | Description | -| ------------------------------------------------ | ------------------------------------------------------------------------------------ | --------------------- | -| `/carla/[]/` | [sensor_msgs.NavSatFix](http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html) | publish gnss location | - -##### Collision Sensor - -| Topic | Type | Description | -| ------------------------------ | ------------------------------------------------------------------------ | ------------------------ | -| `/carla/[]/` | [carla_msgs.CarlaCollisionEvent](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaCollisionEvent.msg) | publish collision events | - -##### Lane Invasion Sensor - -| Topic | Type | Description | -| ---------------------------------- | ------------------------------------------------------------------------------ | ------------------------------- | -| `/carla/[]/` | [carla_msgs.CarlaLaneInvasionEvent](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaLaneInvasionEvent.msg) | publish events on lane-invasion | - -#### Pseudo sensors - -##### TF Sensor - -The tf data for the ego vehicle is published when this pseudo sensor is spawned. - -**Note**: Sensors publish the tf data when the measurement is done. The `child_frame_id` corresponds with the prefix of the sensor topics. - -##### Odometry Sensor - -| Topic | Type | Description | -| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla//` | [nav_msgs.Odometry](http://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | odometry of the parent actor | - -##### Speedometer Sensor - -| Topic | Type | Description | -| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla//` | [std_msgs.Float32](http://docs.ros.org/en/api/std_msgs/html/msg/Float32.html) | speed of the parent actor. Units: m/s | - -##### Map Sensor - -| Topic | Type | Description | -| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla/[]/` | [std_msgs.String](http://docs.ros.org/en/api/std_msgs/html/msg/String.html) | provides the OpenDRIVE map as a string on a latched topic. | - -##### Object Sensor - -| Topic | Type | Description | -| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla/[]/` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | publishes all vehicles and walker. If attached to a parent, the parent is not contained. | - -##### Marker Sensor - -| Topic | Type | Description | -| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla/[]/` | [visualization_msgs.Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) | visualization of vehicles and walkers | - -##### Traffic Lights Sensor - -| Topic | Type | Description | -| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla/[]//status` | [carla_msgs.CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightStatusList.msg) | list of all traffic lights with their status | -| `/carla/[]//info` | [carla_msgs.CarlaTrafficLightInfoList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightInfoList.msg) | static information for all traffic lights (e.g. position)| - -##### Actor List Sensor - -| Topic | Type | Description | -| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla/[]/` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaActorList.msg) | list of all carla actors | - -##### Actor Control Sensor - -This pseudo-sensor allows to control the position and velocity of the actor it is attached to (e.g. an ego_vehicle) by publishing pose and velocity within Pose and Twist datatypes. -CAUTION: This control method does not respect the vehicle constraints. It allows movements impossible in the real world, like flying or rotating. -Currently this sensor applies the complete linear vector, but only the yaw from angular vector. - -| Topic | Type | Description | -| ---------------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------------------ | -| `/carla/[]//set_transform` | [geometry_msgs.Pose](https://docs.ros.org/en/api/geometry_msgs/html/msg/Pose.html) | transform to apply to the sensor's parent | -| `/carla/[]//set_target_velocity` | [geometry_msgs.Twist](https://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html) | velocity (angular and linear) to apply to the sensor's parent | - -### Ego Vehicle - -#### Control - -| Topic | Type | -| ----------------------------------------------------------------- | ------------------------------------------------------------------------------ | -| `/carla//vehicle_control_cmd` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | -| `/carla//vehicle_control_cmd_manual` (subscriber) | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | -| `/carla//vehicle_control_manual_override` (subscriber) | [std_msgs.Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html) | -| `/carla//vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleStatus.msg) | -| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleInfo.msg) | - -There are two modes to control the vehicle. - -1. Normal Mode (reading commands from `/carla//vehicle_control_cmd`) -2. Manual Mode (reading commands from `/carla//vehicle_control_cmd_manual`) - -This allows to manually override a Vehicle Control Commands published by a software stack. You can toggle between the two modes by publishing to `/carla//vehicle_control_manual_override`. - -[carla_manual_control](carla_manual_control/) makes use of this feature. - -For testing purposes, you can stear the ego vehicle from the commandline by publishing to the topic `/carla//vehicle_control_cmd`. - -Examples for a ego vehicle with role_name 'ego_vehicle': - -Max forward throttle: - - # for ros1 - rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 0.0}" -r 10 - # for ros2 - ros2 topic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 0.0}" -r 10 - -Max forward throttle with max steering to the right: - - # for ros1 - rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10 - # for ros2 - ros2 topic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10 - -The current status of the vehicle can be received via topic `/carla//vehicle_status`. -Static information about the vehicle can be received via `/carla//vehicle_info` - -##### Carla Ackermann Control - -In certain cases, the [Carla Control Command](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) is not ideal to connect to an AD stack. -Therefore a ROS-based node `carla_ackermann_control` is provided which reads [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) messages. -You can find further documentation [here](carla_ackermann_control/README.md). - -### Other topics - -| Topic | Type | Description | -| ------------------- | -------------------------------------------------------------------------------------------------------- | ------------------------------------- | -| `/carla/weather_control` | [carla_msgs.CarlaWeatherParameters](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWeatherParameters.msg) | set the CARLA weather parameters| - -#### Status of CARLA - -| Topic | Type | Description | -| ------------------- | -------------------------------------------------------------- | ------------------------------------------------------ | -| `/carla/status` | [carla_msgs.CarlaStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaStatus.msg) | | -| `/carla/world_info` | [carla_msgs.CarlaWorldInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWorldInfo.msg) | Info about the CARLA world/level (e.g. OPEN Drive map) | - -#### Walker - -| Topic | Type | Description | -| ---------------------------------------------------- | ---------------------------------------------------------------------------- | ------------------ | -| `/carla//walker_control_cmd` (subscriber) | [carla_msgs.CarlaWalkerControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWalkerControl.msg) | Control a walker | - - -### Debug Marker - -It is possible to draw markers in CARLA. - -Caution: Markers might affect the data published by sensors. - -The following markers are supported in 'map'-frame: - -- Arrow (specified by two points) -- Points -- Cube -- Line Strip - -| Topic | Type | Description | -| ---------------------------------- | ------------------------------------------------------------------------------------------------------ | --------------------------- | -| `/carla/debug_marker` (subscriber) | [visualization_msgs.MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) | draw markers in CARLA world | - -## Troubleshooting - -### ImportError: No module named carla - -You're missing Carla Python. Please execute: - - export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/ - -Please note that you have to put in the complete path to the egg-file including -the egg-file itself. Please use the one, that is supported by your Python version. -Depending on the type of CARLA (pre-build, or build from source), the egg files -are typically located either directly in the PythonAPI folder or in PythonAPI/dist. - -Check the installation is successfull by trying to import carla from python: - - python -c 'import carla;print("Success")' - -You should see the Success message without any errors. +Installation instructions and further documentation of the ROS bridge and additional packages are found [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/). \ No newline at end of file diff --git a/README.ros.md b/README.ros.md deleted file mode 100644 index 2102b34b..00000000 --- a/README.ros.md +++ /dev/null @@ -1,99 +0,0 @@ -# ROS - -## Setup - -### For Users - -First add the apt repository: - -```shell -sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 1AF1527DE64CB8D9 -sudo add-apt-repository "deb [arch=amd64] http://dist.carla.org/carla $(lsb_release -sc) main" -``` - -Then simply install the ROS bridge: - -```shell -sudo apt-get update -sudo apt-get install carla-ros-bridge -``` - -This will install carla-ros-bridge in `/opt/carla-ros-bridge` - -#### Note - -Currently, the debian package is only available for ROS melodic. Please, follow the Developer instructions if you want to use any other supported distribution. - -To check the different bridge versions available in the apt repository run: - -```shell -apt-cache madison carla-ros-bridge -``` - -### For Developers - -Create a catkin workspace and install carla_ros_bridge package - -```shell -# setup folder structure -mkdir -p ~/carla-ros-bridge/catkin_ws/src && cd ~/carla-ros-bridge -git clone --recurse-submodules https://github.com/carla-simulator/ros-bridge.git catkin_ws/src/ros-bridge -source /opt/ros//setup.bash -cd catkin_ws - -# install required ros-dependencies -rosdep update -rosdep install --from-paths src --ignore-src -r - -# build -catkin build # alternatively catkin_make -``` - -For more information about configuring a ROS environment see - - -## Start the ROS bridge - -First run the simulator (see carla documentation: ) - -```shell -# run carla in background -SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl - -# Add the carla modules to your python environment -export CARLA_ROOT= -export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg -``` - -### For Users - -```shell -source /opt/carla-ros-bridge//setup.bash -``` - -### For Developers - -```shell -source ~/carla-ros-bridge/catkin_ws/devel/setup.bash -``` - -Start the ros bridge (choose one option): - -```shell -# Option 1: start the ros bridge -roslaunch carla_ros_bridge carla_ros_bridge.launch - -# Option 2: start the ros bridge together with an example ego vehicle -roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch -``` - -## Testing - -To execute the tests, using catkin, use the following commands: - -```shell -# build -catkin build -DCATKIN_ENABLE_TESTING=0 -# run -rostest carla_ros_bridge ros_bridge_client.test -``` diff --git a/README.ros2.md b/README.ros2.md deleted file mode 100644 index b9adca9c..00000000 --- a/README.ros2.md +++ /dev/null @@ -1,60 +0,0 @@ -# ROS2 - -Currently supported: [ROS2 Foxy](https://index.ros.org/doc/ros2/Releases/Release-Foxy-Fitzroy/) - -## Setup - -Colcon and ROS2 Foxy need to be installed on your system. - -```shell -# setup folder structure -mkdir -p ~/carla-ros-bridge && cd ~/carla-ros-bridge -git clone --recurse-submodules https://github.com/carla-simulator/ros-bridge.git src/ros-bridge -source /opt/ros/foxy/setup.bash - -# install required ros-dependencies -rosdep update -rosdep install --from-paths src --ignore-src -r - -# build -colcon build -``` - -For more information about configuring a ROS2 environment see - - -## Start the ROS bridge - -First run the simulator (see CARLA documentation: ) - -```shell -# run carla in background -SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl - -# Add the carla modules to your python environment -export CARLA_ROOT= -export PYTHONPATH=$PYTHONPATH:$CARLA_ROOT/PythonAPI/carla/dist/carla-.egg:$CARLA_ROOT/PythonAPI/carla - -source ./install/setup.bash -``` - -Start the ros bridge (choose one option): - -```shell -# Option 1: start the ros bridge -ros2 launch carla_ros_bridge carla_ros_bridge.launch.py - -# Option 2: start the ros bridge together with an example ego vehicle -ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py -``` - -## Testing - -To execute the tests using colcon, use the following commands: - -```shell -# build -colcon build --packages-up-to carla_ros_bridge -# run -launch_test carla_ros_bridge/test/ros_bridge_client_ros2_test.py -``` From 6951952a00799093607bd0c0cff981fed252c909 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 14 Apr 2021 16:53:17 +0200 Subject: [PATCH 592/627] Replaced README information with links to the relevant parts of the documentation --- carla_ackermann_control/README.md | 45 +------------------- carla_ad_agent/README.md | 38 +---------------- carla_ad_demo/README.md | 45 +------------------- carla_manual_control/README.md | 18 +------- carla_ros_scenario_runner/README.md | 64 +---------------------------- carla_spawn_objects/README.md | 58 +------------------------- carla_twist_to_control/README.md | 15 +------ carla_waypoint_publisher/README.md | 42 +------------------ rqt_carla_control/README.md | 8 +--- rviz_carla_plugin/README.md | 58 +------------------------- 10 files changed, 13 insertions(+), 378 deletions(-) diff --git a/carla_ackermann_control/README.md b/carla_ackermann_control/README.md index a6479089..0928ab91 100644 --- a/carla_ackermann_control/README.md +++ b/carla_ackermann_control/README.md @@ -1,44 +1,3 @@ -# Carla Ackermann Control +# CARLA Ackermann Control -ROS Node to convert [AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) messages to [CarlaEgoVehicleControl](carla_ros_bridge/msg/CarlaEgoVehicleControl.msg). - -- A PID controller is used to control the acceleration/velocity. -- Reads the Vehicle Info, required for controlling from Carla (via carla ros bridge) - -## Prerequisites - - #install python simple-pid - pip install --user simple-pid - -### Configuration - -Initial parameters can be set via [configuration file](config/settings.yaml). - -In ROS1, it is possible to modify the parameters during runtime via the `dynamic reconfigure` package. - -## Available Topics - -| Topic | Type | Description | -| --------------------------------------------------- | ---------------------------------------------------------------------------------------------------- | ------------------------------------------------------------- | -| `/carla//ackermann_cmd` (subscriber) | [ackermann_msgs.AckermannDrive](http://docs.ros.org/api/ackermann_msgs/html/msg/AckermannDrive.html) | Subscriber for stearing commands | -| `/carla//ackermann_control/control_info` | [carla_ackermann_control.EgoVehicleControlInfo](msg/EgoVehicleControlInfo.msg) | The current values used within the controller (for debugging) | - -The role name is specified within the configuration. - -### Test control messages - -You can send command to the car using the topic `/carla//ackermann_cmd`. - -Examples for a ego vehicle with role_name 'ego_vehicle': - -Forward movements, speed in in meters/sec. - - rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0.0, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, - jerk: 0.0}" -r 10 - -Forward with steering - - rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 1.22, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, - jerk: 0.0}" -r 10 - -Info: the steering_angle is the driving angle (in radians) not the wheel angle. +Find documentation about the CARLA Ackermann Control package [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/carla_ackermann_control/). diff --git a/carla_ad_agent/README.md b/carla_ad_agent/README.md index be79391d..5e5cdee6 100644 --- a/carla_ad_agent/README.md +++ b/carla_ad_agent/README.md @@ -1,39 +1,3 @@ # CARLA AD Agent -An AD agent that can follow a given route. - -It avoids crashs with other vehicles and respects the state of the traffic lights by accessing the ground truth data. - -For a more comprehensive solution, have a look at [Autoware](https://www.autoware.ai/). - -## Subscriptions - -| Topic | Type | Description | -| ---------------------------------- | ------------------- | --------------------------- | -| `/carla//waypoints` | [nav_msgs.Path](http://docs.ros.org/api/nav_msgs/html/msg/Path.html) | Route to follow | -| `/carla//target_speed` | [std_msgs.Float64](http://docs.ros.org/api/std_msgs/html/msg/Float64.html) | Target speed | -| `/carla//odometry` | [nav_msgs.Odometry](http://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | localization of ego vehicle | - -For risk avoidance, more subscriptions are required: - -| Topic | Type | Description | -| ---------------------------------- | ------------------- | --------------------------- | -| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleInfo.msg) | Identify the carla actor id of the ego vehicle | -| `/carla//objects` | [derived_object_msgs.ObjectArray](http://docs.ros.org/api/derived_object_msgs/html/msg/ObjectArray.html) | Information about other actors | -| `/carla/actor_list` | [carla_msgs.CarlaActorList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaActorList.msg) | Actor list | -| `/carla/world_info` | [carla_msgs.CarlaWorldInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaWorldInfo.msg) | Selects mode for traffic lights (US- or Europe-style) | -| `/carla/traffic_lights/status` | [carla_msgs.CarlaTrafficLightStatusList](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaTrafficLightStatusList.msg) | Get the current state of the traffic lights | - -## Publications - -| Topic | Type | Description | -| ---------------------------------- | ------------------- | --------------------------- | -| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | Vehicle control command | - -## Local Planner Node - -Internally, the CARLA AD Agent uses a separate node for [local planning](src/carla_ad_agent/local_planner.py). - -This is currently optimized for `vehicle.tesla.model3`, as it does not have any gear shift delays. - -The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedia.org/wiki/Ziegler%E2%80%93Nichols_method). +Find documentation about the CARLA AD Agent package [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/carla_ad_agent/). diff --git a/carla_ad_demo/README.md b/carla_ad_demo/README.md index a2b62ae0..9ce5c049 100644 --- a/carla_ad_demo/README.md +++ b/carla_ad_demo/README.md @@ -1,46 +1,3 @@ # CARLA AD Demo -This meta package provides everything to launch a CARLA ROS environment with an AD vehicle. - -![CARLA AD Demo](../docs/images/ad_demo.png "AD Demo in Rviz") - -## Startup - - export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ - export SCENARIO_RUNNER_PATH= - - # ROS 1 - roslaunch carla_ad_demo carla_ad_demo.launch - - # ROS 2 - ros2 launch carla_ad_demo carla_ad_demo.launch.py - -### Modes - -#### Following A Random Route - -On startup, an ego vehicle is spawned and follows a random route to a goal. - -You might want to spawn additional vehicles (or pedestrians) by manually executing: - - /PythonAPI/examples/spawn_npc.py - -You can modify start position and goal within the [launch file](launch/carla_ad_demo.launch). The route is currently randomly (regarding the left/right turns) calculated. - -#### Scenario Execution - -If you prefer to execute a predefined scenario, launch: - - # ROS1 - roslaunch carla_ad_demo carla_ad_demo_with_scenario.launch - - # ROS2 - ros2 launch carla_ad_demo carla_ad_demo_with_scenario.launch.py - -Select to example scenario "FollowLeadingVehicle" within the RVIZ Carla Plugin and press "Execute". The ego vehicle gets repositioned and the scenario is processed. - -You can specify your own scenarios by publishing to `/carla/available_scenarios`. See the [launch file](launch/carla_ad_demo_with_scenario.launch) for an example. - -##### Troubleshooting - -- If the example scenario fails, please analyze the ros log and follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working standalone. +Find documentation about the CARLA AD Demo [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/carla_ad_demo/). diff --git a/carla_manual_control/README.md b/carla_manual_control/README.md index 71c67ee6..bb8c4303 100644 --- a/carla_manual_control/README.md +++ b/carla_manual_control/README.md @@ -1,17 +1,3 @@ -# Carla Manual Control +# CARLA Manual Control -The node `carla_manual_control` is a ROS-only version of the Carla `manual_control.py`. All data is received -via ROS topics. - -## Prerequisites - -To be able to use `carla_manual_control`, some sensors need to be attached to the ego vehicle: - -- to display an image: a camera with role-name 'view' and resolution 800x600 -- to display the current gnss position: a gnss sensor with role-name 'gnss1' -- to get a notification on lane invasions: a lane invasion sensor -- to get a notification on lane invasions: a collision sensor - -## Manual steering - -In order to steer manually, press 'B'. This will toggle manual-driving mode within carla_ros_bridge. +Find documentation about the CARLA Manual Control package [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/carla_manual_control/). diff --git a/carla_ros_scenario_runner/README.md b/carla_ros_scenario_runner/README.md index eb50be5f..74aedeb3 100644 --- a/carla_ros_scenario_runner/README.md +++ b/carla_ros_scenario_runner/README.md @@ -1,65 +1,3 @@ # ROS Scenario Runner -This is a wrapper to execute OpenScenarios with the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) via ROS. - -It is best used from within the [rviz_carla_plugin](../rviz_carla_plugin). - -Currently it is not supported to switch the CARLA Town. Therefore the scenario needs to use the currently active Town. - -Please have a look at the [example scenario](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ad_demo/config/FollowLeadingVehicle.xosc), especially at the way the ros-controller is set up. - - - - - - - - - -By this section within the openscenario definition, an instance of `carla_ad_agent` is launched (i.e. `roslaunch ..` is executed). Any additional `` is appened as ros parameter (name:=value). - -## Setup - -Please follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) and verify, that scenario_runner is working, if started manually. - -Additionally, please execute: - - sudo apt install python-pexpect - -## Startup - -The environment variables are forwarded to scenario_runner, therefore set them to: - - export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ - -### Using ROS1 - -To run the ROS node: - - roslaunch carla_ros_scenario_runner carla_ros_scenario_runner.launch scenario_runner_path:= - -To run a scenario from command line: - - rosservice call /scenario_runner/execute_scenario "{ 'scenario': { 'scenario_file': '' } }" - -### Using ROS2 - -To run the ROS node: - - ros2 launch carla_ros_scenario_runner carla_ros_scenario_runner.launch.py scenario_runner_path:= - -To run a scenario from command line: - - ros2 service call /scenario_runner/execute_scenario carla_ros_scenario_runner_types/srv/ExecuteScenario "{ 'scenario': { 'scenario_file': '' } }" - -## Available services - -| Service | Description | Type | -| ----------------------------------------------------------- | ----------- | -------------------------------------------------------------------- | -| `/scenario_runner/execute_scenario` | Execute a scenario. If another scenario is currently running, it gets stopped. | [carla_ros_scenario_runner_types.ExecuteScenario](../carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | - -## Available topics - -| Topic | Description | Type | -| ------------------------------------- | ----------- | -------------------------------------------------------------------- | -| `/scenario_runner/status` | The current status of the scenario runner execution (e.g. used by the [rviz_carla_plugin](../rviz_carla_plugin)) | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | +Find documentation about the ROS Scenario Runner package [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/carla_ros_scenario_runner/). diff --git a/carla_spawn_objects/README.md b/carla_spawn_objects/README.md index 73c65fbb..757df65c 100644 --- a/carla_spawn_objects/README.md +++ b/carla_spawn_objects/README.md @@ -1,57 +1,3 @@ -# ROS Carla Spawn Objects +# CARLA Spawn Objects -`carla_spawn_objects` can be used to spawn actors (vehicles, sensors, walkers) with attached sensors. - -Info: To be able to use `carla_manual_control` a camera with role-name 'view' and resolution of 800x600 is required. - -If no specific position is set for vehicles, they will be spawned at a random position. - -## Spawning at specific position - -- It is possible to specify the position at which the vehicle will be spawned, by defining a ros parameter named `spawn_point_`, with `` specified in the `id` field of the vehicle, in the config file. -- It is also possible to specify the initial position directly in the config file. This is also how the initial positions of sensors should be declared. -- The `spawn_point` specified for a sensor attached to a vehicle, will be considered relative to the vehicle. - -It is possible to re-spawn a vehicle at a specific location by publishing to `/carla///initialpose`, but only if an `actor.pseudo.control` pseudo-actor (with id ``) is attached to the vehicle. The node `set_initial_pose` should also be running to handle the message on the topic. It can be launched using [set_initial_pose.launch](launch/set_initial_pose.launch), and `` should be specified by setting the ros parameter called `controller_id`. - -The preferred way to publish the new pose message is to use RVIZ: - -![Autoware Runtime Manager Settings](../docs/images/rviz_set_start_goal.png) - -Selecting a Pose with '2D Pose Estimate' will delete the current ego_vehicle and respawn it at the specified position. - -## Attach sensor to an existing vehicle - -It possible to attach sensors to an existing vehicle. To do so, a `sensor.pseudo.actor_list` should also be spawned (define it in the config file) to give access to a list of active actors. The ROS parameter `spawn_sensors_only` should also be set to True. `carla_spawn_objects` will then check if an actor with same id and type as the one specified in its config file is already active, and if yes attach the sensors to this actor. - -## Create your own sensor setup - -Sensors, attached to vehicles or not, can be defined via a json file. `carla_spawn_objects` reads it from the file location defined via the private ros parameter `objects_definition_file`. - -The format is defined like that: - -```json -{ "actors" = [ - { - "type": "", - "id": "", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - - }, - { - "type": "", - "id": "", - "spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0}, - "sensors": - [ - - ] - } - ... - ] -} -``` - -Define sensors with their attributes as described in the Carla Documentation about [Cameras and Sensors](https://github.com/carla-simulator/carla/blob/master/Docs/cameras_and_sensors.md). - -An example is provided by [carla_example_ego_vehicle.launch](launch/carla_example_ego_vehicle.launch). It uses the sensors from [objects.json](config/objects.json) +Find documentation about the CARLA Spawn Objects package [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/carla_spawn_objects/). diff --git a/carla_twist_to_control/README.md b/carla_twist_to_control/README.md index 298c9f0c..7e367637 100644 --- a/carla_twist_to_control/README.md +++ b/carla_twist_to_control/README.md @@ -1,16 +1,3 @@ # Twist to Vehicle Control conversion -This node converts a [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) to [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) - -## Subscriptions - -| Topic | Type | Description | -| ---------------------------------- | ------------------- | --------------------------- | -| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleInfo.msg) | Ego vehicle info, to receive max steering angle | -| `/carla//twist` | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | Twist to convert | - -## Publications - -| Topic | Type | Description | -| ---------------------------------- | ------------------- | --------------------------- | -| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleControl.msg) | Converted vehicle control command | +Find documentation about the CARLA Twist to Control package [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/carla_twist_to_control/). diff --git a/carla_waypoint_publisher/README.md b/carla_waypoint_publisher/README.md index 24190c98..e2f230bd 100644 --- a/carla_waypoint_publisher/README.md +++ b/carla_waypoint_publisher/README.md @@ -1,43 +1,3 @@ # Carla Waypoint Publisher -Carla supports waypoint calculations. -The node `carla_waypoint_publisher` makes this feature available in the ROS context. - -It uses the current pose of the ego vehicle with role-name "ego_vehicle" as starting point. If the -vehicle is respawned or moved, the route is newly calculated. - -Additionally, services are provided to query CARLA waypoints. - -## Startup - -As the waypoint publisher requires some Carla PythonAPI functionality that is not part of the python egg-file, you -have to extend your PYTHONPATH. - - export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg:/PythonAPI/carla/ - -To run it: - - roslaunch carla_waypoint_publisher carla_waypoint_publisher.launch - -## Set a goal - -The goal is either read from the ROS topic `/carla//goal`, if available, or a fixed spawn point is used. - -The preferred way of setting a goal is to click '2D Nav Goal' in RVIZ. - -![set goal](../docs/images/rviz_set_start_goal.png) - -## Published waypoints - -The calculated route is published: - -| Topic | Type | -| ------------------------------------- | -------------------------------------------------------------------- | -| `/carla//waypoints` | [nav_msgs.Path](http://docs.ros.org/api/nav_msgs/html/msg/Path.html) | - -## Available services - -| Service | Description | Type | -| ----------------------------------------------------------- | ----------- | -------------------------------------------------------------------- | -| `/carla_waypoint_publisher//get_waypoint` | Get the waypoint for a specific location | [carla_waypoint_types.GetWaypoint](../carla_waypoint_types/srv/GetWaypoint.srv) | -| `/carla_waypoint_publisher//get_actor_waypoint` | Get the waypoint for an actor id | [carla_waypoint_types.GetActorWaypoint](../carla_waypoint_types/srv/GetActorWaypoint.srv) | +Find documentation about the CARLA Waypoint Publisher package [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/carla_waypoint/). \ No newline at end of file diff --git a/rqt_carla_control/README.md b/rqt_carla_control/README.md index 44e6b43c..2267f680 100644 --- a/rqt_carla_control/README.md +++ b/rqt_carla_control/README.md @@ -1,9 +1,3 @@ # CARLA Control RQT Plugin -If `carla_ros_bridge` is configured in synchronous-mode, this plugin can be used to control the stepping. - -## Startup - -You can start it e.g.: - - rqt --standalone rqt_carla_control +Find documentation about the CARLA Control RQT Plugin [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/rqt_plugin/). \ No newline at end of file diff --git a/rviz_carla_plugin/README.md b/rviz_carla_plugin/README.md index 80bd1692..dcb80680 100644 --- a/rviz_carla_plugin/README.md +++ b/rviz_carla_plugin/README.md @@ -1,59 +1,3 @@ # RVIZ CARLA Control -A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. - -![CARLA AD Demo](../docs/images/rviz_carla_plugin.png "rviz carla plugin") - -This plugin is expecting a ego vehicle named `ego_vehicle`. - -## Features - -### Provide the RVIZ view pose to other nodes - -When a `actor.pseudo.control` is attached to a camera (using the [carla_spawn_objects](../carla_spawn_objects) node), it allows to move the camera around in the CARLA world, by publishing a Pose message. - -### Visualize the current ego vehicle state - -The current vehicle state is visualized: - -- Vehicle Control -- Position - -### Allows manually overriding the ego vehicle vehicle control - -By using the drive-widget from the [RVIZ Visualization Tutorials](https://github.com/ros-visualization/visualization_tutorials) and a [node to convert from twist to vehicle control](../carla_twist_to_control) it is possible to steer the ego vehicle by mouse. - -### Execute a scenario - -By using [carla_ros_scenario_runner](../carla_ros_scenario_runner), it is possible to trigger scenarios from within RVIZ. - -### Play/Pause the simulation (if started in synchronous mode) - -Similar to the [rqt CARLA plugin](../rqt_carla_plugin), it's possible to control the CARLA world, if synchronous mode is active. - -## Topics - -### Subscriptions - -| Topic | Type | Description | -| ------------------- | ------------------------- | ------------------------------------------------------ | -| `/carla/status` | [carla_msgs.CarlaStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaStatus.msg) | Read the status of CARLA, to enable/disable the UI | -| `/carla/ego_vehicle/vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaEgoVehicleStatus.msg) | To display the current state of the ego vehicle | -| `/carla/ego_vehicle/odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | To display the current pose of the ego vehicle | -| `/scenario_runner/status` | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | To visualize the scenario runner status | -| `/carla/available_scenarios` | [carla_ros_scenario_runner_types.CarlaScenarioList](../carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg) | For providing a list of scenarios to execute (disabled in combo box) | - -### Publications - -| Topic | Type | Description | -| ------------------- | ------------------------- | ------------------------------------------------------ | -| `/carla/control` | [carla_msgs.CarlaControl](https://github.com/carla-simulator/ros-carla-msgs/tree/master/msg/CarlaControl.msg) | Start/pause CARLA | -| `/carla/ego_vehicle/spectator_pose` | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | Publish the current pose of the RVIZ camera view. | -| `/carla/ego_vehicle/vehicle_control_manual_override` | [std_msgs.Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html) | To enable/disable the overriding of the vehicle control | -| `/carla/ego_vehicle/twist` | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | The twist command, created via mouse | - -### Service Client - -| Service | Type | Description | -| ----------------------------------------------------------- | ---- | ------------------------------------------------------------------- | -| `/scenario_runner/execute_scenario` | [carla_ros_scenario_runner_types.ExecuteScenario](../carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | Execute the selected scenario | +Find documentation about the CARLA RVIZ plugin [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/rviz_plugin/). \ No newline at end of file From 0fb7aec8fe6d667262e1fc48b0b164160101e998 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Wed, 14 Apr 2021 18:03:49 +0200 Subject: [PATCH 593/627] Add pcl recorder section to docs and changed README to point to that section --- docs/index.md | 1 + docs/pcl_recorder.md | 44 ++++++++++++++++++++++++++++++++++++++++++ mkdocs.yml | 1 + pcl_recorder/README.md | 36 +--------------------------------- 4 files changed, 47 insertions(+), 35 deletions(-) create mode 100644 docs/pcl_recorder.md diff --git a/docs/index.md b/docs/index.md index aa42b149..cf64684f 100644 --- a/docs/index.md +++ b/docs/index.md @@ -34,6 +34,7 @@ The ROS bridge boasts the following features: - [__CARLA Twist to Control__](carla_twist_to_control.md) - Convert twist controls to CARLA vehicle controls - [__RVIZ plugin__](rviz_plugin.md) - An RVIZ plugin to visualize/control CARLA - [__RQT Plugin__](rqt_plugin.md) - A RQT plugin to control CARLA +- [__PCL Recorder__](pcl_recorder.md) - Create point cloud maps from data captured from simulations ## Explore the reference material diff --git a/docs/pcl_recorder.md b/docs/pcl_recorder.md new file mode 100644 index 00000000..dad12d5b --- /dev/null +++ b/docs/pcl_recorder.md @@ -0,0 +1,44 @@ +# Point Cloud Map Creation + +The PCL recorder package allows you to create point cloud maps from CARLA maps. + +--- + +## Before you begin + +Install the `pcl-tools` library: + +```sh +sudo apt install pcl-tools +``` + +--- + +## Using the PCL recorder + +The PCL recorder package will spawn an ego vehicle that can be controlled with the keyboard or via the autopilot functionality within the Carla PythonAPI. + +__1.__ After starting a CARLA server, in a new terminal run the following command to launch the PCL recorder package: + +```sh +# ROS 1 +roslaunch pcl_recorder pcl_recorder.launch + +# ROS 2 +ros2 launch pcl_recorder pcl_recorder.launch.py +``` +__2.__ When the capture drive is finished, reduce the overall size of the point cloud: + +``` +# Create one point cloud file +pcl_concatenate_points_pcd /tmp/pcl_capture/*.pcd + +# Filter duplicates +pcl_voxel_grid -leaf 0.1,0.1,0.1 output.pcd map.pcd +``` + +__3.__ Verify the result: + +```sh +pcl_viewer map.pcd +``` diff --git a/mkdocs.yml b/mkdocs.yml index 794b1203..4db903f2 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -22,6 +22,7 @@ nav: - CARLA Twist to Control: 'carla_twist_to_control.md' - RVIZ Plugin: 'rviz_plugin.md' - RQT Plugin: 'rqt_plugin.md' + - PCL Recorder: 'pcl_recorder.md' - References: - CARLA sensor reference: 'ros_sensors.md' - CARLA messages reference: 'ros_msgs.md' diff --git a/pcl_recorder/README.md b/pcl_recorder/README.md index a60ffee6..e8f162f1 100644 --- a/pcl_recorder/README.md +++ b/pcl_recorder/README.md @@ -1,37 +1,3 @@ # Point Cloud Map Creation -Create point cloud maps for Carla Levels. - -The point clouds are created by driving around with an ego vehicle, using the autopilot functionality within the Carla PythonAPI. - -## Setup - -See setup of carla-ros-bridge. - -## Run - -Execute the Carla Simulator and the Pcl-Recorder. - - #Terminal 1 - - #execute Carla - SDL_VIDEODRIVER=offscreen /CarlaUE4.sh /Game/Carla/Maps/Town01 -benchmark -fps=20 - - #Terminal 2 - - #Execute the PCL Capturing - #The captured point clouds are saved to /tmp/pcl_capture directory. - export PYTHONPATH=/PythonAPI/carla/dist/carla-.egg:/PythonAPI/carla/ - source /devel/setup.bash - roslaunch pcl_recorder pcl_recorder.launch - -When the capture drive is done, you can reduce the overall size of the point cloud. - - #create one point cloud file - pcl_concatenate_points_pcd /tmp/pcl_capture/*.pcd - - #filter duplicates - pcl_voxel_grid -leaf 0.1,0.1,0.1 output.pcd map.pcd - - #verify the result - pcl_viewer map.pcd +Find documentation about the PCL recorder package [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/pcl_recorder/). \ No newline at end of file From 13d1d51316576e31e78a46fd5a226664993c5471 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Thu, 15 Apr 2021 12:43:30 +0200 Subject: [PATCH 594/627] Added section to docs about ROS compatibility node. Replaced info from README with a link to the docs. Updated index and navbar --- docs/index.md | 7 +++++++ docs/pcl_recorder.md | 2 +- docs/ros_compatibility.md | 18 ++++++++++++++++++ mkdocs.yml | 1 + ros_compatibility/README.md | 14 +------------- 5 files changed, 28 insertions(+), 14 deletions(-) create mode 100644 docs/ros_compatibility.md diff --git a/docs/index.md b/docs/index.md index cf64684f..918e2f66 100644 --- a/docs/index.md +++ b/docs/index.md @@ -18,9 +18,14 @@ The ROS bridge boasts the following features: - [__Installing ROS bridge for ROS 1__](ros_installation_ros1.md) - [__Installing ROS bridge for ROS 2__](ros_installation_ros2.md) +--- + ## Learn about the main ROS bridge package - [__CARLA ROS bridge__](run_ros.md) - The main package required to run the ROS bridge +- [__ROS Compatiblity Node__](ros_compatibility.md) - The interface that allows the same API to call either ROS 1 or ROS 2 functions + +--- ## Learn about the additional ROS bridge packages @@ -36,6 +41,8 @@ The ROS bridge boasts the following features: - [__RQT Plugin__](rqt_plugin.md) - A RQT plugin to control CARLA - [__PCL Recorder__](pcl_recorder.md) - Create point cloud maps from data captured from simulations +--- + ## Explore the reference material - [__ROS Sensors__](ros_sensors.md) - Reference topics available in the different sensors diff --git a/docs/pcl_recorder.md b/docs/pcl_recorder.md index dad12d5b..543f4b18 100644 --- a/docs/pcl_recorder.md +++ b/docs/pcl_recorder.md @@ -1,6 +1,6 @@ # Point Cloud Map Creation -The PCL recorder package allows you to create point cloud maps from CARLA maps. +The [PCL recorder package](https://github.com/carla-simulator/ros-bridge/tree/master/pcl_recorder) allows you to create point cloud maps from CARLA maps. --- diff --git a/docs/ros_compatibility.md b/docs/ros_compatibility.md new file mode 100644 index 00000000..5d40e88f --- /dev/null +++ b/docs/ros_compatibility.md @@ -0,0 +1,18 @@ +# ROS Compatiblity Node + +The [ROS compatibility node](https://github.com/carla-simulator/ros-bridge/tree/master/ros_compatibility) is an interface that allows packages to be used seamlessly with both ROS 1 and ROS 2. Depending on the environment variable `ROS_VERSION`, the same API will call either ROS 1 or ROS 2 functions. It is used by creating classes that inherit from the `CompatibleNode`. + +--- + +## ROS parameters + +Parameters need to be declared before being set or accessed in ROS 2 by default. This is not the case in ROS 1. In order to keep both ROS 1 and ROS 2 modes working in a similar way, the parameter `allow_undeclared_parameters` is set to `True` in the ROS 2 version of the `CompatibleNode`, allowing the use of parameters without declaring them beforehand. + +--- + +## Services + +In ROS 2, services can be called asynchronously. This is not the case in ROS 1. Consequently, the `call_service()` method of the ROS 2 version waits for the server's response after calling it asynchronously, in order to mimic the ROS 1 synchronous behavior. + +!!! Warning + While waiting for the response, the ROS 2 `call_service()` methods spins the node. This can cause problems (errors or deadlocks) if another thread spins the same node in parallel. diff --git a/mkdocs.yml b/mkdocs.yml index 4db903f2..98279579 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -11,6 +11,7 @@ nav: - Install ROS Bridge for ROS 1: 'ros_installation_ros1.md' - Install ROS Bridge for ROS 2: 'ros_installation_ros2.md' - The ROS bridge package: 'run_ros.md' + - ROS Compatiblity Node: 'ros_compatibility.md' - ROS Bridge Packages: - CARLA Spawn Objects: 'carla_spawn_objects.md' - CARLA Manual Control: 'carla_manual_control.md' diff --git a/ros_compatibility/README.md b/ros_compatibility/README.md index 276ed9bc..7e4b3c6a 100644 --- a/ros_compatibility/README.md +++ b/ros_compatibility/README.md @@ -1,15 +1,3 @@ # ROS compatibility node -This acts as an interface over ROS1 and ROS2 to allow nodes to be used seamlessly with both versions. -Depending on the environment variable `ROS_VERSION`, the same api will call either ROS1 or ROS2 functions. -It is used by creating classes that inherit from the `CompatibleNode`. - -## ROS parameters - -By default in ROS2, parameters need to be declared before being set or accessed, which is not the case in ROS1. In order to keep both ROS1 and ROS2 modes working in a similar way, the parameter `allow_undeclared_parameters` is set to True in the ROS2 version of the `CompatibleNode`, allowing to use parameters without declaring them beforehand. - -## Services - -In ROS2 services can be called asynchronously, this is not the case in ROS1. Consequently, the `call_service()` method of the ROS2 version waits for the server's response after calling it asynchronously, in order to mimic the ROS1 synchronous behavior. - -WARNING: While waiting for the response, the ROS2 `call_service()` methods spins the node. This can cause problems (errors or deadlocks) if another thread spins the same node in parallel. +Find documentation about the CARLA ROS compatibility node [__here__](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_compatibility/). \ No newline at end of file From 7131891ff972caf77de8816efa78cbe0bebc78a7 Mon Sep 17 00:00:00 2001 From: corkyw10 Date: Thu, 15 Apr 2021 13:11:50 +0200 Subject: [PATCH 595/627] Updated CARLA version requisite for ROS 2 to be 0.9.11 or later --- docs/ros_installation_ros2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/ros_installation_ros2.md b/docs/ros_installation_ros2.md index 22517390..3835e1ba 100644 --- a/docs/ros_installation_ros2.md +++ b/docs/ros_installation_ros2.md @@ -19,7 +19,7 @@ You will need to fulfill the following software requirements before using the RO - Install ROS: - [__ROS 2 Foxy__](https://docs.ros.org/en/foxy/Installation.html) — For Ubuntu 20.04 (Focal) - Additional ROS packages may be required depending on your needs. [rviz](https://wiki.ros.org/rviz) is highly recommended to visualize ROS data. -- CARLA 0.9.7 or later — Previous versions are not compatible with the ROS bridge. Follow the [quick start installation](https://carla.readthedocs.io/en/latest/start_quickstart/) or make the build for [Linux](https://carla.readthedocs.io/en/latest/build_linux/). It is recommended to match the ROS bridge version to the CARLA version when possible. +- CARLA 0.9.11 or later — Previous versions are not compatible with the ROS bridge. Follow the [quick start installation](https://carla.readthedocs.io/en/latest/start_quickstart/) or make the build for [Linux](https://carla.readthedocs.io/en/latest/build_linux/). It is recommended to match the ROS bridge version to the CARLA version when possible. --- From 6cc11c99762c4c5bf35333bd6e2a7e24f3fafd59 Mon Sep 17 00:00:00 2001 From: Bernd Gassmann Date: Thu, 15 Apr 2021 17:06:34 +0200 Subject: [PATCH 596/627] Fix actor_factory Fix: Actor factory uses correct actor transform also if no parent is set. Fix: ego_vehicle: explicitly cast numpy to float values Feature: support an empty controller_launch command --- carla_ros_bridge/src/carla_ros_bridge/actor_factory.py | 8 ++++---- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 6 +++--- .../src/carla_ros_scenario_runner/ros_vehicle_control.py | 7 ++++--- 3 files changed, 11 insertions(+), 10 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 03a18321..94a6a3c1 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -224,15 +224,15 @@ def _create_object_from_actor(self, carla_actor): Creates also the object for its parent, if not yet existing """ parent = None - relative_transform = None + # the transform relative to the map + relative_transform = trans.carla_transform_to_ros_pose(carla_actor.get_transform()) if carla_actor.parent: if carla_actor.parent.id in self.actors: parent = self.actors[carla_actor.parent.id] else: parent = self._create_object_from_actor(carla_actor.parent) - # calculate relative transform - actor_transform_matrix = trans.ros_pose_to_transform_matrix( - trans.carla_transform_to_ros_pose(carla_actor.get_transform())) + # calculate relative transform to the parent + actor_transform_matrix = trans.ros_pose_to_transform_matrix(relative_transform) parent_transform_matrix = trans.ros_pose_to_transform_matrix( trans.carla_transform_to_ros_pose(carla_actor.parent.get_transform())) relative_transform_matrix = np.matrix( diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 9f65f973..639bfb8c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -150,9 +150,9 @@ def send_vehicle_msgs(self): [wheel.position.z/100.0], [1.0]]) wheel_pos_in_ego_vehicle = numpy.matmul(inv_T, wheel_pos_in_map) - wheel_info.position.x = wheel_pos_in_ego_vehicle[0] - wheel_info.position.y = -wheel_pos_in_ego_vehicle[1] - wheel_info.position.z = wheel_pos_in_ego_vehicle[2] + wheel_info.position.x = float(wheel_pos_in_ego_vehicle[0]) + wheel_info.position.y = float(-wheel_pos_in_ego_vehicle[1]) + wheel_info.position.z = float(wheel_pos_in_ego_vehicle[2]) vehicle_info.wheels.append(wheel_info) vehicle_info.max_rpm = vehicle_physics.max_rpm diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 113d328e..f3ee5333 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -45,6 +45,7 @@ def __init__(self, actor, args=None): self._current_target_speed = None self._current_path = None + self.controller_launch = None self._target_speed_publisher = self.node.new_publisher( Float64, "/carla/{}/target_speed".format(self._role_name), @@ -68,7 +69,7 @@ def __init__(self, actor, args=None): # add additional launch parameters launch_parameters = [] for key, value in args.items(): - if not key == "launch" and not key == "launch-package": + if not key == "launch" and not key == "launch-package" and not key == "path_topic_name": launch_parameters.append('{}:={}'.format(key, value)) cli_args.append('{}:={}'.format(key, value)) @@ -93,7 +94,7 @@ def __init__(self, actor, args=None): self.node.loginfo( "{}: Successfully started ros vehicle control".format(self._role_name)) else: - self.node.logerr( + self.node.logwarn( "{}: Missing value for 'launch' and/or 'launch-package'.".format(self._role_name)) def controller_runner_log(self, log): # pylint: disable=no-self-use @@ -128,7 +129,7 @@ def reset(self): # set target speed to zero before closing as the controller can take time to shutdown if ROS_VERSION == 2: self.update_target_speed(0.) - if self.controller_launch.is_running(): + if self.controller_launch and self.controller_launch.is_running(): self.controller_launch.shutdown() if self._carla_actor and self._carla_actor.is_alive: self._carla_actor = None From ed503a21a76c01794f5b7381f2536b8de5053439 Mon Sep 17 00:00:00 2001 From: Bernd Gassmann Date: Fri, 16 Apr 2021 18:53:09 +0200 Subject: [PATCH 597/627] revert path_topic_name --- .../src/carla_ros_scenario_runner/ros_vehicle_control.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index f3ee5333..5ba8879d 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -69,7 +69,7 @@ def __init__(self, actor, args=None): # add additional launch parameters launch_parameters = [] for key, value in args.items(): - if not key == "launch" and not key == "launch-package" and not key == "path_topic_name": + if not key == "launch" and not key == "launch-package": launch_parameters.append('{}:={}'.format(key, value)) cli_args.append('{}:={}'.format(key, value)) From 6fe8fe147997769079d7272887b587a1e8aa7112 Mon Sep 17 00:00:00 2001 From: umateusz Date: Sun, 18 Apr 2021 16:00:51 +0200 Subject: [PATCH 598/627] fix matrix initialization --- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 9f65f973..e8956ad9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -145,10 +145,10 @@ def send_vehicle_msgs(self): wheel_info.max_handbrake_torque = wheel.max_handbrake_torque inv_T = numpy.array(self.carla_actor.get_transform().get_inverse_matrix(), dtype=float) - wheel_pos_in_map = numpy.array([[wheel.position.x/100.0], - [wheel.position.y/100.0], - [wheel.position.z/100.0], - [1.0]]) + wheel_pos_in_map = numpy.array([wheel.position.x/100.0, + wheel.position.y/100.0, + wheel.position.z/100.0, + 1.0]) wheel_pos_in_ego_vehicle = numpy.matmul(inv_T, wheel_pos_in_map) wheel_info.position.x = wheel_pos_in_ego_vehicle[0] wheel_info.position.y = -wheel_pos_in_ego_vehicle[1] From b355e9416c6d11dc37445a4ec96f43b58c75f52d Mon Sep 17 00:00:00 2001 From: Bernd Gassmann Date: Thu, 15 Apr 2021 17:06:34 +0200 Subject: [PATCH 599/627] Make waypoints publisher topic name configurable --- .../src/carla_ros_scenario_runner/ros_vehicle_control.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 5ba8879d..257b3b7e 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -41,6 +41,10 @@ def __init__(self, actor, args=None): elif ROS_VERSION == 2: logging.get_logger("pre_logger").error("Invalid role_name!") + self._path_topic_name = "waypoints" + if "path_topic_name" in args: + self._path_topic_name = args["path_topic_name"] + self.node = CompatibleNode('ros_agent_{}'.format(self._role_name)) self._current_target_speed = None @@ -52,7 +56,7 @@ def __init__(self, actor, args=None): QoSProfile(depth=1, durability=True)) self._path_publisher = self.node.new_publisher( - Path, "/carla/{}/waypoints".format(self._role_name), + Path, "/carla/{}/{}".format(self._role_name, self._path_topic_name), QoSProfile(depth=1, durability=True)) if "launch" in args and "launch-package" in args: @@ -69,7 +73,7 @@ def __init__(self, actor, args=None): # add additional launch parameters launch_parameters = [] for key, value in args.items(): - if not key == "launch" and not key == "launch-package": + if not key == "launch" and not key == "launch-package" and not key == "path_topic_name": launch_parameters.append('{}:={}'.format(key, value)) cli_args.append('{}:={}'.format(key, value)) From 1276bbfa2664e8fac1058e5253e5e8f4cd991e8e Mon Sep 17 00:00:00 2001 From: Bernd Gassmann Date: Wed, 21 Apr 2021 16:36:32 +0200 Subject: [PATCH 600/627] revert fix already merged in master --- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index d9f5c23d..e8956ad9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -150,9 +150,9 @@ def send_vehicle_msgs(self): wheel.position.z/100.0, 1.0]) wheel_pos_in_ego_vehicle = numpy.matmul(inv_T, wheel_pos_in_map) - wheel_info.position.x = float(wheel_pos_in_ego_vehicle[0]) - wheel_info.position.y = float(-wheel_pos_in_ego_vehicle[1]) - wheel_info.position.z = float(wheel_pos_in_ego_vehicle[2]) + wheel_info.position.x = wheel_pos_in_ego_vehicle[0] + wheel_info.position.y = -wheel_pos_in_ego_vehicle[1] + wheel_info.position.z = wheel_pos_in_ego_vehicle[2] vehicle_info.wheels.append(wheel_info) vehicle_info.max_rpm = vehicle_physics.max_rpm From 3c78a6ff90dfdda19c9074cfd5bccfc89121520f Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Fri, 23 Apr 2021 08:56:34 +0200 Subject: [PATCH 601/627] Update docs --- docs/carla_ros_scenario_runner.md | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/docs/carla_ros_scenario_runner.md b/docs/carla_ros_scenario_runner.md index ab14050e..bee2097a 100644 --- a/docs/carla_ros_scenario_runner.md +++ b/docs/carla_ros_scenario_runner.md @@ -36,6 +36,7 @@ An example scenario is found [here](https://github.com/carla-simulator/ros-bridg + ``` @@ -84,4 +85,11 @@ ros2 service call /scenario_runner/execute_scenario carla_ros_scenario_runner_ty |-------|------|-------------| | `/scenario_runner/status` | [`carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus`](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | The current status of the scenario runner execution (used by the [rviz_carla_plugin](rviz_plugin.md)) | + +The controller `ros_vehicle_control` provides the following topics: +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//waypoints` | [`nav_msgs.Path`](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | the path defined within the scenario. Note: The topic name can be changed by modifying the parameter `path_topic_name` | +| `/carla//target_speed` | [`std_msgs.Float64`](https://docs.ros.org/en/api/std_msgs/html/msg/Float64.html) | the target speed as defined within the scenario | +
From 4161cf85bcf4f45dcd3a7d2cf415c5d2430d60a7 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Fri, 23 Apr 2021 12:26:38 +0200 Subject: [PATCH 602/627] Refactoring AD agent (#523) * avoid different ways to import carla_ad_agent submodules * ad agent refactoring * fix initial type objects variable * Merge branch 'master' into joel-mb/route_service * traffic light sensor using latched topics again * ad agent docs updated --- carla_ad_agent/CMakeLists.txt | 2 +- carla_ad_agent/launch/carla_ad_agent.launch | 2 +- .../launch/carla_ad_agent.launch.py | 2 +- carla_ad_agent/setup.py | 2 +- carla_ad_agent/src/carla_ad_agent/ad_agent.py | 205 +++++++++ carla_ad_agent/src/carla_ad_agent/agent.py | 398 +++++++----------- .../src/carla_ad_agent/basic_agent.py | 129 ------ .../src/carla_ad_agent/carla_ad_agent.py | 124 ------ .../src/carla_ad_agent/local_planner.py | 246 ++++++----- carla_ad_agent/src/carla_ad_agent/misc.py | 16 +- .../carla_ros_bridge/traffic_lights_sensor.py | 3 +- .../test/ros_bridge_client_ros2_test.py | 44 +- carla_spawn_objects/config/objects.json | 2 +- .../carla_spawn_objects.py | 10 +- .../carla_walker_agent/carla_walker_agent.py | 2 +- .../carla_waypoint_publisher.py | 7 +- docs/carla_ad_agent.md | 83 +++- .../ros_compatibility/ros_compatible_node.py | 96 ++--- 18 files changed, 629 insertions(+), 744 deletions(-) create mode 100755 carla_ad_agent/src/carla_ad_agent/ad_agent.py delete mode 100644 carla_ad_agent/src/carla_ad_agent/basic_agent.py delete mode 100755 carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt index 5871b5c3..a02b4f9e 100644 --- a/carla_ad_agent/CMakeLists.txt +++ b/carla_ad_agent/CMakeLists.txt @@ -18,7 +18,7 @@ if(${ROS_VERSION} EQUAL 1) include_directories(${catkin_INCLUDE_DIRS}) - install(PROGRAMS src/carla_ad_agent/carla_ad_agent.py + install(PROGRAMS src/carla_ad_agent/ad_agent.py src/carla_ad_agent/local_planner.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY launch/ diff --git a/carla_ad_agent/launch/carla_ad_agent.launch b/carla_ad_agent/launch/carla_ad_agent.launch index cd6e688b..5440aaf5 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch +++ b/carla_ad_agent/launch/carla_ad_agent.launch @@ -11,7 +11,7 @@ - + diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index 2c8c0db4..dc66b062 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -46,7 +46,7 @@ def generate_launch_description(): ), launch_ros.actions.Node( package='carla_ad_agent', - executable='carla_ad_agent', + executable='ad_agent', name=['carla_ad_agent_', launch.substitutions.LaunchConfiguration('role_name')], output='screen', parameters=[ diff --git a/carla_ad_agent/setup.py b/carla_ad_agent/setup.py index e64d76dd..1e4706e0 100644 --- a/carla_ad_agent/setup.py +++ b/carla_ad_agent/setup.py @@ -33,7 +33,7 @@ description='CARLA ROS2 AD agent', license='MIT', entry_points={ - 'console_scripts': ['carla_ad_agent = carla_ad_agent.carla_ad_agent:main', + 'console_scripts': ['ad_agent = carla_ad_agent.ad_agent:main', 'local_planner = carla_ad_agent.local_planner:main', 'testing_waypoints = carla_ad_agent.testing_waypoints:main'], }, diff --git a/carla_ad_agent/src/carla_ad_agent/ad_agent.py b/carla_ad_agent/src/carla_ad_agent/ad_agent.py new file mode 100755 index 00000000..d701933c --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/ad_agent.py @@ -0,0 +1,205 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +A basic AD agent using CARLA waypoints +""" + +import copy +import sys +import time +import threading + +from ros_compatibility import ( + CompatibleNode, + ROSInterruptException, + ros_ok, + QoSProfile, + ROSException, + latch_on, + ros_init, + ROS_VERSION, + logwarn, + loginfo, + ros_shutdown, + MultiThreadedExecutor, + ServiceException, + get_service_request) + +from std_msgs.msg import Float64 # pylint: disable=import-error +from derived_object_msgs.msg import ObjectArray +from nav_msgs.msg import Odometry +from carla_msgs.msg import ( + CarlaEgoVehicleInfo, + CarlaActorList, + CarlaTrafficLightStatusList, + CarlaTrafficLightInfoList) + +from carla_ad_agent.agent import Agent, AgentState + + +class CarlaAdAgent(Agent): + """ + A basic AD agent using CARLA waypoints + """ + + def __init__(self): + """ + Constructor + """ + super(CarlaAdAgent, self).__init__("ad_agent") + + role_name = self.get_param("role_name", "ego_vehicle") + self._avoid_risk = self.get_param("avoid_risk", True) + self._target_speed = self.get_param("target_speed", 30.0) + + self.data_lock = threading.Lock() + + self._ego_vehicle_pose = None + self._objects = {} + self._lights_status = {} + self._lights_info = {} + + self.speed_command_publisher = self.new_publisher( + Float64, "/carla/{}/speed_command".format(role_name), + QoSProfile(depth=1, durability=True)) + + self._odometry_subscriber = self.create_subscriber( + Odometry, + "/carla/{}/odometry".format(role_name), + self.odometry_cb + ) + + if self._avoid_risk: + + self._objects_subscriber = self.create_subscriber( + ObjectArray, + "/carla/{}/objects".format(role_name), + self.objects_cb + ) + self._traffic_light_status_subscriber = self.create_subscriber( + CarlaTrafficLightStatusList, + "/carla/traffic_lights/status", + self.traffic_light_status_cb, + qos_profile=QoSProfile(depth=10, durability=latch_on) + ) + self._traffic_light_info_subscriber = self.create_subscriber( + CarlaTrafficLightInfoList, + "/carla/traffic_lights/info", + self.traffic_light_info_cb, + qos_profile=QoSProfile(depth=10, durability=latch_on) + ) + + def odometry_cb(self, odometry_msg): + with self.data_lock: + self._ego_vehicle_pose = odometry_msg.pose.pose + + def objects_cb(self, objects_msg): + objects = {} + for obj in objects_msg.objects: + objects[obj.id] = obj + + with self.data_lock: + self._objects = objects + + def traffic_light_status_cb(self, traffic_light_status_msg): + lights_status = {} + for tl_status in traffic_light_status_msg.traffic_lights: + lights_status[tl_status.id] = tl_status + + with self.data_lock: + self._lights_status = lights_status + + def traffic_light_info_cb(self, traffic_light_info_msg): + lights_info = {} + for tl_info in traffic_light_info_msg.traffic_lights: + lights_info[tl_info.id] = tl_info + + with self.data_lock: + self._lights_info = lights_info + + def run_step(self): + """ + Executes one step of navigation. + """ + + # is there an obstacle in front of us? + hazard_detected = False + + with self.data_lock: + # retrieve relevant elements for safe navigation, i.e.: traffic lights and other vehicles. + ego_vehicle_pose = copy.deepcopy(self._ego_vehicle_pose) + objects = copy.deepcopy(self._objects) + lights_info = copy.deepcopy(self._lights_info) + lights_status = copy.deepcopy(self._lights_status) + + if ego_vehicle_pose is None: + self.loginfo("Waiting for ego vehicle pose") + return + + # ensure we have received all the status/info data of traffic lights. + if set(lights_info.keys()) != set(lights_status.keys()): + self.logwarn("Missing traffic light information") + return + + if self._avoid_risk: + # check possible obstacles + vehicle_state, vehicle = self._is_vehicle_hazard(ego_vehicle_pose, objects) + if vehicle_state: + self._state = AgentState.BLOCKED_BY_VEHICLE + hazard_detected = True + + # check for the state of the traffic lights + light_state, traffic_light = self._is_light_red(ego_vehicle_pose, lights_status, lights_info) + if light_state: + self._state = AgentState.BLOCKED_RED_LIGHT + hazard_detected = True + + speed_command = Float64() + if hazard_detected: + speed_command.data = 0.0 + else: + self._state = AgentState.NAVIGATING + speed_command.data = self._target_speed + + self.speed_command_publisher.publish(speed_command) + + +def main(args=None): + """ + + main function + + :return: + """ + ros_init(args) + controller = None + try: + executor = MultiThreadedExecutor() + controller = CarlaAdAgent() + executor.add_node(controller) + + update_timer = controller.new_timer( + 0.05, lambda timer_event=None: controller.run_step()) + + controller.spin() + + except (ROSInterruptException, ROSException) as e: + if ros_ok(): + logwarn("ROS Error during exection: {}".format(e)) + except KeyboardInterrupt: + loginfo("User requested shut down.") + finally: + if controller is not None: + stopping_speed = Float64() + stopping_speed.data = 0.0 + controller.speed_command_publisher.publish(stopping_speed) + ros_shutdown() + + +if __name__ == "__main__": + main() diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index a2f9b2f8..662d3cfc 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -9,31 +9,27 @@ Base class for agent """ -from carla_waypoint_types.srv import GetWaypoint # pylint: disable=import-error -from carla_msgs.msg import CarlaTrafficLightStatusList, CarlaWorldInfo # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus # pylint: disable=import-error -from nav_msgs.msg import Odometry -from visualization_msgs.msg import Marker -from enum import Enum +import enum import math -import time -from transforms3d.euler import quat2euler + +import carla + from ros_compatibility import ( + CompatibleNode, ros_ok, ServiceException, - QoSProfile, - latch_on, - get_service_request, - ROS_VERSION) + get_service_request) + +import carla_common.transforms as trans -if ROS_VERSION == 1: - from misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import -elif ROS_VERSION == 2: - from carla_ad_agent.misc import is_within_distance_ahead, compute_magnitude_angle # pylint: disable=relative-import - from rclpy import spin_once +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaTrafficLightStatus +from carla_waypoint_types.srv import GetWaypoint +from derived_object_msgs.msg import Object +from carla_ad_agent.misc import is_within_distance_ahead # pylint: disable=relative-import -class AgentState(Enum): + +class AgentState(enum.Enum): """ AGENT_STATE represents the possible states of a roaming agent """ @@ -42,287 +38,177 @@ class AgentState(Enum): BLOCKED_RED_LIGHT = 3 -class Agent(object): +class Agent(CompatibleNode): """ Base class for agent """ - def __init__(self, role_name, vehicle_id, avoid_risk, node): - """ - """ - self.node = node - self._proximity_threshold = 10.0 # meters - self._map_name = None - self._vehicle_location = None - self._vehicle_yaw = None - self._vehicle_id = vehicle_id - self._last_traffic_light = None - self._target_route_point = None - - self._odometry_subscriber = self.node.create_subscriber( - Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) - # wait for first odometry update - self.node.logwarn('Agent waiting for odometry message') - while self._vehicle_location is None: - time.sleep(0.05) - if ROS_VERSION == 2: - spin_once(node, timeout_sec=0) - self.node.logwarn('Odometry message received') - - if avoid_risk: - self._get_waypoint_client = node.create_service_client( - '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) - - self._traffic_lights = [] - self._traffic_light_status_subscriber = node.create_subscriber(CarlaTrafficLightStatusList, - "/carla/traffic_lights/status", self.traffic_lights_updated, - qos_profile=QoSProfile(depth=10, durability=latch_on)) - self._target_point_subscriber = node.create_subscriber( - Marker, "/carla/{}/next_target".format(role_name), self.target_point_updated) - world_info = node.wait_for_one_message( - "/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) - self._map_name = world_info.map_name - - def traffic_lights_updated(self, traffic_lights): - """ - callback on new traffic light list - Only used if risk should be avoided. - """ - self._traffic_lights = traffic_lights.traffic_lights + OBJECT_VEHICLE_CLASSIFICATION = [ + Object.CLASSIFICATION_CAR, + Object.CLASSIFICATION_BIKE, + Object.CLASSIFICATION_MOTORCYCLE, + Object.CLASSIFICATION_TRUCK, + Object.CLASSIFICATION_OTHER_VEHICLE + ] - def target_point_updated(self, new_target_point): - self._target_route_point = new_target_point.pose.position + def __init__(self, name="agent"): + super(Agent, self).__init__(name) - def odometry_updated(self, odo): - """ - callback on new odometry - """ - self._vehicle_location = odo.pose.pose.position - quaternion = ( - odo.pose.pose.orientation.w, - odo.pose.pose.orientation.x, - odo.pose.pose.orientation.y, - odo.pose.pose.orientation.z - ) - _, _, self._vehicle_yaw = quat2euler(quaternion) - - def _is_light_red(self, lights_list): - """ - Method to check if there is a red light affecting us. This version of - the method is compatible with both European and US style traffic lights. + self._proximity_tlight_threshold = 10.0 # meters + self._proximity_vehicle_threshold = 12.0 # meters - :param lights_list: list containing TrafficLight objects - :return: a tuple given by (bool_flag, traffic_light), where - - bool_flag is True if there is a traffic light in RED - affecting us and False otherwise - - traffic_light is the object itself or None if there is no - red traffic light affecting us - """ - if self._map_name == 'Town01' or self._map_name == 'Town02': - return self._is_light_red_europe_style(lights_list) - else: - return self._is_light_red_us_style(lights_list) + role_name = self.get_param("role_name", "ego_vehicle") + vehicle_info = self.wait_for_message( + "/carla/{}/vehicle_info".format(role_name), + CarlaEgoVehicleInfo) + self._ego_vehicle_id = vehicle_info.id - def _is_light_red_europe_style(self, lights_list): - """ - This method is specialized to check European style traffic lights. - - :param lights_list: list containing TrafficLight objects - :return: a tuple given by (bool_flag, traffic_light), where - - bool_flag is True if there is a traffic light in RED - affecting us and False otherwise - - traffic_light is the object itself or None if there is no - red traffic light affecting us - """ - if self._vehicle_location is None: - # no available self location yet - return (False, None) - - ego_vehicle_location = get_service_request(GetWaypoint) - ego_vehicle_location.location = self._vehicle_location - ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) - if not ego_vehicle_waypoint: - if ros_ok(): - self.node.logwarn("Could not get waypoint for ego vehicle.") - return (False, None) - - for traffic_light in lights_list: - object_waypoint = traffic_light[1] - if object_waypoint.road_id != ego_vehicle_waypoint.road_id or \ - object_waypoint.lane_id != ego_vehicle_waypoint.lane_id: - continue - if is_within_distance_ahead(object_waypoint.pose.position, ego_vehicle_location.location, - math.degrees(self._vehicle_yaw), - self._proximity_threshold): - traffic_light_state = CarlaTrafficLightStatus.RED - for status in self._traffic_lights: - if status.id == traffic_light[0]: - traffic_light_state = status.state - break - if traffic_light_state == CarlaTrafficLightStatus.RED: - return (True, traffic_light[0]) - - return (False, None) + self._get_waypoint_client = self.create_service_client( + '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), + GetWaypoint) def get_waypoint(self, location): """ - Helper to get waypoint for location via ros service. - Only used if risk should be avoided. + Helper method to get a waypoint for a location. + + :param location: location request + :type location: geometry_msgs/Point + :return: waypoint of the requested location + :rtype: carla_msgs/Waypoint """ if not ros_ok(): return None try: - response = self.node.call_service(self._get_waypoint_client, location) + request = get_service_request(GetWaypoint) + request.location = location + response = self.call_service(self._get_waypoint_client, request) return response.waypoint except ServiceException as e: if ros_ok(): - self.node.logwarn("Service call 'get_waypoint' failed: {}".format(str(e))) + self.logwarn("Service call 'get_waypoint' failed: {}".format(str(e))) - def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branches + def run_step(): """ - This method is specialized to check US style traffic lights. - - :param lights_list: list containing TrafficLight objects - :return: a tuple given by (bool_flag, traffic_light), where - - bool_flag is True if there is a traffic light in RED - affecting us and False otherwise - - traffic_light is the object itself or None if there is no - red traffic light affecting us + Executes one step of navigation. """ - if self._vehicle_location is None: - # no available self location yet - return (False, None) - - ego_vehicle_location = get_service_request(GetWaypoint) - ego_vehicle_location.location = self._vehicle_location - ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) - if not ego_vehicle_waypoint: - if ros_ok(): - self.node.logwarn("Could not get waypoint for ego vehicle.") - return (False, None) - - if ego_vehicle_waypoint.is_junction: - # It is too late. Do not block the intersection! Keep going! - return (False, None) + raise NotImplementedError - if self._target_route_point is not None: - request = get_service_request(GetWaypoint) - request.location = self._target_route_point - target_waypoint = self.get_waypoint(request) - if not target_waypoint: - if ros_ok(): - self.node.logwarn("Could not get waypoint for target route point.") - return (False, None) - if target_waypoint.is_junction: - min_angle = 180.0 - sel_magnitude = 0.0 # pylint: disable=unused-variable - sel_traffic_light = None - for traffic_light in lights_list: - loc = traffic_light[1] - magnitude, angle = compute_magnitude_angle(loc.pose.position, - ego_vehicle_location.location, - math.degrees(self._vehicle_yaw)) - if magnitude < 60.0 and angle < min(25.0, min_angle): - sel_magnitude = magnitude - sel_traffic_light = traffic_light[0] - min_angle = angle - - if sel_traffic_light is not None: - # print('=== Magnitude = {} | Angle = {} | ID = {}'.format( - # sel_magnitude, min_angle, sel_traffic_light)) - - if self._last_traffic_light is None: - self._last_traffic_light = sel_traffic_light - - state = None - for status in self._traffic_lights: - if status.id == sel_traffic_light: - state = status.state - break - if state is None: - self.node.logwarn( - "Couldn't get state of traffic light {}".format( - sel_traffic_light)) - return (False, None) - - if state == CarlaTrafficLightStatus.RED: - return (True, self._last_traffic_light) - else: - self._last_traffic_light = None - - return (False, None) - - def _is_vehicle_hazard(self, vehicle_list, objects): + def _is_vehicle_hazard(self, ego_vehicle_pose, objects): """ - Check if a given vehicle is an obstacle in our way. To this end we take - into account the road and lane the target vehicle is on and run a - geometry test to check if the target vehicle is under a certain distance - in front of our ego vehicle. + Checks whether there is a vehicle hazard. - WARNING: This method is an approximation that could fail for very large - vehicles, which center is actually on a different lane but their - extension falls within the ego vehicle lane. + This method only takes into account vehicles. Pedestrians are other types of obstacles are + ignored. - :param vehicle_list: list of potential obstacle to check + :param ego_vehicle_pose: current ego vehicle pose + :type ego_vehicle_pose: geometry_msgs/Pose + :param objects: list of objects + :type objects: derived_object_msgs/ObjectArray :return: a tuple given by (bool_flag, vehicle), where - bool_flag is True if there is a vehicle ahead blocking us and False otherwise - - vehicle is the blocker object itself + - vehicle is the blocker vehicle id """ - if self._vehicle_location is None: - # no available self location yet - return (False, None) - - ego_vehicle_location = get_service_request(GetWaypoint) - ego_vehicle_location.location = self._vehicle_location - ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) - if not ego_vehicle_waypoint: - if ros_ok(): - self.node.logwarn("Could not get waypoint for ego vehicle.") - return (False, None) - for target_vehicle_id in vehicle_list: - # do not account for the ego vehicle - if target_vehicle_id == self._vehicle_id: + ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_pose.position) + ego_vehicle_transform = trans.ros_pose_to_carla_transform(ego_vehicle_pose) + + for target_vehicle_id, target_vehicle_object in objects.items(): + + # take into account only vehicles + if target_vehicle_object.classification not in self.OBJECT_VEHICLE_CLASSIFICATION: continue - target_vehicle_location = None - for elem in objects: - if elem.id == target_vehicle_id: - target_vehicle_location = elem.pose - break + # do not account for the ego vehicle + if target_vehicle_id == self._ego_vehicle_id: + continue - if not target_vehicle_location: - self.node.logwarn("Location of vehicle {} not found".format(target_vehicle_id)) + target_vehicle_waypoint = self.get_waypoint(target_vehicle_object.pose.position) + if target_vehicle_waypoint is None: continue + target_vehicle_transform = trans.ros_pose_to_carla_transform(target_vehicle_object.pose) # if the object is not in our lane it's not an obstacle - request = get_service_request(GetWaypoint) - request.location = target_vehicle_location.position - target_vehicle_waypoint = self.get_waypoint(request) - if not target_vehicle_waypoint: - if ros_ok(): - self.node.logwarn("Could not get waypoint for target vehicle.") - return (False, None) if target_vehicle_waypoint.road_id != ego_vehicle_waypoint.road_id or \ target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id: continue - if is_within_distance_ahead(target_vehicle_location.position, self._vehicle_location, - math.degrees(self._vehicle_yaw), - self._proximity_threshold): + if is_within_distance_ahead(target_vehicle_transform, + ego_vehicle_transform, + self._proximity_vehicle_threshold): return (True, target_vehicle_id) return (False, None) - def emergency_stop(self): # pylint: disable=no-self-use + def _is_light_red(self, ego_vehicle_pose, lights_status, lights_info): """ - Send an emergency stop command to the vehicle - :return: + Checks if there is a red light affecting us. This version of the method is compatible with + both European and US style traffic lights. + + :param ego_vehicle_pose: current ego vehicle pose + :type ego_vehicle_pose: geometry_msgs/Pose + + :param lights_status: list containing all traffic light status. + :type lights_status: carla_msgs/CarlaTrafficLightStatusList + + :param lights_info: list containing all traffic light info. + :type lights_info: lis. + + :return: a tuple given by (bool_flag, traffic_light), where + - bool_flag is True if there is a traffic light in RED + affecting us and False otherwise + - traffic_light is the traffic light id or None if there is no + red traffic light affecting us. """ - control = CarlaEgoVehicleControl() - control.steer = 0.0 - control.throttle = 0.0 - control.brake = 1.0 - control.hand_brake = False - return control + ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_pose.position) + ego_vehicle_transform = trans.ros_pose_to_carla_transform(ego_vehicle_pose) + + for light_id in lights_status.keys(): + object_location = self._get_trafficlight_trigger_location(lights_info[light_id]) + object_location = trans.carla_location_to_ros_point(object_location) + object_waypoint = self.get_waypoint(object_location) + if object_waypoint is None: + continue + object_transform = trans.ros_pose_to_carla_transform(object_waypoint.pose) + + if object_waypoint.road_id != ego_vehicle_waypoint.road_id: + continue + + ve_dir = ego_vehicle_transform.get_forward_vector() + wp_dir = object_transform.get_forward_vector() + + dot_ve_wp = ve_dir.x * wp_dir.x + ve_dir.y * wp_dir.y + ve_dir.z * wp_dir.z + + if dot_ve_wp < 0: + continue + + if is_within_distance_ahead(object_transform, + ego_vehicle_transform, + self._proximity_tlight_threshold): + if lights_status[light_id].state == CarlaTrafficLightStatus.RED or \ + lights_status[light_id].state == CarlaTrafficLightStatus.YELLOW: + return (True, light_id) + + return (False, None) + + def _get_trafficlight_trigger_location(self, light_info): # pylint: disable=no-self-use + + def rotate_point(point, radians): + """ + rotate a given point by a given angle + """ + rotated_x = math.cos(radians) * point.x - math.sin(radians) * point.y + rotated_y = math.sin(radians) * point.x + math.cos(radians) * point.y + + return carla.Vector3D(rotated_x, rotated_y, point.z) + + base_transform = trans.ros_pose_to_carla_transform(light_info.transform) + base_rot = base_transform.rotation.yaw + area_loc = base_transform.transform( + trans.ros_point_to_carla_location(light_info.trigger_volume.center)) + area_ext = light_info.trigger_volume.size + + point = rotate_point(carla.Vector3D(0, 0, area_ext.z / 2.0), math.radians(base_rot)) + point_location = area_loc + carla.Location(x=point.x, y=point.y) + + return carla.Location(point_location.x, point_location.y, point_location.z) diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py deleted file mode 100644 index 009375e3..00000000 --- a/carla_ad_agent/src/carla_ad_agent/basic_agent.py +++ /dev/null @@ -1,129 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2018-2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -""" -BasicAgent implements a basic agent that navigates scenes to reach a given -target destination. This agent respects traffic lights and other vehicles. -""" - -from carla_waypoint_types.srv import GetActorWaypoint # pylint: disable=import-error -from carla_msgs.msg import CarlaActorList # pylint: disable=import-error -from derived_object_msgs.msg import ObjectArray # pylint: disable=import-error -import math -from ros_compatibility import ( - ros_ok, - ServiceException, - QoSProfile, - latch_on, - get_service_request, - ROS_VERSION) - -if ROS_VERSION == 1: - from agent import Agent, AgentState # pylint: disable=relative-import -elif ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup - from carla_ad_agent.agent import Agent, AgentState # pylint: disable=relative-import - - -class BasicAgent(Agent): - """ - BasicAgent implements a basic agent that navigates scenes to reach a given - target destination. This agent respects traffic lights and other vehicles. - """ - - def __init__(self, role_name, ego_vehicle_id, node, avoid_risk=True): - """ - """ - super(BasicAgent, self).__init__(role_name, ego_vehicle_id, avoid_risk, node) - self.node = node - self._avoid_risk = avoid_risk - self._proximity_threshold = 10.0 # meters - self._state = AgentState.NAVIGATING - - if ROS_VERSION == 1: - cb_group = None - elif ROS_VERSION == 2: - cb_group = ReentrantCallbackGroup() - - if self._avoid_risk: - self._vehicle_id_list = [] - self._lights_id_list = [] - self._objects = [] - self._actors_subscriber = self.node.create_subscriber(CarlaActorList, "/carla/actor_list", - self.actors_updated, callback_group=cb_group) - self._objects_subscriber = self.node.create_subscriber(ObjectArray, - "/carla/{}/objects".format(role_name), self.objects_updated) - self._get_actor_waypoint_client = self.node.create_service_client( - '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), - GetActorWaypoint, callback_group=cb_group) - - def get_actor_waypoint(self, actor_id): - """ - helper method to get waypoint for actor via ros service - Only used if risk should be avoided. - """ - try: - request = get_service_request(GetActorWaypoint) - request.id = actor_id - response = self.node.call_service(self._get_actor_waypoint_client, request) - return response.waypoint - except ServiceException as e: - if ros_ok(): - self.node.logwarn("Service call failed: {}".format(e)) - - def actors_updated(self, actors): - """ - callback on new actor list - Only used if risk should be avoided. - """ - # retrieve relevant elements for safe navigation, i.e.: traffic lights - # and other vehicles - self._vehicle_id_list = [] - self._lights_id_list = [] - for actor in actors.actors: - if "vehicle" in actor.type: - self._vehicle_id_list.append(actor.id) - elif "traffic_light" in actor.type: - self._lights_id_list.append( - (actor.id, self.get_actor_waypoint(actor.id))) - - def objects_updated(self, objects): - """ - callback on new objects - Only used if risk should be avoided. - """ - self._objects = objects.objects - - def run_step(self): - """ - Execute one step of navigation. - :return: carla.VehicleControl - """ - finished = False - - # is there an obstacle in front of us? - hazard_detected = False - - if self._avoid_risk: - # check possible obstacles - vehicle_state, vehicle = self._is_vehicle_hazard( # pylint: disable=unused-variable - self._vehicle_id_list, self._objects) - if vehicle_state: - self._state = AgentState.BLOCKED_BY_VEHICLE - hazard_detected = True - - # check for the state of the traffic lights - light_state, traffic_light = self._is_light_red( # pylint: disable=unused-variable - self._lights_id_list) - if light_state: - self._state = AgentState.BLOCKED_RED_LIGHT - hazard_detected = True - - if hazard_detected is False: - self._state = AgentState.NAVIGATING - - return hazard_detected diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py deleted file mode 100755 index f78ef18f..00000000 --- a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py +++ /dev/null @@ -1,124 +0,0 @@ -#!/usr/bin/env python -# -# Copyright (c) 2020 Intel Corporation -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -""" -A basic AD agent using CARLA waypoints -""" -import sys -import time -from std_msgs.msg import Float64 # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=import-error -from ros_compatibility import ( - CompatibleNode, - ROSInterruptException, - ros_ok, - QoSProfile, - ROSException, - latch_on, - ros_init, - ROS_VERSION, - logwarn, - loginfo, - ros_shutdown) - -if ROS_VERSION == 1: - # TODO: different ways to import the carla_ad_agent submodules (e.g. carla_ad_agent.basic_agent) between ros1 and ros2 shouldn't be necessary - from basic_agent import BasicAgent -elif ROS_VERSION == 2: - import rclpy - from carla_ad_agent.basic_agent import BasicAgent - - -class CarlaAdAgent(CompatibleNode): - """ - A basic AD agent using CARLA waypoints - """ - - def __init__(self): - """ - Constructor - """ - super(CarlaAdAgent, self).__init__('carla_ad_agent') - - role_name = self.get_param("role_name", "ego_vehicle") - avoid_risk = self.get_param("avoid_risk", True) - - self.target_speed = self.get_param("target_speed", 30.0) - self.agent = None - - # wait for ego vehicle - vehicle_info = None - self.loginfo("Wait for vehicle info ...") - vehicle_info = self.wait_for_one_message("/carla/{}/vehicle_info".format( - role_name), CarlaEgoVehicleInfo, qos_profile=QoSProfile(depth=1, durability=latch_on)) - self.loginfo("Vehicle info received.") - - self.agent = BasicAgent(role_name, vehicle_info.id, self, avoid_risk) - - self.target_speed_subscriber = self.create_subscriber( - Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) - - self.speed_command_publisher = self.new_publisher( - Float64, "/carla/{}/speed_command".format(role_name), QoSProfile(depth=1, durability=True)) - - def target_speed_updated(self, target_speed): - """ - callback on new target speed - """ - self.loginfo("New target speed received: {}".format(target_speed.data)) - self.target_speed = target_speed.data - - def run_step(self): - """ - Execute one step of navigation. - """ - if not self.agent: - self.loginfo("Waiting for ego vehicle...") - else: - hazard_detected = self.agent.run_step() - speed_command = Float64() - if hazard_detected: - # stop, publish speed 0.0km/h - speed_command.data = 0.0 - self.speed_command_publisher.publish(speed_command) - else: - speed_command.data = self.target_speed - self.speed_command_publisher.publish(speed_command) - return - - -def main(args=None): - """ - - main function - - :return: - """ - ros_init(args) - controller = None - try: - controller = CarlaAdAgent() - while ros_ok(): - time.sleep(0.01) - if ROS_VERSION == 2: - rclpy.spin_once(controller) - controller.run_step() - except (ROSInterruptException, ROSException) as e: - if ros_ok(): - logwarn("ROS Error during exection: {}".format(e)) - except KeyboardInterrupt: - loginfo("User requested shut down.") - finally: - if controller is not None: - stopping_speed = Float64() - stopping_speed.data = 0.0 - controller.speed_command_publisher.publish(stopping_speed) - ros_shutdown() - - -if __name__ == "__main__": - main() diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 341edc6f..5001e329 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -10,26 +10,19 @@ low-level waypoint following based on PID controllers. """ -from collections import deque -from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error +import collections +import math +import threading + from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION -from nav_msgs.msg import Path -from nav_msgs.msg import Odometry + +from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error +from nav_msgs.msg import Odometry, Path from std_msgs.msg import Float64 -import time -import math from visualization_msgs.msg import Marker -import os -ROS_VERSION = int(os.environ['ROS_VERSION']) - -if ROS_VERSION == 1: - from vehicle_pid_controller import VehiclePIDController - from misc import distance_vehicle -elif ROS_VERSION == 2: - from carla_ad_agent.vehicle_pid_controller import VehiclePIDController - from carla_ad_agent.misc import distance_vehicle - import rclpy +from carla_ad_agent.vehicle_pid_controller import VehiclePIDController +from carla_ad_agent.misc import distance_vehicle class LocalPlanner(CompatibleNode): @@ -47,148 +40,145 @@ class LocalPlanner(CompatibleNode): MIN_DISTANCE_PERCENTAGE = 0.9 def __init__(self): - super(LocalPlanner, self).__init__('local_planner') + super(LocalPlanner, self).__init__("local_planner") - # ros parameters role_name = self.get_param("role_name", "ego_vehicle") self.control_time_step = self.get_param("control_time_step", 0.05) + args_lateral_dict = {} args_lateral_dict['K_P'] = self.get_param("Kp_lateral", 0.9) args_lateral_dict['K_I'] = self.get_param("Ki_lateral", 0.0) args_lateral_dict['K_D'] = self.get_param("Kd_lateral", 0.0) + args_longitudinal_dict = {} args_longitudinal_dict['K_P'] = self.get_param("Kp_longitudinal", 0.206) args_longitudinal_dict['K_I'] = self.get_param("Ki_longitudinal", 0.0206) args_longitudinal_dict['K_D'] = self.get_param("Kd_longitudinal", 0.515) - self.target_route_point = None - self._vehicle_controller = None - self._waypoints_queue = deque(maxlen=20000) - self._buffer_size = 5 - self._waypoint_buffer = deque(maxlen=self._buffer_size) - self.path_received = False - self._current_speed = None + self.data_lock = threading.Lock() + self._current_pose = None + self._current_speed = None self._target_speed = 0.0 + self._buffer_size = 5 + self._waypoints_queue = collections.deque(maxlen=20000) + self._waypoint_buffer = collections.deque(maxlen=self._buffer_size) + # subscribers self._odometry_subscriber = self.create_subscriber( - Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) + Odometry, + "/carla/{}/odometry".format(role_name), + self.odometry_cb) self._path_subscriber = self.create_subscriber( - Path, "/carla/{}/waypoints".format(role_name), self.path_updated, QoSProfile(depth=1, durability=True)) - self._target_speed_subscriber = self.create_subscriber(Float64, "/carla/{}/speed_command".format( - role_name), self.target_speed_updated, QoSProfile(depth=1, durability=True)) + Path, + "/carla/{}/waypoints".format(role_name), + self.path_cb, + QoSProfile(depth=1, durability=True)) + self._target_speed_subscriber = self.create_subscriber( + Float64, + "/carla/{}/speed_command".format(role_name), + self.target_speed_cb, + QoSProfile(depth=1, durability=True)) # publishers - self._target_point_publisher = self.new_publisher( - Marker, "/carla/{}/next_target".format(role_name), QoSProfile(depth=10, durability=False)) + self._target_pose_publisher = self.new_publisher( + Marker, + "/carla/{}/next_target".format(role_name), + QoSProfile(depth=10, durability=False)) self._control_cmd_publisher = self.new_publisher( - CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), QoSProfile(depth=1, durability=False)) + CarlaEgoVehicleControl, + "/carla/{}/vehicle_control_cmd".format(role_name), + QoSProfile(depth=1, durability=False)) # initializing controller self._vehicle_controller = VehiclePIDController( self, args_lateral=args_lateral_dict, args_longitudinal=args_longitudinal_dict) - # wait for required messages - self.loginfo('Local planner waiting for a path and target speed...') - while self._current_pose is None or self._target_speed is None or self.path_received is False: - time.sleep(0.05) - if ROS_VERSION == 2: - rclpy.spin_once(self, timeout_sec=0) - - def odometry_updated(self, new_pose): - """ - callback on new odometry - """ - self._current_speed = math.sqrt(new_pose.twist.twist.linear.x ** 2 + - new_pose.twist.twist.linear.y ** 2 + - new_pose.twist.twist.linear.z ** 2) * 3.6 - self._current_pose = new_pose.pose.pose - - def target_speed_updated(self, new_target_speed): - self._target_speed = new_target_speed.data - - def path_updated(self, new_path): - """ - set a global plan to follow - """ - self.loginfo('New path to follow received.') - self.path_received = True - self.target_route_point = None - self._waypoint_buffer.clear() - self._waypoints_queue.clear() - for elem in new_path.poses: - self._waypoints_queue.append(elem.pose) + def odometry_cb(self, odometry_msg): + with self.data_lock: + self._current_pose = odometry_msg.pose.pose + self._current_speed = math.sqrt(odometry_msg.twist.twist.linear.x ** 2 + + odometry_msg.twist.twist.linear.y ** 2 + + odometry_msg.twist.twist.linear.z ** 2) * 3.6 + + def target_speed_cb(self, target_speed_msg): + with self.data_lock: + self._target_speed = target_speed_msg.data + + def path_cb(self, path_msg): + with self.data_lock: + self._waypoint_buffer.clear() + self._waypoints_queue.clear() + self._waypoints_queue.extend([pose.pose for pose in path_msg.poses]) + + def pose_to_marker_msg(self, pose): + marker_msg = Marker() + marker_msg.type = 0 + marker_msg.header.frame_id = "map" + marker_msg.pose = pose + marker_msg.scale.x = 1.0 + marker_msg.scale.y = 0.2 + marker_msg.scale.z = 0.2 + marker_msg.color.r = 255.0 + marker_msg.color.a = 1.0 + return marker_msg def run_step(self): """ - Execute one step of local planning which involves running the longitudinal + Executes one step of local planning which involves running the longitudinal and lateral PID controllers to follow the waypoints trajectory. """ - if self.path_received is False: - return - - if not self._waypoint_buffer and not self._waypoints_queue: - self.emergency_stop() - self.loginfo("Route finished. Waiting for a new one.") - self.path_received = False - return - - # When target speed is 0, brake - if self._target_speed == 0.0: - self.emergency_stop() - return - - # Buffering the waypoints - if not self._waypoint_buffer: - for i in range(self._buffer_size): - if self._waypoints_queue: - self._waypoint_buffer.append( - self._waypoints_queue.popleft()) - else: - break - - # target waypoint - self.target_route_point = self._waypoint_buffer[0] - target_point = Marker() - target_point.type = 0 - target_point.header.frame_id = "map" - target_point.pose = self.target_route_point - target_point.scale.x = 1.0 - target_point.scale.y = 0.2 - target_point.scale.z = 0.2 - target_point.color.r = 255.0 - target_point.color.a = 1.0 - self._target_point_publisher.publish(target_point) - - # move using PID controllers - control = self._vehicle_controller.run_step( - self._target_speed, self._current_speed, self._current_pose, self.target_route_point) - - # purge the queue of obsolete waypoints - max_index = -1 - - sampling_radius = self._target_speed * 1 / 3.6 # search radius for next waypoints in seconds - min_distance = sampling_radius * self.MIN_DISTANCE_PERCENTAGE - - for i, route_point in enumerate(self._waypoint_buffer): - if distance_vehicle(route_point, self._current_pose.position) < min_distance: - max_index = i - if max_index >= 0: - for i in range(max_index + 1): - self._waypoint_buffer.popleft() - - self._control_cmd_publisher.publish(control) - return + with self.data_lock: + if not self._waypoint_buffer and not self._waypoints_queue: + self.loginfo("Waiting for a route...") + self.emergency_stop() + return + + # when target speed is 0, brake. + if self._target_speed == 0.0: + self.emergency_stop() + return + + # Buffering the waypoints + if not self._waypoint_buffer: + for i in range(self._buffer_size): + if self._waypoints_queue: + self._waypoint_buffer.append(self._waypoints_queue.popleft()) + else: + break + + # target waypoint + target_pose = self._waypoint_buffer[0] + self._target_pose_publisher.publish(self.pose_to_marker_msg(target_pose)) + + # move using PID controllers + control_msg = self._vehicle_controller.run_step( + self._target_speed, self._current_speed, self._current_pose, target_pose) + + # purge the queue of obsolete waypoints + max_index = -1 + + sampling_radius = self._target_speed * 1 / 3.6 # search radius for next waypoints in seconds + min_distance = sampling_radius * self.MIN_DISTANCE_PERCENTAGE + + for i, route_point in enumerate(self._waypoint_buffer): + if distance_vehicle(route_point, self._current_pose.position) < min_distance: + max_index = i + if max_index >= 0: + for i in range(max_index + 1): + self._waypoint_buffer.popleft() + + self._control_cmd_publisher.publish(control_msg) def emergency_stop(self): - control = CarlaEgoVehicleControl() - control.steer = 0.0 - control.throttle = 0.0 - control.brake = 1.0 - control.hand_brake = False - control.manual_gear_shift = False - self._control_cmd_publisher.publish(control) + control_msg = CarlaEgoVehicleControl() + control_msg.steer = 0.0 + control_msg.throttle = 0.0 + control_msg.brake = 1.0 + control_msg.hand_brake = False + control_msg.manual_gear_shift = False + self._control_cmd_publisher.publish(control_msg) def main(args=None): @@ -199,18 +189,22 @@ def main(args=None): :return: """ ros_init(args) + local_planner = None update_timer = None try: local_planner = LocalPlanner() if ROS_VERSION == 1: local_planner.on_shutdown(local_planner.emergency_stop) - local_planner.loginfo('Local planner is starting.') + update_timer = local_planner.new_timer( local_planner.control_time_step, lambda timer_event=None: local_planner.run_step()) + local_planner.spin() + except KeyboardInterrupt: pass + finally: loginfo('Local planner shutting down.') if update_timer: diff --git a/carla_ad_agent/src/carla_ad_agent/misc.py b/carla_ad_agent/src/carla_ad_agent/misc.py index 9495b815..cf02aa7e 100644 --- a/carla_ad_agent/src/carla_ad_agent/misc.py +++ b/carla_ad_agent/src/carla_ad_agent/misc.py @@ -11,18 +11,16 @@ import numpy as np -def is_within_distance_ahead(target_location, current_location, orientation, max_distance): +def is_within_distance_ahead(target_transform, current_transform, max_distance): """ Check if a target object is within a certain distance in front of a reference object. - - :param target_location: location of the target object - :param current_location: location of the reference object + :param target_transform: location of the target object + :param current_transform: location of the reference object :param orientation: orientation of the reference object :param max_distance: maximum allowed distance :return: True if target object is within max_distance ahead of the reference object """ - target_vector = np.array([target_location.x - current_location.x, - target_location.y - current_location.y]) + target_vector = np.array([target_transform.location.x - current_transform.location.x, target_transform.location.y - current_transform.location.y]) norm_target = np.linalg.norm(target_vector) # If the vector is too short, we can simply stop here @@ -32,9 +30,9 @@ def is_within_distance_ahead(target_location, current_location, orientation, max if norm_target > max_distance: return False - forward_vector = np.array( - [math.cos(math.radians(orientation)), math.sin(math.radians(orientation))]) - d_angle = math.degrees(math.acos(np.dot(forward_vector, target_vector) / norm_target)) + fwd = current_transform.get_forward_vector() + forward_vector = np.array([fwd.x, fwd.y]) + d_angle = math.degrees(math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.))) return d_angle < 90.0 diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index e2f4a70a..48c1cfe4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -26,7 +26,6 @@ class TrafficLightsSensor(PseudoActor): def __init__(self, uid, name, parent, node, actor_list): """ Constructor - :param uid: unique identifier for this object :type uid: int :param name: name identiying the sensor @@ -95,4 +94,4 @@ def update(self, frame, timestamp): if traffic_light_status != self.traffic_light_status: self.traffic_light_status = traffic_light_status - self.traffic_lights_status_publisher.publish(traffic_light_status) + self.traffic_lights_status_publisher.publish(traffic_light_status) \ No newline at end of file diff --git a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py index 5ce94562..95703c66 100644 --- a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py +++ b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py @@ -128,7 +128,7 @@ def test_clock(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message("/clock", Clock, timeout=TIMEOUT) + msg = node.wait_for_message("/clock", Clock, timeout=TIMEOUT) self.assertNotEqual(Clock(), msg) finally: if node is not None: @@ -143,7 +143,7 @@ def test_vehicle_status(self, proc_output): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus) self.assertNotEqual(msg.header, Header()) self.assertEqual(msg.header.frame_id, 'map') @@ -161,7 +161,7 @@ def test_vehicle_info(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/vehicle_info", CarlaEgoVehicleInfo, timeout=TIMEOUT, qos_profile=QoSProfile(depth=1, durability=latch_on)) self.assertNotEqual(msg.id, 0) @@ -193,7 +193,7 @@ def test_odometry(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/odometry", Odometry, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "map") self.assertEqual(msg.child_frame_id, "ego_vehicle") @@ -211,7 +211,7 @@ def test_gnss(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/gnss", NavSatFix, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/gnss") self.assertNotEqual(msg.latitude, 0.0) @@ -230,7 +230,7 @@ def test_imu(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message("/carla/ego_vehicle/imu", Imu, timeout=TIMEOUT) + msg = node.wait_for_message("/carla/ego_vehicle/imu", Imu, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/imu") self.assertNotEqual(msg.linear_acceleration, 0.0) self.assertNotEqual(msg.angular_velocity, 0.0) @@ -248,7 +248,7 @@ def test_camera_info(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/rgb_front/camera_info", CameraInfo, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/rgb_front") self.assertEqual(msg.height, 600) @@ -266,7 +266,7 @@ def test_camera_image(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/rgb_front/image", Image, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/rgb_front") self.assertEqual(msg.height, 600) @@ -285,7 +285,7 @@ def test_dvs_camera_info(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/dvs_front/camera_info", CameraInfo, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") self.assertEqual(msg.height, 70) @@ -303,7 +303,7 @@ def test_dvs_camera_image(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/dvs_front/image", Image, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") self.assertEqual(msg.height, 70) @@ -322,7 +322,7 @@ def test_dvs_camera_events(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/dvs_front/events", PointCloud2, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/dvs_front") finally: @@ -338,7 +338,7 @@ def test_lidar(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/lidar", PointCloud2, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/lidar") finally: @@ -354,7 +354,7 @@ def test_semantic_lidar(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/semantic_lidar", PointCloud2, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/semantic_lidar") finally: @@ -371,7 +371,7 @@ def test_radar(self): ros_init() node = None node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/radar_front", PointCloud2, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/radar_front") finally: @@ -387,7 +387,7 @@ def test_ego_vehicle_objects(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/ego_vehicle/objects", ObjectArray, timeout=15) self.assertEqual(msg.header.frame_id, "map") self.assertEqual(len(msg.objects), 0) @@ -404,7 +404,7 @@ def test_objects(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message("/carla/objects", ObjectArray, timeout=TIMEOUT) + msg = node.wait_for_message("/carla/objects", ObjectArray, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "map") self.assertEqual(len(msg.objects), 1) # only ego vehicle exists finally: @@ -420,7 +420,7 @@ def test_marker(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message("/carla/markers", MarkerArray, timeout=TIMEOUT) + msg = node.wait_for_message("/carla/markers", MarkerArray, timeout=TIMEOUT) self.assertEqual(len(msg.markers), 1) # only ego vehicle exists ego_marker = msg.markers[0] @@ -445,7 +445,7 @@ def test_map(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/map", String, timeout=TIMEOUT, qos_profile=QoSProfile(depth=10, durability=latch_on)) self.assertNotEqual(len(msg.data), 0) @@ -462,7 +462,7 @@ def test_world_info(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/world_info", CarlaWorldInfo, timeout=TIMEOUT, qos_profile=QoSProfile(depth=10, durability=latch_on)) self.assertNotEqual(len(msg.map_name), 0) @@ -480,7 +480,7 @@ def test_actor_list(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/actor_list", CarlaActorList, timeout=TIMEOUT) self.assertNotEqual(len(msg.actors), 0) finally: @@ -496,7 +496,7 @@ def test_traffic_lights(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/traffic_lights/status", CarlaTrafficLightStatusList, timeout=TIMEOUT, qos_profile=QoSProfile(depth=10, durability=latch_on)) self.assertNotEqual(len(msg.traffic_lights), 0) @@ -513,7 +513,7 @@ def test_traffic_lights_info(self): node = None ros_init() node = CompatibleNode('test_node') - msg = node.wait_for_one_message( + msg = node.wait_for_message( "/carla/traffic_lights/info", CarlaTrafficLightInfoList, timeout=TIMEOUT, qos_profile=QoSProfile(depth=10, durability=latch_on)) self.assertNotEqual(len(msg.traffic_lights), 0) diff --git a/carla_spawn_objects/config/objects.json b/carla_spawn_objects/config/objects.json index 4b87671c..daba209d 100644 --- a/carla_spawn_objects/config/objects.json +++ b/carla_spawn_objects/config/objects.json @@ -22,7 +22,7 @@ "id": "map" }, { - "type": "vehicle.*", + "type": "vehicle.tesla.model3", "id": "ego_vehicle", "sensors": [ diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index bceafd20..f14cb8d3 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -68,7 +68,7 @@ def __init__(self): def spawn_object(self, spawn_object_request): response_id = -1 - response = self.call_service(self.spawn_object_service, spawn_object_request) + response = self.call_service(self.spawn_object_service, spawn_object_request, spin_until_response_received=True) response_id = response.id if response_id != -1: self.loginfo("Object (type='{}', id='{}') spawned successfully as {}.".format( @@ -118,7 +118,7 @@ def spawn_objects(self): if self.spawn_sensors_only is True: # get vehicle id from topic /carla/actor_list for all vehicles listed in config file - actor_info_list = self.wait_for_one_message("/carla/actor_list", CarlaActorList) + actor_info_list = self.wait_for_message("/carla/actor_list", CarlaActorList) for vehicle in vehicles: for actor_info in actor_info_list.actors: if actor_info.type == vehicle["type"] and actor_info.rolename == vehicle["id"]: @@ -326,7 +326,7 @@ def destroy(self): destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = actor_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.5) + destroy_object_request, timeout_ros2=0.5, spin_until_response_received=True) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.vehicles_sensors = [] @@ -335,7 +335,7 @@ def destroy(self): destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = actor_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.5) + destroy_object_request, timeout_ros2=0.5, spin_until_response_received=True) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.global_sensors = [] @@ -344,7 +344,7 @@ def destroy(self): destroy_object_request = get_service_request(DestroyObject) destroy_object_request.id = player_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.5) + destroy_object_request, timeout_ros2=0.5, spin_until_response_received=True) self.loginfo("Object {} successfully destroyed.".format(player_id)) self.players = [] except ServiceException: diff --git a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py index 7ad24620..a703edd6 100755 --- a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py +++ b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py @@ -53,7 +53,7 @@ def __init__(self): # wait for ros bridge to create relevant topics try: - self.wait_for_one_message( + self.wait_for_message( "/carla/{}/odometry".format(role_name), Odometry) except ROSInterruptException as e: if not ros_ok: diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 639aca8a..63bff79e 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -109,14 +109,11 @@ def get_waypoint(self, req, response=None): carla_waypoint = self.map.get_waypoint(carla_position) response = get_service_response(GetWaypoint) - response.waypoint.pose.position.x = carla_waypoint.transform.location.x - response.waypoint.pose.position.y = -carla_waypoint.transform.location.y - response.waypoint.pose.position.z = carla_waypoint.transform.location.z + response.waypoint.pose = trans.carla_transform_to_ros_pose(carla_waypoint.transform) response.waypoint.is_junction = carla_waypoint.is_junction response.waypoint.road_id = carla_waypoint.road_id response.waypoint.section_id = carla_waypoint.section_id response.waypoint.lane_id = carla_waypoint.lane_id - #self.logwarn("Get waypoint {}".format(response.waypoint.pose.position)) return response def get_actor_waypoint(self, req, response=None): @@ -238,7 +235,7 @@ def connect_to_carla(self): self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: - self.wait_for_one_message("/carla/world_info", CarlaWorldInfo, + self.wait_for_message("/carla/world_info", CarlaWorldInfo, qos_profile=QoSProfile(depth=1, durability=latch_on), timeout=15.0) except ROSException as e: self.logerr("Error while waiting for world info: {}".format(e)) diff --git a/docs/carla_ad_agent.md b/docs/carla_ad_agent.md index cd7d4993..3e6de0e1 100644 --- a/docs/carla_ad_agent.md +++ b/docs/carla_ad_agent.md @@ -2,33 +2,91 @@ The [CARLA AD agent](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ad_agent) is an AD agent that can follow a given route, avoids crashes with other vehicles and respects the state of traffic lights by accessing ground truth data. It is used by the [CARLA AD demo](carla_ad_demo.md) to provide an example of how the ROS bridge can be used. -- [__Local Planner Node__](#local-planner-node) +- [__Requirements__](#requirements) - [__ROS API__](#ros-api) - - [Subscriptions](#subscriptions) - - [Publications](#publications) + - [__AD Agent Node__](#ad-agent-node) + - [Parameters](#parameters) + - [Subscriptions](#subscriptions) + - [Publications](#publications) + - [__Local Planner Node__](#local-planner-node) + - [Parameters](#parameters) + - [Subscriptions](#subscriptions) + - [Publications](#publications) + +Internally the CARLA AD Agent uses a separate node for [local planning](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_ad_agent/src/carla_ad_agent/local_planner.py). This node has been optimized for the `vehicle.tesla.model3`, as it does not have any gear shift delays. + +The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedia.org/wiki/Ziegler%E2%80%93Nichols_method). --- -## Local Planner Node +## Requirements -Internally the CARLA AD Agent uses a separate node for [local planning](https://github.com/carla-simulator/ros-bridge/blob/ros2/carla_ad_agent/src/carla_ad_agent/local_planner.py). This node has been optimized for the `vehicle.tesla.model3`, as it does not have any gear shift delays. +To be able to use the `carla_ad_agent`, a minimal set of sensors need to be spawned (see [Carla Spawn Objects](carla_spawn_objects.md) for information on how to spawn sensors): -The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedia.org/wiki/Ziegler%E2%80%93Nichols_method). +- An odometry pseudo sensor (`sensor.pseudo.odom`) with role-name `odometry` attached to the vehicle. +- An object pseudo sensor (`sensor.pseudo.objects`) with role-name `objects` attached to the vehicle. +- A traffic light pseudo sensor (`sensor.pseudo.traffic_lights`) with role-name `traffic_lights`. + +--- ## ROS API +### AD Agent Node + +#### Parameters + +| Parameter | Type | Description | +|-----------|------|-------------| +| `role_name` | string (default: `ego_vehicle`) | CARLA role name of the ego vehicle | +| `avoid_risk` | bool (default: `true`) | If True, avoids crashes with other vehicles and respects traffic lights | +| `target_speed` | float (default `30.0`) | Target speed of the ego vehicle | + +
+ #### Subscriptions | Topic | Type | Description | |-------|------|-------------| -| `/carla//waypoints` | [nav_msgs/Path](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | Route to follow | -| `/carla//target_speed` | [std_msgs/Float64](https://docs.ros.org/en/api/std_msgs/html/msg/Float64.html) | Target speed | -| `/carla//odometry` | [nav_msgs/Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Localization of ego vehicle | -| `/carla//vehicle_info` | [carla_msgs/CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) | Identify the carla actor id of the ego vehicle | +| `/carla//odometry` | [nav_msgs/Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Odometry of the ego vehicle | +| `/carla//vehicle_info` | [carla_msgs/CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) | Identify the CARLA actor id of the ego vehicle | | `/carla//objects` | [derived_object_msgs/ObjectArray](https://docs.ros.org/en/melodic/api/derived_object_msgs/html/msg/ObjectArray.html) | Information about other actors | -| `/carla/actor_list` | [carla_msgs/CarlaActorList](ros_msgs.md#carlaactorlistmsg) | Actor list | -| `/carla/world_info` | [carla_msgs/CarlaWorldInfo](ros_msgs.md#carlaworldinfomsg) | Selects mode for traffic lights (US- or European-style) | | `/carla/traffic_lights/status` | [carla_msgs/CarlaTrafficLightStatusList](ros_msgs.md#carlatrafficlightstatuslistmsg) | Get the current state of the traffic lights | +| `/carla/traffic_lights/info` | [carla_msgs/CarlaTrafficLightInfoList](ros_msgs.md#carlatrafficlightinfolistmsg) | Get info about traffic lights | + +
+ +#### Publications + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//speed_command` | [std_msgs/Float64](https://docs.ros.org/en/api/std_msgs/html/msg/Float64.html) | Target speed | + +
+ +### Local Planner Node + +#### Parameters + +| Parameter | Type | Description | +|-----------|------|-------------| +| `role_name` | string (default: `ego_vehicle`) | CARLA role name of the ego vehicle | +| `control_time_step` | float (default: `0.05`) | Control loop rate | +| `Kp_lateral` | float (default `0.9`) | Proportional term lateral PID controller | +| `Ki_lateral` | float (default `0.0`) | Integral term lateral PID controller | +| `Kd_lateral` | float (default `0.0`) | Derivative term lateral PID controller | +| `Kp_longitudinal` | float (default `0.206`) | Proportional term longitudinal PID controller | +| `Ki_longitudinal` | float (default `0.0206`) | Integral term longitudinal PID controller | +| `Kd_longitudinal` | float (default `0.515`) | Derivative term longitudinal PID controller | + +
+ +#### Subscriptions + +| Topic | Type | Description | +|-------|------|-------------| +| `/carla//waypoints` | [nav_msgs/Path](https://docs.ros.org/en/api/nav_msgs/html/msg/Path.html) | Route to follow | +| `/carla//odometry` | [nav_msgs/Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Odometry of the ego vehicle | +| `/carla//speed_command` | [std_msgs/Float64](https://docs.ros.org/en/api/std_msgs/html/msg/Float64.html) | Target speed |
@@ -36,6 +94,7 @@ The PID parameters were gathered by [Ziegler-Nichols method](https://en.wikipedi | Topic | Type | Description | |-------|------|-------------| +| `/carla//next_target` | [visualization_msgs/Marker](http://docs.ros.org/en/api/visualization_msgs/html/msg/Marker.html) | Next target pose marker | | `/carla//vehicle_control_cmd` | [carla_msgs/CarlaEgoVehicleControl](ros_msgs.md#carlaegovehiclecontrolmsg) | Vehicle control command |
diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py index 18f6a8a9..9dea7219 100644 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py @@ -75,6 +75,10 @@ def __init__(self, depth=10, durability=None, **kwargs): self.depth = depth self.latch = bool(durability) + class MultiThreadedExecutor(object): + def add_node(self, node): + pass + class CompatibleNode(object): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): if rospy_init: @@ -138,7 +142,7 @@ def new_rate(self, rate): def new_timer(self, timer_period_sec, callback): return rospy.Timer(rospy.Duration(timer_period_sec), callback) - def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None, executor=None): + def wait_for_message(self, topic, topic_type, timeout=None, qos_profile=None, executor=None): try: return rospy.wait_for_message(topic, topic_type, timeout) except rospy.ROSException as e: @@ -161,7 +165,7 @@ def create_service_client(self, service_name, service, timeout_sec=None, callbac raise ROSException(e) return client - def call_service(self, client, req, timeout_ros2=None, executor=None): + def call_service(self, client, req, timeout_ros2=None, executor=None, spin_until_response_received=False): try: return client(req) except rospy.ServiceException as e: @@ -185,6 +189,9 @@ def on_shutdown(self, handler): from rclpy.exceptions import ROSInterruptException from rclpy.node import Node from rclpy.qos import QoSProfile, QoSDurabilityPolicy + from rclpy.task import Future + from rclpy.executors import MultiThreadedExecutor + from rclpy.callback_groups import MutuallyExclusiveCallbackGroup, ReentrantCallbackGroup from builtin_interfaces.msg import Time latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL @@ -230,14 +237,6 @@ def logerr(log): def logfatal(log): rclpy.logging.get_logger("default").fatal(log) - class WaitForMessageHelper(object): - def __init__(self): - self.msg = None - - def callback(self, msg): - if self.msg is None: - self.msg = msg - def get_service_request(service_type): return service_type.Request() @@ -253,6 +252,9 @@ class ROSInterruptException(ROSInterruptException): class ServiceException(Exception): pass + class MultiThreadedExecutor(MultiThreadedExecutor): + pass + class CompatibleNode(Node): def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): param = Parameter('use_sim_time', Parameter.Type.BOOL, True) @@ -306,7 +308,7 @@ def create_subscriber(self, msg_type, topic, callback, qos_profile=None, if qos_profile is None: qos_profile = self.qos_profile if callback_group is None: - callback_group = self.callback_group + callback_group = MutuallyExclusiveCallbackGroup() return self.create_subscription(msg_type, topic, callback, qos_profile, callback_group=callback_group) @@ -316,37 +318,35 @@ def new_rate(self, rate): def new_timer(self, timer_period_sec, callback): return self.create_timer(timer_period_sec, callback) - def wait_for_one_message(self, topic, topic_type, timeout=None, qos_profile=None, executor=None): + def wait_for_message(self, topic, topic_type, timeout=None, qos_profile=None, executor=None): + """ + Wait for one message from topic. + + This will create a new subcription to the topic, receive one message, then unsubscribe. + + Do not call this method in a callback or a deadlock may occur. + """ s = None - wfm = WaitForMessageHelper() try: - s = self.create_subscriber(topic_type, topic, wfm.callback, qos_profile=qos_profile) - if timeout is not None: - timeout_t = time.time() + timeout - while ros_ok() and wfm.msg is None: - time.sleep(0.01) - if executor is None: - rclpy.spin_once(self, timeout_sec=0) - else: - executor.spin_once(timeout_sec=0) - if time.time() >= timeout_t: - raise ROSException - else: - while ros_ok() and wfm.msg is None: - time.sleep(0.01) - if executor is None: - rclpy.spin_once(self, timeout_sec=0) - else: - executor.spin_once(timeout_sec=0) + future = Future() + s = self.create_subscriber( + topic_type, + topic, + lambda msg: future.set_result(msg), + qos_profile=qos_profile) + rclpy.spin_until_future_complete(self, future, self.executor, timeout) finally: if s is not None: self.destroy_subscription(s) - return wfm.msg + + return future.result() def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): return self.create_service(srv_type, srv_name, callback, callback_group=callback_group) def create_service_client(self, service_name, service, timeout_sec=None, callback_group=None): + if callback_group is None: + callback_group = MutuallyExclusiveCallbackGroup() client = self.create_client(service, service_name, callback_group=callback_group) status = client.wait_for_service(timeout_sec=timeout_sec) if status is True: @@ -354,26 +354,26 @@ def create_service_client(self, service_name, service, timeout_sec=None, callbac else: raise ROSException("Timeout of {}sec while waiting for service".format(timeout_sec)) - def call_service(self, client, req, timeout_ros2=None, executor=None): - # uses the asynchronous call function but behaves like the synchronous call - # this is done because the basic synchronous call function doesn't raise - # an error when trying to call a service that is not alive anymore - future = client.call_async(req) - if executor is None: - rclpy.spin_until_future_complete(self, future, timeout_sec=timeout_ros2) - else: - executor.spin_until_future_complete(future, timeout_sec=timeout_ros2) - if future.done(): - return future.result() + def call_service(self, client, req, timeout_ros2=None, executor=None, spin_until_response_received=False): + + if not spin_until_response_received: + response = client.call(req) + return response else: - if timeout_ros2 is not None: - raise ServiceException( - 'Service did not return a response before timeout {}'.format(timeout_ros2)) + future = client.call_async(req) + rclpy.spin_until_future_complete(self, future, self.executor, timeout_ros2) + + if future.done(): + return future.result() else: - raise ServiceException('Service did not return a response') + if timeout_ros2 is not None: + raise ServiceException( + 'Service did not return a response before timeout {}'.format(timeout_ros2)) + else: + raise ServiceException('Service did not return a response') def spin(self, executor=None): - rclpy.spin(self, executor) + rclpy.spin(self, self.executor) def get_time(self): t = self.get_clock().now() From 00a90cbe6729a469a4fc7f5e989e833bada3cbfa Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 6 May 2021 09:19:07 +0200 Subject: [PATCH 603/627] Carla_ad_agent: Use target_speed from scenario --- carla_ad_agent/launch/carla_ad_agent.launch | 2 -- carla_ad_agent/launch/carla_ad_agent.launch.py | 7 ------- carla_ad_agent/src/carla_ad_agent/ad_agent.py | 16 ++++++++++++++-- carla_ad_agent/src/carla_ad_agent/agent.py | 9 +++++++-- .../src/carla_ad_agent/local_planner.py | 6 +++--- carla_ad_demo/config/FollowLeadingVehicle.xosc | 12 +++++++++++- .../ros_vehicle_control.py | 8 +++++--- docs/carla_ad_agent.md | 2 +- 8 files changed, 41 insertions(+), 21 deletions(-) diff --git a/carla_ad_agent/launch/carla_ad_agent.launch b/carla_ad_agent/launch/carla_ad_agent.launch index 5440aaf5..71b78102 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch +++ b/carla_ad_agent/launch/carla_ad_agent.launch @@ -1,7 +1,6 @@ - @@ -12,7 +11,6 @@ - diff --git a/carla_ad_agent/launch/carla_ad_agent.launch.py b/carla_ad_agent/launch/carla_ad_agent.launch.py index dc66b062..90edd787 100644 --- a/carla_ad_agent/launch/carla_ad_agent.launch.py +++ b/carla_ad_agent/launch/carla_ad_agent.launch.py @@ -8,10 +8,6 @@ def generate_launch_description(): name='role_name', default_value='ego_vehicle' ), - launch.actions.DeclareLaunchArgument( - name='target_speed', - default_value='30.0' - ), launch.actions.DeclareLaunchArgument( name='avoid_risk', default_value='True' @@ -50,9 +46,6 @@ def generate_launch_description(): name=['carla_ad_agent_', launch.substitutions.LaunchConfiguration('role_name')], output='screen', parameters=[ - { - 'target_speed': launch.substitutions.LaunchConfiguration('target_speed') - }, { 'role_name': launch.substitutions.LaunchConfiguration('role_name') }, diff --git a/carla_ad_agent/src/carla_ad_agent/ad_agent.py b/carla_ad_agent/src/carla_ad_agent/ad_agent.py index d701933c..44a55d05 100755 --- a/carla_ad_agent/src/carla_ad_agent/ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/ad_agent.py @@ -55,7 +55,6 @@ def __init__(self): role_name = self.get_param("role_name", "ego_vehicle") self._avoid_risk = self.get_param("avoid_risk", True) - self._target_speed = self.get_param("target_speed", 30.0) self.data_lock = threading.Lock() @@ -63,6 +62,7 @@ def __init__(self): self._objects = {} self._lights_status = {} self._lights_info = {} + self._target_speed = 0. self.speed_command_publisher = self.new_publisher( Float64, "/carla/{}/speed_command".format(role_name), @@ -74,6 +74,13 @@ def __init__(self): self.odometry_cb ) + self._target_speed_subscriber = self.create_subscriber( + Float64, + "/carla/{}/target_speed".format(role_name), + self.target_speed_cb, + qos_profile=QoSProfile(depth=10, durability=latch_on) + ) + if self._avoid_risk: self._objects_subscriber = self.create_subscriber( @@ -98,6 +105,10 @@ def odometry_cb(self, odometry_msg): with self.data_lock: self._ego_vehicle_pose = odometry_msg.pose.pose + def target_speed_cb(self, target_speed_msg): + with self.data_lock: + self._target_speed = target_speed_msg.data + def objects_cb(self, objects_msg): objects = {} for obj in objects_msg.objects: @@ -136,6 +147,7 @@ def run_step(self): objects = copy.deepcopy(self._objects) lights_info = copy.deepcopy(self._lights_info) lights_status = copy.deepcopy(self._lights_status) + target_speed = copy.deepcopy(self._target_speed) if ego_vehicle_pose is None: self.loginfo("Waiting for ego vehicle pose") @@ -164,7 +176,7 @@ def run_step(self): speed_command.data = 0.0 else: self._state = AgentState.NAVIGATING - speed_command.data = self._target_speed + speed_command.data = target_speed self.speed_command_publisher.publish(speed_command) diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 662d3cfc..7665361c 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -18,7 +18,9 @@ CompatibleNode, ros_ok, ServiceException, - get_service_request) + get_service_request, + QoSProfile, + latch_on) import carla_common.transforms as trans @@ -58,9 +60,12 @@ def __init__(self, name="agent"): self._proximity_vehicle_threshold = 12.0 # meters role_name = self.get_param("role_name", "ego_vehicle") + self.loginfo("Waiting for vehicle_info...") vehicle_info = self.wait_for_message( "/carla/{}/vehicle_info".format(role_name), - CarlaEgoVehicleInfo) + CarlaEgoVehicleInfo, + qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.loginfo("Vehicle info received.") self._ego_vehicle_id = vehicle_info.id self._get_waypoint_client = self.create_service_client( diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index 5001e329..cb2e01cc 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -14,7 +14,7 @@ import math import threading -from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION +from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION, latch_on from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error from nav_msgs.msg import Odometry, Path @@ -74,12 +74,12 @@ def __init__(self): Path, "/carla/{}/waypoints".format(role_name), self.path_cb, - QoSProfile(depth=1, durability=True)) + QoSProfile(depth=1, durability=latch_on)) self._target_speed_subscriber = self.create_subscriber( Float64, "/carla/{}/speed_command".format(role_name), self.target_speed_cb, - QoSProfile(depth=1, durability=True)) + QoSProfile(depth=1, durability=latch_on)) # publishers self._target_pose_publisher = self.new_publisher( diff --git a/carla_ad_demo/config/FollowLeadingVehicle.xosc b/carla_ad_demo/config/FollowLeadingVehicle.xosc index 885ed1ab..d9616078 100644 --- a/carla_ad_demo/config/FollowLeadingVehicle.xosc +++ b/carla_ad_demo/config/FollowLeadingVehicle.xosc @@ -92,7 +92,17 @@ - + + + + + + + + + + + diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 257b3b7e..38f7b128 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -15,7 +15,7 @@ import carla_common.transforms as trans from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error -from ros_compatibility import CompatibleNode, QoSProfile, ros_timestamp, ros_init +from ros_compatibility import CompatibleNode, QoSProfile, ros_timestamp, ros_init, latch_on import os ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) @@ -53,11 +53,13 @@ def __init__(self, actor, args=None): self._target_speed_publisher = self.node.new_publisher( Float64, "/carla/{}/target_speed".format(self._role_name), - QoSProfile(depth=1, durability=True)) + QoSProfile(depth=10, durability=latch_on)) + self.node.loginfo("Publishing target_speed on /carla/{}/target_speed".format(self._role_name)) self._path_publisher = self.node.new_publisher( Path, "/carla/{}/{}".format(self._role_name, self._path_topic_name), - QoSProfile(depth=1, durability=True)) + QoSProfile(depth=10, durability=latch_on)) + self.node.loginfo("Publishing path on /carla/{}/{}".format(self._role_name, self._path_topic_name)) if "launch" in args and "launch-package" in args: diff --git a/docs/carla_ad_agent.md b/docs/carla_ad_agent.md index 3e6de0e1..62a24903 100644 --- a/docs/carla_ad_agent.md +++ b/docs/carla_ad_agent.md @@ -39,7 +39,6 @@ To be able to use the `carla_ad_agent`, a minimal set of sensors need to be spaw |-----------|------|-------------| | `role_name` | string (default: `ego_vehicle`) | CARLA role name of the ego vehicle | | `avoid_risk` | bool (default: `true`) | If True, avoids crashes with other vehicles and respects traffic lights | -| `target_speed` | float (default `30.0`) | Target speed of the ego vehicle |
@@ -47,6 +46,7 @@ To be able to use the `carla_ad_agent`, a minimal set of sensors need to be spaw | Topic | Type | Description | |-------|------|-------------| +| `/carla//target_speed` | [std_msgs/Float64](https://docs.ros.org/en/api/std_msgs/html/msg/Float64.html) | Target speed of the ego vehicle | | `/carla//odometry` | [nav_msgs/Odometry](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) | Odometry of the ego vehicle | | `/carla//vehicle_info` | [carla_msgs/CarlaEgoVehicleInfo](ros_msgs.md#carlaegovehicleinfomsg) | Identify the CARLA actor id of the ego vehicle | | `/carla//objects` | [derived_object_msgs/ObjectArray](https://docs.ros.org/en/melodic/api/derived_object_msgs/html/msg/ObjectArray.html) | Information about other actors | From 425a210b8a134e46108d5f44bc75bf9dd2ec7fcd Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 6 May 2021 10:02:44 +0200 Subject: [PATCH 604/627] fix carla_ad_demo launch files --- carla_ad_agent/src/carla_ad_agent/ad_agent.py | 2 +- carla_ad_demo/launch/carla_ad_demo.launch | 6 ++++-- carla_ad_demo/launch/carla_ad_demo.launch.py | 13 +++++++++++-- 3 files changed, 16 insertions(+), 5 deletions(-) diff --git a/carla_ad_agent/src/carla_ad_agent/ad_agent.py b/carla_ad_agent/src/carla_ad_agent/ad_agent.py index 44a55d05..46378fb6 100755 --- a/carla_ad_agent/src/carla_ad_agent/ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/ad_agent.py @@ -107,7 +107,7 @@ def odometry_cb(self, odometry_msg): def target_speed_cb(self, target_speed_msg): with self.data_lock: - self._target_speed = target_speed_msg.data + self._target_speed = target_speed_msg.data * 3.6 # target speed from scenario is in m/s def objects_cb(self, objects_msg): objects = {} diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch index 3a230af0..2d73c568 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -14,11 +14,14 @@ - + + + + @@ -40,7 +43,6 @@ - diff --git a/carla_ad_demo/launch/carla_ad_demo.launch.py b/carla_ad_demo/launch/carla_ad_demo.launch.py index 3c39b824..19336f89 100644 --- a/carla_ad_demo/launch/carla_ad_demo.launch.py +++ b/carla_ad_demo/launch/carla_ad_demo.launch.py @@ -24,6 +24,15 @@ def launch_carla_spawn_object(context, *args, **kwargs): return [carla_spawn_objects_launch] +def launch_target_speed_publisher(context, *args, **kwargs): + topic_name = "/carla/" + launch.substitutions.LaunchConfiguration('role_name').perform(context) + "/target_speed" + data_string = "{'data': " + launch.substitutions.LaunchConfiguration('target_speed').perform(context) + "}" + return [ + launch.actions.ExecuteProcess( + output="screen", + cmd=["ros2", "topic", "pub", topic_name, + "std_msgs/msg/Float64", data_string, "--qos-durability", "transient_local"], + name='topic_pub_target_speed')] def generate_launch_description(): ld = launch.LaunchDescription([ @@ -61,7 +70,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='target_speed', - default_value='30.0' + default_value='8.33' # in m/s ), launch.actions.DeclareLaunchArgument( name='avoid_risk', @@ -86,13 +95,13 @@ def generate_launch_description(): }.items() ), launch.actions.OpaqueFunction(function=launch_carla_spawn_object), + launch.actions.OpaqueFunction(function=launch_target_speed_publisher), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( 'carla_ad_agent'), 'carla_ad_agent.launch.py') ), launch_arguments={ - 'target_speed': launch.substitutions.LaunchConfiguration('target_speed'), 'role_name': launch.substitutions.LaunchConfiguration('role_name'), 'avoid_risk': launch.substitutions.LaunchConfiguration('avoid_risk') }.items() From 2e39733e59866eb289d4703c1f761fcf21585a10 Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Fri, 7 May 2021 11:21:35 +0200 Subject: [PATCH 605/627] Use underscores instead of dashes in setup.cfg (#536) --- carla_ackermann_control/setup.cfg | 4 ++-- carla_ad_agent/setup.cfg | 4 ++-- carla_common/setup.cfg | 4 ++-- carla_manual_control/setup.cfg | 4 ++-- carla_ros_bridge/setup.cfg | 4 ++-- carla_ros_scenario_runner/setup.cfg | 4 ++-- carla_spawn_objects/setup.cfg | 4 ++-- carla_twist_to_control/setup.cfg | 4 ++-- carla_walker_agent/setup.cfg | 4 ++-- carla_waypoint_publisher/setup.cfg | 4 ++-- ros_compatibility/setup.cfg | 4 ++-- rqt_carla_control/setup.cfg | 4 ++-- 12 files changed, 24 insertions(+), 24 deletions(-) diff --git a/carla_ackermann_control/setup.cfg b/carla_ackermann_control/setup.cfg index 5cfd1ab5..c68e601a 100644 --- a/carla_ackermann_control/setup.cfg +++ b/carla_ackermann_control/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_ackermann_control +script_dir=$base/lib/carla_ackermann_control [install] -install-scripts=$base/lib/carla_ackermann_control +install_scripts=$base/lib/carla_ackermann_control diff --git a/carla_ad_agent/setup.cfg b/carla_ad_agent/setup.cfg index ddf4d548..751d435d 100644 --- a/carla_ad_agent/setup.cfg +++ b/carla_ad_agent/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_ad_agent +script_dir=$base/lib/carla_ad_agent [install] -install-scripts=$base/lib/carla_ad_agent \ No newline at end of file +install_scripts=$base/lib/carla_ad_agent \ No newline at end of file diff --git a/carla_common/setup.cfg b/carla_common/setup.cfg index b59f6965..5233821a 100644 --- a/carla_common/setup.cfg +++ b/carla_common/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_common +script_dir=$base/lib/carla_common [install] -install-scripts=$base/lib/carla_common +install_scripts=$base/lib/carla_common diff --git a/carla_manual_control/setup.cfg b/carla_manual_control/setup.cfg index 18dba7db..eff79aba 100644 --- a/carla_manual_control/setup.cfg +++ b/carla_manual_control/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_manual_control +script_dir=$base/lib/carla_manual_control [install] -install-scripts=$base/lib/carla_manual_control +install_scripts=$base/lib/carla_manual_control diff --git a/carla_ros_bridge/setup.cfg b/carla_ros_bridge/setup.cfg index bf9eb67b..0086a7f7 100644 --- a/carla_ros_bridge/setup.cfg +++ b/carla_ros_bridge/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_ros_bridge +script_dir=$base/lib/carla_ros_bridge [install] -install-scripts=$base/lib/carla_ros_bridge +install_scripts=$base/lib/carla_ros_bridge diff --git a/carla_ros_scenario_runner/setup.cfg b/carla_ros_scenario_runner/setup.cfg index 90722478..9f051eb9 100644 --- a/carla_ros_scenario_runner/setup.cfg +++ b/carla_ros_scenario_runner/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_ros_scenario_runner +script_dir=$base/lib/carla_ros_scenario_runner [install] -install-scripts=$base/lib/carla_ros_scenario_runner \ No newline at end of file +install_scripts=$base/lib/carla_ros_scenario_runner \ No newline at end of file diff --git a/carla_spawn_objects/setup.cfg b/carla_spawn_objects/setup.cfg index 05c97668..1a7ce0a0 100644 --- a/carla_spawn_objects/setup.cfg +++ b/carla_spawn_objects/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_spawn_objects +script_dir=$base/lib/carla_spawn_objects [install] -install-scripts=$base/lib/carla_spawn_objects +install_scripts=$base/lib/carla_spawn_objects diff --git a/carla_twist_to_control/setup.cfg b/carla_twist_to_control/setup.cfg index e19fecd4..bd2706ab 100644 --- a/carla_twist_to_control/setup.cfg +++ b/carla_twist_to_control/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_twist_to_control +script_dir=$base/lib/carla_twist_to_control [install] -install-scripts=$base/lib/carla_twist_to_control +install_scripts=$base/lib/carla_twist_to_control diff --git a/carla_walker_agent/setup.cfg b/carla_walker_agent/setup.cfg index 0031b079..07ca1d58 100644 --- a/carla_walker_agent/setup.cfg +++ b/carla_walker_agent/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_walker_agent +script_dir=$base/lib/carla_walker_agent [install] -install-scripts=$base/lib/carla_walker_agent \ No newline at end of file +install_scripts=$base/lib/carla_walker_agent \ No newline at end of file diff --git a/carla_waypoint_publisher/setup.cfg b/carla_waypoint_publisher/setup.cfg index 80a8263a..0b882d6d 100644 --- a/carla_waypoint_publisher/setup.cfg +++ b/carla_waypoint_publisher/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/carla_waypoint_publisher +script_dir=$base/lib/carla_waypoint_publisher [install] -install-scripts=$base/lib/carla_waypoint_publisher \ No newline at end of file +install_scripts=$base/lib/carla_waypoint_publisher \ No newline at end of file diff --git a/ros_compatibility/setup.cfg b/ros_compatibility/setup.cfg index 9c25a3a8..60845706 100644 --- a/ros_compatibility/setup.cfg +++ b/ros_compatibility/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/ros_compatibility +script_dir=$base/lib/ros_compatibility [install] -install-scripts=$base/lib/ros_compatibility +install_scripts=$base/lib/ros_compatibility diff --git a/rqt_carla_control/setup.cfg b/rqt_carla_control/setup.cfg index f9045d9a..c2aa2ab3 100644 --- a/rqt_carla_control/setup.cfg +++ b/rqt_carla_control/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/rqt_carla_control +script_dir=$base/lib/rqt_carla_control [install] -install-scripts=$base/lib/rqt_carla_control +install_scripts=$base/lib/rqt_carla_control From eb1f2d64708a8b771ab6672a43ab9848b1aca7cc Mon Sep 17 00:00:00 2001 From: fpasch <46815108+fpasch@users.noreply.github.com> Date: Fri, 7 May 2021 11:52:52 +0200 Subject: [PATCH 606/627] Fix tf for sensors that are moved by actor.pseudo.control (#537) Co-authored-by: joel-mb --- carla_ros_bridge/src/carla_ros_bridge/actor_control.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index 8c13655c..37213877 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -13,6 +13,7 @@ import math import carla_common.transforms as trans from carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.sensor import Sensor from geometry_msgs.msg import Pose, Twist from carla import Vector3D @@ -74,6 +75,8 @@ def get_blueprint_name(): def on_pose(self, pose): if self.parent and self.parent.carla_actor.is_alive: self.parent.carla_actor.set_transform(trans.ros_pose_to_carla_transform(pose)) + if isinstance(self.parent, Sensor): + self.parent.relative_spawn_pose = pose def on_twist(self, twist): """ From b26af64eb8af0105ace11ea72ddd9b8de9a7c55d Mon Sep 17 00:00:00 2001 From: Joel Moriana Date: Fri, 7 May 2021 13:28:56 +0200 Subject: [PATCH 607/627] fixed unicode type issue pexpect (melodic) --- .../src/carla_ros_scenario_runner/application_runner.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py index 1a1f84d4..1a813ad7 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -132,7 +132,7 @@ def run(self, process, shutdown_requested_event, ready_string, status_updated_fc Sending SIGKILL") process.terminate(force=True) try: - process.expect(".*\n", timeout=0.1) + process.expect(u".*\n", timeout=0.1) log_fct(process.after.strip()) if not signaled_running: if str(process.after).find(ready_string) != -1: From 9e7fa11ad5cd4a27a23d7eba9ada2082dd431ff2 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Mon, 14 Jun 2021 17:04:35 +0200 Subject: [PATCH 608/627] Bridge Refactoring (#542) This PR refactors the ros_compatibility backend. The new backend tries to copy as much as possible the ROS2 API. All the other packages have been updated consequently. --- CHANGELOG.md | 1 + .../launch/carla_ackermann_control.launch.py | 2 +- .../carla_ackermann_control_node.py | 55 +-- carla_ad_agent/src/carla_ad_agent/ad_agent.py | 75 ++-- carla_ad_agent/src/carla_ad_agent/agent.py | 30 +- .../src/carla_ad_agent/local_planner.py | 44 +- .../carla_manual_control.py | 237 +++++------ .../src/carla_ros_bridge/actor.py | 6 +- .../src/carla_ros_bridge/actor_control.py | 22 +- .../src/carla_ros_bridge/actor_factory.py | 49 +-- .../src/carla_ros_bridge/actor_list_sensor.py | 3 +- .../src/carla_ros_bridge/bridge.py | 97 ++--- .../src/carla_ros_bridge/camera.py | 22 +- .../carla_status_publisher.py | 18 +- .../src/carla_ros_bridge/collision_sensor.py | 4 +- .../src/carla_ros_bridge/debug_helper.py | 8 +- .../src/carla_ros_bridge/ego_vehicle.py | 49 ++- carla_ros_bridge/src/carla_ros_bridge/gnss.py | 7 +- carla_ros_bridge/src/carla_ros_bridge/imu.py | 10 +- .../carla_ros_bridge/lane_invasion_sensor.py | 4 +- .../src/carla_ros_bridge/lidar.py | 12 +- .../src/carla_ros_bridge/marker_sensor.py | 3 +- .../src/carla_ros_bridge/object_sensor.py | 8 +- .../src/carla_ros_bridge/odom_sensor.py | 3 +- .../src/carla_ros_bridge/opendrive_sensor.py | 10 +- .../src/carla_ros_bridge/pseudo_actor.py | 12 +- .../src/carla_ros_bridge/radar.py | 6 +- .../src/carla_ros_bridge/sensor.py | 30 +- .../carla_ros_bridge/speedometer_sensor.py | 3 +- .../src/carla_ros_bridge/tf_sensor.py | 9 +- .../src/carla_ros_bridge/traffic.py | 7 +- .../carla_ros_bridge/traffic_lights_sensor.py | 13 +- .../carla_ros_bridge/traffic_participant.py | 6 +- .../src/carla_ros_bridge/vehicle.py | 7 +- .../src/carla_ros_bridge/walker.py | 10 +- .../src/carla_ros_bridge/world_info.py | 10 +- .../test/ros_bridge_client_ros2_test.py | 103 ++--- .../carla_ros_scenario_runner_node.py | 43 +- .../ros_vehicle_control.py | 71 ++-- .../scenario_runner_runner.py | 5 +- .../carla_example_ego_vehicle.launch.py | 18 + .../launch/set_initial_pose.launch.py | 39 ++ carla_spawn_objects/setup.py | 3 +- .../carla_spawn_objects.py | 69 ++- .../carla_spawn_objects/set_initial_pose.py | 39 +- .../carla_twist_to_control.py | 76 ++-- .../carla_walker_agent/carla_walker_agent.py | 137 +++--- .../carla_waypoint_publisher.py | 67 ++- docs/carla_manual_control.md | 2 +- pcl_recorder/launch/pcl_recorder.launch.py | 21 +- pcl_recorder/src/PclRecorder.cpp | 2 +- pcl_recorder/src/PclRecorderROS2.cpp | 18 +- pcl_recorder/src/mainROS2.cpp | 8 +- ros_compatibility/CMakeLists.txt | 3 - .../src/ros_compatibility/__init__.py | 112 ++++- .../src/ros_compatibility/callback_groups.py | 33 ++ .../src/ros_compatibility/core.py | 20 + .../src/ros_compatibility/exceptions.py | 39 ++ .../src/ros_compatibility/executors.py | 35 ++ .../src/ros_compatibility/logging.py | 49 +++ .../src/ros_compatibility/node.py | 252 +++++++++++ .../src/ros_compatibility/qos.py | 25 ++ .../ros_compatibility/ros_compatible_node.py | 400 ------------------ .../rqt_carla_control/rqt_carla_control.py | 43 +- 64 files changed, 1399 insertions(+), 1225 deletions(-) create mode 100644 carla_spawn_objects/launch/set_initial_pose.launch.py create mode 100644 ros_compatibility/src/ros_compatibility/callback_groups.py create mode 100644 ros_compatibility/src/ros_compatibility/core.py create mode 100644 ros_compatibility/src/ros_compatibility/exceptions.py create mode 100644 ros_compatibility/src/ros_compatibility/executors.py create mode 100644 ros_compatibility/src/ros_compatibility/logging.py create mode 100644 ros_compatibility/src/ros_compatibility/node.py create mode 100644 ros_compatibility/src/ros_compatibility/qos.py delete mode 100644 ros_compatibility/src/ros_compatibility/ros_compatible_node.py diff --git a/CHANGELOG.md b/CHANGELOG.md index 9e9ff0fa..e44739f9 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Added hybrid ROS1/ROS2 bridge. * Added passive mode. Wordl configuration and ticking are performed by other clients. * Support spawning of pseudo-actors through service * Use new spawning service to combine carla_infrastructure and carla_ego_vehicle into carla_spawn_objects diff --git a/carla_ackermann_control/launch/carla_ackermann_control.launch.py b/carla_ackermann_control/launch/carla_ackermann_control.launch.py index de1b0d0f..6fda877a 100644 --- a/carla_ackermann_control/launch/carla_ackermann_control.launch.py +++ b/carla_ackermann_control/launch/carla_ackermann_control.launch.py @@ -18,7 +18,7 @@ def generate_launch_description(): launch_ros.actions.Node( package='carla_ackermann_control', executable='carla_ackermann_control_node', - node_name='carla_ackermann_control', + name='carla_ackermann_control', output='screen', parameters=[ Path(get_package_share_directory('carla_ackermann_control'), "settings.yaml"), diff --git a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py index e14aee99..dc03b707 100755 --- a/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py +++ b/carla_ackermann_control/src/carla_ackermann_control/carla_ackermann_control_node.py @@ -9,9 +9,17 @@ """ Control Carla ego vehicle by using AckermannDrive messages """ -import sys + import datetime +import sys + import numpy +from simple_pid import PID # pylint: disable=import-error,wrong-import-order + +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode + +from carla_ackermann_control import carla_control_physics as phys from ackermann_msgs.msg import AckermannDrive # pylint: disable=import-error from carla_msgs.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module,import-error @@ -19,10 +27,7 @@ from carla_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module,import-error from carla_ackermann_msgs.msg import EgoVehicleControlInfo # pylint: disable=no-name-in-module,import-error -from ros_compatibility import CompatibleNode, QoSProfile, ros_init, ROS_VERSION -from carla_ackermann_control import carla_control_physics as phys - -from simple_pid import PID # pylint: disable=import-error,wrong-import-order +ROS_VERSION = roscomp.get_ros_version() if ROS_VERSION == 1: from carla_ackermann_control.cfg import EgoVehicleControlParameterConfig @@ -42,9 +47,7 @@ def __init__(self): Constructor """ - super(CarlaAckermannControl, self).__init__( - "carla_ackermann_control", rospy_init=True - ) + super(CarlaAckermannControl, self).__init__("carla_ackermann_control") # PID controller # the controller has to run with the simulation time, not with real-time @@ -78,7 +81,7 @@ def __init__(self): callback=self.reconfigure_pid_parameters, ) if ROS_VERSION == 2: - self.set_parameters_callback(self.reconfigure_pid_parameters) + self. add_on_set_parameters_callback(self.reconfigure_pid_parameters) self.control_loop_rate = self.get_param("control_loop_rate", 0.05) self.lastAckermannMsgReceived = datetime.datetime(datetime.MINYEAR, 1, 1) @@ -122,37 +125,40 @@ def __init__(self): self.info.output.hand_brake = True # ackermann drive commands - self.control_subscriber = self.create_subscriber( + self.control_subscriber = self.new_subscription( AckermannDrive, "/carla/" + self.role_name + "/ackermann_cmd", - self.ackermann_command_updated + self.ackermann_command_updated, + qos_profile=10 ) # current status of the vehicle - self.vehicle_status_subscriber = self.create_subscriber( + self.vehicle_status_subscriber = self.new_subscription( CarlaEgoVehicleStatus, "/carla/" + self.role_name + "/vehicle_status", self.vehicle_status_updated, + qos_profile=10 ) # vehicle info - self.vehicle_info_subscriber = self.create_subscriber( + self.vehicle_info_subscriber = self.new_subscription( CarlaEgoVehicleInfo, "/carla/" + self.role_name + "/vehicle_info", self.vehicle_info_updated, + qos_profile=10 ) # to send command to carla self.carla_control_publisher = self.new_publisher( CarlaEgoVehicleControl, "/carla/" + self.role_name + "/vehicle_control_cmd", - qos_profile=QoSProfile(depth=1)) + qos_profile=1) # report controller info self.control_info_publisher = self.new_publisher( EgoVehicleControlInfo, "/carla/" + self.role_name + "/ackermann_control/control_info", - qos_profile=QoSProfile(depth=1)) + qos_profile=1) if ROS_VERSION == 1: @@ -182,10 +188,7 @@ def reconfigure_pid_parameters(self, ego_vehicle_control_parameter, _level): return ego_vehicle_control_parameter if ROS_VERSION == 2: - # annotations not supported in Python 2 (ROS1) - # def reconfigure_pid_parameters( # pylint: disable=function-redefined def reconfigure_pid_parameters(self, params): # pylint: disable=function-redefined - # self, params: Sequence[Parameter] - # ) -> SetParametersResult: + def reconfigure_pid_parameters(self, params): # pylint: disable=function-redefined """Check and update the node's parameters.""" param_values = {p.name: p.value for p in params} @@ -565,11 +568,15 @@ def main(args=None): :return: """ - ros_init(args) - - controller = CarlaAckermannControl() - controller.run() - + roscomp.init("carla_ackermann_control", args=args) + + try: + controller = CarlaAckermannControl() + controller.run() + except KeyboardInterrupt: + pass + finally: + roscomp.shutdown() if __name__ == "__main__": main() diff --git a/carla_ad_agent/src/carla_ad_agent/ad_agent.py b/carla_ad_agent/src/carla_ad_agent/ad_agent.py index 46378fb6..9a7b792d 100755 --- a/carla_ad_agent/src/carla_ad_agent/ad_agent.py +++ b/carla_ad_agent/src/carla_ad_agent/ad_agent.py @@ -14,32 +14,20 @@ import time import threading -from ros_compatibility import ( - CompatibleNode, - ROSInterruptException, - ros_ok, - QoSProfile, - ROSException, - latch_on, - ros_init, - ROS_VERSION, - logwarn, - loginfo, - ros_shutdown, - MultiThreadedExecutor, - ServiceException, - get_service_request) +import ros_compatibility as roscomp +from ros_compatibility.exceptions import * +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + +from carla_ad_agent.agent import Agent, AgentState -from std_msgs.msg import Float64 # pylint: disable=import-error -from derived_object_msgs.msg import ObjectArray -from nav_msgs.msg import Odometry from carla_msgs.msg import ( CarlaEgoVehicleInfo, CarlaActorList, CarlaTrafficLightStatusList, CarlaTrafficLightInfoList) - -from carla_ad_agent.agent import Agent, AgentState +from derived_object_msgs.msg import ObjectArray +from nav_msgs.msg import Odometry +from std_msgs.msg import Float64 # pylint: disable=import-error class CarlaAdAgent(Agent): @@ -66,39 +54,41 @@ def __init__(self): self.speed_command_publisher = self.new_publisher( Float64, "/carla/{}/speed_command".format(role_name), - QoSProfile(depth=1, durability=True)) + QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) - self._odometry_subscriber = self.create_subscriber( + self._odometry_subscriber = self.new_subscription( Odometry, "/carla/{}/odometry".format(role_name), - self.odometry_cb + self.odometry_cb, + qos_profile=10 ) - self._target_speed_subscriber = self.create_subscriber( + self._target_speed_subscriber = self.new_subscription( Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_cb, - qos_profile=QoSProfile(depth=10, durability=latch_on) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL) ) if self._avoid_risk: - self._objects_subscriber = self.create_subscriber( + self._objects_subscriber = self.new_subscription( ObjectArray, "/carla/{}/objects".format(role_name), - self.objects_cb + self.objects_cb, + qos_profile=10 ) - self._traffic_light_status_subscriber = self.create_subscriber( + self._traffic_light_status_subscriber = self.new_subscription( CarlaTrafficLightStatusList, "/carla/traffic_lights/status", self.traffic_light_status_cb, - qos_profile=QoSProfile(depth=10, durability=latch_on) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL) ) - self._traffic_light_info_subscriber = self.create_subscriber( + self._traffic_light_info_subscriber = self.new_subscription( CarlaTrafficLightInfoList, "/carla/traffic_lights/info", self.traffic_light_info_cb, - qos_profile=QoSProfile(depth=10, durability=latch_on) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL) ) def odometry_cb(self, odometry_msg): @@ -133,6 +123,11 @@ def traffic_light_info_cb(self, traffic_light_info_msg): with self.data_lock: self._lights_info = lights_info + def emergency_stop(self): + stopping_speed = Float64() + stopping_speed.data = 0.0 + self.speed_command_publisher.publish(stopping_speed) + def run_step(self): """ Executes one step of navigation. @@ -188,29 +183,27 @@ def main(args=None): :return: """ - ros_init(args) + roscomp.init("ad_agent", args=args) controller = None try: - executor = MultiThreadedExecutor() + executor = roscomp.executors.MultiThreadedExecutor() controller = CarlaAdAgent() executor.add_node(controller) + roscomp.on_shutdown(controller.emergency_stop) + update_timer = controller.new_timer( 0.05, lambda timer_event=None: controller.run_step()) controller.spin() except (ROSInterruptException, ROSException) as e: - if ros_ok(): - logwarn("ROS Error during exection: {}".format(e)) + if roscomp.ok(): + roscomp.logwarn("ROS Error during exection: {}".format(e)) except KeyboardInterrupt: - loginfo("User requested shut down.") + roscomp.loginfo("User requested shut down.") finally: - if controller is not None: - stopping_speed = Float64() - stopping_speed.data = 0.0 - controller.speed_command_publisher.publish(stopping_speed) - ros_shutdown() + roscomp.shutdown() if __name__ == "__main__": diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py index 7665361c..c79157e5 100644 --- a/carla_ad_agent/src/carla_ad_agent/agent.py +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -14,22 +14,19 @@ import carla -from ros_compatibility import ( - CompatibleNode, - ros_ok, - ServiceException, - get_service_request, - QoSProfile, - latch_on) - import carla_common.transforms as trans +import ros_compatibility as roscomp +from ros_compatibility.callback_groups import MutuallyExclusiveCallbackGroup +from ros_compatibility.exceptions import * +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + +from carla_ad_agent.misc import is_within_distance_ahead # pylint: disable=relative-import from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaTrafficLightStatus from carla_waypoint_types.srv import GetWaypoint from derived_object_msgs.msg import Object -from carla_ad_agent.misc import is_within_distance_ahead # pylint: disable=relative-import - class AgentState(enum.Enum): """ @@ -64,13 +61,14 @@ def __init__(self, name="agent"): vehicle_info = self.wait_for_message( "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo, - qos_profile=QoSProfile(depth=10, durability=latch_on)) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.loginfo("Vehicle info received.") self._ego_vehicle_id = vehicle_info.id - self._get_waypoint_client = self.create_service_client( + self._get_waypoint_client = self.new_client( + GetWaypoint, '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), - GetWaypoint) + callback_group=MutuallyExclusiveCallbackGroup()) def get_waypoint(self, location): """ @@ -81,15 +79,15 @@ def get_waypoint(self, location): :return: waypoint of the requested location :rtype: carla_msgs/Waypoint """ - if not ros_ok(): + if not roscomp.ok(): return None try: - request = get_service_request(GetWaypoint) + request = roscomp.get_service_request(GetWaypoint) request.location = location response = self.call_service(self._get_waypoint_client, request) return response.waypoint except ServiceException as e: - if ros_ok(): + if roscomp.ok(): self.logwarn("Service call 'get_waypoint' failed: {}".format(str(e))) def run_step(): diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py index cb2e01cc..202eae51 100755 --- a/carla_ad_agent/src/carla_ad_agent/local_planner.py +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -14,16 +14,18 @@ import math import threading -from ros_compatibility import QoSProfile, CompatibleNode, loginfo, ros_init, ROS_VERSION, latch_on +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + +from carla_ad_agent.vehicle_pid_controller import VehiclePIDController +from carla_ad_agent.misc import distance_vehicle from carla_msgs.msg import CarlaEgoVehicleControl # pylint: disable=import-error from nav_msgs.msg import Odometry, Path from std_msgs.msg import Float64 from visualization_msgs.msg import Marker -from carla_ad_agent.vehicle_pid_controller import VehiclePIDController -from carla_ad_agent.misc import distance_vehicle - class LocalPlanner(CompatibleNode): """ @@ -66,30 +68,31 @@ def __init__(self): self._waypoint_buffer = collections.deque(maxlen=self._buffer_size) # subscribers - self._odometry_subscriber = self.create_subscriber( + self._odometry_subscriber = self.new_subscription( Odometry, "/carla/{}/odometry".format(role_name), - self.odometry_cb) - self._path_subscriber = self.create_subscriber( + self.odometry_cb, + qos_profile=10) + self._path_subscriber = self.new_subscription( Path, "/carla/{}/waypoints".format(role_name), self.path_cb, - QoSProfile(depth=1, durability=latch_on)) - self._target_speed_subscriber = self.create_subscriber( + QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) + self._target_speed_subscriber = self.new_subscription( Float64, "/carla/{}/speed_command".format(role_name), self.target_speed_cb, - QoSProfile(depth=1, durability=latch_on)) + QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) # publishers self._target_pose_publisher = self.new_publisher( Marker, "/carla/{}/next_target".format(role_name), - QoSProfile(depth=10, durability=False)) + qos_profile=10) self._control_cmd_publisher = self.new_publisher( CarlaEgoVehicleControl, "/carla/{}/vehicle_control_cmd".format(role_name), - QoSProfile(depth=1, durability=False)) + qos_profile=10) # initializing controller self._vehicle_controller = VehiclePIDController( @@ -188,14 +191,13 @@ def main(args=None): :return: """ - ros_init(args) + roscomp.init("local_planner", args=args) local_planner = None update_timer = None try: local_planner = LocalPlanner() - if ROS_VERSION == 1: - local_planner.on_shutdown(local_planner.emergency_stop) + roscomp.on_shutdown(local_planner.emergency_stop) update_timer = local_planner.new_timer( local_planner.control_time_step, lambda timer_event=None: local_planner.run_step()) @@ -206,16 +208,8 @@ def main(args=None): pass finally: - loginfo('Local planner shutting down.') - if update_timer: - if ROS_VERSION == 1: - update_timer.shutdown() - else: - update_timer.destroy() - if ROS_VERSION == 2: - local_planner.emergency_stop() - local_planner.shutdown() - + roscomp.loginfo('Local planner shutting down.') + roscomp.shutdown() if __name__ == "__main__": main() diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 4b53a0bc..5cc25d15 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -27,52 +27,13 @@ """ from __future__ import print_function -from carla_msgs.msg import CarlaStatus -from carla_msgs.msg import CarlaEgoVehicleInfo -from carla_msgs.msg import CarlaEgoVehicleStatus -from carla_msgs.msg import CarlaEgoVehicleControl -from carla_msgs.msg import CarlaLaneInvasionEvent -from carla_msgs.msg import CarlaCollisionEvent -from sensor_msgs.msg import Image -from sensor_msgs.msg import NavSatFix -from std_msgs.msg import Bool -from transforms3d.euler import quat2euler -from ros_compatibility import ( - CompatibleNode, - latch_on, - ros_ok, - ros_init, - ros_shutdown, - loginfo, - logwarn, - ROS_VERSION) + import datetime import math -import numpy - -if ROS_VERSION == 1: - from rospy import Time - from tf import LookupException - from tf import ConnectivityException - from tf import ExtrapolationException - import tf - from ros_compatibility import QoSProfile - -elif ROS_VERSION == 2: - import rclpy - from rclpy.time import Time - from rclpy.callback_groups import ReentrantCallbackGroup - from tf2_ros import LookupException - from tf2_ros import ConnectivityException - from tf2_ros import ExtrapolationException - import tf2_ros - from rclpy.qos import QoSProfile - from threading import Thread - from builtin_interfaces.msg import Time -else: - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") - +from threading import Thread +import numpy +from transforms3d.euler import quat2euler try: import pygame from pygame.locals import KMOD_CTRL @@ -99,6 +60,21 @@ except ImportError: raise RuntimeError('cannot import pygame, make sure pygame package is installed') +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + +from carla_msgs.msg import CarlaStatus +from carla_msgs.msg import CarlaEgoVehicleInfo +from carla_msgs.msg import CarlaEgoVehicleStatus +from carla_msgs.msg import CarlaEgoVehicleControl +from carla_msgs.msg import CarlaLaneInvasionEvent +from carla_msgs.msg import CarlaCollisionEvent +from nav_msgs.msg import Odometry +from sensor_msgs.msg import Image +from sensor_msgs.msg import NavSatFix +from std_msgs.msg import Bool + # ============================================================================== # -- World --------------------------------------------------------------------- # ============================================================================== @@ -116,22 +92,17 @@ def __init__(self, resolution): self.hud = HUD(self.role_name, resolution['width'], resolution['height'], self) self.controller = KeyboardControl(self.role_name, self.hud, self) - if ROS_VERSION == 1: - self.callback_group = None - elif ROS_VERSION == 2: - self.callback_group = ReentrantCallbackGroup() - - self.image_subscriber = self.create_subscriber( + self.image_subscriber = self.new_subscription( Image, "/carla/{}/rgb_view/image".format(self.role_name), - self.on_view_image, callback_group=self.callback_group) + self.on_view_image, qos_profile=10) - self.collision_subscriber = self.create_subscriber( + self.collision_subscriber = self.new_subscription( CarlaCollisionEvent, "/carla/{}/collision".format(self.role_name), - self.on_collision, callback_group=self.callback_group) + self.on_collision, qos_profile=10) - self.lane_invasion_subscriber = self.create_subscriber( + self.lane_invasion_subscriber = self.new_subscription( CarlaLaneInvasionEvent, "/carla/{}/lane_invasion".format(self.role_name), - self.on_lane_invasion, callback_group=self.callback_group) + self.on_lane_invasion, qos_profile=10) def on_collision(self, data): """ @@ -201,35 +172,31 @@ def __init__(self, role_name, hud, node): self._control = CarlaEgoVehicleControl() self._steer_cache = 0.0 - if ROS_VERSION == 1: - self.callback_group = None - elif ROS_VERSION == 2: - self.callback_group = ReentrantCallbackGroup() - fast_qos = QoSProfile(depth=10) - fast_latched_qos = QoSProfile(depth=10, durability=latch_on) # imported from ros_compat. + fast_latched_qos = QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL) - self.vehicle_control_manual_override_publisher = \ - self.node.new_publisher(Bool, - "/carla/{}/vehicle_control_manual_override".format( - self.role_name), - qos_profile=fast_latched_qos, callback_group=self.callback_group) + self.vehicle_control_manual_override_publisher = self.node.new_publisher( + Bool, + "/carla/{}/vehicle_control_manual_override".format(self.role_name), + qos_profile=fast_latched_qos) self.vehicle_control_manual_override = False - self.auto_pilot_enable_publisher = \ - self.node.new_publisher(Bool, - "/carla/{}/enable_autopilot".format(self.role_name), - qos_profile=fast_qos, callback_group=self.callback_group) + self.auto_pilot_enable_publisher = self.node.new_publisher( + Bool, + "/carla/{}/enable_autopilot".format(self.role_name), + qos_profile=fast_qos) - self.vehicle_control_publisher = \ - self.node.new_publisher(CarlaEgoVehicleControl, - "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), - qos_profile=fast_qos, callback_group=self.callback_group) + self.vehicle_control_publisher = self.node.new_publisher( + CarlaEgoVehicleControl, + "/carla/{}/vehicle_control_cmd_manual".format(self.role_name), + qos_profile=fast_qos) - self.carla_status_subscriber = self.node.create_subscriber(CarlaStatus, "/carla/status", - self._on_new_carla_frame, - callback_group=self.callback_group) + self.carla_status_subscriber = self.node.new_subscription( + CarlaStatus, + "/carla/status", + self._on_new_carla_frame, + qos_profile=10) self.set_autopilot(self._autopilot_enabled) @@ -349,39 +316,48 @@ def __init__(self, role_name, width, height, node): self._info_text = [] self.vehicle_status = CarlaEgoVehicleStatus() - if ROS_VERSION == 1: - self.tf_listener = tf.TransformListener() - self.callback_group = None - elif ROS_VERSION == 2: - self.tf_buffer = tf2_ros.Buffer() - self.tf_listener = tf2_ros.TransformListener(self.tf_buffer, node=self.node) - self.callback_group = ReentrantCallbackGroup() - - self.vehicle_status_subscriber = node.create_subscriber( + self.vehicle_status_subscriber = node.new_subscription( CarlaEgoVehicleStatus, "/carla/{}/vehicle_status".format(self.role_name), - self.vehicle_status_updated, callback_group=self.callback_group) + self.vehicle_status_updated, qos_profile=10) self.vehicle_info = CarlaEgoVehicleInfo() - self.vehicle_info_subscriber = node.create_subscriber( - CarlaEgoVehicleInfo, "/carla/{}/vehicle_info".format(self.role_name), - self.vehicle_info_updated, callback_group=self.callback_group, qos_profile=QoSProfile(depth=10, durability=latch_on)) - + self.vehicle_info_subscriber = node.new_subscription( + CarlaEgoVehicleInfo, + "/carla/{}/vehicle_info".format(self.role_name), + self.vehicle_info_updated, + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) + + self.x, self.y, self.z = 0, 0, 0 + self.yaw = 0 self.latitude = 0 self.longitude = 0 self.manual_control = False - self.gnss_subscriber = node.create_subscriber( - NavSatFix, "/carla/{}/gnss".format(self.role_name), self.gnss_updated, - callback_group=self.callback_group) - - self.manual_control_subscriber = node.create_subscriber( - Bool, "/carla/{}/vehicle_control_manual_override".format(self.role_name), - self.manual_control_override_updated, callback_group=self.callback_group) + self.gnss_subscriber = node.new_subscription( + NavSatFix, + "/carla/{}/gnss".format(self.role_name), + self.gnss_updated, + qos_profile=10) + + self.odometry_subscriber = node.new_subscription( + Odometry, + "/carla/{}/odometry".format(self.role_name), + self.odometry_updated, + qos_profile=10 + ) + + self.manual_control_subscriber = node.new_subscription( + Bool, + "/carla/{}/vehicle_control_manual_override".format(self.role_name), + self.manual_control_override_updated, + qos_profile=10) self.carla_status = CarlaStatus() - self.status_subscriber = node.create_subscriber(CarlaStatus, "/carla/status", - self.carla_status_updated, - callback_group=self.callback_group) + self.status_subscriber = node.new_subscription( + CarlaStatus, + "/carla/status", + self.carla_status_updated, + qos_profile=10) def tick(self, clock): """ @@ -425,36 +401,28 @@ def gnss_updated(self, data): self.longitude = data.longitude self.update_info_text() + def odometry_updated(self, data): + self.x = data.pose.pose.position.x + self.y = data.pose.pose.position.y + self.z = data.pose.pose.position.z + _, _, yaw = quat2euler( + [data.pose.pose.orientation.w, + data.pose.pose.orientation.x, + data.pose.pose.orientation.y, + data.pose.pose.orientation.z]) + self.yaw = math.degrees(yaw) + self.update_info_text() + def update_info_text(self): """ update the displayed info text """ if not self._show_info: return - try: - if ROS_VERSION == 1: - (position, rotation) = self.tf_listener.lookupTransform( - '/map', self.role_name, Time()) - elif ROS_VERSION == 2: - transform = self.tf_buffer.lookup_transform( - target_frame='map', source_frame=self.role_name, time=Time()) - position = [transform.transform.translation.x, - transform.transform.translation.y, - transform.transform.translation.z] - rotation = [transform.transform.rotation.w, - transform.transform.rotation.x, - transform.transform.rotation.y, - transform.transform.rotation.z] - _, _, yaw = quat2euler(rotation) - yaw = math.degrees(yaw) - x = position[0] - y = position[1] - z = position[2] - except (LookupException, ConnectivityException, ExtrapolationException): - x = 0 - y = 0 - z = 0 - yaw = 0 + + x, y, z = self.x, self.y, self.z + yaw = self.yaw + heading = 'N' if abs(yaw) < 89.5 else '' heading += 'S' if abs(yaw) > 90.5 else '' heading += 'E' if 179.5 > yaw > 0.5 else '' @@ -644,7 +612,7 @@ def main(args=None): """ main function """ - ros_init(args) + roscomp.init("manual_control", args=args) # resolution should be similar to spawned camera with role-name 'view' resolution = {"width": 800, "height": 600} @@ -660,23 +628,22 @@ def main(args=None): manual_control_node = ManualControl(resolution) clock = pygame.time.Clock() - if ROS_VERSION == 2: - executer = rclpy.executors.MultiThreadedExecutor() - executer.add_node(manual_control_node) - spin_thread = Thread(target=executer.spin) - spin_thread.start() + executor = roscomp.executors.MultiThreadedExecutor() + executor.add_node(manual_control_node) + + spin_thread = Thread(target=manual_control_node.spin) + spin_thread.start() - while ros_ok(): + while roscomp.ok(): clock.tick_busy_loop(60) if manual_control_node.render(clock, display): return pygame.display.flip() except KeyboardInterrupt: - loginfo("User requested shut down.") + roscomp.loginfo("User requested shut down.") finally: - ros_shutdown() - if ROS_VERSION == 2: - spin_thread.join() + roscomp.shutdown() + spin_thread.join() pygame.quit() diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor.py b/carla_ros_bridge/src/carla_ros_bridge/actor.py index 471b724e..adc59b2a 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor.py @@ -10,10 +10,12 @@ Base Classes to handle Actor objects """ -from geometry_msgs.msg import TransformStamped # pylint: disable=import-error -from carla_ros_bridge.pseudo_actor import PseudoActor import carla_common.transforms as trans +from carla_ros_bridge.pseudo_actor import PseudoActor + +from geometry_msgs.msg import TransformStamped # pylint: disable=import-error + class Actor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py index 37213877..65fa8749 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_control.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_control.py @@ -9,13 +9,17 @@ provide functions to control actors """ -import numpy import math + +import numpy +from carla import Vector3D + import carla_common.transforms as trans + from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.sensor import Sensor + from geometry_msgs.msg import Pose, Twist -from carla import Vector3D class ActorControl(PseudoActor): @@ -43,13 +47,15 @@ def __init__(self, uid, name, parent, node): parent=parent, node=node) - self.set_location_subscriber = self.node.create_subscriber(Pose, - self.get_topic_prefix() + "/set_transform", - self.on_pose) + self.set_location_subscriber = self.node.new_subscription(Pose, + self.get_topic_prefix() + "/set_transform", + self.on_pose, + qos_profile=10) - self.twist_control_subscriber = self.node.create_subscriber(Twist, - self.get_topic_prefix() + "/set_target_velocity", - self.on_twist) + self.twist_control_subscriber = self.node.new_subscription(Twist, + self.get_topic_prefix() + "/set_target_velocity", + self.on_twist, + qos_profile=10) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index 94a6a3c1..f4fab84f 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -6,44 +6,45 @@ # For a copy, see . # -import time -from threading import Thread, Lock import itertools -from enum import Enum - try: import queue except ImportError: import Queue as queue +import time +from enum import Enum +from threading import Thread, Lock + +import carla +import numpy as np + +import carla_common.transforms as trans from carla_ros_bridge.actor import Actor -from carla_ros_bridge.spectator import Spectator -from carla_ros_bridge.traffic import Traffic, TrafficLight -from carla_ros_bridge.vehicle import Vehicle -from carla_ros_bridge.lidar import Lidar, SemanticLidar -from carla_ros_bridge.radar import Radar +from carla_ros_bridge.actor_control import ActorControl +from carla_ros_bridge.actor_list_sensor import ActorListSensor +from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera +from carla_ros_bridge.collision_sensor import CollisionSensor +from carla_ros_bridge.ego_vehicle import EgoVehicle from carla_ros_bridge.gnss import Gnss -from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.imu import ImuSensor -from carla_ros_bridge.ego_vehicle import EgoVehicle -from carla_ros_bridge.collision_sensor import CollisionSensor from carla_ros_bridge.lane_invasion_sensor import LaneInvasionSensor -from carla_ros_bridge.camera import Camera, RgbCamera, DepthCamera, SemanticSegmentationCamera, DVSCamera +from carla_ros_bridge.lidar import Lidar, SemanticLidar +from carla_ros_bridge.marker_sensor import MarkerSensor from carla_ros_bridge.object_sensor import ObjectSensor -from carla_ros_bridge.rss_sensor import RssSensor -from carla_ros_bridge.walker import Walker -from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor from carla_ros_bridge.odom_sensor import OdometrySensor -from carla_ros_bridge.speedometer_sensor import SpeedometerSensor -from carla_ros_bridge.tf_sensor import TFSensor -from carla_ros_bridge.marker_sensor import MarkerSensor -from carla_ros_bridge.actor_list_sensor import ActorListSensor from carla_ros_bridge.opendrive_sensor import OpenDriveSensor -from carla_ros_bridge.actor_control import ActorControl +from carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.radar import Radar +from carla_ros_bridge.rss_sensor import RssSensor from carla_ros_bridge.sensor import Sensor -import carla_common.transforms as trans -import carla -import numpy as np +from carla_ros_bridge.spectator import Spectator +from carla_ros_bridge.speedometer_sensor import SpeedometerSensor +from carla_ros_bridge.tf_sensor import TFSensor +from carla_ros_bridge.traffic import Traffic, TrafficLight +from carla_ros_bridge.traffic_lights_sensor import TrafficLightsSensor +from carla_ros_bridge.vehicle import Vehicle +from carla_ros_bridge.walker import Walker # to generate a random spawning position or vehicles import random diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py index 9331ce49..9bddbcff 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_list_sensor.py @@ -11,6 +11,7 @@ from carla_ros_bridge.actor import Actor from carla_ros_bridge.pseudo_actor import PseudoActor + from carla_msgs.msg import CarlaActorList, CarlaActorInfo @@ -42,7 +43,7 @@ def __init__(self, uid, name, parent, node, actor_list): parent=parent, node=node) self.actor_list = actor_list - self.actor_list_publisher = node.new_publisher(CarlaActorList, self.get_topic_prefix()) + self.actor_list_publisher = node.new_publisher(CarlaActorList, self.get_topic_prefix(), qos_profile=10) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 5cdaaae3..49111dfb 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -10,51 +10,32 @@ Class that handle communication between CARLA and ROS """ -from ros_compatibility import ( - CompatibleNode, - ros_ok, - ros_shutdown, - ros_on_shutdown, - ros_timestamp, - QoSProfile, - latch_on, - ros_init, - get_service_response, - ROS_VERSION) +import os +import pkg_resources try: import queue except ImportError: import Queue as queue - -import os import sys from distutils.version import LooseVersion from threading import Thread, Lock, Event -import pkg_resources -from rosgraph_msgs.msg import Clock import carla +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode + from carla_ros_bridge.actor import Actor from carla_ros_bridge.actor_factory import ActorFactory - from carla_ros_bridge.carla_status_publisher import CarlaStatusPublisher from carla_ros_bridge.debug_helper import DebugHelper -from carla_ros_bridge.world_info import WorldInfo from carla_ros_bridge.ego_vehicle import EgoVehicle +from carla_ros_bridge.world_info import WorldInfo from carla_msgs.msg import CarlaControl, CarlaWeatherParameters from carla_msgs.srv import SpawnObject, DestroyObject, GetBlueprints - -if ROS_VERSION == 1: - import rospy # pylint: disable=import-error -elif ROS_VERSION == 2: - import rclpy # pylint: disable=import-error - from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error - from builtin_interfaces.msg import Time -else: - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +from rosgraph_msgs.msg import Clock class CarlaRosBridge(CompatibleNode): @@ -70,7 +51,7 @@ class CarlaRosBridge(CompatibleNode): # wait for this time until a next tick is triggered. VEHICLE_CONTROL_TIMEOUT = 1. - def __init__(self, rospy_init=True, executor=None): + def __init__(self): """ Constructor @@ -79,25 +60,18 @@ def __init__(self, rospy_init=True, executor=None): :param params: dict of parameters, see settings.yaml :type params: dict """ - super(CarlaRosBridge, self).__init__("ros_bridge_node", rospy_init=rospy_init) - self.executor = executor + super(CarlaRosBridge, self).__init__("ros_bridge_node") # pylint: disable=attribute-defined-outside-init def initialize_bridge(self, carla_world, params): """ Initialize the bridge """ - ros_on_shutdown(self.destroy) - self.parameters = params self.carla_world = carla_world - if ROS_VERSION == 1: - self.ros_timestamp = 0 - self.callback_group = None - elif ROS_VERSION == 2: - self.ros_timestamp = Time() - self.callback_group = ReentrantCallbackGroup() + self.ros_timestamp = roscomp.ros_timestamp() + self.callback_group = roscomp.callback_groups.ReentrantCallbackGroup() self.synchronous_mode_update_thread = None self.shutdown = Event() @@ -139,7 +113,7 @@ def initialize_bridge(self, carla_world, params): self.debug_helper = DebugHelper(carla_world.debug, self) # Communication topics - self.clock_publisher = self.new_publisher(Clock, 'clock') + self.clock_publisher = self.new_publisher(Clock, 'clock', 10) self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode, @@ -157,9 +131,9 @@ def initialize_bridge(self, carla_world, params): self.carla_run_state = CarlaControl.PLAY self.carla_control_subscriber = \ - self.create_subscriber(CarlaControl, "/carla/control", - lambda control: self.carla_control_queue.put( - control.command), callback_group=self.callback_group) + self.new_subscription(CarlaControl, "/carla/control", + lambda control: self.carla_control_queue.put(control.command), + qos_profile=10, callback_group=self.callback_group) self.synchronous_mode_update_thread = Thread( target=self._synchronous_mode_update) @@ -183,11 +157,11 @@ def initialize_bridge(self, carla_world, params): self.get_blueprints, callback_group=self.callback_group) self.carla_weather_subscriber = \ - self.create_subscriber(CarlaWeatherParameters, "/carla/weather_control", - self.on_weather_changed, callback_group=self.callback_group) + self.new_subscription(CarlaWeatherParameters, "/carla/weather_control", + self.on_weather_changed, qos_profile=10, callback_group=self.callback_group) def spawn_object(self, req, response=None): - response = get_service_response(SpawnObject) + response = roscomp.get_service_response(SpawnObject) if not self.shutdown.is_set(): try: id_ = self.actor_factory.spawn_actor(req) @@ -203,7 +177,7 @@ def spawn_object(self, req, response=None): return response def destroy_object(self, req, response=None): - response = get_service_response(DestroyObject) + response = roscomp.get_service_response(DestroyObject) destroyed_actors = self.actor_factory.destroy_actor(req.id) response.success = bool(destroyed_actors) for actor in destroyed_actors: @@ -212,7 +186,7 @@ def destroy_object(self, req, response=None): return response def get_blueprints(self, req): - response = get_service_response(GetBlueprints) + response = roscomp.get_service_response(GetBlueprints) if req.filter: bp_filter = req.filter else: @@ -254,7 +228,7 @@ def process_run_state(self): while not self.carla_control_queue.empty(): command = self.carla_control_queue.get() - while command is not None and ros_ok(): + while command is not None and roscomp.ok(): self.carla_run_state = command if self.carla_run_state == CarlaControl.PAUSE: @@ -276,7 +250,7 @@ def _synchronous_mode_update(self): """ execution loop for synchronous mode """ - while not self.shutdown.is_set() and ros_ok(): + while not self.shutdown.is_set() and roscomp.ok(): self.process_run_state() if self.parameters['synchronous_mode_wait_for_vehicle_control_command']: @@ -359,8 +333,8 @@ def update_clock(self, carla_timestamp): :type carla_timestamp: carla.Timestamp :return: """ - if ros_ok(): - self.ros_timestamp = ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) + if roscomp.ok(): + self.ros_timestamp = roscomp.ros_timestamp(carla_timestamp.elapsed_seconds, from_sec=True) self.clock_publisher.publish(Clock(clock=self.ros_timestamp)) def destroy(self): @@ -397,20 +371,19 @@ def main(args=None): main function for carla simulator ROS bridge maintaining the communication client and the CarlaBridge object """ - ros_init(args) + roscomp.init("bridge", args=args) + carla_bridge = None carla_world = None carla_client = None executor = None parameters = {} - if ROS_VERSION == 1: - carla_bridge = CarlaRosBridge() - # rospy.init_node('carla_ros_bridge', anonymous=True) - elif ROS_VERSION == 2: - executor = rclpy.executors.MultiThreadedExecutor() - carla_bridge = CarlaRosBridge(executor=executor) - executor.add_node(carla_bridge) + executor = roscomp.executors.MultiThreadedExecutor() + carla_bridge = CarlaRosBridge() + executor.add_node(carla_bridge) + + roscomp.on_shutdown(carla_bridge.destroy) parameters['host'] = carla_bridge.get_param('host', 'localhost') parameters['port'] = carla_bridge.get_param('port', 2000) @@ -467,16 +440,14 @@ def main(args=None): carla_bridge.initialize_bridge(carla_client.get_world(), parameters) - if ROS_VERSION == 1: - rospy.spin() - elif ROS_VERSION == 2: - executor.spin() + carla_bridge.spin() + except (IOError, RuntimeError) as e: carla_bridge.logerr("Error: {}".format(e)) except KeyboardInterrupt: pass finally: - ros_shutdown() + roscomp.shutdown() del carla_world del carla_client diff --git a/carla_ros_bridge/src/carla_ros_bridge/camera.py b/carla_ros_bridge/src/carla_ros_bridge/camera.py index 1b5b7d9c..c9404e2d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/camera.py +++ b/carla_ros_bridge/src/carla_ros_bridge/camera.py @@ -9,20 +9,24 @@ """ Class to handle Carla camera sensors """ -from abc import abstractmethod import math +import os +from abc import abstractmethod + +import carla import numpy import transforms3d -import os from cv_bridge import CvBridge -from sensor_msgs.msg import CameraInfo, Image, PointCloud2, PointField -import carla -from carla_ros_bridge.sensor import Sensor, create_cloud import carla_common.transforms as trans +from ros_compatibility.core import get_ros_version + +from carla_ros_bridge.sensor import Sensor, create_cloud + +from sensor_msgs.msg import CameraInfo, Image, PointCloud2, PointField -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +ROS_VERSION = get_ros_version() class Camera(Sensor): @@ -69,9 +73,9 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self._build_camera_info() self.camera_info_publisher = node.new_publisher(CameraInfo, self.get_topic_prefix() + - '/camera_info') + '/camera_info', qos_profile=10) self.camera_image_publisher = node.new_publisher(Image, self.get_topic_prefix() + - '/' + 'image') + '/' + 'image', qos_profile=10) def destroy(self): super(Camera, self).destroy() @@ -401,7 +405,7 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self._dvs_events = None self.dvs_camera_publisher = node.new_publisher(PointCloud2, self.get_topic_prefix() + - '/events') + '/events', qos_profile=10) self.listen() diff --git a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py index 20f9be3b..7e39eb52 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py +++ b/carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py @@ -11,15 +11,9 @@ """ import os -from carla_msgs.msg import CarlaStatus # pylint: disable=import-error - -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION not in (1, 2): - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") +import ros_compatibility as roscomp -if ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup # pylint: disable=import-error +from carla_msgs.msg import CarlaStatus # pylint: disable=import-error class CarlaStatusPublisher(object): @@ -39,11 +33,9 @@ def __init__(self, synchronous_mode, fixed_delta_seconds, node): if self.fixed_delta_seconds is None: self.fixed_delta_seconds = 0. self.frame = 0 - if ROS_VERSION == 1: - callback_group = None - elif ROS_VERSION == 2: - callback_group = ReentrantCallbackGroup() - self.carla_status_publisher = self.node.new_publisher(CarlaStatus, "/carla/status", + + callback_group = roscomp.callback_groups.ReentrantCallbackGroup() + self.carla_status_publisher = self.node.new_publisher(CarlaStatus, "/carla/status", qos_profile=10, callback_group=callback_group) self.publish() diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index 1eca28fa..89d0c253 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -11,6 +11,7 @@ """ from carla_ros_bridge.sensor import Sensor + from carla_msgs.msg import CarlaCollisionEvent @@ -49,7 +50,8 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy is_event_sensor=True) self.collision_publisher = node.new_publisher(CarlaCollisionEvent, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) self.listen() def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py index 75e4860b..4f6ee567 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py +++ b/carla_ros_bridge/src/carla_ros_bridge/debug_helper.py @@ -11,12 +11,10 @@ import math import os -from visualization_msgs.msg import Marker, MarkerArray # pylint: disable=import-error - import carla from transforms3d.euler import quat2euler -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +from visualization_msgs.msg import Marker, MarkerArray # pylint: disable=import-error class DebugHelper(object): @@ -33,8 +31,8 @@ def __init__(self, carla_debug_helper, node): """ self.debug = carla_debug_helper self.node = node - self.marker_subscriber = self.node.create_subscriber(MarkerArray, "/carla/debug_marker", - self.on_marker) + self.marker_subscriber = self.node.new_subscription(MarkerArray, "/carla/debug_marker", + self.on_marker, qos_profile=10) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index e8956ad9..5d86781d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -11,11 +11,12 @@ """ import math import os -import numpy -from std_msgs.msg import Bool # pylint: disable=import-error -from std_msgs.msg import ColorRGBA # pylint: disable=import-error +import numpy from carla import VehicleControl + +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + from carla_ros_bridge.vehicle import Vehicle from carla_msgs.msg import ( @@ -24,12 +25,8 @@ CarlaEgoVehicleControl, CarlaEgoVehicleStatus ) - -from ros_compatibility import ( - QoSProfile, - latch_on, - ROS_VERSION -) +from std_msgs.msg import Bool # pylint: disable=import-error +from std_msgs.msg import ColorRGBA # pylint: disable=import-error class EgoVehicle(Vehicle): @@ -65,31 +62,37 @@ def __init__(self, uid, name, parent, node, carla_actor, vehicle_control_applied self.vehicle_status_publisher = node.new_publisher( CarlaEgoVehicleStatus, - self.get_topic_prefix() + "/vehicle_status") - self.vehicle_info_publisher = node.new_publisher(CarlaEgoVehicleInfo, - self.get_topic_prefix() + - "/vehicle_info", - qos_profile=QoSProfile(depth=10, durability=latch_on)) - - self.control_subscriber = node.create_subscriber( + self.get_topic_prefix() + "/vehicle_status", + qos_profile=10) + self.vehicle_info_publisher = node.new_publisher( + CarlaEgoVehicleInfo, + self.get_topic_prefix() + + "/vehicle_info", + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) + + self.control_subscriber = node.new_subscription( CarlaEgoVehicleControl, self.get_topic_prefix() + "/vehicle_control_cmd", - lambda data: self.control_command_updated(data, manual_override=False)) + lambda data: self.control_command_updated(data, manual_override=False), + qos_profile=10) - self.manual_control_subscriber = node.create_subscriber( + self.manual_control_subscriber = node.new_subscription( CarlaEgoVehicleControl, self.get_topic_prefix() + "/vehicle_control_cmd_manual", - lambda data: self.control_command_updated(data, manual_override=True)) + lambda data: self.control_command_updated(data, manual_override=True), + qos_profile=10) - self.control_override_subscriber = node.create_subscriber( + self.control_override_subscriber = node.new_subscription( Bool, self.get_topic_prefix() + "/vehicle_control_manual_override", - self.control_command_override, QoSProfile(depth=1, durability=True)) + self.control_command_override, + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) - self.enable_autopilot_subscriber = node.create_subscriber( + self.enable_autopilot_subscriber = node.new_subscription( Bool, self.get_topic_prefix() + "/enable_autopilot", - self.enable_autopilot_updated) + self.enable_autopilot_updated, + qos_profile=10) def get_marker_color(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/gnss.py b/carla_ros_bridge/src/carla_ros_bridge/gnss.py index 9506bb81..b560add2 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/gnss.py +++ b/carla_ros_bridge/src/carla_ros_bridge/gnss.py @@ -10,10 +10,10 @@ Classes to handle Carla gnsss """ -from sensor_msgs.msg import NavSatFix - from carla_ros_bridge.sensor import Sensor +from sensor_msgs.msg import NavSatFix + class Gnss(Sensor): @@ -49,7 +49,8 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy synchronous_mode=synchronous_mode) self.gnss_publisher = node.new_publisher(NavSatFix, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) self.listen() def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/imu.py b/carla_ros_bridge/src/carla_ros_bridge/imu.py index 4c90eef4..9ba52ec0 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/imu.py +++ b/carla_ros_bridge/src/carla_ros_bridge/imu.py @@ -7,12 +7,14 @@ Classes to handle Carla imu sensor """ -from sensor_msgs.msg import Imu - -from carla_ros_bridge.sensor import Sensor from transforms3d.euler import euler2quat + import carla_common.transforms as trans +from carla_ros_bridge.sensor import Sensor + +from sensor_msgs.msg import Imu + class ImuSensor(Sensor): @@ -47,7 +49,7 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy carla_actor=carla_actor, synchronous_mode=synchronous_mode) - self.imu_publisher = node.new_publisher(Imu, self.get_topic_prefix()) + self.imu_publisher = node.new_publisher(Imu, self.get_topic_prefix(), qos_profile=10) self.listen() def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 92e052f3..6e038696 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -11,6 +11,7 @@ """ from carla_ros_bridge.sensor import Sensor + from carla_msgs.msg import CarlaLaneInvasionEvent @@ -49,7 +50,8 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy is_event_sensor=True) self.lane_invasion_publisher = node.new_publisher(CarlaLaneInvasionEvent, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) self.listen() def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 946d500c..88e38e9d 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -13,10 +13,10 @@ import numpy -from sensor_msgs.msg import PointCloud2, PointField - from carla_ros_bridge.sensor import Sensor, create_cloud +from sensor_msgs.msg import PointCloud2, PointField + class Lidar(Sensor): @@ -52,7 +52,8 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy synchronous_mode=synchronous_mode) self.lidar_publisher = node.new_publisher(PointCloud2, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) self.listen() def destroy(self): @@ -67,7 +68,7 @@ def sensor_data_updated(self, carla_lidar_measurement): :param carla_lidar_measurement: carla lidar measurement object :type carla_lidar_measurement: carla.LidarMeasurement """ - header = self.get_msg_header() + header = self.get_msg_header(timestamp=carla_lidar_measurement.timestamp) fields = [ PointField(name='x', offset=0, datatype=PointField.FLOAT32, count=1), PointField(name='y', offset=4, datatype=PointField.FLOAT32, count=1), @@ -121,7 +122,8 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy self.semantic_lidar_publisher = node.new_publisher( PointCloud2, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) self.listen() def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index c2b030da..0b46583e 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -46,7 +46,8 @@ def __init__(self, uid, name, parent, node, actor_list): self.actor_list = actor_list self.marker_publisher = node.new_publisher(MarkerArray, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 1f6b8a6e..8cb96430 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -9,10 +9,11 @@ handle a object sensor """ -from derived_object_msgs.msg import ObjectArray +from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.vehicle import Vehicle from carla_ros_bridge.walker import Walker -from carla_ros_bridge.pseudo_actor import PseudoActor + +from derived_object_msgs.msg import ObjectArray class ObjectSensor(PseudoActor): @@ -43,7 +44,8 @@ def __init__(self, uid, name, parent, node, actor_list): node=node) self.actor_list = actor_list self.object_publisher = node.new_publisher(ObjectArray, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 143ee645..7ab4facd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -42,7 +42,8 @@ def __init__(self, uid, name, parent, node): node=node) self.odometry_publisher = node.new_publisher(Odometry, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) def destroy(self): super(OdometrySensor, self).destroy() diff --git a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py index fbdc1830..83a5a4c4 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/opendrive_sensor.py @@ -11,9 +11,9 @@ from carla_ros_bridge.pseudo_actor import PseudoActor -from std_msgs.msg import String +from ros_compatibility.qos import QoSProfile, DurabilityPolicy -from ros_compatibility import QoSProfile, latch_on +from std_msgs.msg import String class OpenDriveSensor(PseudoActor): @@ -43,8 +43,10 @@ def __init__(self, uid, name, parent, node, carla_map): node=node) self.carla_map = carla_map self._map_published = False - self.map_publisher = node.new_publisher(String, self.get_topic_prefix(), - qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.map_publisher = node.new_publisher( + String, + self.get_topic_prefix(), + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) def destroy(self): super(OpenDriveSensor, self).destroy() diff --git a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py index c1aa6abc..6cdfa0f9 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/pseudo_actor.py @@ -8,14 +8,12 @@ """ Base Class to handle Pseudo Actors (that are not existing in Carla world) """ + import numpy as np -from std_msgs.msg import Header -from ros_compatibility import ( - ros_timestamp, - QoSProfile, - latch_on -) +import ros_compatibility as roscomp + +from std_msgs.msg import Header class PseudoActor(object): @@ -80,7 +78,7 @@ def get_msg_header(self, frame_id=None, timestamp=None): if not timestamp: timestamp = self.node.get_time() - header.stamp = ros_timestamp(sec=timestamp, from_sec=True) + header.stamp = roscomp.ros_timestamp(sec=timestamp, from_sec=True) return header def get_prefix(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/radar.py b/carla_ros_bridge/src/carla_ros_bridge/radar.py index a5c465fd..a2afc8cd 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/radar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/radar.py @@ -12,10 +12,10 @@ import numpy as np -from sensor_msgs.msg import PointCloud2, PointField - from carla_ros_bridge.sensor import Sensor, create_cloud +from sensor_msgs.msg import PointCloud2, PointField + class Radar(Sensor): @@ -50,7 +50,7 @@ def __init__(self, uid, name, parent, relative_spawn_pose, node, carla_actor, sy carla_actor=carla_actor, synchronous_mode=synchronous_mode) - self.radar_publisher = node.new_publisher(PointCloud2, self.get_topic_prefix()) + self.radar_publisher = node.new_publisher(PointCloud2, self.get_topic_prefix(), qos_profile=10) self.listen() def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/sensor.py b/carla_ros_bridge/src/carla_ros_bridge/sensor.py index 47334648..1bdd36c3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/sensor.py @@ -8,25 +8,29 @@ """ Classes to handle Carla sensors """ + from __future__ import print_function -from abc import abstractmethod + import ctypes import os -import struct -import sys -from threading import Lock try: import queue except ImportError: import Queue as queue +import struct +import sys +from abc import abstractmethod +from threading import Lock +import carla_common.transforms as trans +import ros_compatibility as roscomp import tf2_ros + from carla_ros_bridge.actor import Actor -import carla_common.transforms as trans -from ros_compatibility import ros_ok, ros_timestamp, ROSException + from sensor_msgs.msg import PointCloud2, PointField -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +ROS_VERSION = roscomp.get_ros_version() _DATATYPES = {} _DATATYPES[PointField.INT8] = ('b', 1) @@ -119,7 +123,7 @@ def get_ros_transform(self, pose, timestamp): frame_id = "map" transform = tf2_ros.TransformStamped() - transform.header.stamp = ros_timestamp(sec=timestamp, from_sec=True) + transform.header.stamp = roscomp.ros_timestamp(sec=timestamp, from_sec=True) transform.header.frame_id = frame_id transform.child_frame_id = child_frame_id @@ -138,8 +142,8 @@ def publish_tf(self, pose, timestamp): transform = self.get_ros_transform(pose, timestamp) try: self._tf_broadcaster.sendTransform(transform) - except ROSException: - if ros_ok(): + except roscomp.exceptions.ROSException: + if roscomp.ok(): self.node.logwarn("Sensor {} failed to send transform.".format(self.uid)) def listen(self): @@ -179,8 +183,8 @@ def _callback_sensor_data(self, carla_sensor_data): carla_sensor_data.transform), carla_sensor_data.timestamp) try: self.sensor_data_updated(carla_sensor_data) - except ROSException: - if ros_ok(): + except roscomp.exceptions.ROSException: + if roscomp.ok(): self.node.logwarn( "Sensor {}: Error while executing sensor_data_updated().".format(self.uid)) self._callback_active.release() @@ -236,7 +240,7 @@ def _update_synchronous_sensor(self, frame, timestamp): carla_sensor_data.frame, frame)) except queue.Empty: - if ros_ok(): + if roscomp.ok(): self.node.logwarn("{}({}): Expected Frame {} not received".format( self.__class__.__name__, self.get_id(), frame)) return diff --git a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py index 213cfc6f..5f92be99 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py @@ -42,7 +42,8 @@ def __init__(self, uid, name, parent, node): node=node) self.speedometer_publisher = node.new_publisher(Float32, - self.get_topic_prefix()) + self.get_topic_prefix(), + qos_profile=10) def destroy(self): super(SpeedometerSensor, self).destroy() diff --git a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py index 7a4b7789..0dd9dcf3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py @@ -9,12 +9,17 @@ handle a tf sensor """ -import tf2_ros import os + +import tf2_ros + +import ros_compatibility as roscomp + from carla_ros_bridge.pseudo_actor import PseudoActor + from geometry_msgs.msg import TransformStamped -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +ROS_VERSION = roscomp.get_ros_version() class TFSensor(PseudoActor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic.py b/carla_ros_bridge/src/carla_ros_bridge/traffic.py index 2a7317bf..462ba825 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic.py @@ -10,10 +10,13 @@ Classes to handle Carla traffic objects """ -from carla_ros_bridge.actor import Actor +from carla import TrafficLightState + import carla_common.transforms as trans + +from carla_ros_bridge.actor import Actor + from carla_msgs.msg import CarlaTrafficLightStatus, CarlaTrafficLightInfo -from carla import TrafficLightState class Traffic(Actor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py index 48c1cfe4..0635229c 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_lights_sensor.py @@ -9,13 +9,15 @@ a sensor that reports the state of all traffic lights """ +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + +from carla_ros_bridge.pseudo_actor import PseudoActor +from carla_ros_bridge.traffic import TrafficLight + from carla_msgs.msg import ( CarlaTrafficLightStatusList, CarlaTrafficLightInfoList ) -from carla_ros_bridge.traffic import TrafficLight -from carla_ros_bridge.pseudo_actor import PseudoActor -from ros_compatibility import QoSProfile, latch_on class TrafficLightsSensor(PseudoActor): @@ -49,11 +51,12 @@ def __init__(self, uid, name, parent, node, actor_list): self.traffic_lights_info_publisher = node.new_publisher( CarlaTrafficLightInfoList, - self.get_topic_prefix() + "/info", qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.get_topic_prefix() + "/info", + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.traffic_lights_status_publisher = node.new_publisher( CarlaTrafficLightStatusList, self.get_topic_prefix() + "/status", - qos_profile=QoSProfile(depth=10, durability=latch_on)) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index d906a0a1..f37521e3 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -10,12 +10,14 @@ Classes to handle Carla traffic participants """ +import carla_common.transforms as trans + +from carla_ros_bridge.actor import Actor + from derived_object_msgs.msg import Object from shape_msgs.msg import SolidPrimitive from std_msgs.msg import ColorRGBA from visualization_msgs.msg import Marker -from carla_ros_bridge.actor import Actor -import carla_common.transforms as trans class TrafficParticipant(Actor): diff --git a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py index 8b8dd44e..7ddc54c5 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/vehicle.py @@ -10,12 +10,13 @@ Classes to handle Carla vehicles """ -from std_msgs.msg import ColorRGBA -from derived_object_msgs.msg import Object - import carla_common.transforms as trans + from carla_ros_bridge.traffic_participant import TrafficParticipant +from derived_object_msgs.msg import Object +from std_msgs.msg import ColorRGBA + class Vehicle(TrafficParticipant): diff --git a/carla_ros_bridge/src/carla_ros_bridge/walker.py b/carla_ros_bridge/src/carla_ros_bridge/walker.py index b9adc276..41f828d2 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/walker.py +++ b/carla_ros_bridge/src/carla_ros_bridge/walker.py @@ -10,11 +10,12 @@ Classes to handle Carla pedestrians """ -from derived_object_msgs.msg import Object +from carla import WalkerControl from carla_ros_bridge.traffic_participant import TrafficParticipant + from carla_msgs.msg import CarlaWalkerControl -from carla import WalkerControl +from derived_object_msgs.msg import Object class Walker(TrafficParticipant): @@ -44,10 +45,11 @@ def __init__(self, uid, name, parent, node, carla_actor): node=node, carla_actor=carla_actor) - self.control_subscriber = self.node.create_subscriber( + self.control_subscriber = self.node.new_subscription( CarlaWalkerControl, self.get_topic_prefix() + "/walker_control_cmd", - self.control_command_updated) + self.control_command_updated, + qos_profile=10) def destroy(self): """ diff --git a/carla_ros_bridge/src/carla_ros_bridge/world_info.py b/carla_ros_bridge/src/carla_ros_bridge/world_info.py index 94f8fdce..c41d3ef7 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/world_info.py +++ b/carla_ros_bridge/src/carla_ros_bridge/world_info.py @@ -10,8 +10,9 @@ Class to handle the carla map """ +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + from carla_msgs.msg import CarlaWorldInfo -from ros_compatibility import QoSProfile, latch_on class WorldInfo(object): @@ -34,9 +35,10 @@ def __init__(self, carla_world, node): self.map_published = False - self.world_info_publisher = node.new_publisher(CarlaWorldInfo, - "/carla/world_info", - qos_profile=QoSProfile(depth=10, durability=latch_on)) + self.world_info_publisher = node.new_publisher( + CarlaWorldInfo, + "/carla/world_info", + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) def destroy(self): """ diff --git a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py index 95703c66..e89abeb0 100644 --- a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py +++ b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py @@ -15,7 +15,10 @@ import launch_testing.actions from ament_index_python.packages import get_package_share_directory -from ros_compatibility import CompatibleNode, ros_init, ros_shutdown, QoSProfile, latch_on + +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy from std_msgs.msg import Header, String from rosgraph_msgs.msg import Clock @@ -126,14 +129,14 @@ def test_clock(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message("/clock", Clock, timeout=TIMEOUT) self.assertNotEqual(Clock(), msg) finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_vehicle_status(self, proc_output): """ @@ -141,7 +144,7 @@ def test_vehicle_status(self, proc_output): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/vehicle_status", CarlaEgoVehicleStatus) @@ -151,7 +154,7 @@ def test_vehicle_status(self, proc_output): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_vehicle_info(self): """ @@ -159,11 +162,11 @@ def test_vehicle_info(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/vehicle_info", CarlaEgoVehicleInfo, timeout=TIMEOUT, - qos_profile=QoSProfile(depth=1, durability=latch_on)) + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.assertNotEqual(msg.id, 0) self.assertEqual(msg.type, "vehicle.tesla.model3") self.assertEqual(msg.rolename, "ego_vehicle") @@ -183,7 +186,7 @@ def test_vehicle_info(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_odometry(self): """ @@ -191,7 +194,7 @@ def test_odometry(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/odometry", Odometry, timeout=TIMEOUT) @@ -201,7 +204,7 @@ def test_odometry(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_gnss(self): """ @@ -209,7 +212,7 @@ def test_gnss(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/gnss", NavSatFix, timeout=TIMEOUT) @@ -220,7 +223,7 @@ def test_gnss(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_imu(self): """ @@ -228,7 +231,7 @@ def test_imu(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message("/carla/ego_vehicle/imu", Imu, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "ego_vehicle/imu") @@ -238,7 +241,7 @@ def test_imu(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_camera_info(self): """ @@ -246,7 +249,7 @@ def test_camera_info(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/rgb_front/camera_info", CameraInfo, timeout=TIMEOUT) @@ -256,7 +259,7 @@ def test_camera_info(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_camera_image(self): """ @@ -264,7 +267,7 @@ def test_camera_image(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/rgb_front/image", Image, timeout=TIMEOUT) @@ -275,7 +278,7 @@ def test_camera_image(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_dvs_camera_info(self): """ @@ -283,7 +286,7 @@ def test_dvs_camera_info(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/dvs_front/camera_info", CameraInfo, timeout=TIMEOUT) @@ -293,7 +296,7 @@ def test_dvs_camera_info(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_dvs_camera_image(self): """ @@ -301,7 +304,7 @@ def test_dvs_camera_image(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/dvs_front/image", Image, timeout=TIMEOUT) @@ -312,7 +315,7 @@ def test_dvs_camera_image(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_dvs_camera_events(self): """ @@ -320,7 +323,7 @@ def test_dvs_camera_events(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/dvs_front/events", PointCloud2, timeout=TIMEOUT) @@ -328,7 +331,7 @@ def test_dvs_camera_events(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_lidar(self): """ @@ -336,7 +339,7 @@ def test_lidar(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/lidar", PointCloud2, timeout=TIMEOUT) @@ -344,7 +347,7 @@ def test_lidar(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_semantic_lidar(self): """ @@ -352,7 +355,7 @@ def test_semantic_lidar(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/semantic_lidar", PointCloud2, timeout=TIMEOUT) @@ -360,7 +363,7 @@ def test_semantic_lidar(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_radar(self): """ @@ -368,7 +371,7 @@ def test_radar(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = None node = CompatibleNode('test_node') msg = node.wait_for_message( @@ -377,7 +380,7 @@ def test_radar(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_ego_vehicle_objects(self): """ @@ -385,7 +388,7 @@ def test_ego_vehicle_objects(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/ego_vehicle/objects", ObjectArray, timeout=15) @@ -394,7 +397,7 @@ def test_ego_vehicle_objects(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_objects(self): """ @@ -402,7 +405,7 @@ def test_objects(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message("/carla/objects", ObjectArray, timeout=TIMEOUT) self.assertEqual(msg.header.frame_id, "map") @@ -410,7 +413,7 @@ def test_objects(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_marker(self): """ @@ -418,7 +421,7 @@ def test_marker(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message("/carla/markers", MarkerArray, timeout=TIMEOUT) self.assertEqual(len(msg.markers), 1) # only ego vehicle exists @@ -435,7 +438,7 @@ def test_marker(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_map(self): """ @@ -443,16 +446,16 @@ def test_map(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/map", String, timeout=TIMEOUT, - qos_profile=QoSProfile(depth=10, durability=latch_on)) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.assertNotEqual(len(msg.data), 0) finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_world_info(self): """ @@ -460,17 +463,17 @@ def test_world_info(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/world_info", CarlaWorldInfo, timeout=TIMEOUT, - qos_profile=QoSProfile(depth=10, durability=latch_on)) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.assertNotEqual(len(msg.map_name), 0) self.assertNotEqual(len(msg.opendrive), 0) finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_actor_list(self): """ @@ -478,7 +481,7 @@ def test_actor_list(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/actor_list", CarlaActorList, timeout=TIMEOUT) @@ -486,7 +489,7 @@ def test_actor_list(self): finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_traffic_lights(self): """ @@ -494,16 +497,16 @@ def test_traffic_lights(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/traffic_lights/status", CarlaTrafficLightStatusList, timeout=TIMEOUT, - qos_profile=QoSProfile(depth=10, durability=latch_on)) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.assertNotEqual(len(msg.traffic_lights), 0) finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() def test_traffic_lights_info(self): """ @@ -511,13 +514,13 @@ def test_traffic_lights_info(self): """ try: node = None - ros_init() + roscomp.init("test_node") node = CompatibleNode('test_node') msg = node.wait_for_message( "/carla/traffic_lights/info", CarlaTrafficLightInfoList, timeout=TIMEOUT, - qos_profile=QoSProfile(depth=10, durability=latch_on)) + qos_profile=QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.assertNotEqual(len(msg.traffic_lights), 0) finally: if node is not None: node.destroy_node() - ros_shutdown() + roscomp.shutdown() diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py index d1c1894b..448494d7 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py @@ -10,26 +10,24 @@ Internally, the CARLA scenario runner is executed """ -import sys + import os try: import queue except ImportError: import Queue as queue -from carla_ros_scenario_runner_types.srv import ExecuteScenario -from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus +import sys +import threading + +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + from carla_ros_scenario_runner.application_runner import ApplicationStatus # pylint: disable=relative-import from carla_ros_scenario_runner.scenario_runner_runner import ScenarioRunnerRunner # pylint: disable=relative-import -from ros_compatibility import ( - CompatibleNode, - QoSProfile, - ros_ok, - ros_init, - get_service_response, - ros_shutdown, - loginfo, - ROS_VERSION) +from carla_ros_scenario_runner_types.srv import ExecuteScenario +from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus # Check Python dependencies of scenario runner try: @@ -47,8 +45,7 @@ Please add /PythonAPI/carla to your PYTHONPATH.") sys.exit(1) -if ROS_VERSION == 2: - import threading +ROS_VERSION = roscomp.get_ros_version() class CarlaRosScenarioRunner(CompatibleNode): @@ -69,8 +66,9 @@ def __init__(self): port = self.get_param("port", 2000) self._status_publisher = self.new_publisher( - CarlaScenarioRunnerStatus, "/scenario_runner/status", - qos_profile=QoSProfile(depth=1, durability=1)) + CarlaScenarioRunnerStatus, + "/scenario_runner/status", + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.scenario_runner_status_updated(ApplicationStatus.STOPPED) self._scenario_runner = ScenarioRunnerRunner( scenario_runner_path, @@ -81,7 +79,9 @@ def __init__(self): self.scenario_runner_log) self._request_queue = queue.Queue() self._execute_scenario_service = self.new_service( - ExecuteScenario, '/scenario_runner/execute_scenario', self.execute_scenario) + ExecuteScenario, + '/scenario_runner/execute_scenario', + self.execute_scenario) def scenario_runner_log(self, log): # pylint: disable=no-self-use """ @@ -115,7 +115,7 @@ def execute_scenario(self, req, response=None): """ self.loginfo("Scenario Execution requested...") - response = get_service_response(ExecuteScenario) + response = roscomp.get_service_response(ExecuteScenario) response.result = True if not os.path.isfile(req.scenario.scenario_file): self.logwarn("Requested scenario file not existing {}".format( @@ -132,7 +132,7 @@ def run(self): :return: """ current_req = None - while ros_ok(): + while roscomp.ok(): if current_req: if self._scenario_runner.is_running(): self.loginfo("Scenario Runner currently running. Shutting down.") @@ -165,7 +165,7 @@ def main(args=None): :return: """ - ros_init(args) + roscomp.init("carla_ros_scenario_runner", args=args) scenario_runner = CarlaRosScenarioRunner() @@ -182,10 +182,11 @@ def main(args=None): scenario_runner.loginfo("Scenario Runner still running. Shutting down.") scenario_runner._scenario_runner.shutdown() del scenario_runner - ros_shutdown() if ROS_VERSION == 2: spin_thread.join() + roscomp.shutdown() + if __name__ == "__main__": main() diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py index 38f7b128..1256882f 100644 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/ros_vehicle_control.py @@ -9,42 +9,40 @@ ROS Vehicle Control usable by scenario-runner """ -from std_msgs.msg import Float64 -from geometry_msgs.msg import PoseStamped -from nav_msgs.msg import Path -import carla_common.transforms as trans +import os + from srunner.scenariomanager.actorcontrols.basic_control import BasicControl # pylint: disable=import-error -from ros_compatibility import CompatibleNode, QoSProfile, ros_timestamp, ros_init, latch_on -import os +import carla_common.transforms as trans +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + +from carla_ros_scenario_runner.application_runner import ApplicationRunner -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +from geometry_msgs.msg import PoseStamped +from nav_msgs.msg import Path +from std_msgs.msg import Float64 -if ROS_VERSION == 1: - import rospy - import roslaunch -elif ROS_VERSION == 2: - from carla_ros_scenario_runner.application_runner import ApplicationRunner +ROS_VERSION = roscomp.get_ros_version() class RosVehicleControl(BasicControl): def __init__(self, actor, args=None): super(RosVehicleControl, self).__init__(actor) - ros_init(args=None) self._carla_actor = actor self._role_name = actor.attributes["role_name"] if not self._role_name: - if ROS_VERSION == 1: - rospy.logerr("Invalid role_name!") - elif ROS_VERSION == 2: - logging.get_logger("pre_logger").error("Invalid role_name!") + roscomp.logerr("Invalid role_name") self._path_topic_name = "waypoints" if "path_topic_name" in args: self._path_topic_name = args["path_topic_name"] + roscomp.init("ros_agent_{}".format(self._role_name), args=None) + self.node = CompatibleNode('ros_agent_{}'.format(self._role_name)) self._current_target_speed = None @@ -52,13 +50,15 @@ def __init__(self, actor, args=None): self.controller_launch = None self._target_speed_publisher = self.node.new_publisher( - Float64, "/carla/{}/target_speed".format(self._role_name), - QoSProfile(depth=10, durability=latch_on)) + Float64, + "/carla/{}/target_speed".format(self._role_name), + QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.node.loginfo("Publishing target_speed on /carla/{}/target_speed".format(self._role_name)) self._path_publisher = self.node.new_publisher( - Path, "/carla/{}/{}".format(self._role_name, self._path_topic_name), - QoSProfile(depth=10, durability=latch_on)) + Path, + "/carla/{}/{}".format(self._role_name, self._path_topic_name), + QoSProfile(depth=10, durability=DurabilityPolicy.TRANSIENT_LOCAL)) self.node.loginfo("Publishing path on /carla/{}/{}".format(self._role_name, self._path_topic_name)) if "launch" in args and "launch-package" in args: @@ -67,8 +67,10 @@ def __init__(self, actor, args=None): launch_package = args["launch-package"] if ROS_VERSION == 1: + executable = "roslaunch" cli_args = [launch_package, launch_file] elif ROS_VERSION == 2: + executable = "ros2 launch" cli_args = [launch_package, launch_file + '.py'] cli_args.append('role_name:={}'.format(self._role_name)) @@ -82,20 +84,10 @@ def __init__(self, actor, args=None): self.node.loginfo("{}: Launching {} from package {} (parameters: {})...".format( self._role_name, launch_file, launch_package, launch_parameters)) - if ROS_VERSION == 1: - uuid = roslaunch.rlutil.get_or_generate_uuid(None, False) - roslaunch.configure_logging(uuid) - roslaunch_file = roslaunch.rlutil.resolve_launch_arguments(cli_args) - roslaunch_args = cli_args[2:] - launch_files = [(roslaunch_file[0], roslaunch_args)] - parent = roslaunch.parent.ROSLaunchParent(uuid, launch_files) - parent.start() - - elif ROS_VERSION == 2: - cmdline = ['ros2 launch'] + cli_args - self.controller_launch = ApplicationRunner( - self.controller_runner_status_updated, self.controller_runner_log, 'RosVehicleControl: launching controller node') - self.controller_launch.execute(cmdline, env=os.environ,) + cmdline = [executable] + cli_args + self.controller_launch = ApplicationRunner( + self.controller_runner_status_updated, self.controller_runner_log, 'RosVehicleControl: launching controller node') + self.controller_launch.execute(cmdline, env=os.environ,) self.node.loginfo( "{}: Successfully started ros vehicle control".format(self._role_name)) @@ -124,7 +116,7 @@ def update_waypoints(self, waypoints, start_time=None): super(RosVehicleControl, self).update_waypoints(waypoints, start_time) self.node.loginfo("{}: Waypoints changed.".format(self._role_name)) path = Path() - path.header.stamp = ros_timestamp(sec=self.node.get_time(), from_sec=True) + path.header.stamp = roscomp.ros_timestamp(sec=self.node.get_time(), from_sec=True) path.header.frame_id = "map" for wpt in waypoints: print(wpt) @@ -133,10 +125,9 @@ def update_waypoints(self, waypoints, start_time=None): def reset(self): # set target speed to zero before closing as the controller can take time to shutdown - if ROS_VERSION == 2: - self.update_target_speed(0.) - if self.controller_launch and self.controller_launch.is_running(): - self.controller_launch.shutdown() + self.update_target_speed(0.) + if self.controller_launch and self.controller_launch.is_running(): + self.controller_launch.shutdown() if self._carla_actor and self._carla_actor.is_alive: self._carla_actor = None if self._target_speed_publisher: diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py index 3dc540ba..a4db093c 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py @@ -6,9 +6,12 @@ Executes scenario runner """ import os + +import ros_compatibility as roscomp + from carla_ros_scenario_runner.application_runner import ApplicationRunner # pylint: disable=relative-import -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +ROS_VERSION = roscomp.get_ros_version() class ScenarioRunnerRunner(ApplicationRunner): diff --git a/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py b/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py index d5563b5d..7b523775 100644 --- a/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py +++ b/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py @@ -11,6 +11,10 @@ def generate_launch_description(): default_value=get_package_share_directory( 'carla_spawn_objects') + '/config/objects.json' ), + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), launch.actions.DeclareLaunchArgument( name='spawn_point_ego_vehicle', default_value='' @@ -19,6 +23,10 @@ def generate_launch_description(): name='spawn_sensors_only', default_value='False' ), + launch.actions.DeclareLaunchArgument( + name='control_id', + default_value='control' + ), launch.actions.IncludeLaunchDescription( launch.launch_description_sources.PythonLaunchDescriptionSource( os.path.join(get_package_share_directory( @@ -29,6 +37,16 @@ def generate_launch_description(): 'spawn_point_ego_vehicle': launch.substitutions.LaunchConfiguration('spawn_point_ego_vehicle'), 'spawn_sensors_only': launch.substitutions.LaunchConfiguration('spawn_sensors_only') }.items() + ), + launch.actions.IncludeLaunchDescription( + launch.launch_description_sources.PythonLaunchDescriptionSource( + os.path.join(get_package_share_directory( + 'carla_spawn_objects'), 'set_initial_pose.launch.py') + ), + launch_arguments={ + 'role_name': launch.substitutions.LaunchConfiguration('role_name'), + 'control_id': launch.substitutions.LaunchConfiguration('control_id') + }.items() ) ]) return ld diff --git a/carla_spawn_objects/launch/set_initial_pose.launch.py b/carla_spawn_objects/launch/set_initial_pose.launch.py new file mode 100644 index 00000000..811ddee2 --- /dev/null +++ b/carla_spawn_objects/launch/set_initial_pose.launch.py @@ -0,0 +1,39 @@ +import os +import sys + +import launch +import launch_ros.actions +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + ld = launch.LaunchDescription([ + launch.actions.DeclareLaunchArgument( + name='role_name', + default_value='ego_vehicle' + ), + launch.actions.DeclareLaunchArgument( + name='control_id', + default_value='control' + ), + launch_ros.actions.Node( + package='carla_spawn_objects', + executable='set_initial_pose', + name='set_initial_pose', + output='screen', + emulate_tty=True, + parameters=[ + { + 'role_name': launch.substitutions.LaunchConfiguration('role_name') + }, + { + 'control_id': launch.substitutions.LaunchConfiguration('control_id') + } + ] + ) + ]) + return ld + + +if __name__ == '__main__': + generate_launch_description() diff --git a/carla_spawn_objects/setup.py b/carla_spawn_objects/setup.py index fe09fcd3..70fbce8c 100644 --- a/carla_spawn_objects/setup.py +++ b/carla_spawn_objects/setup.py @@ -41,7 +41,8 @@ tests_require=['pytest'], entry_points={ 'console_scripts': [ - 'carla_spawn_objects = src.carla_spawn_objects.carla_spawn_objects:main' + 'carla_spawn_objects = src.carla_spawn_objects.carla_spawn_objects:main', + 'set_initial_pose = src.carla_spawn_objects.set_initial_pose:main' ], }, ) diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index f14cb8d3..daad53da 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -15,30 +15,20 @@ """ -import os -import math import json +import math +import os -from diagnostic_msgs.msg import KeyValue -from geometry_msgs.msg import Pose -from carla_msgs.msg import CarlaActorList from transforms3d.euler import euler2quat -from carla_msgs.srv import SpawnObject, DestroyObject -from ros_compatibility import ( - CompatibleNode, - ROSInterruptException, - ServiceException, - ros_init, - logfatal, - loginfo, - logwarn, - logerr, - ros_ok, - get_service_request, - ros_shutdown, - ROS_VERSION -) +import ros_compatibility as roscomp +from ros_compatibility.exceptions import * +from ros_compatibility.node import CompatibleNode + +from carla_msgs.msg import CarlaActorList +from carla_msgs.srv import SpawnObject, DestroyObject +from diagnostic_msgs.msg import KeyValue +from geometry_msgs.msg import Pose # ============================================================================== # -- CarlaSpawnObjects ------------------------------------------------------------ @@ -55,6 +45,7 @@ class CarlaSpawnObjects(CompatibleNode): def __init__(self): super(CarlaSpawnObjects, self).__init__('carla_spawn_objects') + self.objects_definition_file = self.get_param('objects_definition_file') self.spawn_sensors_only = self.get_param('spawn_sensors_only', None) @@ -62,9 +53,8 @@ def __init__(self): self.vehicles_sensors = [] self.global_sensors = [] - self.spawn_object_service = self.create_service_client("/carla/spawn_object", SpawnObject) - self.destroy_object_service = self.create_service_client( - "/carla/destroy_object", DestroyObject) + self.spawn_object_service = self.new_client(SpawnObject, "/carla/spawn_object") + self.destroy_object_service = self.new_client(DestroyObject, "/carla/destroy_object") def spawn_object(self, spawn_object_request): response_id = -1 @@ -140,7 +130,7 @@ def setup_vehicles(self, vehicles): # spawn the vehicle's sensors self.setup_sensors(vehicle["sensors"], carla_id) else: - spawn_object_request = get_service_request(SpawnObject) + spawn_object_request = roscomp.get_service_request(SpawnObject) spawn_object_request.type = vehicle["type"] spawn_object_request.id = vehicle["id"] spawn_object_request.attach_to = 0 @@ -184,7 +174,7 @@ def setup_vehicles(self, vehicles): spawn_object_request.random_pose = True player_spawned = False - while not player_spawned and ros_ok(): + while not player_spawned and roscomp.ok(): spawn_object_request.transform = spawn_point response_id = self.spawn_object(spawn_object_request) @@ -208,7 +198,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): """ sensor_names = [] for sensor_spec in sensors: - if not ros_ok(): + if not roscomp.ok(): break try: sensor_type = str(sensor_spec.pop("type")) @@ -242,7 +232,7 @@ def setup_sensors(self, sensors, attached_vehicle_id=None): spawn_point.pop("pitch", 0.0), spawn_point.pop("yaw", 0.0)) - spawn_object_request = get_service_request(SpawnObject) + spawn_object_request = roscomp.get_service_request(SpawnObject) spawn_object_request.type = sensor_type spawn_object_request.id = sensor_id spawn_object_request.attach_to = attached_vehicle_id if attached_vehicle_id is not None else 0 @@ -323,28 +313,28 @@ def destroy(self): try: # destroy vehicles sensors for actor_id in self.vehicles_sensors: - destroy_object_request = get_service_request(DestroyObject) + destroy_object_request = roscomp.get_service_request(DestroyObject) destroy_object_request.id = actor_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.5, spin_until_response_received=True) + destroy_object_request, timeout=0.5, spin_until_response_received=True) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.vehicles_sensors = [] # destroy global sensors for actor_id in self.global_sensors: - destroy_object_request = get_service_request(DestroyObject) + destroy_object_request = roscomp.get_service_request(DestroyObject) destroy_object_request.id = actor_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.5, spin_until_response_received=True) + destroy_object_request, timeout=0.5, spin_until_response_received=True) self.loginfo("Object {} successfully destroyed.".format(actor_id)) self.global_sensors = [] # destroy player for player_id in self.players: - destroy_object_request = get_service_request(DestroyObject) + destroy_object_request = roscomp.get_service_request(DestroyObject) destroy_object_request.id = player_id self.call_service(self.destroy_object_service, - destroy_object_request, timeout_ros2=0.5, spin_until_response_received=True) + destroy_object_request, timeout=0.5, spin_until_response_received=True) self.loginfo("Object {} successfully destroyed.".format(player_id)) self.players = [] except ServiceException: @@ -360,16 +350,15 @@ def main(args=None): """ main function """ - ros_init(args) + roscomp.init("spawn_objects", args=args) spawn_objects_node = None try: spawn_objects_node = CarlaSpawnObjects() + roscomp.on_shutdown(spawn_objects_node.destroy) except KeyboardInterrupt: - logerr("Could not initialize CarlaSpawnObjects. Shutting down.") + roscomp.logerr("Could not initialize CarlaSpawnObjects. Shutting down.") if spawn_objects_node: - if ROS_VERSION == 1: - spawn_objects_node.on_shutdown(spawn_objects_node.destroy) try: spawn_objects_node.spawn_objects() try: @@ -380,11 +369,9 @@ def main(args=None): spawn_objects_node.logwarn( "Spawning process has been interrupted. There might be actors that have not been destroyed properly") except RuntimeError as e: - logfatal("Exception caught: {}".format(e)) + roscomp.logfatal("Exception caught: {}".format(e)) finally: - if ROS_VERSION == 2: - spawn_objects_node.destroy() - ros_shutdown() + roscomp.shutdown() if __name__ == '__main__': diff --git a/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py index d2e46939..c70981d7 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py +++ b/carla_spawn_objects/src/carla_spawn_objects/set_initial_pose.py @@ -17,25 +17,32 @@ /initialpose might be published via RVIZ '2D Pose Estimate" button. """ -import rospy +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode + from geometry_msgs.msg import PoseWithCovarianceStamped, Pose -class SetInitialPose(object): +class SetInitialPose(CompatibleNode): def __init__(self): + super(SetInitialPose, self).__init__("set_initial_pose") - rospy.init_node('set_initial_pose', anonymous=True) - - self.role_name = rospy.get_param('~role_name', 'ego_vehicle') + self.role_name = self.get_param("role_name", "ego_vehicle") # control_id should correspond to the id of the actor.pseudo.control # actor that is set in the config file used to spawn it - self.control_id = rospy.get_param('~control_id', 'control') - self.transform_publisher = rospy.Publisher( - "/carla/{}/{}/set_transform".format(self.role_name, self.control_id), Pose, queue_size=10) + self.control_id = self.get_param("control_id", "control") - self.initial_pose_subscriber = rospy.Subscriber( - "/initialpose", PoseWithCovarianceStamped, self.intial_pose_callback) + self.transform_publisher = self.new_publisher( + Pose, + "/carla/{}/{}/set_transform".format(self.role_name, self.control_id), + qos_profile=10) + + self.initial_pose_subscriber = self.new_subscription( + PoseWithCovarianceStamped, + "/initialpose", + self.intial_pose_callback, + qos_profile=10) def intial_pose_callback(self, initial_pose): pose_to_publish = initial_pose.pose.pose @@ -47,9 +54,15 @@ def main(): """ main function """ - set_initial_pose_node = SetInitialPose() - rospy.spin() - + roscomp.init("set_initial_pose") + + try: + set_initial_pose_node = SetInitialPose() + set_initial_pose_node.spin() + except KeyboardInterrupt: + roscomp.loginfo("Cancelled by user.") + finally: + roscomp.shutdown() if __name__ == '__main__': main() diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index d35ae514..ab640ea8 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -9,25 +9,16 @@ use max wheel steer angle """ -from ros_compatibility import ( - CompatibleNode, - QoSProfile, - latch_on, - ros_ok, - ROSException, - ROSInterruptException, - ros_init) + import sys -from geometry_msgs.msg import Twist # pylint: disable=import-error -from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo # pylint: disable=import-error -import os -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) +import ros_compatibility as roscomp +from ros_compatibility.exceptions import ROSException +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy -if ROS_VERSION == 1: - import rospy # pylint: disable=import-error -elif ROS_VERSION == 2: - import rclpy # pylint: disable=import-error +from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo # pylint: disable=import-error +from geometry_msgs.msg import Twist # pylint: disable=import-error class TwistToVehicleControl(CompatibleNode): # pylint: disable=too-few-public-methods @@ -39,22 +30,31 @@ class TwistToVehicleControl(CompatibleNode): # pylint: disable=too-few-public-m MAX_LON_ACCELERATION = 10 - def __init__(self, rospy_init=True): + def __init__(self): """ Constructor """ - super(TwistToVehicleControl, self).__init__("twist_to_control", rospy_init=rospy_init) + super(TwistToVehicleControl, self).__init__("twist_to_control") + + self.role_name = self.get_param("role_name", "ego_vehicle") self.max_steering_angle = None - def initialize_twist_to_control(self, role_name): - self.create_subscriber(CarlaEgoVehicleInfo, - "/carla/{}/vehicle_info".format(role_name), self.update_vehicle_info, - qos_profile=QoSProfile(depth=1, durability=latch_on)) + self.new_subscription( + CarlaEgoVehicleInfo, + "/carla/{}/vehicle_info".format(self.role_name), + self.update_vehicle_info, + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) - self.create_subscriber(Twist, "/carla/{}/twist".format(role_name), self.twist_received) + self.new_subscription( + Twist, + "/carla/{}/twist".format(self.role_name), + self.twist_received, + qos_profile=10) - self.pub = self.new_publisher(CarlaEgoVehicleControl, - "/carla/{}/vehicle_control_cmd".format(role_name)) + self.pub = self.new_publisher( + CarlaEgoVehicleControl, + "/carla/{}/vehicle_control_cmd".format(self.role_name), + qos_profile=10) def update_vehicle_info(self, vehicle_info): """ @@ -103,7 +103,7 @@ def twist_received(self, twist): try: self.pub.publish(control) except ROSException as e: - if ros_ok(): + if roscomp.ok(): self.logwarn("Error while publishing control: {}".format(e)) @@ -113,27 +113,19 @@ def main(args=None): :return: """ - ros_init(args) + roscomp.init("twist_to_control", args) - role_name = None twist_to_vehicle_control = None - - if ROS_VERSION == 1: - twist_to_vehicle_control = TwistToVehicleControl() - role_name = rospy.get_param("~role_name", "ego_vehicle") - elif ROS_VERSION == 2: - twist_to_vehicle_control = TwistToVehicleControl() - executor = rclpy.executors.MultiThreadedExecutor() - executor.add_node(twist_to_vehicle_control) - role_name = twist_to_vehicle_control.get_param("role_name", "ego_vehicle") - - twist_to_vehicle_control.initialize_twist_to_control(role_name) - try: + twist_to_vehicle_control = TwistToVehicleControl() twist_to_vehicle_control.spin() + except KeyboardInterrupt: + pass finally: - twist_to_vehicle_control.loginfo("Done, deleting twist to control") - del twist_to_vehicle_control + if twist_to_vehicle_control is not None: + twist_to_vehicle_control.loginfo("Done, deleting twist to control") + del twist_to_vehicle_control + roscomp.shutdown() if __name__ == "__main__": diff --git a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py index a703edd6..7fd3329e 100755 --- a/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py +++ b/carla_walker_agent/src/carla_walker_agent/carla_walker_agent.py @@ -8,26 +8,18 @@ """ Agent for Walker """ + import math -from nav_msgs.msg import Path, Odometry -from std_msgs.msg import Float64 -from geometry_msgs.msg import Pose, Vector3 -from carla_msgs.msg import CarlaWalkerControl -from ros_compatibility import ( - CompatibleNode, - QoSProfile, - ros_ok, - ROSInterruptException, - ros_init) -import os -ROS_VERSION = int(os.environ['ROS_VERSION']) +import ros_compatibility as roscomp +from ros_compatibility.exceptions import ROSInterruptException +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy -if ROS_VERSION == 1: - import rospy -elif ROS_VERSION == 2: - import time - import threading +from carla_msgs.msg import CarlaWalkerControl +from geometry_msgs.msg import Pose, Vector3 +from nav_msgs.msg import Path, Odometry +from std_msgs.msg import Float64 class CarlaWalkerAgent(CompatibleNode): @@ -49,28 +41,36 @@ def __init__(self): self._route_assigned = False self._waypoints = [] self._current_pose = Pose() - self.on_shutdown(self._on_shutdown) # wait for ros bridge to create relevant topics try: - self.wait_for_message( - "/carla/{}/odometry".format(role_name), Odometry) + self.wait_for_message("/carla/{}/odometry".format(role_name), Odometry, qos_profile=10) except ROSInterruptException as e: - if not ros_ok: + if not roscomp.ok: raise e - self._odometry_subscriber = self.create_subscriber( - Odometry, "/carla/{}/odometry".format(role_name), self.odometry_updated) + self._odometry_subscriber = self.new_subscription( + Odometry, + "/carla/{}/odometry".format(role_name), + self.odometry_updated, + qos_profile=10) self.control_publisher = self.new_publisher( - CarlaWalkerControl, "/carla/{}/walker_control_cmd".format(role_name), - QoSProfile(depth=1, durability=False)) - - self._route_subscriber = self.create_subscriber( - Path, "/carla/{}/waypoints".format(role_name), self.path_updated) - - self._target_speed_subscriber = self.create_subscriber( - Float64, "/carla/{}/target_speed".format(role_name), self.target_speed_updated) + CarlaWalkerControl, + "/carla/{}/walker_control_cmd".format(role_name), + qos_profile=1) + + self._route_subscriber = self.new_subscription( + Path, + "/carla/{}/waypoints".format(role_name), + self.path_updated, + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) + + self._target_speed_subscriber = self.new_subscription( + Float64, + "/carla/{}/target_speed".format(role_name), + self.target_speed_updated, + qos_profile=10) def _on_shutdown(self): """ @@ -103,44 +103,25 @@ def odometry_updated(self, odo): """ self._current_pose = odo.pose.pose - def run(self): - """ - - Control loop - - :return: - """ - loop_frequency = 20 - if ROS_VERSION == 1: - r = rospy.Rate(loop_frequency) - self.loginfo("Starting run loop") - while ros_ok(): - if self._waypoints: - control = CarlaWalkerControl() - direction = Vector3() - direction.x = self._waypoints[0].position.x - self._current_pose.position.x - direction.y = self._waypoints[0].position.y - self._current_pose.position.y - direction_norm = math.sqrt(direction.x**2 + direction.y**2) - if direction_norm > CarlaWalkerAgent.MIN_DISTANCE: - control.speed = self._target_speed - control.direction.x = direction.x / direction_norm - control.direction.y = direction.y / direction_norm + def run_step(self): + if self._waypoints: + control = CarlaWalkerControl() + direction = Vector3() + direction.x = self._waypoints[0].position.x - self._current_pose.position.x + direction.y = self._waypoints[0].position.y - self._current_pose.position.y + direction_norm = math.sqrt(direction.x**2 + direction.y**2) + if direction_norm > CarlaWalkerAgent.MIN_DISTANCE: + control.speed = self._target_speed + control.direction.x = direction.x / direction_norm + control.direction.y = direction.y / direction_norm + else: + self._waypoints = self._waypoints[1:] + if self._waypoints: + self.loginfo("next waypoint: {} {}".format( + self._waypoints[0].position.x, self._waypoints[0].position.y)) else: - self._waypoints = self._waypoints[1:] - if self._waypoints: - self.loginfo("next waypoint: {} {}".format( - self._waypoints[0].position.x, self._waypoints[0].position.y)) - else: - self.loginfo("Route finished.") - self.control_publisher.publish(control) - try: - if ROS_VERSION == 1: - r.sleep() - elif ROS_VERSION == 2: - # TODO: use rclpy.Rate, not working yet - time.sleep(1 / loop_frequency) - except ROSInterruptException: - pass + self.loginfo("Route finished.") + self.control_publisher.publish(control) def main(args=None): @@ -150,18 +131,22 @@ def main(args=None): :return: """ - ros_init(args) + roscomp.init("carla_walker_agent", args) + controller = None + + try: + controller = CarlaWalkerAgent() - controller = CarlaWalkerAgent() + roscomp.on_shutdown(controller._on_shutdown) - if ROS_VERSION == 2: - spin_thread = threading.Thread(target=controller.spin, daemon=True) - spin_thread.start() + update_timer = controller.new_timer( + 0.05, lambda timer_event=None: controller.run_step()) - try: - controller.run() + controller.spin() + except KeyboardInterrupt: + pass finally: - del controller + roscomp.shutdown() print("Done") diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 63bff79e..0787e7be 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -21,27 +21,21 @@ import sys import threading -from ros_compatibility import (CompatibleNode, - QoSProfile, - ROSException, - ros_timestamp, - latch_on, - ros_init, - get_service_response, - loginfo, - ROS_VERSION, - ros_shutdown) -from nav_msgs.msg import Path -from geometry_msgs.msg import PoseStamped -import carla_common.transforms as trans -from carla_msgs.msg import CarlaWorldInfo -from carla_waypoint_types.srv import GetWaypoint, GetActorWaypoint - import carla - from agents.navigation.global_route_planner import GlobalRoutePlanner from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO +import carla_common.transforms as trans +import ros_compatibility as roscomp +from ros_compatibility.exceptions import * +from ros_compatibility.node import CompatibleNode +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + +from carla_msgs.msg import CarlaWorldInfo +from carla_waypoint_types.srv import GetWaypoint, GetActorWaypoint +from geometry_msgs.msg import PoseStamped +from nav_msgs.msg import Path + class CarlaToRosWaypointConverter(CompatibleNode): @@ -66,7 +60,9 @@ def __init__(self): self.on_tick = None self.role_name = self.get_param("role_name", 'ego_vehicle') self.waypoint_publisher = self.new_publisher( - Path, '/carla/{}/waypoints'.format(self.role_name), QoSProfile(depth=1, durability=True)) + Path, + '/carla/{}/waypoints'.format(self.role_name), + QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) # initialize ros services self.get_waypoint_service = self.new_service( @@ -82,8 +78,11 @@ def __init__(self): self.goal = self.world.get_map().get_spawn_points()[0] self.current_route = None - self.goal_subscriber = self.create_subscriber( - PoseStamped, "/carla/{}/goal".format(self.role_name), self.on_goal) + self.goal_subscriber = self.new_subscription( + PoseStamped, + "/carla/{}/goal".format(self.role_name), + self.on_goal, + qos_profile=10) # use callback to wait for ego vehicle self.loginfo("Waiting for ego vehicle...") @@ -108,7 +107,7 @@ def get_waypoint(self, req, response=None): carla_waypoint = self.map.get_waypoint(carla_position) - response = get_service_response(GetWaypoint) + response = roscomp.get_service_response(GetWaypoint) response.waypoint.pose = trans.carla_transform_to_ros_pose(carla_waypoint.transform) response.waypoint.is_junction = carla_waypoint.is_junction response.waypoint.road_id = carla_waypoint.road_id @@ -123,7 +122,7 @@ def get_actor_waypoint(self, req, response=None): # self.loginfo("get_actor_waypoint(): Get waypoint of actor {}".format(req.id)) actor = self.world.get_actors().find(req.id) - response = get_service_response(GetActorWaypoint) + response = roscomp.get_service_response(GetActorWaypoint) if actor: carla_waypoint = self.map.get_waypoint(actor.get_location()) response.waypoint.pose = trans.carla_transform_to_ros_pose(carla_waypoint.transform) @@ -221,7 +220,7 @@ def publish_waypoints(self): """ msg = Path() msg.header.frame_id = "map" - msg.header.stamp = ros_timestamp(self.get_time(), from_sec=True) + msg.header.stamp = roscomp.ros_timestamp(self.get_time(), from_sec=True) if self.current_route is not None: for wp in self.current_route: pose = PoseStamped() @@ -235,8 +234,11 @@ def connect_to_carla(self): self.loginfo("Waiting for CARLA world (topic: /carla/world_info)...") try: - self.wait_for_message("/carla/world_info", CarlaWorldInfo, - qos_profile=QoSProfile(depth=1, durability=latch_on), timeout=15.0) + self.wait_for_message( + "/carla/world_info", + CarlaWorldInfo, + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL), + timeout=15.0) except ROSException as e: self.logerr("Error while waiting for world info: {}".format(e)) raise e @@ -263,26 +265,21 @@ def main(args=None): """ main function """ - ros_init(args) + roscomp.init('carla_waypoint_publisher', args) waypoint_converter = None try: waypoint_converter = CarlaToRosWaypointConverter() - if ROS_VERSION == 1: - waypoint_converter.spin() - else: - spin_thread = threading.Thread(target=waypoint_converter.spin) - spin_thread.start() - spin_thread.join() + waypoint_converter.spin() except (RuntimeError, ROSException): pass except KeyboardInterrupt: - loginfo("User requested shut down.") + roscomp.loginfo("User requested shut down.") finally: - loginfo("Shutting down.") + roscomp.loginfo("Shutting down.") if waypoint_converter: waypoint_converter.destroy() - ros_shutdown() + roscomp.shutdown() if __name__ == "__main__": diff --git a/docs/carla_manual_control.md b/docs/carla_manual_control.md index 8bba5a3d..2be53b17 100644 --- a/docs/carla_manual_control.md +++ b/docs/carla_manual_control.md @@ -13,7 +13,7 @@ The [CARLA manual control package](https://github.com/carla-simulator/ros-bridge To be able to use `carla_manual_control`, some specific sensors need to be attached to the ego vehicle (see [Carla Spawn Objects](carla_spawn_objects.md) for information on how to attach sensors to vehicles): - __to display an image__: a camera with role-name `rgb_view` and resolution 800x600. -- __to display the current GNSS position__: a GNSS sensor with role-name `gnss`. +- __to display the current position__: a GNSS sensor with role-name `gnss` and an odometry pseudo-sensor with role-name `odometry`. - __to get a notification on lane invasions__: a lane invasion sensor with role-name `lane_invasion`. - __to get a notification on collisons__: a collision sensor with role-name `collision`. diff --git a/pcl_recorder/launch/pcl_recorder.launch.py b/pcl_recorder/launch/pcl_recorder.launch.py index 978253f0..d2510032 100644 --- a/pcl_recorder/launch/pcl_recorder.launch.py +++ b/pcl_recorder/launch/pcl_recorder.launch.py @@ -6,6 +6,16 @@ from ament_index_python.packages import get_package_share_directory +def launch_enable_autopilot_publisher(context, *args, **kwargs): + topic_name = "/carla/" + launch.substitutions.LaunchConfiguration('role_name').perform(context) + "/enable_autopilot" + return [ + launch.actions.ExecuteProcess( + output="screen", + cmd=["ros2", "topic", "pub", topic_name, + "std_msgs/msg/Bool", "{'data': True}", "--qos-durability", "transient_local"], + name='topic_pub_enable_autopilot')] + + def generate_launch_description(): ld = launch.LaunchDescription([ launch.actions.DeclareLaunchArgument( @@ -20,20 +30,19 @@ def generate_launch_description(): name='role_name', default_value='ego_vehicle' ), - # launch_ros.actions.Node( - # package='rostopic', - # executable='rostopic', - # name='enable_autopilot_rostopic' - # ), + launch.actions.OpaqueFunction(function=launch_enable_autopilot_publisher), launch_ros.actions.Node( package='pcl_recorder', executable='pcl_recorder_node', name='pcl_recorder_node', output='screen', parameters=[ + { + 'use_sim_time': True + }, { 'role_name': launch.substitutions.LaunchConfiguration('role_name') - } + }, ] ), launch.actions.IncludeLaunchDescription( diff --git a/pcl_recorder/src/PclRecorder.cpp b/pcl_recorder/src/PclRecorder.cpp index af9af938..e73aeb58 100644 --- a/pcl_recorder/src/PclRecorder.cpp +++ b/pcl_recorder/src/PclRecorder.cpp @@ -23,7 +23,7 @@ PclRecorder::PclRecorder() if (!ros::param::get("~role_name", roleName)) { roleName = "ego_vehicle"; } - sub = nh.subscribe("/carla/" + roleName + "/lidar", 1000000, &PclRecorder::callback, this); + sub = nh.subscribe("/carla/" + roleName + "/lidar", 1, &PclRecorder::callback, this); } void PclRecorder::callback(const pcl::PCLPointCloud2::ConstPtr& cloud) diff --git a/pcl_recorder/src/PclRecorderROS2.cpp b/pcl_recorder/src/PclRecorderROS2.cpp index 42a4ab69..ce18a59c 100644 --- a/pcl_recorder/src/PclRecorderROS2.cpp +++ b/pcl_recorder/src/PclRecorderROS2.cpp @@ -4,19 +4,17 @@ * This work is licensed under the terms of the MIT license. * For a copy, see . */ -#include "PclRecorderROS2.h" -#include -#include #include +#include + #include +#include + +#include "PclRecorderROS2.h" PclRecorderROS2::PclRecorderROS2() : Node("pcl_recorder") { - rclcpp::Clock::SharedPtr clock = std::make_shared(RCL_ROS_TIME); - rclcpp::TimeSource timesource; - timesource.attachClock(clock); - tf_buffer_ = std::make_unique(clock); - + tf_buffer_ = std::make_unique(this->get_clock()); tfListener = new tf2_ros::TransformListener(*tf_buffer_); if (mkdir("/tmp/pcl_capture", 0777) == -1) { @@ -28,7 +26,9 @@ PclRecorderROS2::PclRecorderROS2() : Node("pcl_recorder") if (!this->get_parameter("role_name", roleName)) { roleName = "ego_vehicle"; } - sub = this->create_subscription("/carla/" + roleName + "/lidar", 100, std::bind(&PclRecorderROS2::callback, this, std::placeholders::_1)); + auto sub_opt = rclcpp::SubscriptionOptions(); + sub_opt.callback_group = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::MutuallyExclusive); + sub = this->create_subscription("/carla/" + roleName + "/lidar", 10, std::bind(&PclRecorderROS2::callback, this, std::placeholders::_1), sub_opt); } void PclRecorderROS2::callback(const sensor_msgs::msg::PointCloud2::SharedPtr cloud) diff --git a/pcl_recorder/src/mainROS2.cpp b/pcl_recorder/src/mainROS2.cpp index c4451fe9..93c2a286 100644 --- a/pcl_recorder/src/mainROS2.cpp +++ b/pcl_recorder/src/mainROS2.cpp @@ -4,13 +4,17 @@ * This work is licensed under the terms of the MIT license. * For a copy, see . */ -#include "rclcpp/rclcpp.hpp" #include "PclRecorderROS2.h" +#include "rclcpp/rclcpp.hpp" + int main(int argc, char** argv) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::executors::MultiThreadedExecutor executor; + auto recorder = std::make_shared(); + executor.add_node(recorder); + executor.spin(); rclcpp::shutdown(); return 0; } diff --git a/ros_compatibility/CMakeLists.txt b/ros_compatibility/CMakeLists.txt index a249a699..8c0ff3e0 100644 --- a/ros_compatibility/CMakeLists.txt +++ b/ros_compatibility/CMakeLists.txt @@ -20,7 +20,4 @@ if(${ROS_VERSION} EQUAL 1) include_directories() - catkin_install_python(PROGRAMS src/ros_compatibility/ros_compatible_node.py - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - endif() diff --git a/ros_compatibility/src/ros_compatibility/__init__.py b/ros_compatibility/src/ros_compatibility/__init__.py index 5760b616..34272fe7 100644 --- a/ros_compatibility/src/ros_compatibility/__init__.py +++ b/ros_compatibility/src/ros_compatibility/__init__.py @@ -1 +1,111 @@ -from ros_compatibility.ros_compatible_node import * \ No newline at end of file +#!/usr/bin/env python + +# +# Copyright (c) 2021 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +__all__ = [ + 'get_ros_version', + 'init', 'ok', 'shutdown', 'on_shutdown', + 'ros_timestamp', + 'get_service_request', 'get_service_response', + 'logdebug', 'loginfo', 'logwarn', 'logerr', 'logfatal' +] + +import ros_compatibility.callback_groups +import ros_compatibility.exceptions +import ros_compatibility.executors +import ros_compatibility.node +import ros_compatibility.qos + +from ros_compatibility.core import get_ros_version +from ros_compatibility.logging import logdebug, loginfo, logwarn, logerr, logfatal + +ROS_VERSION = get_ros_version() + +if ROS_VERSION == 1: + + import rospy + import rospkg + + def init(name, args=None): + rospy.init_node(name) + + def ok(): + return not rospy.is_shutdown() + + def shutdown(): + pass + + def on_shutdown(hook): + rospy.on_shutdown(hook) + + def ros_timestamp(sec=0, nsec=0, from_sec=False): + if from_sec: + return rospy.Time.from_sec(sec) + return rospy.Time(int(sec), int(nsec)) + + def get_service_request(service_type): + classname = service_type.__name__ + "Request" + module = ".".join(service_type.__module__.split(".")[:-1]) + request_class = __import__(module, fromlist=[classname]) + return getattr(request_class, classname)() + + def get_service_response(service_type): + classname = service_type.__name__ + "Response" + module = ".".join(service_type.__module__.split(".")[:-1]) + response_class = __import__(module, fromlist=[classname]) + return getattr(response_class, classname)() + + def get_package_share_directory(package_name): + return rospkg.RosPack().get_path(package_name) + +elif ROS_VERSION == 2: + + import ament_index_python.packages + import rclpy + from builtin_interfaces.msg import Time + + _shutdown_hooks = [] + + def init(name, args=None): + rclpy.init(args=args) + + def ok(): + return rclpy.ok() + + def shutdown(): + global _shutdown_hooks + for h in _shutdown_hooks: + h() + rclpy.shutdown() + + def _add_shutdown_hook(hook): + if not callable(hook): + raise TypeError("shutdown hook [%s] must be a function or callable object: %s"%(hook, type(hook))) + _shutdown_hooks.append(hook) + + def on_shutdown(hook): + _add_shutdown_hook(hook) + + def ros_timestamp(sec=0, nsec=0, from_sec=False): + time = Time() + if from_sec: + time.sec = int(sec) + time.nanosec = int((sec - int(sec)) * 1000000000) + else: + time.sec = int(sec) + time.nanosec = int(nsec) + return time + + def get_service_request(service_type): + return service_type.Request() + + def get_service_response(service_type): + return service_type.Response() + + def get_package_share_directory(package_name): + return ament_index_python.packages.get_package_share_directory(package_name) \ No newline at end of file diff --git a/ros_compatibility/src/ros_compatibility/callback_groups.py b/ros_compatibility/src/ros_compatibility/callback_groups.py new file mode 100644 index 00000000..b253c084 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/callback_groups.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2021 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +from ros_compatibility.core import get_ros_version +ROS_VERSION = get_ros_version() + +if ROS_VERSION == 1: + + class CallbackGroup(object): + pass + + class ReentrantCallbackGroup(CallbackGroup): + pass + + class MutuallyExclusiveCallbackGroup(CallbackGroup): + pass + + +elif ROS_VERSION == 2: + + import rclpy.callback_groups + + class ReentrantCallbackGroup(rclpy.callback_groups.ReentrantCallbackGroup): + pass + + class MutuallyExclusiveCallbackGroup(rclpy.callback_groups.MutuallyExclusiveCallbackGroup): + pass diff --git a/ros_compatibility/src/ros_compatibility/core.py b/ros_compatibility/src/ros_compatibility/core.py new file mode 100644 index 00000000..0916f741 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/core.py @@ -0,0 +1,20 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2021 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +import os + + +def get_ros_version(): + + ros_version = int(os.environ.get("ROS_VERSION", 0)) + + if ros_version not in (1, 2): + raise RuntimeError("Make sure you have a valid `ROS_VERSION` env variable set.") + + return ros_version diff --git a/ros_compatibility/src/ros_compatibility/exceptions.py b/ros_compatibility/src/ros_compatibility/exceptions.py new file mode 100644 index 00000000..2d2c454b --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/exceptions.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2021 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +from ros_compatibility.core import get_ros_version +ROS_VERSION = get_ros_version() + +if ROS_VERSION == 1: + + import rospy + + class ROSException(rospy.ROSException): + pass + + class ROSInterruptException(rospy.ROSInterruptException): + pass + + class ServiceException(rospy.ServiceException): + pass + + +elif ROS_VERSION == 2: + + import rclpy.exceptions + + class ROSException(Exception): + pass + + class ROSInterruptException(rclpy.exceptions.ROSInterruptException): + pass + + class ServiceException(Exception): + pass + diff --git a/ros_compatibility/src/ros_compatibility/executors.py b/ros_compatibility/src/ros_compatibility/executors.py new file mode 100644 index 00000000..1249789e --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/executors.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2021 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +from ros_compatibility.core import get_ros_version +ROS_VERSION = get_ros_version() + +if ROS_VERSION == 1: + + class Executor(object): + def add_node(self, node): + pass + + class SingleThreadedExecutor(Executor): + pass + + class MultiThreadedExecutor(Executor): + pass + + +elif ROS_VERSION == 2: + + import rclpy.executors + + class SingleThreadedExecutor(rclpy.executors.SingleThreadedExecutor): + pass + + class MultiThreadedExecutor(rclpy.executors.MultiThreadedExecutor): + pass + diff --git a/ros_compatibility/src/ros_compatibility/logging.py b/ros_compatibility/src/ros_compatibility/logging.py new file mode 100644 index 00000000..a0b19773 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/logging.py @@ -0,0 +1,49 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2021 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +from ros_compatibility.core import get_ros_version +ROS_VERSION = get_ros_version() + +if ROS_VERSION == 1: + + import rospy + + def logdebug(msg): + rospy.logdebug(msg) + + def loginfo(msg): + rospy.loginfo(msg) + + def logwarn(msg): + rospy.logwarn(msg) + + def logerr(msg): + rospy.logerr(msg) + + def logfatal(msg): + rospy.logfatal(msg) + +elif ROS_VERSION == 2: + + import rclpy + + def logdebug(msg): + rclpy.logging.get_logger("default").debug(msg) + + def loginfo(msg): + rclpy.logging.get_logger("default").info(msg) + + def logwarn(msg): + rclpy.logging.get_logger("default").warn(msg) + + def logerr(msg): + rclpy.logging.get_logger("default").error(msg) + + def logfatal(msg): + rclpy.logging.get_logger("default").fatal(msg) diff --git a/ros_compatibility/src/ros_compatibility/node.py b/ros_compatibility/src/ros_compatibility/node.py new file mode 100644 index 00000000..3d710522 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/node.py @@ -0,0 +1,252 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2021 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +import ros_compatibility.qos +from ros_compatibility.core import get_ros_version +from ros_compatibility.exceptions import * + +ROS_VERSION = get_ros_version() + +if ROS_VERSION == 1: + + import rospy + + from ros_compatibility.logging import logdebug, loginfo, logwarn, logerr, logfatal + + + class CompatibleNode(object): + + def __init__(self, name, **kwargs): + pass + + def get_param(self, name, alternative_value=None, alternative_name=None): + if name.startswith('/'): + raise RuntimeError("Only private parameters are supported.") + return rospy.get_param("~" + name, alternative_value) + + def get_time(self): + return rospy.get_time() + + def logdebug(self, msg): + logdebug(msg) + + def loginfo(self, msg): + loginfo(msg) + + def logwarn(self, msg): + logwarn(msg) + + def logerr(self, msg): + logerr(msg) + + def logfatal(self, msg): + logfatal(msg) + + def new_publisher(self, msg_type, topic, qos_profile, callback_group=None): + if isinstance(qos_profile, int): + qos_profile = ros_compatibility.qos.QoSProfile(depth=qos_profile) + + return rospy.Publisher(topic, msg_type, queue_size=qos_profile.depth, latch=qos_profile.is_latched()) + + def new_subscription(self, msg_type, topic, callback, qos_profile, callback_group=None): + if isinstance(qos_profile, int): + qos_profile = ros_compatibility.qos.QoSProfile(depth=qos_profile) + + return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) + + def new_rate(self, frequency): + return rospy.Rate(frequency) + + def new_timer(self, timer_period_sec, callback, callback_group=None): + return rospy.Timer(rospy.Duration(timer_period_sec), callback) + + def wait_for_message(self, topic, msg_type, timeout=None, qos_profile=None): + try: + return rospy.wait_for_message(topic, msg_type, timeout) + except rospy.ROSException as e: + raise ROSException(e) + + def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): + return rospy.Service(srv_name, srv_type, callback) + + def new_client(self, srv_type, srv_name, timeout_sec=None, callback_group=None): + if timeout_sec is not None: + timeout = timeout_sec * 1000 + else: + timeout = timeout_sec + try: + rospy.wait_for_service(srv_name, timeout=timeout) + client = rospy.ServiceProxy(srv_name, srv_type) + except rospy.ServiceException as e: + raise ServiceException(e) + except rospy.ROSException as e: + raise ROSException(e) + return client + + def call_service(self, client, req, timeout=None, spin_until_response_received=False): + try: + return client(req) + except rospy.ServiceException as e: + raise ServiceException(e) + + def spin(self): + rospy.spin() + + def destroy_service(self, service): + service.shutdown() + + def destroy_subscription(self, subscription): + subscription.unregister() + + def destroy_publisher(self, publisher): + publisher.unregister() + + def destroy(self): + pass + +elif ROS_VERSION == 2: + + import time + from rclpy import Parameter + from rclpy.node import Node + from rclpy.task import Future + import rclpy.qos + + _DURABILITY_POLICY_MAP = { + ros_compatibility.qos.DurabilityPolicy.TRANSIENT_LOCAL: rclpy.qos.DurabilityPolicy.TRANSIENT_LOCAL, + ros_compatibility.qos.DurabilityPolicy.VOLATILE: rclpy.qos.DurabilityPolicy.VOLATILE + } + + + def _get_rclpy_qos_profile(qos_profile): + return rclpy.qos.QoSProfile( + depth=qos_profile.depth, + durability=_DURABILITY_POLICY_MAP[qos_profile.durability] + ) + + + class CompatibleNode(Node): + + def __init__(self, name, **kwargs): + param = Parameter("use_sim_time", Parameter.Type.BOOL, True) + super(CompatibleNode, self).__init__( + name, + allow_undeclared_parameters=True, + automatically_declare_parameters_from_overrides=True, + parameter_overrides=[param], + **kwargs) + + def get_param(self, name, alternative_value=None, alternative_name=None): + if alternative_name is None: + alternative_name = name + return self.get_parameter_or( + name, + Parameter(alternative_name, value=alternative_value)).value + + def get_time(self): + t = self.get_clock().now() + t = t.seconds_nanoseconds() + return float(t[0] + (t[1] / 10**9)) + + def logdebug(self, text): + self.get_logger().debug(text) + + def loginfo(self, text): + self.get_logger().info(text) + + def logwarn(self, text): + self.get_logger().warn(text) + + def logerr(self, text): + self.get_logger().error(text) + + def logfatal(self, text): + self.get_logger().fatal(text) + + def new_publisher(self, msg_type, topic, qos_profile, callback_group=None): + if isinstance(qos_profile, int): + qos_profile = ros_compatibility.qos.QoSProfile(depth=qos_profile) + rclpy_qos_profile = _get_rclpy_qos_profile(qos_profile) + + return self.create_publisher( + msg_type, topic, rclpy_qos_profile, + callback_group=callback_group) + + def new_subscription(self, msg_type, topic, callback, qos_profile, callback_group=None): + if isinstance(qos_profile, int): + qos_profile = ros_compatibility.qos.QoSProfile(depth=qos_profile) + rclpy_qos_profile = _get_rclpy_qos_profile(qos_profile) + + return self.create_subscription( + msg_type, topic, callback, rclpy_qos_profile, + callback_group=callback_group) + + def new_rate(self, frequency): + return self.create_rate(frequency) + + def new_timer(self, timer_period_sec, callback, callback_group=None): + return self.create_timer( + timer_period_sec, callback, callback_group=callback_group) + + def wait_for_message(self, topic, msg_type, timeout=None, qos_profile=1): + """ + Wait for one message from topic. + This will create a new subcription to the topic, receive one message, then unsubscribe. + + Do not call this method in a callback or a deadlock may occur. + """ + s = None + try: + future = Future() + s = self.new_subscription( + msg_type, + topic, + lambda msg: future.set_result(msg), + qos_profile=qos_profile) + rclpy.spin_until_future_complete(self, future, self.executor, timeout) + finally: + if s is not None: + self.destroy_subscription(s) + + return future.result() + + def new_service(self, srv_type, srv_name, callback, callback_group=None): + return self.create_service( + srv_type, srv_name, callback, callback_group=callback_group) + + def new_client(self, srv_type, srv_name, timeout_sec=None, callback_group=None): + client = self.create_client( + srv_type, srv_name, callback_group=callback_group) + ready = client.wait_for_service(timeout_sec=timeout_sec) + if not ready: + raise ROSException("Timeout of {}sec while waiting for service".format(timeout_sec)) + return client + + def call_service(self, client, req, timeout=None, spin_until_response_received=False): + if not spin_until_response_received: + response = client.call(req) + return response + else: + future = client.call_async(req) + rclpy.spin_until_future_complete(self, future, self.executor, timeout) + + if future.done(): + return future.result() + else: + if timeout is not None: + raise ServiceException( + 'Service did not return a response before timeout {}'.format(timeout)) + else: + raise ServiceException('Service did not return a response') + + def spin(self): + rclpy.spin(self, self.executor) + + def destroy(self): + self.destroy_node() diff --git a/ros_compatibility/src/ros_compatibility/qos.py b/ros_compatibility/src/ros_compatibility/qos.py new file mode 100644 index 00000000..1dfbd977 --- /dev/null +++ b/ros_compatibility/src/ros_compatibility/qos.py @@ -0,0 +1,25 @@ +#!/usr/bin/env python + +# +# Copyright (c) 2021 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +import enum + + +class DurabilityPolicy(enum.Enum): + + TRANSIENT_LOCAL = 1 + VOLATILE = 2 + + +class QoSProfile(object): + def __init__(self, depth, durability=DurabilityPolicy.VOLATILE): + self.depth = depth + self.durability = durability + + def is_latched(self): + return self.durability == DurabilityPolicy.TRANSIENT_LOCAL diff --git a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py b/ros_compatibility/src/ros_compatibility/ros_compatible_node.py deleted file mode 100644 index 9dea7219..00000000 --- a/ros_compatibility/src/ros_compatibility/ros_compatible_node.py +++ /dev/null @@ -1,400 +0,0 @@ -# pylint: disable=import-error -import os - -ROS_VERSION = int(os.environ.get('ROS_VERSION', 0)) - -if ROS_VERSION not in (1, 2): - raise NotImplementedError("Make sure you have a valid ROS_VERSION env variable set.") - -if ROS_VERSION == 1: - import rospy -elif ROS_VERSION == 2: - import rclpy -else: - raise NotImplementedError('Make sure you have valid ROS_VERSION env variable.') - -if ROS_VERSION == 1: - - latch_on = True - - def ros_init(args=None): - pass - - def ros_timestamp(sec=0, nsec=0, from_sec=False): - if from_sec: - return rospy.Time.from_sec(sec) - return rospy.Time(int(sec), int(nsec)) - - def ros_ok(): - return not rospy.is_shutdown() - - def ros_shutdown(): - pass - - def ros_on_shutdown(handler): - rospy.on_shutdown(handler) - - def logdebug(log): - rospy.logdebug(log) - - def loginfo(log): - rospy.loginfo(log) - - def logwarn(log): - rospy.logwarn(log) - - def logerr(log): - rospy.logerr(log) - - def logfatal(log): - rospy.logfatal(log) - - def get_service_request(service_type): - ros1_classname = service_type.__name__ + "Request" - module = ".".join(service_type.__module__.split(".")[:-1]) - request_class = __import__(module, fromlist=[ros1_classname]) - return getattr(request_class, ros1_classname)() - - def get_service_response(service_type): - ros1_classname = service_type.__name__ + "Response" - module = ".".join(service_type.__module__.split(".")[:-1]) - request_class = __import__(module, fromlist=[ros1_classname]) - return getattr(request_class, ros1_classname)() - - class ROSException(rospy.ROSException): - pass - - class ROSInterruptException(rospy.ROSInterruptException): - pass - - class ServiceException(rospy.ServiceException): - pass - - class QoSProfile(): - def __init__(self, depth=10, durability=None, **kwargs): - self.depth = depth - self.latch = bool(durability) - - class MultiThreadedExecutor(object): - def add_node(self, node): - pass - - class CompatibleNode(object): - def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): - if rospy_init: - rospy.init_node(node_name, anonymous=True) - self.qos_profile = QoSProfile(depth=queue_size, durability=latch) - self.callback_group = None - - def destroy(self): - pass - - def destroy_service(self, service): - service.shutdown() - - def destroy_subscription(self, subscription): - subscription.unregister() - - def destroy_publisher(self, publisher): - publisher.unregister() - - def get_param(self, name, alternative_value=None, alternative_name=None): - if name.startswith('/'): - raise RuntimeError("Only private parameters are supported.") - if alternative_value is None: - return rospy.get_param("~" + name) - return rospy.get_param("~" + name, alternative_value) - - def logdebug(self, text): - rospy.logdebug(text) - - def loginfo(self, text): - rospy.loginfo(text) - - def logwarn(self, text): - rospy.logwarn(text) - - def logerr(self, text): - rospy.logerr(text) - - def logfatal(self, arg): - rospy.logfatal(arg) - - # assymetry in publisher/subscriber method naming due to rclpy having - # create_publisher method. - def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): - if qos_profile is None: - qos_profile = QoSProfile(depth=10, durability=False) - if callback_group is None: - callback_group = self.callback_group - return rospy.Publisher(topic, msg_type, latch=qos_profile.latch, - queue_size=qos_profile.depth) - - def create_subscriber(self, msg_type, topic, callback, qos_profile=None, - callback_group=None): - if qos_profile is None: - qos_profile = self.qos_profile - return rospy.Subscriber(topic, msg_type, callback, queue_size=qos_profile.depth) - - def new_rate(self, rate): - return rospy.Rate(rate) - - def new_timer(self, timer_period_sec, callback): - return rospy.Timer(rospy.Duration(timer_period_sec), callback) - - def wait_for_message(self, topic, topic_type, timeout=None, qos_profile=None, executor=None): - try: - return rospy.wait_for_message(topic, topic_type, timeout) - except rospy.ROSException as e: - raise ROSException(e) - - def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): - return rospy.Service(srv_name, srv_type, callback) - - def create_service_client(self, service_name, service, timeout_sec=None, callback_group=None): - if timeout_sec is not None: - timeout = timeout_sec * 1000 - else: - timeout = timeout_sec - try: - rospy.wait_for_service(service_name, timeout=timeout) - client = rospy.ServiceProxy(service_name, service) - except rospy.ServiceException as e: - raise ServiceException(e) - except rospy.ROSException as e: - raise ROSException(e) - return client - - def call_service(self, client, req, timeout_ros2=None, executor=None, spin_until_response_received=False): - try: - return client(req) - except rospy.ServiceException as e: - raise ServiceException(e) - - def spin(self, executor=None): - rospy.spin() - - def get_time(self): - return rospy.get_time() - - def shutdown(self): - rospy.signal_shutdown("") - - def on_shutdown(self, handler): - rospy.on_shutdown(handler) - -elif ROS_VERSION == 2: - import time - from rclpy import Parameter - from rclpy.exceptions import ROSInterruptException - from rclpy.node import Node - from rclpy.qos import QoSProfile, QoSDurabilityPolicy - from rclpy.task import Future - from rclpy.executors import MultiThreadedExecutor - from rclpy.callback_groups import MutuallyExclusiveCallbackGroup, ReentrantCallbackGroup - from builtin_interfaces.msg import Time - - latch_on = QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL - def dummy_handler(): pass - shutdown_handler = dummy_handler - - def ros_init(args=None): - rclpy.init(args=args) - - def ros_timestamp(sec=0, nsec=0, from_sec=False): - time = Time() - if from_sec: - time.sec = int(sec) - time.nanosec = int((sec - int(sec)) * 1000000000) - else: - time.sec = int(sec) - time.nanosec = int(nsec) - return time - - def ros_ok(): - return rclpy.ok() - - def ros_shutdown(): - shutdown_handler() - rclpy.shutdown() - - def ros_on_shutdown(handler): - global shutdown_handler - shutdown_handler = handler - - def logdebug(log): - rclpy.logging.get_logger("default").debug(log) - - def loginfo(log): - rclpy.logging.get_logger("default").info(log) - - def logwarn(log): - rclpy.logging.get_logger("default").warn(log) - - def logerr(log): - rclpy.logging.get_logger("default").error(log) - - def logfatal(log): - rclpy.logging.get_logger("default").fatal(log) - - def get_service_request(service_type): - return service_type.Request() - - def get_service_response(service_type): - return service_type.Response() - - class ROSException(Exception): - pass - - class ROSInterruptException(ROSInterruptException): - pass - - class ServiceException(Exception): - pass - - class MultiThreadedExecutor(MultiThreadedExecutor): - pass - - class CompatibleNode(Node): - def __init__(self, node_name, queue_size=10, latch=False, rospy_init=True, **kwargs): - param = Parameter('use_sim_time', Parameter.Type.BOOL, True) - super(CompatibleNode, self).__init__(node_name, allow_undeclared_parameters=True, - automatically_declare_parameters_from_overrides=True, parameter_overrides=[param], **kwargs) - if latch: - self.qos_profile = QoSProfile( - depth=queue_size, - durability=QoSDurabilityPolicy.RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL) - else: - self.qos_profile = QoSProfile(depth=queue_size) - self.callback_group = None - - def destroy(self): - self.destroy_node() - - def get_param(self, name, alternative_value=None, alternative_name=None): - if alternative_value is None: - return self.get_parameter(name).value - if alternative_name is None: - alternative_name = name - return self.get_parameter_or(name, - Parameter(alternative_name, value=alternative_value) - ).value - - def logdebug(self, text): - self.get_logger().debug(text) - - def loginfo(self, text): - self.get_logger().info(text) - - def logwarn(self, text): - self.get_logger().warn(text) - - def logerr(self, text): - self.get_logger().error(text) - - def logfatal(self, text): - self.get_logger().fatal(text) - - def new_publisher(self, msg_type, topic, qos_profile=None, callback_group=None): - if qos_profile is None: - qos_profile = self.qos_profile - if callback_group is None: - callback_group = self.callback_group - return self.create_publisher(msg_type, topic, qos_profile, - callback_group=callback_group) - - def create_subscriber(self, msg_type, topic, callback, qos_profile=None, - callback_group=None): - if qos_profile is None: - qos_profile = self.qos_profile - if callback_group is None: - callback_group = MutuallyExclusiveCallbackGroup() - return self.create_subscription(msg_type, topic, callback, qos_profile, - callback_group=callback_group) - - def new_rate(self, rate): - return self.create_rate(rate) - - def new_timer(self, timer_period_sec, callback): - return self.create_timer(timer_period_sec, callback) - - def wait_for_message(self, topic, topic_type, timeout=None, qos_profile=None, executor=None): - """ - Wait for one message from topic. - - This will create a new subcription to the topic, receive one message, then unsubscribe. - - Do not call this method in a callback or a deadlock may occur. - """ - s = None - try: - future = Future() - s = self.create_subscriber( - topic_type, - topic, - lambda msg: future.set_result(msg), - qos_profile=qos_profile) - rclpy.spin_until_future_complete(self, future, self.executor, timeout) - finally: - if s is not None: - self.destroy_subscription(s) - - return future.result() - - def new_service(self, srv_type, srv_name, callback, qos_profile=None, callback_group=None): - return self.create_service(srv_type, srv_name, callback, callback_group=callback_group) - - def create_service_client(self, service_name, service, timeout_sec=None, callback_group=None): - if callback_group is None: - callback_group = MutuallyExclusiveCallbackGroup() - client = self.create_client(service, service_name, callback_group=callback_group) - status = client.wait_for_service(timeout_sec=timeout_sec) - if status is True: - return client - else: - raise ROSException("Timeout of {}sec while waiting for service".format(timeout_sec)) - - def call_service(self, client, req, timeout_ros2=None, executor=None, spin_until_response_received=False): - - if not spin_until_response_received: - response = client.call(req) - return response - else: - future = client.call_async(req) - rclpy.spin_until_future_complete(self, future, self.executor, timeout_ros2) - - if future.done(): - return future.result() - else: - if timeout_ros2 is not None: - raise ServiceException( - 'Service did not return a response before timeout {}'.format(timeout_ros2)) - else: - raise ServiceException('Service did not return a response') - - def spin(self, executor=None): - rclpy.spin(self, self.executor) - - def get_time(self): - t = self.get_clock().now() - t = t.seconds_nanoseconds() - return float(t[0] + (t[1] / 10**9)) - - def shutdown(self): - rclpy.shutdown() - - def on_shutdown(self, handler): - rclpy.get_default_context().on_shutdown(handler) - - -else: - raise NotImplementedError('Make sure you have valid ROS_VERSION env variable.') - - -def main(): - print('This is a ros1 - ros2 compatibility module.', - 'It is not meant to be executed, but rather imported') - - -if __name__ == '__main__': - main() diff --git a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py index c582ec64..a90b2d71 100644 --- a/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py +++ b/rqt_carla_control/src/rqt_carla_control/rqt_carla_control.py @@ -8,21 +8,19 @@ """ RQT Plugin to control CARLA """ -from carla_msgs.msg import CarlaControl, CarlaStatus # pylint: disable=import-error + +import os +import threading + +from python_qt_binding import loadUi # pylint: disable=import-error from python_qt_binding.QtGui import QPixmap, QIcon # pylint: disable=no-name-in-module, import-error from python_qt_binding.QtWidgets import QWidget # pylint: disable=no-name-in-module, import-error -from python_qt_binding import loadUi # pylint: disable=import-error from qt_gui.plugin import Plugin # pylint: disable=import-error -from ros_compatibility import CompatibleNode, QoSProfile -import os -ROS_VERSION = int(os.environ['ROS_VERSION']) -if ROS_VERSION == 1: - import rospkg -elif ROS_VERSION == 2: - from rclpy.callback_groups import ReentrantCallbackGroup - from ament_index_python.packages import get_package_share_directory - import threading +import ros_compatibility as roscomp +from ros_compatibility.node import CompatibleNode + +from carla_msgs.msg import CarlaControl, CarlaStatus # pylint: disable=import-error class CarlaControlPlugin(Plugin): @@ -40,15 +38,9 @@ def __init__(self, context): self._widget = QWidget() - self._node = CompatibleNode('rqt_carla_control_node', rospy_init=False) - - if ROS_VERSION == 1: - package_share_dir = rospkg.RosPack().get_path('rqt_carla_control') - self.callback_group = None - elif ROS_VERSION == 2: - package_share_dir = get_package_share_directory('rqt_carla_control') - self.callback_group = ReentrantCallbackGroup() + self._node = CompatibleNode('rqt_carla_control_node') + package_share_dir = roscomp.get_package_share_directory('rqt_carla_control') ui_file = os.path.join(package_share_dir, 'resource', 'CarlaControl.ui') loadUi(ui_file, self._widget) @@ -68,11 +60,16 @@ def __init__(self, context): package_share_dir, 'resource', 'step_once.png')))) self.carla_status = None - self.carla_status_subscriber = self._node.create_subscriber( - CarlaStatus, "/carla/status", self.carla_status_changed, callback_group=self.callback_group) + self.carla_status_subscriber = self._node.new_subscription( + CarlaStatus, + "/carla/status", + self.carla_status_changed, + qos_profile=10) self.carla_control_publisher = self._node.new_publisher( - CarlaControl, "/carla/control", QoSProfile(depth=10, durability=False)) + CarlaControl, + "/carla/control", + qos_profile=10) self._widget.pushButtonPlayPause.setDisabled(True) self._widget.pushButtonStepOnce.setDisabled(True) @@ -82,7 +79,7 @@ def __init__(self, context): context.add_widget(self._widget) - if ROS_VERSION == 2: + if roscomp.get_ros_version() == 2: spin_thread = threading.Thread(target=self._node.spin, daemon=True) spin_thread.start() From aef573de7a0ed05fb4bc1f3856a2bd5530d270d0 Mon Sep 17 00:00:00 2001 From: Jean-Baptiste Magnin <47941074+jbmag@users.noreply.github.com> Date: Mon, 14 Jun 2021 18:05:27 +0200 Subject: [PATCH 609/627] [0.9.11] Markers for Carla static objects (#458) Gets bounding boxes for some static objects from Carla, and converts them into Markers to be displayed in rviz. Co-authored-by: fpasch <46815108+fpasch@users.noreply.github.com> Co-authored-by: Pasch, Frederik Co-authored-by: Joel Moriana --- CHANGELOG.md | 1 + carla_ad_demo/config/carla_ad_demo.rviz | 45 ++++++++--- carla_ad_demo/config/carla_ad_demo_ros2.rviz | 28 ++++++- .../src/carla_ros_bridge/actor_factory.py | 3 +- .../src/carla_ros_bridge/marker_sensor.py | 79 ++++++++++++++++++- 5 files changed, 139 insertions(+), 17 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index e44739f9..daf69537 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,6 @@ ## Latest changed +* Added static markers for carla environment objects. * Added hybrid ROS1/ROS2 bridge. * Added passive mode. Wordl configuration and ticking are performed by other clients. * Support spawning of pseudo-actors through service diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz index 1451cd95..eaca2678 100644 --- a/carla_ad_demo/config/carla_ad_demo.rviz +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -3,7 +3,8 @@ Panels: Help Height: 0 Name: Displays Property Tree Widget: - Expanded: ~ + Expanded: + - /StaticObjects1/Namespaces1 Splitter Ratio: 0.5 Tree Height: 632 - Class: rviz/Selection @@ -60,11 +61,30 @@ Visualization Manager: - Class: rviz/MarkerArray Enabled: true Marker Topic: /carla/markers - Name: MarkerArray + Name: Objects Namespaces: "": true Queue Size: 100 Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /carla/markers/static + Name: StaticObjects + Namespaces: + Bridge: false + Buildings: true + Fences: true + GuardRail: true + Poles: false + RoadLines: false + Roads: true + Sidewalks: true + TrafficLight: true + TrafficSigns: true + Vegetation: false + Walls: true + Queue Size: 100 + Value: true - Class: rviz/Camera Enabled: true Image Rendering: background and overlay @@ -79,11 +99,12 @@ Visualization Manager: DVS Camera: true Depth Camera: true Lidar: true - MarkerArray: true + Objects: true Path: true Radar: true Semantic Camera: true Semantic Lidar: true + StaticObjects: true Value: true Zoom Factor: 1 - Alpha: 1 @@ -101,9 +122,9 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 0.9798224568367004 + Max Intensity: 0.988507866859436 Min Color: 0; 0; 0 - Min Intensity: 0.8187355995178223 + Min Intensity: 0.8189489245414734 Name: Lidar Position Transformer: XYZ Queue Size: 10 @@ -240,7 +261,7 @@ Visualization Manager: Views: Current: Class: rviz/ThirdPersonFollower - Distance: 15.07965087890625 + Distance: 17.54503631591797 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 @@ -255,10 +276,10 @@ Visualization Manager: Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.17539866268634796 + Pitch: 0.2903985381126404 Target Frame: ego_vehicle Value: ThirdPersonFollower (rviz) - Yaw: 3.155400276184082 + Yaw: 3.130403995513916 Saved: ~ Window Geometry: CarlaControl: @@ -269,10 +290,10 @@ Window Geometry: collapsed: false Displays: collapsed: false - Height: 1145 + Height: 1136 Hide Left Dock: false Hide Right Dock: false - QMainWindow State: 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 + QMainWindow State: 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 RGB Camera: collapsed: false Selection: @@ -285,6 +306,6 @@ Window Geometry: collapsed: false Views: collapsed: false - Width: 1871 - X: 49 + Width: 1866 + X: 54 Y: 27 diff --git a/carla_ad_demo/config/carla_ad_demo_ros2.rviz b/carla_ad_demo/config/carla_ad_demo_ros2.rviz index 490024e7..cd1eab15 100644 --- a/carla_ad_demo/config/carla_ad_demo_ros2.rviz +++ b/carla_ad_demo/config/carla_ad_demo_ros2.rviz @@ -86,11 +86,12 @@ Visualization Manager: Depth Camera: true Grid: true Lidar: true - MarkerArray: true + Objects: true Path: true Radar: true Semantic Camera: true Semantic Lidar: true + StaticObjects: true Value: true Zoom Factor: 1 - Alpha: 1 @@ -128,7 +129,7 @@ Visualization Manager: Value: true - Class: rviz_default_plugins/MarkerArray Enabled: true - Name: MarkerArray + Name: Objects Namespaces: "": true Topic: @@ -138,6 +139,29 @@ Visualization Manager: Reliability Policy: Reliable Value: /carla/markers Value: true + - Class: rviz_default_plugins/MarkerArray + Enabled: true + Name: StaticObjects + Namespaces: + Bridge: false + Buildings: true + Fences: true + GuardRail: true + Poles: false + RoadLines: false + Roads: true + Sidewalks: true + TrafficLight: true + TrafficSigns: true + Vegetation: false + Walls: true + Topic: + Depth: 5 + Durability Policy: Transient Local + History Policy: Keep Last + Reliability Policy: Reliable + Value: /carla/markers/static + Value: true - Class: rviz_default_plugins/Image Enabled: true Max Value: 1 diff --git a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py index f4fab84f..fa0aed0b 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py +++ b/carla_ros_bridge/src/carla_ros_bridge/actor_factory.py @@ -304,7 +304,8 @@ def _create_object(self, uid, type_id, name, attach_to, spawn_pose, carla_actor= name=name, parent=parent, node=self.node, - actor_list=self.actors) + actor_list=self.actors, + world=self.world) elif type_id == ActorListSensor.get_blueprint_name(): actor = ActorListSensor(uid=uid, diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index 0b46583e..24b71758 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -9,10 +9,46 @@ handle a marker sensor """ +import itertools + +import carla + +from ros_compatibility.qos import QoSProfile, DurabilityPolicy + from carla_ros_bridge.pseudo_actor import PseudoActor from carla_ros_bridge.traffic_participant import TrafficParticipant +from carla_common.transforms import carla_location_to_ros_point, carla_rotation_to_ros_quaternion -from visualization_msgs.msg import MarkerArray +from std_msgs.msg import ColorRGBA +from visualization_msgs.msg import MarkerArray, Marker + +# Using colors from CityScapesPalette specified here: +# https://carla.readthedocs.io/en/latest/ref_sensors/#semantic-segmentation-camera +OBJECT_LABELS = { + #carla.CityObjectLabel.None: ColorRGBA(r=0.0, g=0.0, b=0.0, a=0.8), + carla.CityObjectLabel.Buildings: ColorRGBA(r=70.0/255.0, g=70.0/255.0, b=70.0/255.0, a=0.8), + carla.CityObjectLabel.Fences: ColorRGBA(r=100.0/255.0, g=40.0/255.0, b=40.0/255.0, a=0.8), + #carla.CityObjectLabel.Other: ColorRGBA(r=55.0/255.0, g=90.0/255.0, b=80.0/255.0, a=0.8), + #carla.CityObjectLabel.Pedestrians: ColorRGBA(r=220.0/255.0, g=20.0/255.0, b=60.0/255.0, a=0.8), + carla.CityObjectLabel.Poles: ColorRGBA(r=153.0/255.0, g=153.0/255.0, b=153.0/255.0, a=0.8), + carla.CityObjectLabel.RoadLines: ColorRGBA(r=157.0/255.0, g=234.0/255.0, b=50.0/255.0, a=0.8), + carla.CityObjectLabel.Roads: ColorRGBA(r=128.0/255.0, g=64.0/255.0, b=128.0/255.0, a=0.8), + carla.CityObjectLabel.Sidewalks: ColorRGBA(r=244.0/255.0, g=35.0/255.0, b=232.0/255.0, a=0.8), + carla.CityObjectLabel.Vegetation: ColorRGBA(r=107.0/255.0, g=142.0/255.0, b=35.0/255.0, a=0.8), + #carla.CityObjectLabel.Vehicles: ColorRGBA(r=0.0/255.0, g=0.0/255.0, b=142.0/255.0, a=0.8), + carla.CityObjectLabel.Walls: ColorRGBA(r=102.0/255.0, g=102.0/255.0, b=156.0/255.0, a=0.8), + carla.CityObjectLabel.TrafficSigns: ColorRGBA(r=220.0/255.0, g=220.0/255.0, b=0.0/255.0, a=0.8), + #carla.CityObjectLabel.Sky: ColorRGBA(r=70.0/255.0, g=130.0/255.0, b=180.0/255.0, a=0.8), + #carla.CityObjectLabel.Ground: ColorRGBA(r=81.0/255.0, g=0.0/255.0, b=81.0/255.0, a=0.8), + carla.CityObjectLabel.Bridge: ColorRGBA(r=150.0/255.0, g=100.0/255.0, b=100.0/255.0, a=0.8), + carla.CityObjectLabel.RailTrack: ColorRGBA(r=230.0/255.0, g=150.0/255.0, b=140.0/255.0, a=0.8), + carla.CityObjectLabel.GuardRail: ColorRGBA(r=180.0/255.0, g=165.0/255.0, b=180.0/255.0, a=0.8), + carla.CityObjectLabel.TrafficLight: ColorRGBA(r=250.0/255.0, g=170.0/255.0, b=30.0/255.0, a=0.8), + #carla.CityObjectLabel.Static: ColorRGBA(r=110.0/255.0, g=190.0/255.0, b=160.0/255.0, a=0.8), + #carla.CityObjectLabel.Dynamic: ColorRGBA(r=170.0/255.0, g=120.0/255.0, b=50.0/255.0, a=0.8), + #carla.CityObjectLabel.Water: ColorRGBA(r=45.0/255.0, g=60.0/255.0, b=150.0/255.0, a=0.8), + #carla.CityObjectLabel.Terrain: ColorRGBA(r=145.0/255.0, g=170.0/255.0, b=100.0/255.0, a=0.8), +} class MarkerSensor(PseudoActor): @@ -21,7 +57,7 @@ class MarkerSensor(PseudoActor): Pseudo marker sensor """ - def __init__(self, uid, name, parent, node, actor_list): + def __init__(self, uid, name, parent, node, actor_list, world): """ Constructor @@ -44,10 +80,22 @@ def __init__(self, uid, name, parent, node, actor_list): parent=parent, node=node) self.actor_list = actor_list + self.world = world + self.node = node self.marker_publisher = node.new_publisher(MarkerArray, self.get_topic_prefix(), qos_profile=10) + self.static_marker_publisher = node.new_publisher(MarkerArray, + self.get_topic_prefix() + "/static", + qos_profile=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL)) + + # id generator for static objects. + self.static_id_gen = itertools.count(1) + + static_markers = self._get_static_markers(OBJECT_LABELS.keys()) + if static_markers: + self.static_marker_publisher.publish(static_markers) def destroy(self): """ @@ -56,6 +104,7 @@ def destroy(self): """ self.actor_list = None self.node.destroy_publisher(self.marker_publisher) + self.node.destroy_publisher(self.static_marker_publisher) super(MarkerSensor, self).destroy() @staticmethod @@ -66,6 +115,32 @@ def get_blueprint_name(): """ return "sensor.pseudo.markers" + def _get_marker_from_environment_object(self, environment_object): + marker = Marker(header=self.get_msg_header(frame_id="map")) + marker.ns = str(environment_object.type) + marker.id = next(self.static_id_gen) + + box = environment_object.bounding_box + marker.pose.position = carla_location_to_ros_point(box.location) + marker.pose.orientation = carla_rotation_to_ros_quaternion(box.rotation) + marker.scale.x = max(0.1, 2*box.extent.x) + marker.scale.y = max(0.1, 2*box.extent.y) + marker.scale.z = max(0.1, 2*box.extent.z) + marker.type = Marker.CUBE + + marker.color = OBJECT_LABELS.get(environment_object.type, ColorRGBA(r=1.0, g=0.0, b=0.0, a=0.8)) + return marker + + def _get_static_markers(self, object_types): + static_markers = MarkerArray() + for object_type in object_types: + objects = self.world.get_environment_objects(object_type) + for obj in objects: + marker = self._get_marker_from_environment_object(obj) + static_markers.markers.append(marker) + + return static_markers + def update(self, frame, timestamp): """ Function (override) to update this object. From 153fb48047fa3f2360f1343fe5bb0a4b865475a6 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 15 Jun 2021 17:12:07 +0200 Subject: [PATCH 610/627] Fix timestamp synchronization for some sensors (#551) When generating the header field for some sensors, the timestamp now is used. This is leading to race conditions and synchronization issues between some sensors. This PR fixes the timestamp by using the timestamp provided by the sensor data. --- carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py | 6 +++--- .../src/carla_ros_bridge/lane_invasion_sensor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/lidar.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py | 2 +- carla_ros_bridge/src/carla_ros_bridge/object_sensor.py | 3 ++- carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py | 2 +- .../src/carla_ros_bridge/traffic_participant.py | 4 ++-- 8 files changed, 12 insertions(+), 11 deletions(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py index 89d0c253..aaaf4ae7 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/collision_sensor.py @@ -67,7 +67,7 @@ def sensor_data_updated(self, collision_event): :type collision_event: carla.CollisionEvent """ collision_msg = CarlaCollisionEvent() - collision_msg.header = self.get_msg_header() + collision_msg.header = self.get_msg_header(timestamp=collision_event.timestamp) collision_msg.other_actor_id = collision_event.other_actor.id collision_msg.normal_impulse.x = collision_event.normal_impulse.x collision_msg.normal_impulse.y = collision_event.normal_impulse.y diff --git a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py index 5d86781d..5b5b4319 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py +++ b/carla_ros_bridge/src/carla_ros_bridge/ego_vehicle.py @@ -109,14 +109,14 @@ def get_marker_color(self): color.b = 0.0 return color - def send_vehicle_msgs(self): + def send_vehicle_msgs(self, frame, timestamp): """ send messages related to vehicle status :return: """ vehicle_status = CarlaEgoVehicleStatus( - header=self.get_msg_header("map")) + header=self.get_msg_header("map", timestamp=timestamp)) vehicle_status.velocity = self.get_vehicle_speed_abs(self.carla_actor) vehicle_status.acceleration.linear = self.get_current_ros_accel().linear vehicle_status.orientation = self.get_current_ros_pose().orientation @@ -185,7 +185,7 @@ def update(self, frame, timestamp): :return: """ - self.send_vehicle_msgs() + self.send_vehicle_msgs(frame, timestamp) super(EgoVehicle, self).update(frame, timestamp) def destroy(self): diff --git a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py index 6e038696..0c77da05 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lane_invasion_sensor.py @@ -67,7 +67,7 @@ def sensor_data_updated(self, lane_invasion_event): :type lane_invasion_event: carla.LaneInvasionEvent """ lane_invasion_msg = CarlaLaneInvasionEvent() - lane_invasion_msg.header = self.get_msg_header() + lane_invasion_msg.header = self.get_msg_header(timestamp=lane_invasion_event.timestamp) for marking in lane_invasion_event.crossed_lane_markings: lane_invasion_msg.crossed_lane_markings.append(marking.type) self.lane_invasion_publisher.publish(lane_invasion_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/lidar.py b/carla_ros_bridge/src/carla_ros_bridge/lidar.py index 88e38e9d..9cb39ab1 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/lidar.py +++ b/carla_ros_bridge/src/carla_ros_bridge/lidar.py @@ -138,7 +138,7 @@ def sensor_data_updated(self, carla_lidar_measurement): :param carla_lidar_measurement: carla semantic lidar measurement object :type carla_lidar_measurement: carla.SemanticLidarMeasurement """ - header = self.get_msg_header() + header = self.get_msg_header(timestamp=carla_lidar_measurement.timestamp) fields = [ PointField(name='x', offset=0, datatype=PointField.FLOAT32, count=1), PointField(name='y', offset=4, datatype=PointField.FLOAT32, count=1), diff --git a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py index 24b71758..ad13cd13 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/marker_sensor.py @@ -151,5 +151,5 @@ def update(self, frame, timestamp): marker_array_msg = MarkerArray() for actor in self.actor_list.values(): if isinstance(actor, TrafficParticipant): - marker_array_msg.markers.append(actor.get_marker()) + marker_array_msg.markers.append(actor.get_marker(timestamp)) self.marker_publisher.publish(marker_array_msg) diff --git a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py index 8cb96430..7d881444 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/object_sensor.py @@ -71,7 +71,8 @@ def update(self, frame, timestamp): - tf global frame :return: """ - ros_objects = ObjectArray(header=self.get_msg_header("map")) + ros_objects = ObjectArray() + ros_objects.header = self.get_msg_header(frame_id="map", timestamp=timestamp) for actor_id in self.actor_list.keys(): # currently only Vehicles and Walkers are added to the object array if self.parent is None or self.parent.uid != actor_id: diff --git a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py index 7ab4facd..ac6279fb 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py +++ b/carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py @@ -61,7 +61,7 @@ def update(self, frame, timestamp): """ Function (override) to update this object. """ - odometry = Odometry(header=self.parent.get_msg_header("map")) + odometry = Odometry(header=self.parent.get_msg_header("map", timestamp=timestamp)) odometry.child_frame_id = self.parent.get_prefix() try: odometry.pose.pose = self.parent.get_current_ros_pose() diff --git a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py index f37521e3..43935102 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py +++ b/carla_ros_bridge/src/carla_ros_bridge/traffic_participant.py @@ -123,14 +123,14 @@ def get_marker_pose(self): """ return trans.carla_transform_to_ros_pose(self.carla_actor.get_transform()) - def get_marker(self): + def get_marker(self, timestamp=None): """ Helper function to create a ROS visualization_msgs.msg.Marker for the actor :return: visualization_msgs.msg.Marker """ - marker = Marker(header=self.get_msg_header(frame_id="map")) + marker = Marker(header=self.get_msg_header(frame_id="map", timestamp=timestamp)) marker.color = self.get_marker_color() marker.color.a = 0.3 marker.id = self.get_id() From c9f33e079f20870e21d8d0e136d8bde22685d7af Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 15 Jun 2021 17:18:09 +0200 Subject: [PATCH 611/627] Fix bug when spawning a vehicle with rolename other than ego_vehicle (#552) Fixes a bug when spawning a vehicle with rolename other than ego_vehicle. --- .../src/carla_spawn_objects/carla_spawn_objects.py | 4 ++-- ros_compatibility/src/ros_compatibility/node.py | 8 +++----- 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py index daad53da..0160d6a3 100755 --- a/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py +++ b/carla_spawn_objects/src/carla_spawn_objects/carla_spawn_objects.py @@ -46,8 +46,8 @@ class CarlaSpawnObjects(CompatibleNode): def __init__(self): super(CarlaSpawnObjects, self).__init__('carla_spawn_objects') - self.objects_definition_file = self.get_param('objects_definition_file') - self.spawn_sensors_only = self.get_param('spawn_sensors_only', None) + self.objects_definition_file = self.get_param('objects_definition_file', '') + self.spawn_sensors_only = self.get_param('spawn_sensors_only', False) self.players = [] self.vehicles_sensors = [] diff --git a/ros_compatibility/src/ros_compatibility/node.py b/ros_compatibility/src/ros_compatibility/node.py index 3d710522..f80e8536 100644 --- a/ros_compatibility/src/ros_compatibility/node.py +++ b/ros_compatibility/src/ros_compatibility/node.py @@ -25,7 +25,7 @@ class CompatibleNode(object): def __init__(self, name, **kwargs): pass - def get_param(self, name, alternative_value=None, alternative_name=None): + def get_param(self, name, alternative_value=None): if name.startswith('/'): raise RuntimeError("Only private parameters are supported.") return rospy.get_param("~" + name, alternative_value) @@ -142,12 +142,10 @@ def __init__(self, name, **kwargs): parameter_overrides=[param], **kwargs) - def get_param(self, name, alternative_value=None, alternative_name=None): - if alternative_name is None: - alternative_name = name + def get_param(self, name, alternative_value=None): return self.get_parameter_or( name, - Parameter(alternative_name, value=alternative_value)).value + Parameter(name, value=alternative_value)).value def get_time(self): t = self.get_clock().now() From 9a9eb9b586ec06cc41e5362b55feb59e6c2f730e Mon Sep 17 00:00:00 2001 From: joel-mb Date: Tue, 29 Jun 2021 15:43:25 +0200 Subject: [PATCH 612/627] New register all sensors parameter (#544) Adds a new parameter (register_all_sensors) to avoid publishing data of all the sensors present in the simulation. When enabled, only sensors spawned by the bridge are registered. Otherwise, all the sensors present in the simulation are registered (current behavior). --- .../launch/carla_ros_bridge.launch | 5 +- .../launch/carla_ros_bridge.launch.py | 35 ++++++++++---- .../src/carla_ros_bridge/actor_factory.py | 47 ++++++++++--------- .../src/carla_ros_bridge/bridge.py | 1 + docs/run_ros.md | 4 ++ 5 files changed, 60 insertions(+), 32 deletions(-) diff --git a/carla_ros_bridge/launch/carla_ros_bridge.launch b/carla_ros_bridge/launch/carla_ros_bridge.launch index b4f47fab..e92eb0e1 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge.launch +++ b/carla_ros_bridge/launch/carla_ros_bridge.launch @@ -17,6 +17,9 @@ + + + ament_cmake + rviz2 @@ -27,6 +29,6 @@ catkin - ament_python + ament_cmake diff --git a/carla_ad_demo/setup.cfg b/carla_ad_demo/setup.cfg deleted file mode 100644 index e69de29b..00000000 diff --git a/carla_ad_demo/setup.py b/carla_ad_demo/setup.py deleted file mode 100644 index cdf6f054..00000000 --- a/carla_ad_demo/setup.py +++ /dev/null @@ -1,40 +0,0 @@ -""" -Setup for carla_ad_demo -""" -import os -from glob import glob -ROS_VERSION = int(os.environ['ROS_VERSION']) - -if ROS_VERSION == 1: - from distutils.core import setup - from catkin_pkg.python_setup import generate_distutils_setup - - d = generate_distutils_setup( - packages=['carla_ad_demo'], - ) - - setup(**d) - -elif ROS_VERSION == 2: - from setuptools import setup - - package_name = 'carla_ad_demo' - setup( - name=package_name, - version='0.0.0', - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), - ('share/' + package_name, ['package.xml']), - ('share/' + package_name + '/config', - ['config/FollowLeadingVehicle.xosc', 'config/carla_ad_demo_ros2.rviz']), - (os.path.join('share', package_name), glob('launch/*.launch.py')) - ], - install_requires=['setuptools'], - zip_safe=True, - maintainer='CARLA Simulator Team', - maintainer_email='carla.simulator@gmail.com', - description='CARLA ad demo for ROS2 bridge', - license='MIT', - tests_require=['pytest'], - ) From 0c6a4ddd767f84f792121752e115e2f8bd8d5676 Mon Sep 17 00:00:00 2001 From: Wen Jie Seow <35338681+seowwj@users.noreply.github.com> Date: Wed, 1 Jun 2022 11:57:27 +0200 Subject: [PATCH 621/627] Update RVIZ config for ROS2 CARLA AD Demo (#588) Fixed lidar topic path Co-authored-by: joel-mb --- carla_ad_demo/config/carla_ad_demo_ros2.rviz | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ad_demo/config/carla_ad_demo_ros2.rviz b/carla_ad_demo/config/carla_ad_demo_ros2.rviz index cd1eab15..cf07258f 100644 --- a/carla_ad_demo/config/carla_ad_demo_ros2.rviz +++ b/carla_ad_demo/config/carla_ad_demo_ros2.rviz @@ -123,7 +123,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /carla/ego_vehicle/lidar/lidar1/point_cloud + Value: /carla/ego_vehicle/lidar Use Fixed Frame: true Use rainbow: true Value: true From b37c0ce6f35b348f007d7c7765c90ce6eb62fc3c Mon Sep 17 00:00:00 2001 From: joel-mb Date: Wed, 1 Jun 2022 12:44:18 +0200 Subject: [PATCH 622/627] Fixed CMake check format (#616) * Fix cmake check format * Increased client timeout to 10s --- carla_ad_demo/CMakeLists.txt | 7 +++---- .../carla_ros_bridge_with_example_ego_vehicle.launch.py | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 1c9afd8f..7d377dab 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -26,10 +26,9 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(ament_cmake REQUIRED) - install( - DIRECTORY config launch - DESTINATION share/${PROJECT_NAME} - ) + install(DIRECTORY config/ DESTINATION share/${PROJECT_NAME}) + + install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}) ament_package() diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py index d396a799..05279401 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py @@ -16,7 +16,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='timeout', - default_value='2' + default_value='10' ), launch.actions.DeclareLaunchArgument( name='role_name', From fd35a573d2063c26caed1fb232ed6a1ab8b7e614 Mon Sep 17 00:00:00 2001 From: Felipe Gomes de Melo Date: Wed, 13 Jul 2022 09:04:58 -0300 Subject: [PATCH 623/627] Remove empty launch args default_value (#622) --- .../launch/carla_ros_bridge_with_example_ego_vehicle.launch.py | 2 +- carla_ros_bridge/test/ros_bridge_client_ros2_test.py | 2 +- carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py | 2 +- carla_spawn_objects/launch/carla_spawn_objects.launch.py | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py index 05279401..8714df58 100644 --- a/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py +++ b/carla_ros_bridge/launch/carla_ros_bridge_with_example_ego_vehicle.launch.py @@ -28,7 +28,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='spawn_point', - default_value='' + default_value='None' ), launch.actions.DeclareLaunchArgument( name='town', diff --git a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py index e89abeb0..0828db92 100644 --- a/carla_ros_bridge/test/ros_bridge_client_ros2_test.py +++ b/carla_ros_bridge/test/ros_bridge_client_ros2_test.py @@ -77,7 +77,7 @@ def generate_test_description(): ), launch.actions.DeclareLaunchArgument( name='spawn_point', - default_value='' + default_value='None' ), launch.actions.DeclareLaunchArgument( name='objects_definition_file', diff --git a/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py b/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py index 7b523775..ee24a672 100644 --- a/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py +++ b/carla_spawn_objects/launch/carla_example_ego_vehicle.launch.py @@ -17,7 +17,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='spawn_point_ego_vehicle', - default_value='' + default_value='None' ), launch.actions.DeclareLaunchArgument( name='spawn_sensors_only', diff --git a/carla_spawn_objects/launch/carla_spawn_objects.launch.py b/carla_spawn_objects/launch/carla_spawn_objects.launch.py index ba878484..f8aa1c1a 100644 --- a/carla_spawn_objects/launch/carla_spawn_objects.launch.py +++ b/carla_spawn_objects/launch/carla_spawn_objects.launch.py @@ -15,7 +15,7 @@ def generate_launch_description(): ), launch.actions.DeclareLaunchArgument( name='spawn_point_ego_vehicle', - default_value='' + default_value='None' ), launch.actions.DeclareLaunchArgument( name='spawn_sensors_only', From 1604eb54f7ea7efda479d44157eb35b30a848813 Mon Sep 17 00:00:00 2001 From: berndgassmann Date: Thu, 21 Jul 2022 10:34:03 +0200 Subject: [PATCH 624/627] Fix CI rosversion cmd missing (#626) * Fix CI rosversion cmd missing * Add missing rospy dependency * rospy dependency actually not missing fixing workflow ordering * Add rospy package again * disabling melodic temporarily Co-authored-by: Joel Moriana --- .github/workflows/ci.yml | 14 ++++++++------ install_dependencies.sh | 1 + 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 6c627397..a03662df 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -23,10 +23,10 @@ jobs: strategy: matrix: include: - - docker_image: melodic-robot - ros_distro: melodic - ros_python_version: 2 - ros_version: 1 + #- docker_image: melodic-robot + # ros_distro: melodic + # ros_python_version: 2 + # ros_version: 1 - docker_image: noetic-robot ros_distro: noetic @@ -52,7 +52,9 @@ jobs: fetch-depth: 1 submodules: true - name: Setup - run: ./install_dependencies.sh + run: | + ./install_dependencies.sh + sudo apt-get install --no-install-recommends -y python3-rospkg - name: ROS2 Build, Test, Lint if: ${{ matrix.ros_version == 2 }} shell: bash @@ -69,8 +71,8 @@ jobs: cd $GITHUB_WORKSPACE/../catkin_ws/src ln -s $GITHUB_WORKSPACE cd .. - catkin init source /opt/ros/$(rosversion -d)/setup.bash + catkin init cd $GITHUB_WORKSPACE/../catkin_ws && catkin build --summarize --no-status --force-color catkin run_tests --no-status --force-color && catkin_test_results diff --git a/install_dependencies.sh b/install_dependencies.sh index c85c605f..e96914b7 100755 --- a/install_dependencies.sh +++ b/install_dependencies.sh @@ -11,6 +11,7 @@ if [ "$ROS_VERSION" = "2" ]; then else ADDITIONAL_PACKAGES="ros-$ROS_DISTRO-rviz ros-$ROS_DISTRO-opencv-apps + ros-$ROS_DISTRO-rospy ros-$ROS_DISTRO-rospy-message-converter ros-$ROS_DISTRO-pcl-ros" fi From 4f52fe672e69f8ad3dae317055b641ea41cd04a3 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Thu, 21 Jul 2022 10:42:24 +0200 Subject: [PATCH 625/627] Added missing dependencies (#617) * Added missing dependencies * Fixed cmake format --- pcl_recorder/CMakeLists.txt | 3 ++- pcl_recorder/src/PclRecorderROS2.cpp | 4 ++-- rviz_carla_plugin/CMakeLists.txt | 2 +- 3 files changed, 5 insertions(+), 4 deletions(-) diff --git a/pcl_recorder/CMakeLists.txt b/pcl_recorder/CMakeLists.txt index 3310bbbf..546f863c 100644 --- a/pcl_recorder/CMakeLists.txt +++ b/pcl_recorder/CMakeLists.txt @@ -50,6 +50,7 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(rclcpp_components REQUIRED) find_package(sensor_msgs COMPONENTS) find_package(tf2 REQUIRED) + find_package(tf2_eigen REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) find_package(pcl_conversions REQUIRED) @@ -65,7 +66,7 @@ elseif(${ROS_VERSION} EQUAL 2) add_executable(${PROJECT_NAME}_node src/PclRecorderROS2.cpp src/mainROS2.cpp) ament_target_dependencies(${PROJECT_NAME}_node rclcpp sensor_msgs - pcl_conversions tf2_ros tf2) + pcl_conversions tf2 tf2_ros) target_link_libraries(${PROJECT_NAME}_node ${Boost_SYSTEM_LIBRARY} ${PCL_LIBRARIES}) diff --git a/pcl_recorder/src/PclRecorderROS2.cpp b/pcl_recorder/src/PclRecorderROS2.cpp index ce18a59c..62f6864e 100644 --- a/pcl_recorder/src/PclRecorderROS2.cpp +++ b/pcl_recorder/src/PclRecorderROS2.cpp @@ -27,7 +27,7 @@ PclRecorderROS2::PclRecorderROS2() : Node("pcl_recorder") roleName = "ego_vehicle"; } auto sub_opt = rclcpp::SubscriptionOptions(); - sub_opt.callback_group = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::MutuallyExclusive); + sub_opt.callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); sub = this->create_subscription("/carla/" + roleName + "/lidar", 10, std::bind(&PclRecorderROS2::callback, this, std::placeholders::_1), sub_opt); } @@ -47,7 +47,7 @@ void PclRecorderROS2::callback(const sensor_msgs::msg::PointCloud2::SharedPtr cl Eigen::Affine3d transform; try { - transform = tf2::transformToEigen (tf_buffer_->lookupTransform(fixed_frame_, cloud->header.frame_id, cloud->header.stamp, rclcpp::Duration(1))); + transform = tf2::transformToEigen (tf_buffer_->lookupTransform(fixed_frame_, cloud->header.frame_id, cloud->header.stamp, rclcpp::Duration::from_seconds(1))); pcl::PointCloud pclCloud; pcl::fromROSMsg(*cloud, pclCloud); diff --git a/rviz_carla_plugin/CMakeLists.txt b/rviz_carla_plugin/CMakeLists.txt index 48c1e54f..83904edb 100644 --- a/rviz_carla_plugin/CMakeLists.txt +++ b/rviz_carla_plugin/CMakeLists.txt @@ -74,7 +74,7 @@ elseif(${ROS_VERSION} EQUAL 2) plugin_description_ros2.xml) ament_target_dependencies(rviz_carla_plugin rclcpp carla_msgs nav_msgs - carla_ros_scenario_runner_types) + carla_ros_scenario_runner_types rviz_common) ament_export_libraries(${PROJECT_NAME}) From f47454a0b644d69b7fcef0e0f71fbf02c8ce3a07 Mon Sep 17 00:00:00 2001 From: joel-mb Date: Thu, 21 Jul 2022 16:00:34 +0200 Subject: [PATCH 626/627] Fixed scenario runner node shutdown (#629) * Fix scenario runner node for foxy * CHANGELOG updated --- CHANGELOG.md | 2 ++ carla_ad_demo/CMakeLists.txt | 2 +- .../carla_ros_scenario_runner_node.py | 6 +++--- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index a76d9037..ee767257 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,5 +1,7 @@ ## Latest changed +* Fixed scenario runner node shutdown for foxy +* Fixed actor synchronization creation * Fix of scenario runner status ## CARLA-ROS-Bridge 0.9.11 diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt index 7d377dab..b57753a1 100644 --- a/carla_ad_demo/CMakeLists.txt +++ b/carla_ad_demo/CMakeLists.txt @@ -26,7 +26,7 @@ elseif(${ROS_VERSION} EQUAL 2) find_package(ament_cmake REQUIRED) - install(DIRECTORY config/ DESTINATION share/${PROJECT_NAME}) + install(DIRECTORY config/ DESTINATION share/${PROJECT_NAME}/config) install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py index 448494d7..ef8796e6 100755 --- a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner_node.py @@ -176,16 +176,16 @@ def main(args=None): try: scenario_runner.run() except KeyboardInterrupt: - loginfo("User requested shut down.") + scenario_runner.loginfo("User requested shut down.") finally: if scenario_runner._scenario_runner.is_running(): scenario_runner.loginfo("Scenario Runner still running. Shutting down.") scenario_runner._scenario_runner.shutdown() del scenario_runner - if ROS_VERSION == 2: - spin_thread.join() roscomp.shutdown() + if ROS_VERSION == 2: + spin_thread.join() if __name__ == "__main__": From e9063d97ff5a724f76adbb1b852dc71da1dcfeec Mon Sep 17 00:00:00 2001 From: joel-mb Date: Fri, 22 Jul 2022 09:37:00 +0200 Subject: [PATCH 627/627] Update CARLA version to 0.9.13 (#630) --- CHANGELOG.md | 4 +++- README.md | 2 +- carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION | 2 +- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index ee767257..145615f7 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,4 +1,6 @@ -## Latest changed +## Latest + +## CARLA-ROS-Bridge 0.9.12 * Fixed scenario runner node shutdown for foxy * Fixed actor synchronization creation diff --git a/README.md b/README.md index f291bea2..2d037e26 100644 --- a/README.md +++ b/README.md @@ -9,7 +9,7 @@ ![rviz setup](./docs/images/ad_demo.png "AD Demo") -**This version requires CARLA 0.9.12** +**This version requires CARLA 0.9.13** ## Features diff --git a/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION b/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION index 583b27ac..62ea2590 100644 --- a/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION +++ b/carla_ros_bridge/src/carla_ros_bridge/CARLA_VERSION @@ -1 +1 @@ -0.9.12 +0.9.13

eiapMwMU@}w=0kdvrCt~9?A?gJ-NH9AGY=lkBRf9@}QLP@Pj-jDT6@ftJCs*-a z`lVN51$SJrC3nAEaRg7jgA_$wrB?K{IFqp@J5CZ}(7PDoE6MgyRjeRB*49i~;!x~7 zDqP{@2?^!|q5vE$6l7DJa)@l^AyV-2b%p%B7^%a(R$9m1{X8z;IO`ub>AJeQ&egzM z2MLRpHe0auyN->#zvCN(0(8CT_T4jm$^X{8&uUvfxyCe9-#_@nH6ryw@1K7RBKmpl zAWPD;2DhlD?{kVWf&h^-2M1x>t4IevPJ@B=b4tmlyK_i`P)GR+h;T=${>WD+$U#^( z?!mZO5~z1DETF!Oc^!A>_mn9V-3a+7j0xs4Y{0n($lIDFN@Q-hfarlrje*;X~clAOmKI8bwXC)$fB%2MPLF026&w4KkkoPb3mf0U5p4hWnqC9 zYpuum_Ne_UoM(fv#luTaZC%I)FX&)FT#M3gQ_#-?<&HujB;@V1HJ`uI7}lV7$@y{( zu(6Nse>QWH*SCAk5!uF_M;T*VkvZ}&d$-g2!(3pEA1301=+q4`)BQAz)fTqCwLMzX zE1M?orU){$wvJ%?*a+sH34LXJxhE~`&P>VqJ6K=mED>wo!Au+^fvUTxWq>kRmH7;s zXiMH#+VNe6oP)Icd>CMz5-&kvO*j&{yMK5%itbF|q$Q`Y@CbDBJ4aftQz2E0uE&Jk z>7?x09DmI|PT^sH?%leBi}UYho(jIx(-?5L#4p7nsP(T~W*nh~=*ff70Vr{K-nZV{wOHwTJ>)v9Ac0k#Wi0WM|J!?YBC zs|?0RN0ku!tv6SA4FMqlol=$?bY}PU$pDZzK=zpw>~Au!3pXMH2{ONJ_^~CcL4;z1 zPG2o60RaI_Eh{n=0?BLJ{0z7rp)%v=r$;3vB~{iWOEwM*+)xVlv_Ap-UuP)K2M3V> zbh2xLMmYRrYg+6E&3ovM2XGJiKAq>NRs5Ol^b-T7PJrpmB!Jdgp%5onG9WlO7`=W5 z!sH2q7x8Y}e$J8?bj9k-_<$lvCj0z7qcmv_yU42c(+oTKppU*{L;Z0$9AlnS=nFnx z*AVs;E5NyDHx^k<9l24ssg-{n45aL0!aIEv0|<#cRYPy%FYR7e)viwQkC>u^MPnI& z;|4yV8gLBZVT$|k>Sxjv0nS%6p1>`zU2qZ3qE+Kwa@pjWyI5aRhLwNmO#mU@+ACq= zw^%)kqbn&K4y*29 za?L(tt`YyqPOd4->gMV$o*WNUsOb52@U3XPnHmA=3jmOsmOWWO92_h3YrA;paltLD zW4pWs_Fgck0I1kZ_I%4JO)}3v$@~+3q|7Tp7!Nn|5Z8kl+(Hx_pxCzL*Vfe!KS8v-u#M^PU>swBL;@T_zEP2UDG6WZSuFa7!(2on2rbbEP~nUfT1 zV?PpPsXJ|g#LqPoihBe?Js0e^q>c!U8(6_qfKoyF{WY(0=OxK&ZigkCI$%V_p!wQg zIs_9MzXc*f7?Tu+ZdP8ub#_i_^%7fMYU&KVRr7lI?oP25WSI8Cfm(?kd7sVg+E<}O z+f4OB(8(l8k3uL%<#BSrQsBcMRe*}X!Ahi93wZQyzb&9Kr25Dk=29(}DYFT6)#2}nr$@RD73SUfgh-MjC3UY12=-#hlD-fFb ztKy@-$XmlEqVgTys zam+@v#5EF(d1fHdZ!X3Ze zHtyC41_C*y${y7MZ5yOtX8jSBxznmaa5S24ri z8$dZXP8C-ZP!c6QDT5MZW}Jc1jfjodJ0+Eh7*g!Mf0v-8IV)+<$I3OPH$ravDO&4t zw;vvEgoYoH(u=6(g(ERdJQ1^aNi0?Xgn$tZJA{av z;Ifc!*~Z`Ww9CRTwNN6mTvTu67kX{v;XpSo`M2(C+v!=AI1qo+lmtp7y5D zeDWz=tVSeAgrxbTKV?QwZ~1(B*)zDQdD*c0^ld@H?`_l2@SVh7+avryM72_$=kDay1g}%giub(;BnNb0 zvyEe*_bpLp4u4@#_hlb=q+2Z~euQBv{!(d@y3l|oViR+WE zuV?~Ic5132(8r))dA=LE&Jp=2D(3qSh1j!Wh(V4tVt?BN){8$B#ETpq z8*`jB3av5fK|~Cc;Lj0=P8edVa%)G5)T=5F1y6GDylh>v5wVV)sVzr;W+4EHX*~}Q z-iW9%F)?7FB2$tAFzx_Sp`S4)JzeNKo_oh;O=cTvVKxi7)x!>M_`j-KK?bp$-AfL! zMvSf*j2Ac4fiffbfRTp=JtP6oYYe8(u2kDLU)7r4i6`OfB^TV{Y)|Wc+Nk`n$;rv6 zzm*b|w`pnU)e~gqV3q>r(KR$l5T&Dqx3A408f6~<&;dHKbP$Y**~95T8fsi42M!xQ z^{YvaB!#)|!nykUtD_MikZx}?SNmed70m4OASI@0FOn33oqmk=_DcVKFDom{-Q#$~ zgDrasE=^V>M@K5iCyIss1xZ5jb-#onYihU_6OS}l3HGkWQ_|AY zyK7nbZDz#*vky?va&OCT;*g)?epfu}0>5SlfdbCL*Oz?!y!Pk!I;{F~E76bQ_UT|8 zxzK1!+}fzi&Lbq0?kc_HSReiwPe#3Lnsvd_+L{?Yl~0aPW)k*aX^i>QRD!jrb3Z3~ z|CF*7zzL3yaYmkE**i5}*LLildy0Z*y|{wgsU|n=E021|?bplb($l%WesW7*NYB_c z{Wy$y3WJ_CpayX2C$>19{%CJ@ut^JgbSOnuoa4>iXj@08j3WSYtObvnd|9~SDM)CL z;j+&&cO1Z`kEw%8A~G^F@FBn?zNjht#>>iU+2?wxZC8e)o0Ano?7>0*vQ!g$z>%Ko zKYtZC)F5A#A=3d)*x*JIyh658ZLUrk$hz)@x_torP6J09I_aSP!FV-Y+fV_6P(?<+1Tlf+y4UFZ8>F{>0VM!Vkdw zIsSff8lp?7Zd=@5c{*CD9g=72``qzp>vrPnuh;5kM1%;;V^FnSrei-bUL;+k-O@0K zkv%J~0XOuOLhtZ|fYj1T|_8kfoq(Vs8qNjpx6z3wCFYwVhMtCA;bvW5NUgRo1V5AK-RJ;M8=Sj)}B}5?QFkehAEfAPTYr{oJZ;fK7qq4|Pm zo8gZ2H#|NpO;C@ZF>EDlAa=^!B+_lbrJn3~>Ay;q4qVL^O1j6N{!Tys70kE2h2Wt0 zq)JowVaoe!d_yj5c@gYCxW`kSygO)hSLo5GY_s_g7wN8j{^5|(&Z13JLGU}xha@|E za$W*tWkQxKE}HNtTUA6Z`H8701P$71DH596xSFrTX{mAHQ3;wX+?>X7aH;aSszaPc zyMxFaa6wW;iroU;Xo#uErFLna#j-=69pKOys<9N-GeonK5SCQwxi!MHu+fl}(ah9O z3+3Oka~2*O{p}#^T(l^65ct@lvePsj{E&VAeD<&&DQMFii0y@UnA&x0q~V3PKZ2)- zrk*L2t`X|=r-1I;TP_@%UW`bsxBy~pt+=nM)KEv(iss>uR8DF48xf1=k-iV}&GEy?C9QC|*h-S_lG&d2xG=vjo%;P*G z+f6c_52mVo(^cmb`lhQ%1dfMN;fUc|G8HrgTvHJakL)8^9y*U6Uo8DO zsg3tG2H>%%6oLf(KR0Z=u0t>%bQ&_NS+p=jLcqZz;AS>?;TlyPMsh{;Y9vS_#;#57 zE&Eg)&&4RQkaaS}$t_CV5=Ld%?v2#^BdmUbc$##aLgJBnCQKs&B_bsf<2Oatc7%r% zbK@9ePib?CC=5t_wdKZlj6O?oCUnLZsuwR&0~+`pNjC)_G;e*#ihna3rJub*fCY?j z*_ZZPsrzi}?L|XQLl+lbnhcTS@nj~D>Z3Z%>~q)Qn(18Fo^X{m?QgrB@?n6KoDJEJ zQ~NL}z{BSa=8R}4>M+@%GYfGeQiAnZj+7reh2Qj}^uYW2+HcVV)?G?7R!`)QiRy8k zvM&j&T)UH=I&M1}=ih8$E;W|H>c!wiYNL4XoCsD~7AI|8ove%}vwdVt8F3NHin1z8 z8!3Z*(Anceh64euk&%%~Dk^n;&%Q;)#UMqkxzY%3G!91?5JdD3 z27Ydr7{I{&zPlEQk+5$60px$RbLr?M2^RG9^xU->{k1NK>bN9)1V|2GXB19|k>u5$ z3z(1q*RZ*X%zg8xQ7(>w_H@%Hg}Li#97&snU+O`Ziv|@MC_S8NE7KcFxR(WqhjVqI z_a~h>8fAUm-Ebf(k|KNO3}l#_8lL6RitgQ2v$8}^eyYvtZy`U{5;PE-@~ptDFw8U% z#zeW9PRc_H0HM>04x4drse=r`)aV|zBBjDiy{dT~H5+W&t8+cj$i6JMI0FeIJO?6v z&)0tAac{|oz!xEKe+W$PAtbfuHuJT?uiN*OML;gF5ssY%?pxCe7U6UpH8Q5z9AN3XM%NwsNFrbNrIL%uXpH)5IRq1-4^|gWQ&KPeokGmX6e}U-v(E@Kfw`AjzULc?7 zfnE<#U%WUsicem)(q7 zh>n2BdUIf}=&$qxmwQBb<@Vjvrpi-L6^MRsyK1PSi^wlfXb*Z zi!^|WX240(f85tR|B2}v3;oVA>{^&IzP}UNqkZ*NDCd50r*`NAQ{UIu%W^flr|X2B zskgTtKzxb8-g?NL&$u2)@!%(N;xWFVZ10H+GTlrX87(zVfz+fIN%RyJ`ZCLp$JeJS z&lf5ekgR7iVK-CmaRnyuDVxw`?{a`e4#^2;czymPMXeDZt+T888q$f8OJ1Yl|xA^E>X=~)G@S1S+baTxY8 zztQFLkvysL3}GNzZ$FC>p>yZz-y^4tm;oSz^JC9A&g-}%1E`59l_#{D?8uo?iAqZY>L{K9UBtNUeDMUaZAlS@?vE>W(ZpF7UU z^e^%WxkN>OoefZovl!eecrLLwExD0wY~U`QwV#+N?E)wUJ;#6|d<*VIfZK0;2Z82O zt`GvG!lyCMH!&zQ%{p6TC+CBRgUP@rgVVt2u^!t} zka3W~zyN|6Mn6a%gXKdD)uVcaOX&TN7bWOeACU8O1zt^S2+)Q4Baa{RXl7f)xDuZC zvsUs9@|T8OZpQaVafTI8;+S`@;KXZLV!o9rYgNjO zD$;dwX~-$ebXp9OT?lAw%SnsYJ=rv#W`u%zdclrc~a6IyLX= zL=>!4%|3Y}(0I|OrLOc>^O+J|cZJ8&1uwbmYWo}?Esls@!y+0X@o3-$D>JbhBJvmQ z7>3FmPDu3gb0-!4wPwp(!yV!@`8NC~;co=%=wN@8O|QvMKj|nVmZr%QVIJj<9jDjAnU3;)&GKT)q5kQ4?LsFVIH{ zRO@43P;~woU}NQ}{)i9^n_p0^K;Sl6u!+a5ZA+XXXLcIf*oZ(Y%UVM{b#*F%AP0v| z&01K!PQ-#J%v~*o2JlL zl^EbR?*r*UxB`#gB#}s`+#sh`eV8ua4`Q|!A3o|R$|q}sz|ADDyv*4 zK%@}(r1zzsmkE}n)F zP_w#f;)6@&17Dp?P0dRp13LQ1O}J+W)M||#p&#@d6$W71192;#sdHXv90L*vBWs3| z9om=V6o>Pe{Jt8EP3B>rl+>C&EO+zUQT{jfb-}@P&Aq`W|#SclUm)@tW;lpc))tf_I)XOK}|K z8mP8i;J*?*g@Ha90XkfBt@0uR218J4!a+pHxW~R)&M<(M=%8B70b8E%=VMb)HkFi> z&u07{XGTXy9e|tx!klyi9k^U~d`7Z&?@0oaw3a3Ig(iCob92P;819u(@Tg@6@*caE zJpyP+t2G(G0E$W#2hiO+K;O-JI0H8rY5^kzJ^YaXMl#cE>t_yt{tS|px%v3|03QHc z7f@Q`{FfIOwBXJGuoYtD0R0rp9y@1?JEAEHh1~`ZeFmo>%Q;7{mE91anun3j2Q+s4 zRMG!w0l>Z+Sg_Uf$Y#Di{42N;V+K!jAbEuknBIl_ZbJPA12IMAK#1!|G8@W)i%X(; zT^bv3WxqbBCy;ai7akYkbV$WFRiQARtHgC@8f{^>7s2me$m>&RjfP??lW4&Zd%yby z-E++obMOM1ZR_~Wl_Nj})3@|_W$c6BlZMjoO|Z~x=NrW%p1t=5$?fcbX#eai(fRp# zjI~Ro(#X^}JEY;ltEudp_XzFaXX%U|D5L1c&cgB$R4_ zqQ4!0Qa9^=tL(I{++rvyjxfG>eq4DTizX9p26oBR?Ch<%abLG&$~*?FtTi>ItqkDz z&UrkvNXy9Bfg<2y(H%h-Nc%lBWJlL|j1PSAzW1X%KuDATf<%dX9!krWlZQ(Dwpa|- zLd72JMbFbZp;}}qg&}A~{w1)1Zf;=#t@Q1SAyO*CUdoF}!hh@-h<(rDI)jBGpX|Fo#kE$y=}8CHnm3|N z2BOIp0e6$AK=(`R*&8|mJkP`Q2?P8e)_~*pnFGLig1A>t=4s{>T_+SmT?bg`np=6ft%qY0|Uy`DDBvtPd?8Yde17*o$-QCB&@&$ zC^e892v9z>-O~q?xpU#pbK!8IfJA8{IZjejVvQKLgsheN{e105Aa%E0I=Q~x)B6kp z?^Dy$jX|azfQkE;LSU!~HW4R_J#EZ5P0A3SfyH$>itImvz_O5x2B1h6+K~=hC3oY=i)8aRNSBSWqKa^zU_`=no3W{sDR{X54$52OP5V=7Y-T zwOy0wyd`U@AVXF&LJHP{!!?Bp4HN5?j$V5?#I~K^eo`j|sZaD00~G!*lWlO&VPE)g zp_v7y#&*H?z;?oRR1k@IlKEZ#z&!g!*eRS);lVA@sX&Vpf|`bqzP|Z}EX+xPJ~%>| zQ4*aepMrH2=}j1%PJ<)8t%RBCnn!haP0?vRx4pmL87FX{Gb`efkv_!>37s}i35kgWk zCWda|nK%K&xXE|oN~Q>@sH0fra>m4T)cD3BQr(OQR#*|K0sqc`KBhcuhv^u&U5dGx*{a5emhssM|(M$RLKWSI`pE^GsK{weu64~0B z%zI;~IAaF{$G!;qD{T$i5$kS_JHs5XZG6k$s7AR*Fi{w6FFs-oQRY7j?oEtqbEf5` zxSf(;TRXrOo`3DbD|t8(I^nPSHVCn?jD{C;=Jd2dd#`gY^(*v`I~nZj^r%Coc}j;i zzZ6*#MtrV=*Pic?Yc?Gbu&y-_t*qFXxA8ibD2ajK78ZApa~$7-0bJrO#K&_`tt~utyswiA=s8I~)b%e`pGPoNzi-(=YrsKC zhRc%%qhc(dzFm+gs2A_uNUQA+AIx1 z6&Z!*)`ZgQY5Wc*sHKsjZpbB`Ua-V=WPW)lOM)z=Egp?r1}tVjRFsY(NMOOs@<{ZM z1q@`_47{_~`#>{C7SsJM`5UwB=h}5QS8s(v)i+gYqC{bH7Q;eH)0V9L$ENu zlQ4;|x&A=b;c1%aT9!!@&#Jq{fp@Xz&(Q|MZGE^|*Cj1F*sZPH1EI&qM_so$GjBjx zZTuVIusB})0X1VnDIAy2pLsyT4^8ui#}w(>5&f)8E3+^&u>F-}Z-3tya9Pmt$oaAt ze-0?ZjCiP--v5UF(4pR7)D~( zocy6oBTk9_zi}CuJpBN3r5nIN5t7h$O1G|H-pY73pu@p)DsU$p=C-LPA4t7dv%F1TAuY^3CWjTK6XPMFW zV(avHaD;MoP?VP9u7#$ecUar%CI#LTX zB=2{EIraZNJVRdrFoJ;1>xZ&evkdN+`_oX(FX`t+M|2Df5ZPoUC<-vX`C{7S($W}U zdImva-~bS>$g`&`&^a{nSb=Rj02E%s82`R{fkpuCAZYZUR~ zzVbyNm|w?8(qPf4_qxCPK4T4ZUcKZfS|RwIDrA7=dC3@g80@;|wc`uerc@FNxi z)Zg~=r^J7@upi?-Pjo{b;Iy08YRiU%GU1`3zkGRC#(&VFCaP=u3(Q{iqlNa7uK0{W&barf@46 z03A4kks~-4V0z4uGu{;NdqZ$DR?67VnQvR8_5L(zanr6U!5ZiVkB{xZA)GU@{LXeX zxp~@yS*%+buQbn_fkCKu;ak~pXMJ~f*SxzP`2&pFe_Tu{I_jl>9DXn8W`M%Z&Kyp3 zK|pA0x4Cmby$8l1B?WXi;7V-V9aQbCcisyZDblgGol1Iod3iur9;b}d%v5E`)xR$0 z;HP)JzUa+}(WwaeyR5X=vYKiVz2*;(5!TA_R#vuoEhIx=BWfCYw*#WisyIv5Ug_&+=w9U4lOv|z5->S0GcFz}6wcCMmDwVtpzPlEeJ?=BO%=>jiiJUN_VGpcXvvsARU58cS@IZH%K!`$9?9z>)y5I9~EKd z9p*jfIp??c?j?AogjVveWB#wbe-6^qY4Tph|im$Z4&gbntS1gg9a&q>p z02PqPeV-I-mYPC~NA)VPN?Otnbh`@<%>y=6fL#+lx`WyGxWtLKM~KHZv%!UVVJGIW511d=ls`7LAxno z*p8~nzc3yJ6o@xv1K;WLj}J-K!mO~l*lTo1P*JCO9e5(pXr@p&wD21Rb0(>=OawX? zD5`fpzE}RpnkvUTJ)($~;B<$=N&W{xS~|WKCmuJv!k|n*uBSR)KI3;MRYb%_$hrlx z;=qLSS+s>;flLcN)?I>sEq=e4p0fg$KUt0M>#N#7+!Jk|y`Ku{I9SN|EU;uzq{G=I zoOOFp;l1ai(l%-D6%>yz>*5I(iv6;wV3^q1;gaf%u`RIYg2f<9l-B-e@JA_wVm`30 zOfdx>$qygB%OlG@2oLZJPEfhYa@D9~ep~G`WU|MnMIih#YeT>2;2%IiOvL2+GYOAg z_j_#xXXtuGY}z@PJ3d297Av5yZpPnCb>NV?FuCT`P$akbQ+a|?u`$wlZiYJlbW%O! zJbg8G$;-|>p$%gHlJNGu1-U!z>B68|*1_5mN_(r8z=Cd#4UhqQdS=)z)hCSa8JlI7 z4Kl4O1$@aKIi^Ggq8Z@C&|l%GKA`F%I?WAMClNkw>YxYu`_B_i%_Y$3rNKwae`DX0 zW=cCB$!d!A<(zr-N=^&?*N+1P+4z!&^!Jv*lIQ^-NJ!xhu+!XtP~uqf0Zv5qKe86K z^M6qAv_~FSBJ;>=X_g|D)TmR|z^%m9bbL4br?SeIt4Tdun|8PY z7X!DkYWFO5ws34~EobijWF#b&>vR1zmy_L5tyRS#IIl8E_p9#>l@@3BZ-h~dVYK^E zTrWfHy)TV(x2sy(N1I&^`Oor#ZqDOGV^80IsuqD?QsU$hkrUA`R4F~*FX-sUFj%PF z0e8frg~Eo0T-x_nTj}Oc;Z>P`tk7+SO+1?eO{Jus0s_SGS#^3**=)MFZ5h83&sb$Y zJw4U4dUS%#*U(h3vzP5gp8Na&*03=g?CfG78?q%8a21@0z=(U*_4%ry7ywVxm6^n_;3X7;%Q#;Y;ogQ-W4hx4`d zW)Uz?@$9FU&+^z^*mguLn_*m8S+QAeOiCa1hX+Ix}^M;mP{~> zXbdW9Xh?NziavBNR3VD&vn!hcGp!y^Z~Y55ziZg$W=}BCq01a~1j9D4aKkveoF>^n zIibyEGurPR0%@ zQ~DA&o2#G*IY@f*0P9|(+^ux~i;=bB;^KqjaaqV zok$iyU$8i*E=DNf=9Vxy`4Lt-@puf<>aJ;r)RS)UBOreXb!+It^JhCZB;1C zl^|JOf$`vTx%%!XNiPH}WEZ;E*D2xQ;h_q@Pvug8x&ktLiF`4TClnXg;G@0)vTR9J zSPdcI9ePlejGyv%6|lYsao*{K6vZtqB-7mB?E&)efvDicd0+>U=Fq(6doRWL+cq6% zz(LlWQ$bM)8?>hQ=~-EYdet}xRBJ%3uF-IENEo`muN7%$6&e}}r1jy#b$G)!<32s= z)+AHssrHxJU%^^1K9sf9s=P6#Me>=^yhV$pPjZIRt6=W-iOP+e8o+pRU)%)U4m5~m0S9b zSP>QF$p0Ou`1}Psr<~BVG536bV|t#tyhCAnFUUAkXxK-6Vem5|2a6j*VnL&;71~K4 z7|S}zO{PmX$u4#iY-<*YFMTwP?Eb0q8$N93P@IyiH`d^*7jQ*ZigiVC!iJOfM{;w{ zd@(lZ`u9E2g}H&jQL#Y1f&t1GH zZnfVWu#Y~!YuCvkO!`)iHP={PB&MKEOim~ubtxLTXmZs5U3}MNQgBr)eqc49I6~fx zTriU50gRv?SLbY^i8IdoefJ`1N@oS-fiBuVl7WHavW`r~i@ZYKXlM#+{ZnWNRQX@d zoaqzQ(QJbi4BiUBt-#a7Zfq46zut}cBx7apo2K60013O)D>x&p`o&Fi?1TiIF82OM z)+u$ipf9WW#|xqiNTkB)U!S4#)!JgR z)h7OW_2V-~x}+jD@*?(J^m>sVUFW+k6z6q(rL2D`0@Y7T73EPj+Ac1(sxT}sHBOU{$qa|oi=O|+o+O!y~?OIug$K%ZsPjx`qktz z7yI&2)gOC_>EaamjXO)%9+{>t!#ej@`97PEb1ufNKax3-&;rsFOS~n&b{D`g;10^e zN|Z_enVTcft^tb7=0$wlvXe3~WA~5JpKE;F@FQCb2|coFce9`UzURZ}si&%QHgOSc zSMNT4RnLZ-0FW}fViM@!Pl0?Eky0gJ)k%Nm6wesM%mFCYC{vcwY={v%$g{mHz0_J3 z>kv1-%-<`7Vh7?eWVOk-7p;W$Mbf;B-4Um^ z5UqoU%saj8>O+JG_1OJhCRg4LeN+Qy^F4bne;fL<7UBM?jOVv-G3GfqE)`rH)hn8! zZstDOxA(EKaV>}syqTjn-Jen1LEDv+Lk`^^fKx0fAU5<^o3@SqBV3m3pNUoEYZqh} zyC9^&6C8?dqi>iK6y~!Wb~Oo`J27aQCy-5kuX+Jd*|$+CPRoXaGbC}!g=QBg8h!0@ zc3xiT&z}Q8eJ21CCAo*EYvoCcdcs9xau^>UAMQ*SojKb0Nw}%Gxt{rX1Ro#a;|PVU z5?=e&k#ACx=ZJ-9Yp;nGaSI9xOnxqCyl9=Vl3HQOF?oJWy@+*d4U#v_czO~DHtYl? zDnugIu}MNO8+y2-Pp`A&CVj;ZjJu?W*+EeuM9QkayR?9_qFgerGg*_xZ&AxYFo+Z0 ztxvM}Lo~gz5@VXFR<0h5S;GfZRwkT8!0ZJ$Yc3#(shR8b!o?_Tcma1q#ndH&FTL!} zI&q-FmCsnPZ3}_~zP^9oP6(EGm)0`fshK35mttYYfO`#f!u$^6N)uJ4z^R~5f$m%% zq;)>6rK3YMWh}OHNe{FEd>yywK|w+1Mb5iY91u7{LP7&?Z_e4g&)G7-%~E=fr*?r^ z9P)u=*F4(= zzsRzm9Iwcd)6I^%7;-BF4*WT*dZ0KOLtGTS9AZnht7(*)TUr1<4o59*_1p=Qgo6Xh zJ7D%XMt`en%DJT#je)G+(RA}1qH%2(oQatkDIinS$jOi{Rr8Dp8_Z?;W2WXZy5f0Q z>Af#WAu-JjwqcQtTS~Bhi5;)<6 zl~0o^S1{!**;cp)z%LCS;%m zpq2j4p}zjyC$LWWKq&E3)7;7mj=^xXRlM*LMG}47X)%$9rSK99E|7BQyCGql-gKu! z22hM|aW7S)FH$}4$BhTC!&K$MK));2SogR)e{T-KW=XXxs zqT=$*h#`Dn#A;*|s74)eDg2}&fnl1d$uxm%T=YKp7G=38j$Kl0{e7HOrF1;Xq-}sw z_#Us^utO-$coMQxyt9UoAA@97?5yryYR_SbS71?<>U-YOLV12^e_Gn+%LLEudweTw zMUQG2iNE`t7qFk!t1ps|b~wF5~)2f`}k( zKwTIfnbR%BC*jP1CGK1>(cQ-buOLZJq(xYXxrS02g2y~8M&}b99N~-*o3$Hp{(^&N z(BjFXsM6NmlWgTZ^S2d-;H3OAA>EDwN>p`9Iwh$RoL1fwWeCkO)12(^=qwNKjjPA|ZASik z9KE_Je<_V^@!r~sDlvS6iDw~2=_I-P`|-84@vM!bFBVgsgJi0F?K|afaX}T5g!0FO zg*-zPIldWzD>3PjopZH(F~+>NJ2%R5>QTXXaVka#x=4j4_@yLhZ%rM2R-$>NYtA{~ z;T3UYS9*Bh|GKKNUxtKG;icVEzo{(DF7SK(K|93Uodf2<>W`oVx|I@5Ln#Td1>CsX zc~AIYvQlCFbZ~h`qvjLS3rrUVb~rN0Az3^bxAPb}v-l#7)*;qq zDu164DzH1AoSDJn3JnVl1@_F^Iz7h-W4O|J+k@tuw{OMSs1OECIO+UxqoknoaB}an zt{c*)eHqcsdE+>6WA8<00jq_Ysje%rUn`@QEg4a7A*CxT=ckt>pCIlsQzz9XzAic1 zeSg%gC5r#}6zAF&hnUkFYmogU9@k|cIAM*wlz(1jAQIu4D{H>G@?Lohd!pOcp)#3rqr*A?d>hf2Us73cA3{sH_x*|e#p&}?E{!S* zK5N#vbCdLUPDM9mf&jMkG}7YghTN(X>d}-QbUvNo&9-atP}sqDku~QZcVCT3?h~gg zM0ys48ouL$DKbour+3Jr%Ya$p^)Q6cDT&;^OJQC~{bk*uz?-^}koz3ycl+=QAs}pm zC$O`JTO65?gyMU3buRc`QwKD@Vm28f+}yp_K!^-#Nt6ay+$%1C^bF%ldsCq0Eue5m z2#{gT?Yq|f8$-Nc6Y5zY&G;3DWqXLJI?pdJE;xHTh(fE!tpg&Aw0rq;F9&r3!F#u? z+=i(F`nV7)Lp^!6g%z@XE1t2kCs}l*pIBB-1 zftl$l%!QN)K52-r{!_IIvsuXuBf=CovmyhZWo`cbXHwbngLThWTU!Oluui*|4RLHS zrZWB&7x=OGNyusHB;C3pr*%KjvpZdk^4=lC2E<+Ja1&8-$8=tUN|gQsjJ<&TODNX* z=@#;E9ydM#Iu|=+^4o(RAuyf>g7Ne^Ep!D{8F_ZJ$($E-l;=KtNFjiRK3;a;8ii8L z8&kuq#zx+xiqkj1jixhm&HK&D3fBESm`NASI5urY4$IOoubzd%FLh>htvx@6A;aZv z#lFQ~a~s_Ism3^+RusD@P^dDglb#ix0s9S+<>FV4s68u~0Kk|y2^7)M1EKl(g6L+w zj>tnkMlH}EA&Zr%V~G`LiF>k^uQ|O0kOs+T{YOiHu8e;uS3eV?PaL=)@UJwwjpH6853BAa&?=ZdtU-hr zzgl9Wpbm4EB)>0INf44P`1l&FU|hLaHF=m8lu5KpGM7JC%ifSt5GF#Q2|oK()6pC_iAlPxZ}^$j7WvfM3Wd7x{+1i74)$FHU%ad~V)u zh`O{B(<$@X%A(_Gk*)P+kN3>ng6)YFrjo@R8@~Pcn_3ALK{ho5D`xln0o`}iC#jkR zJnPRjyEq4GtrLaQmY{!YuKMYEtOb?)|D7p5ONjGM1{oim=3}Ihebg%5;03!?Xw*>a z@v{tf*H)yupMn(+*gXPqx9QWvZB4Sm=g$POIK6yC%~h(UYRHnCcI{73zCvt;Dy0+C z(|}0tbJ0y<)(kxD0S>cWAa#(4ggnA2eT$zaX>gwYO}5f=b%>J}UnZB2%O8(uVI7^^ zTj8KTQZW%Vwzw@ef2XJ>s5b=RJK+^zNJbC>F2!YQLq~6lIPMbLxUF2kQv{Axs?Wpc z+*~He2>bbo2+_M=X&4E$;JU?(tm)cclq%qhCL;(E2FSp{^Kp$eknq9D?f%)T;dUcL z{TGyA%;HIZ{aW?lJEQJ}6WP!v$Ab<${pBE?6Ece!HHrj9UH!ERa>nWFrLS)gpCWm2 zG*c5=zmyP3n#eDOYpKHai{Mg&VCkZvq6-S5y6fl) z+(hDh4E}_$vadYp&iyD!i79I|nXKzguVO7Ww8=B<)Xmjfvk(hXOkQnZTVWuU{?u z$o$Fk=};XF_`g(yq#*`<+(O((VVL};ArHCgZrRVyiLzFxae?p#2AXh+4*eYbr%+h% z_Py|%G!|t-@;obvRg}73p`HYa&sq;gT z0~4fz6r&F(J?#g49G~?gOTL@q3>;D>rNkNMv42UqAs?ResJ8i7F_UN zD*t>`vM;LoN)zw5zBT*h4(^eD(y!vt8?}(9#@IVzpD;3xs4cJOR}98f2GJpVwFNvq5F7z}=cX{yaa;GV}3;1g>IYVLf&fE>8Ja>=P@JGjN_ zCoC2wH&&56m+$sh5tF!T?%C;6EG6mruylH;k1Nw)gZ(Q{Ro8erR~Xn^vx7M{XZkiE z_2aBP{_5}C`aGNuB!Qg-ux=6f_eT{=B3`K&iU|TwJZO&r`WZ-8ti2W0#{Q9agg$#ymbSx?ud;xSjYOj7}+2haJEY9Af``WzP&ont&-usuq0w zhDSJua%CT9x{&S!JgET55Q%4G&YQ@9s_4Q3T+u){sxi?%*-qheb=CO_;v??W)L@|x z3p1+u(3aa`jw>TW$=cg-WpiH@F-vpSRrOa-s=3DM!>g0#E?S7rBK2*gEo~n29!i3E zOmEZss}avy+M1f$=1v?_S%W)WR??ap0e`zYl8!Tdtqup2*4+-INJ!0~HlvNM!T0!| z`kuahI9_{V$vK^xp6*ezOaue;WEr$CX$+jbKlc$>6G~9NzQw8>r9@2t69YQBf!8>W4I!qMHEbu~ zG;9WibD`RoPt|&(y}byAgpN?R7@+(}7&X&3(pk0Pp^?0;@o85sc2WGj$;rZXlqh?$=6QM-38;@7|L+b`?ZoUwb)}8R4Ntf*4g!N3fl?X!%<`sLCHXk1g zxQx*^`ApS=Z^VJ6%h$#pv(Jmikr5SzqH5-!_oN7GI+AJ%N61m}zf8%|Lu3A&z&4}S zY?K(R?EkX`7xlwX5`A<=+8xOk5*`JPw|ziEG?+;HUZchc5i~IvP>d6VS2E1$IHB8n z3~Td)V|L@kP#mxsG6R!U{}cDcA}GV(m)|Y;e&fPyD|ud0p#?J zZmnBnAgNOrFeaJcZ+t+@5AC@@y#xD&-Aw!bYoCi-?~w=L!-}6bXJMivK&U+cm5xE5 z+ui*=fH?EO+8+=GOnTha01wFVzK{c3gPX@wzc@>a^JR@zca8zFhCnd!zxbo7T;qM~ z2-^SKykK${43$$aGD}CzgK-$x7kw%ZIlTwmizBc_{xZzc@CBeOwN^8X zyW_dz;79{i=n)YU8-XTa*=@~-^h+mfmR}d5j@yb$gQ7d$s z5&_IjxOQzE&jIGFb94Ha=+CZ&Adp`8o|?qaoFqJ*gnlWOrl0An{Lxq7lU#3`B>%nS zk9ArR(fH_p76J&LbzShFZ!HuJ76rhy#!oZ!wZ{`T@IiRIUQ3lB_kdb7XL*ZIto<%k z1SxBzj=!G`j~9PIh22nsr+mh!sTADcV9vl24NBqwRTKwWkPa)}&-&N)MDD;85UQFB zkTtV7nEF2Nia-Z^9cff?%;;=d*7c)n&rxy0U$7t=pAl@CvA#3d+k- z$8U!dyk>iTJ1I(1ODxuYNf63=mlyI00X{6@$WW(jS`0@d|6sDt`)@jf2~`9GdjF+u zVR?^922m`bH$9D(f~BfZ>I1y-pg9o^OR$|G0^ESL6m~#2JtjF}o;7jk=^* z2(I80q|U@eoyzmU?V(7rs*-%2m`EA+l;1-yeYkZgbud`i zYrK;R%?k>)h*`WRC8o&`V8JHo$vPui_&Hi^;3W>ODaH$eRSA(yx;i@dhmbHLMP|J*IKbD9ATMMq{b;B{ z^1V=zGiQFNr}86X=5R8jadJ09L)hOumn*tBt;5^90;Cx)(R?R~Hu z5|Yr75bZqU;j9g>)aI{69K{6bmff9GVo7j{cGZLIg7u%5dSz@914ml@TgHw)|d4lY60{5)-o>V#Zk#BmGaeQp0Gk9Ks zk3mS(YBi}j4B7PFdkL$tYOq9{A9qp!!v&$XEo_b&!|*bEAy)Z~PVg&f%$j&rnu#OK zIZNzj;%>JINm)-6?3iVn3wN@2pf5Qd3dRJL9E`2i7~6VZJG%ueeMT)CW40Mrd$pXy zUB@^zZi4b$Di$)Q_18ltPr`iE#LK34ZnJgVWU$Egd(_u0lko91<+Wu@%4wv@FNsu=GvA$N99$u{mW5%6{_iRie!2f01!dKCQ zVRXc37tRdxyS(;{4<^-MW}PMA1Q5NN+QKrtuK=@jKUL#WyUNanFeD95Sa2J;o;}<` z0J$2&{HLf$w)i#A+{T6>w1C66%a?hWWh)HwmTUd2lEJsFw^e1vUwT;@lFAKx`S0Jx zy$JBovf;hQHgGVX3pOHS@<$IJB>B%*s}q!4;O_>qgW(mYW$BWD_1ML&5J(aRp1Yvq z!CCS>3BRdnnVX9(%rfWwe)J~n=#{bhD6Pvw_Q>rVb*e3!d6_`vMciFgnSE##qzpUu4Ow*GdQu_&~@(LEj2p5i5zwYjt1iBmBUlBuI}Bt1&q)Q!nS=O>3wz z8x32iH3c510Z{D>070QT>#2jw_xqRfDl^ycz_6uruKkLqf9a|4z&QiFIjhf4*T#fM zP!SX`pm`ZZz=mWnnh^!9&<>zHO|GqtXYdf51J{}mfLeySwH@jP8~#>R7VaAmx#9p` z9h2Xr9=1e%!^eG21fdG%meqf(fB(t$-vL5)ucRP$^X|}o_mAr9>J2rgdg_Sz8a3(~Vh#ic+*ROn8m@x1>R_;FB)1^@{3&pP3s zyMU+`3tCorZI^)-i6-@Ze|sYkc^~(!e*f@>@_RJQdAj4zC0J>lxtM|XgZ?mJ)x`gi zUZvE1YocO?keGNAqzzy{Umlb<-u*2HTp++>&w)fbdUaKAR`ee(Dgo;@H24J2C>v1t z0z_xOg%&uFC`N+;Oka*f9e``E1N3PFUp{a$4IbfO`)F(TRgJ(0&i<0RS@(0M1RwTM?01+a*xO z`+dhi*3WUM|C@Zq2+SENelW`bizs){DgM`s0d?2R)$D2#XhCYh3QOeiKp7ID>>UX0 z51?=@9@8hNOwMt|W$wSw@ySWK)tgZGG(LNB@MaX2mq&pPVlQ%VaBzNL)5QU@ru5L# zqB%d)UkEu@DaCysz7+9}nbvnJh7TzG2Nh@@6UX<6!1@g^$v|v#nh&ra9_v}4Xt$oL zGTj-%xw&fS7%eT%8G;T-yw>jZfY93w0(v(Pu?m)9t>-cJCObo4fpAFVG9SYMG4!7d#BsmBOeh2_T z4VBq%mB0}U`Z0r!ed=wO`t$7t34u)lIr%OSrp0s}>#!2+MUbsHpA3-*q$Jfk-#I#I zkh1PJ?dehe%nQ$=KQEm|%f}O=Q}0BlpYjM!O%Q=D{ ztuCauR-)5HxuqA}c3tB06UWyZUV;(M*fRDT2P{I9-924B^fU;HlE`EXF$9QklE{() z?)r&XDSFv4h?Z;4NW4y_#x{=BZGw;$6=kercPlTymyWbKn+3I zfSq+z0!4en8{(8q@tcoaQRW^uW_WXF6W*{H;Q{Jxh|+oagZoIc6KKI$n?!g;Sutsz z5uqpRnm7ob@Wx9vUc6$_#iWzy7NhhI`Vbmy`$d>L)4f*8KZ*ejZLZ&HfkpzAil%BN zFCncL2YY(l2+8ayiT)Q%e$&1d8IUs*^IWP#2@LAp^}uGy=j;{p8hbdEWb)LaBuz$) zBG{#T^vlZ2qf)>rZJ1Dj9nFi)fnl+c*#GvH>VQ3h9QSM)xiI(tiBVnH4qFtHzEHGH zq&gV=xU__vtt4Jf3q^6aiE$l2*n7O^P+tLp<_&^z;odKQ5w+}sGW5lr5LKTDF*HR% z?ub=#`q)=lZ6a(f>^4Jo6P9m0n&uVX?zbaxO9C}T8cnv4>MnoPWMK}Gxwhf!Dbx~r z>zi2`hG8ihIFkYe3xqtWdivk8^+YIjB!YPRB(UAb5|u~>Sb1O-=UpJzV?)g|A%w1# zfF5NS`r!=436In-t=T<8iz~n$&;QXJ=eNFl$zlpz8Yl_GazBcvTWG(w{`_{wgedej zYMJYFSUukdn0Wkrvx@SnV|Lx%oMrcy=P4PiWOjSblGlkf?1O79%3F~5BxbO7?V!tN zHsUH$_28~vDWiG8VDPy{`D;uT94%hw(%KpY&S!s(8I=IGm;7qm3A(VHTmeKbq(zqB z4n0SBeSaCx-#%skYnqdfT!OSVx|aPts5-25*pde4MH|?Xe#yr-7h_(l5OSNP{(9R_ zm0BUmiT|0Y8O@Zb1Hq=sF|l`zMs(Z`DCFU5EtBCDRCw#|;4s{$*D+&dV)W?^u134J z063ok$e*5^?dxZ?EaxdXS%$$qi0!Z_3lbq-WA$07l7TAhwN-41lQ1uDKUg^Q^z?vA zfDi8ZAl2HKu40QHdaHu&wxIJK0Rg!h4HIu~?=YVAx#oQ1U2k^*MUrgtR(UI39?8~E zPBvZwQZZ4rvg*90k-ZH}@jtorPnlhR^&iE)IH`)Y^-|=@uHDX#L3>G%-Q?@M+dDSC zLf-kT#k14;t%g|3ee@=ulB+=}47 z4{q*I^{O|30;1VAhgn-dkMntp{}s5M?m%rv+}!~=Ne*T~13*L2+Z}>h!yE;)15o?~ z8d%Whd_RVGM)Q`>kqZ+1xeU`8$dHE+|HKHXCDu~8sG$i(35Os!|D*A7Z`wa zI}yPS*n!H^0%tIR&F}_LZuPQMi)KUg0YK(!pQ$bN3c&h|K?a-iV*Udr=fa82{ z>fJuPN3iwt41D$Q~ue(sq zEO(d8W_*j4g=rBKZgmq=RgP2xSL_U8SDpg9h^Y4Xf1FYguY7Xg#v?uad5Gkzyz)l zC=_a#QK=B1r5rji0mKNDRz+oP^apZW_A9UUofK{GRZIZsz2zsW2G+npYLxNzMsws2<(fmMpVZAIm|8Tg+kBs4OOIFJGfz7UcX)&Ut|o?6B?ux(^^?jt|t z4*Fb6QD$7BRSA|Vj-@+}O~)@tZgIh~;ax>X4mmJ`ZM`x5smVMX>GRTiEe@9IKLJpl zWi%SbKn#kNq54ye6$DHKHtpz_*h}XQX|N;aQS+zy1X71Tma1)DJChc(1d+1TMmRH? zNtM5|&M;fnOjRm|cBg>0fZ-;NX@r00LH_1o8Q3-hvBoAVI9_10<$%>w)|YM+D1Zud zHg8q|TKh|b+6`zv)EK2$bIq+BIn4;lV?XrG9$lJDxCpP#^AN{qSb2A`12L6l-*+mDGOCP=H?O<9PYw$WWH3|gpZUO9D8u>qUa{Jv(b^nSx1u!Lc z2SXAdY^KW{uYG>H|IemiKR?V!6JPZCb{wd{&;e8p_dexlw2wf41e(wXh-~0s^V|#Y zB*mQjE$J&A{&%2f)W7K_a0kLNLj6?vNwGmfmmGWDx!cJ&-(HU4)V^D3xwN%vj+Oso z0m=_QdX)T8A=eIVFeqeczf2+_^xJyVQS*fABc3!`i^YLoM?K+BNmD>@P=DW2*PkrlRv5#!)zI!6fU*9e-%ph_zY~(`BTdf--%)qRl9s<~aMf zj;u8*vjN4c(MNrn3L5PS(F=;D6JsX_;TRh{rn-W*MDq2+S1iLl$@mNMuqzx1T4K{x zT-iheT%Pl7#7Hhei)3yBjdp0*`q3pJX>@6SW35I5eu_O zcUS&?hhpi;->#H*KF%AV+T2J!WoEZqmVT*8l<26rn2M-aH-y-A6O@z@f5iT}P>R)kB?O?Wo_&4@92fhf1QwT%&q~jn zuuc!vpKskdO1SX_fmK=*k6%4nn@-={Jv23bilT^Kjah}4UV+02?L*~0A|7-OJYVGZ z)aw~Q)Q{)7_{|X`(JZT4t@?_Idzv+NBM{%MySCPm8JLYF22lsURyhG>C3bJ z)hhFB3UejozLJXC_2^*adYPk~^XJPl|G#!YT9gPZd`4E=aLth~Iu%9hn5jf3*xVCW z*ix7~<{g7rI@}9c@{6>jkzrR%;jKs(k3Y2#OSb$DEF)z+bv_a95%F5(sQmSSc^?(s z0?G2S|750arm~lGB0RnNmU>pJW;XKl`SID0Ztyj}ox)sUvO~Y+Mfk{=Ty$x!)7zpe z=c0yMiCJyiG&yc)a@w-wvW`WL=y2?)>`dz=mxn;8XN=O+ z);5}H->#`0;3C)xDzzf;JEM5!$X2pFaNQdtYj38*i9pQUCQw#ZURYbR7h56FbI<>{ ziR01^TtB2E`Q#G&-)by2(s|&Gw-V5}y;-l@j$Nx1EsGwge>gVvpPcruFJ38zYo(Qw zNHN8g>RMeT9}}o$eyylVmxKa6wPrrBc8)(CjVGFF8tZ#_dyfEr+io|XIk%4~v|e6b ziersS$BxdK%nKFuS;I*dPhXaAFK%nmq_SbJZhl>C59`fP6cb<&jIYOE7W?h5nUX+*GQ5*m zS;+#N$M*M2KJJb{vcSv*(I4v1Y7eJo2Lv^(OU5O-3J^VfOyn)yv%H3XT|fQxo8FWXTfRS! z6g>g9kGz>Y#7~am;K_CwoCSYsR|{8H?*kX~=R!q_fgZe_wzjr?`69<*OsPubg3WB2 zU);c!*$)gP__49E492=!@70@2t4d&P7Cm5G-_QUI?X$A7Kt!HWanDMNTa(KnKKRzm z!}ALZKv%~1=lQ%bB_ri!5)kl6`_{K5Xt1Up9UnXR`mV|%hnt@P%QkpDc`3ExX-h$- z*tJACyP%IPEiDSgs^8vN@yc(KFeFvFvuRr|tS)SR2@K#P1$Q+R$@g4IL z$Lu=`qE9f2ZH$e*GS%eGD}%X)b7#emlFs>bXD*Tp0^&(TUoHrd>vfE^wYX&tF&Znt z|D}@)bc#JbKJKUV<;~n^vxjlH&8|DQI-Vn*4G;GB&29y7TAQm4y9jeLYX4Uu#MmUv!}}?1NWsWUn-!)daJRDtA8n{rgN5BaMax ze|2?r1B`2Yo;E}uc%D|*?v-ys^luQM$r1zqYL-wtp_lphAffI1V&rn|GTh->6W+|4 zjt*s9sZlzm{(v8l9oVh2vmfbUi8Pi%lV7BA&A`c+zntZpAsynW)e+QBEAo4aefb5BW7IW!5kC|Z9R^)+kbK{P9Li~WN%Ybg_iHIr`w{rY*E@oG*fCS zo0pkG_eC=xbNFjrYmZNUsn&Pe3}aN}mlIlZQj~W=U5S@(p8EBlH#~959<>-X2uYij zW)Y`vg5_$fm1YHyu}WaS>#Ovd_a?k{VGx|_Rhs^%d-N@c6+8MEI~!>9+d2kapZ&vn z_->}B{RR(?6wAf}zqL>+?`;nza*m04F(YMbRz!u*c2=vdNB0~CPVw7Rq$%zmE!sN6 z6}Sh_hMEW#{#>SG2wncIxBa5oFDU=SY4M)%`QkG7qVXQ@Vg=9KROy4kOPQ11MiaS# zSMz!+U1spOAKr28KHl>u;iT#&$2rJj{ph9Y+R`jVq;h;GNX<+($oQ?=%Or{RQBPh8 zDMET6v=)t!;A1~xlymUFr0%O9RNoZj%Nh%#N&EYHw^*}VWhzv4iZ_J>jK7T!7G(9h z%9+1N%VQ`|MT_M=ogP-bYoc@g@Hg@2PV|a4g{cSre9rNg#|PsF?YXB{WFW%f`lbF2 zP zZ8BDEzPxFREXN#1##8ILLuXufmNIl|tx8JiF(KipCB@}yOjz0Qvhx<58`7>2MD;!1 zc6(HB-KF~x@@wZz5IO(uPCT%Z7d&Do8=pTuF-k>ouu0FvlB(-wnCQa( zn%x{fJeSkzk!&0pe6sM0&8;J5%!7jBbE{o@uU*afc$!~W_6~X6+w0qo@hAU+jZ9Ju z@^y^&{UAUPagJI4&?uVg(0Ud@_apH&4}qO9!#^GPR!?-8xv4RG*bW^==Eu>)^TRrN zF1#-7DR0^Ft5VQM$jA>d=YII-6j&)6h^WuOCf&>Xt@_2A6+=93rMDlL#PV12a^n8I zR10_s%f5~i=$cpT@_bWR?@?NWYbRcW-u5LbGs?cWqcwK$?Z_5Zfwr3_4gLOyNtWg# zMU03~D9?`sez))_4|e!s9op-Aj|jeO_e)a#D%y#)ET#+fO-Xx8uI<;FoxMf$n{?I+ zG!`L-4O*4Nm=YJ5wm;mHvVSeC9{bsT$w$8#a%y8&q%C$xFyDO(OPLck_zR^%6l4FM z*+A!_0M51F!8`xYxzt5tA``=Kt!31k$czUW5{;y+;i8fHUn$&*nL1g~c$F@;x{YH= zQAb}AX_ni4GJ%K0aj7v+?3OgP7DHcG7wG8sBXstG^*AyWci~qWxeU@T)pOR~R(lYE zY^7pDy7xJ?=-tRA4Jc^80%l$HJx((ps-uko(-mibfYHUbxV{L1@v_y_A>!iXRhMVe943w-J$n^d- zD`Ge}&-%e*w)OROu2WSP*>>yw;}cj;4faKaT@<-_dilodG+ioY2KXf0bwlvUh0%L` zRz1EXS$biWU#)ol)vMb@7O%*jvs)`Zoz+^WHjNs6vR)#sqdnw%MjEI3#|-n^U5IWR zYF#^ea9}BUubfy&l&4ZdMLE2&K}AnbkN)0WFq=0AQ|jZF(^X+mDu8q~X7c|0oC7pW z=#*;ec)&o;8m0_PDjYpM7r85bMD0O5wiuRj9!$GHwf{x1oTkMfZUDor&hGEQ56=2~5MAm#(g^ z6Ixv4aZRpUNO9ysl;cjow?Z;!FIxI_m2OMFw}?I68-LLCN@H{|zgJRLCPG6}>>Hbw zcpx%yqMX5-GMhd~-uN;Pv!T)jUgM*0M?#)%<)`IVkDsMwgOIH3Y%<_+`+9+?9Sbh@ zkal{{FdGi6R3|byc2?H;$%oiBsKRPH!H+TlOD*))9=-{WD>4Y6V~9E@T(`I_bt)(6*Ba)@_FvVR>EIBur;9-KlTfTvZUOA1wFUcUqh z)DI6?U`oexvD~dj@PW{3kTQWfq3;T?CPJQOz*Wz*4L*=`c7#}%5T?pBe2X6A) z?ZzzFNPog#ZuCf+aa_3BjU4I${Z&wx|M{&zgWU@CI7B)_+B@(2-w!7-D=WGZ$ly5^ z`2(RGk6ve+Z*G!He&kKYXLYF*Q;@q6D#a@G-c&OY$PY3%AP}d}9z&npf{b(C-0{QF zDT4{zXq``e|0=?M0`??gAdaHomsxzF3500JrvJE2_-Q!zrut@Q?Z$L7pr~2(!- zgs5jl_z(Pe3}5|%C>fyKvpe2vxjKYUDX~QLeM=uF9{h#zPNTIqAM_Q~MQEOP>n z0x3+lV17f&@gTRJ<^(P4cB6#k_Y$>1e&V0YY*eQ|v{$$L&OW*>qazLbkXOcr_cO3v z>Y0^}rK=T>pa${5GP}#eVJ1_*X}c<%MmU~3BApO7`fNby5Xz9{7; zXSZCY`aEplIk_&H!F5c4FD~t?ako%>W3sq&r&7&(qTT4D%xyvXXy=%SPf7YO)Uyb;) zzn&#Cl6L>)GN!sEqxQ!;Y-KTz_r@u}yJXbLy078UnB(p+2EP`_ z?%H5n@n6|v@1dAKiM)U5IfL#hC-<4`BzJko_|e|;`LTo7MP_3E9R_>Xi`aEEPzJKJ6s3kM4)OD$|~U(fRR<=9HLn z#vLw4Oim#e-VT!5yf!>`M2yO{llEfUQ=I>e28)@(KLI^Flk-5%!NG^DW%FJ-JD3wB z_76NHb$TrwSO2sTCl1>*(C=!CF7Kq7c3Hk$*KT=3@MHF27*fjA-ic7-lJB8PBy+_T zGfyFwS$~jLWkqdXocN`C_mQHu5Xs)hf89Vh)>_lta{34Bl$!m=%C9dNKVXrM8%)rm zb39HM7eBno{jfGTx=Jsrllswl3TB}(a7@NGhm=b&}#vn^K|@K2kp>i^x5_# zj}2L8)Rec_pkd}~l9mpg<%DocJ2Y?(M$* z7+k{v8sLAE34m}L)WX>5e^r4<6lpR}$!F5f&dz3!JJ{M*b1PQPjW^YF8b2Z;a`AHS z?fs6xCnV%Z?h15hf`)x22T5y5f65C90Z*Hxu(Y&97oYcRNHZV*==R{|;<6H&2O5tQ zS$#YB}G&)+11|4Ox^q=K5S~3pI zYPNE!a`v%>OXV6CnNlWd?_4*Ay#|q&UnV-N)4aI~`tS)Wu`A;*9TxIP5suR0Z$fPq z1La=a=BwwN1x_01hm#m9^*g)MD~41YX}>?ZaP1u(st$HImGZe9z+8^GeIu z_s;U?rh`T;A$o#3daMcl%5VC8W7`6lFW?U!%j9f-(#gaT@smoU0Z;~T zKsbVoY7L9X(VVwFjRyC>ey?<(bI6!-`+F`176iQQeCqlhQ`yu<^!D=K@>z0ZGxHNA zyYm3=&AO?@2&2Q!|GB!heSG>E;>|aOg@5sH$>`o~`S~{{$$^naJasgefIu1AFm-8^ z{Pe$gIRuAMbvwQPU|cdoOl3*`(6O? z2(5Z9K>J=^UPim!0DFuk4Ph>$=}TY+xS{0nl1@Y#10am@r_Jx*-;l8Du9S@{WtpQZ zl*V$tFO{lL6Wa!%Q>dwnQ(da0Q5@WKWYU$cN>z1!2OG-A0Js^z^uzO2I$GZ4c0P$W z7wb9Re_!ypdQ0%6|0CCMfBs|i{w*z8^WTlhGxgV6{6{(bOqbo8J>?pDErYPI8Jjg~ zJ*N#(PUFcuSLsbv)mlrJMem}})hh|p;#5Py`3~eViwkI%bT|tkV0}nbs1_V&Gd?us zi8;>ExJ~KKxwa;_TjLwDi@7-iwb}LH7rPWW`cL3#657xcHhHg=OpGwzCs>~H>^F#Q zc&vmbGePd67bDSXbQ{f&Fm_x!@kOMXDrQIbzEEdatm!Cs{OTT~l?!M4SLQzcPeOqi zL-Tc57r3j~Q2tZv6j11m}4B&DRo;TdBm)U?49(4O!FB6DhlE$Y|=)E{8k zLY2aJV=<^0<|&CJF?`OO1DLv6wUuhWileY};qO3o{Ua9Lm1%Oq&}O(Po|6m+|2XTe z8b!sH-a^ixi-nDtI%#1xT4K~*uPayLm!rQ7q3HhR6F91#$Kul81ZLABwho2#p2d5M z4S36l9wlG60Cr!_JJJJ$50G*O%Pr0u>9}|{S;IssGFpA(VE^p;9d*6o|9!r3+ep~! zALgXwmB_6WIEMZ}NsZEKB6h_ovmKj;?bp9q@>THg_*JFDf@nE~iRQlln#p(0P*J3l zOO2SuVy0!z+zjneHn&{VGFTQ){ZmT=*EbrLW}Rx4mc+$KG>Rp!qFB1e+_81EJtcp) zq2qUD@90M1Xo=MxYC%#!@Ulkp{J{(vU1$kV$2f z+PC(xhF;JKb7}(DzOnhP@5ikqR1H-d%q5;+K~>gIIs;VUyUGHf7(rJk!N)g;@V2HR zIE7TH!{oP7XC@=yDz5+4W%@p<2z{lNFiYX)ZP`FRw^ z-g{JlRRrj?6M?5rs$Wv3@HnFY+*3@*`DKnj-&_+%bi`Su)v5>X&SWt=MdY zyc^9oA^dh|==u?6;FPvLwZzjrK&=dbwx+*G`3-Ff*23G(SJvGMj^ z)aF<394e0-;5x-er}-hbyMp~2U`n|K1RP4tYFqII{il|fHOMwL%c|jip99QdB`ONC zI_}xc!6<^NtF3JeFpDE1A>lz)$>m8W8O841-?wCzgn9Y+x`no;0cBXD8l&FtW%57D z_2;Io&!C13d(r|x82?Oh$~yrD`!XHLLj&{T=HA{dsdNWNN6y=s+dKfzo!vN-wbLh; z1iC4svxDR)UAMQjZBx=Pl@&b-N5P< ztYktcL7E|&)ZN1aFW2383`U4AR{_s@k%O8JUhSq~>h2vz+s1g6pJCl)1S}X1npQoW z^xJnxun}w^NvL?f;^rh3MwdJX(o98$U8wWERi%nK7HdwbPM+3xXi__)J$XFz#&Zf_ zAb=Wu^SQacZo-D^?C!gX&LEY4*fhmBr z0nq8?m#xiky9$gP|IH6IR{+Z9xLkQ8K;AVd>FIwjWpoCZQtw`agQo^9`iAAE=H@>Q z59SACPYG%RFm$TqMS!OhYo7TZHz20QBBZj_0+`Y|5j!~{`Rpb~dvveT9q++6#Nh_- zLYd6W(de_kuRX)*8mudEl#sGBo@D@ymh#-IZ{?hS;4#fLr7y{+x3*z!J95&wM5v5@ zvh1}E_%pKIy!ziaw__)KSNwCQ{4Pn+*2H3h!(tg;a@uMVrQ~DGVsg&KNs#c(wTp5s zd9oT>Tc_7P-d1N)7>MpJ4;)Vd-h;l(8AeU<-~vhMp!L5A8}|%E1U7ah3I!}%JmV3p zOF}Hi8tS8@j9P>G+CB!tgcn%7Z!Ge(hE{3S%$$Sij51_J zFiE@8X|#-{TA3aezL=FI^g*zHR~VdWn)l4XKFUU~{@`E(r*G!VG_!^E%`iUUH}`Pf zja>4p@GuT_dU2u*a-yf zZ|IFKw^;8DMyR<#d@of$M?G9t!6MJW1s+GT?_&d8&&U610XFy`wPn@nz6$CC&#OD4 zfyeO`ns!(HSEzS=aWG{Zs!Km9^(@O2NiZqn>C?$B_-}*wTVHXfpr#t8O44?mx~j2B zcvF%nhB8$wBPute-cg-2+2ClYThQMx2t`dup0wTMS2_FlusI{?d0yC+O}p?RXugq4HZhcMJ&3F zr%3vUW)4j7=7j&#h-lI(P&a6oukcI7Kpw&r_W?t!zx7ru0TeHfC}n>e4G9+zM5`7G zni1926CSA0`NLwcGDs6vq0Q;Tsz>cBx0cLqK*!1KFn_iOI7|}2S&{r2zw`h6vs#-C zGIV^E$2lLMJ@`f%uoRO~aYYe12bIealq0XP{Z{*(>XNL}ms>HhYzt!fyXmt2@~Azs zS8~uZA9ou^A2D|cM`YTGSFscoc31_+#5p-9z02YtU#hPX9(~G9uDNz`+G-kX`n%@F zxz0%K;rd2kSBtE6+VsiTQ_}7-^nF{+gCdah zger~#Z1#$a$$+v7RIu@r_5u4&P6+g^?QI8i&8HREL@Z__#tGpO=P5u6hNm)W(nu_g zIx{;9M2ot0>;I<;Zq}j)!aU!4M=U!L)CA%5941@auiB?St+B|gYC8e-?C*6%5~uTJ zhC0K3#JPmSb)x`0J%1{rLrSgOE^*I}d{gh2&`l=9pepA$`SLsW=X2I3IqTIevyoHS7eyRrwRK@#=B zK0(IJ+*}1cK_uyp)Umt0eMO4Var?eW3&^Ci2uc_iD{(pMNV-U;MJWJ%h1j%L47W$H z@5J=V4}@#tg27&Z;#^x!k{0B<^kZ)s& zWWnOLxh23yBq2&0r1<29KB2?!jRUYw1Q(h$n~DU@(#x8}Vo%q;;{7*VNG}jDPmVflPBkJ&HP~ z^3HO2*R|z92EM&5)y|J?Cc0vPe{%P-0m24c|Cc21v}%vK)PYTmhf9*zY@EcF$xq zS0!s=-?#p+FL~1Sw|3Z~M>qLSt`zo0rA=GC8DA{8J}1x_^V@dWV4>7#RHs?GJU|dL zY;PBdpp4$2nQGcjn<&3|uY43VXdLK8F;^wF(@f%*{uKa}&e(4yW>w@*53N*f5w0+_V&`UhFjd}gW`A(AB~q-QnGNXX(vWQ!ZHoEko5(fj?&J14 zd}!nLfsrWXeO7e8aK^P znB|j`B{{`=u&&7v4Ff60VWOwdkXTgAzC>$6#b1(xMXe6rDSJs%jGqLVCv=2X!|tg{ zMdr6QK>d@})d|wsjQYp$l!YCFH<0A9^2hIW?g~b*{$_tnX*7?`1EsGvg=mYw+1!2x5zCn(n~@@t^P4( zT52drdFxN83*%Cx*o0{^SN(0u?){~R_{p(x$KUiB8}R<>=yY`)slMM}j^)Tc8u9e< zE#?bqr;=JUs-42RGh&5;$J1TvMpYIEq2idLvhI{CELVgxdhAs-E%ur~UeexJF@jux zLetd_OGZY^m~?`9V6UZo z4)YS>gGD4U(S!0K$#4iecem(=gC)*fYLO`d$Ir}XNP{JN{g5oga#~p3D-b(K2_c2j z>j_k*hd2_e`!3JMfAdw_k`=gm7*fw4U;*H^VHv9lVelyu;#tU~MK)3`63xB3Np5WB zV+E#8o=J-dnrJ=xOP9OwBa&8(brZ}AJ}xdYts>&uwJk?BK50Xmc9z|n0x#%{m;TXK zyrrvo*Aun@zxt{Bqzt$x{Kw5aWoDw4j$4kOtY=$mGfHlxqyzU7@0k%t~ ze1x1rO$n8Rg8rM-hx+aegH{fv%tZ^p)$oQCzvDLNW#jx~o_taXcVC4cApt>QO3})B zVXFl|1!2SECjGes>0j{2+G@_;9=&`r*IowcPnt!;ul`A+4^`7g5HY{p0w=x4W_Iw+sn?C@U!dcOZRR|{QTF7DSuxq#wXv0d1rLBXTB*Qkr{>@ zOh}7*wzli~Z~l2iX6n~hOFrSQUaCrD#S~0-r!eZ}^2~voF4Gorqe)4aR_K)Ju7$dfx-m~)7lH&zz&FALn|shp#wC97i#C1%_vfHWv+=;* zbP_Ca3WPd%u&_FQ_o%P)i)0VxKW65WSZ|~T(NpT5dAK~qBoQI!@Kp?M^+v~vHyjC? z+?~~MsW~nX`k)viEB@Z=rGcZWyPz2K6ZP7I*e04gldHIDoT;N>!3$G2yzC;VtLo+3;V_-n>tYfQ$T~2JWX8g=h!pQT+3O~R1X7cD$&>KltkR-R_`dhvlzE2LbM-ou6ZsxyBA>D6082O z%As|{_>5;|`X)q)@Lf4BaY&Hr8bOGs*ex6-9Kz*kyZDaXg~1|sY5pY!vT^5B1{&p@ zA++aaEwJYTT38woA-7OR4_U-@^AiVdxgdz4xK4fl4ZHvS-(5<=g39-3DUKQCiaxoa zs(IS2#1%q}XUegx^wFub)De&zoSQlQQjGW5!)UjB;6x$d=EYrs(sV`0tYbbGDY{c3 z#Y7%+QB>IRv;dONj2kb;Xm$%mjJ{kWamF~P(PcHV)u@FDRIa4^Fk?NoLl8Q5SihkAn(7{in-dj{OKirduo9keap=b}-BC(0HF(CnjED{U9camh%sOOh?BZ zU}L}+-c}5vo`}94VQ#r(Zw(W?Hrrl2T>;Ri*kzEEhjNG85+|L03>ttpOZNdvHBU-J z!EbMj9ivy`(x39kEeQTCN7DJ__TRyc^B%M0m2Rw0{MK&PlP0i0(=Ll%o~o`GO&;22 zJ<#yqh(YMGRW|MSm3Y5(k7sRPM94EeH<`8s{W)PU!ulZq`U4W$A%41uIrOfL(t)WZO80}va4whCa=!3!LNH*{=)JuL1* zwix~>pbuMH)Bc^~zy3~ovUui}AxAmQ4p-@5X&G_kG7fBIBm7Sza1%arr;P1K+~4}r znJHbQ$>g5<>ghZfF84u#IBvC{q-C(^NjJ5K^+}= z@C<`<0m$NI&8sCv~0j|vC%~u|;a=t2BY3fKCC3B(TLYCe0MpU(> zz#N5dDNhe?zFL#lOVT`OHe+ZqHIH0|yM6@=kQ@py6N#F6&Ax*L*-BvoJ1!?XLsh{C z&j>E5DEv~=nj7~H7cQuT36&^`km^=rvb2JtXR&Nc5ao@f5-1f#%wjmD1ztB*4McX6iCs;QgD z2UWiL(_l|=KR`s~Q41d*Egns6p|nY#GWGbO7;UDBIV6`M{ERTB%4lx}W;jKKhPHT~ zt7QSZeojq3HG&nf94?2ZGNqg;&xjrw4LA=6_v+bo&SZAUqJ?Uc=;8JZDk9@f z2~Wx>QFf}rQ@_*@EfBjzAY({^kqdoeA5kWBudCAFGzk@j-e7C#-GAp_|Nq5o-M&|G zLtM{EWQs+*91USQc~?9q)XLp`883d{XFB)w%IdmbYWJ~hsIXWmLGE7Qpt{<3%Q~XF zu1~a?B74|wvxQE@%5qQ5Y9SnxYh2o&j797IA*iJ`!_fkUVcY>C7guAk%mEJ-)jMNXP<@kBQ1o9p`f9vSWf^OQt2e7>}lLmk;Wol4Lfhi z$yNI=g>@6v8NJ)QO93l7lj!Kf~Y)M)Y{UboX1FV=6PPmuXB^)T?4o2WUtZ$6J z`R7Bfw@|!_LIYCasw$g9D?l$y9w&C&Yfp8Zl6DXRvE7$Vos5cs-$kojI%=j*DyYXw z2gUSU$fjF#e3Kp=C@POZZdBO#Zbw=(1Y zyl|GEIGXl*PyTb_@`~cGgzr)SPCGoG8>>q?TD_pg3q&!7XUHuK3d{rqZE_<^UV#Z1 zCZ3HUr&<&%Ar@(ip)S&Cu#3{33H3$JpnAqaQFX?Uu!%~QxY6Wg^HDvs&dBPhAJn29 z9#lB%4>6p2ro#eKFx+zV0rUd=AS=H?4C)AjW_319BEAVvyMK{>(V&>~v1nfjjA{Xa z`Em=8&{zt3wC&Q80fQG^%x2 zL)@h2AO{Y)FqD>6UZZKb*f4k$2CRG~_e6+`59gl+zU*H66OS;c_I{)pi`kIL5JkTE z^<1%3INWYU2>zmq&UWLCGsOEq;zN|AC*rmola_qVW-i)I$;T^ca{DDN7a42s*Qr&Z61k8aN8wplaDlA0Ai; zNY$9IEuCdn(lxSecUNwwY1K|!^Xqj4sVbIPLqvodAX-1ikj|c~{VEW=5r9)sf9d+Q zUmyg@33FssU1E2k9e6;q>RZi5)T6Hu^~@E1y2g&32*_((65Km6_RWsh#`TEi(fLFp=!o9S?9{ zzMq#q^X#n~j~}rd1?y>(_N-L-P%7;>5%#>oo-vghP>CDFn|IU`t+TFZb`BfB^~C~6 z^rb6?kh6zJduJL42>r?8V}L!8X>(+OJ~i=40x&)}v@yVLTvEN*7c_#Ro&B9=UQZju ztnO;lbKhulRHf`d=#hQ%xmw%WG6$q#^%!3|pkuYI)6VNc1r5=|g4*k{pN}m!cp_GT z)}WQ8kwSLNfK;6cd$$)D(@bj3Suz`d)e^{{VhjgaJAc}dr81KpcyZBpT6^*n5?9^q z8^3w}H-%qwF~`LmFJ;qp{+z_sn{Y1mZ9!Y*)7II;xQf~Fg7oLBZ$BZyl!7nw@}e?@1SyxL(C|3;hN_qBb!1>D+9 zi^yjq7$~EgX=}VqmyK_55MKTi#vdK}$oNmO*6nfS^7Kz1U_OJ^;X0|KEm)ry5k?K2 zb~QP|_T|AEy1QlDH;#^gjgiUSqXGx9?LcJ=&r=j*ZQAFrxSiBoRB-1pX0QB#zovFK zC`C*KhdHHhq~)*yH7;<$f4wlmN1otEa>iHtg%oHB1b^f%E;J{ z1s5}6+9Nn0Me)12NX?6U;|L zn+_G;Q5o+IDKmG5N-6riK6jkk_y@G9<;Euzu5E%fv>CMZ?3a?F(XkEpei*#L*u?*d zo4|ZtXpl{>h|I_cEk)eCd(sX^EeiIudP%Yy@DkYxLLQT-=CwW-9*tLM_E(#or;R0G;@uT()2R?~B5NyVn=G8jujEp8gOP zQkrJ?v&my?)UM#<1AYERS>yPtmCEV*_bbV`ZA&{gW7Hg2J(#gyY&bVQJ&#q2u3#YE zZ0i2q|KI!f{5k2UWiwa$=j`)-`93yac{=ro^A!I)?W>qAW(g=(UbWEVk?ez-;Ry^dP8HLd0! zO3TRk(z*fpU?}tfg0L+!YShjr>iM@C%juXy4@Piz}8!iGB-|o&gxg8YQBS&LK;~U9k7%+zJ1tR9E<;&6({_C`M7hB-3xtf{Z)%# zBQS}yf-S0yj^(}4HZb`3(Dv5-q0_0L?43NDa%TLX_9R`#Z}N@ei&V%<86ANbdz9HL4^W~C8oToQKrbO6F1t@vNAWHnOyy|4=2vC5VI3D4YwYTqbmuQ-M|{T|pR zr6(#61rDf`O6X<7fA6`{1hj3KHs>Gunq9;M=idi(uL>J5+EXvgfnm$`kNGv8jr-2$ z%+2&hAGV{zXxU099Yz&pam7jhX-Rzf=iV)!7(5o}CsSxHcec!f=KhWi1uzMERPpg-uTU%Sc z7rF;FTjjW<3>@eSodvQmjQ5V+Fa>~22niO@$@Zwu0|CDoTjhuNwZakDS2A|iQO)*h zplt`&?$Xwp&sFl9q$U<6(wrSo?w3a2Jy5h@g! zlbLTAk~gBCFZW;Mxws28vMTp$j0Q$bFVKJfhSn)^BPkVCwv4K>+NK)R206teLJ@&6 z$E~Ut*aYllm6}pFWer?xt9Q0>>Ykin_Y zKe)C}Qf&gJEN+G_lg)E;0#du;@A;!D!RW95jdbqRBx>x!s@9&{FHBH%$SPD=+9n4W zY4L$bD-1LS_Qrp^_8-^mZ2WRd#-|9A`^-qc&&^(va-T7G+^_lJ)4$P2oWwTyOkq2l zJ~$7`C6=N|Oqx~+D_EQLH>ANizR-tbzO`GNhKJvrH+tqTMmg8dgSKFWw}b2N{+Q;g z@+-$!9&TMRLN+Aap5gjGUai_w=ClCt&il|NmSgzV?tl_ztiQ|NYUUu_(PotQ`^8Dj z9KWtgNLT~2W5Tq;&p&+}HlIsRZ_>KTNV&9jNjkVth0wA>yUtTuOl7C==&1cP*IOV^brYzG~32vKnAnPMt3xg9< z3t@>h@}L@u2wJFArbnZdH8P2`*?Ss6W{(|x!gvZ*Jgkl_G$TP=$*nQj9#!9nmrPHM z>Q|MycrXcwLV7{fdYZ{JkH+GKYCT_;&c2pvNbf`U_AQA-(4#E~?;Rt;4wIbuCQRJAPM5bWT1d9Tuhjep_c_;a1MaF}K*jpB)DXj(9 zd6dc|EnP!Zvqr_dZNH_?BcA3>&B<^%vtEq93lTPjf%x-|R{9>)14_|I-3UGlJQD_mRg-XkHc|`IAE~t=a*o zJeJ<;5Zqg1aM$hEEO`2}SIr6?44x>t$V~eYS`3G@9Ki!;SsnGDbZ|@oclV!zJ0^_< z8<#BD@PF~sTkqfe01?#eUJhBDDF~pFb;f7SpMA;Qc_9G#AB%BxNC2Y#G^}e)Qz-vK zjRGr0=NbyqIEza+>&oabLxLsk(f%er#)8!v(4D*CH~$EaiF{x5;-VU+?3+j-Nln}k zcsbJv1>zWwaTDTz=0QG7XR7U6a8w<5k*#usHC;Muv*W&D-!>hQi19v6_&@ckUKt%y z8GZiDP3ljJ@$&S^UD@r?84^9wzw>@Df5FYmFMr7_ck}A`cLfe4?X<$5>lG8e)%y!R ziv2r|RUJcU=1kbY)yDRia6kc3WIrg8(^`l;bdW*)(~!jkcSP&sIkEEBfMSB@pbqKx zf*w*>aPMQDj~NCQRg^N!au=AWKH=<2nHc4`4nhl1Q<|UgUxx!XCgY8wBWY*2 z-5sx)yngZJstywbYYrVHb?Bg~8cQoV5FPMn(HqoLPe+TKoURu5#&7?HTBexe{+)@6 zK`*YP){Wt@rSHZ_#eIGqbiHRA^)+*#y{jIC(TP}dEK`Dc!YwktF!E-lU9V0hIM>x|}-W!D-m%k?xl%?P;zbSCQ5yG8y%^m4VFyMPX)mv54gncJq1 z_jK>;YmCk(dzxI$M0;vt=71^u8>bh=_FicIE%+C~w!ePJ; zw#$@oVmuY7U8`#LpACr0)!v2S9BZGc_IJaB^xJ@-%Ff|UL8I39D{8#y z><3*fDleAi(YS3QW+Gap3O-$Xw{#duCE6`VL7&x!^MLl%`bB21joRsF)F;Y5hE%V617B4pB{EU=s;7CxtHT`I_u6O=ToBM=CD1fbpx+h}cF99sFUQIXTfgxnH0O-Cw^oSkZjmk%%QWa;uLLAFTA?b4`P< zk-@R`>`I0PFfmY9-|H=>mu;fgo#f(_{|y)r=9ZM_{caGq3fkZOtVcHMn&Z0o<71PO zQN2lz@}>dY-^2Cv?&52fx2OGldRVKictb4uhq&pe5c{ls)4~XeJ#CU)oNFAA_$Axx zC;0Sjzke6p&L>hKJAcXMA*V-f{g4tTpK-}TM2<;BW~+Fd7MH+E z{pyB}o;DZ}Idlk49Jxz#H&tqA9c}7QvVZa4CJE(&REf-)0QRK~YpDs}f}FE2Ub| zzm~QV$S7#(#90mqaarn1N}fMSM!CfGy>f2ND9N&q`5I+)>}eh;QmZp2CHbJQ28U4U z*%zr|;(mh3ttb6{v8SAdzoht~;rw+SYTo!uHnLB4>R|?2=%oBaY{(Ldj*JA|^Q6H6 zRKDOIG)Iy)eu7V)>x56h;s^ei?6~v>YAUIfBvYKmBHK1eikPjaQ_x&j4jVoLZWUeZ8ORvSa9LocN>C=Fi~oUuG_C)+JN_jh@a-I2 z(Xzbe7GtuQ2)Q|J^l$7Lz2tBtTe$jB0_kW*4lyJNY!8U6P&GUOg3K|rrI2?{jaAEU zx_Eb-k(n|35wTRyrQK38SMIl%>X>m2yg(>X*+c?II)gmENWDc_|tT=53#8gcKQKk0{hvGn(wpcz1HJ_MU$XnhYjxW@fX^~Cw|tT^ z<2J4P?E!D?D|UN;5VUmSpyhotg(?KSJm%!;8O1fOB|G)=L#sLK&SA zWGlPwNPd{WG|(d%=^sbHy)$o8PxDjXWa2~8nsh4j^v+&}_f=(;4MS~i;MSt1{GXcm z^qGLMDh0o0gofUUO@)`Kn;-qwy_>_b3DsLa2EGf-T5Y&9e1X(F9H80Wuv{OO8anKs zyxuS_iT-&GM4e+}w~7CYBH49a-? z1sv)K0g6uiJyfo&#!dcp@(b@!XW2Nd#u1r@c7by4Pyu3jBnS^rk){@n5S$*o)EYBG z6aDX2!WFI93FvcMMQ||3?r*PC>7lP6r8>AbAgX4OsRbxXI}=`p)8kVRmkaFqdngI2jy2Ek;UijOd}0?-X)8XI{zINOmMEAR%VUjUny4pEk6_&{zI+i zPe7o745#CzFvimJJwXHn(UAR6CxnTOPElJ%;ljt)(phAgu-QeH5PyqmiqzS-Q$zn? z8mWKW@N1%9mMfQOCt&c)>DAEXYMtii+3LcCd?Jcko0zfll(P7ElfdX`4*ljYP1b0w z1W4pQ@k}8!#fBylo=Gzm77zAyD>ua;1Qw%Is-YsQ=-BZki5D-M96LJ*`5=KtWdxg$&$FS;DKzdOTWG@A zfc@uiTX1xW-Q0r2X*z{ z-TLfL`JMFRE2p10GpX2Q+G(|!|IU0OR#qu#o?}V|RmszCsS>xhhp{-_e_eeSSdn5u zjTts!kWMhi(K&DB9Q*EmbGPbb-&Kj&i#Ed9--03~0CNVFb0}L?rQ^eXVS<%^>-;*H zUR|X#iCKzZerwPtV?1T}*JALf;*>-v0W({005$?EQ6hr<^xW*EIJ$<1yB8T+IXGRa zaGrFxr}P2y#3pvx3@xm=?e3%0(uPHeFJUf=LW4V}NeW_Jp7&T*c|I#`PNHl(LHc(| zj#I%?h6Q({-k!+J!Ha$@9XFp>a>(%yo#v7SSa&DA!U~DDa6$ zN9Wt6b3%0VBvvtZwwUm0^b zTl5+mnM{z5kggAW)|y#-$3>qZglJ0m%(gHJvs;V)jx35t)9S(r1iG+0WZRmV3{xC2 zz6wN91U4TtbPLFs!TJkTu>=IT2rBf}r-FB|Qy}>KS_d(YdmCc!;*TlfEQ9Fovu)9f zOPQv+{$kO`2{uw#Gr_+s;h)dl9rSIDh@6eJ9OFk0VE%xRD$bQ;qsKBLw#WWog3nK968`;C}1RTzP`S$sa8;_7oK4@e7P-~1PF^D^yP-UZbLwj!= zp!=p8cgR!tgr*z)qHpz!g4TB7LVqcb|56$`|M76Z-C@qYW2romx7#r$LIQ0iIfW!R z<;tJU=T*>O0S>Vd5fM3L%)fd->PV0~D*MB4`?Fs?peGz@y*px^J7LuDKlRj?vedo5 zKK=UMwys>>9_>N=zn%i}0ZWg)oC6>*{t)mq1MUXxICQ})1mE|NI)ST!yO$h5;9=9M zlPtNQS9PBC_HY^v+tZaAtM);|RJ`A^OJ@G;5(?)WgeQO63fsMr$ zyHW~4=xFm>$=i3sI{{XfW4c{zUD}@L&7F$aXAGS%DLI_@x}l$g=DXeW<-?_7&Cbnw zCwQ=7-T#M&IC)5p3esS}lxacp52!JebyGd~_8bcc3|;|Rwkz4mMbyjcp1e^p`tRZr z+G!xRvlb+z$>V0dBoCi4tY31GxgT{PbR<&W22Iqdu5yHS0!1EbkfhUNRh3;U9&Z$g z<$gtB2*hjc5UYz-fo!7`iH!`fZzbw9tkG1Tb#q}{lS*>FS#gR+N&TZMiNt?~>0|_v zhmKn^nR)Y#NBWJVG*hq@s~I1VSikZ`8*v-ydIK8J_lzi*?H^zM$t+7VZW2UUUI+Q3 zTapZdoneBf%q=#`e2*CS);&6Uw{`dow!G`x+#s%7=(1a0V+Rwa-!8f}qC@j%{88DnC1qnrl1ZUwh7qinq3p(~x&~h*tF|`yc%drpi zBMZ-Y&=UpDK;meKzu`f-LJ-DL6OSz8ThJ5G)YHV?5O&v-X zM3yWeBH4tSL2%#YJ)ZhvDDr?shEjrYg9dn-6}@sNAqbYIE=mtrd3SF#uxPyDK`j!6 z{hcx0^1qd5b+~kvcAiA<+r2mQ@4tbuiP9e36xrK@aKdZ&1^S585J8#OX0+E%4}lU~ zz)z(dP0WxNsf1%e3hfX@p0wvAfQlQRrTbW&qnmub>C}GhsUc9#faP2A#oX?=^J|2= zi2uOff1*jtcpZ|ND}}C`l>UcEtqn_J2$R^JFc;wINeSIV_9h`N$AL1|=Lyea#Ju~! zUD!IbJDyU;jB*4o`H5(l+#lQ{&w2N(s_QRJc?<@N1`*KvGXL+H)^Jq zRs#9_`1w`9OPAy_yTCOnj3)jzuXY9V{yQa;(V4;FLHqezE`^RziY_56J%T(g(E}OJ zZ2hN8WlML4TwVZni2soUSaA9nDVFUlm$c6fwU8Y;*Lduh^wMe7-TLIkX8Y*TC)EQO zd!x4}D7WXPQRfFNLKfNok!yoDV-vN-!p;7Z{(JIj=lR9p6Wi-1V4pI4Xa6As{DcRT zudu}SXh9x%P^+#bA2xe-J96SPF-3-+X|ef^(`z$%WOMyzaK;WsN~;ocWMstZv;i{7 zVMW40DhdQu`3utMKvJ(4y&r<#-%hkF)>9zNXrg6^T?TUEObTdV*n_}^sFiY*Qw}nw z?5cnBv}&pl7(5u4-_#R4YWSG9>I)gu-Z=XdS*_{55L{-~l(OKvPKFWBys*$@tf?>G z>H2z%ZYvn`4f6~`xi7HK5c)BM3uK)hXAsV8)vG(hMAgE)Qo$IU6xM${Fd6(`$=N$Q zJ8PGqV1!f?6^!55o5s%A-_P16AAWYp5N_>jRW5d1TiMxNz*%H(DA-}=((eBDlg3}V z-G-T|u+Mff(Yb=_SkeXL&=AB3hv6}E7&zzj2+UzhfbWWV>EJ}TS$bW?=Qi_HF&FsIu^hv%6I9QCmr*46PxP^#pDCn3S$txqd@`IwZ>>x<*55@M300GKDjcgLI1j6fCc!eQ2i1}xG$?; zhAJqmSTmksyV79kl|jWLotX2O7>+26tbw1v^jQsY9_pmwOjYSeoh$#lXwu`zLM($C zJ~%3i6Ct-Zw+kl|TMP^%X+g&4*BnC@jE+AdTQ1=;7me)q57uR@?-~Aui4`y@*YyP? zpaTllB(nn63@_MgX3t^eaQ3BtyWHsXi{0}^!PoT0A!ZR;`eUkas1=qh#f7*CG@|{Q zPSuivbBx=YLxP^E<=nXn4I$Twwzh(ZmP3r0mO`pET$1KOsvN_r=&wLW<8ns?t0 z9zcS|evXqALc#}XYX`WTLVJUat?iw!z+Aqr@=>;54*?R*eK@~T^I;ha#e*A++hrGQ z;CY=pU_%OzSIg02DG_7G0i@zZ%1PtOZ8iS2b#S7z(-M)1%%#rtQE@L}QQ1?WAbpXY z#?p9$5}x@NVku|)G9b)yv=?wlaibG|ugt5%jbxXPr2V5tagowh0;cnEk|$=u5!JZm zkjiks0A~Wv?z)lC%erJabf$jKI7+8cOlI!(35OgqUCh2KkX(IrV|(QZP#V0DneRYA z^4>x4wvPgUz6i1L$5vD@0qoGf_9)P~0IN_;3rCO!cN{|f@MU+9!GmqtgEu(7N{}z8 zhkFS`fXRSLI6Pl}?8QW;tw&Ml6R-DBvS&R3{t{4q^(y_wm!zUdVn5DB-C||L>5Ins zszIjzeUJq|(BD+21~+@`Gd6D@;}{0Yx|<4qs85D3(KAtO?Z!};Pm0=jj&XO1pw)WH z+nZ00pihTytZGC9gAM~00Woo-9@Ep~UMz$b{GHy7s>R##8*i+$ew4^DOXGdw?FZ*2 z*HrA)Uxiv5x(b{IqfinnyjGiKaEVdOlXuTOZi;HnXOwwAFc{2Sw;yV~10cXRUNU9{ za_GohMrefSPBq@Yp147%Md*mlvP+x{ZX8MwRn3Z(fmC4oNDulkPPDRh|YnU`;&iZ8xeG3G>x`baqkscp`+Q1;k`xEjh zFI8xdBCdZKTbrRrEkDh`A(v3OO<>x9h1j_YZF;#?Ekqf34?`}qk+Qa^pA&?U8$?2R zMk|CE!*AhcWk$o}oY=Yo>hOLrP%n;@P3{Cq$-}C+;@{3rz`+X__n;x8vN?N2g=chS z=XLd4MkWUc$HZnN&(h$=RTQYhd&@-e3`jRARV`*`VmQb8&(`c`aE6uB67IIEcB47 z@bQ%s6m;n`qChPI+!r4Z%fePQ%qcm)y$y`+Y;@J+6O@2Ts%zv+@)u% z_S$OMHwgdw3(-;R<2v{QuJRa0;{Zc_AXF&p53fdU`TjkK^07$rQVJ&VZk^ z+?AVym>gyPai|g|1!g7&SdnFuPw@ID?o;<*HZ7@2vtdN;Ve}}TO)H_s`{|W)Lmf&=Tra&w8RUW4Q zaatp;g8sfi-*oGX6l{C3g#8&2RTz$+XGu=)93=P4{9){Xet#FUNH33v&ksvHa zpHF(8LG?TyY?R-AVobo4@;|S^q-ro9yrKh~t$9hfLSE@+^ZtJppofm>c82=;=~;b8 zn7ivAzo!I}4;{+|hOPKn1YseRi53(H)*yuFRsn50KQ-jtX!v_c#&Qe)vMEvhVArte z`3D2IQO3X>h=l^ZIn#v9+j{rHd>y?(A@b@?boA6hb+M*|W-N2kTlSQs?UFfd2E0cC zPnS611{TQlc&wxzg8_e$14;o)UjqICxNXVgkkUIdp`L75hjU9VIO`kLI;)!TBY_E~ z-+({9I8rGy25gFft{beZfs>SnC!Dl5e;&jvHvdptC^Du_fQ6qOpdm0q$jq{5U2WQ| zTYcVR6a~pzxe)Jryc4vg#jLh4LfWDd3&?E`gwVm7tyq4FXT=DqX(AFN4_kh@ zT$}Dezm58h>a`n{ZurgqgEIfd8RWa@YJ5L?e;4$~sqMBxA4R-`czyrd%uhf7B4an+ z`X+JD^i$3IqlKz6HMAE35FFX*19ENu4oAi?Cv+o17GaHtMNH|HqGqO8`LV)BaeL~a$^!eT zlhRNUX%MdabPHQICzCtQy&Fu+f)5GH-~wKXFVX$E_Ph5PVfK>0I)D691nK7u-A=*H zuf4h8Cr=v%Co}iSo&V;_;pN8`myg8F%#o@yhxnm7Wtt7XVe6-zj&{g{;#GUdQU=8O z(Nj0xKrzv9N7eut7x{_GLhxI6O2#`}eG&;ahyAsz6EP0I zd4$?tKI$`spj*i%C~)I7x#MQgBC_k8_1L_Uxx&gu^}vivWhr@NyZ{r7qlUiF2oPcQ z&7^UR9i@x8GVs1pz}NX&tl`G(a%nEbDZ@fcLw9ZaD=B%UtZh5KxmlRXmHSih%_@Qj zUjxY;jN=xIC*KxZ^c7k`KjJF%T!CC!c^rDd@1Mw9Y>C|u=9HHeJJy#KadgLRRFBFZT-lcLyv-eVyk@ z=A}gIp1~2))t7YJ=E_8lX0!cy>V1H4J3?6mL`M7i#FdtOszkKnV;nK(aEaZUF3Gz_(m#~T<5qviHjQ{{-Rs+YnWV6S_nIqD0v>7DFLa__Xg zMoe4QVqM9i;B;kn#x`HOJf}D&vZ@jrOL465`8kg+SFgnBQ%n#VDlbXh%LdAHml_VL zCMa;&@)rtBIF%Zls#Rb_7KhR*U)JUGl-=d#Uh7k0s2{|QLd%TmB%uUCyz_GT7f9};6OIGO)A zWO8{l#^7dYrQ?ekS_4NZh3Vf24Q_FXo`-nBOHfa7`TQxY#Ep_81~bRrp;Z$@hXk$U z(0VfSygm;rop`+djL`Lc8PHipaiP}xfEeU{*6O=8EIT9^(NEgcd2|8i2*LzGKg;z8 zFXU_#Z3qwD8ySpQ)8kB6@!E)TM&kN2_j^a23=`eXaoPxE9ZP4By6r|9HZu`5LlSl& zgP{V8rUap^Mk!9tUR(C@-H-SI&fHCw7Y~L|A%a|%Q(s_L$*D0=GG;mFNB=CSOn!On zvq^P)(p{X7fWgB2LvdiB!tygHjEJ?L>+Xgs{l%sQKJ$I!uvRc@5WCtByIO7VX5Bev z@2UBJs>*PK?c*4qkeJofeOt~@yM4)p?lWhDzh8(V{Pdc*Ne&Bp1 z82W2Op;TPRIzO~)a8Ppi#*Ys-a>;5>>rX#_UDvvKw*twtn zNjHB?ISdC>a1&(%8JEU~L8BH;MRPHl684y(s-yz$i8~q;@?^hM%S>aU&}s=45p^|0 z|6nYUIQ$vk{WbI{=stttnFx>Bi|6;WTH7LK7#6J-03-PHD9*UxVno`_?t=2gsL1T~ zr~5Iy`roCFG^Tq! zUbc)aQ66QUd^Qcn~VZ(QsB(O#G)qz#;pp_SIX?EE@}9;^94=sPw0WT<=o^a zaI!4`3Y|n22lSW-K6QYmirX)v4w%ECG?&emhJLyA3%HkWwlg@CvL-XHU&sPNPx0Bv zES=K=u-(h++@t=Tq9|7}Z5D?xo{jbUOLc=eKW7542KzpMSj z#&&XZ`!E0g`w5f%wd%AGHLM11m{D9`RGz3X+{SvMvn3m0nU%flo+pYSYW^)r@b{qS zjT{wcFNb4Nfasb3BTWa)KsFmZGev;g`PT0lzL35FPLKn-`B!)zK?Ln*9q@ui--g4> z$mXoE&H<@(k{}nLvPD9F`SeDKLs7I|};R71o^VUzcBH z>&e*6++1mq;j+niuoFV!^ywwyovKqy2d7E8H=f!7FSwi!PeKW9^Hjr3)zMs(CHZ<{T!GZUBr$&mX8 zhh&LfEK2L;uh$V?Z6GWD+${idY0ri_4ogY|QG-2m0>6;p#$m& zsEzo$ai;LZPBUkcDlvNLyc^1D#h#Uu-b&oCiMs-_$aTK%AV^)&$>o)B&zD%v3FR$i z!Aun&ZI$Yc@BJ?*j%Xq|wm$gElNY`qRP}9r*e{Xtz&*zXrhDN|=q#1+vNLjqW7GG= z2Ey5UdS33GZtZ=uiD+1`vi9=W7&B=&Ez-XW+1rdRD-QCs3 zo31*2cI#M0BrQA5$bCP1+tBN-s?FVM7W~k~3;L0~wheEPa!~V8^Hr<&KDrgsxqfd8 zJ*V-cEr(JC1lExdl2LwiovCH%H`pnBg3q$m**6hO)l=}|7^0Pc2aB;~OnuLQQ1~A(5xqd7`K$;!0dO&(S95Ihh5@EV z&U4NqtD1N`C~#$U&11EmTy!SpvgYPbv?>YtC=*+FDoJ3-${6cs-Z8NMKXeyFOiJE; z^Ul!w?50Kz`f2Le`r&+i@cFt2Tq`h_|L;KK56>SFF5rb!sw%cFGRwM<5{DIDvYU*D zzp-r}w?rdK?@=;YJI->b_vwer+Vh|)NoLuYLpD~#waK|O!~uf69e3Y9Q_i6f_+qP7K;%@(~V^~4jjJ?4RF~=kWlzR^#?51#6;7GtJuUol|`Z(bpo}v z#`X4|cjI_xC0PndaWyWoq-T-@4rO3Q9>Zo;cpjTdluRh1rTND~W0Etq@LLM)N|^;d zC<>Lt=RDCo`!(5CJRSoMuU$jvV-7IM-@V%h~k2MmB@`pm=qHRPrp#wo2hGAQJ2fRepj=L;K_PSD!jNja*1`OK0Hx|#aR6NC5*;5+nQ?W z>rlwd2SKJ7yX^T3gU~R2xQ;|?9y*TMM4aDx;8P2O%UnNy`tH4b%W8ObWBZ|j>lR5u_&SN;LNI+yad8S~v92byjViQ@AS5eVS-~_`l5;Y4TDqRkl zTm;OtnpuH6I3oD`WMjj+$Nh?>?lNTB~mN3xt`<6(xyxtKq9xMF%V&8Vi(P& zMgDyb!_3%q)+MfhnCsO6GSAxO2u^s=mvQFT0p`n4zsFDrL-lTo%>xF|0<5r zi=5jEkPvmMWv`z5xo9+d$Ll+%2S#Vw8kf#o9s~e~rIWQp1TDI}pH%kt@0_?; zvVkvV{9rtBVQ||)lQ@0fzXRc6sRy3ko96qlzQBda!BE{ZufqOK~csx7{ldLvbK0L zU_CCAIz@Ds7;`R@8al}of(e?JAGv;h;Bg5(!}G51EuEjf3MsvtMOaMtI^75rRh4EX z$3DHd`Q?6E-YmsZ8jJ2<_fJ8*U{tvy;^=v(SIPh6_p;v?!~S1*-3Xg`Ym-YhSOc&V zuO_3vd^RR_R`ELtp4w7(E@3RIU>qcQBV9|A?%@5b@qV}dfz_JRrKpy3wUzS$=I?P0 z6wePVvG#1&r*!C7oxvu!AZGJ%kIKP&zqsj*CPD< z10LQ+%$)*LXGiha!m~OtMF2_40uWgjO%WyuuiWS4SBvhxVB0-vFVK92trAwAmI-Q^ zd|eV|CEQsJ}e(=8LP%H7P+U zb2xND_`Hrtx|Gv${3yfd;2uS4n6@UA;!kux^_Uepx%sE09_(xhrb^$tav1pyEhg+Y zs;aovD1+s}y(G4JSZ{KpK{mCVA9`1EwE^I_OYl(i@zc0iz2dDK+ww&3Yquf9n|V=y zI&9n6n=#NNVAX`h(G{{yup`PDY~waYfAmuMu;v3RkleL6tqhTEseg4$zIy)4HUe4B zb<{w%?iCfI4N=F=9X+6)Gr?Mj3Qk?)w`02rL_!7uOs=(<)@xVwSETYl+yNuCAJ4UJ z;mTlTT_;~(MHP&hFo)a zNo(6+0U+aw@NKZTIQ|}Ie%g7;EjTK2(L1W(DD}*h&ARI`54yqHX}`fzsqr!NnL#=+ zA$+#OEH%wz!i?cOWkKdb+>y?EVdXW9FHwxm5!dm#}@I?5M6|;Ml23r@&iAt>4>WSgA61H_&V> zkk9+qGT4q(iG%ut^rcd)26M#w$YSUdrdb$Gzvd3P3tFn?@ z!#do;2?$g0-*Ayq#`sDq$2RQeVLq-V3njOuHw;)Dc@Nv!?Cx;!~ zd7F>9_s;LFb+yDAcY{+C6CJTt2Su!z=(Wy%Ab?-mA2%u8#8j3Tru^cPSvTa!eDK6oyEKLLTsLBA@=i$>J~L7 zdd@LdWYGyaZnP8*KlRzYAhVbryu9}uZtwSJ{uP?q=5QG=6=DPUp?8Ucgc{xvrcA#~ z|IGZef2QDsw0fCoF6aQUZ8vmu_faas2BwkuDY52G1;;w$mOIdptl@2)4T8MObalA# zdS3(S1Sbn|DAWU$=B;)EcR;6@6~FPMWXMk=EEL>vvEKciG;7$i;rZUd7Nmg1q-8>w z%)ORU2OQX7W1%C54?8;Xl_3zJ?*(_M+oFpTx?wwl;Rbw{ZKpvk%%p*{Ky<9n;@y73 zgEfp~>yx(~oh43>ptlYBjig$PRUlP&~^6Z9n4aHy2EqgN^{(AywCn9)ex z91#*g>Ex9jVl5~#OV;W_|Hv9S_bGuEca7lmdQIN*BgUrYue-SJej-LSbIRC-rYE;( z7F!CKDaxTAp!u?BMY9m#o)gy0IOoQIPD|NfhW>3U@cp&sgND(7kyNtF9)KY$O98(} zSv=KFd7<1+ZeZ8*J157%_?pq^pF4BUFbbC6P~w>{b@MCj3vxf+*_j0q05@y^{g;$! z#yC@1ip!@kY(|_<+TNEq@r8jRydwEjljCB$L-C=sXhBFFpPYa5roS*ey{?MFDcJJi zo@#ze3jKRnMq(kF$MWT4udsJ2-Vd_^;b0+wAH&<}nf|YiH{1oBlb@g4;QuD8nRUdE zwTGR&f$}HDwyU+*_y=3tYx~G#==?Mn*KUgMUMVl7O>`tpa0J7HMVRusEHv+k_>ncL z1J2F5bNksB+3JX>a5*WZ;0KyNfTUAl=>uU20xWz6(Rz6ERjR$0V?HSHk$)I(M8d)T zl4S8FOw@^#3vHhqWe-1le~z{e7ZiiNcB*<&7hy?!F}aK4-`uV~uDwcmvdRkSY~nAP zjVQ6P5Yjls%-g?2}Wt#s-FOCB{f1b2k1~Fj>{jklV5K7Mf!7^?RPNzv7S5 zJyqq*2`G*yrwTVN+%1{DTSfk78+RKxZ{=dOfv1{Zz13 z+mYj|+I!=W*<;^#p=>7brC}+ffQDuwp`)hv57!AK_XAnVKwM|;7aq4qsKYprG^6|L z^`!bEcXM0eZTacfY42pw#vo3(d)Ky!Z{|bA zrz+bS9U=zqSg`yMV^QL04sB(SIGo5KtGaSFip_=6PmMl0sY(IOR{v7_JTYO(Xe7c? z%~>|m=X?S9NnA2|m+!sJJJtuSS1H@c9`V%+@rP2E8yHpTenv$U?ROxj zU=eqky`~aNeG#|a>I~aSNj?UTmy68awh5iNT3D6JkjX)Vbru;d z*@baoWqR*?4+4OMj{P3|EB6OW>9WAx81D1GEWeUBJU5~)gjzgbqmMNEjcu%4B94do zITMay{1S-B39riWPsxvXMpV+T)iI=qCqZl(X9Tq~+@0^}?~RKeGmvLC-IQ#NoL+(K zV`RICu&B}g>85O=J|<(D@fsLtNsK@y4Y?+BT=7biaz^WB4aa8u&&~TVKPtbP4yPQc zeikRi#n0$(SWphC_{=Z7=bB8*cO{I+I+%{@)ODq3wx;&s@UPop?;x^2y@mYDJNNds z#A|xPE!XFM6Z~yU_jKZ?|Fi%Jb z>ZiQ->g3js=bl=#4(j4K17q`OcZycx2Vz^7d$p$tjg2f5lj8InAA{SxuNe}rS?N-^ z^M3Xu;4Kt)W{y24#kFY5KW;>goQ3y&T zLGqnF5|j~392?%{lq#+b+vinAB%jGrP|4?ii0bGh%|Bu-?IU;=x`;**Ah}u0S0s)# zMHmQ(Oa0Qwq4}Gw!v)O#*mWtHzbRUEP#R~VAgP> zxb|&i*Y0tK7vxtC=C|#DGJ`+gpmf&BJ>@WeR3Qc33F@@V?Gmiro1;c?s8{44A(SMd zKHSgL^>$0mow8sWmmC9f18RS4bMf$W5^H@Me-G=)02m_v|11EVc4ymkJZUqEt9@1xg8PV5Ov0zcF^7}zOc z0z5=B;N0d4XOW;&==6x+m>PM?`Y<;6fEzUgoj{Spx>^lM|0DMCD9#CLnDIvZUd83} z995y8pvLH;6R)^TGp|6!0$M<5a)dnWt~aT* zfxc)!4k(5noDMN-4ZHn9=5Aqr&eU_9k`M9HDb(5KQdyMA%TbV8g_x%r!MJO%$hC;* zIA+Fo2+H8>Chd~otBoTvViurbxQ2xXg6P#P>ubbK@k0APOIQgAaLPQi9z`oUQ1v8n z+l+-8Tl@I8z#6<3q>?{>mz9?UhXcu$eDm2c=7wtdFYTFN=RDg8iG zY5n`Hmc{zhA4h5OFPa`z>h6xZY~)2?5q9&=7zf&NSWF65XY1N9%Gdyr_3z#uZF*vUYtP=eiTnPUm|oTMYzbVT!=Iu|%uGWo!} zfF<4M?yQa~93*&kjfLomJ$KFUExs%3XX_6?0=MruKRA$KJ6mC?{vru`Fxl`SX0;~+ z&Z{F1?cgIerr(;O80?l(D;qjLlej@wFaf_+TF+~QoT!|)$JZY1EE60sb|ONm%x~Fp z%DhezBlBvDjGs>#9W}ZAVfsGjKQ7&%cbV2&=_0$KvJxnC4r{P%z78{VhhkUl4n`ek zj-fL@dqYnW-9PBVZEj?RH9&P>liZR?d1%9X-?3H6Qf>kL4ZPp+53V&wz$!%DtrHiHv9*~~ zE}`kYm2cjEUfnQmo@nkLwC1|Uv<|b5folxDpmo+fp6c%P%&abIjoD3<0g;Pvt zP9@fK<$wW@jBFH3kwwH(Mgv1Ht$#uTgT)D+G18l_AA0Re<}}9$(|Mcb-ZSyM^-sIo7S<74z#c!- zjV!>a&n4ajsla$z^4RcSEj(cwT{r+0D!^71t@bMp0NPB}TF_|7gXvci`Y{4parpre zU6YCKLPgXP7(<-3QrXwnwu8b9ECW9p285;^&@*QusVh4Q>nA@-$X!M=Th=bV!Y!YN zt8|&p2zTCYSr*4gw)pB3bO9%xFD!C98-hg+=c6|J&yy7`@Dn4zRA8VKR47IZ94AQ# ziw{r-s9Mm79j&klijW`_$Q^Rth*v5jxQE8Zkia2|6#d+vap(!`?S8~bmm4iKOW_;- z9X#HgwIw*Bw%3U9ZRUNa8}?OA9pt{q6k2?bh^pbXVJb&mc&-c`%yk4(HkiTXf@_W? zm~`dldnf2TXHuJE-B=;NC_W+?tD^XVB_V-!ydtj(74oMjOtnrWrzk^nWdOa1VuCDC z_yjQ_Z97=vS9_F(eOOU3CR-K*pS=jzhPDI@A~S`7v~vNf9_j~8D@@v9*6Xc~hJSzws^aq5jB7c-sxPXqQPk79fw<|9$oiifLmay1?i z#42-;YQBkN37RD~sJYkzFYxm|9a%7`2BIl@;~4Y+T@?yVItl)mj1S7`B7)vw+MS&I z;$Hu%9EfeKrE9bam+k8*|7}93`$|v5#?MshJ#72xgTMW1Rhj4}3b}OIJL;{y`lFC< z`Xi0qY|V>eFb)N&vzJ9+;Ox|%s`I2SGt{CpIL>$TW5(t^hl6rJdN!hrLbpV^++qV7 zAccn5z)8u6LnaX$_ia)c4R37n*K~&{0EUPbW{CTvDu#w2(J|NlK*rV8wca;Zle0)- z$b1n!qeO8S~bMCFZmjQ>V);hORN6c->6U=J7dVwwGubh;F*4n!nBHk z+ySA~N`90^G!TRwTa=6lxnn^okdTUwfH$QS!J$Ai{oFL6+(d6o+~oo+j@JpC3zUaj zGwky$2x4V7Y5z$s5MIT)BxP2oCdWOuyGO(lDfbdr`vKSu(~isLZx<(PBDDlsJa|`` z243?#QJ5`kMP@_oXrDZ-2D)qkXR2mW?|llt=YC^(k4bnI@P4hZJ3e_Kg3pezTsW8J z*qZ*Z10XW4HPLU#nA!9 zgL=CJbwvDzaH1mFTwo{RXY*akELh54-%TI)e z&!j0hvCS#Iy}f6xaIot*jeuh8k(&GS6R>`AhQaxkhO&1u+?VCFp31(*AL-}6n}uXg z++3{xMl5=0BYWR{gf5cB;+=AJ2-)3jhSq{ltgvi!ZdaYsXJSq&7e6*+CEq3c?h4MO zx@WXlm8!7l3GUVk4@?BWx{;&H&@c!XGCDBX;Ax(CszWG4(NEIoYGD<|)CBV+44#@JIYk;p7Oo1ZNhWB4LokKF9(vi|4oQ<8 z$8>g1n7)n?h-xv9Ti87DxMIxL?SH{lq|q<7Q~a0B2lvG{HI~bV>KBy*VcvWiVkush zEuVcKrShjDb|59Nfl_;Pok)OXXnDJsa;Q&U9zkLxZ;>?Lf*~2#{eIQcXVJ-S z3Hzh=h=EOzoTY3LdXKkm3lZUMzW*6jpZGCK9M`)@O* z_c1VCh+*<9j>gs-dGxWUF-uW0H&L#gBX7IK*5}!x)HyS)egWrR$lgOzGT%Maok!}TL-BS@e|F_-EPua>Mhjl_h+W=ST4Xqu)!jfqc0(6 zw?uo1TJMB>*D~YQ-l1{DA?77vp#0U~IC7H+4aVXeG&plD!wdz*DT7I?KW>f3|41K# z_Szq~WA-v#zB$0=PT&XNjySydbl|nZ{Ik1W+RL~_*K)lMsdo1AT>^%u) z&$*jtm~3u`z(ytheux;l)?>;lO|f*Qtm{cKMj|<``9343r&$jE@Mhz|$)UQDAME#r z{SmlOs>B>g+4HvEn@#)}Kui+cS1Nc%EBJmDyVp&vpvI)v*7xyb_x|PHW4fU0An<@; zI4v`ygc+;(zd{|SYEb(3@@d8|=lkQY@7uBON3rJXR*N1wDay-?cJ6~8qcd-RXY{#7 zVkOBTK3-*AHOMK3R7|Q6)e6ku<>GB8OPX#B(l@CMN;E%g?wb z!!=W!*DVe+fKV{2{UeP2TR~ffyuhEi`aMp!kBGd2KA_m|;NC{RFVpet>t|#1k2JHQ z3rigHa@M9RmjB4F9)74z#H*P(O)S1U3wX`*J}La!?qK^dA6}E9Ui+Zf${0om& z*60i>!d5UIu!A5vtrHpm>R2Wo$qqND9XYsXJz|Tshs(4Wz+6=ep1GVA&34yT@jFz_j{%kb4 zg`y7vP^_|D4L1U!r69B+J!CFRlQdX!6{h|zIAhk)S?D?z;dC++@tP_XoD= zrRNjbm&oNqDt}TaI#sk`GZh`>Y|C76Vd#u|@{hUYyfP8lqp01R=}G5^h6bwLy;-YM z<1_@^!emaR?XR1JmmqyQQb(&YW8d7F%T`J>@Ql)AXE&4Wx?L8&^GJ@k|Jf6Jlr}+# z&zmQzwNDk)p~*%{0UezhKw@PQ_xR+wQeT`)7^EsLBP!{P*37(WlF0ThqK=6Zipsl) zaRP17e&=a`)(gk{(5CF0f1-VaR!f;$B~R*x1cYwe0eP&h8U+_qql=>{*XZmWoBm!{%A? z1J&ztY8Lob42@q^C*6e^=^-Q{bq6?{t$H5uJ(Y%=0cX;{S@%;Canb8tqdPt6GN z%tz>hrJKyax|dP{MOAgR!`+F7@7uCpw%=Q=->>X!xtY_?5HqFwP3BgVQ;ZamM=%aK z#Mjzv0CTuiM%s(~`Gm`pfiC{u)$M;EocH(0P%A6idyIA-pFcK)o~YGL$8z6~bFXXP z7iZAPrB^9;HsAiavEdMC{SjRMwL>Em04c|N(h0$<){?c$dnoVQD34df9|%Rkivkh} z<|iHWlJ5KQQjeojf&(vGAHF>oFFmo*QwmGV%ki=*T9_Id_4Vxt&OPHJZ@x#Qr%b2F z%SqBUs%nPw8~~Fo4bSa_!Sw^T=jqQFcjYm zxKwIVe`eGv%9Q{x(p#%KC{CH1NYt1$c|?E3muBxSQ0isW&P959dGO;p%grZjdNt)M zo}yTwH&#WZ38R4(WZ}-Q(|ij(QvAFCLuq7k6HFx2S+K zVBB4o&_01DvWg59vmu}etB8>XrX0~45I0^>kf)JR&%#ZMfZF6nlVMx?N4;v9F^(lk zpu{M*4O?1t7#815`{tBl^U|%}DC?Vd)E{@z0%d~)4%%`y@ec8-WWulKrX$)YG9=RB z$RzsnGTifH!RY+Fm~BV(^Jw+v7MJ0rESS~Sw2MGm*aef&J2tV9LXMjI>B3Bowd#cK zd$dF&@uhodF>pL%A(<6rkYhHn_ja!8AF&hVn_s1ZBfk&%PrJWFWV@6QC<{3!(-FqA z<9?gMbFAtUKWP#l7f!+}=Vzk7>Je#cuj;_&#z(cFw(uzxWdys$Qh-d;8qX<-o{(z4 zBY-;hd!rJJ=SKPP6&B)Ao;1an;+%`aH^8>~nRa`9BG{%mH`V+X zG7?ry9vr+1Rp$f5P|%rzHv2-r|=z{f4JDW%>dOx|+`q9C!o(oj8z$ za>4uaWY7cSf&g)8RPLfCxja4b@cWYWE&j~*W&HVyP+KmY8*29rpIUJL$!`L6aM?QS z{W_sMgw_H{lzZ_cuaKrtrzt$Fnu*%Nh|wMwX><^Zq+#DZl?l_}afyA7oJYilC8ZH2 zX(pei{RlIZhA9IEx^61zQwEX_@`jR&!lZ>+3UnloaynP^%Lq$}9m01>cl|$_zA~t- zw(S-zQrxX*aHqISaJS;_-s0|1T=U@WPSN7-S}0C&FYXR!_nq_oVJ1UJcEZek?R71S zawm!)nmQ8^TRMCiYsmuPC&1~aebW>Ua!X7+6XTZ1DJy@b8mc#?gd5B#qQ@~~D7qTa zruqgVMGOZ8V-g)xvIJuju~Iv-xH-o5Fenod$JDBHHFSvbyCy{Z>PH#`E*~acMyAm; z&6V61BZ#|sZU`0)Um8wm$V^pydo+?=qz`NBIIR@%!*W%=n>ZDx5~5o9Xl9H_<~I($ z*gDt`XNGFX!B=y#As55buEXC*HYU6p3q`96&8?j9Jd%fRvyB-xl)C+y*UcV%yZinK z{cQLCwt8C7*Q?A44|0L;g+pg9pX8<4OPqFvp6yox zvYuc6hIeH{w|j@MXtzcapC;$NfVzPj;K^a(J9c-E;f{;2`>WTD_t%cwYNtJTR!?Y$ z)!F0QvWh6f+Mf^^Amqwx9pGj6_i2FY*dtfDoC6KbFm@(C|Km0(IoXVoIXA`Moc8wi z7~;kp=_)wzLj-_1d1+}0cm#+X99FLq<9$OnUM4qo<&B=OfXBZi&@UxKZY2J_pM`@% zY+DV`q_%j}uS|oT1nT7*{>p3a!|(oby!&MwP*W+t-zYZ# zZ5AmOK!K1wcR!!BDo%_P&=36PCZeSocAwMK#8vW}o&rv3-32|BMW1~7x|sd3!0%(o zRf$bkIX80UTg5QXa}zv|ELP*fq8AZhz?|}M=Po?F-T%lSpXb1lUf0?r`K-t$)s;e# z5^Yk{pn$umNe@q^Dkswaeao{-_%oj2r|wJQ?q0q1t8S+B&R755W5auX!{?Pnj?Br2 z6DyH%qxV}Q)@XwDi*TNcAavhAvX@@6q8dA;9KqHb_gp0!L<+j7ZGNYugKKR~M$MQ% zl1zsSb89qg$ox{Zr(M#^bz0&x)E%MJBjIHkagoGo5k&dqVC9|=6*ymnK3O2K=~xw0 z!P>g;co)^|fXpgH`Y&{19Q0C<)M8P|;H<~jUVc2!d}vq#aTE+AYA z3w71r-#?fFDhxwVkro-JD#OUNb{ZuK>zLI*vOkv91+_hOX`Q{waJcgVM%H%kohHr< z#$1GI`|v>Q#mbCSkOx{he1wu?!+Z`+o$LCDP|Tv|5r%Goa zyS8neG#3Go@_>#-$l3anwC--^WJ$+%tUKa zYtntP>Q}08_gIEcE?s^}4o!;147xmKJwz3nAQtMnquI=)7UNEM71Ded3h^5v!~wbs zRmw0?#N`Fl%uM z%JTRzS`%RPH-l>ro|$|$F|@8T{#l;a?qya- z6Wx=2L+{@uZLo-P_Nj-jNdrak~%5@>!S? zGXjb6_i=bpi-pDsF$(<97!0hUlwBxf=J16-;uZTCA$x$!2oEwD`FZn3p@f{V&0w_t z3iE2&<2MK^`1Jy-dC-DrFCFjmhl1@ugBv!hpG*1ODeO(y!ga4?ghu>%YCihx_z@EF zG9=gnlnfE+h3N|llWCY#`dbNfMCzDd7%DrQ;hfmSFp7%iQI&MCN)sr=!q8;UKSKGQ zS=4lhfn_6rIzA;S@QwWbMT0jQK6JWN8vKW3R72;#dS2Eyl$QS4A4e-6lHQqQyN$=V z1up5UGG>g(I8GeuFhT6@V>kownO^Mvpad8sj@TCCx_mg3Uv1JF$i$_b`I6Z7673mq0X$yh;R zO@WV2{%Ic$;c+9$>T^lI!%F=?r2ucY6p}+YgivV#OcF+t&`Obci-(^6UFSG^0BO+h z^Pa7DN@80SDNWCK{K3XQicmf0)~-3MB~o{t0rAFOyL&ih<6r^*r_01-PivvClau>; zp{S_c=~WB-X4`{q86D}H?vIdI_QgFtbiHFPMVC*!ojvkj2z!UpirWfZ9FK%LN2+U0 z`M--CP~Q6!Kn(ti>Cz;9w|wpTd+9sp=2_Eoq$>P_=W51}``}$yUQA?hC!Tt*HeL^= zn*wgEzG&l|m9Ruol`UJz>-~9Sx_$kY#j+tP;B9(CF2w>cpkL;r`$dpF*OBe?B9MXY z)~KOYQUHGv+&6s7Ew3C#Ltn-J(*nQ(t#KFYpGnXJoXVIa=-sky?*D?=2vAylA35ac zW7z460ZmZ>T?&x75yjJW8T<16{o?&1W3eMD_aQRZ*v~Ipn#>P^9`MlLaq8ey=%5Fj z%%jEfsVT|PO)0>VsG+k{Q56T+>vMB+(~Udxd7*v?Dc(H;MiVE|<-Y^Hx|(_YWuM38 z?;Jfq3Z*1Z3=MsdO-cYE0pcaV887&AAwzH)ND?`?N&lQB;t|IxatR0I7>|vEbE~)X@wmp2sY<1(2wRFll1uj9 zj}nEj6uMP0x_vrKNlskRW5I#n}3BvMkMQ}5u&wLt`FiI6j$g;)NK)K~PXWo&(gsjIYS6l$Y^60>@Ougw$_O^%Xq<{>-? z7`VTvng}BmMd7Qic$e82b@d^Q&Zxi4yq#qtFW?++tKRR=6Sr z`p-*yOIG5334xFKu(SVK#0frJq^Atl!eh;gMGnhPK;o!dsw!Gw{_lr&vJjpW*7w#&)})|RasUF zqME^q|E7!R+nEohKiePuvxEzRQVN1((BW`cgNU#>IbkCE7(`fcR7U9NgL{8h6H76w z6=I@65>IHfY|h;@D&#*{Im|$3P-5)cy8#uX9EC?(3a4;;oa}Vv8H~nH4XXg~@fZ79 z&f%W(H4^8pl(0wd^5DN!0b%DaMiN;Y0on6nDk&{YeKHi517-Xe+*6D4rAXpCl5z83eJ!lcDafZ;5Uyn67SgeAo zp4%iCDB6FE297=)Ca?VX;{?V`^&e(Hge)S~ep7?SRZ4N$xVFkAacMJISnY3Qrj?>4 zjH5}*b~yVjWavNr)48~{r}%<1*JjEkPMKVMx578co4e3TXzF89k%&_*^s>G@`yeSe zYzBr{Ui<=#!-5A_dnt!48LjSskoN>3(8e=nwshSRrBLAyM)7oFXEDRzZjoM>=ELR1 zZ>^Zx%7{UIgeoD$swzzL3p(9`&$>uUOCG{u<*GSosc#NBH;`H`jo|fFCT|dyx~KoD z&0d&m4OWQgx=#C|k#|>D02-+DOf)_aUL10Z*#k9#`RUK%I@kKQBPx0;Kh!ehQP@x` z5$IFWy&xGHlUXi-PQEvglsSwEij9d1t(z3)7A$^hY8wb3edTwDz(##*4q4pG&Jz03 zTc|kzSX}~J!WbDdJ@0% z?)4jXN$&;bPCgi9x!~Fx3f-I7oa$x2fAM-F_Tt%4aC~A+-#{Y^Sn7Xh<#>ueSgdvY zgSX@HUwBuGjqvM{@^#LA$9Ju+tN&g`b6=2bGMvAD4OENDeN4~oC6LHD7$8_)U$=B| zNd^$gt+za@j2X(#Wg0+B(`;zf8d~s@%r-N-ou(_$h-!&-mHkDe0EUw1)<+{5P0cyC z*n3ht=8#_F(Qx05=k?)#VC!wK`(?vxhj?Qo5}P(9@9OT3+s@9;^PGM>si~=nx{zu5 z+D^@49q9WKBn5srIG|F%0R_tA?j9$*j! zI7lqJew%0Fv(bb2oril4eonr$qWG|L+hQLcXunrlVR zt_D#2@ZUw&s-}+n&hug>I|x?CncK!Fg2+QJwej-^Rs7ex6P@*&5}uj!`$wnTN0j$X zf$n7GfTwPDk~^=*@$N8>j-7y=wR8Xb`UC|2<^-V>Ab6Swn*|<}*veFN((%_fOG}y( z)0NcEgr)t&Vi++_b(SIiKA4yV3L^}{tl_okb)0fYXF~7ht zKj0&V3l4M2IX2I;I7thwzh(rjP*@cFs_|RSA=QkvFAU2^?dq>eL9qtg>j;RS+Ny&=yy(K)_R-wa z#WHl8njy%a*ixH>>Mc=O1(4)fg__QuG~grAZ0S#rf`{n8&k=?8VVC(yID8_7W*9Du zF;>s|1)eAD`HQjN`mNR6Z2XUlrr@NEb}*#MA*)wWSIQZ`$U@nm$hOoPE}Ue8=*dx( z&!w?n#zME?B<(Ll@MXq;LGmxxzS*=7Rz33ZxTL|o(K3{{a>1NYP`vnU;Lc;LJBmQD zLPECmmb|`rsi|+)r#$tDQ$2pCeP^%GjA(>a9y(=F<+X)Tv`;;G5P;>E1<$Sh zVY`<`S(}tPz!zq1yC7n>LWs)a|KfH?utZ5JLb5)ZP_NGQVD)|yu8oz%0z(dEJkTdQO=FW02~(~UV_*s>kgnYv{c~xiCKkVbzTbrpl74jT zjQ`~|^D#CJsPD88Xwut)MyE7(3yHwQlswoY=I0L3p9;C|t1fP=8}bafLwc>)Twj)z zYKSVG{kW?$^%Jc-1YyvorbYU3cBCO$zr>#HzlkJ2B0@yoa7!6}`B9Cr3FSm0`!%(yy(QyOpA6LoX-01u z>J-0D6}-#(hJK7dKw+ldIIb!z8TP2lx1q(npd(fqN?s@y8iv%HjC_FgtvYOR)fa3gdY@FJmd3xdm`$-uyyN^NA9##m|S`wT8eakVK^XFAW6h`~q z^j~&4pHMt7x&!uQ;1Tr=@?h01c$r>sLn< zHZ7SY>&d0jpMbt5G`SC%h{Txcif4N$d{@RUT~W@ z6u7gG8Tbe-CvkGO#635nt@_(o{d=mJrFZkNnf?J;|`q3r%k8;@nv_y6U*FYVk{W>t1(<5SBz8*oYM zr1)NhkePdUOw_)v)UpHQ*ra8auwTaO>nk ziH$|A(QobBi5Hpj*?2bm$3bI@Z%(9te%T^>qv$k@7hJTT5+Xfr+s{7tr6qeDkzU%^ zpdA_^UcdO@e`gioPEWj6_o-3|<|otRywR&BHxG~3@67c^^D9Sthi^xH@BrIklkvfh z`CvNt;Gd-Eu|eedGnC=`)8h4%M^`cesV5W#+^c^sPxs@b@BZi9t&?S!-PU~odhM3_ z|1Et0E@O)tNu+~I zuaiX{ll5Dj!#uj5*95OdsCW-Nm&XlKfA+S*e zX{^B*J59ni8R4Uz3I>bT)$~y@^;N0KJ`FI4WW%vvAUkzW^HDR_1LyB==d6n{=)OSN zPd0C_J^x;+|52*v&5ZQpukXSW0_&G(vrJ}!ME^sPz^9|wxr8vur?^9Xln)AfA1Y8e z^sHL%WMAq=PxrR;#|KoEQFFaX)PBA()~dnq^u$=$qSnD5A22Y0Fg*$e*uE`;;raN+!F=Y7O?J%%hg81(bVk+=91+wBHXp?`AS#;zmrJxNNI;;`%sX=JvLE6|Il5(-^ zg!yxHiIm_TglH9GjnpbT{Schs&E99FeXYnqEFvKDPYgmz1|O-+rkW?y3-619$c#xj z8x`(N*D{xLj1||GuSf((t@Xi*-fS{Ws1J9Paj150b@JzovNH>g)uY*CyDy)x)S3E1 zJ@!NmxBbocO;DdUk(($A*0yYi<}d7%c=zSQTB>5&Cqly@T1jw7qmUX*o96=cnb zqkLs3KbI}YgbdJ0XmZIUW0{jjM3qr};Wcd}KNwVGFLuSGhSNzg&MvmhELHZ8Lg&eq zjD|DP3f&I8bw=glvQEWXB}wNSb4_j2GL?w_mSoZ(#eY=CwQMS%T~xua+qPN2KWxud ze55DGLp6gX-9rn#ssYkL_)5)h)$!Sq?mLcb?k`^Rwb*gRM3ZdlBDO1^rK+P2hL92^ zOY2@iE9hSIIe)*FjnQb-l&QI!X@f!(R8C zCY3`*Uy8U(jjDl8L_B_qW6C-f;0g-_|O#yA>8GfD1oFl)A z-z_^Xj#bRMK!X>2@JN?SymQK% zYL5`%mPK4Pn8&PA`B={*-FFq-nS2y}DUC{g$TDKv( zmWlm8&vP03Tm?MD8PiHUTSXCM2pZyQLTS<=QzTv^_b(m^{ofe>l{VwHv9iEny_^N(9rTG(TZB zZy~0QQS+H}@FocNYmwOxLE}g38&>z!0?)7hhVeIbzU@8BezML1m8a()8#mDIvLDe~ zQcpNILrc(jjzl+)T={A5-3Zij4qX15|Ca&`%)d9wUC_c98rkrGjj{Ezhn6tYz`k(H2F=}H78kVO}Ms}xv+O8D>Hcpu~KX)dP zA@VXuZA0fywjDS6b)$nWUyScJ_H2H>52Y`@zikJtocEF*{6s$Yz$04Sf!2z2Ge|z* z)6}FW290xAHV`fvczja!p51A^==*rE-tO_|8v?LRX8|BoTg`HJfJpyVg3)u6k=b;P zknd%*(QXLY3%P94gKOk>-g_V+;`Z$}~HSk^dhQj@HWpG~0NQg|3ALHcVa)*S^IjOSNpR3c*iDlUL zeybl~s;&gBEG*!wxuyf&t_kCZJMNllsfR}XO)tleOR27xJyxEH?6&51Pa;|fyxLI>oiQ|sydyXsI3-`h%~z1Q=1 zsCNKt3bOhg$pfhbfX1yHk;3zF+-Qnc_>$i6wt`VdTYIyR?3Iqy|MGnb_&vJ5_fc_t z6q=8v+Y(yzmFvlR1Hy)q%G#3AqNA|(owraulZ2h3PRjLZ#h7WeL(*4)y5Cyw_ybzq zPnuB$ro1OE%ND8ZM6udNdQ^()HC<1(P*1NEP{VPg7B)bs@f3e_?)ziz4)B)Nl~*cL zLVmIARaI39pi#8LXFrUClz7?!B)dM-5DQBju2_%>HB+adm@D3CtluBGEGVNh`6|; zKSa!^Fvm~qoZL~030fj5Vu#a7WQeR`EVF|+#`W6(H%OmQ83w}X8DZX5FQhfa>gV(Z zVqu9SIF4NgXQ#=pLks0SE^13_Xk{i%*Q}Ov6>ow}ZN#;a=d@4el8__Sf^9m(HDOKj zMH&|KQar#a38Dx z7u@TNP6i7rV2Xn$dz@tqtF#Eo&s(5g_cTR8+)`CD(U8OQIrJ9Aa?kheg`syVTcT6S zs}N0J0KLL1I1N~)eZAhzP874$^d=@yDiP>R68@8#gD!sLE;@tfpzFAZxki%Y-&&fL z6<3I0N7%xc#frqCArAvD7j-VQoidVw*WPX?PT6%WTX4{-Md6fhNYAYX+QQ+k(oDp| z2QU&mea!|jDG@_(kTxkiLlI>#*<~6h*a{M3rWA6^{|r0@-)=j0akK}uu*jCu@9css zRT2cgyFxR9`poHYzi3L-G@i6o+T3<3{i&{Yie<13=@Ax478kD&bKtLXiL z7fDM6#WdjZRg@A(NxN1|drxSqJzSO#OP8A7cpK}g;@?C3Dbr)LwB;nK>?@K zW)_t!R@^6np|{uP%XOElU0F0zK^dJCh(#m>aONF64xt6Ij5{mQH7+Ds5Ki#{oYDRP z%ml7c7zRj|Lo1efJc(2BV64$V&%sL6V|WpIYL##*8{r#*wv!dQ$3e~kpPRw7*wty( z^J&$(BUv`lsUQ0d*_qIv+qzTo>vTW6XP?#St)RQ^?En0X?zhtY9w!7}Lpqha=U-o| zaZtL{cX~X=e?IFChFm?I^1t83xlRkwdfqkUDrS^a)z*H_oa8;oa?v(2vNACV0@}m? zj|r*aU41G=vALaH^Z`(f?fZIcbns8J04Om4jm6a!hbHd7aiNrR5HoBhRfzfV<3~_r zn!Mt@w~*o6RVwh3GQV*SNPwWO&ty-(zIy_|bHJP81ysAO*!-#zdwr5NEK~w9uw_$JziOXj25F@4{|s@i z@^?-_UtksDz=Sa~i%S+jQ2W`WD51^4Wr2&>8oxka3WIy)BVmKDP-WTaI^bCCqKasY z6UDg5s{&=6(VH@{5Q3RRGM(L%sJ0Lb)?-f(P_)pTYg!X%SFH+4f-k!YeY+kID)v~} zWobN9^UdRR(h{t~F?e)F;6nJx3x>QTt3gTv1<0G`$GN&Z2di?v!X1s@L~*cB8uR4B z%Vgu%q7M?oEaY+%b6S$4E%9Bp)+O{I1|u^MZf}jg_#UHrhqQ#9_Mut(F|*LeB!g*0 z)!{J(B`Yi9mT1ZU!Kq@)euW9H`r6m@T70=2TTmc}oCP5e5Pifca7;>A!8VuN7Lwx2 zsvvH)!$jmrf>)*kH3e(f6v^lPor(5Y`YkZj z;cZ?&%%nibWT9cJKy9fok5WKW$q*4WhU2LjT*hvgtQCS6(X3b(=&EhAx?{I&Qhn2K zvKwcnj+PH2qZJf0;f=@0{eyx7SKZP?JOjCg_05QdKq!0`V*eK#Vqbt255c@eT#fS7 zQLn@zCNbQH`&90i$MOk+7u*9vW~DUrvSshLjn+&l6YOJrx|#7W6}6^y-=?7bAlXxj z+bd(MYGNTN!yp(%z-TU0hOIc40j8&8?);^V=y_D87`Z4}NU(+7!Nv<@T;$L(h&K{Y zsH!Hmk;>MI3V*88BFigd z#J{mK30i(|ak}_2woh*T)=VF88yfTCsJZ2cURWvXEzgh|!bev}7RFoc1E@~_jGagl zp?g3P6-SYOS|QHy+VleL!3;m?`Cgt8N316<@Ev4GoNViJuYHh?7U0c_U!GX}rkjvY z=pBL-tTuna7X1_aYjP>jS@Qq10Q?Mc7g*6n*2U$?7^>_Tsv2q>O6m}$BPybVj+GEK zTtm2mtRUCGQiIn(YbHIMxCz7<92qKEIFNYaD5PsWWX(B^(~O2m)h9R{0}km!hv-M7 z8A?eg@b4*cRmpKA4-^3nNQhhT5>(S5P=7JT#St&2#FkIPj2+4|5o1oojHoh`UjS+$ zsU%_eB4Z-PodOEQj3A<*#W?-btsM&Y$p(204$g!fT7m5_?<@PDbfmPHj4^jX>C@6! zeV)`VaeFIUC&W)r85~N;6ZZP>#_+Rs+UyQ7Zh`tJDCUsaId6%Hnvx)5QdetL(wrp! zlrj&g-WKXX8V;vih8~gERN+z_HXI7hB5~$tB^ap)W7d7G`I_lNtBT zGP|YrayLH?72S%MelN>r)uB6^aJ5cD;Fq%iMvLFe3L2ez{jb$tm14lGKFgWipe_(> zFnl5O8@uH>05PbdVt?aQLq|aV7n(kE6pYaqFry0>tBF`?FvC zv|!2Sjc5O4m5oSg8dAux(_;D7I^_KJ*6oWf>q=blN1)x3_vFCe;?eteTuuY;JBYJC>s~|dE7QL@V3RQg9f@Y#wHf?z2>^v2>t3|LFm}2SoR<9!88vrieK)1g zbYK4S2LP2oXYr268FRWoc3 z28?eYM#5=R$9w4D{q^!s*}La*@5zRe1PZXU4kwZ~J!qYWiJP8tT@ou9defd9E3v>U zqT7hRxV7q_FqM91I|RX*Y|YP2FTf82JsarNa&@Kw7Mg>Dk_%t7fE$yS0p%CC*jhE5l+5iwylN)Y2(b%B)wm)G#myHZLFWZct^I6IM10BnF2(8s*Qt zkyNNm?af&wdl;g%NLl4H*lxz4H^15hX?=EOHB+l`wtIz-gV3s)k`=a~cupyk^*{cW zPx#_2tyy3tq1KS=_v$xdifOVrb+u9coQX3?1e?8GB{mo;vlCX)cT`6g6{rb?x%1du z)qUkEPh}RRZVc)feUF$qAg37Pf20uu-`L^RIc$9yXe_4*udl)EC*lDOD0n_#b(^#F~z$7I! zQ1hhCRnD!b7Q;JgVAe$>NN}Ql)`3$?5YK*G?iJz9Fw#MOI?sld1$RNmFHls(NG;>oYMQW*nte23Kp8I%=}EjwF%yh;*7?GA;cW7rBHj z3Q>>@&X_a=lh-ID646GCKeQ@w1+$3C8=i8*t6()U+mjbb*q9@ef?)FS1*Qcg8RA*(~P1KO`ar!(|o%#F9S^~hQT?gR}Vb_#zCw^tdY_iOj?-? zlNSkQ=kvE2(sF#{I4Tz|KWkvqw*1xtp8c(Gi{~*)PYqoQqpD-6kRU~6J9#?D(*gvL z?)KCZE#?`0t$KH}C1b1qzDRUnq0TwCF_3|UB*Pk^wpm4UD8;hQDBrJ8rK*Yzkp#oL zHM}uc$iiu`q3(diQDB(+^!r-VL%_#+>($wrb$UL00o|%!e@qIh?C(nEf*9#bsVN&Y z+$0r1+}y3GPOzF~o?rMP-Ef6j9r zMJN$h+|H=rUZhm|^2K*n73}A|pfC*zyMn<5mjuBHBLqvB#xGOQocH(ZXcz6+0(IEv zcW>RSA1*vh^`E}< zM$=vZy5G~s`8`&3?Joam@eX1(r$n^nfd7oo+UpyzpIU!@x2t>o302i}@5SsPBPZ}JS9>VrQB70xdg`pRbn&>ZLvZ(Q)d_H9;^E^1 zhp)LHsmtB6RYO~wTnwfeO28FuK;J)ykn?XvBQd#=YY5Z$NIi-jGp$mV=Lh$hL05SW|uG{JtK;|xF^w5WYbngQ+oPOoq-5pH^o(G_|gT&t zs&SlBrEF6{(uN;D*t+SnTw?T~9_Gr`1&?HvO@W*K6lw}M01pAr+}Y1`8uC$2v9Nc* zz3~-)B^rZib_aNW!RgFPabqxTE0Jbk+%IhF|`0*fjTE{AT zQ0V?of0y4gn{1!Cpe1)^)3xNSwNXxhvPf0!W3qjeW=UOM3MK`W6di;I%qTnO7(+Kx z7yK*Y*lVk9U7~6f;zUhLjVURL9oF+vqDYopB5PbE8jtP^bVs0?g=fA>U=*sE_I5_m zXB8ZE-w5;1VQDcx*u}yu)TU_EVZ_2e2BH%r7D$F8XQ)UZCLCvpCZjaX@orrd*mm5K z^h98&nI7&GQo^Bk$+}}1z^Z*vR!JdeC~_?;n+Z&aDz6ozk1;5r6O`U%KAc%BSLieC zLYN6z@58P;&OG!V!}K7Q8HLXj85Q%OK)B_zAEEMXGpb*I|4_$9SBS*0nLP|28xcOy zydF)tt)WhiBS}uKitb~cU_WIG7nN>c#fI?`u!D}FvD+e|(9F0aJ){gmS02!y?gW{j zKkJa5?}?;}jO*y(=PwOLJrf!Fg|tUy5-d{VQh)xGM$ISrqm2AWCk!!zpPv$IPYRBL z{w9r%b7j9sj4IgHoWM-{d(A=2nQ&NJ%w!5@r=GsIC zudIWejNtII$L1A14T2G$ec6mygVu?amK%!}(;G>>QhE$`>sF1jDpQVeQb|?Yjwkfk zPeWhb!VXK7{Shch-AxP8_MuE&A0$!*pN^q)z8@IoJrxTLBRmJPN$L;vmw9M-n4FYx zhr^@`PFEqBXIY zCa1HJ8j@>FS=z5_`d;a*=<3kFN+$zKg1i4oLT(x`RfAO7K4P0v{=hAZh1cJc#iwlG zE#$@(+Bkr@_pCzAf=JVE7pcZr_bOxVbp*m^z!Z{yQbUA5<1>BHL?j#y=Zk(d$V$UG zDdrRx`y|Ib&b2_x_~WO^@P|_*ezgI5c6DvCZ+&Likufl=s8YS0MuiHPWi-O0^~gV#JQ9RD2`<7{-Io%q(tc~lh@q>ep9Rk*1YR#y z^eiKnt7TPu8*5(W9yC;>SUM^o!o^{r>(Jn}C|3-c$IUeP6kWt=w)-nN{zDpNA*sSL zos#MZlG_*KCwkcwbuePhKqB_s&wJOz7D%r>AtAM9n|LB#i*+QXT5eJc2_}l}2V*G} zGgFR!TX@G-=m1Gr!Lg;FKgbagcS6-1STp@8(4TO18?ROn9S>J!G%&P# zGU(X@5$XA5f={9b$cJ!D$tXQF$;(9p6KYiL^AlUpI8=@T)p7rGAU*AzlX3Q*k9ga) z&uP1ezKJ4XZ~0!Ul`GBU^~J}?>MOLiCWo9$^IYJOb(p{$vuEZ`lLYPN=Se0{FcW4y zxILnt9xmiRBttlyB$3UJ4nngo7eRH2!J`>PM zscUZL9`@q@@~w1XrOt8M9ND8N=S;iVXUY9wzq6Ds>d~LSc=1%Yb795j5y!*f=POSP zJIaR;ALxls(AN_?$A+ag-nD)XsZMY1fzR0wy)g)I{>dN{z=;Gx($t)!zxc=oz z&kZ6wZnZvZFX4Y`QVnt7<>lo`gnb_jUA^h4J=Watfyamxx?k~!b}nC}vJ`0OiuX@H z18j=Ee%9ysc4AgptXa-M-F^H0Gm`tWweg`L*D34c3ZXAwzOa=%`rrF}`tirB`HLo3 zt@fi>y7|;x#)b}x5ZlFbwead?j$Z_N4YQd@=b{r{o$FfHmI`sgWmdgJr76DXM>p95ymF4RcA42Of9(|^Bn7*3Lp(f)5p|c**W#SE2%!#5h{)jNGD$>m z9z6RV3DYt2%}g)38&$V{3lifKh{IfAl7XdV;Ybm?5T^E0i6TqXE2xr!K}-e921|pI zh|Gw=9+7T_#BR9A9%~)-TKfAwZwCt4DNr;4HCYNF5*f>cL*LrG!cVR6nXBF@eZF$e z{l7u`NJSTPkAVQ%NrXRyP81~<+RvUWuFB%^R0@miQkZ^YU4QF}IH(ZEZJVISk(Bsd z8%28?>#%7xB zI#cF%nQhDFrEZ@3qSU@fF^B-N~UM9}X$cCzU#?U|N>~>4jkziX?F>?7>=Qilt>XIv5 zlO_Gte`^U(>-=Df23VX7Z7=cDIx0!sI9_c71*ZI!_QC9Vp1S0WEqk7KSt0EI2)mNr zKN1h}tDpbi%qu~x(A>4QD<}eaOU}WRg1Av3vb`AwTM?bv^P@-|?vQ>$;$vcaQUft4 z%8xCoVM}}EZeh`+^W;vb<6rDFXv$w=UV5Mom?Fn7bybFNt7;;J$vbKBN$H`}F^h}i zKKnAMeEX%%65-BA0Rs;DMh_lk%1%Tc6|YNmwPdr1)8bNt3%xpoVEZ)9{ZpaaTnn_f<0R6-NOJ6y%(EuUe~g(A-MKX=3X_;b@xPlMs55Qx8KL)rMl}xxY$r2Ik&k8#lH=vzXk4BQ8y6YtYI<1>OQ4e0;3`i*q||H#|3^7GBd79ANb${6POkcE)R*vf)$d2<-z{X2 z`a;SuTBMf4hPrtW!{7=oz^cD5^r#K#B1$e_v8ifz(LVGX&zQJE{kk zr3E7Mj+!?mxZu&Nf4E@O{FelXD-_%D&|b*PjQyNKxCFc+&*R;fpe^0EeX0YTHV$BK zr=PDhJ8NIwem-@m`<_Crf@JrZmQTqK?)>Z##I_n0T)ywPuD7pUdQ7adq*gYSR8;U$ z{Y*|g6AW(mbL;B2+K+A*{C3~jR&$WzDjvZ{;6tPS*tOy;5Z7REx2!9WnsCBhd$xflBL{W(DDhXKJJ zz&Q!nWCNZ`0}5)W{>=wMln)@;KDR}KVPF>}g5dXaqX>8cKpOzZrk@ho;czLA*%0M(gT=0*Wc|@)6=n(9V1d7nPYQ0dMynpMp+^yJo9myNX87zik zEOmOY8g(7fuyo$2bST>MiO5<7JyN_4 z(cOlxnw(NL|6q=g&%S>p;7rQObd`X`BR2c>p#oat>KhGJLi61ue?p!CSdJ@a(Amw5jL*VazzO-IudA+#6gB6G| z>Vn0h5s2BK3Gb)qzWCVPgCKlC3%ve6@x?8B|myIaj8;1S-9#6DT?%&e$T zk^44?tF@{BIsA1b{sqx1=Q99w<{hV6AG5G`3bm46R*x#*E4Nc-tW<3BV(dUVqPEct zAU||qixK?>g9Q@%RGi?!J{hlOcVQcWP0vL{|Mv?`t4RzZk(VCW8kDa$I)E6;Jqk|n z+*4Ih{T78r&kwS$g$h$ADz!z{+D^lq)oj!?=@cGXd$auD7)ijScZ4i11K~V0Mnp4b z9=!<^Jl^Rny`wJ9+?GUDBgc-#sSzs3ptH+@CbOvACs(Pvy#G(NKzyA|z6gQHskP|r z=cpPGYf!OHM8P~7Mzs{fHd+R2A8Pi8;}zwn3lBq)uh1)H^q}EgWY*S~FcJmPEK|Dh zo9J;b=NG;Yw-K`b_(sU@eT#oHmkF}^G6@mCV-xLg;FU^fKyXU>%D;QW!(-Bo(_<;B z-P1XU(ObeXt%z$X^UVuP4F5%M(9P~crMzX~{c*?pq?tQetr!>ezB%-C&RaZ;aiP>1uxRn3wV`QKwldhQ5hI!439r20unIHS))qgn2&=6@>=&CVH8yKF?Tp zB=H4a9r9qBCO@pouUH*dhY45=u~Fe&XC@F^CcHTu8*(^h1!oP+1Vc(NtoVW)c2eNd z4&6`7tVY^j^9eScN+f&)AIukS%m~$H`G-G-MZm}2G>c0HAtMvw=&X&fOwS@UmH%iH z_X)W}-XV@W428Xtm5@TJ%9HZ! zcu$p`vMke0cMkP84^2cu@K;1k3}{Qe;NoIx4p6zu+#Y?0`XR5m&7&aNSLn~(O1k%n z!UYyRNZ;cWlNRMA6F!u~De;T{@KoP!z><@!)uw5SAQPpwiV2afBrPZ2E;P=7cyd`} zII7CS`UlMw7kw#^fHn2Wr?|nGp&CGrfT89_w2r{TB;E&78_Ft5$mvlcDE=Q!=NKL5 z|8@N~YLdpbHL)7oY;3Es8rwD+b7I?S+}JiJw)xEOzn=Tuthq9?uF1?==bZiB`*Wz7 zoRlw_?V?JHlZy*eRFYHDPB6@VM;l@sb)a}@08)R}_NJB5p)`?2B;fo|y6C5%e4l5% zN|4(RKEh2^0s0T%noh^4HkHHvTBQy7Cpq3UB25z=REn!w3~&$s%0%AKc>NU{3a#XL zAy4m{(pYxyV+YjRnSVD}OXI!H#*rmDd04~!``C2(3PHoGewpsuwnmxN;@1Od(sACd zOPU1}Fl9OfPr9nRd+cr7V*BlZ2Xy$+v-Wiz3FpG*me2Y} z;q~3i0|Wd-teNi84{;^MB^TLPXD6*AB+fM?fh8AyjjRp31~&uSF7OTb|FxGCzAVf% ziLR`!zUc(<$5m8&LW5_S&wjStXSp2k{PUlh=5)5q@}K2w^J$3l27Iuw*ZKK=2?9?k zgj1f24M&f!>kj>ha#WPx$HvxOh6$ZutP?4mq^H1q1;+LxGMJ#`it6^r&uhVtZ>f5& zxL;~~&aMA5rU`+GJV!GHPF)W_13h@MSqYG&6N9mPo(8=yoO1Vi-dn7n)_UG`s#|yA z3zOG6sXGHhfYJ!1vAcL+@$sOqQhgDcXMVGg&mp6GNXBR>VILb9cr*( z_*CbHv_7i_F zyXf88e?EBVgJs5>*PhSUESE*Cb)O|Y0zUWn5!1d6x2=g9aM}BPJ7G|;1h)1iZoO}8 zQI4^KN56HEzudz%9427LTz%HL^FOwi!$)O|jtjAhXsdEki`jCC)X)SS5{Aj$*>}MR zXJ#Z$r&;KqgK(Kf5(rq>d@`J@Q?w_c0qFQ`o8c5vvUy){VMRD1xMo=WO!vlUYyT}j zH#JqF?`UgT#GxTN;gFMjSG7wjUp1T~5~mX#!B7kqL**;wiGNOpyheE)=SIMm$fCX6 zad=l#-({f{IR#NGNvYcSH;~|`3mK2STr-@O+`r3{4NQA0z#z`Bvxe4lf6tbnh*Xp) zXN?~qDhT;1?vbo=!)4X0BuRtSq9|j8-NNPgW^FUD_I!ATZzE?Oy-qqQojd*yiTjYu zs%lv3TrxO%K-3nV;}stTvMi~Th9=QJ6$v-95NMecuFf%jusrJEmJ=e(4yPy zN+~v#6Z@4AL^gkM^31LD? zbTu5U_|P1eYC!T#;c?&wAQdL}=IP}QSSKrdjerF-m6y5*SA8e3tqBr-A~+Uq9=F0J zb;&sT0q2wD68=RS53MGB-i%ySKq?)B5=z{eC_mFSBpd}g#Xlt$v8@kV{WFA19?+k5 z-zwtFrhATR*`IX-UUe(3%(>|Xyl#&o1L}=hw5K*+ut@!qyZNDx72D(+g?6ms$tXDx z+@~sbyh=e=C}T{iN!D~PX3ausJdKkr^p!s;5iUf7NM}6WQUW$%H07!AS}>)GvtWyn zlJLNC>!j_{VGdcWvxWMxA8(9o-bB*g=r2%{0_I!MfVDz=0u3Iw8+EU{G*fizU;fx( zs#FIO{>*EOKgjkQ!s$Q%m4CJ5C#eeK(yQa<6Zs>Dl8w=5k@%?3v6-Tk&FMpp7ucxT z5Hcq|)@=8Zgdn}fD8I(ORB-+YMS+ToH>qRV5p0&0YjCSUWqD8yf3#iGEZ5_psV{cAeHJC$Pm@ZR#a30YW^Yygt7S zU(R--TcOJ!gW1rx+j{w>L+YUSdCk7(kPK@|m;IeZCfLS5Z|KYBPBJBYn4{(1$_Egr za`}H=fZEsitlY7OQ|GNM-uD)j;G^z}RS32vEWD96)4I$@4_rJ0yDv569&6d%C-TJM z=Ug6m`xbPM_}w~l&9?ZQ^jr~16U{Mt0oLz3n8BTdZh9(5WOSyAg$rb~6heQGBS+bN zG@A5}vQup^0_G3tt>h1%B+oE%hpKD zNhO-4shU$QX@kY_k;>a8DBoiyl`E@J^N;(p1B0XG4gUQD_{20|{`3%o56P&fCCGF| z=Vpa9E44AjBe}c}pFuYk!V?Y|4hu&>Lxsw>%kiK9etoO|l{4E$((dmPaFp+gr8A)^ z2ib?&>Iq(vj*lq0+=A8*e=^U-r9aW$v6`W(Y2;)PNfUV5Gjv62%kk~`P+N>i|b zSnDpO+lS)vVlhb*pSQp3aLF6RyaqS-Nw66N;F9j)97px`{7js9hOkkBjR<5as~u(% zq{REa>_BQmm$wVuHH5Cn1l~aC=oH?}&!QHX7E(?EqAzw3V3C!-l5Xn?jU48gPj>A?RB`loJkHmpcbB5j=BQ z=A&NFRJ_ofR-#Ho8aGR49R7<(>l*0rpARjkmj)Iqbz)EeNcdJyB|O^+-MZ>0?vqgp ztp1*YW%?h`-}^XD4f(!Gqr}9>n8$1vmC%)Ww-#RiVvt(ngwS&=PTdaqD~QXquktkG*x8ebZW`=J%yScE=VL(k`Gw>Kb{YwL zyt(=xfU6G|L48wGNK?xHm`%7-?lAxPB>b+i{d&O{!ESj19_Mhd4FR0!W&K~6jJM~O zR~IZ|Mh{bB8+eCbzPi~4boo$5cgENh7cIa^o)4WWxmzzqw57WQGf%=2js-hu$SH- zUQ`i>5z5r7+C|$qz`_7O1n*a3zq)<86(dJjpEnP9-Y21b*6B*4T2eP)g zd1$lC3v@oKR`{Qbo;3`a_>k%IhDk}L&VEY(ETbNBW+x}=b+|c!2;Ce$@LWEecQN0lAOZj}SYQDJfXDGj8ZRESh5J{g#|Wpaf-f#CvcC_WqpUz13CquV4XrS;wa)4F^045o=_=O z>R1|({eUAZr4S+il97pU%*7^P=2AT_DOCp#^#Gr30SoK zGf)OkN~cV{vX|l@{F|LWLa+8L!_xC7`pFko)^lvtZe!KQ55I>^ihuR=Ot-J^Qx0LA z&lne|xCyvgilQoV5qNmP%y5+eTy6GW7ITZgNLbkQqE?ly=;qqBzTl5|=0lq;vL<28 zLXtC!>ArA$%kZo7B_Vwxqk<$0A>KwVu(Tw zWt^afV3p3>3hvJ^&9tqwHUOq<^hl+HO6nh^vT|wdv!Uhu8kS$SZR>lGX!{4Ctj1v@ zddJrgF9ktKs`AJ=7y7snc!K=YF)TQ`VSbtK&9N{2N@-=L<(g42xAwO0jz%}EanV#a-?%v0Ta6mXMQWeO`->9MVrJqZ%(Mf%=rXte@=18?ACz0JRyCg z7>2?$<9Apda^d^pZ84RE#$PM<$u7cbOO=aG@H0}1;Tkj=hPDB53{~{k^+JDAL_(ja z4h2jw8IWvy3#Cp7IMfZoINOF@r{NIdZe9)h!wfbV z%mNO(!7Rtm8}~QW&dR7?#GW@A-?_o^+M$x>&iNg;@Da#$b+l+)Fi4ZHz@P0*(8~Mv zJ|k$_xw&_CmHc@tOT0I74M{7wZTbMF<9vYBW01%zNYnxw2bHI-5KrM~ zRj6#}u0kroN}{f~#rkmXl_a)nAy_OR7&VW}C9ZTz@@@Kw+DQHSLxUmr`Hfg*v%V3n zc9d+>I1wee0D#XkH=`ByAR0P>g2}M$P+Y*Een$lqp-QGnMS+&KPL#orDHsF>Q5`(# zB19ZG3$qegBS0~apg{8+xQgQ@3e^qbG@yGY4bbD9)S@EsOH)$7FJj_jOX~|p{0w5E zdHWIqK?t|FqZ%a34=0|0KxL_FURq|ULZ-^?_g>3ybVN@S{lL!5(yF0SSy%-D2k-tanKQ6Xr*b|H&LREsn|?m zS22UX6u|}8Ql(*`hB#&bE9$xjj?YZ7uDNU#M^NSr$*-v5g=EaIM%0G1g2<@yFL@r2 zsTyNSW+PoU3@iO_#3G!bP@?YPF@MiXPSfQOegLRw67_eYA=S{9638qea@r!r5JMS< z0}BHsENL3PRH;Sv=Bs^k@0{l{gB|(8AAtE2tt&(EpMN<%Np=6Jtn*C4TO^Pstr)LR zq|Hcwny8t=5kt7gR<$w4e@vVTKJ|5}xc0AD$WK>|_1W}rjm)OFQ`e2^wI*h#jqb8n z&=M=P4}S=?j^z0wfR3!gVzTP_O5AR@;$jh$FrwqwY?+b$mj^FqQ^X$H74`^}FuCcq z+Ps1L)?VF@(@;=n_h?k{HAbR9kA2&!NdzFi zoiUWi!~*+QS62+)ce$@^xqJV$MGCnBMf9@ZY@%g`Uh6&6`z+IcA$ZuT9||1lv5VR% zW0b`2N0Kwzmwhc@xC`>lcd!o61p-@bb@lZx%E`cKNwU6~nVAbRx5>Jemf`>O5drYu z{r>%1WUYDp7aN$}R&Bj_`h(McbAJik#JN@P3>ph7VRZOk*j`*%HT7{1XY;yo@$(=2 zhb03qG&%SU_xJjm<-e50e{h0@Y)xGZ=$ftvyt!ilfHH^AcN}~*_w&pgtm|kn4_)mb z`=uE?|1sFPVP*2QZwTwC-n+R;)G+Y*^S>^1d)tunAC8IZza#rW{BbbT#?Km#=i0iH zScL2Vxe!0>?}cMSZDNmt{Q`*MqiMKb|8c=S`&X5jK<@3W;O8w^&G9`n|Bw|kY_fWK z8um+#^Lumqii31YxZ~Yr_gwOM*K>dk?r`hGdkeyl(|?wLzp;)un`=tHf`t7oDEX3@ zF*4XdiReijExm1YoQ-@6k?B&`zzq3X>GnR&?ZUJD)kDS|NNDNqwp-iADWwV$;ru6R)k7sLpwl8L9z1kxthD9i>FE^%8k zS;?)FppU#x4e_U7+jg93O8Z--#auQF)R{xhMo+KS)q>Vr{9*@wr1nqkKByy z9j!U1&lDL8*(fO-tp-UQNom$&C9p_U^u#zW|BMBevJNi#O(3Qb;T666abL1kZ?lLl zg)iMV-PbRGEoa8`U;8;Ad5~M!L;ezd5t*fH1lI9bN^N&&2QHDXsO*}sv~Smhq&ct( zK6=t4(spi7O$4PJXxfA%1rJ3ToLqvH5p3~$)6w(wxxLHL`(}rF#U44mak#PmaOVil zsbk1cN!o!nFeIKpAENtqKp+YWFUFd%n4RDlJ@l4*D7D3M9>8PiJ!eFdP+GTYqnwLb zG~cPZe%KLK<9Pez)w&P(boCkOvg;kc>llPkg5Mn~XX1wAQ>bH?;b^thLm>}N>oT!D zxwg&IgQ~<+?m!i%wbYG^X4i90-a|X3mYT0zA}kcM#RO1^T)7hi8WpKx?h-K2%T^H@ z7g2$E#=eCPdGA9LnNBP-cr|FFuu7ol!DVwdZWdG3GK$0ijt2|~Qd}`hU~^$3Dx)`J zC`$;bDvTObmURLvuSWqzxiUJ1qJ=0t3Ymq85>4o0{ZUH#?|60qJdZ!cL@iCj-xs9y zZms!I5J2M-QYjn>_$_zWE*494U{Fj|q=vkgLUB5nvWO;{k)@pkt`RUZ7;mWnwAA1i z5nlSCsd8)MAwlpXTp9(_zDf7+lxG+dw%VFTt#@-9s>P}nX#iTnH5bEEb%&+fu*M7e z60NK?4^ctskMRIe|6oNj0a`hrq>TC^m0%Rr&-{(p$+$b4dPnxI0u#gsg9#W&1Ow4X zhZ|uUai}H)!p>!%P;fIL85eMAj8>+?^;y7FfSe+{KSy6mb_8s*Zr$It7F{K{X|-5E z1`40V^CAs}JAB#Z^B+UFL{K?Qw0{P^hZNCE1g1$v2Eyl{pyAui9NJSxIjzV&9d4ER z9}(4H$d7}TCU|HGkBf|e-=2QPQ?VdPCa)U1$b#zK&m1i13McJ#s}d$%NeHDS+Q13z z-A2g=h!}%wuFc^AmPvU)XsEE>-Wkf}E5QbM4TQ1>Z!jVzr0OWmXCY7L#j&j@MhKj! zTrCZR%x^23=&!ka0x$?LGq|TEjfz&XXkCEhF|w*SR6z3vQwKn873FQ^5YB!bMElFD zm<*l9*wRfby11I?w9seA9H{(Mkf zpMCHw{iVHaAxb!xa+c1@Kj$0JFX)4j$Fx+qB=Dq@1aG8_vYIpwH}hweNaOP;)t zs@TqPkf^P4#+LpLA_gzvV^v{@ceK47CoI(ar+x49R%6Iz&yn^3=j-ZVQ|)z?k8jNy z=fjKp%w>-@)ujd)K&12_-gg$&>~`-0?g;Wz|0s8a&tQ`RYq}Q~Y__WA+)gt#1ngg5 z8yXt0iTc5qQMW0bnk8Q0W$u;}`8OG=UpyqQA9QV?K@}du8XGfAJh=uVWnJ&> zk=fmz`qez?2F{x;Ak)_mTjCbKj`!7zEj8@h1)uhe`?m=PgQuvAC4&b?Z}}a!HE#6^ z%&@SqMq4ljwY@rh3WOovYskC}PP%}XnyFwwH>}v0yAdOW@h;iOL_B*>g0F#ll!M<9 zPOSB1xyilU0X-`vbJZlmU4T0OXwvq)at~T zo11$J4)7R7uaK57F*3UT++h$A5_6?F%H*_16UnpHF^(o6CT`GWbc49x+$8eZVk3$> zZnvYRV#12r5WlT*PkOOhX}0&c;QXBFo{(OT+9FQiGzseI?%nn5^WM<-{QY9J^$6Z5 zx|WjrQkJ``lKTSbd%olgUIKq+;+!oC;CM`w^LUc{JR-jN4_Esi>4-j6w(}9pK?gTP zEY8e0XUt42;0~l`(ssHhP~D_61Knz>+zu6Cldp*JBWv%s#5uyB-_ehogLGi>2V?Z(Pa8clMV=3p7MJ&y891Yb$?DoZ{HN0ILubgfbK{3{p4%m6-8R)le&{1%_cj zVrjE!h*aX2qwKWEJN&yWiNWBXcr2lXzo~u16R&65H9&EpyDTjcM@6;?E$aloaWobSAEnb5W(sE=02az300~1CjE-y8` zOyB9QCd9tnO+}-5L?kFxYAjFA*0-wkgql6`6hK}o6fH8Xb?jJ8?(#kHH-Rd-9ixF! zJiRC;w?nACfwy4Lia>Q-7PdlyhC=!n_b$N)lVs^M6r562dM?h|(YlJX<0edW;B-Y^d$DLZqGb_f97DIJ0Y|=m(gB!8-mPrFjXu-NCR(lvv z#ERv2XTH zh@lWRU%Xw}I<+onW}AwW&TOSWIoV|;tc7$0lTGN@t7s)2 zO*)qj6DS*7>bW{khNawi^i!odpj*dmxFB@WpG`!QUeP^P0zaz@b{E4;P)KsHwc=`V z?j$x4L!sHCE^|3LG`t{FLRwTR*$S{sMFcgW@ED6|EWYda_zSxu zYb&C4|1^<9o$t8wjX!$Z#J4-YUMUH_wNDk_&$|}xTjc3mpO4L61vX6r7S6|~AnMO= z3IUF-y&d}<-1PQ4vF4?Dc^aA;hKaqyUjSqw+myBO0E5F@u$PKGr(u>& zduZvd;cpus8H2hz=*jlkpf|8#s&&33dKTpp&AxDICIhn=2L(P?FWSDr<6P?mdS<_m z8k3z0E6r5NB3M@{2uIl)9rd({nnpoUQB$_as@$wsQ7fa?(4DLJ8g&kFdWsgtHIR_! z@EUdF1HL4M;0)IS!***nU8>KpEB|abxtglzU;CY0f0ov>_=m?Ue(7kQcmK)}%PO@e zaYPXr#k6q*>;Ng+EB%x>q8JdK;ty)q+HL~FEN@19$iImx$geg0G50hDN3TQ$2;$|; zBP1+-%d$L&EYtx=jw%*kc!m(mwYtP@1l>KoCPv^~oU9}R$ zgy|C)6W+cYP%j@4%_ghf2me}NmQ&emcqIBzzr{N>8?F@CS9oP&*?4v1!+AsHSdcr& z^71keJ04K-A8YPcnOlohpPwBTGZfF|37q6QY{Vz$3n!<^cAPiz|Cv`nPTN8U zCAa^2s=hzb#0ZbhO4JpeQ;3(94J;_Kv-=X+{SV2C(CPu?_B?gs_je$>HWBypTdC*9Lw`95l)RG(rZvAo=Nv@Q4&2H@V+m ztsy7b?_OB32@BDVznzWXY!j*}S2bPD^5W`6yc{C{KxBO3paOtqyvM@Ty%(pO! zirxN>+*Q={U@qnw z^nYllU4WoBD`Iy+gR2z=9S|pUYsjQ$?2Wb(H&L4npzBR0RxLg3W^c>!7(kz`4T| zxJH7@HQ@<(;!Z{zO3TLS#H5Y_f=j90X7@x=7;>A-D+luBmLy=%ly!yMsYT>mon}+t zLQUqJsgvLiAc>>qUS_8tebCE6VKhAupGyxyDHI$usII;@(A29}q* zE)bNIlw@UPk&y9uJwyX(P!b3)JjN`y4qs`DG#OJZsO{&y<5aNKpQ9Wr%Ev7!tHLb*3fsNDq-aH?u(`QKnoV(`7GLli+ppbBo z4%ZBi*ya;pFPvAzg{?D1i%m;I&zfztl(~x7){b7`@|`jL5+yu%W|i6~?SF4LgL7_a z5_QbLIjh&*@I<=l_xeLjoapCA+E&LCLxzEKp%cNR#M3lM0YKI*0#^cvd6nYdTR}u&Jhf4QX<;fyaP_DtZbj{2R+$D@BTixtAFaoXsWk?+yz& zU1rPsmSUu~`vMKIT&RR2g8;Bnz8k=acT*fLFA!dg>_e(Wi(oX(2v*Xxg>@fDY1`ev zb;zLoQ}`2h()`gGZb;|k0JUY@RyFtP56IVBgdROhgWy>-G%C=gZrArZZLx8nSn@S6 zKN{7{NxxwflT3!A?N-{UwddRSehPJj`{2**No1vGQB}@u1tRZA4#v`rV7K8%6;4r+ zE)sd!c_aC<(6d2)2}k0Y@2WV;X+iWhT2qO*pb54`qx9h%fdf9>B1PJ$a9~Iq{Zqq5 z9AFJ~!g$2PGbQ_lI8j3D2kbJ9G4Cw~Hdi7T|?Yf;@@Kj6KTR4pPN zZN_U;8c))d{1?4z;+L7PaF`goy~-p?_E{Axq_}38;?+k>{QcdBle_!~q9gNsW*d{j z1jTgEBbQH>a?5*-SvNJ4zG0l9egk9zLhbM^S824^78QnIYzW87at2cGPE-6)!qNgr z5jtEipDtet(pc(_$9&@?kJCg<#4Bb&%U>K#$s;hfgGF%9eh-E;7uGTfw_3DhI=usv=y%TG(3L;UjX3??SFiL)>76>xuFgb@xg{FOiy-vV(;NkOOJ85M3J} zMyG!JV-+v?2Zs1W%n6p;y_fsthZ|dh=;TJ0px@gtdpUVKxA{4Lmb&f{V50D#(pLz- zc-}LvEORdw-uMX4i_n@|95YO7{zr~~e~3%9jmp>L(Lf8<4wKta5Lsg@VO;M(xRLnZ zd=AFb_((o%IROQ@1u76uW&|aKunW|Nq4K|FV+!5?HL48N_jvrMwe{o8v330$iBB`4 zrd)E>?Sj6P1>Owa?>gp{Lx2X1)4C1$is}%$JxaAWA4VUJM z*!AM|X{BUkXM^#7u5wQcR)ZGoyEivC3=eNW8dq#( z{k$W$pNCa@kK5b+KpODmzokZQ)8O6m+S$?)7JjyT4$ea?ScQZ;oGvo_R8ZjN;o05Y z4eT}iYshTaq>XA)SbdsJ!$%b7W?aJ(dhOon#nfI6-qmH&3LcfPUym%tkXzae;i%MiZ3!|Q`B_&5WMfF%CB zCI&$gKYamj8FO?Lo?}M{>$m5|c;YNa29NM=o7L(Swx0$V(8I&Sn%2)Bm!G~b-I4%t zy(MsG0GoXJkh-SvDHCj9fKn)#iBz+6H@j;itid3CjGELhWP{#JtY{%`lA}Z$hl~t} z;x5x8mjPii6``mYI*Wvmng!0^t@M(K&_dM^ka{??;*3;pQLOM6xWWb6V14&sBi8u)CRcL>AyR* zxDxBsM^zQAKu?6A4UiX^u_|myW1loGr3k!nC;W${BB`oHG5-COM`0sz0*PkEnKr>H zOeF!Qp;R-?Uux8&5%P&MHFy91!v#i9-X3dR_A}$aO5TRf8;vF}TJ&PFCu(WvlQif) zyet3U`vvl|^9v+Vi^6sBn1wJwC?gYvWE6G?o4o5ku8!Ve9tc7nPn$1$QJuTx^$kpl zXtiQ2P&47QUnIfIyacfQUwUphkb_Fq2u^zMYZ3b*){$v=ROnyRm_DwGt### z=TFqV55}og1t)>bnP!I9-~W(rA8{%m5BUxrv3sUc??qo4O?Q!`eJDa@F@VyPyXQDVoh zmFZJxJ>6SPXn6E#o}Dph1OoeiCER+x>5%3qZX@+PCcXlaav|hESy_88-7UlRft^9b zizE9IR&w=~=atI0@cg9L4&PD%H*;l;7yW4C+VAz`aC$ZdlnwXNqj5o!(Xw+z=Z zCbp_DC{P3kie%1a6?f8WTG(>8sVs%eO+HT)Nu@0BQbMgx6wTHeoqtJGQJDMc6(>0 z5o~zbqZ3h4UGj@5U7@%5C7w8pzn?gHdp^8ooqUVlhY>XL&GGT+OB%s`R(-)N~K{DeM;!Np2ap!6almFqCx;2PQ^hSLahOgVs z<~!yWZGK9m;mX7|S20%Dp&`1Lk)(qn$3EX;XYd*I(Zh7s}h=aNZ=uWf)5?KQ>}|lbZ=t`65~P z;5Q`C|KMs$sIFQ}2BQ%E)dUd;jZIiQ-CDk*{|N0|%XMH`jyYr@f~kpkxZ+5N00}0m zro!Rv(u|@J%B8?}1glS{rzqYxmXkUsXonu%J+NlT)8MpyUByX!xMLUNllI06Gyy77 zVMB<^D<%SP%C`(}c7!gkWj+~wjc?|X&;6tDAD_EkiA(UOaEDDok@fS>6f_ZX$-u3< zb`S&CnH{;0aapjUyG^Z_bY)cNW+iMf=}CAbN&tOSA50$85e?u*YXEeDP)kOl@c>kug}7uGwIRH0)sUQA$ZUqX=W4S_vwrOb z@5urY=NVjoL8PFUtMu(Gxd3;Er0yHz;8lEs-C(2ds5?S|>$s60de^G?27qx-B}Gj# z9NU8t6Op#{%$166X_Pj4R;p%Z#xDNEezx32`T4g=j5DdG4)GA)V&<6{aI6QEj91ixs_3i6ML6gR@|(cCoB#pt7szj-`=@416M z&e<^$sgfxW^bgLA3Hd^i7-X|9968LwI-DsE6a|3E{iBf<+w_dn#RHLFG3$7MO{V58 zNLlwP@Vtj+&pJ}ntsluKhgo6NdE{hEx&2^QLhW-^JBQOobxmAPL-sL zwSn|>*NN$Sl-+B&y9Z{%8_?DOQ{5m~)^}6s^^fB4l;CH1yeH;@x69hp_bH8*Iu~LC zajPEKjdwDPTUX-h6Llsu4}*EX?u@y|=l3qVOU0)jRDwmP?S%F2QNrD;hqup@dae33 z;Bsu-rh5Ulob-C0?pv+7ww#||io$}=1;ENZxH5N)Xm^}itVM5E2pZHZfy4NEn4#f@ zRU6QbkX#^|v8?kJmrc9dfEL`YwfC*v;u@kob)mKHZ}M|z56>qYEyIEYNS14^)DAY; zqig5(sB=2&cMD5OGUrf_RZ{PKLGL=yx1EI3%^(f=@jVS0lfA0LbzWWoMUc8|Wc!}T>j{Xds{)U3U?8o-ta z<2wHyiN~+f0sD{=bb-lFjcuRm5&KJ(uUKkycpD8Dkh$3(NDDxT$k)3AmC6egc2Y`D zb0u)GL7O8q^ppgMB<3tq=a&K=X`(2#;a^}?UH z4I|^xVoT;Fxp0-C*v>q0O$QEQOCHLKIG(C^;j=ge5k6vaWKv;b`Bz@iyQocDQ%Eje!+}rSz3})*c6{-(h2XhthgGpcC&jZM_brS zkrpf{O*=D!9%Df4dO-jJRtv+%Ulu?1oFUPzMYO?Avl_|uvaJat?}+k8z9YdPX*_;q z_xkPZ`xqn&UPrPFF;}LQG`)O)7H~9etP_h+*rW5f{%@_)v?>G~%+_NXa3IA?b2SV7 zgm*e)Ry$ES4(KiW)gi zB@=+4v7MwWJeG#}H7NWXD-%e17z^jEb2Tg0$qn0sR}wOEV0WQvF*Lq6X94X;ac2j8%2 zePb-ja#dB;PV37JguD3W49AzVuX=M1(?r)dM@a2-X)Jp=?+|QkqQ|=Q`9WW6I06#w zi5IK~3}fP>MRCIxa|-tux9Y7IX^NEe6&Kk+xCeOy!_igBN=JQo2Gy3-3=O-{tF-f; zaQdWbWQh)==#ZLp6a{H7-@9v{5OTRc30P~_lV0f~DXXQPD3TLtrg{0rIU1T<+c>iK z&rUJ$lP#hV!dXhrv~6jc6j42%uhQ;42WQn$Zb1I651NQc-M_ZZ$mOMVU`~p5%x>-M z9K!z4YwE#d=&oG_$ugdN8Xvy9a9SV`FQ460w{@&jJ#}r#`D_Hdzoy=$+}Lz`((BM zRcOe?QM2tW%fq$5a`!cvk`%VUAzRRLw;Un6G6`UzTMN$ly|llbGmhhL8}W~ zg&~`7jRchO!)LA1lL$bmkbE2+cs(Qdu|V1OG$H!mD3(QLT2&r~f>VafJH}6G4k(Uz zf%eZm0-u@5tcKZ(>-gTN59CG!ZE^|@K}f{>(&i_T*y8v{R2VDLmH*l*+DU0bPU(Y#fszCHLE9NZHJ)VfwlY#! zRVI`5!~1;N*O|utwJX(AE327aWj}Qy!-{3$YudfHuHZYG5f;6Y>nJFD(?fsNQZ1qa zIB;9C1Bs$1xQ@?MA2P222R3&T>%x?zv_S)DO4CXOiNa{fzeEmXk=|KWvB!6zOOA2n zwb2$5li4w$rKzJ)osR*|g{r73P>Y9IcI=XNeUv5aJJB;USx!C0ICvS&MXGq$iiQr^ zgHLFbv1#lq4?m78pxUKV!}f?F?u0INTS!= z+(rof-{3D?$F4TslEgHbmkCf>YbG6!Zk;J3GPfG0N;>H`Iysr6(xXNGrkP8Ji^|$w zlsaep42c?gQh<$e;WBBRBqSPQAtFGG%u)x(f?isB(hHd+vyXKR(P>Bf0FZt~^a>e0 zP81_(MuprKom*%Un&5A0Hwaen!DGE%%jrWb^i~bU7e9v1D}w`;&VT8zf5f(`e%>~T zZK3q_gt>2K802g%F1Q?G=NIK->(@g;_(~nutJf3RV#X4#u;dkx zqF9axHue}Vj!Pv@-&2YMmaF@UqsfYxa9=Z{`x%BN2q|2d+onSJ4D)$-_Wn{0h$(NO zp#agyprJZO`d#oF8>Z~is@NR+>D2H3QoV8l-e8~^xY$F*^bsyjFsnxUn2O@FCN+D{ zh)E-dq{-66*pa|d2e`2F7DrBRrW%ed>1_Ini?6vceo~xom#3fH%`7 z9M#m*-E)cN_@$_ME5NN6_iXuw-8&-8Rf1gBxeU-X=p0(kLeNUib9$6K5%n4@ z?`nV**n|^(LxQVUr6L9#!H^+w!74%ke!G(v{=9Q@-{Suhu8VNcNNZqH=5rU{qK>50pUaNVRK(&k%Is7br2tQD?Z)4T@+DIZ6b#& zGRU;qP>Z>-jzOrF#C<2k4F&<{!@QHZv)0HR6k-MmWWZ@Qg+mcex6w8Y!l0>}xG1ka z!Mk)n9DfT1?@A|QRoLq8RMXQFuan*P2oTxux)^b~iHd$BW6gPd=08VmZ$?2lP_EVX zt63f2*$w8L)mTZBRrUK`e|2&v`_}&X=t1e7{&@ddiR>HX^jH(2emuV|0@;v%cg$wq zSdRLOT5c#_muxgxnP!BfjAsu!{}&1yHrO1iah=!R`)Th@uz?UXSMgTn?0g{nWwg*%d*dPKZ4gs~bff!N}RwhIGe_7y2 zfzjcZp~_MjBT?zIxQmBAME{5#D@A^fhCMTk%ceJG92J=t5KpI%Cr_c`TO#F4j|w~A zIrV0Kv7_MB2-kCngJw$Y&~?+n+XHV1?KG~_++%Kzj{$1Mw;AE8cb;tK;a-pyiT=bN z_^~_@`TCyfe!oj+D%c-_B03Zni~b2;6IxRjLms!9U`eRSsP24Ay2baBSxA~kZT|Lg ze~E%E!3W$ zU9RHW9s_$8aJ-;YBi;9uOuK(~&=jn`P#Brf2J(iq!;PGjT^OK(vhH(*Fw-wP? z<8Cac#8bwSYLVJpcLaBqODYA~BzUMckrK@f(S0)B+nAC3C&9^gZi-6uP`j8x<@x!_ zWm6I??FJ!JvZhf!@er6ikb;W*69fWe{S zBAn=Nax{*q-1zye8yQ_Dq{;2bWzXGSoqiL?RU*wrVsUH#BtMT1iBbvWIfO7%8q^XeDDb5cM-r{}kV91qV-4!U7e71ZoqD{o zIS+I9G-f%u!7FK0H}~S^h_5z+1P#3$0-9xpb_=MjjjQmxbE%s50KPV9@1ZRUzW#N6 z7|`bMx1Cgf7`S=rClMfq{Gh(~S`0g~66mex$K$L)B_6A&gve@)P&!hZa+FEV7r+1+ zc)zvpx+!578MEcxVT8>8wILtTHyV+G%GI7efp}Ok8keiUj3IUw2QU<*zG&~DR!z8_ z9+-R_?|uGJ;}Xd>TD8M{p-$tjZA3~1|BAzMI}3#}X@7gh|33i1Kt8{j=wT~W=x$O^ zlY3kYG^Gl^#R%CbNgT5qF{RL#6)r8Ar5>m*(vp*OpF5i`lNBE54>-_Q`9}IRPByO- z%Owx&pYUDtCZpS;J7N5`Zbh5hx_y0b>$X1Y{Q5~y&tJs3`TTQy(K*|T+_69I{O)<7 zc8^?sR!n|gwEZ~8^s~b0^RD6Nzkh$u`f+ErFS>^3h2-Zk&L1Z-@2~aa#_C1x;Aj8- zqDFxI+3;TUeO`cn(X~DM^Kb8e&yDBp5Zu-mK`d&Th7iIH=K7QH1wZomzu@C@y+fm0 zYiZk-d7c@^@x}#ydU{IV_cx-@-g$a`eNE2!#^runA9G;X)bZKpA*YmXP|i7L?%lh0 zBTU}T)gONadl7x#jIdvn_h{^WN7vr*>zuoF{QiV<)j3Dkbu1Q(8(PH|p^`78Y>~1= za>C?mBuAW#Xz(;~THK?Oa!HRt6C<~WmW&E`!u?+~U!KOfOw zeuZ{EqBVCZ?viaglSHeFS(IcG$_ zaCb`_);KLRgX3s<%tB7MG!tg@c++!NUgEDE|4okMF6ZMZHYw-veWo&?P0aue(~OVc zvL_p1Y%7k_?mvr^or6d!a?|A&ryiFD6&PGWZN!VMbJSFK9y@WsBNWXzRhnhXJZ0Qs zL7FZ14^IebAg4&%TgITEj?3+u_lLK6aQXrpq9i0M3l@}ONST^RS!Qezy6EwCL5VZs1#5&Ok^|jFa`cN zI3At8OXGV!IRA*t#TiepA91KlzWwmGIh>Bz9wt7FKOo*67~LgL{99~!!lr+OSqxAD zi7nTQM_7$)nx~v`!B7D#5<>t0AOJ~3K~w_K6k;2p-&yDtG#lm^nan_FCJdnx0o2l$ z9&c7G+yT}KqePkmi){qvimLUw!;^8XCHlaSX2_nS?wFV&rAv(C$kavpaY18xj{RLu zvuCj|EEf$;GTfUEIDE3?q<@7WU*mGmL}qIT8fWQTgI5SfKga50&^e)VA!#Cw5p@am zr4j{5AY6Hiy@&U%8-&;ktRuIz46J8so3|mruUU zqsOO|e$DX8hFNCRG^{rlEL;`%1kh4x3~Fq3G8@75o>U6kG+`VJ@d~k~;#j?9a7wX} zckBb4fnWvf0u6;R5BOCexiwokr?iPl!6W1n>AMyyh9M2)r1);vWR*r5TD*67Z4qOL zHj=5t1-pw@u*Kr%8r@WUV2l}Y4kJR5%yt@a2c|YWhJi*qO13!dDDyxp6D^;;3C*XL zZ@%_7=r)JE$9E|qFtaA*kr=Chy`ZN^zJVmkUcl7qn54iJYyQRM?=S{~3vgu~BV{7H z$kU^1#0hh{W_e&~=0Yni*P196qE8jOjK^sU+E7fXdxny5)-unLVgecrjaw0iiAJE1 zD3Vc=C=$^k7%ZX{*j(>b4t=sbGLVNfkN5QP1w2T4W>A37K~b|2k-bD|N4p~v+Wdyq(a&C~052q7@qE%BZ~uF85@Yp%hcRh33@;RnIDoV7GA_-&!fo!1|2ijt^HaE!bfU{5=2%@oQ>1z{N1+b7? z!MO!@%u9UT{vuz`ze4euf3kf{G+Wl@5eQgDireDih|e?fx$eKWbz8T><`=bYQO~#U zk3X;Z@oCHRG_?Qs7vYzI7n-=9b;$0;;}<=jXYtO@ zI%hxacs!fo`*A=2`OM=_Gbf%EabNWK=QE1;XUQ)b?@w|t-`1b5TjBS%eyX)tEC?ac zG!53;8&@U#DB|ERYu&wjmk`2@;2UGS!IYO$SS%KJ@43FdCdSCo(a{YmyzhHrjJK2Q z$5hvKH)!YmBEQGDKX~xqW^Ufj)gQB%?1bKD5zo(dhYiEkQQDTVX% zb3zCl9v*&Sp4;dIq=no>VU6S&XP{)T(ve+e$}_on){u0DXXOsv_wxk2$5r>Geb69^$8>4eUB;ylyIL7m&Pp~E975y~}2GFlwPH-r>%?GJG_ z`{)W69n&zu;*)mR5#J01xvIIv)?=_}1hPZ4sR#G!kRqr_sExQ1$V5PCiUUn#3aQNu z%@su=P8>xuCJC*sAl8GzHY*)M79pg8wpbEdw)fxXA6@-@mg9XaGxNcR%=VHY2fF1U z7wLkNzQN54?p^#0f2aGexHEng%LQkPxA>>=H~7%ML)!#qGcfiSq{WtGHY`HR{p;89 zY02yYvyV(ZlKsdO1ATWuPT-mY*3-z*(UKgdovU)jdXG{`7$rJVDu^?TdQEdUlg)&i zJ7R|IvI=!c9oF_3KXZBbHvcgFw}28)9UKWhcXZ)|`OZYhXN-1>^^Rp+aUSvF|M?3-^)*$FRu^mqAu_i#hPl|sn_eUq6>fTVce5ynKviZ~=Z3n-rJZNwfN zGn9eBSr)A)uOn8#6w7cO@CPe2dHUr6Vah}wDGK5oO#@j1m*Em?1INC@P996cJ$J+= z7jy#eKvE#i174~K5Jf0XG1ZWU%?-vD#5P2YOku3e6%HVgj<>wG`7WC;T|#kOF4v6x z2H!Ri4VQtR#Yk#Lf(dN;Oa8&d|3H&EhNo+W?wVz8&^+>guK#CT>Y3uq`u>`^ zbp%Pwhi6rMvYAFZOaOmidE!6f|9+$t92^V!b14 z!Wmb`HiNi|WVblTkV^vfw7P`Rp|)_;+(jlwv4*w3V(SM?XIQ!em|>VFnpMYo954$< zYkMSrzI#B<8Rs0{c=Gr|@{aeOtdUQm&=xFXX`yor?wY(T*aD_8Ktptep_xz{5N1k- zmL+jmQtTnof|gS(GlmFerkEDRLTQm~5zW|=K{8m!W}Gp`;qb%&z7*6MvX3Mp&h=Oo zbeQRSM`pgk!`G%BU&G6(Q2^F@jEObUL+nlTlre_G!$X>;!3X~%P7#qEiqICe%}lgE zJfM@(R5x+*^r=Orh66ohmGAOPul*{EctF`&ju&_Ny*K|~-amYcNk(iV7&R>0CGj-X zY~9#Yk#={!7A3H?TQ(ND)e@&dF^Vlc8e34I=x*K4nN}^iEGj%%whYyT4NPw4s(DC0h}fbuNyy3L8X+1&lwsb|b{8C^iP>7xEhX%>ZtJ#g>$d)k>WheU z{-o#nBJnrI_=(T|#|hVa^UGeq++&~jqUQdbet%Z_yo2?5hwc7r&u8;K`~A;8w`Vca z&kC;3?!901_-E12&tK2}XYUO>FA~N-F3xZNZ~Nc77r$TR2!0k1{k&+s|K5EB>ur6? zv-;a1xUHXN9UmXFUat|6o6OWt!VmoE5Bz_z>-_xuCbQZY!*aRAT6-e`TWfDbw!ZIg zMB$t><2e3>$%6hjIllWv<5`h%zaZbgfB$x_e#$E-rTj>a`QH7zAJe`2d_T6TN{sPl z9QQf!e|g{SpKh-18x#QMdH%vYzuAJAf++<-DFStmmJyR{#vS_g*Iph00Z68%Ff#FW};QHtzDYpEVg){Z(lSKLF@BAj>I>tV+9xgZ($D&;z&Y-4HP+Dm@Fh`IR+meZr z7|j-3;-tTe4;`6N&Iz3idCr)=!xq8jmMDd*)nimBTwbND0Sle6L)EkN9r*HnF|pk^2GJZD_=Rsi@La5}&tWyNx|B z4foNIF{SWi{)p67%0}Zn7=tV-=37HSb4C?XC}>ck%fvj=NJD3Pj9al)C@B*14&QDK z#tKfU*``*BCNlXED~aR90&s{p97;lKhPURLBVMGs<_##i>&mvc;;;zY>jCRpoa;e^ z7)wQXdrLZj$L(W4m|d##PaUQhHr))}%(@#1wmRu)W**%80WMePUUe2jvWcfh4=Ff; zSdu`pzM`GoSlSAR&m?zrgR;ZzCHT&@C}N~9RWy1!)GUox&DhCpz+Mg_>s&_`1H zm~2O)3)t*wlf|k76KiffKrt8`QY?zw34OA2D(+AZutVop5jW3!1EHP~3c%{sw# z4xLAA5t`7T1%gCu5!$(-L6{q5W+rOJW`i#sMoJ}8#DZ5}b?KdB-Q}9?T8yG5W5m*= z7B)~CFxC=MB;`UcOXiD$>ldUHC{EGVP=di2%jYor*ZrcK*&bd|Vqt5pPze|i$_ZJ9s6u+G(p+Dw`E4LWRplPp(SDqh)tjgRmi50t-&Bz+u+1g;>=vu zjQNU^JlS;QmwDW=ZfS_=jwnNj{)u zMGOV&6-%U`D0R)h!%2&%t(|7 zwl-*pgT^b?+d4*brOPziV~&OfoQK8CxP=l7V~Av1vxAS9_gMEIF}5Eumx+l?tA!FR zB@6roJ}daVjcSDKZ#@Zr@eN3-skrs$Lh0~ z;^zh2k8}7wKUN<%?k^I8pMU%(W%xc{&pz+xU$kKI7MW&t|hBrF4@;+jSkr7(xhiT}RV248w5aH2buI z3)F;~~?_04AOi`3YWYytt1OALyUKut@d3MjG#1VciK(qy5@0;&{=#P$p|g2W?o zxyw)-XFMhNKP0+K9uD8473G(Y{x0|J&yp5}@27volXA}WbjqTvXp&H9K@_udy5>^I z+0YpHq3Bx=Un#b_ZcNRStp}$CN_7RJf+;P}3KCKTwMwC$9`BBEF+nI{CvfXEr~Cjl+hm)`tC>r4%FwJarr=VcS8%eW-L|}Z^;hWRfNitof+t-0OJYA)tY;Z$Y=fFA zJ^>UXC>|{a%M4}!qo`?-($K^XDV{!6@i&^0B$Qw7_)mPWv7HFno(A{R0;1gn!rnJz6~?_$&T!`bOdeNz7cX&$;f; z5Myb>k|mKr2DDMIh3o4}UY}m!Z~6a(JN6ayaNswu{x9C_{(w{_mf@H(7<}{;rwj*M z#vIV8$D1X_E>QxJnYMAnlqkJrE`=l>-@Z&KnJj_X4g^2ooX3?rG{rHPb;Zo?FyM2u zCi-iV8&MpRKubfm6U9yxyGC+DKeg4h+ZoQLM?97fXNkjnFkcC74Q?EdkX)HW_0qCOL{WwCNr$3)U4%QY1NYDHJDcogsHKYT_>U z+0um`n?18wqE%)qBwI1d!7AB}SXE5%7_GV9#Za4LP;yyP@Z{oZ7IsdEVTYHkB44(V zY-V7l^pVM2k-H6xZb>*9d0*G$Ie}MFpD86XyEPXJNE?S5VQM$fLN+s3M1p)D=Y`Op zGMQ_VwQS3pC(HM_KDuCDeF;{;re#Qphxwd~Zi|FWbdjmw(AY#Ddvb1>rK_ki{p_(M zQ@iD@@JDpMr$`}`8LZZ(jqEVGz)DXRMNP%*>#onNm_(a|gSo|Juo6i&FiL%`OmR3h zHA~$>Ca0f-DrQTGV8cn@|&& z%}A>q%gqXcA)G)C1BaWJc%%Os=5&dyEbq4enz6qoG=V_C<1kt+!Zhrk%iEswi4^*|o_=)EKgWRiVv_%@L$#^GfkZ>Ny-M9VNRB z$!&>trijqS6*l&WIY4b8wp+5F(QH9`yn38^WKv9<8FgSQiLn{!WyNYO_$$MGJ%R={ z`3c(2s4J*3cD9-?$NL=Q4paG^ImxCW|sIH@s)xXumF3mT z^z(v+Q>OEYL%ZU&pLZf66j9*gJ;?%$tca4rM&UCyKzQljj z{XN>WBd5qwxktEuoppN1>?69^GBl9nkQgoY*6n*+w{=^$ zbz8Ufm!`f*8o{$d>a!yAPujTf?Bn+5&@XaKzsN!SBHiT2Ijeu%82&hI;Lp49;a2#) zt)FUr;~U@L%{SlVt+(FdcYpVHZv?bGkN&o9>(62#*=Hb#2q`6;a~vHVad>pVU;S&p zb|XseZ}9u9-#zx(Id?l(Z|e&&SNCr7FIuBPF$qjUO~tYZg|gdX7y*&Fx>dCvkU1?# zsjj+YBGDJJso`dUnX~ek7-z(E&l(q29m;OVJ(kncb2fQM(= zNp2?E+9VKs29sz~1Eu9)@iIvjhohuKk%=(`+9WvjShJ|(E*WV|6*4uEB|#CK+KSdR zk!UJDRgqn;Vy;d%sjrtSLYt~66Kz6$WUZI@rXh}S=nlAC7v?FadU0bOG_j}N(Xg z8}DJ~CCNo5xngQEvoEB4g%wY>7Gs4u8cbGfPM8!?Eksc!O;}Ui!&brVT!h7BR5H=c z6f&laJ5f+-=5_87b@=SCMUkeE+eqlP%xy$%A;rMZYzcnk{q4ILS6e1rYIja~Lvk}X zp?nV8pG!T*!)vV8_Xy3F_VPQpmPiSam>sD& zNIk_0Lcx@XNWm6^*A|k;`v%oWid#%hG<1k{ObTNhnOF7x(#7|nuM)GkcyMSevNu_lS%{h~jVjGXunvH2x zK`M4Po1Np%2$tF;VoV|%szX#2DL@Ik6#xttqgA9Awbc<^8YnwQFO_Cto@pX7D(rJs z&9fp=sV?%lWYk594OkDZQ(Up&9maU3>jAfmAd%M5X2)@Jm!o(W)Uci&VH!izw&V>Q zUfqYuFx}lSH~Wrwt%6~x_ko%dTIW_uTRPX$#ul(-JK>7srT7}Ze(*QAclZr1?HQNu zL$1veD2ZYeDWy8%`Ro~?b2Bm=ez2Ranc`FR+-t^UgT-TtrC@hWCN)RBNZL7=A=rpF z;EDqCE*_vZPFSr1q@iMi)wEy>#VAJVebFgofk~7k1yRKo!R4CAzHo(N1KWIsU3iiW zq!jS!K3{3x;COw6+Q{X+Ve~_7;xR&JJF4R9D;mC3SE(%tjN8pYC6e)Ct012<>N0bu zO!9yW`;-)76})XFskl-d<-5rVsb=8b;G}o2M{Rb6sioOD<3&AEDmvU~1KL7S&>o|y?iZ|*uo&GFRVqnk z??krh@yQWwph%{WND9UX*(WSeio=x#qdigzrK|~IB8NnYP(q7IwO_(-EI;GE&d(kF zbq?JdnAxK4f{*gsgn48mkJyfiCU`6lxMm>vOf(9TaNc0F-jiK6sF7V>bLERW1s82a zD6`M+7BZHC!xY7q$S3m1KcPe|z3s7BoXvOxO(}>eG?K~EFo%XF9&#t&MFvIlNbs4{ zb|Q+QPcP9AD~|escs_D*@PM=Un76_M;-DNJk7zM9Q`$I!nkufl7B!wub=RbFTeo#v zw{=^$bz6VY>d(T#{CUqfpMM^o^!3l08NDY;?$1e|6?C69&ODFIel`dB$2pomt?>Ir zbF|+Izqj>Mt+s7>okJ&)&5V)CuXIXvr=fU>6k{>vh+Hh5 z32nBV%PCjokP`1ggeC;;`XzGj0()dI;&G2Q9E6uSSicI_nPmsFe8i|VXEW{aj(*kP z?3&C-G4pP-)&flx4$&Vvvr1E4I0lMM*!;so`m#eitEnyx3fLlKV3bI*8J8P6=Wr%t zWX3c?Yg^{2x@SAJM4eFvqK||w(=;B>%XIVW*fNuchS?MbGcxIhNv>)7YEcudf@U^V zaLC5eW{+w|0p`{aZ54(&2=nLEM|d2e_V>n>@u<19a7m6gV3?kpP4 zgOGh4Gc}OJP)vi`ilX$F3w(f13)zpzfiNp{=@1)gK4tM4*KaXaF%pR>5shM;!K4Th zNPZw&MWm%r-EvqkX2urfFbGY~v?+o13|8uR`Ifd3tVE924(PMpUNp*1*Z=*~L+?(#q5zI=&IbIP~Q{t1`s z#}EQ9ZQsCMFX-+HAC-4_azek&3Rh zGffiO*kVf+%cHG_|F$UobVMILK36|}vPzcB7_Km#A+D695wAq3xA~do zXR)c_>hL4}m#6Tj{oSGkf$d~1Hd`82b-ewi)Mo1QGJQT$mk1H8(T6|d$i(z1-v@<5p)zz02XD!ZJ zypIf$cEY4!OCh+4LSkqVP*{d48P0CTspDwuF$K2mOlU`@c8kl7!|M~;(2%f1ml^CO zpe(`xMlG|SQK=|;DGnbNNC9nT)CNKe*Wnr~f-R0VosdFd>6fS`G|r4VGU^$Y2AeXH z1>f};7a7Y;$O*rla4NK=$GVoQIB;ENbjS1e+G3((OomA#jV%}|3f3pV2aDC7Vp_0D zEEixtYjlAUN#vcAvY3Kc#TucQf;Ebz3gJHO=ji^fUWJ@sYvYob8Lx(1mQ@J!8w?{( ztJq~zjapEnD6!cR{gy7e-9AMy>geYsJ}wZg*|wU;s&AHt_R!-v!$r$W)0g@6qyK=ze8{Fb z=dnCxv|DBwnR8%OJULp7XZQL?jLFnpL#p#;M;bB4V6wr~6bjU5W;>B(L%XWtw<{jW zQu{iJK}&7)F|N*QH8sN-D$;vD(-lR0!D{AGuSiKL#juhM;h@rXR83aHC3duI;05JMubcX)eq^4M^N{I^BBqecf~?A%gsod)oW-RPn{S2Rk2_ety}sMJ zt=qbN|KHw!{%sqdkIOFp^BVsjhx`6G)bghlsXtEm1#XC)AEysIpLe|fy0!L4$dsSu z`o5_1|5o_Dt)FU5^GMgX6cpzz!?;DP0d6xfZtKrr!K^&fn)A7vQw1gO7KOHLS+Cbv zYgw&UFU&^X3vBZ|b9i`2jFD#NyfC+Y3Agq6wnU%!uX}9!zA0v&=Rbuf`J$BDof+-l z5~>c0uSjAe6dR$~YEIobtw6{{t1~zVVjNBr#w&AwjhY0p#f640I=15#-+uC2Y}e`k zXYb8^ElbktzTX$a9?o#b94c#I^~4@1wwfe3fD&cE1|dO)U_gN01i$&8@ZVv>ZwCBe z8+x$>3x-Tnl-(vNn-tk(H+y1tRae)L^Syb8GwmUU&ku3#&8%cq7hT!v>L$+uE>7Md z&)GY6MC{nHzO@$W3}JB0{VRO##xGGd2UJzh$?zwf4~FC_7Gq*L8mg>xat?MN$$;V^ zw z`?%z2 zBGEt{9WEJMiY05=Mp9vow<>2!PODCfibY#g1vHe+bu(<0qXw{r&n>qw`DNxVVq8)7tssw0^mv5_o2Y7C=Qj4w8tiDJ{547luZYM+vk;t>*dyT(pZ zGK~xIZ%BP4q)gUT(PN_+_U#MPYdqu zy+v$0tT&jmiq_7U#(l!!nm8sJ*K$00iU0KQA9L8>;_cykY*q_4_6$2lUeeD%=TP5r zfB6728)$%bJ;RMnsjFyuhV~R&DSf%1h!%ySQ3I*Q$D*i04K6{I1e<(OstX`%)C9yq zluXjh5F>Rp!&*huprc@=!Dc~{CFha2RZy!@M3ln#eY_ju;5$zC-enOMxCX}k1)Iqw zp+5>TrlC!OoLU=KDYUN`xS2N z-GbKe=JZWsALvM|J7s@-1#eo`?IkPsn2jsf-Pz(@px%+ZFOC8+78~XaeqE7bBJcH> zI?PnaxN6ZyI2`)M8w*Mmof@0NU)i7$w{*`PnDuq~NByZc+phYc6 zA~E3TP!yy=WoxG@C9e|UT4AbrL**?}?U4i2mBp%I>ZXicMj9pOgvk|HL#zylVp6Hp z$Xb+qV#>9)y~9Q+Jq6{Im#wkS%cv1Uq5vX*QUUEJVIq!RGru*MaueAy5*B9dNU z)o+SAHcC;qLs8P&;wmBKR4{t=Dxg<6tA=PHI?9}%1yNJ7d6jM6XGIk}F4d?yMjIJ? zA=e};K5p-P3Qv`<+bVG>WOO!Ve3)D`!&%&Rya5ua7q)7P5BarXrH*;|c{f_L2wTUBa^E#6O^SON?%v8Fag<)>KHl7r<(@ zBx=NFOC>d4YbtH9;&9dxasZRIWM*kwqXrv`^>f-+WDzmLdNIuB-7E``ny;hU0jHg?&sF z_K~(ibweOyY>lejX6`1e_GqCGK`hBSP{D|ST*jJ+#b8k_n@ZkzL`or-rfqX$kgeLf ztOZI01J~`7xBo8P(pEy0fvAvGF%yq7o(-1}651zRwv3GAI3r6JUD+7V`?_0Cz*4exN|P*hxE;oA+CASK0!81!stlG zV;X_l5l3H~SFAj3Kgv9iwnZbQkfTI_6fYQC?D`c{4Wj9~oj?BU1u}Hx92k5@OT+&7 zD)TfWC(Dox3k*IUa?^aC+uf`95u82ZkDLF%dHaMvJ^Mpu;~dv5xo{5|^CeLNmu5+t zlpJZH#v5PM)Omsp31c$Gfb2Hkci3Tv9d_8^Z{A+`b0q6u*GBo1IJWEE(f=Qc+N-bU zZK9w5{)0aIdH2L;T|A%7VE!?+5Vu{Wz7tMxnTZksI zw?1U{;E+50gf!eHup}-9#&JWtKWCB~Hho4-huzCX;YvdBWNnL0vgv>UpC}f}rVywY zP%T!HRue^;1yTG~?NVd5mYG&F6K4w5CXn60Xgdr6mtwJZ)N&nFEJNHtqhJ+BLt|R@29HT_ zd3wQgPsrUFgIn;<(brfzq1|)fH*EB*sF6}36YJ=U0t=XJ_V|1Af5LHpgf(ySy(eGg zL0)3AvTtt@$36UHpY!yP)A0$Z+90mj@&>PDW5HTPYm!)Of+m`4TjN63Pl+}WWh7RK zEJckp34tm(EK^b#&?YjZKwVEsNsAgNCQ?c`UlB#``(Gy2I%$bbG+x*NonMd9{mmvZ+rtxq+Py3Gu*&CLtUTKH^j5O%1W8);U&3I-iJUz2&|#R+S_poB9%^B4aTMN+gRg z+G0^W>VnXZR2Ai$%nVF2mVmkYXa|snG_OPZVc_Fc2(>`L9z$6`F)5pvCHQ6vVQ&d5> zcBP4ghNq;Ap-k#Zv2ZSIaCzV^D$hbBN-m_Ik%(1873NgYv)9$w3|-aH)g6l_V6$b~ z2`-n6S$&28y2}1cuvM9EE6`n0Btt2HQi1)|F)y8bo=Kduo}P1FpRk;rbL4OFmFCy^ zO!GxrH(^m-@YU{jSlI=#PPFSO`;T71`2~~xIpQs~X_)6DKFcp~phqmtIc=PBE}78{ z<$fiZZ1S~gQ`AtYFy@ZsB$5n731|y<-FNw_UgG*Y*om-kr!=N2Bw@(l62@$cEI;NP z;F9B3b$d(13mOE~QjH%aG7JORZ?la}y0$!b$>Ea4lE`+6Nw3PHq^=ERH#Emu&{B4Xfs{4VRQqk6|-)S*W^?DM*H{in`4H>1{;J<2Bz^4 zHy+?GZ&9^Cs>u^Ur-rP8*s4TFWP|81YFa)f6rsfEh%wV4&bHg|$ z#5-gSPAuA|Em@n2eR;g<<7unX9!hjaEJbr7j)Vm>kW64S0Tn^DjMpk`Ny*cR($97=`cvPO+4xQJoAR`gpb1tKcu zI`-q^B1<4mAmxOYDYxPm_~r21ycB;PM0nCX;t$8)V^u{~k~r9S_Qo6B(j~`s%4YT+ zkM_UC{iL{N#LRm9CNhmJtFgnj4o@cAfsG5;3~dip&Q#`-Bw%0g9=^j4JM6H-4m4g%2lipZ)%Ma`r{Z(C1aeA9M`QI)Og>yDOD&O6jjyL4VL^c<+Do^XW$r$2-OE z4m<3y!wx&_@G}LY4m4jYBt+SgrgqlR~H+MK6BKhEqZ#@1Uxhh0J zMz{HdMdfSNV)RPE<%<%{#A5ZQBV;WqJRCyYDsLT|k!FL2dK&{394>0j67t&m-)R0`%C#txt#d11%>Qr;M zt`UVcIE+R{n~BztsL`#G?Mf9`i0rzw17I|5Z5yw0ElXA~2+li35i&)IE=drp=uk5E z_NNt93s06K*^R{cWBSIh$|KgMVmZBiZ-Js{+-@}1(Q)WoZs;DPIYc%sZQf(n+~Mbs zehXLKK;L6pS6FXIO-GWRu3fPhE{R=WZ*{VT_{-(j zxHzhq%?|mp{d>H^myulYFulpQ+`pxhB}PkCsc2CuvK>pJg;*%L(1vINql*L^KoXk3 zC1DskoJ?@il2gy91ASi68c*w|_|T$KvX|9zod+GWqME6(AA9bIuH(GA2TmB`1>>Y6 zyB=?aJO+e>Bm-__NF5J0Z}I2r-{*UqZ_wqA%Znw;n+wEx#=SNDtqU&oJr>OaHo9hv zk#$~kDNBqwrH=y-$NM~4oKjDFnmDCi?=c;2GO-Ua8;5v@Z7R|vBR7lTrlhQm~^*5Eq%RW z(_EltV5E#SD8&l8&7IAXi>fT!lIe*dOUGyvB4JA+38D@)u8b^oWQio3u{mKo5B1g6-RkG|WIa)qof z%IgGMo8Bw+@Ka>C(hSN|)$bJnTu9z4!nb_>)jV9qnt$~AKc!vI`C;{K{&M_t*6Sr9 zBNghQ3}9Rs+_0 zJf#3EyOKTbOc~cDtGK9qvryJdfK|oBh?Q81m_*14OeiFyb5mlD80nBKv~dp~Yixj# zj$yK9^jo{(t-AeLN12!+zN)a^quQgI2pMARvEC3&B<8?6teM0bO&Q}LCCJ{BZCM}4 zm0Ee**RO1M73FB#l@pO5ZD^Y?GyIk!dMvh$e1JN77RjFbN@HWNYfKX8V6+ zJ2^zugfh;x%p-=PuC4l^osV?YuqMMg??cuPfP1l7z)yv{CukuiL& z#+O{aFGlb@JBwev?)1ew{B0szcGzKu-T42&d*?@xoImdQ#XCGNAI|D&>f zKkE3dteroI+09cEs-vJM6H-4m<4d zLI~zcSp|^61i)P92o~GXlIxqF*sdn*GQu51{%m7)s`R`CQ6b>)`%BCYX~J#SM7FF%o-3+pEG0& zB8W>QEjg*i8ocr3m@&!Xs1SXcMVZVq$}s`OVp4-kE%tKC9dn22P=g(L=-y*JU19f? zi&aORZZolaEV>2O_tZ^KpDtK85sj7!g4Kji8MZ2xXt*XZMok#!NI4^TT4O*HgVUnE zmB4C<&>SO@34O#OSOgO-G1eI4aMptgX)GCqd-Hu>n;)SUZxE(SPW6&;en?*3;fB7# z!Gq7@=QGAz13!59gqb(^#UZbr{~FO4+AsZ(H~Vi-y*eSVCa)m*Lzy4bO2=h!U)W>d*iMKZ~j^UaZK8|{yU ztcVj<<`Na9%2RZcan2I6feJuTTQQo%JJkXo&i(T@VSl7g1CvI%*gs>l2|P-V*hnB%p5DQR6+I)aNwhes z#hm(VkNx~bZtwpZH~A8m!wGbU)O#7ZaJ(}46rb&W8C@hUUpr@!zE0AboBgZ&=ktG# zjh=_MzsK+X@L$uJ5#uT{<94hK*ZHtzmJG$V`AR9M7O=%Vf$cn#9nG+Z;)r%+s5T5v zaVaxN7Ndscs>97&#%{xHeU(?=`8@S7;WC`_VD%pJ+s6!j&t!d@YG|2zWo$bx>dK}^#$71ShdXR15zKUvfUP$2+@M-4A(bU zNq8eA8a}1+ARiM}6sLl-vL)b(LNc06v@lvFn#@!^Y`t|_vJNOw0#cXxM5=McgGLw66&_jrEC^RD&2-#@ISFwY&c_qDHm-S@NiOw+~} zI1AD$qW5q6#>eMLX%(@oMf?$Eomz%W2-(kj2=A2U^xJxduD1pf;s=Kv$?c}b#rxkduduVT3u=Jq7EJ9BNyPH%0}zk#9$Vh>+^-LPz9?8t!{FE1IzUs~#e zW2*b}siU;`_ol*O>Uv!P$cES@mYqZvtRH5)<;^i98GojHQs(ye>E5_weuUk$_nHlv zRT{DCzcbn09@2;twf9?#wyxCP1DVSy$_3=h6BqP)`tB3(=thc-TYUXmPNI1hf9{Q0 zYrtqrfcmM!O^6MXa-xxP(8O#X6Cx}oR`zD=ff*FjNW;KU*I+Qe?O*L7l;L4p5y2<* zo4K4Bo$mC3bgSDt&&Jo}9eO0y`-G`iIdv)t>>N0b?b2dTEvsTfp{T27>qMK{zuh*F z&4*ZVtsC&klu7hXkNiC)izK@TtR9iA-cP<_<;{+ekp&GA3MswInTf-;Xsxn~xUxZP z?PW5{jSw!%JpIOq64z3yFxmWJLEvPsOAB{DkjbgO@*}Y$TjfF=*oPr}VLl7n+ zg)%soeyQ7M{?)|;$jfTGilATu;tRU?c*KS5z1aJo=BZcwf)*{s~cwA%WB`1$_UAAAp|t5U`eWZv~vlU5#E5#@6hKE+RO^_gN z$1nC|%G!ZJL27Tqr)iYbOPqfuOD^_YrsAi*VUpkE<&4$CI9yWcCHrkCEmFGKv&G?CpEg^y zf|8$YZ%cXh7YU}6{@w-H<}SKCK8V%YD!FB49L;!pmgS*RN91Nke;GV2`9+j&y+!qk z97r4{lH;nJw(901n^bpWz3+tkZ1KKni!CUN4Jf;au#C}?)%CYiI;GdX#9`N9Cz}*- zUqn~9jVS2!qp9D^*b14_U*Gofm!0);aT4x-0TVCmM<|+Mj``AO5Rac>`TDg;!JAzM z9@NPC^)x-2s_UEI%+H%o6I-#IBoxN>Vov_IM`x*$X}jzQ!} zmG@GyVB3zHo1H(pTQgwPOYgMbZ9FylnY%f&yLDZg4Srs>y14ncxw+y%DvdpGa5#-2KFK|0u>_GWyr59UE7`2LgppP&W$2V! zy3#XtKUgay`q3OVwQ;c>^8MHywGFm@tovEQ)Z9XvD?zFd=HL_ZnuoEtdEGaC6fw`t zpQ|AG2lV{skfRUBibzkBKXt`yXb>_`-*O|8_ktPkga1A%5gh-7zb~R;f`v@qfBDTB zr6p4VXYQwWUkg5SqV*AQboH1&OHC>C$5Sx1XC(Kc-l_~+ z^owYfYA(>ov3AafE4qLt2!|jSI!|5;o~J7=EX8@P=)9aU!J&AwANV;A?a})9BGy&| zvq>~g+vj2f+=1p9;0pKY$k4eHY+1Vh+Un*DzM2%=;DY9yfk@SXw=M%7c~g9(cn=*c z&Gs-+jl=JPpA){aG%+tDJ2MOVZnQXlYR$m=?uFWZ85|hy-h+({COn0w8 z)a#nlB4@+a!!%@JpK`@qQR%V{ZP$HGlk+iS|H)VZ>4?~wHSO4*x(wIYEnR$atYRM zQ=gVh6(uWgKwvfQ(L&Zb9EUvJvq;^Z1kxD_z^ab$kt~N^E#J{7W;=%r^stn%~-$tP+hrRBF3GBV>CE6jmrGB8(}l~<%kjomP_-9sic=u#K&mR>29Rd z#S1gXP!QwlsjFpQJW)!@{+7BSGeX$;2ob8~(_$1>57`$Jp&GX(4A6d`o`&T+dWhIE z{20@iYQreZLdP%gbyo+1_rUdttZ+k)kVVA-bN&U^LWrwW>*SQkd5)Z~p?r6$rDurx z?Z@NfwvnZCL?Xej3}0eYtwL(K5L^xm5G9BpHFfW48!i!-Neq_uBuSC?WX7YcvBZg& zr`-lcS>F$Ie46i3uM~4{pj?lRZ84~>t$1)-a$P5fz8{nG zoFL7C=|19xP6bR`u4H;fygI{2>oR$*W6E91iApP5%A&32<#9pzaM%g%D!C>P@#qG> zd?bq4hY%PA=xel%Ka%UHHKdRnT^^mT+xs@9x758w7gSX{AzlOuVJ2drC%h8!rI4ho zU-X(3Tdb-ji)*NDTs8}r7Ns<#Rp2bsaG{Gvv`#D35qC1!NN9gw7Oy`kSV^w6D{!syV zTMg>O2iXJ};By>w1-ny=FA2w!U;BDYmK{B>Y1zlJmAk8rrv5<1H|t>Ca+JAW?^BXn?T4LPIzN)!Q3Hnkx$j2>@(Fn=WV ziSug-Q>tj>0;yDP8aRZECFy^P$7wBVz#l8b;49zyc$!jvXa3vmoQ5#~Xw&quQ8FS? zL&PP?-Si7WeNockBMBqpN4MsC(i9GZqEO6!FYm9Y@fJD+5} z%{WrzWuqzrzT!&66_dvf$j72`vk0MPC8;qv+0+kCgGut^ZW1WcII(7|hRKIaP_J|z zts3>v6z{u2WrpYviTiIAhNfu<*mdZHoWeu9zhaPRDBwJ=MxU$H04o&OXLnkQ-;5-i zl1vn>qma1-w45)SH!|oOVDc@6p+QNZVrj%2Lph>P zOxPtEbK(}hNzykK;PITfZelr7mc6GiobK4h zhs3|OQUkh%L_*@#*I%{#!kf!z88$tOoZ3uDRX3M43S)g8X3ADL_ul8XU*-2-NE?m1 zm>q~>m=mW~^nKVY8e+((CA;j69HLS=ZLo(1BMnqO0m1&~{RMdIgZ@PI=naZwk$51+ zZvOOhj2$NhmLQXk%`A>^qq-kCnFRU7>EPh`l_Zr2cVY$2#SWJ9ni|RS{n`Kn$a8IL z896&iWTm?2Pgz;DU&PxUbk$!*sMBWS&2z=rrlu@xS#VqhnVR^XK{QV!hS@ zzqLEoV{&UYIN-D%4yKhW@W~9y<8b-#FX~z#blic9vY#b>k zyTf&H>4>>bN!3lQjHJZvH@qWOz0Bb`z1&6XgRystDkT~^`Ps%5GA3BhD*#6j8H&2N z7uFnR+S8a0dd$z{{RB+j@Qb`$kvKImsjlzi3FwTDCLjDc|8vmLw^J#TIdifbd$vS# zQ+70pK3s@_ipogu?EZq2yYY7yTg@pX$tcNCx z6=GG8!87tz9)vsEX0LsO-OSPtCdEBeRTEDyiETHy$?*1X5ln_IxQlRrY zkR+1ICqbN4-V6=BAgZSN@wFbP&UNvsVcb3u;b43XDWLgRM_o{X(iNKvrTG$76|x2c z?R6r#1Ln3rx-0HnvqO*QrDo3y%hgKT;B`tWycDejVwZDS|9GD1K!>@yJZ%YDR3rLm z24%qy?h!=9@yR&|@0UIs2K{Oy0i4Dk-e^7AfCtUgE+35e@&4@1M-2U(@DIN$GmMu2vWQsq?8@JZK1yJ{&w1G>9BQQFSE`+AcYNRlYQJ~Lm-ih+kKr?E zXGn5@B$d*BhT!DLGO*XGO)o@x$dIpwzK^KDyL6{%84jzhLJfB)hY7bSu*+X@-?O#X zz%jOAsUi2u^4;~3mSYtJjgkp&&Cjsr7U9FKzKyH&f_dc}B~56%ERDO!F8WpeB4Tm$ zaZN1xdmpyam07$ul`KF>_RKq|!Y8 zSzEdJsGDQ_z`Q$ z4a`o1)a*AyOeS8~J*JM&f{1R;17BrS#u=KDPO0PZ1raT4g9FOb?vUd$sv8^zZ!Cn& zIWFY0Ksm<_2>1oh4_ojqGGUrGI-e0t@)*1)zkS4XuKdVy9uZ!8&g zdo3_cV%zkov~!cDbo7Kft23+QbIO2=L1LN%OUt0=1!n;|r?aXN@fc=I;aR9NcH2vW>C4bYH9sy4K4HH^O*Ox@BCfvfJ@ z3rgeYX6&f4HAV`kC4Yv1Qp50J9Y`$itq>Al>S@TFd|~H?F>%q?dX(Tc%VVLw3j^N# zjQctyN+3lAv-T~ae;4r_>hLj?uPT8{8^$i2mZ^4Av$=G~-}f7HJ+x96R>a-MeJZj3 z+OZ_lQ+4Ur=ydP#bfI;BaRJ<8Ewm;~e+REnrJ^P*M1YW79@>%{ z!xaWGB;9F3Tdmk~etcT&)!Fw^({7ZB^Nm@lq$FQsOTRyBcvU`&^ozM14F-%XsgN0; z%03 ze!ov@b=TLN-h__?DHy*XmP=(Oi{RR}jV_%`j5iS1IS%z+Gt!8J`+fAj8A|1MOR1SR zNbbqL6S+i>;Hr$+F;l3BkyTAG+WVN)DHQ&0OD@1&`!3US{)J$?56{ou5T4W@DoPF3g}&$rML=T2idsV^7RsDomwOpa&e zEacRqHa8ZyT5O`cc@g^@8M8`EVkn1~B7(H^{R9CnvjeMlJaiwN!h14B?=-TsE9WEl zfMIa>Br1Z$42Y(psy>L zQBnvN{)kf}EbT#pc^q`1Ut2)aW5;U9b0?b6diOrJ$OyPKc=Cf4T=hHaf z=i-Y|QtPo3kp(5Nc~UdB_ss=4|1zYjhz9mNaCQW|-`z*>SNaXi=ON?`M37eGYQAO7 zoS_^%z4eDq`Jj+q0rvzU;6IlIBaq%HCkbz(b1QMCQ@;u&*)girRMp0Arb^gnW^c5% zHe$-7PY%@@c=~+>!n&^!(}TmiUHGDY#CJ+(;FTeWVMy)rW-t}Z@y%7fZ4kC0f_^9S zd#PolcPuTkNwO;3u#k;KNVzwW)*m&^Spz%Ebol$#%?tJ6#l~ZAlm@unzAk1vv$)bP zzaLm)pEoZAfJ0=1*L%k{VdW%+dYJ4L!x)ukp*K(OB-_DV7V)Xu$V3DVb$Mtw2O5Sr z-}i#=?TajL-lI2TcVw z;MCSQwtTawQfb=#-J;BzA>?KP{ecA~Ju|pY*HK0<@iC&+Go*FD=@s9j zF6dyf@xkt*+_4d;H^%#pD`>I%dBC`|Y~&=Wf+VKo+a6JbDJz!{pHKJW<@e)nUZM@J z8@gefizN@DqM)Yzkbg;G^}%v7ypxNWs?woX^`bpvv8}vz)9?{;Ss1KrTBO66aP6I= zv{vLazm?j0X?j0<1Xm8Herm35wfMbGw6c##Y)|{NNsLk?l|5gx4P^s$nJ5%O4P#dP zF{LZGkXKr0BX`i;QLYwVDPK|cYLv}V-jWZKrhD$Emcj-~@~~oJvKnNYT7o-3onf?4 zo77V;Eu16cCow)~f`fbHhZD8A)Ei%QhTQbC($;($bF`tGAFX$$h>OU%ny0-$@k$)K zO4b8NJ@-&b{CVXd>%5e2RjS=W?5) zt46m`Ph|Rq#JEQ3G3^Vx&u!Xlm3(?EpOmTSP&l{RTTjKTO9!h$-@ASdCNzSqXa}$_ z9W9CDG+GsA;r_yba-H;q{1A$(l8l&F#;cT)T1}{t3zfqvDmbjNLL$ZDHJgbpa(fZ* zjv2YO?4+`nHo}G>N-9wHyOqLFk|)Nlv(V7agG+J0cmDRT2wu5Rk>dC~YRfP`Nmxr4 z&=`>&zc{lBRh-#Bkt=C35qGAA$&`X;VtrV#!oPfrg*4A}cKu45v|ZkF|0L>Q44=oe_KR zxX@?r2TNt~xx0UAZEeZ5TfVxi(E*1FdbgL!wjtn5)S)kZ?Or*HExmjy%bPQUb2~z6 z+wjwcK}ullS;Tk)vtsONm|MbcVnypwZerb@dgJ&96idXBfzOkU)|a0Lp_r@h>e!mZ zF|o`MaYW*&fNsc^i)oA22^$Lr7RC|5=R~vS4{Ap*(yEr85ihOixDJmq3MUZiTCP!b z^)Y9!BE|`1p1;5=-XgFbRcz|*B^-$y=+y<^u)Pmfjvbq5D-K+f70V=9=;f-PfM2#5 zL!hH8X3Rl^Yhig|ukdRMda!n;ej(>CZpR56m@ZvR;tIcf*CS|cm#Z{pXVQ04iWsgx z<|J~A*Mz!8HhqRiaZLB)wQyi_;;BKbn0tYC1Q|79ZI=m}SS1iC4Zk}&Bsi^fdLk_w z#&x=jn2}pFTTk_%&(~r^S4tVP%f!_zN)3NA~HVwViNQdftRtT7im zNHwcQQxU~lb(YM1DA(SULeEA%alk{(3h1RNTsCG)(3f&N*hFlN$WsdZZ@nMQf?lazqsD^E|}HJX5x@d8S<@; zK^lY_JRr7R^l6cj$I4PwEZS=H#`CIwQ!3Be-qAJ#Z|O{DSl>W(J!d4)kk?el>eNj> zby(4138{G6QggCwG5@A*>=tgQ(=(n=p(wlIXe9X41~fVGde7<&TN@)&L0NSLfst-- zIbk%eRecsdkMvAdi}?!s;4cF&VP^X4vRe)_&(JBvaujL1MkV#(g`;Dmi`zM^sPqZ? zY8=Jg%4%FJv}1RFn>W)e?`)KeQdVO7Ed5x2>f+h5t8WCi;vBwJ03(43?`Fa&INV;% zF*d@TR4sN;-uhChW7NaUNYd~0H)u^D~) z<+X^ZW2)^$oDf~a1t}44k+mNryr&kwwCR)5UeNFe7_4WR8q$1~U2TCXZW$VO3(XyH zB1aH#q{#l^d(#|Slp~MA(TCZl63el*vOJ_S=&Zi$gRI#m_uHgk*vX=dDTR2_j2-_K zGHL)plxvH{BX98p@|HN7J7TUwsEvQ2vJ#dnluq|;>CESA{Bot(5N6UUH`zBrF*Pb% zj&1pEVYTtYJ=;vN;&+h3mLY*xS3@T7-TW9-7bD$kZGtjw;a; zS}8~ErE*jje9N-2+OIGnmKdkTH>r^eni<&{&7P3Qx-RpvbWP>Vf1Ga9BGqryW;_#= z^j~t#!F#Q40KyJdP^UQ!!SFz*m(JM2oVRHHn)x&6XYAd0hTUD1N%3XJUH|cXWxtA0^kh-qZ7w>e5Ac zxcvfiU_Sl^eiReq=<#T01oLI{@P$C{E)DtzsHy(QReV!M;W8!NvQ(>5fe9)v^T*_N zD#)#D)@=cG1DjirSZj{S0Mi%LIvj^Rd(#jpqvY9dYU`J;jW85nwY{rK7tM9cwM@-Z zB(!0Rf`yy5&_PY_JTVrCV&QHxUs^j<>%rzRiIXFRUOxy_tZfeMr`v?H*!}cYkR+(J zoU4V>I1_ntYkwBf6r-dS9zyReKUf)0NM{2jqq-p(Q6v>GGICIzrTuUUzgC*aG)Z^r zsV9DOHQ`WE>9Jl+53|&pDIgLOO%KFS zFc)ti$5;<@&5M3u7E@WniqLnyzpsIF*%W3GzR1rd!}&$&rd#>j?P*+ClFb82^$dkn_MQiE8e$$&+ljrKnbuOds_>HRGfBF{5=4|6GfnS$}<`j5{GvMkB;7TBc3Ex?T09 z2C1B=1fsinmPYu{w#S0+g9J{#^(5qZmOB{o45xRSx{Hq5##b3l(F7kueES9UUb8i) zamB*aW|a@BZEe z;N(I(*vaT~*8D=Hr&Q+1@r4x?SuQ=Bbs#04Z!C!-Wx6!C@~29uu;MI3u>Y#0;>U!7 zf=mmU*zbV_bPO^H{B})U=Y|n`&stG_wr)1KIuSOV!oq0B6=g)wW?%D0faq0qjl4q$ z@rxRSB$A7)2@s-=JW6kx*>*VTpQFGa<8keXlF8T`>_g{2^3mI6Cm%RB=P~=?#Bb~* zu1eNCB|b({`;KTi>Snr{-mY_ohtV&It(MU1WftQo4FI17|k_rI!fM0m&M zcbf0=Jl0GV*8(d$tkYd$W|~VCt3P?d{*%+01BB6Ho=1Emk@W)x7DO4b&^QTKx6#qG zS)hliPn?tpFLnacr8z5@(AmU72j#c*Y^8+Di#ws2{BLmFmm$B|Tr@LL#;J@n%&e1; z<~E49$Mz#6#C2p18>5ATd0~A+<`Gq+0M3Ut3 zrcxz*3!UN|S+&=ePuyN;t-AOYX=ly8PI>u9oJfX+?ku?e?rao>HAz2-lCy6p!(d*j zYzw!-y-D1P$jIdS)=&}4tKOhQJZT#?D4smYYxIK97mglhnd-k#uj2A8m<=(+^=B;i zNUExC9*66fdDY+OZbyd!l6dBc>MzP0?51uI)V}zgp_SPLt(7hKLKNWy_W1;xf8fWB zw`pc_#7=zWLhV^Ar^j7s{C9NV1u{MJ`|I)x{GF43SW`XP0f{)Tg%&w$ZrM92RzmG8 zv{*U0wE+Ah<~BsA5&w!2sxM>WcwLVoWU5lvV$?K(NpD%fnAnyuss@>o{qyRHMn^*q z-HVXsjfaN%K1JmfIT3E^0`d@YaWw3N1J=+{xlTEn_W=aBIXs>2zCrz;NqwnyQF(md=iD6jLsfzE%<%T8=kmIxsN$tHn*1 z{dgWtWsEJyygbEd&Qx;s8155MFrO2K7pr|+bAlWNQY^b2X#oP$O6Y-4vGyIht+)PE z{x^Bo_B?7FFqPKe}QpI$P6eExjLBosJJT;tpi1)ww2^@Z{Zgm#4)G>cCrwDEa5hpNAiTi&vU&{yGTe16MW zF*Cb3d}ZHqrKQ(O4kuxlDgfIhm8Ul9G{l)RC*ACAH?7zc9`UjIR=KiQk! zVx6_EElbJ>^-%QEl5SCvkw8XuZLOFt3=>5 z{J6S}?kNBJocb3>{G)#RhwADApwjZ2$4pKoY!|VLWT0potXNG+W<~wqkM%5x52?Qe zhW_*KwS%|MLD|&12#wM-q0IQklF>h!$_UT{@TV?3NYDd%9Au~1PG6w>nJMt+4aHLb z=P`@lozOuH(uD#;5Kpjbd^s~>DZ8oWm(CToTxyi-(|-pL{(bSkH1(g+Y*y#ZGdA|G z&st7@(eYhOEAOZB%V@@X?a1gGG2y=!!_m z<9`CiKg0hHqk#RlkBj2O{VJ+{weg(>U!B66%A}&78>0fXnkc03!^BflQ&(EeJv~#d zz2vdQzMA|uGb=0Y2cLs@D3cXF<3i*=tMTk14oirCb-lF`q% zbTS%=#4w9zP)gZ-JHKX8A1}w`?Z8cM|L(_YJ07r8Tz*!aOOFGp^G0#a?6eDzzEMbx zYbnQ5W={kb6+Ic(nqouKj5jFFEh7qLz8`UJkV5y47SG0<)rwUbHe>zr<%`8)d=@o6 zdH~RQrK+(pXg2xUYjkuJT~$>P!Y(&e(cCDG}`2@r;%AM+TFX!IS7?JgIi`ZuI zjTok8Jafj_U{wipv(9EhE4#MO^CM;Rzbjp{b?_DI&s3?d#r@e1aT#@ikAUDsQqkv+ zf_xwO4#V0`{zxAG{PCa@5;tupPsA0LmKMj3liu$R1Q|FXleao@Ln*|Vrf7&NlH ztk=H4^E|DzcK_(8y0Wr!bJOh6Lkpx;GBgN#3{?D=~V~*p^P47XgSty-eqw)SFnPRQjewt10KCcDbpavAe8b^J;=4 zA9%B(^hpN-#?M%w+2w1$x24SfT;aF-bFT>yulhLKI+vG8HRDfy(Usdj-ot^Xx~~O& zut+YFAyEtF3J-!cjBSU(@QqPF=`XnRq#2d=;&+>{WKstUuyPKuprfPPk5)D|4%$6z z+Bxn_Qu>^6g0YVHVJC@BTcZwcZf>gAo3F>wj#T3*Z5A(&fbUr9O%`>RmW-;Z+tF>6 z{$GRoKT9(M{1aQOGvs62famfVDJl5Qfoh88$+eXj2O)eWZp6}){A*rW^HrV_J>ILf z)41~EyR)&g6<>_1%F2lsJ}|C48||VZa;Y~}^u`=14kv4352qg=quJyDr+!w?{og&u264lYwORdI71s%7~}yKE{fPa4#P>T=5vdSu$YWH3jK#)%1=Ti z2*ebPAX+r7dr@R-(1%6vP_9gZ#bVvq6+>{=*gjzERrE=+RNnE9)CwdwSOF!_&ztW2 zi6qauIQLg6{#)N)_^^wdvFhF2r0QOcB)hF7dryQeL{kyJYVu54SzVQEQAPSfsx;Hc z30sWsdOfD)?sTZeX2?t6!>_Z{9cO7>2%DVmZ1RTVpwk$Czy9NeJ}Y6^)qsRR7nTBF zXQSs)?<_m?;j+HbdFM^W&2;|Nu6p|~qso;D2{KAKlj}*UfVI{!%n|X@Y&WFD`^BlME`Hkqt?4VyE}2R5j}cbZ~fJ@ zG!nCFf|$XakE^K^QW=%RRt6svWKx~HIqV0d<)d>jhy&hC{Xbu?L$j%7pJU^CGxVOZ z4_{|73znEg4R}hYTbGx>*6<N_x^9=@0s_~A3a67YAG2du zy^lP}vL~K{7-l_M)JxP}WKUeNksnxS_ag~jWeVWm9d{qCw|lM109!5Lz8)okAJJc; zMu(0b9tgt*F%+wIy75s4XHBt8ruQ0&C8K}-^;%5VW{*!lk^&h(?WQtrZtg$GgpUdo z1WXx897_O@!@v8TRJ5XM+`jI=dvFpDS1X*&*~tGlTD^3TN$$&vHDgPDZ7veL@kX^C zwNDvw`OF;rV6FlB zeS(Y+jME1J#PGNyc>h7*c7Dv!&Fy6e5Pt;WPJ;a#LkZUlkhZ>8;9C;L-=66a;5(St z`g^j~{rPGQ&>wRIKWu?V%>~W~^xCfYN$;cJ$JK(j)n3QGWU>5zaqbXT@7t;CVJo0z z{eyggoE;WyMjRmmIzS0>$iulu(-V#w-f(u)mj&CJx z>%o<;2T9;K+w0IN1GbT%Z{*}8o!pmWDXfa~L}PE9aJR{XYuLU_tguYQ1(J}^ChMdb zpJNHQBi9ynaF(6@-H4q}Ocnk0*5h4<6M%;4o`>8I_0R{B(S7T)P7I&O2%qz8uagk{ zb?~F0z#!lRws})DHjAf8V_yE?N3w_a3O?)Icf(^qE3wlL;I8&t*T-<^{StJe%kQkp z75RVQ(X+G`j%1K_hxpgKYzG~=&DjW_gjWp{go&emcprWVpNF;!H~s=JZ|wdA+=t)2 zznuv1S2KzJ7T7nW3DP3fQD?S1jWS8uAGPt4pe6H-c+?(W;i6XPc;E;6Ym zZa>Skv*td}FetvstVJY_;J?I&0x<&s#%y|-Eb6Qx+L~D|R}g2f;_&q_VDg;KjXgWKNtFoox*{fVtB>}fZUB;sl!+~Th&_K zEg^WLxW=_nopDd^o(^j@XGuDqi13LeyPqIyJ=_!50^x?d0HP9rZ>yc80O$sgdc6F~ z7W8BwB$!Lef>0(}blOFR*fQ21_(j1{Aunk};ocvB?d$7fKmwwQc%iLWeJ$=5u>&zH zKI)T1`Fz0pi2K*wM*+b3&g|dX%HIcL*1ucBOOo&7d$@uPZ#k9JhKj#mz8-ZwO*`_E zxTODY{{P1Fo)oHJ@>C}_IRxjE&tIF0G=Op&{l)+pcx?DXhyW(21&UST+PcBFdTd(0 zEi<>n&WzplEq*t-pPF3;ik!sF%3q}D%7QB=`ctLu8!^JA@z z%wnCW;ayn%Ww>!w3EjnAr0tYgkiT+!IkJRePhTJ6llJ3R z?Hzx@9zX$$XaRm)G5ah1FXQ`f1#VM6D1N_28aX2_WtWP!Kl}|)V|-(`)4>moj}N!k zOHiQesJy(}ktb9peG7oZ_CAj%TuRatY-pq0z?c{US8vDo&QKNjFR%q4&jc|#yadeo zl34I_@`;{EcUsjNu@N3mD=PquXW&op0Y2iM-oBZ#w2xFj`=;N4?80`jPQe?9oB&*3 z5_GIqs;V-l$v4`sK5I7rk~p@-ceUaRWF__wckVz`6;mAe|62kOw*QdMrT$MtRr`x4 z4?PNZ&m#mMxE2=|O*H#H2%I2aUS4tm3}=Ys^Z>{SuSCeKY3}foE-}r?Cgx5c46w>=$!FyL3@Ugwy~fB!bA)j9#SUxK{Wzz?Q>K-}jM4$gqywnAYFkLL=|$OEkZEbDKKf`DqZqD%<@ zjLEYEavs2IC&!wbn}JI8ia_)LP$S8?)UDfCFXSfX@lIk{E2I{;lpU~T9Y*)V>-JS` z=nXEAHDZ9Ty6>(69*}{LJ^_-1v$%3E;EL0ZjEd=~=kmqNBM(UPP1q}!{4i!a$&CLp z<^N{m#(TVsC5Bnva*9HBJJ&x@g$iP@S!5xNu$wEZv(W|;ZZ004HP(!4)Chqa>i+)z z0>Ovj$GvX?z8rGOu}Z}0!+*j)kkjXvfwVkb*5~j=qDAkH1wDRLn~zo0*80KIi;9ky zjYEZKC^c*U8}>g=^XpIVwDq;#5Wbu3>=tO?v+cj9{|MgC;B z>2NAigv9FqHl-i0Nk9w$8{-?hUWT_JbwD2upjFMyi|~uq^gPSCr6p4)e0!)jJcJeADxFy?PBX*#2A$t`v5r!1Y7fk^akS65my2Ede-FAg!c2?~1Uel? zKyzY~YurlrY}y@`&K$XbC6wAw|02%CF7}e**w%ZGf(eV9Ao|`Q4yu{$ariBkw!`B4 z?Ln@Z9%1p)+bhk93u5|63&<6sKHUGU=x=(-Rjb1Y$V(QbL0N%7Jo_nAwzRO2RT8`> z0A?cupm3aW*Z)ham3zw(1flLzLhDd*rw)jLHn{oI(ZVZy83HVhyd z)*SDH&ux|-fNUFa#6>s86u@;rMRNeo4$-&nRW~X#_o|5nVy*&m7Bgax9_nqhC)ubb zlVf5K02H!ZNY2uz1eC_~1lNlzl8Am{Vq$~Pr*Gwye^pTou`JZJIuu?ldfiR_5sb7z zYg~Dj$qyP;8uXIUvVH9hA^n1!zaO)yvn&Zu`HuR9qABjd7y;cr8DB;Lkh;CSm8FV- z)M9uZ0rs@vI8TNp{4sdZ`wj)_)Xt!DpKh}Vych?+Yi+q&I{G6r{qg$1td}l}5ejPz z{93hrS|RXsKnHYeqzEQIo%s&r2Sr7Domt-P-L0KlP$Hcb2~3+sB~=_P5D*Fhlm?R4 z^et-BvfI1k`L0B}Mc~Bm=|EM9-Px&H>jR*-d<9;jX%+UXggv|Gfzvv`hd zw=*v{^|~Jr!oC8qKFLNI4r`-7)wM@*@0M_8_|n`M$~OksIx3>?)OAWq2&Sm(Z3mFe zmusix0ff9ts}xZ0D3GOTfUn{oA}F<3hi^lKwo0)zhwf0$+z3gC0*3$W!r|NB z96Am5nU85>`-h)ZUwruRffJRlZAQ1rIjFRh;cJ_vJ6A!Nc=p3j*AKat!L{*umKMqW zod%y2v90aws&zIw`5!_iPtT_mSd(NM+)j)hJ@LdQGCBZqtcVRjqZSB|+o*%vW* zLere?O(0b&#-?=zPtuaKQHjfacL-h%4yuF(!kS`=xcU% zwhy@d9xok&_sj$dNuuSr9(w=HxV8*bQu{}jfw;8)qw9%k5g-jcS$AKC9~JD~ z+=gR~Ggwb)0bhi@55|_uA9c4%Fd*QFmEQjqp1-QiLXeB*+m;E@qI+>ld2bB_#!0 z%;BcB@4gLJOi{3Hu}+Mp*MO5wLgKX<$FY?uHNDJHjh#ZiV09 zevq0Z1NWr3mif?yg8v6}JxlNDnb4i^{~SBi*et%Vx+wKKu2H)uR!+`SU*bftyI#+Z z9Cmkho*uK~-kMuprW!kYaQZz0B(s2h0NLMR>!S~2+qsfpJ&qVB{PywQ^Ufz@4qUMP z_bvc$3N!wf;n$Hbv0|4!tLS0t>p2Gj#xV3qB&c1yw*IFKuCo?WZP@EcauTM`Cm8Ss(9dB41zN*#zqhnxbGA6W~k=?(Z{etDb4Bh>9JsJ*uEs7@e9R@T0;_CYJX7FKgXz93z7a#RT zYBnQB2OfD{}Tz@zP0z^Y`Yfyf8B~qILU9n(x2$YwSEFg?T>ctk;_=Th{3&RG59J&|@0B4>fO zfUDqTOP^9HzFowK0a)>5Z%_a6T4fQ6P*dHKUr5N<$mqHeRsx&e3LtaF9M}m$Lpw8| z8B0g|fBt;(Ra<>q1^*_9>Z$Ut5$(T3a{{*nkB67H6eI2ZoHE*OAPRH#DcUVHl}=Zo zzl1&h8)dfBU`PNFIk&t9xS++mHuw2x?1*_sPY*ia)>Qe@1}`devMxKHhj=A6U}s$O zwZ+COF={ibpCnBo4IjHbv!igRHJcGO%i0I?!<3Kg;Fo!^NtGsmI&lqMQClq(5Wasy z*ezOUXR{~A#|OGT{yU_D%VvWqRC2F?Fx6XHuj-+Wd@cmp%A1-7#>dB1FfrT20=CHw zMwDw4od@lpJ)3h;OGjV)UINHgQ33I) zO#2c0H-&f;J+JNJKPP*H(8V0EoOB#k`iYTV#9y6UTzgQBcJ{s^238q5Nkv$F$timK zq}BM#Hh<~lyL@kwe#=c>?6WRDX4)HQIpGmKjuD-_(-`SR>dQ^VLMeMIpeH%9XDXpk zEBS}U5Dwbq1J!VCK{Tf1A&P36*jBW-n{8r2)lM*P zS`G+@w#y^DicSeo73ZZ7cnwlYC}=`5T?f8ec2`&>t$hCU>*SDRhQ;_i;1Y+piRvq; z8=sk>0Y|V?b<<3q*(B`vco|#;751+hu{H2#OwW+aHO}Yaap7gN{**J}-%v11EG;)a zN7DnNL6A+(g~aECl;ho4^n4Im#hp#N_Nx`o2H{8OpxTyDlb7Gs(iVUf zE2I}wSa+cM42v=2UbK1Fre%2i**`fM@KT?AkXG6Jxn_u2*sH}df=zVoP_I;gdS>ds z7oTIB*ui5xfQi6O$1KKf@{DS|XzsZ+-S{ehg5Yy;Kxa=)i}r5uZEx|f?l7McWns)} z*VzYnuxZaN9UVQqz|^~J_T(c27aR;<1D<3>dGiS`gmG+LD@%o4l zf~y|~OwXBv!3h~!h2dRRS2tOTQ=8hB{o-R0x@fFYh@YRIH??EA`oEam4PvJGSyTjD)k4|()7vJ z^4-*EaJ!2mTuY$$DcZf=hI`lC{pv#mdWbhz0YMbg@&MU0oPs>xvlwlwgN>M=>g zn;2`1-}Y!%zcZwBr$4|*ijn2PH*Yl7KuVWx)f*)k_@ND6XL@>Q81Hd&LAh8wI{FB1 z?7;yKZ0NAMYfXrT5Kft)fg4cte>Miy3Dy+KYrvi8$6ht|JLE^vq&zo zQ7DH}yGkgrbE`PNsVRMyzYDOP9u-Y2_Z_2^{STMJ2XjC7+=*f`oMetf#NN7kvA^i9 z#_8&`eRJVwT~gY_i#~*T>Qy_B-Su%lY;(V22UYEN*Jh?p^FKJ3ZmEJIcYmute+)=B zY*Oonq>;Y>A0D)TwOYV4OziK8%{ zNt3AF$6>4(K|oIDi(+~_uG~lNZ)_Q4JBn`ypg5z%^cjr%{Lx2j@1lzlIDWLnnSJ%K zQRfb>p4M$|;a5zuVgbQ|CCGhPURuP>Dg;!<0W&ar+^)iyN)gD!e{0$AvS-A#hYQXPc8rq z62*Ne`tPpP>8V%2fkM1ccnpgBf-qDfy{ch`Q-Cae+^=l|)rrz|2|VYFHNEo-mmu$b zTGIxmpm@v7_Uyb*yJf&m^~F({j?%*MU|QjS7)lHK7!Hp%LRZ8+(!mp%ITkmw`Ln;i zlJZEmaiRtj<1kA!pL$d4&nf!5;mX6Q_MLeHRQ2{0KcMmY4IiIXGP9v{v#sxR5KR$P zBP4L2Evk{2bE(rlh>6VLdW|oEn3L1A`+_sAaeWCu9s!sL2vCP)7P>FZRHMHeWo_C2 zI^^!|uHJg@)-S+Ue$CszJGQDc8mL(4u?B~?1&uMK6o0&YqCz$A3?UcAQ6|zlUsD9+b%pn)2Fx(P`_rE%6mNtKOyvHlVu4{7^A(_>D=0MivRjvQ= z%7@IL^K-B2>gp1VTq2_r*7SX&uP1iYvIK#Rh-V9#V;~!}p~9`SWIOEO^86 zx+v8zmd5z7t(wcDJ6m`Jrl4elR@kZMwU-Q_CUTV@X}1A{x}Qoc$-R#ZK;Z^?bMx~j(6 zMeJ)g-|#XzyOi?Y2M-esZ#{`PUi+e%*G@Wn#Wr4{QWRcaS`0wx)duc;*tjZOT9_%R z{zU;_qD6FI)j`+$*aSZ7e9hT;E6f8Q_%|RHo{EglYyQ$Ytp9d-qKIP?D3eU)Zvhq(;2g{nE&edtE!p!;6RG{``57*~%zxfB;*~ z+ifa#UmC_-g;rX;kNbpnyJ@^+^_zMp2I%#s_p4k{9yafFYr(B)Zx-g#!?h~Km~mD+epzMG(_n!wRt@WR z;A6!q5rY{nIXxL(D?Hn=LxO6SJ`QAU=EgXjOf(K6&|7KO=snt(_D`JshstM0WiJ{p zL{lylOYbRTO->ms>{{2<)q%}@Hg0oHAbPP#@t2St%Bzu%Lq`0TZug1PAiJQzg5G(d zPiN^_Z|T(cBesytJGTPu9$Wz8x(=l4SNgX2@hFIJ_eH5V&4s^`&7g?dL2hBgZ#&f{ zJu3tIuxXk??>pBYKeqWDgZ|Q%4`E|SCAT(bGM>ob`|J?HX6M|hrZz`?n8$WiEB z^!fC(T%azKs^0*2f!U2x`CY+?0sL1wdV43rCj~LSX{Fm71)6@R*ys5djQ~|ae6ESP zrKKBd%*6hC`n7+roakGr6XnDj8W}BqHqwbVQM>8eUgrs&uM>|Y({8qTpW>>)V1>qDvv$>c6PbhdlR$=Hfmii zxA$UHugf1M5p_7cHJ8P6Xu0@FyCQ9`v&fF%6I?&k4yRUy5_~~yR)uMy0IkK z?tbV^t=kPg_g;19n#T0dCa=*%bzkCrknlZ|m6nd${|yNlhd))Q3fuX%%T>|KR6&>T zSyFn-{U#+r(S?wD!~O--r|wD=RGxP3VswteRiUTZ8V=OjN%~Ci950#m^B7=rLc3 zOVC@cx4b=?ZTG68(w>NGTXVcbBT%Lw-hmePgObYnQh7kcXt_88=(1}wO@eszvU6aa z#<<1p$1Q9%pFS!m&@eVLi%CkNLw$f3Q7zGC>IxIv38gcWl)N=IHWuxVZ=`C>Gw##k z8+o@=o;^N*8xYm5ex2S&AzI$qdru2FZmAj7ua`_;oS#a)zi9 zon7(}j~m_8cB}+Oogw#^mX|YB3loLhI0A7VM5FG8OY(ahu+qm!&oDe~elt~juSqvz z(yDol1n+1l@iMcFZBy#{yDNoirS$MU@!o@CcDl3685i#5UZ>9X4i0V`#WltUuf39q zqeNMD*ES+_%27e|tWPC_gk8ELsqAOE4mb72eH$CExgY+;?m+K=?4J%-dIve(!HW#- zxRKk;*jIfb&1v6{=u?vf-@}nWyCr7+Lo+jqNT8V95TmYT!|4_oA#>Ts;)HXo4qflM zx}@~Nk^R27YJ6 zhB((bdNb8Zb(fZw6ciQTNoGYY{qCahkxduzQeec_c3Y0KnyOXwCLoWv{dQr&kiRP? zI$D7_j#aB#7PoZ4D`amJYFCjF|Ht?^F4ir!-X$kKvi@Y=h|Nu_Np-bZfo7csXTm62 zfz%IXX>O7{qyFs%At52~tE124UcNLN$&`rBzqyp;Ua+y}-ef<39oSx^+mwX!KtP`- zxd+~Q`+ID@)WJ{@Ed#;xt(3w9uQE(2jh!>h>^u{@qrCLRL}B)uG65LjnxUx0c4IEQ zP+z4C-;cgS)o&OCSpr+m_qXiNEPrUa$*V9c`-|VJD^=r5S^MJdmb>qEZq6;BEK@b5 z*GaT{dfxw$-EV4Ys@_Y0ut7Nd-#^yxqYe{QmI=y{EOF15tB$n&wft?%?%6Smy?LaJ zs*q;NjXW*9Mt9ZcZmMd8WHB8+79N&=kfh<7)2&8w3XE9whdk8tj8}a;g_30H9R(h= z>MJn!288H_Ri2zys`L6_vNMd2ot#>n+o`^K)t)Pty!Nw-1-jEB7|C6WJKZR+gGn=3 z0jUgy$L7P7B1d!A>n=hnlg+>4V&A#K@G@;_r;8#_JP=2{SXDlS@115b=$&(p0*O3t zNM65wP0PT*>AJ0NVPSDWLt=vKvF~GZ!4Uc68anNN{qe)+0>8vKv%E!w@So__rXK&U z#i;$b6FcL1TXmlGE<<+Hp)@&D)5iA-Vgik34T%#NA3&eaVL(+@hMwS!({cw757RQI zmrWp5eq7m`?U7b1;iN7iVG0YUR#b4nV6kc3;efw*TA)zwxUM8}dFF6&wknFO+vmc< za&^`)GXCfY(MicmZ?B`#^b3Ebf+eJH|83YZ==$)0Rj)ba>^(NW%KYi0(QjNUQZM(7qLH#c+BUG_ zABg9pl>Y808k47WMMYr-?eEKNW<^SxPb?%O z$mNF8gdt3F!|y47K_}|UtoP|d2so@jw=n+t_GEFdv7hb#epbXi%*BlU$!-HN;xyYzHw6k)ea9DFV)Dl$I#w{A6A5fB@Tf4ujGhqPQh?4`)@jjWMwB)+Pma-Xf` zj6=_B|Gvk;W|WQrH#axzc2GLsJ$dW2F%EU(^4NNc51H7#aV&KgCmWM3J}tBZ)7HH6 zwjb$U#1EGlh+9}%j%@712i-{+$Q(@5jT8;O6(Q< zMmzXB-FKV9^XuA379fJy@T+umbVuj+G^?$c4#%EQzMZs^1YlBC(6tCv2dK+?v{gJu ziQS|ZA1M$<`~}zrjXU2gzC}>H1lX1>#)lhRW{G;_DME4o{(TThAtYQ?Rn=k04*LQp z@H*JsGC9=T-1qZFVb8akbIEv^S80ZWnX$UpvqJwAH+jJHGx+F|SzK>sQjA0|Wi>5& z=}KFws}HE9LVbADI?6b4`z5xcLj$AN9Z)N~aCgdgnjPW5GCqeo&O7Ej~V9G#?T^(*ERe_}AVWbvc#hxhpMlvPMHG zzm2YCT7Dsy#1+iee6&D)Kg(7EhNdzE*xYuFZ()`F`6r91o!ws^!ko$s=)m?na+-2 zyk%lKG8`k0#7DhD$1a0oJ~widqzw$HM$}U_Eys%zt+J1xTe)sE9TIVxV%@xXbN5|o zcDBC)qf9c-o9)x{@4{lmsxeVf@8Fov9rOf0V6Z5rl@CF>u4@^AkTw0jz)uqX{mbiD zlN0#i-yR6Ub0m+D5+QRJBCk6PGL2PdegErEyj*q#ddShFu6kA;bSGWiN2DbFhSRHi zQHhBNaE8~}6}lVVxfcwqFU5!YGQX$@3ql6+dF`v1ue7v6r>&(5lzTU@kIoWwTKq9| z!bA<2mK_C%xy$bNN1;88Rob{2c z+k(!Ukq0Y=AI4lrq~{{03-SI3y}9AdYlv}_AX6qY_q{|dbLNkIow1x;;aHjZi041| zCaW_7GEHb6JjvL3qf9zhI*$@)Bji+B2nW+k8JN)lFttJbK<6|zHh#`4Sc+n?yba+2 zcu;TNJiO)i)LyM^uF9KR2g&F>C@}y~>mhVx4PqIQVV0i@3aFs_k8=P! z!q3LYRIv@BK9Low2|e+7^X5&8R`(!1K8B)-O2DL5Zhd`HI4SSNy%@LT=`U)Jo!}Dxp%jTV8H=92%Y~M-JEGk z7M=DcMY56r&yUW%0Sycw+0~er59gCCOXg3g{Llm2VdFf?l}-E_P4~ihwG|SRflv<= zN{slxY;2d~)V}8{(rA#??+u>TE`+cUiF!AFF}c4~6zNNfb*o5P`iH98i?Kr0LONlV z(C?gP`T6;jOiaN^NhI*zh$kmg*qELcj>#yY^dBpzs7T1mDs1|GP z?Dnx`DKpp2zb9S$Rl|l!z^dQok6u9}YT8c(l+eR@Yeo*p*Q0uzj00Ss)xBf&Mpt$u z{P#f6xdRwmTAFv1@9ybViy4r$MrgaTNnGd&eG+>s1M9;X*O4S)rRhL)0Iwp^S(SwD zwaeW77VCTAsN`5B#oznx(l1^td?U4?B?;$%7o?X@>Hhley4z-X7ZJAwzG+MVlH`jJ zxrjZE=wBY!vWe>)|7FvX%J4q;3g&-i0n%K3Th5m0X52R(ehVW;EPl7uX}PoYgI^y- zeMF+n)mL;?Ra7!Y*NtPIdyTPt%~#AapRCAH{t%41*HJ9#V0ZOj$4C}1GGGeXDsJ}n z8~`W6!m!|Ai!y%jrYuA^lnSzozTgKDTJP=d0+it}8v5hB2yb3mI^*Yhbag)TfuD>5 zWH`{#VJ>B7XFpfMUce@GZqSL&WsVDhVWC+Z?;oiC;*kX7#2@E^Y9+Y8|71Py-v%n; z?95ZZ>30Y3tmpN!=$b!=r*88BgvL^ln#H*qm8P(o!7%Pe%8jHFe=&9I0eFJ57qS39 zH0m9hdU|@Wh#tSKh9dw!ElchC9@czPEo5S0p&!M}fhe#dp#qUsFJMXl{K zm((s`L`TQeDY(4FbG`sWB2I>`D-%U}GN3wo{T5ba;8&Q-(I{Q50TneJiP>f^y7B_l zh8+l!J>qxaYN&fLJsr^Zp3BHY4?Jg(PoZREW19&l3{}+9dSP#0k@Cy;hOE5&w|U#{ zI%Zbg7xL-!qM{V(D2E z*j(EH|KYG!BA*@gbc2f-SaxTBYAJxl%w;06BZGNXx6wqcl=v za-xB9x_u)N;`1g~h3bJvCUkffnw^tlclxL1Mc{iNC7+bVvLwSFCl4q+Wl6#VK<%ks zN9LbXI}s>B6Zh+n8Dv82^+0raMt$%2tBPJQ1x}zznv0A~h|nF(&Nq*VIt+zwu5!PdwvF@&NrR@UYy>%xj_R-<_qSo<9@N4O$_bfA$yv(qNi!-*~YW(jeTM zbkiDS>G2L{JlKrjJ6i!|T*0CcNhvB~g}2)da>cR$l|Z(51`_Qyf-iOlc3x&ZEs(_X zhPmstlM}aziHRqOHbvTX(J)%@f}gETl+$!}c3RCeCc+cnp-wj2@%djv4EN~rnzzrl zt!2t7L8Eda*vAzjoNs<|9b2Wv#y)%fn(6rFO=T5TT%5q3p1!Q{<>-Y#sFx{gUU)Ik zMx@Q!;8VkEA0HpXddR$Z(bL@>$?eoyivBcb#5}vYIv##})45@32nYs1JCGUVy+zDk zrc%?|LG8Pk_E@}9gHkwv*WBO6zVLIK&wMeIKuXDgNBo{@Q97=PO)lVkwzt>g<^Np;S5VKZk0fq8573jLVNe% zV7$e>)_;NR^8#a0<%41hOraHqwm@@`DwUVN{?A=lBt0Sy4p&A}iJOmozOSKi{KaNA zO@q^{0ze@Gbxlp_0|Elz0A%2|m`U#{TOWB}w9g48K`w0M|&1rxwOnIn{eXEJGcc7A1 zK>85rP14&TIM*_8ic44i0Bp2Gl`QwMwPXYHOab&@ns9aVXBB3{wEXG8pB?w62`iqT zUtWvDK;rW}+Lqu6+5dBidvqwqIQ+~sg_8QF!PbuJk`PeDrPWnVXrPU{Y;kdMz(Wzs zL9@!L_22ra2~Sr0JmtfO;V@`o($l-(b&SPtQWCPVr;*_VY8S=C#4P7tAzYOUeeZYT z9M~43Y&?lh?fmCw)zZpJblm-#0^M3$Dkvntx6I7U>NVC6plRhnuQxVZRZ>v+iu89t zLrhFe9F~qiinwfMQrg<$swj65XHw`E&HM?i?N!12CP zZ%}Zz@?J*?rI&8>4Ib*-; zk`VNa8d}%A(9VfE2L{06&}2SP2ujviPea$CVq=S-5`SOjacE73a~mL+Q+8YD-bwmX z#}o8E2e2b-?`0H>nCBN17);gLAvESWtuM^?fh2Cnt(jC`-)k5cNear!9pA!9HJUy7 z7r%wKn}1PMSMLtF&jLsu$cMDk1)MSf?sA79G~lVrHj?vtj^pF@BNbvuNr z$8=JusJjn=YS{3%9;TaS_g;c-Y1bcTqnclCke!-naA8XoaH?M$W*rOz+y@An)Q&nT zNa*F&@4IST6F+M3aO0cAUNcpMusL}Fi`w;ch4dG+nax|=L|9zbQ$(QMj#)?mucrTW zdBfP$G&(V=7ue#`D)Ka{-;iFR@IK0zYNv@p1HzI0)UWp15e#0WJn-@H6|}VxJ@g2O z*HuO)rn*hbP*!MO%qq2ZnQBa9^_hwaDZ~<3Z{-O^{WObJeOoDG7+!vZ9#&2}nk98- z#&b_@%DSd;wr1Ly6q+>r#^KK@Eba%JJuIb-VjvKxsHnhuT5xV4=CL9QC*f{0EFUe^ z6UCtrVMT@NKkkOc1?Y|Lq2?F;wc!lU^L+SS%?_OBJwPUtW*i3YYYQ_6?{C zp0@Mm1XXI-?=9>WlT`WtZViD+G$%@QiTN}6ggaCJF=Ljr#NRUcysXB?6ks?)*1Q1d z@d*ex{+(>>oSrMIsbwh@AfFXEH3lOJ8EAv4f}{0LmL%L3&%C`wYNqTlyCNteLZx*c z_4f6Fw1FI(L6kSx0vcVT>yFB*s<>!35FG4v@-G8;Ha?emKf+8ZGkswIJD_x26m@h! zV^|7iNc#j08G6)r5K3-g5q$*#tMhx#3uqD4Fy;X(?yV%-$jEc@^Ak7e4%IttFg|)j zFHDmRzq-tz{nq-K$K2Pe)-C7GBs^9@!c1`~DP%AYhTttr%gDtYGTjn78g5r-<=Nfa zLk`VdO8w?-Axxn2mT+kqT7^pidK#wzOYu|svpI1Qu$jll#o0CYw@#EBcYM|Kj<0j>+1m9cYeI;Q*UrCrhS_^!U);%1Pd)tI;9_FP~Ky{*%}|Z z$y+(u4=qfgaIw?uX)MChO#45!It)F`s;&KapRKV27DVdl)2oNGKB5l<9Ou}4+!AYM z++Q%ig1mVIf3}dwsD-|3HC?ZQBNEu&3RE1CWiSG+CG>TIy7X2i#}Hm6I{RLLuA)C~ z#|Or?YM7@WPs-esa(1rn$8;7*<+2Z)16P*@~_$ zwJn*YsNqVu_>ys00>_CFKQlM?z1Qi%{9XVPBjemsPfUt{PTQE8UbtrQ3RH1+US3RE z+M{B$l7_zmDPvW!v9bC!zg~|tGKHqOCLwaD0wb-?)n_rjN(Dgjzzw;o!0R(c#&7Qr z-pu^rshvP7nW%S)Eg!3jkfClU&I9Q3@Ou*lT^`X$eOQ7nxV)a1P7msG%9J(~niS<- z{qNb*teXFbVA!ozp>&M^-NA+hVHYF_>SSIU)3c);uu{SR#DRvhB*0-!oOYR&b9b+ARLeY-GNs04aDv^=@48LtGULV|m&{`V4dr{UQa_x; zd${KVz7UHJUfcX*VfTM?&;U7Fwjs3)SU|N%y)`f0n>qO2)7~JbEbpr#??lO|IqO9_ zyeEO-d!MW`6s!q)op6bsJBE#91@29|oFb+qot$E`9OK{rlYh>f`DfuGx2$?HCo%V4z^l2zhw@9CKM1lx$E53 z_(xvR;FfT>?Q(&MC=H|qt{=Gl`g=AyOb$cfAuv^8(72uLbZHz-;5n`hzhg-EjDAkr z1}iZD-}V$Hld}M_4^kZS?SX6_=O9d0+*?+1;3f%|u{;F43H&IOkWDggbZ5dSLVDvj z;9l5;cWu5iK75#ypZ}b^%u9pR5Ct)3+*Thzb!Q7Vsq4Xtg9z~nper1u4g!c=P>U7V z4q7rI?LsAkV$i_oBAJ4HRoeQ`R9y`0R7}`>vs+ytlYVzf z0rKUt__4;D`n2;{$5=!#RsQ?;@5u89Bnb}??!2bmg}N&MdFO7Bj6~z;dN#s7LEe`L zCC`xvC75zs_1c`OdzBU}dc1_k!O5A(ZArj8?T7~!Hgt?gM7Ys^{2Wv^2uq|-wD^d^ zX;YYfwBh=v(jQ;0BLier}8VpfARAMUl_17iRrKImHPvuZ(&i^Iu=z)44?;fh9(SWN?<~Z@tfT;gT@05?)hr7 znx5Bv;6Bi(+*XEO04BH%e1n>FO`Y{y&8&B*ZmHQ!qZ{}&!oU-()7&xP2&pj;9prC7 z)7d^+jDWp7n=xhq5{nTS$^FfX)?f$pu&`air6Ap5#GC+$s9*-z^11qq5&(8@w=6AL z0^MpEyZ{iY<3<_e=l0zf_t{gE%8ewE`$gcctkQ1AJfAA>J&%lwhnLUsKLX~xt9A;T zDimOW%!|Qtn65M0Rq;{0SmJr3b|?Q{U%|k@xRQNY1zJY@J7|RTL?K}7fO>=6^n#44 zM9wY!i?d_dG@(SW*zgL+n2YaKX%_e6oK_8dX2cEIlrC1)l9Hsp|2cC_2#7CSGypQl zN}jkdcsY&RZJ0p$5Xl4#?PGv?iCnL70f9_`%K|nYVm1L6=AE*=4sydnoSN=@HF1p+ zWG$e(PzR5J5I$|)HE*jOeWUpE=W7cDjsW37_5vf(#MvA&4xqP3i_8P?mLhla2SN}9 zKx;VfB}Mb`3h8^C2ffHVW+iAht=xej5*-!w6ac&l>MMA0Zs6pb+*6BmxXXauiE7oq z3ySFLR26GRd}`220goARktFikq$wMC!)-+HUZuCux9k;V&s}83@Sc2dQN%CR`&yd* z%LO(zI2HhSmXmFo!NE)gDGoD0tQDlHCGGpFpELQ`f?}b!UfXFL2KrKIHOYa?GWPH_J`>2s9e8Ze&)( zd|TaPhjlJcM-LDquGb19j`)KSygK{`Y`f(!mm_0HLe-(whzL(ZGT+ zOv_Ifuv@`VQny0l+xqEC+R@~ z3BR$R=`ZJf%}40Q4ogvrQTaz&d_)xk?`Q~ka=B(P>|?x!>5g#TneN%k=BFz?X`()9 zAsB?vYa?Zj5VsY+smW(>t`+6*Z%q;EoA#KJ1nW_a2)dGTEglh;MZv#_PD2h;#68Vr zi=z2eYiIQOwfmTg+DNXP2N1n37-U!1X16Trowhm?^t^kZNAo*x5&>}6Z#!aV)v3pa z=L_mGqB_|$AJZe&7z9fbEVQ`FIgA__-NC9T5^?ACU&}8n(u5U(bi>LtRD@!rxZYeI7}(%|B5}&&T!8>2|r7 zUPVL-4j}^nsw`2va6v={DD|g*8{FXH3ASF3hs?|i;N`{3aU4!L+<7T_{)KkfUv7K3 z5DI zx7U2CmK`DJ%yj)}!pY%VjYAL)tKA>hVuER(S&;-J00cJkA77XN2FBHmLz*gAZL1Jk zaG>XQ9X=@Lj^O~kXnB&u!EAu?SB2#Y)-7$@ikSUXZe*hmO%o71YLeaV-fN`q9H${( zDI7qXsCQxk)&{#6y=C^LqT)Sp_-KSVV|MpeiMj2$TxK0afk;Z0qADR%bn6azKa3u< z8`mHj00RWn#p~5OA~_S{uPTf(u~~MG(1ugFYrcjz#Tzt{f>C z!HN71^ofaXS7`Hc5N|F)&pIzZKggWVesUkI$UaksV%5+|s}-msKv94_s7Rk%*UsNU zgfK1=Izd4M&ukBi-x&e^`m@GnXe3Jt#zM?eQTG!9hZ-;zp?bg%z$W2Bu2=!x%N9fy zq(NjVFxCPNfjxnk_eGjjAz*n=a#0Q5Zn3^5`@aYyC0u|EoefmHyD%@&3MwkzgEFF^ zq(ttMD_=bf%vjfL`95GK*oBL*x#ltg$rnJ)H-_~nf|MLEDxkoi+tzC90@B1}zX^M` zu(Uae-H4$K+6AI#gUSV87%&gG$PnybV1V|ca=eIIf?W6km>0Ag*b)F*2N3x6@?~B{ zMfB&-%wS7_@3D)Xd5hnE={X3UuX1HGR0>rQf6@eQXgL0^1QSqvwyfHdo+Q zNL=egZ%*Xy4e&*H-uxT}Q6SCd!j0gOHsf&#Iv)LSp&A>!lpKf*MC^t)pl*%8w**>! z_OA8?3RK4{kSwUxF7eTBSs&ZtMcE)}mitf&FtOl0-155$R3rdX9$xyz;-MWK|0pF7DxaN2(R)#x6p>Yo4Byu2FA}kQt z(((YWUIqwr$YoLgHYa01{n5}3WE8@%-%p^vU9rvFmP$8TqSixglrsDlkSa6_u#ONw z1l@Oj|0K8*f8tLM{4X{(<$COoAGQ4Mo3y-Bk1;|!-|O0RtYX4=W%%$wkP7_|*mKbH zmX-iT`YNwqa0YEbRu6y~E0+x@6wuCy!TABif`l5B$pA{)L6=185dm5N()E1Kx#9m+ ztZzfEjUjiK0qH`rjK^?RoA|N*+b=cu17@GoQje*_(1a^Y5ObRb<1>s9Fp(8CHD&tZ zAHsw;0JuXY;22~&kksRw-p%(SviVXlUvCcYX6Fg5ty5Lt!UD_d@gh1THQ4IQur}KQ zSF0Q(DPJj!#SkK=sH!3t%Rqxa9R;rQXholSglkH$<^um5b=(;DgKkl|aJ&o+U=LC@ z?C$@}0qKC<8WO{&T1cC6m5ZcyIbLg`cE`qQ>WCMSijYVPc-7u5m(+dYidgrLKY+cK zugt7jWg!7H1ky~VZkQ|z5SReb2f#Na*@wcPVC$|;)p5@Hw4|H##oIMMQr6|W=?QRP z;*BZTz#)@Xor^moIWKsXqGOJB`*faBv&*~~${Kx5%wbF1_U4oihCRM z*dF$|!&A7{O({HY%)*3Sy(o$~PDXQ1iu&IBI~0S7oMyHHsSqoSVkxQh?TKNiH0r{U zJ_xCzGk9>Ee)DNBYRC!L&%fVem~VkN<6#82f@rl4MlFbEj=z7TVUzN7yL}pY0*{X_ zDn2QRnNuYh)L%ZVz&jN2&mKK-cRw*Hm78e9xP6D+tTT;9*%3a_?ymi$EF8qk5gT9J ziHwdGgJ$viCzpIs5Z0W$PJ5cVN>vr-^pJv< zn;Y(wkkZv{wdrkfY?%HIO~XOu86(=hrL;6U=(z|8{qw7a)8(%=Lhhi;KfL3fnNfV< z_T)@ssuDJp-2gYr7T_ERnrIz&*5-DD*@-t=imjJR9D(6-qT>9zAcfX1javIaVkwz5E&@|Xe00= z&tM0TiFkelPP7LTbO+FUPo=u5DgnSNcuo6-4s^tJ1~nLwiowSM_Ai>%r<1O}1&RWs z4}g+z=zqNemWn($Lja6cAd;2fkzLEMpZf9wt%D*T%kl5j{T9)VG~v_jQ$Hx)M<{L1 zNasHS!#NHNGafd0-ae7YQpPDgg#rndobT@$B?>o%o-=P7+t#*X{)1UQT?D30u}g>A zg`eK@fKsp+goSl*zdAPrBh&<#3lb&+CZOjA;RNHfmr$Bf&(9h^kC@X2GkpWojfRHC z4@OSgd|8;tb7^VF4=ofG(c%U__BwHtmAszrb-)iB(|!MUJ1~MShoRz6)#KtaG9=^? z5$dw7U?D@d()ReHj~{Y0VL96@ESdEl-ZM_&STE!ro~?&W~|*Zuxn z2*5cP&{rcUfuKg=q1}Lkqe{fAR%=%wHth=67b0jCG7>_7G?qb}?^xW?uhP_L@fJQk z+{!B}y9+b=BfAlw{Sx_H4cmWa0fNrz46#p^j~SCDX#cn8S4(>%n0e~+!chAyB-&VM z(&y25exQY<0fC3yK(Z(=Aty9{w1Wo{cj`uIOBy2W6AtM$NX5tL%>9JO_ZMj+k>jOT zZS#x}rlTi&C!bmm`{&!vBE!f!7MG1~2Y@hHNlAhc#vkMEPz&&sEi8pW&^D^1yN4m6 zz^Ht~&mdFradNRamjFC}Zf@)E-#K6erSQKJ<0JZJ&NW*7Mld>N(^W|1hs8q>2E>b1 z0pMy;M-f@qB(Rj2OEfq?I6B#whTq(%>oe^!lA(}arf!8#s3-jxKPP*MY=rTKpB?T>^Kg!;Mn}dmoUo+kZi6^T5npVn$V_k|9##Kanut37%QStGT zkBMmc`4f@h2md?*ZgO-0k`6bdDr&?k6^?Q2efGBgBz8}YJgAi^#BFD)2@OD^EnnEs zs(40_7NI2<%;kqr8#GKz7hZA9y7>LwK`i&jEa)IJ@TBzBUR$Wo)4T|?PHyWd|D3)H zSylocoeZIS8rp3$yY|xuVgryl+&=dFF0+FKasbPig8l_C9oh3BSc1|qW#9LZ%W5K$ z+j6`NBwX){W3$9``l2#0fFa1B56LRT&PU7uE$g}fuo!zETPe!kmvB`K3xM2T2>A}@ zLjp`B4F@?{1L!QCK+_-_L>klc%)lUnRsS^?NrAHL+-$Jxj%wuf?TE1lGIUlmXCjuU zX2rap=k$f_QfU?gibtyGvOA{I%% z-7-5=YqvPj=*C&v(j46$c!$$rMYf`%LZNUhMaVe}9HZwOyXN>X(_~w`&zH9RZed3o zt2C}ZVd;tj+Y!dmGYyTzFLFf%1yQQ&aE2~@C~&~E-TVh4rcC`k zs{gm$?x0?2iVc%x%5@R3>!38CR&swX0}(cqHN^}VSm6H}ry>tF9)?612nM*J62ApJ zGM)D5=t=3GWl2d(2P>m2sx%XOT$z3hZNr^BN*XNBH56qDmk23);w(#>;*kPDa-Coy z0JO}RE&z9HV?R?B$r#`8YdsRkMfEu`5n*L26#&rNk;QY6Wqu~y*<1hzfXfTo@0lG4n~OzWY~^ALcxHe%$ki=^vkHu#@cZHjK3~Xl? zEK;5u!1&TdnjoA_kzZ1>02Cdp;o%|;PW~ETkrFU^AikXkSkAv~XY=nYhiEVpOb>c8 z9GDu}uRcIEK%YdSRFJ_LE!N_NEn>_XY<>d%ObGAU&2~7(6I9))7M+;*B6+-%OyD1$ zNNM_)FI+*LC`L6W&&_X{k;X6SIXPqWhldcKh8~f2IRuEQ+hsX1y&iFSU91gm|`!ZEhDLNd%vHe9> z2Y*E04y__bg!7d{>OVgJ{d*!rU?-@hWbl3=UJw)Hy`L4U8dgpYuP<;n!LNZMF8p36 zw2&^>AJ#)L{=M-jbK%;&t-s*kj}owput^E@A159CE-d}+pYJrZEvcg;n;2C0!+>k8 zpxDWvO4Ck2;sO0%SMwSz6R!)3aT~F-gOh=+4wK@vfZ_^;iQvW_r18LZMO=ixHZ2A} zza$^;7N(k4k=XCqclY+rH66|_M@f-C%~4&j=a+u*GN<}m_^($GQ=*7TibvuUpu~Wv zq9L?@>>2hzFdl-XyYK+OSCWTVJRBBMXQg-O{9)mw^OQsPE1p|RCL<|>PZZA^JC$y> zM745ttkAKrt__ed7WUl~K6RMZ;0F7n1^97UslOGyYkKk}nMlNtr~|(v2shMMGpo&_ zN+!;V@@^!tep|(^Qc%nQGo+-pL+e%5ML?5-hXxL4ZGRIGWK!TH2@;lmtzVH$Do9oQ zPQUR%cZfXrkhvjBgoOwmpb&sPL<8}o=JyKkLpFk+QFFci{*2(N#E32>K1L_{HT_oK zo329S@GR&`8NmM0dV9m$#_lYpe z!wf^D9;_u0AUR+_Ra;Mo0GbzM2<`93pK&w0emLVoSk6c!cdISqv1uqeoKCYTarbMS zVl6S(cxKWWP`@R$ecS|!jpPTi9zb1#kis+Ol#r3Z0C~amy(G1rm@?y10JC1+D4_fM zcLEP@erhZkZ!S5OLYgp+9if4c!Tqw%uk=LH0gE%J`L|N|F(LFoaFgNP0Nt;X*~b= z%a?R_!|tLT!QUL6i{SS%5`+euvsyoWQ?9;rLdPS`?((Sa=<^t%MrLTKgra&RIkeLi z+)&nS;M;HLkuc8d*9HCR1Ra&AjU33hJxK||#b$>@C?qG9yk8dG+ z_nRlq@KlE`iTCt0YOFB>gwDh+zNu8m9Ra8Ti67t?BIrS2AJVR@Iw!2jyk1{x8d|dQ z^XcI5Pn=Bq#}OmDh9;r%HE9qBLPj-ueiV$NANc{|6l;Z<`r$dB{Gh3^@!il)08EfT zglr3}pS{m5+NTc>jM*R*r zCig~&Sba>HrqJycp&wlu!HsZ?h@s97B#Y7nu zXsp+O;Ko>n*&g0Cj-h;a_M%Om4alP`qM?zA%T`T;)?SJLPB+m9|U1m#mo6GSp8!wHc3b<>{UPC!B4N- z?}5AGgSs}pnN|+xyzqeILJX#%R}05F#;%`aDKUK%GQo{ta}Rk);r*3&c5|WE`Hf=X zVmJ<9H);s&0$qk@7S^|nd{|{=Z?AdvcwMD5MgdR_?)4-wi` z88B}E@-wPnkZ^V9<&I0ZYu@s4TbD2$OzBCgDuiG$IwSRz)9N&B9&N_xXV=3f7wA{3 zhrMTd$pdhZfSQ3J5DqTZ=MKGfBo2DEAa{S^xO3~!sB#ib(mQVJtngS*R7SGn(-R?q zr&G6cl!74`0pkw@GC0fl3>ff|cqN4M0hb`-4&qdMAfp<{^_M zak$G`tjzoxL}`fc#mIP!)Q(k}y^NKiyCbxH1(Y^u6f#opPjGIaH>`?Umo`tGMKBo# zdwl#KX5$%enyB}dkE*Wr>B;T8?4b+CYTJU;-&ygovJ@?YB?}6DZld23E7Cb7@bI4K z+xIJ7oOg>DZa}GUng5@*zB;PPw(IkVC`d^ON=ZqJbc50%-6$m`B_$04ib^Ssq#)fO zT@q4<5J?H?k`e)FBxc|5teN+lwdVQDrH`J&eP7p(U+f*Jrd-@^%{9MsHS2K#yi#kv zxxCs3y1G|!?tnWW;)xHih}K$DNjUO%6uaF?SwdvmvT~TTmWvq4!U)4(2e6z6T(6jr zVxa;D&!=I#Ye9i|{LW<`Cd@#dK~crTIl6r!rmbyAdxt+!p93TG=Dbs+6Qgma{dnFb z?zy!NwZR-W?(k5=-${slvbgoQP%ay;*3|*qACM%lkGPWXSV+00=4s3HG2ReDlWuUS|8Y=jlO8GIo6X#5hxqoUBUt3{1k&Z{(IOELByZ(1VTAWz*pcG2 z?s^S~cw#xN(^(3Y9p^^Z3F7Y`pL3mkuz~!B*XikQ$w#JFg=_aDoxnqgYJBq`tV|hv_8U;>GG3 zac_4l)3x$D5K(z5coyv5ij-8J>iud~$HT$i&>dW&8@b;qs2(ea(?!&w;yw%{k`XV$L2G#(y?AdaMZgTS~~A0 z>y-XVX)Yq|B3>FA=ZU7Xhv(;q&B)*bC3;xSFx2S7Z0x%u8-Dw~BK)}q3xqyxr`3Tc zCx=`8OWlINty~9(Q|E=v)?{W@Ua4DiLCK#Izh zAxSibA92$+Gx((pBOM#P441c)lh?v!?n`lDEIZzG+;YJhJBGv-R0&Uvr+;kexs9D= zdOLd4@?e@PyR1JB>rhs^Ur^}x@9^J`^Mk`pd(H@Z0h3hTFA7h~i^y^@m<&D;y_bW1 zIS@savWZDtWg=H2Ha29~;$BVIbF%-H2_FVM!MaPR9jtPKS;8zhqV|O8t1fl5*xA)3 zS9Ns!PIua_b3p_5j)oTpIIq?*x$u@xl7XKjONCDNy5`HH&%Sj!dz2}0v-a|A@ppz( zhe1)#qXDy%cF_0Fi8{=p{^dka3KGB>m*gOm=1G((({C^J+h=ETgBIg0;DwYRQ=Dww6w_YBGOJH9E>gTAMmtkiDSRuZp2*<48{&X7hqKhX%oeI*&+uSY#xh}X-PyjGT z#00xa4%}D*B`F=}mu)G(hz}pgm|8(m@EW>EYACo`p;G(&w4Y`QxPFwYCQ{k|GR_Un z_^fF_DqC4o1LQv_w>%ObvOmW2tt&f;ubEtXM{`+s;uWNgd5^8eFq8AY@d-jU7$7Y)bq3yI4t{dE)WW1K>K`HZ!k;+P@HSOz{nO*sQ zd*C_%m-342W=GreEFVIJy!Ti*sYEb=wP*qPBo|OR9RR{^`nGa#SXu=i4D$cdk?u>SJn5#Ypw%p@LpK}9|YgsMYAhR(au2kF5!wq{Bm70 zQ!X@g@UY_F*zB?Q=B_3lo=kjHRIkoQygA}UTxd+?Sgl~+;0sDHyqlg9oDIKu_BQ-! zIBVxH3{M>6*EpZw5%;%&-;*`hL5AJ_#cMZVJNvvbuKS&@#C1gxjUUGOe(S5N0o_^5m3d>P zWx?f*saSP};UPCPZ);wc3Tk_)%ybzbJ|JZ0Pc|G|K%C^%eJ8%f=#PmAFmKAq0{GF4 z2;CQHc?-FwhMeR{$;qHxQ1x+Mtza?WbzYEBP7xvkh}zoLwiTfK*Wuv=h(Pm)mf(yh z1C9489SS)R5T@yn^%F4jj{pczK9#m|%ihnRd@=N1%dUk<^PiuusEQqon-`IWqZe-q zyD%c27-|trP{Xp(CiiuID6_zN*f`|3UuZH9N&-ZJKJ((x2rzhR#AnEio$t?`q1%<0I;j`2nx zLEVy5A|$;q1<&~Xd-i+!pXj%w{kurpxZ_C$=TL&|p7A?SjheyZfaVUq1lGZyGirzW zHPIreY??`lv{Gd}J4B*@v==25^i_XfUBN}jcT@{-?!f?dF9NM3o3Gt^`MOvDylKEj zX{;R_tbTlIn+KzKC;Im7R$!Q%|J1EyWM*EDxZgyyk~T{YehzLCQPDE1K8lf%5hwFw zM9c_!(+3i1=$fYeyWn-X1mRp1e5s+}yCW7>@zT%Sm+w<|rne!41uzZ05o zxSuHSgCbDj{{DWEi)iu@vn(H~IxR<{X^9rbVN8^0e6WOba22{CX(JnrE{yz+i57+9-bZ}j{he8ACgp?x^zGST1n&if!IM__C?qb`I{)!ihz{tzmlm$g z_EMcCfKD2w03Mhuq&&CPFfl2uk&DFi6yt1P#Q83qOGZ<38H9N4Z_|q9`6xQz#36?Z zoah9Ihaln^TPw_o50S~hotL*@DW;BQ1g!RR!AAvCC_v1^ajvhguOFQOfx)M8Z)$zI zK@fSCD#_<0@P;}-x*w^OJuo=<5_Dg!Ru%Kx^KA)2J7(`F58b}}{X5Dl5;5Ju#u^=h z*T1rhk)Kc<; zB@|ijAYnr*6c==HHhb}2Dm?(sn@iakc!jqY!tR+NJd3!G0L*WAWiJp00@`hwMG$Ad z;^@68Zp*ff)Zg>Ccu#y(rS3ub3jyy zm3-e{0@T%$mmO!m+yd4P7-DIOw4mPQR(!!J6hsCno^Jz7+zD!sP-Uh-sDO9GWI74O{z_1yN}A8TISh|pBq-1M3F{VCO>LdU>zDc7 zsxb&=<4)*f5~31#-6lzjBMd?1`e5^gS6*RZ8we%9pV~hM3d8m($`!7%d~zkS<0J?0 zf`tj@)$GDR5iYZKY!GRXIMm=@hr#KHbO0oEc#zig%a?TVs6|L2?Sla8Eel46*(I6? z+#foUVzujZzJI&X3BXXMzBn-Wa^`=qfOWt2x@s(J<*i6n z=j1TKI0?%Cj8lPVLkF`CfIl!A9X>hnhI^^4q%fdNS4wvB&=% z#FenaMQ}r21u;Vq=-sh^{cgEJZWw?pbSkAR?u+BLnY-;@EbxDlJd*8S4ok7j|Hf5n zAQz9UkF9;JDlJB5)psct-EKL##rom+hFeB5;B7m(;J{C&W7eM~0f&uV#PT zegXT=8+wM9RM_bgl@^m{PnpiodJ+|wVmtw@eo}^w9C<*W2BxMUtT?vUyQzK3&b}i3 z7Vjl3Hp2gYHvNhLX05MVhYZO-9xKKvWxM#u8Qn}&$|l6djO<_0(9%O6a}XCqCh2}a z{B#b}3SKa>AH2n3KtwDu-}fR-^E+W>QcK0t(Q$@(FG$Qk`*(;=JKtme?gbe;q3>6@ zR?@XK*QDo(!?|i`D4Id9F~55}=TgVz@n_2A+)7lJ!^Dr?pG2j+H~0Hf43Lb=zIY)H zok>J>wSYsvTlJD-&4dqJD5-Q*%_LMSuMQ5}b-!tvDG_10QuoO@}q7w;oFm49ny}DL*p|ZRG;hsr2 z5NKpDE&+&PhKL{4I4pA{0oPNBkoMZ22CzCQvBKURMflEeI;!@F5uT}6`l>2vp+vfLq$h=Hci z+RjdzDF$&p?!XORfUB@zv3s(=F~9F!=Cx}D5op83|Ja{KINMQriLWh=`_#3d{wK>%6mTA!M%WPR@ zrs*8=ZX~J>q+Q5pkR~eJA%c6_B2o}5Y%_J+X|5oMZ-*P=yVAx_%|S#z1=VIPwcll z@A}5ZPTOrxw2I(#d#JPKQIk~65CDE@reRRw({ zWpQyaVk7{+*H>=-C#{&(`T$S6x#?Kj+qc6Pdr~vW?Q_77lt8Ae=n7hFWUNGF_Y$2V z2IBL;qVWv476ADd5o*J9Eph!q{P*5l-FdT^ z=KV*rhzL3YD3%Qd6%O8`)WN|;ZtVFIR{;E05ug+WP+So%8B}%vuE{@r%FJ8{=96H} z{MSGo0su{o47Wh0vp|hhojuBj4>m-3J3Dq@6rGNjveG?X@BfOVAZEY8iNnt0El@gouC~ z8vsi?p#VZo4ahXf^^DwZeBdy6HGBF?&=XJqF2@-$-BYFLc3a_^$>Kshl?Pf{Bv2

ZvSy!_A!Rp6@1`0QHfU)uK#n5+ji zv9PCqcqFe%hHxK$V_ArbNMPrpnJ#PDq5P`< zb53r0zbsI}N%=z&7}w0OOs>D`GsLS*iy+<+YHU_?g0$r4(dtWNm>IDhLs~ZcZnFad zv45LkazIXSF;))`A)Xua2_YAO&9=4VA368Vj{8?*wKGjOzVSgcOKGo;8BnJKSMP?J zB~aPj3!+>>(5+{P=d(dG_lvra_j<18gjiMPTRXinTlFt=v+gEFqObUDla)YBPhR(8 z2F0JVMhiQDbDpj|8M{OI{x_1AmJ7EJK}!q-ngdRHpF5bbCU-qOecy#9{}B@dP`+m_ zu;p>Cbx5$t%719Aat#NK62AM2G-iDgr%u(WiH1IaqBkn>K8o>6+{e?QacZ0oEOg)P z;q1L;KpRcEfo4~|k4+e8>@`gSG@r}fJzT~2EA7|;>5yoVcgRVN176-U3TXQJ9Nd8S zBaDM5|MmWa7r+#q@}=8MTM|b;_50BA<-h?nCtOICH#g-UVVM>4d*wMz>Qf-NW24Ea z-9fdu*g~g=_vz*B;qCk$y@U~$1!Y*~v6KZ2q{Ruu7@>sV^J9@4savhit@9^E_xtgq zazzXC%>8~I0C5Vt9UdQ#A|Tt*#~6tJ;xyFSPWDGf^I~(NFb>itCe~hRo!2Zj-rdJr zucO8^*wWL?1}r4#^m|Ik#of#6(-n!kqmNHjMQcL}xrMJqUsDb;aBNbQYuQNmD0QgN zWxXX5|MqggW38dDk0K|Fwo2=~Ad_7OvILVR4y>-tB^GJ7QI6!W`1?YNu2c`)a98Vn?sSC7o>XquSEe6Mn>FiLx-3VPF= zf)ooJRspv>8^6E*+mCX=b;WM-(Z$5+;OH~S^8J`2Nxzy7omUJ$VnI%5^q<*Dkyxm`gDXqW^6NRPI7&-?93IrUqFD4zAX>8 zQHCgV2So-_4U@zh){CiF)@?G;DY7mX*8qHWf%+aiMffiYsV}xHIw}h8xRzv&Kc*L; zmu(%t2TN2o6`=gL!%?KOSfGmP9!%<36u3Wfw!>FDDG$M6;mL$P(o>N31JFYt-=bjr(Hl~WnsSc-mJV;f*3Tdnxj7dtG- z|BZ#@ORG*A4Tfpck`l7 zOXTJ7CQer4T#@n8$EEdIE1LVHx_izkk>_XsF%ys4Xa8J+1*33UT~gJ4%fBS*EIUfP zqcq6k%@2wp8bd2Z`eT1GRg>J^%3RTT*-#zR`4rmm=jH0C&*Z4Jt9|O`0&g6bnG^e4 zatQk~x0m%rTN6V-EpxE+NgI4a7lBo7G^nCOhTN7P)*azhhEE&Je=;jTD>w)q#ENVw zY@%g{#FS{I@wA|TLAdvO}#A9!Hz#_MDU0lK-(H@WD>5KJ~!T`Y$; zUft5T3mqO4)N|_*wf`a+s*0v9CO0d$4 zS3-ZTx{vxSLQY<8y~6a5ghP%>?kZaYZ@}v0z4#RvDblC z(t7XWgGS>bQ}m6pTC1HXY<41*zsWEVhfK<$#9ERKYHBB*!Jp;IVNb3_zZT`_?JycV#~8wz>q0hq3m=mj*wQ>1e(#kv~=MUnDLun9mq=g#mEcfgL7ZJ01~g8Z2w4 zmextJ73wM=9!YDG0y#_FaQNkmFvY>=7P>5Qmejmgvvh$4r7VyhOQMbl@))?oU%Z0# zHE3c78Eu)~^&`*@nb%=I0}qPtFZE}9M=uG*v}I*qFCX99v- z{~GH>hg>=m#u2mD^$&mKo3gjIt4y6!JbQS2<+qNj2bK_m2x=Z^f1V z{EV5%{gVbG;UWIR_E(tHi`@*%r;IfQbB?1Y+on{^wAxGhiyrSSThiDc0-8I!&sBf< zkSBOHAyZS-kEi0&cdMM6R+YqnA0S5^El%Y;9ToW^Ql5V*UC*1Bkx~74s3c_OEf3#P zTv9ZHs!iF__V8gV>6#1U-2${f9w+d+pC)2fKJ_{?8GRJ`)l1BwRDNqEIa~Nmse`3v z^H#NK?+uYDk`J~R0|9{J@#rLo=c8VMgx@tq_j7>gyNwaZWHLBhJ)6buQz?(ipWaV& zz>M_Y6fUK|t#goCfclNJy4Ls}U=*6wN+~-6Hx9e1m}w*a8{;ij^Ca=CIIvh=Q~x1? zLwEE%;=zCzE5k7{%5wC};|;&XNEBAzGRuIl719ZECl!WwHgMh|0$I6~eu>v5*Ag-^ zIW96)yhYx%`!usD(6IOTuj1i^vlK@WG;*t+~q_bFPZ1 zxwvXvDXC@=F9U~vP@v!+fLKl+MSXjXln7|eC2A_LjoLbZtAOJ!{I;lB#1=;_G7l6f z5tsclJ{dznR?qZZi4t~husCm0wjK)@y!!zK={rP>4o~S14QYMP8`tfzFrJv{DCn!k zFZUeyE=H3LEAMQ;mhQ_k1;6hsrL2llQloZK0qDP2fUyj6CXD;L_pWb8ZK?caj#G}4 zlux(9)LsM9SW~kU#D8iMTuIFf@7f;9f)4xE(7(95Sjg3vunl9g=l+MWHDXm|rLR z;-4$q*3AB-RWl3O&~035a-s5+-n^PX&=>GFaq;f`=)#XTq@)M5cKjAKfr8_Xu1u^^ zM7+;=Gv(l|!9;kzzj(p8E7dz87cw6RmjEuNahPOv>znu=xL! zpC<-*FjP~x*howTaEiikyIM^1^BiHh_!0Aps`kp@-i^!TCmmH(%%uHE3O#>b zr0#mjP-vL_p%W(n9jhcP*HK|*B*86iEHs93&rHN;$*uOMj=CR=<#KmFDzx62hK>u& z`wNq7?}dn*btqT7@eks~qY8RVyIE0rLy|B!IvdQ2^eMdj_0MzGW@m4vXl{@9W-NjQ zC|PFE1g90+2%v{yS^YVUlO1os6uzkL-U9BUHOMl z|MDDJSI549l2$KWbRtzS5ZAi8$8-jy@{PyICbPxlYysz+$_%pzu)_FpJ1nY$L68Z$m4Xkb{u??}0w(N%fB}I`{1%)}Jrke(ZTpbqAKIc~@&iif7%3+vJ5Nm)vM$bfEm? z>lO$)QJm7De*E6>XSm2{kpr(XpP`p8KLP9B!iJPo(>~4R2gQDrx1JWxEGSGW*f*); zW?>}SsrVjmFw}?ZnO`YEF=;4RHPHK0(;a!Z%8#o{>)vfo66{b;EDub{YpsVrt@X&c=xjmY~s{9BHSHV3~~##utA6*N4)uXQ`l)ThUkE;0LF0nRNc<#b_m zM2cuXjctefMn4b{JUMM^nAgv|6Z&RJ0(d{bBc|{^>HHn?5AfThKDzhCrMl}zqM%PU zRh>3GZ9`W@Go-Q>d1r2iW8TgFOnc|i!RG*DyK zxN*yn5oU``Rj!rWo;q}Nd%1}pfH=GIk9FI9FqezX`e1D{_G%rynrZ`Tv>G4wr3*uT zL=>5vhJbg(5eTf22+WRM5eeLAkPI=BeqKHgq^9b8`Dkb13xR1^*u<9&tBs~+&8ZO? zrqpHV)2Ah5jlMC+Yam)=HJD1Z)L+X8Z=SWZ-y6O5)~Y;*}{nG=x?p!hDIM&Rg|tCfe1c68>yxKjXugMA|!ii zyCZx}#K>DIRyo7GNK^0 z__bY>gic`(GWy<8u#ie&WlvOn8H^|TO#x|U3(dO`$_Vi=KQ_^AiPaqg6jSrx5gjb8&N}|;glxK4O!`eVKr$ltcoOGJ$Jf3zR958QhW4!| zX>pm~lFG;zjbnpV1`3D66yFOaes54VAYO=JHKD>KpbDo^XfKP}OpwLRmI(0X%#*_Q z?j8EQr<{f2wzXTG4$JhMfP?40o`)8IL1s@IVoyaXRM5q(%4eMwSV7*=XOUvk34m~Z z(lC`H2;S_nyr|kIQvni_q$f$7U%}D z5YC+tbxRWTA|IXDxM8!U7~XhQ1zZIfZi~2|u7QXHcj(`IF_Qty<1bg31ybu>AEbAu zC0V|;WTdm?IEN7l()|X#o3j_8sFw=3Jw5X6LjDDSc6{dsmV;Z11B{2SxVf{0L)*wb z%nXHZl6IFwncnC?porQFp`kEW|C+9e4`mE?L$zg3St7O#%8CB*&`dC`8Qp$TO z4*%wW$lm7->w6+&!T6CxJ5I(w?AH6-z~QvM#in=X$zER_ zVG>4lG2(IzuD?OwqVwpdzha2m)kby*f7#(k?WB&bEJfO03O46lg07aDm;^xAd5eJ4 zk`x>v!aZu+#D(WF7O<=3V+{jwX>nnQ-VAOH*d%htg`zt)rExd8q5}S3%X>V^QKU_W>I-8#4o$zS5vc8jU>T94T)m%avBkrQA)W$iG`}%}@n2Zmm8q12 z!T6F{jv}?wc|X?hIYgLHsKi|3Fw{(kNP9-#SGv;U(53GN#6(0oG_1)_o}$DusBEdE ztrG9+KYsZXO7_iluD>j1vV?&kTQT288Q+=>YVK~$B~%?7m!q?jV8vvegl>bK4UWG5 z5nImmk-Qh9nj|TXkVr^u#GP~fUD}QNCdM)B{ENcD^kD8FZW5aU^^uv>J!RaS#6Q~< zkAd)5dTG}w2TYB1*7ed`jd1kV0{qpiC~A%2pLL(T;;8uBx*in6&2Sk~Mh;7-w?3-> zWO{-;-7%+rXYzNNsNRM;x6ZY;bif?Eghty#%y3l&C*uiiU&SiPjY7Xr9+v{-{tr#(+!y)#{{6JsZsShajLmMtZrn|i zjmfs#Y}>}<+HBW0Y13xgc3t!NKCa(ia|h;ppXYJB@WgH4E4P%c{>Pnx6qnH9aanS7 zu{2t7e)gUg_O>Xu?znMGwBE9~E^>f5Tc4h;xf$onQc*!O1djl6CALN#jX2@@!mHk* zrIS3+>u9`N)<2s4b?C$TUv7#BKo;!KH#qFehp5S%&7Gh&iom{-J$O3x!eeAF&nab3 zcHxKLYvExOBHj;ylrNi?Go@b7Hs*fHvV=>Yu||yLg&3OXp04{=iSF)Fnr+Eh++0D| zZ8pJUHVpl*mU9>qYQuAb$?$zyM{PFLgHf=KrGc-(B&LNG6-k_`@h)7%KdV>DS*9=V zme(IQ`p*%Tzi<}8iy?JtS#&702rnz0Rd>hz055#D0xeMWdjIAEG z$;z~pIV}EW8)i5=b|DX{$XNga;SWN)z?N>LZ92sQDHW{^(z>)YCS9D%|0x7)i2GW5 z9V5%*N0XLxGV1o#HXos*n}L;}UxSnGKkoeM{{(gIjt@yO{VTIB%UpXrJ6TRVZsb@0 zU=E1(iOkIQ?a5XXR&3cIIN^4@JrUWib~xzc(7wfO*L}sx_<68`7)bxrpcCVE_L4nvl>xTC;MAy6;eIL1(6tY`F!r{_(IT z$D#?W%i*xvmjuL%S94OCluYq5Ieubhmuc*aX9Q=oSw37X9?m@vBe8YDf&h%HcD3c{ z?HK)Yb70v%hF0x~^e`F}F%bK>0|Q4(H6tar7e1>b%voOnNFsNS%XLywwI#^)zM6E4 zVytfm{r-P9rI9`BEVn=JlkZrougHI<^#6O5iirN7)^I%**&I|{ojE1SA*Z60oREGi z-=CK+nvnEwWp)0Tm3@3-q8^Nwn#K@=oMs^WsUB53f`Bb9R zh+gcr=(BJq2XVNrrjzVskCv)?DKu9O#MY+n6r{XY+rCwR+l)Ocs=I&xx&FFalnVv!)2nO&4+xPVA$M1L_XYsELe5(#X7UMkdn@#1U<^%-!H(W857gcq9SOueUJfe zme}JO5-NU*#;04b0@RCJqev!kdr6KEA@1N?h|%XX%M3~9v1cyQ*xg|8{;j+Wu9Z)- zuxo7ZSn*lZe-gYBJU{D38gABm*;|} zTR`0BZ&Gv-S~fa~A}A^1maXN~7u$)q-zjzXfV2%ymZlJ9+{o{S`QBv7Iyk1gnRg(K{ zGN1lFHBwRs#S;Vryo>=A392$68?=WhtiYwYwi#>VI#^sZ+7Jd#?F|>=Snl}UDeS&S z4dB%q($7h@knF)i{r5keb*j@06AGKt(q8T5<=3?n$Dx0nl}Tu+WhG^ck~ZzD#UE2v z5@^gpGZ9KSzbd%rM%0PM&qQ!a!KmcMy6T`G5ZqIwOW(u+;XhnRN2uevFS1l%T+Osz zL^BX)6&QTZ>3~(#1}+q9wy< zt_iJQ|4vs|g*pg!|8{38R+YIbSC1mmO!t`o&9G}YC4^4<1(jkZN9qrjYphyVhbwwWlVZGJ`qPxIQLRYtf1b7pL71i18TO%2}6*LS#DM;zW2= zKzV5%OUGrR<5rbRl# z*CCjt?xB6t-{s}mhtfJYyYd2919~61$#}BS+%i9&u%lL1=a(Ipb_B70$XYIQbT^?a zoIlaJz>aqPvvpw{QQcp_ca1&8ANEzgHr_TWXE5MssBnlGP~urkHE8dsc=`6@wrcmq zV$g5saE5>0rqNiW=Gd!Ktu&jDhaY5EotVTvPi2BG8Pr*P&Jr4^>vtvpq!$9~&(nBH zX|x8DmxaO8wFf{i3NVm0|Cqj;9~;$RW#%`tNP?e|ULXuR!2IdBf0kNyz*8Yxoe&=f z_UO;Am!WF^xSFWs;16mss{y?hmrtWsR2>d?L+wcCUoPLDws`e5y4|f@o`;@>-sUK9 z#P7BS^JO7B2<8?)!(h(qQ;a@swtc~c=3XUtun9}T{*vA-HF_$*AifN0Q~JCk`9Xb* z*isY7PDpwJ*m}FfAC9y^-;4U(u#%xSQDL%2QSBdG zoUIa_ot!rDV#X}-!}mWf&NQ!kTs&MRj@>>5-cxkE4WY4hx$p1X)N9{EPo=2$v&8Dj zmNT&;5H9bu;munb2y(*4w{w zljqDCyN>&7o%_1?xgx7RXY+55i;szB!}p>degeu4;T4O!rhXoa>ZLk2e{4ek&kMj? zPRRdHzg8L-`6Y+n!me3?_97raJ9Cv{ixQaXA7pdmI>|8W}kNj9OIT zIl`E(5PAq|!F}xdXKD?tq()hm)gF4ry#!?p&UTG=@{aQ{}dCzck^&TMJK46Tt!A>z)!HxQ(umGD&0 zG3Pr=c&a}^qyiO(Tzp2FpeZAmCgZAR&O4%UOEK;f7@gX%YyeT}f)L#xc7eE^EyML) z6@lG#Tv7^Q6IE&pzr!3sq2sIOk!kLbIAH6npIv^Q8KA6U2+L`6waQ_!h+54QWD#`< z$l#+o@hpmuO%DDsz+7ynG;R@bOZg~m5*g2)^-C#@u>C9G2d)60BcIgK>nuGl<3NBb zZiBrnP|^XzM_nHD6}T18@XLU|JrJ*7==bN%ekbB6bVW`O-4?J(Zf<4{Q02`ED$QBk;Y+1{tGz)#@$>-c8dh( z-*~i5U%B`RGBxNE3@i!v-CDi@PMW5_u)nI)1gfNAnIz6;(#$z*Y^CDY2BAg%aWp4< z99|Q0vWbB{;J|#QmJE&~c9cdI1}1lOtMwu{mAW(L+>Yov;GP!qD%6gm*Yu2o4_w(y8rT4{r z_VP2p=qcaA#{-DB&_pXGSMeqznfCOtJ3#;ZTKE0Hc`LxwK29%_xn?~Gr#+G%8vWB z;eBe_1Wk1j%O5Hm~TAgn*QDIxqi2iY;5b^*C3#u@rdL5cIZzLpYxp-ZMXel_0Q9M z944fWe${t3*4(gy^hI0Ryl!CC@eD0Sx+%*}kxmT`rQeFG$>vSfl(wrY!NwybdC$2b z@NtYKEj4@0;Uv?FhsjhNZ{w72gY0EtFGPOlOzrJX6uOP^zJuk;n@ybrZV!f?uAF1= z$Hm$qt*%V>1a-x&i*Y^n)b1FmyJv%n*y*^CP*;v^Y6(X#xL`g1Xzs!~m_BQG;_Mi+}w;bLz#I^pTOD_p?A6nwVbpM4b z{(&w1V0wt}jUYlf7|nqmH^BbKhddOUv?OR*dY@#;KtVwQ73fo0xi*3^KTfbL987x% z@i;`h_S;PRipd5wx|JHwQ*a=DLRcA+6aFEAtj=HjF=2|Da!@^4df2inQOW52H-`zH z^!pE7X$qviyq}wm&R((4BtJ3RtUyeq- zU2p)LuE*x>UCXL|n&jf8r1nDmxi2x?k5Q;U8}Gy>`{t+&${d z*I)i_E@rb$?hBs#J)A&SN28uT9c|uU7EAL(3KWdFNd?;9N5emYBkogf9nBoPUHMr) z(al?TGKL<=wty3mS3By^sAxZW0-c=jwv=xbcXVNUzn^q<<`4=+DAclG=snbNlTMh5Z630qO}16JUlV`3px5jB815= zu+Ey8J<7vSn>Z7fYbuJ~a3n=q)|#hX>dv=$$uTl)KWm$4-vbbtgrUuuu~#4jvk1K3 ztBQzn{{qg@eV!^8kPA-yPg_Z9i`6Q9V-=_mfdW99q1G zQoTP|CEE7)GeLn`TTfrDQy>AL-Xh?xmpxd|;b9Khu!t*nhgH=n+m+AKEGdw4q`X$> zzP8ihv6(h3lHPD35?S1t{|tO@E^xM#Kr9sbxhN$38apsALqV=UG)N+8pO7VmLO8a# z7^nTqh=y{>H%May-jKMGiyH2nWZJO9KY{+KST?Skl_-57i}fEbC0y#E4Z|@r{b#Ke zZ|P&+2nI{>DMIB&)GYtX^YH0|P$v3-QU@P0hf0%Gzd^iw1mqDo3mK??L~EoC7NY*v zb7skRRQdan*ho=jIlDPK09`9_Btm9-h2aT*6awFuLZDGWT)2h7pQ+8o*_N4^xyVFR z1LJf7*TyJR86zR)$_IB$Te*3cv$dzsCl~=eIR7N`S3mYeXXt0-LdgUEJd!q4kxEF z7t9T@OJ(;g_xJ>|ccKjtNHheeU*zl0e42QD-Mr?B#0eujbxYr>JF-hy-U?GuiJHdP zb!%ql^DJoh`qyeQcU8n|cb7=!Ayvd}|Ls-V?{UbB()VH~@V-0p$h#6pcbAEtD$3#a zb>!*eV3QRtFT|hL-|!;KDbtjje&)Oorcy$ml zO*(D17b=H?&__KgWAkWaxQCYs0i%ZH7O^py+k{+u)+s1i391*-Ed=hYO&S2%Xc%^t zX5Awyj`EK%+*sa3{_dTN1s_6SZI}|o6gdrJDB=vsLc1u3;=`8c2%5QZ?)C;=Pxu#d zoP2b$tn74GpauA+`)02HwTHcIZB)^nNXZj`T6>|WOv1+jKs8~|!OhLi%?*NB_iDA8 zl?t21PEZ#mPv+azR@-5Q=0f(WfE5ivtWI=RDLGCd<*|H}eaeGs1HAm!32ojgj&CP2 z5R~ALqa{(R~Z{dL*u!rI|xv7Dk}TNYT;6xJli1q2KGLt6PMUIHV(zB_=CpF03hI` zs+$ez2uRvskeMpFLa21?96b+<%W)7cMi#=QT(~*T$gukmjX?KX+@vGSH;k{Yyp^A$ zxJ-o0mHt<7nT3G=Y(1E;>oY?HTk{ab4s`?j_vjfM?ZYA$?<1K-+;kYxZye6zAF7Rl$yJB{|v^9OH= z@5xrHcFhC$WA!@RSE+1zbW;_nHF^-X+=(3T`<-P`YrhAkRA>w`IWiR%7pG-EOJV~A z6N!xGs-#a*jDh&wN7y}h!tTxB^{t&$=I?}_^kH?NlPl8FkWP=Ol*imIf0@n)CvDc$ zU;k)O61fz#$XI2sQn&0K_;M**jt)7xAIcw*C_7%qn|&W%p}%J9K85RB&2O8c!tJk> z?8qUr1eop!}3k|GQpI@OL2jQDWKZJH?pn%keafS&oxmx=bDu`%u6lxIqkXxKZY z;U{gz0H;5xNRWmM$-en`I$-9VhrS>BJ-(*uKV6OGwz;_SV3&=M9v^qwXcdXK{X?+- zg$>1gkJN`J!Trlh4wGIX$HhRmJo+JNtj0+2d(h5&-g3ftB7f=eS#?9aDXBYB)!H1t}B1ZfH zHG`cpIJgmQE>;R^kfm8_^lYnXRS!VR{PuOcCT=-imOB3{^!x8f?i<>o{+Hr__ImB_ zBiemns@tN5#Y-#V+L2PjajMozwv;Vg^v+TK7-C4=pst_8{)-;VgBu*?+)yo3o;iL@ zSjm?h6;V~)Q}Wk90}^$q)}@YR2$TEA2qqvg8A+QPcm6Z(PKA55>sH1TO;EH_V6#-7 zARYt)u9$Y4);9gDA(SB5CYaK2T~VF{XyqTr_CkujWnYx;^)zvEtr=R#f9DQ0nP}mispVc{Ph>K6TKrZ@d6LzVMvWk|0Y{7Rv;A zi*9fuDXOW0fgbo?9F(?Yk1x1`u!5`y}w4!2jfDWO`j!X-Q6jKXR{xg zcn(hk02xs6l(fm8L?+D+?@o!Dt$Ke2R01p*9$J6%i`CSE@5v z{55i*hak{7x(Io;xlro+obC!X=RR(wio7qsj}Gd0)ybc7LWK%E96+1bKAwjLPgNAi zKtv$R?%7u`Lrl?tkj|VtW{K--BSK-pS6IV`aBo(axY=?`1TPoP8*OJ!X3W@nxB?XA z#grghG=Jngm3s9@0Zoja^Vc!E-&Nj^W4Uj|KWDPF-F#mw*gEc(uKg~dl$Oa!QSYl) zX%akEa=hr;qTj351fRZGk{~Aa4R9=Pe`eyg%J`kuc&$0({I?Mk9xXi@BFzT7!Mwah~ z$fMGJ7c9Yc_~FyAS&iA?77)~i3e;z0hN2OdyGoU55@2Gx5NF~wk18U9f{8sK4zX2( zB(|7_m>-M5R7Qq#WXf?-W%8o74e}zKuvcfYo%@BE=xIcsKV4z4R zuL&s4jq>;PKB0iA1=yB*Q)Jvms$J_9t6~&T%pc;pqj13 zZSwjJgsnIrPk(tg&?gB(Mf;8q)1tL2r?jswh$hjpQ#>{)+_x(?@+vtBDPTq?bRQRk zTn=LV_%U#@Hy|_^kbk!#b+2n^2C+qq+tcCZmOPW6{-@rmC_~BgvHG8RGBqi(ttcs9Y@~=7UhU^im&;jp=-@MmhJT(~|ar>}(L85A`95Tq9-e&cMy5l6Asb)b> zvk}JCeM~J4&_dIQ^H1_ zGcwb|L5c+2QpqaM>n6h>{tv=siKKzB_rtVT@pVn@2dQ=~j|q$<_j;DWCme}_v>(hY7T1oKK2OO0K^+|oD=G003r`|=Zum?BM%SrtMQ4cep{rSDS z!@b!GN7`yC&Q>iJubT)l7W^dsn&)3l%Q)8kbME%FVG?Z}9b995yX7RwV$O@boAf3sE{9E$BaeMGDn8n4^kGD2fBDw0EwLc?fi z^GJ{+;LxD(Xpg5GM>4NLjd-;S<{(?EAf7Vf3he64iwZtGqEI9-*n`}U6h%KW&=>|x zw?U<&$+eCQR%hws7-y7G1xhO7)>;!^MB910o!sJK*{*ka-7gBd#dhEQwN&tXvBOl) z+^zN5_iPL?oG+d&X|gcj$v8|K=4hzx>9GctkodF58h5F+>s8I!^Vz9v%@!5*ljPYj z8KCK&K0aQ(c#}g~$fCsjZ}*O}-J0Fb*K9L?r{z{yglpb>1u8Eq3w4Bvq!)Fh8=O(q z2Byi&=@x3mv@^-leHuplJ_nsV&%^kHWCr$Fb=J6**y3+C@m#5~9o6swI%mIc_l$QS z%s8pMdt{gnM)d_~)SSHPyrkbhSRi=$JRERfKULjbm^*CmZYRi^*%obZXasH1PBe}= z{)bdon7D4NdMA9sm!h%b~qxZq{xNGKc*04OJgqkz`c0pY( z6bc(@cRQ!C$e{TZ3HKQXCu;>=>FjJGQE^bNLN~3|we#vsb&jd-R{grZlh+L^A1H)U z|1pdAiI2t?2jP>jBCgN^^rS^lI}u$9DCIrZxJ6)Z+y-9|ckc40&UR?->_)BJJD`dMhJ3LF;26>5aM zhv}NboC>503e);bmv_J!rZZ;^AdI7twkU`Or)#P7a6?r_=Jq3k2IJkZGAX z?AFRVnbgr*%+9Ukn_`F=Y0Dog#m&swFTDN`W=sFTT>h=|>$Q3Q2j@(KEx4Xph1(4$T@MrXJ#D0qPQ6W3SA#6)nol4t^3(LJp669UyU*41=Lx8Y zX!f()>uJ^P{PiNWy1QlXwqfiU*@RH5LnB%h){>a#*XN(UH)mezuRXe6vXJwa1EjrI zP$vQacMKgxTDQ5y>ArV#depj!Pe7pWx1ubK&S>gqx~Mjaq3^M|0UXa|R#4$QlV*Gn z2z9})B9Slf+#EG&RVm9tZuH;P-&?V19%qKJXh-{pV<|*CJ3Oe{aasvtq@uV(tt9ic zRsPLaEt`#*Vi_E`GX{Y(D|Yd{3J6)?`&k=QJLEc0YQ-bvfM^*S!3JhQb9# zH+&6a>L?*mQZT<2;Cob2a2J?O!UquGID@&EI_i>bL&M3Kb*R^*6g(`)##<@B!PV8; zA3Ea4XK{w3_bV1Y{UOCa`)0s>>;CWIaP`KtT}n|%Z!4#+o#ML zKT0vQ-!@*}-X@n++<+i&$fo6d6Gm1*FKEt??7kZndK>!rP(%pfFFIAndc1jld|hk% zA1uj?+~u_Y@cz0Xq*;hed5-COqf|`#HD4Riv+PA!5`c(|Av`1Gf!+$FIP+Wn_iis_ zg(E7kwuQ7I&Z&D9+FVp*0}Y-J8r2~Wf0TlBXglO#hth}rF;jVJP0phVy0TJd3Hv9Y z{>`|gaWWF#U1>E+K_RM65TM$tc|DA5PZg85ManZO zlkg3PQDydLu&c-DBI_p;+WD@#U0A{Gtt1~xk0TY3-$h|CrvoamiPnAs{$g3|hOiS+4RyCEk74lrPWQSykeim4*T!OXwY$9N1pV)9A-*>akO zu$5==>8Adwn+XH7RAz<&dF~m=6kUq0S1_&)2vR|2LjwaQnANZsjfpd2%)u|32iR5> zh5b`p`4I)R>VJPHx+aNBLt_rWs!9HU=5)=HFh1-B5d3Gv&>)+Lb<|TmKGSf7UOdY= zItiK&;w(N`rohZ)N#RIQ*MM?*DGZ8Ktg}zyU_WVlQQhp7rL4|?)NsG;$%(G(-~4{p zXQXUZ`mod2$NS{Ps55Rtjrf)sk9?T@d4Sax@|qe-i=kd4o*2sX+YAC!=>^gpktMw> zXkXjv{0rprlH*STJ?ck9d;`fW5e+^y9SY!FSg0#mi0{~d4HGzXv4Ax6D+}JG7p1>g z1M6y+&%6Efn#bN+WbVt3XXDF8|M&HWL}+XDM@xKfl-TtTcBdk1ubbWu27ivn5f7eE zEwzGH(ap7RP;`nt;faFx4u?gj$wsennKTJzA|`nKXP|pmx31^ZNug`VVwLv&ISVW6 ztDL^~H1q4DTie`~B^l+HI(}tK`Dc!O@i|LE;qS`oSzl{wKhzT zpFR*VofLkzV@=g}B}3a!EMyr;<6^F;Za$Z~c1l<46R}yH(Tfi{Va;$*K}2x#GkOI_Q(X>gg6y@4*(j- z06->4f!2z3i;+s^7}=n-gpiB%x9!=FI)jLl>Yc83!3K7`q>WGP44K#d&J=Az2?6vd zm{HrrQ79B?C?krz>a_L-Y89WHafW|D2;$~uFa3))Pa_nW#1lVq&j?vM6ZIq@OLck0 z6b#k-ej|@$Q7YWzxZC0F$j8@{Lo}$KIbvH9Eorf&e+|X&7~*m~L&^K8(`nB<++(&b z`UKNMx%L{^a5-^k? zy7HYYpV99NE|1qPWl^xkWR|e7AqVzi<0t=8wETgi{|$~}Xj&C^2@{({xy$5-#LvDH zR)n1_UQ(H8R!sZn`O(9})n{mq>FqjKSX9*S|7!RrmM5ETKI!0Y{Cu?}BtXBUYtw*0+p77DbNT>z!{hF5>hZUvJd-+Ua)A=Qn{>xv!r(ECT_oYg{a97wx6AbIE^@ARylmqIyCZ1= z5>Eii%+5(>h^uxIuJmPhSR|y!^5ZoWB`If+O@MPUuzxV(kT8SYsmF!Qs3UZ~@qZ6WRLdF zJZ9{-Kg8#$u`l(E~BwYi}b(P*X{Z!UVr_arx6cYZd|7awl3LVKy zv##W_gMu)MOq$%WP_zp72ag2&m{Rr}`%$ASCE)i)Xag(9ZdRex@!9G!*m7@d*M)d6 zNSVu9*!zKffUem#dz=VKMtQkWL`Jx;cxY4Nw<0LKNSRUnUZ{^tst5`58al+AkIeRN zh!dNG3psgf()(yP7!opRri;?P;DM;qTA^mZItjGBoxxU3M)bgQ)nlsJ-iw3?0s`IQ zd5Y~p3(vQzzI%LdPYX&18Cy@A5R*UlX2s1?= z>%CZFSyd_-tvjxL!%HT;vb+q$noJJ6JzWlW6JN^9mPb=_m0ZkVvkNm!1JED@369@zl8mi2|Fb1Oow%Q~t zh$SP^g88=URAe{X$wJpQMwjF5+|)(1_PguLEfxmBIHMUVN2gCz#RrA456K*6 zc^3utMH~&L+ca=#nl!M+>J$5bzg*~KG5lDs$YN=z0gf%pySI+Z(7Z=>b~cYfWPx45 z)HD9RZq*m`7*$=vO%Vx`dU-@H0KmS?IxH*-b%Fu0T1>rHho&P?Bs^yYu+ljo849dR zphfHm$VahDY8p&X`bkv?*kO!D~l2M1ySUz%8$f0YBV zVwFU%d7mu3>Wp_7+G=3Mt|D?hcEiI?lJh}Yh5RIn;ta=rZA$^oj?=tO!=y}5I_wlv>&NrpX_aI>oxLj>-oOx{_hcio8MV$A{4Dc~CghWQjIXN!du0~v1=O`AMl6%^v9SogCl97;$a z^&p-V+o0m6a4>33V$8Dk0)=q>sg0@xQ`zE{&SDGxvfeQ)s<09eoxE-x2RS=>J3rrz zo-VtI-Y=^2E}v@Kb+=NCBRfQk?N3%5IQZ#^$u>K(F zKEA!tQ@$8;e}+y5@v}_CjA;re+tFS^&G+i&u>IW6*>zuXc!h=Vr}{E<1F8M_b7=D< zMJ3O?U3>ez$eeEO-SKe6+zff$7UOz-)D%z+R=tOH97Z0dsIPUFD$2b|vd8;{DJ+-_ zqOeMPhPK_3x2JhYFhi$i$J5}zT)`tit)bc&k2qI1LCsOuuL0JY8cT>w69>sCSn*ew z;yYVyvrB5FK!^I7BBKx&1a&qB4{pp#bCx;rsUsMDI1B!*RC z5q<%YqqZM3>8V*h-$ zn$e`+YNRrUp^Hz|K1{>k-}uf8UqqKlL*R;MJu#jXMTV&y7k?rmgU}9NrK|)10 zcY?^fAT*?@;zSo$YmbYgXmZ&iIBR*F1CQ<$IA}P$F89gGz{$9zOk8Dr-~<(f@gXlv zu~vZ-!_BbnGTFb;lDzT4agYH7Kx#2D{LG1wZdgmrhfG6bu=TMN1jYwdXO!2JsIp1V zZ~wnFFWJG;vH{hy^k-7ghtOw5Gj z{)qqJda5+te0+qX$T7cJvod2f3@YjE5C3Ggq6q0&yIX|dM+O!iS5ypcTHuD;w<{mR zAW5giDKpF(2Vw_8@N4yqciU-XvH&aAf{LQpx|>^nF+q<9Y3+9#&jsjjK)0Un^RgX0F>`LNDC!|0jI~!@;$ytQaFZfnC(y>?F%V(=vit;h)b6V43#xzd zBBrr3sB+=ev$Mwp0Ce)SJcw3F)|Fo%S+9hq(8)3n|0HEM< zRpE7t}TeToLj z@Xg1^;OEwKmxi+odyd@k_Ugb^BKU%KO;(F_Tgw5d7=m$ctxn_k_@7c9*uS=5WXUi9 z5ou|~2-SF00E$EHPX!EANIQCxaQ^Uyfee!|REcn9;&~ailhcpi8<@$u}* z^QmH$^_^HR_#X=Z)QszST36VFDS!DT zwuYy!%3UVG;-!B-1g;(!vfl|+T?38G&Zqj-;6i%$W_kCRS@zi0Y`&sn;4bJ^( zhk+2SlJPdf<+aK0_o?0HI5()?`)=pLx>2|DUCBP>qUI6g!jJj7ds_&@VIv5iR(#m@ z0k8C1Mu`3nGi9M0VGO9`vZF`; zWkr1t$)Z6|UtfQxLs+z1r<$k6@7Zg~DrSJ0K#aSh=*l5q0=YI=i=^Biy|5`d%9xMD z#lhXvy@O963;y5T>+Rs}Go_HQK!%ILbw6e2^+s=CpeC;X?e(1F_`vaTBxT1XVh>x# z#R*Z@#iLma*3b8~Yri|Q@&4h|<8hw*Sb_ybiRhS`6v-rG1wzYu0YO}lB@Umy_)#$I z+j#f8{?IA29<;VMUvp;n7H3*%W~cBG$w4q~wnz;be@zaA0xV~DYqS5Zm`|m!7m_4P zWJm!EpyN@L1sK`Fow@IwDJ<+cu;0#x2|gJj_qXG4sFZgFbGT1AT=}NfD}~0iuHWtD z;NqqER~*l6mlA<}&(}KFg@moN9p@G+Gbh`Y1Y~WiQ$o9%0XsLpriu`$8nZ%uoVK8+ zu^H+EGZIE@-soRl)@ZqGFd%4IJxXx+k!)&rKB}ZGT0K9G$wn_{KnfRPq5|cLE z74g@V2DMezo)iw%6q7%`N+pg|N{*-x6LbD5vsCZk0|lV;qJ_0CwmocjM&JPO(v^dw zP&ns$T>4@PrR+Z8A=`3`pwrr~GZUScC~!sFKDebtB=q(EV3wTwx!+#N!Afe|TxkG@ zO}a59J01P+i6MSf71)r`nhCY<12A2(!D?3ID;SV!E$VBaaDDL9_(vR$>%XwFMH%DF zWD&hnk_kn#SUy3Gc&TI7Ald^V7>XHo>xznah-`+&;rlfeV%?sLWih&k!B=$E`n7Qk zJ$lQ!L_*lD=$Hw5|48}Ta`^hnc7RFbHRY({SsiXwwWqjJu4a-1f-wkWu9@(wN{k9E z)YOAtl3CpyBzM_oJKf$I-489Sw5-u;O|x5*731`t!<>M;jqV+*`@JlE)_;hu>AZTP z?C#QFhN%P>pmC>LHBt~FiM_A!<%U{d4yh%KmW@QrQu!}=HvH(*v>{vQ!;lluB6Dzq z`5}fQ|E;L45245)fP+6RI*t=ZySOt;`Eq6NB*UkncsC&fv(MaQnaiS8maX$4oJeFk zs{iRa_xYr0eJ^X>?;IZfb-Me}l~x-#noPh@q}|%b3}Y_m?6axE*7YK$K?d4e?m7?s z#3VoLu@Fs7tk{s^-k@c}yDVfIGERsd(s@1cjC9?v-8^}=+Af+K>u*Xs$ibcns%kR2 zFn5JFUOc1v66eau(t}Q>i^|N-GIgxN=41Ltk!|sen_uKC4ijBs>B?b2Pu2*~(&ogl zXb)8OCpp{Z!`$wXSFj{Ya&h+W$w*G8p;cjF38hs>(?gSA75XS)Z1Y3U<-4R+CCaoEQg{ zrz^oF{16r2!WZNJ-i|p=uYgy__jlIAC8uir+G#UqKV0a&7t?mPdGq|})}!rBO|3g@ zEruZaIbNO)f(hV@#2%3!%h3@AR97Mxq!L$_*!01unbJ-GEdON5BDZ-hHx@vcGjHjN zI20@kXyVe-JQ~(opyBlEz{f2Ej!TAFzVd%*(l;b2HvBm8_C;D!Iq`krEjMH-RCFz^ z?OM~*53HUQX%FJXgCB^3TSgRo{s2)4C1cFLR+5=N*~POFoB_WooY0Qt@>?1uD70mk z^LznQq|33kF5}OsGUx}fCSx!<&Bgs%5f(3L0d+!QLrSBL1&Z>ICcBlB+DF^K zFPsgy-V!GSle2?Hw)ry~(gLB_WNQ7xkmxAt2qxxYJ(kq6rZESy0-3xs?oZ5A*iN{Z ziMsQ3_(UIPp}6>-k0l#en~dYecc>DjR@{v?Dd;|1PtAhcW)sHor3CC+9bR8^xRxla z=1e8;(kuoNTfH<{ri+P}oihj-^LbP~?W@ERAtS9ie?Km97mt1C@utlRj#buummJ(Y zI5RcHQK-t+tHDC!=gbWD9HcIeB(YUZ1zE7uv#yA@1q4NBgc@p8FQfp244|EEccj;2 zb1KY)ls<=!oYsWhIeTmrx?PF4pIAg%8pZvt-*8cGA`$ybLTlj?lpANia3ZQo<9%Uh zL@-~kxPg)PN}09ya`fbZB1B2k@?lL02o(pnZqH9l(6MKUdBlkaPMFDHX!~7Ar8!!y zM2li6ESEKxU4}moe+QT6LzULB5h9UyC@Z!i>-zTg$g=fm+s+%wU%XNB&q!=CHQ_|? zg2?sN=5*gI^Zsd*D8H~?P4n@tWhV~#$^7ZeERBQ~%fj&-H&t)~bXr*b?=IEOcW}U015^5Onw!uEd_QiLz5(rGu4U6wyWA}ad&kljr zRNLP*f0L%aWBT*-=NADZw4*eWvr>rU@ng#}Eb?mN#ah!)$K<|pqsb+G4uM^qi)uAD zmO~1uNYBJu5ae;9aO%Kg-y>s-kdAk|{%Ez|&)3#&ij=iDUvas0^<>Y%Oa3zkBzbso z(St?Qpedk1237y6GdlCM_aqI_2n=vo{^0xnC!U#2w)*1ifBt*G_O__qBNFZVzY%Ty zs{>PecmU21^O`&N8XN-yt759+|b?% z$fsn{@N-W3#(no2=jw+xWV5E+^hxpeg4=w;Mx$B#KgHP6$DAD;K%;jXmNx%;iWJEb z6+vyd*^#-OM+=|z61IUrF@Ig>8%2r!c%#)|_!+eokDW-vDA%Xs{Fq{%BQxfyLg3?f zF-h@QrzG47y}5N5f1NuX*w8Np<7m_4mH1|TkC)-#3vRtNUn_x9DKnF&Rdt=$394!3 zYC}R!lWD$D!9GNmqdy-cDxM!tfV~X(ZgVUt~|DuxNpgw%yveTr8{k; z1p2rn6>-0}em?^~V;=+0ad56Cf>9RF+vDjCwDep>bLG_pAT~Q;`{etVbR)Wu8YK+Z zgERP+b!+BoQJqT+Pf9BoJ91Pk=cfGKU{WNmhLWlw@u26_r#z|dZj?VaPpmHLPK}^$ zoSU4PbiFdKek>1-7-#Q^-Cmby3-(OyX`NcJzlb6H)mR&wMKILj7bw8HE+Za9Wiv!t zZ?I>=Q;EkD&fIGHMD1H*`wL)FX<3_xsRLf|Uz}L>k+$Y0CQc?#R9|(V(ZXc4^MwkJ zOZD2HIDBVC$0O-QGrX6$43?Di3wm)Y`fRO^zoGHC=$Sgo9caWeZpHV;Z}wq9<{!^R zZdAV1jfzQ44e#RN$Lu#jL1@oIpGclAjYE%LVe`*vg|5fX&|@PJAIZ>K|+#s~D|9F8^4md7OR!6A1o1 zc>XRp{`1$6Doi(}%`JATe?LD+KkT$Cf^{~ZD5mk`p@JkB1TF&2|NCh+-|NR~gjv@;ya|Eqo>nhj$W+^!5 zSVZryV$neQ`R9?`_28#(sEk@8Fkk>O{iZ=o%;BeCSs6R~$VevjqIRBCTW6<~m{d^& zI;(1eD0dWRfPvT66{^Yohs>Q~?=Jtpq0vA8KfK_H(XVP$0T8JU^Lxj2>{sr#8B6gI zxbrn3inFNBb-s5q#=NeV63OwaKTEhyTgW}Uyy7{Zc{82L+X~Ug&p$9#H?Mrsx;9?-rXRbdrdkK|opZl-2jUt<} zD(Ud}JLGZ`tohQ#Qc?|Gr&k5?Zn@#RMMN?gxJ3OvQJ&I22}Vt zb7T4pa`%JuZ$pHgUR#XmZcS+N;Ks7VTiTBvso~OKfWrMs^%)$+K%~s1lAT8;5VGqb zC9icjQIzKQ^cusbZOTo1`wJpbB`oLY!3tVIi>{g~&dsWX68SF}ilxuE%PA<#E6gHQ zINddXXO^&LAUWi>kLE%jd4Q$orQCbWmo4Sb3M#1xU7uC%TG$YCwbpzRJ*#o(VK5t(lbH^mq?pd?m45;r#hDZeU z?N@(WRK6>u$G9cJrqa%@c14^7yxD(G{1J@d;D+W*E;dl0(r-G>!&$|;xzF|mPX75B z4J!AUZL`yIGN)91^2ou%&(ANFMYm3iMzXdkJXldyG%dtJsOY7U%N-rOTbGMIi+-d-)7p{$cT8_pve*JRy&G2)+p1-Co$hEIGZ%JB4lLj|3 zcJwvbS0>HvHcH=nKC2w^iF7)9_+TCQ*f-wdDno&Q0iM}g@u1M+n5^Q^u!A~_T4E3< zR+z|hh)BafWkvp`+y;)adBBT5zFemURjI?bX+u(%RXV;nZ7)rDcDXsp>g&HacbN5% zeI^Lw|M;#g5qoU%9kC!E!OC9Fm4vXS-E-%lJJ@w{GD*hx)!5jkorn9=V^>JWaqK3) znV8MCNuJV5v(-#D0VM73?D+p37cFn$Paj@?4Egd?((>AU{i+_-^LE{&18o;WLde~Q zPNK6{ZFF$x$mf}WqP3_$UuT@g7)dCd{H?7l^^F^tt-qhJRi!d(U=#Z-n`Q;kSGm;k zUWKSa78LBK*jNmo`82^%+CMrjGW|{3|Gd#LXQ;1l3D!Wm$G`ZGrf5&0x?*={Pq*Rs zrf$iIDMZdvgSf6QuImJ%OFUKzTPLc(=(9D`Pf+udYNU}Y>xD)9RMYX@7i^?6Ve}hj zM=0Snl#zC9mQDeIzbj(Q#Qj-gQ+$U-6Od|KdVn{)7N3fExXDLe0>S41EgZ9kJYY;u z`Xbglu8Lc$ycBz3nphnI+=O!R(WLld;1HMY*(kVBH*H=K8i(&?bv{*(S3TVGD`282yvwL zvqY=%_vP>6*q4ky^0e1y#%AhGq93an0^A3%$C+@H=u+AQ)jd8Ia$hmoa9gY(p`herGx)N(XqTozD@a7JHC2)~T9r1(2B zcc3~qU)FUMj2ATEb2X!?;wg{ruyWntilqA?9NU*&Kx_oTd(XJ3Kk*v>-N3}Ehz7r{ zHo}M|)j?X)kxu$@X?Bbjt?KIP;`;RQoZ5;uW^*7`yCvuG?P+M%NRkw~i4~6|nQY0I zxaSmqYF0kK`eoPa{&Yi~<<~{`>)ia5yKof!eIo>|%v3aRvoBPL(D=0b?khP9iNP^d zWM4mOe9eEn%=~bHWouV&^(=h|?O316W@i)-v-x_L6(NBUdy=xc#X}_QixyYTkS0$7 zow1{G>d2`Sr~c`B(r-XD>%oANf=$drZ5NL2b~!XP<4@#E8wD znjXibv0|Gvm)Y8v6l;6Gv6*(-b7eKR!T9)K?W9MstnJ(Q^LOr~7d_+*@!_M<+dpf$ zs1fr1QhZUcvaIqy6~MH%N_$4n1#!skb~Eou-@<>GTF+1$=MhwA5fv@yOY9aM!lIWh zUu_Qp>M1fF@#_mN3*cp$8eP%BrFR7IAYmE&5L^7$zP6?EMOnqAw$ULaE)oE4#e%uC z?O(|x4|QwKaq+n5ASz$1w4mqzp9}DO1U2+}Hkp;A>#4=QeanpG^4JlUpP1M>Lvx?_ z5(k-r4?WxZYRAm|#%m%(aEM-s5y`wzXtxQ8HA6yu6bG5VlaT=`&Co|C%fEcAtZVJ)Q&aQOEtCuA=p`&B(>67!l&o_n z1^KYADNPMbsL`2BcIHd-Cp>M(mExP5qv;ubdOOj-^}=c#_x!JRa{7ie6u7AnpEznidp=8u(l)Ge$JL-e zZ}@dGQUoKG!`j)0{%qW>RaHe&sbp{@$oV$*vlkLe*=@(E6k9;aN8f)*jQ&2QX^4t5 z0e6}5E>crh9q#-Eizih=1&8fcjzA1E=onBc*~HRyV(nQzAKx!SV61yGWoN2dz9aQl zUXWX&pJ(6TZvz?wdQV01q@Iyu*Q@obic{AD+4{d61cOJ~D(hYikn0UPxK7du-t zGPf*(2a*yC;~#H>wSKF9*AF=x+Kqllw606B=PhJ7vP5?K@+qH`-^=+t+d!o3y{3XX*1^AiC}}UXoY^?+_G9y+rNZ%tpuJXM8TaH% zN31@}HUpZgOQMhQfdEfXG*#^Zr=emKq!Hln8z<)cM zw#WaYLgp`rY#eId1_%x?hpGO&VuV7D|8L=a!tq8>`W)*nuH$tM^~3Y_N+Ld2W{jwX z1(D^qYH~zn&&O>ZWWbK55g1#32E#)Nnus^ReN#&c_C*ysbP8RydO?y8HUmT!h?&Mo z)fJ@2Q7rSP>{0fPeCXkfTl0fha%^nkybvlay-9qQ{>7MeGI|}piL5Fw3Gug5{e_l+ zp#r1xV)4uuK=NtZg0lC0n&mNmMt}*V|PmUWhF2^)imhbw(55_0O^i%@K6` zDs+OAQnloIi0COm%As_CYUHM30=Bj(>vvgQ#{WgGu4acS^*tG6M76q8R)2N+MX zUZ}M;TR{yURcu7ZL%tcNWlzkHX|lHzD3@C7Ev%+RjdLclRI-RpRbtd6WA^kt0#Gaz zQ1*{klQ87_J(B~!9T8S{5>w-#a6XBpEX30{dWoNSIn!ri+Zh& zXK4CyuLivL;4dv+Xs4mqQ}MQA@aiq2^k8;u#|3hJ>VP zVlr#@GjVQb>%;D+KcylKF4af%uk+o1_P4pNRi0lqRK{r8GgWx^6P@E?7t|G=3f>;O zFO{C0Z=q7UJ+}Vt{n^|5H@Y;23#b^mN_uS)Yeb`XU;|`jWkWZ2sS(Q5P-D^>d~YFK zd1Xa=x$yRM+lwH?(|ZpqWTDe>#}KomL45QRo*PJ2xgBEv@j?^rYnl8QChw&f`&l-Xuk zvV6?OE=e{>X4IZLG7CNsnRv?azGvfk&*sW8%b^399mKuJ+dtW_ta)qH4eUppzS(u~ zsCf$_!K6Wp$nDd}6*)YZs!sB{Zr#kjPCUH}HbgVX%qt)?>?Q1yo6_#^&X@uCVeKLRz%I%}$`duK?9;q zf5vf^7_G^X0YoAEDQzif^>_qicpi?L9fK2~lgii3hCDZeKZ<_FU%Q>(mgRa$uxNW-a)>;>mgf7?Pg?QD|3m~hKh zuL@@kYF!VK%~sg*o)gNPM`$S;s!LrJR`*qLW@o6WWvw&;)Xi%SW-;6L8Y;hJ@3u8# zD}sC%%$^6Yzd_HMq~9(z97y|VBqk+mQ%qO=y`-9y;A)Melnx>^9e)r`6xutzs24N~ zjW6;_TS>*IqaiIWj_lq{giYYN((QO9sz(!FWr}|Qm^oFH7{T>gIv%bj{~ny*-um=> zMb512jhqHwx!k+^dYqjj?Ib&c|6ZP%Glu*-8}hqw5PLW`?*4l}c`+F_w~APuKxuo3 z9lkQXX0J{j~dL-!}$MDjeRgQuX&4cs(e-~GW)QrKGuyH=kM-i_D z7EWJFIM~qm&`|BCch>^`jF2XuRd;u1H>%Oj6A~s}jB?Mp<|g=%i1d@k)TU!H>3id6 ze0$j&r0&1B`6dTdc49K)5{r(o9J5cEJ7q->B`=SA65d0Z)*I1!FNSE?|9)Yvw@9Y- z1bOAwL`aLn)w)lXGObV4r=*BJgkaiv5zbXtS8=n|sUtd1B_n9qqQZggw)a^blG50l zCx7Dr533n=*~SDLo?|7esOgnfI`UpfO*Ufo$`dZTUUwjVT_GZIJ_IlB)VzDg?lLAz z@-ik{;_aQW?0WWU5*3{RuDWX}k=k@3fgLm7o&0=J^!S8W!Opv$Kx#B#7S;zxIo5T8 z%%K-T+&ITiCb;~tM0({3e)d?Nj;{rC_Fab_$fdKbg1LR{MQz z2OYd}_?z9o53@P>{o|-0bYZnCV=^~;zC?yC0L0h%LQv9{u5*@(8{TL+^~+{Oo+c9K zM^2k*Hg4$wi0a>cq;vCNCB0b!kG!pUH1J5B?|q#9tc`=KJguzSahph$q9TiK9|%Um z{KDz%r|H}xv=P&%W^%hJXnP|$+It-DWchW(CJ`F3Fw|B*(QW4U)R2Vlll@}BZL`f{ zf3Ol&rYNqPgRQD#uNX)We}THt|2pHBiwduSlj9O^vXKs{SW(3ZjJ|Lop(AmXKA3Dl zNKig(993Vr`Wq`rM{rt=LK$@|Z2^#w)`9DJ*i)quabU&zB)-A*09{d#59YSF9w8Dt-nPlqcVV+Eef*o0GC;^p`XZl_9mn)Bz45C(X+A)7r?%PC_xHwI(%iV`xQ@JgMa4uUxn6SZ` zD$$ptV1K_EqJ;zS(ft}s)qhmhAnkv`G)}t%J$*!^LPHW2``zbZ?49-`@c43=9IGRI0heyr4j!to)rn|cH&;X=?mT6 zTh1e@$B&MeZ*337M#QJ4&*?WWW%AFBwi6*3|42Ea!l>{tao-bP#GE_+;Q+xGBB<}O z()A+ED+KxAt{M||mFg^0xCTxJx27D1CTm(axu*U0Ht-Cnn0spBq25&Ki;Rp&b!H#F zIWfz<95{dVLRDIte)sl|0}kWvH+l^#!m(=vD%H;zP}{1ITHkV7JAV z^L`C4*Ky|XZIf&$r;G}Z0_edAuB3x}aIz;R!Ay6E+^pxNqlidz%DwWTq8NUcKD0bo1bi%yz6N!#?98-gax50zta}6hRtTFA2pi_W81N1>^ZJ^E>M?1$*(f2LHp{v>rZ|5t8^!k#l*`- z9q$+?K9aTjWF7bfLi}&e#@LRp3ANfz=^r=xFd7_rB{VO5S_B7_x)NOh!7C() z?YAVx4|QhO4|Vb=j^i#6=l}+qi0#mOH-Zm_cp`?00ji1$QzCYM!(>WX#CKVwrlZ3u z)h0OcVwZlvj6QzS-o8AzGMrkfEa8<3a?lZXw9?Wygn_9F9c`OiJA}SW@2@5PuVSnd zZ+sRRyle7L?iIbxrpspC^xIWA@iCJj|4op!L-ZdlWk}95jJ`UdF-m?tw~_b>h|&@E<^>zEw+jgt3zQ980z;@N35B)d5+# zTo!V9oCdx1YaF%Pke*tzaRcJ-O0a+q#M+vxbx-$RN02A#30UsEC~z>VZVDL3#SUDF z=dc+FAK6l7GYxuWFwO_iEf-d`F9mz|h=o`iZEMFpzk9TUD`PMH~M#uIE z`?bQim~4hs(Mew=`p#XE6CD_G_{3Y4fq_N-oHY2?DM=jOiB;3*X3y7)$W9#yTbAh* z9$6cHIICws6w~``Q{f&#IRP>Po{(aHsQgDeDp)j~?XvtWna5@n*2oKZift6ZR$C;s zL#EMLe z)s`@%#x=qjNiX!;XYy`F-9&8u+W8P5erUplh&_1o)PxDM!P?YakJML|cX{Mf2s>u&ZeAEG zMX;;tglE=7%l?~kXS#`1$a10}!M-8%kRC|j1H@@ZU&z15rY2&`?Q8`6x3>GoyfYj2Bd^@lBQ{VvF?Q)=)%+q4N;_8`fd3 zXj1(2O-T`U02JB$ec3p1k@xq)LJ=B7aVM(3^6A2Y_vNqGgbF4mGlVLG6Ki#4nu*q+&`vhEjwl%Uyo@w`u6k zW&IR729yh`7VJzSwp+ja(%b~w;2>Y)#kZq}PvU>GQ>mr0`o4n)w63X-B?c?nut)Zd zWegttjHR&%ZHdg9p|VxvHb>69G^T-;34dvLctTsETB<5|e129Iu9oMC4b^LAq2=U% zXrl6oFO#xMH>=_U++t~K^FwC#8^v=(7ZE&ymZQ(Y#o{~KOsD+!Ix0@5ri~_O-YzFY zs-`dixp~s)|CJ{4_TZJZ|Mle1m5H~q|6!kg*0Tog8&LaC7Qijq%Hl6qfOB{phtCY{ zMkO}Qd>E|_?qQODWva=Vbwk9uOg$>#xV-0Kb>qB`vuo;VoBo>H1(68z)`fG4DJAK) zO=WRi;~BvY`E5>&_9vw&Yq0E_I4tmb-zdq{itzfX94QOWYX760bX;D49vCOE6yC1inw=Ph|36yh0kOcZH55 zh3ZpYv|C#uR*#g)#wNJi@97l;l%k~S`R7;lwLGeHh2NPG4ZJC=HSPMZ2i^-Ww1v6( zB2c5Iqq-$e`#)@i%-!1c9m(23cgt94-H)C{#@cDr`6W01Q=8k7go-7q2B(WUcV1K% zjf#p3DkUgK^%tW%S$fvvup#%#5=l}eqvBZO>-dqL<(w8M!Ps4Ofp2z>u>lWg$`u_i zzL=AshIyKwAVZG_fA@51DIRt&$CbuWwVdKM9frR}(HIEcPkq##tPDnwS2NSc(UvK=5CsC74v>4}V- z+4L<Ah$P`fcLOi~P8~4J+!0u*=xg$R;2}AhY?j?D$4ew9^N7ot zJO^#cFz;e7;B~#?mnSY${^go`Ib%e({$osmq#xLv9l1$NrYcTQ4;IGKt*g(H4;K*g zLi1x4Y-qME+q1QpfAez7pUDNVJ{ zz)Ny11Juw1`A_n_LsT?#sp?Lp3Iw)C&eCXgXIHsSlUGfhWG(PY5)!1C*5M?$Cnv9` zlUr$5=`Qe^;57KD!yLf)us6ULx^D@yUwdXFEhG8xJI%PPEXQ#fW2RE_h)e=_UG8SMG#;$5LTmoCHH9spQBXad1O&vTU1(<#4vL|=3gfxgRUVjp5QV!-W1QN zo4)<+)smXS_H;XDFat|)&4Ean(;QHKPKvGE>qB55C7!+LD-ggkc}^_38|Btc(Aq5E z*LTM`qSUokkGQ`J_v={%wY~zJGYk-NnVEOp##PHC7?8O`h#IkV?V?k)(V^|0Z^?q$ z;pA~h-ndlexLKS@R7|&wIPJnAd@O+C0jO9w0r_!MdS-Wq1h9GAQ}h~IdL~oy+ByoC zD5$=D{~?^E<5=vpwC0punNfl@UFlcxvIR)!z%l~>f>jA<_AQkLBnlIo6hQKbv_AN4ED z4(Y{MA^Hu7kk#Y2!W5+!7Z;PDG>GyF5@kh5MqdNcP~Wj|j_7?M(8#Y7Z9uK*H?g_t z@ZlG|WugJ{4^_lV>i|qz9z|NsE6rZqJ=!$M&YKD*?pV+pdIS8hFqSPI0Ing{Ndk4| zF*FB@BWPBdn=*g&v7o-jBMdomCG4C0_M}}p%$#1C>w3m?mB%A>6>io~m#(M9Nudj4 z1qO=m+63zAvs*SbhiLfLDr@vhX{Y6=s#)d(=FOhpa{rqvr8-nUPEO=gBt@UljNESi zcLjD?5CpagK-uw6Py|ksrmY4s2cwj+dEBbkMpa+37tJQ5!WKYuVCeI#>}U-bo*ltx zwYNiavton-OFVzL8s{XH0~J2ixw=v+c=Cd6bKCQ>EGFb%J1~6nB&J zw;V3ACJ+X)^>$vq!q;|5;k(GAowc558JaeG-nEq0p<{ztzD$7F#|ts7{7^^};<)AR z;X<3&x5H6#>y`Dxve4A}!xZBa-_xN?-%Kd-{=REEg!9_bWJg=tKjijLILmD1%3%j= z$fpD0EJ71tBkGu0e0Zn7DKu^9O~CMylOv3UrM@yF>XpQPhlF>IsP-9lLV~~O)3C73 zoT$}5?~zP~r_J`Fn>zVt3IA-#YXI{;P{0u~Lqj8?#Yoq3^xHWmi(Ir})6ADG=Hh9O zE=<`W3kDqnxCB&-kSe8Soj+VqFvb?4?afq8Z04||>L$ruEdmmWgu1r0tQ?C?+e3Hl zpT((wCrdXl9Jm{K0Ko4{)h}{$^YXs3WTfj&iEoV?x~v^sU9mW_&q{50ymTfVGCOqb z=xFu3Ifp0e`Aob=1}EFpyniuazqWn)5PKSNV}1WvLdm9Q#;G?##SW?dgCp!Oj}KLB5Wy7=wXC?a>emF zbOmzmI0h&wfcqAu;?+)Yh>s}x*8k@M&>0;XsPnwmN`szRQUlxeEgs;9iN~&i-$)_A){JB@rTz*gQ1P7IR$C=d5>X(a9Gq;2m%h5XTvs+{kC zw@U7)?p}}9Ek#)sInX=bH;f}M1(_Mdd#@|%r%mJ(6hQJOIV$J-Grf_1JvSuzc{#BI z$%{=TkQQf~KhI8>k}+&NL?=T*Bnq>+?)-UZuH@mE6gLO5ZQ(Y8r?8lxrzI*%Qzq)R23S`A#FARq(beAFou>@=1wcbAJBy&$ zDT z{@DK`^lt>Op!M~o#9XZJj%J|?TI|-4NnLsGxVcuu+zX6KF!c#f)F(nCvgjgsoCo7h)>RxP;eNBmGWsFRUX^-Y%x1Eqay{*8~48mJTIX`#g&e z?LpHq1&yrM&uc{8K~@%p`c`*Zw|bS~^69u3N+P>bg+RWa^Noids#a0+`X)%AnI&Ml_S_0jV!FJ?#htay~z| zCfXgU)lu_2CNCQyWp8@H)E~SEQ@5@{oHWmwOdKJ7PQm*1mF$q;J=vqe@SAS7OTgOWjo&`(?H8BT{Y`-M!I^VHdT8if6Vb zyWi#)b;4h3YSlEM1Ai9izE}xl|E&0Yg=*Ou!d}&Ep+bydess>%?1^eJM-oh__SsS{%S8PORrCtqhqs^I}PNp))_ zAWCV|56jQocus{Fa?q{9eZf(Qbu*;N$_zr&$nohSU4){rrL7hyNv^CNb&2%Q0MTo?J!D zzhSDvj@3Jink#LpHg%Yk%{8ATZO7pdZSl9*GcQF{31Q44!#_Pta_MX^*$VfREY!#` zj2YiJ8U2_TE7bT1-gF#L3RorbVpLw*7dIV^|3#gYNDx&m5$Kse$X8 zk7tu#8^IL7ZLYrf$XOEDl~w)A@Z2n$SbHj6E4w`mxj^1Zvl zuDDW`4hOeM!WUE7jrB+&+R~m^JO{ zG-$kcs%zF_c$==%3E^H8Y_zV+L6nw>}r!2L*0ekUByK(kjCtCeeA#?#_2chCnD?EJ9jmKMGE>J_Q38O+FD zbl3a(eDVr@d}aP=+Kt!EDCcTC^E~o2=pURf^gqd5$7wL{?tBShEQ>8tTJph;SasIsWy5R-|g~s`B)Lzxsu=6ti8cs$UxiAYgcP8D!{`jclU= zL3hPVD3e=4Xo@Lh)pTVW;?S2^1O){*SmNU*a>qw}i_`%7@;7YZQ90f7eBs&N#OinNxSv&Y zkNFC=Oagd`m3omly71+B$|4rd+pWd}vB{L8)O0HBw$>czYe*)AXmBBUB7etRe?2-` zb|8UmG`$@!Hz3|!P5tIuc3iJZo|6MMXW6RvpwQ)om}bXua<-n9?TP@Ln$KDw1vfu8 zuX-^j7eZdBbnbD@-ybFJboOQ`T>BG751wy8MkVS76*~k%E7Etu#x!Bsa$M-WnfwPr zy3!@*_13riv(*E_}uZ5LamoK%55*K_64&c}lx+`bScjt;}&3Zf^#O<5o!(ws!w-ms4T@s^l4j0yuu z<&x!4{Z9u9jq+ZP!TMPIKGzRqcF8H|Fgql&$K**$Kt=_9LslPEF=xYXnE-}ZlK0!dy^YgWdCydoK@ zw=RY}IEj<=GtdxV8y)-ZXje;)^LykGW)``-@}+}Mz|_Q=@Olj64;S_04we&Mump1eNIod6m2 z)s_utL#aOJmO{}-zi=dr6g`89NN@*J&ihZ05F(AtA zbc`;J7Q{{}sH(d*h@C(+T~O<#tXyt?|q_K^0(zBqQ*jn6G0X4p^xEjz)W zIXDXIUDFrB$bl~0kYCvaPu+WsJ}*#@sHqBlI(<;f@2Hqq6ctUq7*q9>vEA1ne)=Qx z=)2vj&Kde|Gj>kwY3}JT|I^*s4LjeBDY|>R>C@f-$>b4^jNjjuki$hrDZf^__A>4D zli0%Xueh;&f2vEKf_RnS>YTNFyk(BOkej`8GkD`d4dbm&xQCs;c@c4h&N? zfSa6{t*uJ2a+Z+y_SdhgaB>|B-5Z^-O>Ihh7{H7SmBf6AiR!v&pvCq?Io2#u32~M6 zVf`VjdKfi|b(NF9?6D0oyJ<`sVKd_qz9(Qc%q%jGJ*~Dw#Z++dX6H>|IV&Ul=-?oL zt}GX2Q@7L?vE|;Ylsc5j@SRt~Ll^pQIH-VvaZi1mT9NQ*=B8y7hX6A^gU@4iXTjm- zld^=b`MosSU+{~xlEUf!VS63;K<2eg9lSr0k1B6?f+b97z7ux~0e`gl zUc2|8G2!wY!Q#3FR9nBtnZ2{c71DLwD=h_q(B88%dwQqjU|plApBeQlbDx1lHKpUGkbR% zeNEMTjk%>AFGZx@1*7M*PZf??mDg-64(`g-G}zE@Nz$)?fL zh!8gDX|Nl>QVIKK@V$P1Fx1OM$L3K*CO{Pd1_)yW`;y#GG4Ec-Da5Vhr-`7eWA?dP zi`OexqIte8Thyo%?q7ilV8Io@AoEtSZz!+lPis=z+Cs6z3@`5D5?$a6Hcqr+BU)PW zuf$LjV%8+W8ah!aBe997n`3tEcv~cKzFKzaXdmsL4`}&>@mMpFC9gcPEGXhJ?u4p) z{+jRPKe$yKwXd3!qx%B8+@U_~HdssrrXPM0c~!P@h&H9$4ibItxC;0}Qv$wz-gE!A z&T8MHrlz*NaJnFUv=j1{^8}Q@*v&uk?FhYug`WSL-Ea87H?5_8 z+ugB-2sxBo54_(Kz?c)0@$-Xrbe{&0O^HXwMW^v6@~2hAyK^d4S*<&dI6{Z@41Dj# zyg~yz7;jg-Z~7wV;4|LAjH2SCroyVZ5RmHoQm};P_me_?4oviHLo9wnY(1c;s4+-Y zHA}^Cva7OU$pQ=qBOw)lza0<%w}Dc-SjBaciXT`!okYWA-k?4q?f(!@)IEVoyr@Id z$W3(CxBA2NjLv66QI!zqx_4;-XI-X5JrL zUy4~sG0&4`FBdA-F(?_N>F#+n8vsQ*UT|cIZJNCM_p_$8x4OSYIQC-N-*Y}(!4c@;`=DZioxQtOw&4uo$o+J7HZ-OP!==v zR57VJWf+%S7M|4Qz)A+s-8-q(U5^f08EOB&?}J(qpHPzbxx+&j`0by*F&xG&E7*mP zq+yf0WH>E<2BxskvSGP(HK;!+58`ITKWzk;_luZ{DBc60-KtWM=F_2R0-v$=c|pS& z_)W$Vt^%6I)&uR311&EyTYTmsk1uzgKTW>6cjpOv)aBdw_sp{Y^}^Xm=FMy+Vfi-} zG;JHhG&a_6UQ@O+c8i;R^aB>&?KfutW&5i+qB<_9 zjupm=?J%#*zk9RuC4*eKyRP<|5W4F-fs)@9KBlfMP)|D`WK{0`2Pp}e(93@*>j&#M zr=f@Nszk=8eqXPE~HA*A$G#Xu#2GgZm10sb zP`%fKCICl$@xOf&)hG#GUw^d3sW?QnMD-u$a~7qJ__NICFJ@WGDmn4e(%a%x2G=bN z4dcb*qkhUVQE73$ozR3EsB3XHKTXi@(Lx0ENpVQ_cn61b^$yxk!fca?eEt=!R*y3X zj7G`O?nqBIj z%Ld4~3V?hkQ?0TUyL^Ui@&mq4{H}43Fz5NlATrl`o8Iqia;B7|y!CSNCJb?DS^gKL zvs>FmY-Iwv=_gppoYjV@?VoEVf*qS#KsbXFMXBH81x^h6jOf_b5nxXBsbuP3oozg9 zg)up`-ftBrQa$xxW(S@O9NZTDntMsOA21D?z=|z#@#g2}TI2TyxUM&GZ5?!iaB?Pp zl6`h*mlFx?&ERci6G5?xoNQ__x@g!~`U$1un=PXV01`P!5K8+J*P;%fwNf;Jl9T*m z;-5J$T&VV3UbW>-?LE_d**KG*qdRJK0vhJ7ugUuMVoEKWl@+}sC#ESeF3er*g)SQ`Wr-POL5@B$-0FUhD|QJRc@hcqRVq zykIoD&~_+-RtaTzACdn44_y4u+5v;ig{Wt+zH7}D2wFN`mBSaZ*)S*6g9;y8`3P=B zob1{GkQFhrc(Pe%VuKF0F=!Lncincn!D=wGVaH{*-<4tfpTjV7xwH%mz2#qz=GsUg zG!j^hMJbrLX^PcvXOWvblBK6vOILgkesGxY)6V$)=8{n6NpLuzyiHwX+in^=wqG z{Th7W0Bg*&$5|Bmu#)rlKD1lcVykLsxClePJ|aU6$`HOiH=+4fq2Gr)+xv{05yb!g zzO!7ni7}F`*Hmc1;-Auvt$FHSx0HG4ggU~4eR|8tRy;yGI$&mrH{&0!K$6Aj0K2np z^;~iQ&ro>!Ae!m5cAoU@#0Tk%L+iUHRBGb=$eh@tanD75Pr$=1>eYr3N6TD7s|iIT&c>h|0RuekutFn`{r1xKix zYfIA}{O|1mV^298X*P^tnGhcz0}UmK8ZZ9DGe9fX0#MRO=#GNF8Xu;U&vTcs^y~7c zLQqJ973Q3j(m+JEKZNwZritpNn!D(K#xH`*4oerTe-oU$P1ju23WidBe5A3I`d>}6 zdLu-A7)ok-!a7;|RRO?{Y{Do4Nl(yDVWX!|@x>96{pK(9(hW6zU>f21Zdit}$c5|Q~i@@lO;QyiNEd!$bpYQLb8)*X_hYO zln&|6rA4~C78L1{l9m>bl6ybj`~Q1-J)djlJ?G5pj8@AT(wI9E&KU=9ud2}Ls(uit zg)yP>jj}4a^N|TL|0o|8U|*8JIsXae<)bjyE%FVt@$s+|jX}pu$jhLJQ7pszU|GXyQupi4N1tiiqZqC!4;Pb^lb{F@f(dX^5UX`|kBZuq6 zlvo@e3#WL$H#9w*M*J+%dh{VEIuQdM=)nw@CFNl&)AXI)%ExIlmm3?w|apqT162Ot+z+l@iUoEQ`R?q6&pzGFuyHd}i6@4Wr51h_IebK}= z=!%wN9^%vM-{-Ba7F?bLJM>_7<>7Fo&YvEW>C?1qYPNj!9$%3aC7er)wBPuU-u0lC zUIo=VqCbEt^4jm|*Z2-{RCV*aZ7T4;8Nd2m&n5YHCeeGNJI^-Yxx`>S?)dtCc>daH zao2cq|L5Irh=ilYd;RKpcMB(qv7X7m4Fb7V<7-&$Y!GkP&lB5fs(s&VvObpjI+Qul z{5+?D*5*gDYFwVY+cz5UeqZ0);5CE-fDz(tYgJg?Ty^g1vF=vk@t>Zeb9GWT$lWk~ zJxkv5k0X!0IBs>rSK#S%vZU;P?mq6~6;A}{-|?hLOjed|Ui6?l_+2JfMOtdxgK2dZ z0~4``V{2A~@DPSpt<@S%NXbR~W^yo|rfz0?=pxquM^%Q=RJicO7Q&34&}JL(RcN{! zdudX4r^3l`y5u8=UwzsbBGY(?_uCq4+$M@qwTz zzjZ;Jk{H4OobNm0Hjo5r#a%i3p2{YNMfpKM)!0OzwH!Vp?-t(wOtM8UPXjV7Y-f~{ z--e}5Rwo-p=N#6k_~Y62(2Cr-fAL28Td?-EU5-CXZX`sUZyx!msXtIy_4u093*JQ=B8?PlfRu(w1b>9<5#wfM~s zp_mZRn8p;=e+uwys^=raAVNV?@x%0+kB6hgvNFW0c%UR24A)KrZbX@8J*RW#z3H-y zpKGr!7j$2rPHHYh?Y_LT~dZ{>{kHJCr}5qT)LP6WM39VJJU`}OUA zHm34`zWCnZ`jTWzKk7rXasA?PQ&ZEok6Ycx$JL9yUKiJN&qq@Kl%BYM-DyZ+Y% zrE~@s-XoF~pP$9<&;P#p{oivk?LVPJ%Hk&+0^xE84HWLwz&U7&7`=b3>7p5zQb2fx zwtfeFd-o%pHu1auTv=7N5xENRcQ8?MgBX-`@AX6?=ff}F_w*X92HG4APQ+TZ3?JJ% zp>LI^f%r+C@PR-=YG22H4hp1J%JTO;F6P{|SJtdJc%*KsG0~N_IyvRbmMQYpky68m zo1Fk8JNch_P^)Xs8kG^p>V2iAZ9vZc2-%qPN8 z*90C|KcQ2hGXIQu{X%?&_~u9QftXzxRn01)^62sqEpjXho_SZAi0yLtyQ44mMhtc# zOIB)CGL5K;Biq&tuSR%sa;iGv4M`29=&i;Ax`KQLI(=r7R?S$N_|jDZjH(Hs!vW$F zGBy(eLUIwBxn2389@7`K@L$pdo6ncwO*sP+jFv!2Mq{U<@14-L`^-%F%vV=t;ai|q z3M%w|v!dVH4g|h&IjSQ7X_YmH+O@7Er20k3PN1&n=)76ZI|`%nl7Ys-yP?s2DYEij zIzDZ)J|cgT1ai!(?Tg}usLV)40JA!1>^-t=CO_ zh$3yIqn%rYOBRf)SSZV3^}@2XS0$d23+V9MsCT2lsmB$y+M?5~^^mSBK2Bs>_FQkj`N;x2ePfZXH_!cLIUttA zf^$kP>?NYL(Q5on-v$BxX0Oc0=;s8U&6oI~f)Pv(tC2UFX&93Hj0%DZUe!74^Vee& z6Nnt4*S2R8bT=Yysr;PSUzk$X8)NFYylj5@zu6wD6+f=KHt`2^<|r*L8uS4?`T&+# zj>q-uaEF}Kllzd+kb^IoS8fX2gXk*pr7g$Q-=Hx`>)HZdD3+mH4$t#aX7xYfyf=dW zEELoSKLn$&ushy+^{M{+tLpzu?zHI33${DxpbuU}hrCjH+DaU;(zTrZikwMjhas?s zqsf9vUtT^RR{tsZ2q+UieDYyW!%FH?kJg)knTwmhe-E19cirseSUfy!Jdd_^t_E%- z4xT^JJ=z^S*@)#S$p0-+dS~DKWO93>nXM3^Jjxa?tBY^K#gj2#(8}D{jPOq(PWeZeOjt2 z6*Yjkt$GY+jz2H!S+7jCi+1d3)UHy9O@`5)OFazbZ!|+kP`X~Ng|HN*nW^2MNscDO zs27Fs6L&@{IE*?cok&TS)7=fDaHv1x1r|#5@W*nsJVM`ofUd!E32JcPu&%7UCRX)p zVJQShu?U^G2!5YlNjKq;Y{=u*7b9-Z2*fFu6|FW_NZuv?`j*oxY4ufLp%y$MczW1f zFEKen!4Sb8MOAE!=Dxd8-qE>!J7|}nx9Dj$$ZRUpjx5Hm zRu>=dZ;&Tf00!_p;EFQqX6ji~^50E!UK01W{?&&w)>CV+%P7F)cH^*Wt5yOwzbE;v z%@YtsgNUPMN7q@c87QvCuCa+N>mcb9!<87Jo@RY(W9?tYHM4Qnk!eumbN)+T@LijY zHrcqo9FgJjun&C(c0{b>^JNxfeW-t>Apyo6o|+^4oQs=@Bxgk9PTPdIeUeAl0DOvF z@}RFDMj-=tr;k;B?oj)?#mArc$&R=e{PZnZp+B!>>P}Tbrs!ym6gM*b(kQ>j^0}RY z+J|++gFx=3t1I_{M);sR9_;6*s5iiP(o?`!4uu>%(yobu`6`7FLAiFN2yB`gwYuGW zrc%=%iNBrY1IkCCUhq-07o+PpZVw(!X4g-ErkWNy{vUq3@s)q5dEWp-@FSR9Wwf(I z)bPUKDmW$-lcHIWSBm7sb`&o|;wkp$r~z{ft>5vp;2EXxMPGT6_Vp9;Pg2MF$0gU^ ziRBv|&{e(XZ?E5frnMlFaGAwot(GBDh~2WseP^)HMXb}%C(n_%a|-W0E%@!V6JNz~S|8W*&5^M2&G`s6~+D5@o$pD&m-!5x>?kQ&n0B&HT0Q<0+2B~XGdaQ5); z&-~)I*H6k7zi&^E8@^d~U3BD%CtWY3_#7H$8jwWG#AKbX)0wWHN~f)G;jjS0DOacL z=dgnTLOKFq2=1AU&o)QO*oAX$o5vuD%no0Iwru0_>)ORvU{MK)_1mXYi1#zHK~oAn zpCr8vB61-T6D2Kui?7jM>}Bc-{j;4tn=8Vr~AP4e>DaRnqF#tnmif({v&;F%Ez(@ zd{s{!L<6>BxHMj)T#4u;B_qRr%iH{25@PIInj8HV_W?+Q)mEzOzr5B@_)9!Sxe~o` zoCPc-K9h;o_rxpqW;^x|{z4IcnMclaT81hLS5;u1u zq{@>b7U}kthCGOPuc+asZFzV1s>NO?XR7KUW0d-CByfvY>O3aJcimbid zKxf>ySg%xpMkT-szmJWWki z^!{k`ZEZGu{e$1kK(1zMlu@Z_-K@=%ZmEJJewc?Zq_9L+_e1Fsnfh(zd9j$A?G@%*WdN|_rI&jASxuj z=kS3JfD>v@gHC(JAhssxwB#5@ZGU?45|svsP)nue(_7u+{a+O+@85e;wgeT;HOo_e zMwXt<-VEQ<-w6{Y1#)6WvZ&ZnMiM{8BFUl^a~k>vo3eokX2^7-#kU}75gr_#%$Pz5 zI^76s<(1PS=&iT_oWcfHj#*?RNtCg)n$w;V*MPyi#(;3nZ#LA(9OB3sT#t~qn&pqc z`V=u@6%ER3XcLP`dKEHH;0o6E{+5*~kVZCJauTV6sHMY<#Wp9v?C_QP6SyJO*>1z`SEXA-=pshZK<%GBsj|>1{%5dQ=)&I z6ZUUGdDdLb${v;+0O>$ zHJ<6tepIxC=+9Pi5Wx#YGr*p#s=D?H9NgdMlo?OiL;12^6+iQ+NSK9mz?W)5lRgVK z^PS?{*75fDp9mqqCi{as6y|tO0${qfbheo<`H|;lM zD=NXu{R+5o&TjNSVz)G< z4W)j4i=4{vVQMc4nBEa$Xm53*40*Ww{ZKA}vodY_{BrnWJ2bew{A&MJLt7Q_$!ZzE zi`ImN=Ry^E>5G<%K~DS{$3cgQ0+i(td?On?PZMHD)UaG*a6BIt^`hrIg8Q-m`OzPc zZzkT^)3JQw{PTV$@%i_+-Ye7kd<*k1;b%T%eq_2>5~x$C@JMX!~VR!dIy{@wYi%F55Cp=k42Ell9*B3<9+*c{74 z|ILvfN??J1bZadtVOB*m+)W7H$p8)(TCc_VPdge$e8kDwofV9~=#x6LUd9noRm!5o z@{A+Y^wul0gQHc1c?J;`DiZFhjq_f=SVw!_s<7R4fjL~k?yv~HcL)54qFTc;NfqI) zJ!^~ej2LC@)QTAdP_Igt_$)*q(e(3676t|ZSTjj8DZ@5Bvv1+Wy2JzA0c8R{2)Zhr z@KO%1$c?f>z?D{=T8|cT)Z^2QR3hiWQnk!%xKc0N4uqin9be>{88+XJmuR!43!NdZ)u#>HW^8}io0e%6nH-EBl^_fz;adpA zQg??ljd_u{uBN&r5Kmr{2hwjvHl5s2<{>n1TuHStO6F5FFn;?Rn@f-Q{We=90T-&0 zDZZ(^D_CT%n_Ngm%bExx#2l)-DIv1~F z1w>MAs|hB~6Ji*O0ddnRxgyp&HM)>8W~Y5;0U*YxuD+aJqm^95*DbKzYT`i<{T0F` zm}Eoi`4uhjo=MEK-NjrjV!HnzbTBk#gq%~#n_gO87QyzOfDmD-aP-;Ksf)h;6JNbH zJ@)T|4nf_erY1gt$ytv%m#CnCse6{&f~u8ks1W{+u*MTevbU?}Br2%>At>6~)Uef1 zb=cOYO;p8Ggr_Zy_KUO+h9$KkU?*q-imI>HS7}*@;X`9wI28fDNrw&-PoUI!11 z*d(_&KP_qP{d@OW&`ke)-YL*Kzm-n5P?#$Wh^6&yZjMo=>790%bzTZT1ecjPTt)!3 zd1!h!+ikH-(Rg<4tJAmyABPlV9PsgyltrCX#i079Hte>BzA%gNcOw5}XWI_WCvp?B z5@)?_EI^{Oj#UV2v2<`&%xg)XznlF}_L;B61J0Z41Mi08j$IxPKOT&3U2fl$_jbEf ze5T~im+1Dn+l@lf)_)+Avl0^%1aqd|aZ3mzN#q?je|_-0`8FIE20?I0W_{}_>-$DK zCY9WA%imcq5jDo?S{{G?H$f)0O<%hawFEi;!=!#HhH?I{rqXt6S*zh8N%GRl2z^~{ zZ$fry9#~%<6M~&%z?E)<_?-HyJNl`yp?v99u9@DvdkUlu!+I|lmi9$X^*gR!RaLrU ze>G+f$-Cc3WBOE8>0vCG%$$)Jhxb-kJz9T=c{g|6R2z3HxY#5CFDE)n7DZV-Hp)T! z*tz`IsmOj!yAyTt9Kf}5mq-j7%M_3Ab}$KcdY_Qh>CA-S3t|0AUT+GI{j|OPh3$1K zn^eRPD@?ff6#$Zj5)!ke3M`;2OiHWKzm8BDh^0NWREv(!g-4P3QudJn!-oYIa;Z+q zI&hZcwPj%a?dD`aL;Z$tEZ~gIuKWzwZ^Uacu`cYJ>dlrs=AH9UL72Q`%bw8W-tr)i zZn8#EIwE-~_`O@WgzeGY`jy4>C9TKDw;|dAQEpxw#h%W?x)25{5fGN+JJEDa&|eis z{qCxHH48wac)qapG8+~-RL||@$ek@~q|ltlD*mE|y)}j~-P__5sYBq=}e+GG??Yqu}?|bzs8)>;>{#F zd;LkwK=U}S6e7?wrcM$Zp?)RIrpRv2bwUg@7|0||N+M|pO&~&xL{DQ=l+jlY#jn)( zt4~57XuI0w9Q2WTqid`et*iUziN)qKCz)@W>$cz=mt!O6UTs*Z0G`$A3B~Hk$<$6) zP}MP2>&wk@6{j3S!?vG;&>1+<1O*wC4WT@-6(bNu1^eLIrc%Y`nK?*<50Mn>T`Vt! zs<(oHB%z&qwx4k5r*fKR$w^;YwqIV#>c-c6G4_?g@~oDxlbgN)zbb7H=p$}s$kg*{ z>!1TflpldK+@Bx+4Pw23<(vDT?B?X;2=(6di=B0$otNJ4Z}=Tw4DU`|3or&g*Ls5z zdarl6yKauym6VjYyZ=bbXSS=PSex1VQQb4ZAXX~l*_fwJtC=EAl}BsD{Q{_6$cDpl zr8VC!89A`3`o}w?7K^oK*OpP05~8RnQ#P);Ub&jx|BvMl6S8 zLx(uD0784e&vToydH4_mQNV#yL3LHVLqkt9&0>VDnm|@Yog!@K{1pJgT=mv`7$bFP zP>C4bhrni#Mx!w4$C^Z<9M6Y{BN@wW!Og!l}5#44-RlLS% z#8<&Hq!~Pi?2mBNwmc)lv`VHv!d)LVb4afG(tR%7^A{plo2^GMY{72zcVqMyMZ!0l z7ak%^yaJw0vZk0X*MNT^HtdGs_};-&5J}yyY7|y+R3IUC{&PEV4+2VEblHd!bUwhl z2$VfUgK?gcT{gujyrJW9;`Z)rpRr<0cDVX;+-%B|KlV;QY7$%-? zhX#`~jmjP%StMR{J)~{;M4!QaPXi8H;wxo`ScQsZeNK4CP-QFjM};j@5Fu*dV-Vfam^u_BH*b8?IQx>`Ym2aq8@qc)3%3oMT1v5EO9p`?3X@GLcx4Fvt&`UIqwKg~?q_WXr99QA+7s z01yp!6?X)FJ_7Ok211mj`Do6N;EB7yfWod`v%KPr?oNVMyh{pH4~Xl=>sl4~I8(JU zTtPR}?eJiWd=COTZ&s6~*QR(WTCh47%r^AfI$BJ+9u7`UZpQEK_RsP>VoP6wq?4#c z*6TX!+LzUX6L&znYz)>9;#{1r?m@|@fN;6L28!MC0 zY|V_PiAW?A4%dGhK?w2kQ9ay3PKXwMheDFiuNo!2g@oQ0NOZUV3_Rb8+W0%t3Ifwy z*lq;iZ3H;Z#J- z3#wH9dw69aw;!u#Wo3 z!q&`@c>q)^#K&?YaTDTot3+cR+en^A&1Mv-Mx%%%L}xc9SaCHWTG@N+j2BniloQ6< zg;q{oSOy^0^1#4cj*Z4q{k6A~)&vDiG9b#QOCdC1lq&`pM&<5Mj3Ht!CR9w2U8Wp< zUT$A(-)L`4L7toq=OeEA z_!Mi_#O5t;Cm>1@gGA{5en!OG0_&mO(6eeS!?*#!Z}lxRW>s!BNLn0Z%wqSO!DI=5Z}M4{%C!S zVx#g79Zf@P_PS4xDXkLWH}F@uAsH;-sPr36Ag4f_o2ht#2rC?jk-o7WQ8tIYLc8|h zIQqegm~Xg0SC6#Z4R@-W%{ZzGYj_~}22MGYGe@K~t*XW$yJuW@GhD0B;RQ=%qFl=O z%wKH<@mquuVK?0s{|H!qf$uLho7yygQGIg>3ktFkdhd!%@w|Bg;qN#vo;ka?+zd{s zyF}(%K^4kzovP>F7~6QxhnLGFN4$)jO>G`1XMG_=8eYUqm7)09R=;a+4;kIGm5e524>g?>!Y^ocTm<|djH~#vbVx1ie)2i z0Wx!$%%%Wi;#J(7K>bE~Va(G*18R)3{5(iTs@WcvH3Sj`)xQl5#cfnG)K=XxanmDG zfT$a){)2K^v7fWV61ZlXLgUO(K9RnyW>(21y5LT>hOi3g%9?@*zNSPt0PvYxCdT)O z4x?XcdNZs3kas7LXBAjWflSTv@8-fVb0hThV1$QGRFSJsuccSLs^?>+8IIfnhhGlg z00Rtt5jFE;I>02Y96Jpf3WgWTpS8Yc0Y0!Kg6!fq+QoF|A>M?vn;X0L3nSyew`56K zNFZ2k(Naw&(;N}aJ$_umZn|WUkU7+uq&cwJ3eYT)n0bc2?Ebv~gr{dpR}wlq#S6_O zW@0uJmt-W-VE6XcyDc2h(z^ifMhZf$BH+Ov!4PiA_Ptk_dyM>2San%P( zjhsS>L7N+0g7_#Pxa2g@fKG_$Euf-c4>W^9K66)w&3e5J8M};UK zp6*-d%xhdmSl^fYJRNmI>;YbtG6ywdo1^OUxmtFTpwTe-;~uUkrc|MLbuQN6YW0b3 zanQIhj(wVge@R;zGR=*FqW;m89)y=|ETP`bwp!#*n+Lf3?H_+$LY+OO6+x-{XO}28 zK6H8P6}N6ixOhq>^drC08k>x;N$Gw5s1``4{Ub6Ng;54{Eh6mw{a|+U0E3fK0$n{0 zh?9VS@m)$k5LlyCc^|>u;}_Hu->mOyHc%uw(oK8z0OVEwfL%Sd#aWvy4^m)=@LyoP z$C>!S&y?{4)-S8!oTXCS?h%B>y^ARik1bv=LFYt1A?Ep~#xKSl>bpBSmjk!13Ifk6 z&NhDEJl{Y6m9p?XPeK7n`95wB&)1zrO~F&=91{~3%)H&bev~O@&+*5D+8@$N*ctwS zvnhNX{%b{*2me)$cTR+2@BfCw$gmLu)zF zxpr>DAQe@Ts*E(oYMwYOmTKVlsT$&#uW`zbwv0urA{?4yZ$s#TTShcmoMKk&%q+Ix z4@i8j*&M$IkE*;hRtj?#L^!*yB;_zCw1c)MWt)-+1r_3g9*bWx7()%rgcFfkLFDUuXs@8ByaS#N!b zDq@K?R(QU&pRn?^w1PlFUw!&2UBaIh7rMnw8&EjGecMSa#rI*4?8Ffcg}XB22r%Sp zl(J@Hp^ZSw$C?&&akO$*D9*7Tbcw6%tn}R2os#5DPZXIM-2!dviE0dU+l1Aq_B0f+ z>?pwfX{3g@1fMd)8KZc4J}LMu%2?Q^vg||)V)$e6>y;eRZ@KgO6F+>)4!_AFBU;|;g5ztYX1^L?t5qa47I_-^Q>a^l&?^Xb7W1C7oSR$6<^FAg0JU*Gf@ zDFdwD!_1dNREkKq35!6~}>{7*5+HZ}1B` zd(kaxh$(p#;37PV(d%sr`Vgy1B|SVl``78OU*+^(LejB9Ea%HrL4V|(;YGpnRp2G_ z%w=}vO2#qyrMxzuX4Srwq$_#(^1VGvcCY*&rv_bu<`YC17>SYwq!ju-0gW9^VbQwp zXyT$vRdD2ovSCtc`YQ);qmU&8@_r=8ObP{2n)IKDLc9Z}D0H_iah17MPB@1%wMp9o#`^4!wWDM&Mvwh>HD6zG|#nhu?O>gB@m}t@*QzSoHj5WJnl#Z9M{n9$Nt+J@295tz2-;{xg z5zn1V!cLN}bz%qIy;?XAm*sU?cS^jVo5TNk0s5kyL+&SJSOtco4IRNj4OUv}@;~wx zRmy1ixHPA!9e%tBjHIapQFsYYWl-F{J@#1qaqsKXOnj`HNDu#ZxEhU3nMx+yK|f!T z7Cay&Ct_fu&e*WbDC-RMO2WZgnuf=4 zjf$QVNviuIx{>Q6$i|CfJ?eY6%yKvW9GpMb>ceyJgJHE$@y6i(u=r$?aMz|2%gpi` zBa|u4x9DLW@r0axeX6jGuSefsFa;WFUG$YGCBByM`*Y7;&o7r61YB`p!N2Upw0!#J zeS_-Nx!`^Kchh+psQJk(@z-Oj()wF_0(m`!8ef!v9&bx$M|?=pa^^S(=vzZM&ZJ%` zfmy|c-*dnOWvG2OIYdMDXv!Yk@&O>K zJU_L_v6&LXd~4!m#stR7t}~OR2ED6wlwK`Yi*_@B`Jx-?`(n?uUOEgU<)s{|$!@g_pm7j2iz0Z!-#r@S=6r zZn}QS?qn%yctjuS5Dq|Sr(hG$6X3)}D-oEN?ng&pgr{XUp2^u`E3odX7&117@wahm zAx3G;6YVxWxU=l53VC}o#~2p050)>*P|Bw%tETXA6vsi01Y&%A(>-^{54bZn>88NM zB3YkNC8GG;+Q6q{Di?|Uc{tFCp{=nM#}?od|E?8Hb)+^p60%TDI4ex}baA1w=&8O+ z0VO4mVRvLM6(F*v&Y2JX8TM8-2t}ZpvMTz6meqdHfhvCD3Wr>9d>f9y2uBo{#9|r& zF=qdpX}C6z;PCr1z>UcOY#IophI!`&Luoo@OCv)a4Zu}THrBEY zKdzOgqsYuW%op_KyS=AUj8CemqOA>FsvrDz|vd*=D-V_^odo=wKr;yYUpGjWJv zW2~t+3#D<6$P_Jffj3IxyL#YWA-VSygQl{)#L>Z+!j&+ zK>;G4X2o)DogbdAuj|gPg4U#Z+w#iCgH7Mq&DfwAX3kICy9yc(jwAZ)ve7Z9vH3*R zG8zj2)&iC({4(;*7=>9V>sx+`!%>RlMuXn<^^HgYWYu||K;q9U@ssaC{;Q95D49W& zk!DwdrF@Swc_$Nu-we2uG=!7}>;wkVK@h5FjDcwxDSnKr5L7HMRpw4HXf3|{U&~q3 zs`Xu{2yENZU1TWunk_2}0vku=5o90+*WwrnBc41~oJX2vV{8?(jmCbBNxO$z#=3q` z_r=X&g!YJ0n5d4cS^b7w2oY`?OIAv|M&UGoNk8p^a7-}sNgjuL8sVAmX3I*~C7sB?A}&NPal z6#7%9$|f`{f$t_Fm=T}h+eEHfdU$GdHsvcyabcPAqiLN?`vFJUG^dm~gyCB&W@aH$ z3QvNu+u!FZtez)XvK3aJIIK4kAw>@IzQ7abhxL=!eSY05&Vo*>PA#iMH2jpKrhj>b znRH*NKkd_JBlN2)AMncXPMHWOt8!fDDkCQLjIy$p30YXkgxjLSAL13%@}jfI24p_F zw=FYn(V)Ot$3Ik6LWApMhk%-7hzNb{>uk1k5cco%Kfe;h)zh5?92h`C1!Uv^mVy4U z)@UdF$yc}>y?xiDLJYA;Fv}W(RReo14=33zokS@<|66PZ^2Bi}*6)X{6#l#I*fKu$ zMPl=wWbD1NrdeG%j(iz=H#W_$x!W}OMcfB246ORg!*A-#AW?wDyw&+Nd&rR3fu%bu zo1uI_R^>rtxy(5C5EoW|aca}~wCa~n$A|b-0Ytx;4DDx}qHqCmo0(NbKOfL>xeXOQ zrAu4Qn`lzH5OZgat!*lxR+AX_clXN?a(7jG@hajOJ}G&y|DMNax4?ifSrz*X?c~H=grhZ}d41y|0^FV4ISV=V_FJtOKPh(p zn?q9k>Yqg}R{@|WoE8&Paeoi@%ayi|jpUMMuzLJb32KTE*%y#eDk~l$DshdGU=cNM z4iE-jrn+*cMotE4Dx0lSOvBL)^kn#oQe^+S!y#v3bs+_XLuKzi+NoFabt1S(Kpi!? z>I)As#?bpK-5F0!Jr#mDR|rT#JRkIej;QpT+%qBKxjg z`h+{Q+zfo!P-kehbMukD#lz8OL=XDri+`K9BUWo?w^B&!lUL`HiPU4Y+d;kaDDwH~ z{crmr<;VQ+_5WK)uvf!S+Tsq3-J^SljQ)R4#(zAj^3&ZHN0 z^p59S1P|H#rLGM*$8ckT+y9#U31({Q1$*vZ>i4#DI6o>`by$;WgNp3px%E*gJa5EimqT3fVK5VzQInwpR>yiKx>MR1f8e`Op>=F7AKz10Tywe3-bY&H$fk-T9_q4y-d{xBOY z+533@^Qq*7pWwr3RC0K9+u@3_ox`+Ro$cK(yS2@_MY3S*s)f#6IW7nUeUID2JipfW z!v6xA`sbxKHa3a|)8|wDu3Rrys*%<5hM_0&8`Y>LS8GPODM}m<%gPeXNqG$fGU28Z z3E;|eOl%nh1>C)}2zU;A(R-eg_&n8ncfWi%_3!-QuN+54-T$;*3mo6csV{8qr~2%uHUc_&0zj}z`7%3S?iTSIm6W%| z4q8RZG{fgJ&6u8RIMEmnZ$sbmJ1{ErSsLi+?1kFl%;NB+_oeA2&D504d)59$w@}~e z*YY;lVFd6MiojC9+`OHsYS#0P?xZA_wrrr=EvyJFFI@ywJ^)|cP6Po(;3ee07aVkT-NnlClC z+95(IH>Y|Z+@4Nv8L>RXb(=8D=7)n)=wzbV7%Y+_=bkUSN2J1t#W1<<-g0op{)go% zEoE@*T{tMk!}SeV0OOJ&@~D}N2b~#?DGd87Q^}@{_?V`Ri?c{icsFpq34V{I6Ip@@UxFS+qx&oGs!bwR4}R)NPJ9d4s5ir_+!TN zO5fAjD=R`LB@02=q67rT%)wBe{mstJJ;pAXiIOgXKS>aAB^C5rptuIhy*iWTpR^Sv z_PL7GQo=!xU{9E*U$?Q)!)no4RP}M7)Th)HVMuTh01+IzvEA-MOufVfK^Z+u&mtf) z&nsQX-f5Z_lls?>|5NtDoj~qIAsS|l=$|F$#^Wfbr8dD;`vLxS)Y> z8aa;)Rl5J4hc+rGuy|%Fx%0@w>f8gm@a`YE>s*9Yw5N3#qqCId-4{|CBcg~Fz7mk0 z_`l)uGhK2_6kMJ1bAs5~+7{gXdDZ*0XRz^n`0$y#E+O&X<;K660xl_n|2=^2kqd<0 zP#sRQUV_aV3-g46RkM#*Ckp$<|5KZ6CQPK;V(q9Rv1tU=p~cCXu&PKr|1cY8RUhT% z-!4<@ut<}_PB5RUD^O5Kh*TvgY6C6NkV+)r;DNrO61pCnrfiIi2@nboyLS4JV3w|& z9WR(MPm8*^<{;xVPNEyUdD!qTn zs<(jlTvgR|14G2|-&U!BtS1?HQ|&WT+f}xwW@cg-1#(8*y#2+{)^OJQMBY)#^F%<0gMX0xxV0>_TA90iF{Ol?>e%= zrv~E1h`r4yB|Bv^Q6qa^h@i}`d?@Og`)cjjic)Vu4rihP>8Su|x{e(w(7jzb(>TDn z{?-^fw=?I4uXU!%!m&8LMqTw%NiNt|NRp$H35Kv&Ev%_zMyzgt-qjR?DLlDMoOL~X z#oyCaqrY(+z1#vNqbJ$lBvs=NZ5~-8)1n+THuX9D`ZdUNiBu)|t!c|~;qXk6dMCVo zb-Cof@Gtfdt1ns15S(t2Hc#^tK{r)-DqZr0iHeE?T7i-QQ&<}xPwCKbFbQLgsEHv2 zaxoJleC}IcYe7@{kB+E-c1OqVVe8$K>-|ne1tWqnnLT${-rL>KY^#|y9pc(E8sp|o z0+gP@(Ln5RAvjFgl(w#7%8Id5qiLw_BAEr$p-7j_ON|{b|HmJxZkhQ%hNqD2>g-{4 zYkOF4<2^Dg#cM|x0+Ty23I8cmKn1`K>j&u=zC9g?v08_hl0*gpzSnk~?4biv)E+MG z?}3{a`?ue?^9lM+Kr=OEqZTvN=oM84noI!cAcUt zH9|R_vy2*Ut3aA$fJVj6>>(pMoLVx%*y_YLCYpB>E`t6;xio4{eF!M-u*+bZMg2~k zI9YShK9{+bNQ>2&Vd^XYiy;d@rVDV8<38KwTNaR?8)2ydfjIAgg109OQzEl;J*h?= zkDx=y$QI{j)bp4{bDQM)pxx@YuIB$X<4uT<{~Z6FJH~Kv{pT@y#2qv7Y@(h!V8rO2 zmQ8+Py=6rOXzPfH8A~HSWyJ|GqAF8JLU2lsVND~XK0u&vGWiU(hiZKu}gZ(U`V|2}2FvOSS3d@3Rpua3|}#A{{VRvHhgBOap-#! zr+XV6ZVL2m6l02frFLbIaKrC9V#=|$NoEfVM*4t;@8efuoFuNY!%IJp6o0==S#VasLk5h>Plv4ojs`iY` z$yDB^7m`oB7Q%`f3@*(^TiBa79~ok#k-&$mx;BCBS?3r?6}-aS$ZRs$c^*cK4^ZI4 z6_oi+OXp#_e2c%qwK^OsTSg=VD{_ZXZbSGY&CpV9ekJe2h znEdRD-Lw@V|5`B4C)h_97u$L|oI9sjq^^cp5;yRWS3=GPv1CYon8L@v%f%OWPeX=i zjuxv()W^S)+aD*)-G)LNQb=YKJ2U=>n%*iZU~*zyY_n{~x%sDQJj+@4b830Jv8R@x z@^Rg|^Mcu8Ez)k`X}0RsBo_SFLtHc~L5q!6cS<2CJMt|x31^JF+_cl7l z{x+bX!&(z6CvYHF8x1%`Ed=YIALfPRBs&o@31P`+;*HhOQ_>R2G~7wgm2>soL~I}E zs8+3M&M3)T5o~W!rWs9`{?~($g6y-bDCPe%8cn`xf6QcFj_aB)O=DCSdGjd6F_0^7 zm>Dg{K2w9Pyjq%upoJi96JqZ(@R0AN%;qmQeY0z17pq-K&AjypD($Jui!sn!hv(+LeEy>yoH~g~C7*(rCmUfL za&4>90;7;r6f)1#Yy=dBb2)x$!nM_uUXCpvpF8(_3ii zdJo;mg;#6mS#qL-YCaD#XE^Cf^tmz1yT%Nq)nB^#eo|HzXlgW%KbB z_|xFB!w+2NJq|6ymlV|?)~O6SBJ!8X?L>3)V_P5!LB2)kELxVy7(YS{2#T1hPt8K& zJD7~wQ-F%buo`D)S$xeQze&+I+l#!>FHRJqJD)N;D z*yvK9NOZR@%qLGaE|0vh*tgpQ6Nd~k?CxoOv^PfTJPMTfM*#;mu*-NN^O4Z3g85=- z6VN+KxJLSzlfzzK%IALk>Sk;CK7Q)P%>HMHPV4OY+a_qSG9E9PFu~Q$RIHBbOLkGUL;!*l&%1i@ilup~ zfXY1R`S)PZyj02L6lDFy&OanEqv!R#xQ5P#ErlRpS(r%~@c;32R$*;LTeQZ#K!D;J zym;_p#VJm3_h7|~6>V`S?(Qzd-JOykMT)y?DGmj0&N=tqyye@EJ2Pv}F~=JJQO%!r z+<}Okjn3C|wHN!&wR3K`b4d#^fpcT^y!H#i!2uq99!9>M&Kedxr}h>;M}^~=`0OP) z(~cL(!^imOJRjfnvumT0?LYS-R18~&Z2vr+vz=eZJ6%3sY&df++}Bw%1*!BCIA(a0 z={jx~IWo)txFdu*>vLuZYYl4uZg%WE?zpKm^jNDr)2Y(7&(sqyo1Gc|tktQnw1Fxa zG0n#@Q#{N^-u=eaOBVP$Bg#Y2$#`_thdj9h%n1kp^VYen;+tn#ry?~Y>m_z3U<1jh zwn2oFw7chM)~u5w)fs)PB`n7r%>{jY*6xhlyy0Bn5c+yj=Y4(02Qu6Ll~r%t|5X`4 zy_7yxXUoY$lphy0rVTC;zvv|`*9Oz`ZymVWXS(Py5c9ur{{9xMT4Bfbtb@{wqdr?) z_f~(}9hz>P9p*}@nFLnUPtlrZ$LxIKh6qk5JI+QFbNgxcGzWhS$(ke5jf<~BJg>xe z^**(tTyLi0RS`xPW&4s?Fh7&1mxv&-KZUZMRq z8d_DTvf=nA@>Pid=z^_xhQm4*nysRCixk`NY4h1NYIYgqeX zpiEzLHYURS=G$RUQ9mtq&|c(u-%PW_3 znbby;yC!6Cj?6c@hEBL|I-oqR21h45t?UQiJf57q$y*;RlbpSNa1{-7^SRh=ssB5@ ziy^K0b}c9oqZZ{+oirnQN2BO+IwwPxKpH%2yHMWpS&v9lVW!B=6NSL_vm^riP1fj) zGXLwNvCVBbjt0{hAzToSHK|oEg;%HfYFy`FPXssO5Z+C{kH~D3nUD8% z$f9zYz9BCpVvIW$_ppJoY{$TNd6{5D%>o0vk$u8qK`Oqq?ShuRUWpg-Hfd}`ie&$t z%tXWPo1X@dT74tFh_4z09Zji0U)+Jnt_fI+qM?)*GFpn}Ky+*dDyuck<9#3~R)iOR zC)pv(v1JL8)%&c^VO-$u$oB~Uy6^0~`*5(*ZCy)e=tA7+%h!`&?-Dl1OOTzzu5!Av z48by_cOwd@T6_!85W*wf@+wHt+weDOJ2|~V%by!?Ac*=<5)wQDI}aVUvg3GcEN^T_ zwp4y58T?(ewZKCkh0Z3EppAkt(dBab52i5hUPXDGQHqPy7Ez@HxS0196U!**;f6M~ zlxJepIKT6=uT-Q3Xz(&yKxWbU<``Wx!NvHPN55*Fox0OjM+Yk_V2_XU4gg^>5wXBO zL4GM(ZM;1NPRq&Z15UsF#fcSwo79!!v%ZlR$9AKqQoO&f-ESac{I?{7KxH$|s!0VI zTx4Dkai32dyxR*R_(ePH3K|Lw{1N#_g{mi__JZ9f42MP>=18vhqB26o zK*ySA5RJImd4+OY)HEW8uF zqJJ}UQm97r9o*K|4TO_h>4l43Ui9hhK!5KOFtd7Jqy?FJ8kO#FOVZzJih(cP#!<#v zZKVZvF^IP^F6^IzG2bGwV9|G);P-TJq9^Rw}~Jp6}T zp-E+e`C6QMF|WAuXP&uL?ZEmz`gd731#RcY&ZJu3&cj^vI*MMavlJ99Ls7xUs5|_x zh)Bf>5~qKvIX!TTH>et7*EAxiFN@rL|3KIMeZTkwudwwlok?WGUct^>TdM>GM~@b3 zW0NXetqs`?-+s~G>YVCv@p-@!%7~p+3%ngycPQ7A78Cy7X=k8Sw?dMS=zY7T>*ORZ zBGBEVAJ!34_tvjAz3f7iFk!m2=>vX$cqzR880@1&eyr1i|K#6O>M;V_ChDW;! z@u`-o&rAPe#G1=5hvf*{sPOaYM^j)FD7b!z_(;l8|Np!IRO${BAWLJpl~0W@ft62J zG`a^-hud;R8xVLcJ-q6#TO_h*3SzgWrn<;7PM|xD&?%<(Qvp#F%#kXx+@0L@QG)FL zOy+!GM+!HvBoTB_fjO23hdPFbvf_Zmxs(!+g3?uBTg|w}=-m8!#k9g0j6pxw%-q6> z-M9w(lAki-4uO(_&^Zm zs*JAmjw(4)cc|`@|Z&3oJ9CB*MXtdw~s)6JmEfWUa-==I+(h!iI6c23(Qm65? z4U1(4b9Pm6l+KFeb%S%Jg6tH{A-HanhissXBM5A6?svCX{a|Q&D**xU$FU@3w12zo zA@5`ysyAB{hE9Z@u4}_NM=Zui@1pk{*l6?@!m<}AtWlYW6PfMQFHxsu6!q%A=F25= zY?f@7?GfG~dASt}?HpbJdXSkmy`nTPRR&oxK$5 z_VM-b6`?BI^W0v5;IevrDl-lupFZo@{*(^~BU5ZBJk-K<k=fvvnyy$~CI2Ni+3&)Ncjljf3CP84Wv^B)sq=^R;W5Sip9x=bN zvb1i^iN^6Wu%A_s7!yg0*HOuxl$VfT*--^{c71xfJCtgz)4VWOqjAjcbUy3)$?=yKJ4$txTG_885jrdc{9(f4h0ip&tW zkfDF&mnE3ms)^RJy_4TPy;HVg+kOFy$p5iGs2887MVb~TY#I!Y>F%aATxQT%3@m+jxth8 zU{<4+=(j}g;qkv=?46O7xFl&6Y}NhU%4OQ!E;c#3^3XVOvUBE_{ot89H8nL!8730j+AKjBkQZFc4(_ULf%zSem8^EBnye zI?Q}kLfQWJ{p;Tg-C$p`(f3+bzd72UU}q}2r<4@`zsp0udX16Wm|XTe{BP68d1;h3 z)!9{IUn%!}AT%9TZFdhr(yLLAAVRA7lXVFEex}nZ)81Jl@D3T684gYJu|>B-R|r>q zhdYBy%9QB3sbDlbMFMCZD{m_^D3ldyeHeg@D5I%yt1$nxyji@aY7mJ`2CBf6I1obg zU_qigCm@90Rcdjg`;7Llt=84d{X>4_l9=jCEk?>PjQsHM-H-bu<;>x78 zhe@2&hQ`mz5EVk4K5pe>07I!++TVd}(k#)KE`&iHG)G5?xcb$Zf1ID)l>dl}u;LnL ztD3i!xw3R3!L6&Qu@u+VNt`0PQ4J|@{L{-ZP=P$**Z5HECo5ie2>39w6uTq)&dMnN zM?|QO8i7W+_t0uLb#g#q=fTu9Eh76iwdXtR9+BbwY`fh3W|e~Ii7K(5gfw#5<3D^S zWmX42hcmSqbh4~+%C7p^aU^y%l~P^VfG=@&tftT?d`!G^JM^j>RO^`yK4Vg@V0p!1 zzcbN;Ac&wtVZ6qQ-I?`XB()ma$k0FCYSdp{>N~yv9)9bSaSVJ!A3PV?iTIHg__+V~ zbogfd>Sq~4Z324i8`YXBZ(8Em_gW>?m7zs&aKhknA*3g@@4cQj{EZW`W&~K_M)r6R zP;S5%7_0Fm$u|Gy7B}qTB*c9Ejh%7BT{BZpR(Af3PgJe!+|1W>H@EO1ki>D7?w}x~ z2R!cd-fz**11_x2Mwl}ErC3o?)Q zG08;2Vx2B!`37N8*F!mxZNmkoWPK$wtK~uu;K8sYMSp&*!8dsol<+^;3aJ#wUAszUl@8+wKYJdh{f*lso%GB z{P!BRaE5)kHdN}vEb(9BuQ*gDGFn1l`fT#>jCLN<*izW$ju3+SytN$}lZBpwDA`{N zj8vc65|`T=fLZ-s521<0g)Bx%elmFk4}=b6uHk4Dsv)K0f*%^nvCRSHxS{0)+t*wQ z4P>vB;8U(zOi-QrV1!tw7=xoRUtA*)WeAL1;zfY`OV%WB2=TGqYtGdhee?-hW%eDS zpnmn%`s?pMwXVeN)KT1JOj+P!vZA7T6qyNT2uETN%GbHXJfj|s59aPFXM@2`R!O#U zc9UiWOWaI(7EV@Ry#Ja+E0yw^{ZLc`QIwadmR+v%iMhfC5ISjGl``d<}= z;YkRgcM2I*tR;jFF#7;4K7q+fbY6S2JyuUCKH^~ zjJDO59o4ORnPJj4DPlV-{XF zx@47y7|6z5En=Tr@VROb;}chX(5T{C>E_s@A;Y<3o3fSdfCPO_Uf#2FbY>S;BgG?3 zuJnE*5s>KL$o|LDm8=y6(KkEO(d)pNz3lwe3Ak{B!HvnQw6*ZP z|D2^{sHal_a|OYAca(9i35dg~?b&4s#4g2?70#&=QI;KAMN;PgLcx)#Ekx8ZR+$h4 zdjTx~#EVyxzot1AJd~4>)na?`GjXu|Gm-Kr{X2N9t2|^qE7&jNz{jaFMt}8<%z#u# zRn^`)lEDTDiQu8=%*tb~t%`y7=t1g=bi{(pK`@>Ac>O~BKCMBaVgEa7C@p?y zG*6QT>5Q?$+?MS^;yR61P1mg`;%)M;z2gdH!hC)2!fBY5-p9W|?TkM~CKHDV8~UXx zPUKGm@Q}R#Gf0H%k`|N}@ze-ExhGel0w(YLEsu`MV&qIs2flzU-{n8vx1+hT+ zAl@=%a8)y#l1|_s2P4s*`^_rTqZrC|Wx8i~jIfM)GohN!dtB*@wP|70 znt5p~VsVkBi@QOmWO!`0UkfF!$KB?`lApj@E_GnQ-`R^fiH94(jeRlyhnqC%DJ)+* zs}$)0uhyVPM21l5daBW!PT18cWDKlYJhqGQJz^)|sMd<8nL)bdywrYBXr#5awzgWN zvM?>7(fHer=kH|@OjGZeVb^2&1{TxVQLup6_bYWF8FOf0=3ymu^A{WR6IwzBL3%{w zkkOi$QLBB&^N+s&O-q4XpKE)Gjk|=Y61htfi2*5`DI zv{^uOUl}KQJ2$0PERF;6=GfMBHi%`nK8RxQiinPhk^xGzw{h4gvP$tsmORtM=>bQa zWC-}hkB#p^s~mM#xOb^KTs_e@h)ajR{iW%e%WV=lKhdk^PBK`!5G)bm(3pV2i*QmR zprYVL89zLUH9{Bjy<-S5(nr?u$fD%n2$sG@sjdaZ+I^|GV0(23jj}!&aAlS(3Mj;K zf6TBVizPW@Mpkrt-d9Q=!NsQNcmrdeEhliP+1m^Fba9LQ72#viWK=VJ_^D$jLJ{J~u*A{mY)FU)0Tj31se|4WO z58!cOzfS_iU}bqG)U`~PlSsTu`ttMXM#bDS4eXa=u4d9PMWXb5-J%|2uBB+Wgrx0; zb&HReN2w(qh{d5$?W~qzV+V>`!JVzyZWGs}sp5)rqQ0jK|NG6E+14MXGCG%Oh=!5z zcqa?PjW$!cJ%-jqVRCCyByAxD5VKk%oYDnS9LUEjVgzK~U^;GoG~U0ygX*|XTf0_X zUm8S2#3*r})`Y(AcpsO!v61M;Q6DeiaR&6kvv((YpKAm+oGNL$?^%xD_j9rXKzJA= zgwZ(X=k_(M?h(UV@i76@Cbnh>hM$|jGP99mHLe5rvLPSr8GwIG(ib0GWvrkJkZI%1 zxz!M*kTq?7HZf9^FcEob5hu_-*=#I71l}1@Vd$mmH$RB=GPl6vHvV@6sqO!eC7A$q zJ=D-Fh1RWiUXVy-GtyW+85QG{kTqky57jEciz)+^SYC9ve4Xuy5M({l=_X=rfEz?so2D#Cd*y|6N~OwZeOgTh{+ZwIJxtE)EecR_L~e zI!71mM?{I41p8txxweH;Bq)T47*i94@gIW#*`f@SW+m=wO9jc~KCLb6^-wSqsKlx1 zr!GAkq!!K-h~|ry*?za@GvyQdg$xeE`$hkrch;@UTr&}4Q#flFa3iue?21Q4{LwQ_8>)p8I=ns^GM*6A->h{WcG5Z>!;DkUseNNHM$avlz?NKXMP8 zk4qg3kaNgnosq29s$bopDfP+8(YBxWz18bp{d(-p9Ub<(dGBlM)7q=Ym-~w!wGwUb zW2b(|H8NcGudaSDidMf)`D;8{wr>8j?{k`%7R;jp5{ktuJjU_KwpWHy&G(YNu?O;fE>Z$Ja-@ABSZq7uL^pbj6PSKf|n(plGGNAmZbMn7m7o4Z< zWdMKeM+!kF2+~JxThS`w;oe@x37Y5*3?*ZMcCLAU>G1utxqE%RyK5zZJIMWgM=0pf z+}8zkmVCzcqX!&*>EPV^*p0ps{P6m3e&c1}#`i+?LOdhaWK|q!v31A~Q&nS%`s4IP zL^gd}1-;oCb5vWM+E>CZ+OVyq`6Sq4-qwK@>?J5G zp`>cgkID;Z%+x2wCPmOh?q7?-IcLgH)5fbeM}5WTNWzvDmZ!Bk_{+v#Lrb!h<>>)f2a_ZbaCsnoVAL>$M1RL;w} z<|8ZQIFsL|{mCPa<|OE9k*hNUEse$d7=C5xX^pevUzn82{5W!CjYPDjv_zI6x&zA5x?PZ9mD9yr-y%0u@Dq-)HN*NKbc$d9eA{CCDO`#5kd7_? z?wN;h#v(Q53#6vLGFUyTEko9rinaucXSjgL3!=#z-h%4Hko_(`LjeF_wVM{TUZKIQVTI!KKpV4C2QIY$^q)8P_iy)aQ!^Y`2i0k^^YXH@6`k3-n5i{RRg2gg znlo6Wa}M7mN|NFImitnUGopXjHiDx$iE&xy%pUpWA}=(;!WdQ2=sjG9&Mj-kayYQG zXGAHz#{1UBfenxeX~(DSEL?^HKc;mUex}W2RA;?mO;A`SumMG~Zf?I(CBW=GHN-LK zLKf%ZC2aSlLW`QWwNIe2vZ(9iQZl^KEGS^dG%7RsiNG6;obW3qm?0_4*y%Wm++9I# zImQFA#Z6ulb~k$0_b@Y--kd_mCYM#n+juAH%<@LEP*>YMJj^+YJ|yDYD>`XE72{oD z$YppDTnsguFIL#28){wPyL8ZxAnQ#-5JI?WkUl*epDwIpHAhYwYCW6s zrzNE|jReKwrBFoG=Zoj9;!g?kpI%dU8$R9xrhWz_&wp-jmtcN>$M-O$mHl%`?v)3& zF9lMHBfMVK`81Hu#c_7HN4jmBy}(*_>{q`AQz$!_%huJL^rM#y+|e81r$`I?s2yS> z;)v+E9LvawtG2xxJ=WjSIKT(lbnqU~H zAa(-;1hf?k=;lwlZIq!pB2J*?-t6r2(fIl4_3oM%m*up`W;z@)KIh zpLK)ahw!|BLnoTvm;3qq$Km^J3DHM937VTo9f^3z(I+NVTgq*2FYuk18595E&tCfFZ)DMI20`;VSWxhOUKm9s8 za~9k9TnpbQ{aYtoA3HE!S5#q!iW=Y3hGo@9_(+!l$oxnxf>C${TQ!CdZ0sfoI&-Y; z_L;yTjC$-Xw!0U~F=P5}rVK_x-s&zwWZ9w36@w9szY^EkZ_~~1!1If@SqIFw`y+BW zUeq~GY&s%73kqLjC5i0#HFuhmC)U2&+R-zqu}@&VXExV~Cg&o6c-Rz{*0?ty4>8c9 zDijaxc$N#d)5DiNDAu`C(2mVrgyL%3D`En=FK0zTlIz58+7;UJ2ekOFJ~-_k2S`{p z@@Y3Nm}EUTQI5J&j*!p$RYoyHY|zIic{wYQu8D$NK8kq>HXjlwzbPuJz_3z~Q8QIo zO5Aq=08M5#bF~qcYWH#D=%ssFaM3=Cs$rL$2eXHwtTrGm6@A46uqwsTr7Lu%rYfp~ z%PjfPmL+=1N?qJY8zYD;bQsk#XlaT$CXU@K434f)q*KjG;~^++H+*7XPf(cqn}osd zpn*?RE~!Qo5NdyEqQI(=0 z;;^qi7~zl-;tdSy-90_tZ=b@EdvH=fBf5=jTk8AoDG?d>em;N9gi+;{f;yi-9A@d2 z8EFQbrSfqHqZ@7i!j1!9y2Cd-MlS*$0v|`6d*0m3bBRj{VKv?syi&c5)E-n;l|l^) zn}y9@|5WDV;$1kQ5Q|&1^QmbTIa*OM>NiBwL(~xKlHd||1w1m=Wb78cug$odL zNJ@seeF(lJ;v}IvPH~Hz)6i6vm9}u-p=z+Kg%Z4!E)G$&3ot_FOYOl?A?;x-P#d#_ zQlrH;#D%dGA0_L|&#%#Ka0Br%Ng9*sBXq9Qs{|4fmqgn#QInKb2G{}8?xX4s*lAy@ z_!-R!=ma&32*MgDI1S5Xe^=yyz&Ic=eT&-#;8!%gUHZNa9K&Y~a+u zE6UPJ%1#+~Ajr!WdDR#UG*}ak%!$G`WkFJg+KupvHk2uP4x7SBCRc72I~Grk}i%TB#2 z+T&C?vyT}r>8hrKh5F4UT*LGPN!Q%|*}TE za&Uboo{snC*A#xVPl;kduLY8au;9Ox=Q;o!`s@2GVRa_7<$PjCL`z~@IVw4x36@#u z;k;&y%H%Q3xAdaHtXTEQ{dGU-CaP-WWLd+1(_0g;_?^X?Ns#LNe)!U5w#UO{{rkVA ztv|-Kf<^&f0v@UE0-wiThl?ieHdeEHac95pFg)kFB5(ZRa zYP^iX{AAXGk2m$Q5w|QY$iu(5H3a_I9x~2TljJgWapb6s$oRROwdy)R{k#l@xbm=TZ68E~6wI|3WsPr2?J6*NMw~C4qLxw)ydZ;Jo!7zDd3@S0I z46XrT<|C_F_MgZdDr7^_^@cKQ6LlW5bcTWAvInaXyko0E5@*cXIdBR6Se78@E!__c zcy=TB9ic2;9J5OFwly87N5pBxiFH&M3SQKG?su??b1)99;N;0|x-%GM)Tk(oG%qMMzj! zM2sSgu1=CD{6nR_1BVPgLPRiLe)BM5X);>F%~ZiwG#&jN?YB@Vh0D@!pZ4k&x-QbU zsD0oZqN9g#{)F68>O7o4(h|M5P9i^>sCXjF(uvNQ!$axmX~+sb#aArUkGN%)6?GCu zD`20-;{R{<5eOQFh!hPKK=5&r)aFGE``VLBd6>vN%rJfEKPQOUActbiZnifABfbl(& z)P^Em;y%3dH}V=mZDPA-O+R465gvdlGl$@ip9=unND};d69vXUglU8?$v-0zO0wpO zUT`7+zmSm=B5((X5Z1}zTgW(~)OT`R5nS9h3ivJLc8Jxt(txgzGjd}#Xu^IhtifA_ z=cPe-CTpc>=02W@u|#)vRYpZ6rxK;r1hy3;j8RmaD!x=kOF<|~MJ2;d!voKjc1{_l z7lI0f@}_`CTtz8w;j9d2liuegE|b+&)z(=*e-ABw3(geJW@_AU<~W);gWJxnt-(eE zteml-Sq>GhxF7pI!m3w(*#`@;qYtnZ2l#KyI&-c`pI~)x%^HEE0<4z>vL#jG0O9P7 z?}Xz`s!?a>8X1XF+H*AHNWa-h%*>gxvAHs@L3|5nJnY3G(iu`$m?X#*ruKU0^{NYeyj|Ha+mAC1kTD}@^Kq!*=LnT4525a8S|0(Fa{>!X zn!OR%9m{aG!IZYk2)dfA^9sCT#{=w;nZ9_oC8+4jCFg57@T>e&CUt?^kNd$QJh6?&+ zRG&MHe#a&V12sP^vW@s>5M~2A-ueFW+)_pSokjbiZ?PnlKb{jFwhnPOyrVwHkZO7Y zhi94#Flq8@$J*i`kvPiW7h>d-4bCZ3tq*7rh;VEzHzrYmoX=08)tMnA()(Bdd9)FH zCO6^}20Aanm~$Le?aeulNWXJ5lkYwpq7^ei4G-l?-U0 zl%Ch_8~i*xg{FD8 zs7PTOEkHe=dIw2})~JJ>iB4EJG&BzXn^FrUQ$e1uwPA!N5;B7oEgVMto;CUWEy)0K z7ft!6H=_h!aYlwva?6g+Lu)TE$=-&L5!!sE=Sk`x_*rsJ?U6s@JiP&uRR$cEgVgJe zyDYB;>*PXc9T}YuP5uaZ42o(-)}COFsr#MB`q{dBsVUJa&|VJ8lf5_Ys`9>fy2mmW zu~IrY8MoL{FXp=#sH@*?%F|PHF~m?^CYBx1I&!kB<&j4hpS}FMpM`g@v$OZC`3k`M zU9OZslRStwvPEM;nWu7fejpg9MdIKfC&VX)ln?78mVxQP5j$Gn+I{tb{Uy&K;5%S+xgjRWO33+2RtaFE25^Cj>ZFeDZ<@~Am-&dG418xN`J(`Z*D&?LmrWj;1sVS>A6SwlMR=f6HpNAA8=B zW*IYUuYZXU|E|Mf>d}$D`kO|U?PT`$`jNBp=c?I3fy4LZ( zeml5&XRf29duT)v^Pe($m``rq>~~h2>4#;o{_;nWDn1hpT1CSWL9NQlA_063`BZU;mn@7FjtuB{mwB8BXg*63FNhmJ>RZCFte(m$%yoY2b9msn1>ay z`{Twc2abQp%l3|+RRn>|rCTVAXfVbD`*+I%f!eoN`a}soxakaB?!^H1-Eq|^-yx9k zn&>~JVV_2-G~+by`LJ&YC7+n%^%)4vt+K7t%t2sBEd0h4u&9+n<2B_?6KllA;nvMf z_{D>W&CcG|ALokopy=s5s@si?ILG)`H~Y@tg5j<1LkrpZ14pIgo(iGJ491lZ-U+P9 zlu&ehC6{SmwBIZ@bcJ7!xlcWJ#>YR-3aHJ(U}p_Yr7G|pXmj%5OJArvixOV30zmk3 zwq(+D8;|p(q%z>|pV@`wE@*43ymq(P1|%%ZBq^+qVoz84|tgQ{Zm)+ zbr>$0TRFbuaJ}9>wbFD625xQN-~ZdE{8LK2FMrK8jOa!Pm^^_YaAUK;J(;203>PW_K+S2X!{ zW;jN!_doVK#c{*gU!`_GUC>uoNwnMgKX%(K+C;!q(&I*1J2p#*((N2*BX(n9A|B~1 zhhvU4)u6lSFD%zZvWV|wH>bxQ0Y2dA$a5@AMEt1KJQYrmrF@d?^oo7}tbt=h8yW9{3dx=!B{DEl8hB=G6Hh@RU zJ2>4OGxjb8vX9Zt{)woEeK{3!4s2SvKnAx!c{Mzr+B4=FED<$+QYh1tI$iSF>lC9& zlATY0!m+DxELl?`Z=cqFX&Lf1E)XG_wIsXXq-(*gU3s9(00|Q#qwhPoA75@Ga=-}P zyavZAh6)m?24RHO?>Lh2wedz5emc7aNrvS+&`Et{ed8LXTB48!{X#TpR8X~SeV)iX zd!in>2+QO|AVmq!=y>9ey&Syy+=aJ?1X>~wb#<{d97x58=MHygHFk1BQI#{KWDYh6 zif55LptY!LtZc7h`z>|+b5n%YCtW?B-?2ZTPzZe4AWeRPm2i{HI)Hk#8@oVc>&28M z)RNyvQS;jc%jvoPFD1Hdwaqz{5{E|sR9??8%$ly*y$4dzCD$~epmKHA^}+C$7^1S zN(&Y>D~Lq*($h_>$ty2X4&Lqh5|_O{>&^Vp)}88R98KgeO~qFx%Z*UCvySyWHr2tiP5CT7>5pvZ2Yc7<{pVlD9%4(atsITb$^iRi&+Y z%fr+QYf`j?hEYrUz@Kp&r(B3n)kX!;HtJp%TY8b~wuMp2nzh(V(OkXh8)LJDn)q?9@SE%B6@8L;!0 zrf0o7z$EXLOYN0E$TaYYBJ|!N&D3f;*^&4yx7%@5ZzTg?ksQ({)| z9291d)iHVM8vNbRF=B1VND0x;u5vkjF@HHZ0?~9o1A%^mp~unX0WLYfbqDdXMp=?p zxcH#5(axFGh1w^ph#~mZ0#i+1tNkvfQEAaPUD8&v(A=|)U$fbqG@?PH)<=P%)E*_G zt`d~gjQi_2j_f&@HWA2;KCN{Tx-(F?Em=p95P{tct&6YR@8J{Gw37P7o!;NA?^Ir_ zu$kD$0^rkZW|_C7Mlw(?c1mXFX8M-l)<&C7Z*yQakBSL*d!S?|NQzo`YNGl6nSB}= zpBvbkZR!^@(Y{`*A`1?p?PTL^N3)@#!$QLJPL$NjV)V>o(c8>!b72CqE{Vwx4Ge2U zrx!Jsz$RRC8#4f^w44NFRdyzvTt79oT;*={&(Snz)GoHjXE!I6{_9O)S1ebh+=A%P$}~=3Q_NWx9x@ zzFSy%_aGUT!uT;qzsj@If60w6EfVM_^bolpnckd>md!sUQ{I9axtU@g@MmWScAUaGi)UPWgG4+i~u1-g)&A3N8Y}K2{m?^5f#LiOxpz&iYT(78455UO!~;nEMG}c#=0EPgp6O>q7cs0h|g0N zEtdsK%1{E(e;9UVP{U;r2^m!s$fdp`6`2e4khm%>WT$i{vkv<4v zemA(i!tnM2Gl7nncY3e!yW#t9*&Y&aSE@us2*#c{zmw{!@3upM5#(!M$Yv+PWNvSk z3;38AWqaN0bn3Y^o9N_uFeuHX&iC7LPq0$#RB-oGGR4C7tLUOSKa=tSnR?s_LX}{~ z5s_n?5My0EyGI3$ai~5+k)=JR<+1CCf_&i}^L_;nvnLaTmClwYp|tRzN``#tqnER! zp~2ec4~q)@=9W!*B3q`>Uc{asv`?h+2{92FfY9@RrNgro^n=z7Z@#Wx3g_FhUi41a zfcLS1qPT9Jx2M;CPXuR=s#g4o$_%;^K2&=BFd*6at`1ePi6PMQvOdoQL|1r%vP80B zh$aq{q!#P(G&mtLIbEIXC@%PqTV_1bqjCx*{k=jh$$RDI1Upb5yayv#l}xaszY&bnCE$eCa{lvj-S^kg1NW`-Jr$}dJFYn#s63nQmfj5mfY#krV32W3jSmy?j|2Y16EWN-M3ri#wb3t z?Mkdp`$3tBS-eAIemr*uRffqlE$tjmBLlJ_vZ>adaV#b6gnV8XxM^VR6+aPlKXTL> ze&D;31#sUfL}nqg!?3MGk#&e{282EB7ZPkSc!ZEHU5SN|n6=`XxotS{Dc1qgcsHansImCTeA}vCDO(1w&7_*m|rUWk)`n%B~L za&c$%2ckFxx!wJajy)G%656>7+TDYKHy7y&uC1lyHW9yq79z$-X5(`<2mX1ItwZBn zZX!%xm?m79Mr{uAk{?SKUeC6I5AZ6w<(&(wVN2v7?+;!EMO|RcXSBy~#7bwa;YJPZ#7+O$P#rSjUjunj)f*5padF-!JV} zo}IaPoV6w?C!;g{@>5|z?w#6aE=t{hgPRcXQer|SpGL3phJ5sE2F&k0brHI>q6X@) zW4IZ_ma0L{supnzBvpfqSlPi2Ths3%(&07aqdmvFF!c?fn#^71vlvpXY5Y&jEzcZW|#ci>Df5E6yW7%lgACX_tmR zs1xM;3WVu#e)S4l@4Q}2wf^m6IoWr`^eH03{no%;RdB>egp<{f zfIZVH(pTUw8Q|cw`}exwf{>+OQN+A`DYT+Kj}rtE)gZ28!bU(cB`7vYyK@{Un^?8B zu>1^VlH}Lcj&iEuSEO{*ml0egg&KVSX7cePVipmYJg9QgDz!W#E=nzS%O6Kuj~B9} zg=#mtGgI6t(sW8Aj&Y?5*$jIs%kytxKbsj0zYz6hn$I59Eo(v;$>-A#PrdGer`w6S z>q~+T6hB;+v7}7P0m#U~Eu;cfvK?Nz9|ZOaXbl>)pB%HPm_A-a-fFtDxDc6IzHe;O z2ci5Fb!4iN5Cr*U#QYzo-uf--xZD075Cjp0p+O{uMtTV8aE1nnp-YLOLqb|Xx;uvM z7)nwa0qO3L?vSCo9`1AQ@4239ewsgEf8Kkq^;&!5xR?6|J8(avu_}-V1uG2Hr^7;l zfO{I}UJQ$8^vdbB;XLGO4DB=mc0}xKq>7jM$gvVy$}MEsYq9 z6aONuKfnzu;6#uLp|PLeE?p&D{=3Nem$bnI0vZlC<%BOLsVf@+-{8tSZmm*Slf%&5 z`Cc1|J@$8QF1nVtUL4(Q4;;JF9`fCa|D8HGpIR?jZ)+@{;k2Xj`qsHN>h&%nb@KJK zHg?3R`+1g8?0sSFKRtCAVUgLPY}9S+vlo}_N|u3Uf+`drQ`5pEN!{XES0@(P*Z%uNQx|baHU8(Dh^Hg6K6WX?dtu-0f0kgj4)F{qPa* z`}wJn%!X_0-Ei}wLPhF`-j59ib34~?ATTGvf;}wLqVEyZv0eC#eBUDy`$htj!d_?U zst+PubFby=eKBXA>3wm%J=t)vvnF=?@08SF$rvZ_$e6gOIBK3y*E(?p)dlI&)m+z1 zXwqP19S>?k#&i?wWHV3os;EmS<|EFz7Ys1q1LLI?ize}Ofen)R#G!vJm9j1qs3-yp z@yo&In&UF#DgeYP5pf@GE1ySt0UIIfEB0rbMA1YvqLk_^_)~SfR@~Dhz+`3&F)t)Z z&H^*~P|Dya#bp|B_z%qA9Ad3Bi4xwO&skN=D?_q^`D}%{-?J&`>B7}00DpMKpFQ1N zB$~tpMzi5P_ol{ZbUL)kSsgqhqIiKWA4kp-{Z(6+YIr}ynI}WT1I8*u?k<+zMmFrT zckK2VUb|nAoKK8YpRx=>e$V%3n6DQO@Uiu|bPP|#2?=KwA0A`~SPt_8tmhOY#-3^z z`xQe=CvM`qWi4AWV?wwat#X68p!ztFytp8kgZeCk7P)lBZ#bEQ8+?xl0MbXts3Epa zvy$OiU?Sdi^zSAL&fAgI;EJBy4Sjf4R;wi_Qq~Hgua3wUAMcnYCHNF?=MxHAMrAlzHRSrYH{KTB+Wb;?zPd)b8)Q1gy+VCbAb^161*P#T`fNsR)o#*>T@oierqrfB0Yl9DY^= zhaCDDsf^&q$lQ-fCO(3MTa$Fk%fx3zv)%*Q)8Cx4pgGlz_h` z)?-ECRIEOhra$BqYgZ=fR(`w)2n>~~(Qt>tFtL&%Y6HXPTHc|S23zm1e~EcLtlD?m z-#t`Qqg~xD-$%85yXn4lrEYe*-8fz(C4fBVvyW)e}3HPeszUbE2uItH(xYYgwyKwJK(3 zcSt4XRm3{PCZe`29p>T`1Mg0h&6Mi@F zdtp*})?v`wjTfwH3x|hmLLs3!QLStW;n6rH*xne3;sQ<2QT;@-zXR?bebQFAwlOi^ zEtCd1DmXCfh0|w0E-QLF2jfawE1;9xHEv9zK_ljbfEvVyA7oppGn}PspsYzuD(&Gb zI@NR}9>7S_9w8G_g~m*ja(=355i-aPqGK;IIXN%|L{!yi(p#HOr5#fXd~$7g_jE2I zxiE!4vm{J`8@hFHu(<1G_|aUoOD{!|M*Q&(^O-XqwWtW&!1=jfNr}Sq%N<|lCSAr* zY)0TJ0(2QjgMAt@N%=~uNnP%<$=Oi2pL|^+BhT(XmX#T;z_7Oo054qT)lbDrF~mQK zO`nShx#XfJTH5}gH8%E-Q*wvx#;*yTp*BzOUr?`7Stkn17gBy;^=fa={pd77Lwej zM#Nk~pKe@wA&o&2Mp~{(*F;>_LF=?2>BBHqouGm(F_fLRHGMC6J7EGN{X~;zZ9n`q z2Z4G%b4sv_0h)Vo$#i0mE8fD}S3vSyyX)yh_%sELqgXmL+_zusIRRDi1X-6z7SfGA z7D+79!9S9>QzZ-G;z$SPXc`nV^byo&`rjXyp)*?LR?H%qhj_<<%ioUKt1lLlmT$+Z zm$BB`?h+oQXxff9?LDr3iQU!}Q*v@#ZFlaXh)ih46BDWKd}w*)Fz9W$3gxMQ166E2 zojcEBR@q#Lf!T%jqM1-L(Tdv&^#3WNr-$Y7^Mil>{<-})rA8k9rFF>W=I$E-voe@7>&->{TJgLOxGN3(~`SH_8t@^imLJ(#WD&MU$Ap zx5)1AT(;rk=VHlWJbVucf9X_1R8=9SJRcz#TyTw4orIY4C3BaQ(FhQF6p|%RKmoSG zT7a%?rAGoB3U0mVI%>p?`h>P-C?A zYNC|z0K{-b_)8bfKW(eGE~9=e@atE7k}B%u8KC*wIYqQqg`xLRJC>G~767hKFjdC5 z`E#I52oF%5NqkKBVyNF!Hy;Q_-4gvWCI8izqM@nnE@leLuzrxppN9=IW@gtB@W-)x zr3%y0JN% z*c~$LJR;+gd;K*JB}{P!;|I*IBrtEYdqqKK&Dk=yoFXR=I8=n z?pDK$+`k?#t#_7`3}nuqIC0w!JdVwG4y=<7Jq%5_Iqs7hEg1hMq?OQ9{M1>ZKd!6J z7kdg(#Gr3$@HCnkmrw#vz%*9SJo+KN#a(gB)I8^<5K~1|hVs2G`P7-BdVRIkQ)`hN zxwQC>erI!RD1ecXeF7ve%h6Dwle)+3SCWEFllnHXi&?tKv!f{Cm)U2l^Hx%gXvoY| z6CvN5Tp52vWzMfs`(g=+(Sp6pMb5U&Ui-GI;SwxP@wU6Q>#ozs1JB0+`_?<_0mr+g zl0zs4lBw?Q+ga6=IyPcmzYH2dZ}84-Y(5>1>-k7E@uDj|Dn-`V zQsGe4w~iMxaO7>pio^RxVXmT=MJ#IJaICEl9jUbqwldKX7&?(d;KaJK@z`0#q&{!D zl@?F;z(!8Of~l{#75QE4PqSzI~AE92PEr|tTT)hf_c2%(2?gk%G5ez z^)H`6my(gX;6QwC_iKQzwJ8vCW`jahaz6^>ikcl2m zn0mRZOKeA*<9%Si$ahdRq?-c9@i=Yxp#0DH^4aK}jxGQG#kr3PnD4 z7{Ad>!X1|NVX1bpa%Kcnoi$4Ciu33(0f$`(UwKHu{6^%+&6wH+54^{We?lTK$kLB_ zcQMspd&Vr3PTv&e>&OQzCjR#$Z%5*bF9{QHHK~QzoamA~`p$&yB1hWn++G>fy0>L1 zg~|LuLzRm9q!%BtFGQwKcVgr_s6Fz|MS|TcW7IS$JOlX!^M&w9!5_%IDzEX@hFj8+ zHd!T1gCG}zeM-?>Z`J>s;&6DiobV@+dQ_+YLbBR5BK%JpQcNSd&jq z7Bv#sf4{(&^oQWCOMBx9M)m+Po|@tgVYSG9lbMVh>~ zcZVi=1fuBlAy4@Alp&A!S_0gCq&5 zu}Xt%%`_Q5Y#z%3k#gm7qJuM6UWPz(puV$dGuDhJmY4KH`XkNS^+BxXQ`)IJ&yd_w ziY^`#v(JM4J9ghtm^2&I^t3@d0$+xzLC67^1_a&x+RwDErSQh4OEJSR8`hN|tApf` zgl_P9BoyKwmK@5VP(szX=V0o{?LNs0Em6%k2Gw{R%PMK;swXV_;) zk~obPmzEZn4BBr0%^kbpkLA2GOD3;i&L{pU09bS$`x+dK3&~^oqd3Gk)=a@9&|oDM z!2=d;BogiOawGBS182waiihn;g}RsdXl=Q4tT!Owu4p5y&%6@WtOMn;OBOyEyauQg z@n>6fOeFXAHI?6)y#0y26xccT5kpngL)onjB3TJG)9r@!QzQq=uKvI{O5EOAQcWVf z5o6haK6Foy>m+veMyEwK^L$iFNK)(WHY)7lnAO=qGR!OIQSeoGM1=dxFAZ45ElR&( ztmtsQkef2+cXh=mOVD!#g_hE@=#>*Rem)5~7-3(>CL|1?*eQ>5M_0&=;hE<4&?l4p zOZkyEu%G!CDNJ1>sgnoQc&jo6)qtcFC9%f0U9J_c?B3$F-TWIfSMbcfk&VivOw8oK z(x-g5u@q@J!2ABivui>uP=Wr<4cWc|pZ|oImXH+&1mUW|9u#BwVW}ZVlPRzOY@!nqNAy1*?tTG*U(`-Dg(~KTvZRu0F@U70GcrU0@=MZk0)*6Jk3~_Z z6?gyk#XSyXKqt%JPTNBNRD8S9%1mE!|N4zIe|d9y~XTm~obgP$|JX3Ta!L$H3z>6r-%Zo zr|DA82`KzHSE^DM!m+)~?SeW)al`E(vIr5I^7MUeBiMR-hK-3BG{L17Q=ID5nQ{9p z6Z+l+0!nBGZ3oKt?-@r#d@2g%mCZwHA{o+{DZ$xFa%$1V#=PN0wE>37As{WFEhBQ3 z3aESV+2&xK_GKSuxOd374jtT?8_3D0&0)?M!|lRN%15~Ff-k4aS1G3Hrfd&keWsv% zGah)_L-N|H@yY>jq_;D>7CzvJZRZEIyzu=!QT=H(5wXynRKj4Oj|3~RO+@vCbpi(* z-R}2@myd`vo^C-?Ahul&OaN{U-Yz0ka?(vvnNVbc3iSJ5GO9{=U{DFpv+OAntt~oy zV+_gXS+cV3Yj7TGsoIjYGKBP%Y3#(d@kVXjC}-#|GzTK#C9yP6{JR&s^39WEev9bW z)4%*>wyf#^_|sS_o@EbBo*U$F4G_H6m{@x0oh$fFePu%fOhqAbsd6nl$vO4S(ZL{>x;T~}6&=UiUq_){zlrpU%) z5udX6RR`oAoIvrFXNP+qwReBibhU<)j}27E+FMd^tOzr_^JWqJ8oLE92zzBS=X6;X z0Ca9tQu=9QPCh}$46Mu;f$*bg&s0n3T7Mrz!}2=0Svzft60iSu>2WG5$6IRs`HIDheSvSsH#WoruNLJwYv=L$96nT&0DEUaUcILJub(y&z)4nDX(L9W zt;R)Udh?vKGdz4t7dT4rW6qtSeBVtwN+cwlb)KS-#s)Lt;o(-z>17pVd=WzJz~)go zFS58ugvDoULfi59MAAhh-Ufb-{1Ic=|<_4;uO`~eB2>%+Nu-@jdAEF zE4rQw-r4^sVE>W99v+j^rT_d)2U z+C1#OiG^#jNAIqdv9qoXpESRxOk^6#DAI;EyPp}IX34KGk4#PFt1e#WAhV2_Vz8#< z2z;{oOh*JXqSzp%?fd!N ztYO_nUuVhVgXBVUCa3x%@rZrebWrA!m?t4SCHJPDRircc?YtTVKkb>x)m?N}h4r>~ zj+E_K3S43`W$!3h5m@uJH=MiKQ%0GXgU4rVX73CpX$rP|ilnjoueRW6$y(^9geLQ8 zyhZH}zmD#&kL55zZIeFWb0D{B~i;>ca>gu6}xQ@L5GjL;D;sGN0gR*>kVqRB`Whf z5&2kW-G&u$!f!e{6W=_EAs%B`*&c`e!IOUWpW!BR>@H+yO*wb@sTWiFvR!a+Lc&EW z>H4cMENsBc60aOjBJFUxHVTl!hdnu%yf^lK`FgwXDZPF=S#$HRKB-P_3Gs~(Qa~i^ zHUDafXK%13?0M`1qn!j8T?$kSc=J5@CV&^bXMo!t5;d(D%0P@-N(s@))T^pv)6mDp zj$>J1w5xo738@THwaj#+(pWPOGnBiI1te4C2XB0RHK*$*tNs>f@_xnZ)Knqh78_;w zp{nLh?zi?jzL+DT1h^)GMVd^5JFO8{onP_Om?vK#o~x-4AjH4c=8ejWkX1U7DT^m< zkNkjEk7oESzO52wo_ddWM|>j3&eYVDw)Elt(18KCsk#11FK=w3=UMa8wZB)!JpT7Y z;NvxrDlt9R>y3__&Mo8#%*Oe6_*=<7xvF#N~Fv_BIPPAIStM>wl z-=(I?(sH<(!>f+xq%q~Ee(f*XFVf2t!_EKV5-lvB&iV`5-oc%cHT zDg0Y}ml>xcQ;hirJMDojM)O+JivGICIAicrl_vW4!6qg+h%2gHX1I>*IuawN0R9Rc z;(?(92c?XC(Uwm_TXJspI!3v8o?IQZua}IZ-sx{9tW7}04LB0lS7&A(j=r|sbS>6K zp|?O`=)a<-EKXp#k`d3x<(Zqd^|E#O2+NYq8_nMj4sR3MJE^B%)l!NjvkU|9a|YDN zH_lc$P$rOWuU-qBK@z^c;LfUg3c<_Md_QWDqt6zM*lyvtM|$YGH>Mk!*1}2Z($3i7 zyiGY>E%|lw#W|@j*uY7h9TaNsK?asqeBcr$s(0@p>~vx`XCDC6-)>f;mTp7XZ~nI3 z{6!p>WIn9SEec01iS*;DN?L#t;eI2muIaV7!@YO^D=RP&B-CZw#WgH64 z{KtDKq_MZGhLh~t8@31<8tPM$Xs$y&=o15WY%sDA1X95l9zsU?hOt?Ml1#GPKLK_u zP#;fIzA7CjSAyClbV<5yKx|)=Gg6m;sw=zVzS`&%u&I(TcH>^epF{mUZH&u{DSaX?$)^*iZO&-XE8&`o|CVl#Vtm(E zWxXRfNDh}0pQGh+b+%km#enAG_Y~+FWhssOZIaqO4#~k1G9xNP-q#13e}cs|ue#<% z#-kWh4CqX7IlmHM{3groXCCShMQi1V`>ePZGVIt(G(W1g@sl!f)8S}+AgRL6&TgnQ zzj(ez>(6!bc=YLA+{dSwR7H6?m6%)d-`aO|uI@36z%U6&dQ>qIqV@Vhlr8xQ|t;yyD8QEi-WJa_|@ta z`4n*$GAAH2HJ)?ujGSF!^0$ao{8#tr+?r<}YbcWjHgm%+&YMn;mBd^1lRA>1Ajh}nn&fAzh+->vAPi3iN7!(G z_8LQlI1{hXUxxoPS#>#MrueXDUU(>5I;CuO(y17M9S*@=GuX|R;_Q@x@~;jYoiqm> z=vR;(kXJl>WvgRDi}NKu>ZhrtZxIH_41|8239aQD2ww7p{N#_ttx^ngs3uw6q^sd6 zES5j|K+RZA*JUO8X z-tNgRNrJPo#s=6d%kEJjbEY9KFUiZip$KOyyaN=K*scLRGAL>lH9a_}3nn&@5lD`$ zZDj+b)OM~qeEBlwdDzmXvuwIG{yHeXSO>((5os0iMO^)rEB2E&xB7ZM9r@8ZB9U9& zz*9@M<3(`xuP_i6k96%fIq)0q92tx@g1Vi>#j+Go6+0GTZlb`A_Q<`n7=l8H7Xs!i zQ>|2~UNf`SVJoU*QwZ~qs?0cKEPq4ZP*js2LczMRvk`wT25}JK=oQIS9#~C&4y262 zLPgv=`E(3v4jNSErQGcRySe4$J{N;f<1{&9r>O-(83Yw*#M4E2ZR zWZ6G^c&_ST6V3&6F0#~4PgCqNeJ7-#qwd&_EgLJzqTxhb@EY2SvS5_hvKvvDe5f9l z+{qHJ3y$;#sMun|rfL0_OEtwCmKucu#%5`=;qQ5i3=lDCyox>(GC&HwQi^lq^GozL zVA&t68ucnEQz?{rMcyk<4o8QLtZsVciFCD@U0cNGqXWs0ZuR^+=1N~>c_^Evj%xCc z-m)A@-l!dGv2y3cTLeCRp=;pivabFZo3Ycl(W|-myHCT8E%$_r!D3J-k}qnw=3+9g zVHQH%)7d`H(|vOqXC@Y!WW;^Duk~_C+zWo(1sbW~{C2hC;k`Wl+ZC&I={9%7E~Axl z3yt7X!^Q2eldiv|5PJNsa#R#lPboGtQ#`wHdQ6Hr}dHW z7NIr~o}Y<%8D4Davr^AZLP}fo=hgVoeIaLL;S0##aa@aSmwZOy?v*aJnBM5$j@lhl zq6EH2V_>vz7VRrmruf$dRwkm=)gZuOXHfN8wPKbp@IzT%ANP1lLyzCg%*^$1MY#Q4 z?bT4G*HO^wai-Vfq4(yNwUOZW&Giv69&1$Rds?q-OpqPYN{6S zGZgt}okBkB!sB+X*R|}b1~3e5-3d6ZN!4c+#XeD<&yjF6HOy=zoSel+CfW(l=lw;& z%Q&3?Oe_u#4iN$bZ_?O%)wIXbx18;N{{`fAei-t4Uu}QJpfng=S+5j8VHU~^f^HtK z_mGm3{`&RHsMV{M*E-LGh53^T1G$)CTWdp$aJpw(YxC0;>YC~JD<%r_WOMnVJViSS zgcw4_Pxcwmk`APmUNq@owpzUORq%f!Lw{!{*FoMv#M8n|JDbEYCu)CHdX%gUS~@PY~>z{TIB9h81{qpuJ5)BpKI|O z87O*m+&=Y^x5FP{t(&RBYt*=1;$|UST!=$l#85=Ej#@-m{M#3gyZ#E$LeHm%7(NQC z6d(&#<3<=QsK$1zroow}MFV9)0n zI_h4?mJ8h=^M2l)4JJW#nw-ui{2A~R1dFQC>C-#w{2OI6HqeqLG^uCTt1zDPa9`Oz zAEYiG`hnsvCUXJRC;m8c>kHr6Zw%1hJ$_np7v+0(6lec%bx&QmB7Xm{jCEw4`FPW` zeVLK5WO)?R5V!ds8sIdV|d2!p!@B*NX@H z70r)RGI-SVAOm~5r*`HE8bF2SsFmYHSpAvsY{mN!2+s&1GtA3n6*XBX4nayydW9E> zeyM{4g+w`n6|Ir9K-FT_T1fdmMGTcFArgDL99gA+n{o{BcFU&$Ltl|s0~IBH^KA-- zsuX32*&QwVfqa_qT=%R@H(qAp1788=8ldnb>V7pe@Lz2y1#k+mhTKwEwjNKlnpyRa zxmDmRA67%g0_L=GyQVxfVY?JMEdc>qkSF%zbevv!`UMBiOV|1 z=TcGI;KvV5Xdu@r^k{U;M4tYKP`Ib58+RE@@y#1zxY}JX`g`hIuOAw|7 z54g@WlAAzz;f+S+D=$W;#n=4|0QF4xG`Znlf)EMiIbFV+-{SyQKH@5WsX49&@`-7e z{QSwuI_M$!>c3x#ECLxPj!iU9ioYmEV#1en7A0iJa3q5X6P-i^(>WvW?~2-77ay|A zl=Q^)?}k_1+`k-aE$L9ViHTot)bUw_DpDkUb=B;LgKn%qRlI;s0~(;%Q#SjfzD8wt zEo5R-jW3HrP>GZt75xP&er~n`P)AxB=MTp3pdzKtbWyGpFlF_ zw_a%}@uUpqXoNij>k#iyM@#)-f2+J$eHMRa1Z>JFE8fBpFE>0ovUs>~I~rg0ZD$D+ zdT+RyU@{*tZS8EVkQ(|&;QR5@X-1<~kE@%Yk#ASu4Iajx6u3Z7eQ%GJN7kSJ6`;R= z-u^hc({`u#9q>QT&D{2*!BXf7ynZ8)EH|oE8tbT9{ATXsx05-%Z$3-Q`(iw6r<{hZ z4F=*jTQhB!E%v0X5cU{TUMKq<6uBjPiwM(;-xh+Zwh87$&xw_$z#1!^A#HvBwQ9v6 zHK46dR!4{0zJS$okcucy&d40k8j9(-TZm6|U(2HomOZG1ni@^~0A2&PXiQK=1c&-8;P*MY~F$8aD&+ z`tAv)!inpxt*!HY0r=N1U$Wu&kibys70Ua&uA7qqtpQ`wB(1~d)3cv!f}h8MpSzDT z&s)_V`sRFGMJP4Q!o`|j!bc<$O93~9xS-Gw)j|ozDWN2)IeAJ-W3%TaYofqIx(*Fq zli)h2&8Jc0uG#pM^H#V6pSc-{0paUfjMBHDz=B{)8c}^3>_J!#hON4~&It;!|NMe= z$J;x=)QwSZFVAyE1t_RbIdi&)QcRMQk7uZ;;o4&rbpOl{G-a51>3$y;aF*lCKc|Gk?R2)33XdK$xEadL)?)#$&%J(V7{XO{}x*;}kNz&{e z`B2l`r^`pTm#t<#{374-dBkMOBBKR?rjT7XYic5L_pcf*;AqBxf2+K&3I53NlVifr z7CKFe>>O^2Q73%zf7STuO1<-)EejN73ub(mSKZcwl8%eIe$n2jpfWbidp4^-+-Blw z-CPN^K5QUwXFR?i_6RJ8k%2zNbnK!csi}e~_SyP|32j;BBeXRj6y5=;`y7P({jE}6 zHr_*uk{g2P7G)t4lU1cA@20BChSf9>W0BatNkzqhgHJH-Pnyc|?WfP>UP?|ZwtxIv zH9k1D_E2)jzwN11jg2{Q2VPJ<38B?y+Hhg;N?b5SPO`SO+N@YaIQt66Q1?+w8@zA<`zreR=ZO3t!-*MZ;uYNsL_dI@jH2d^lUHhA*bNT-W+mBHu zM)Mr@U;d`fBzoJKNiN0z#Et0kavirdl znvD1$Q^1#tsL0Q50SG~%%?T$L#gnKqp@e~4^1`>N2iS$!`lvRt&NTKjrxfJ@!+AeF>rll z1e-Z^5*%*hs2i*glPsgA0s#*4Eo^B8{FR69$)WP(MY83kac+sUys+=W$z$lA=(Wu#TT z7!akaf>c@p!>W9arK4Y*R@nKtv&EOgk#@REy#_g7Y^#^!qk>xpjx6^Y4xJz?OX2}K zA7ZAagf>Nr`TvAgBwpeIlb??$HLKxhNK|!cXehx*2Y+r&hv~equoBW^Rj*Mr74ZcM zg|SQy0)PgQSoDT2*J}e6%}!q1i&%&32XSAoQjH%ks_sy$S8d-Gp5jO?e@A9q;WeXB zUULC}cakodgd7XdNTcUSF_U(#KfDStsrW7=d3LQ5mq#d7FB_e^dKD$c%!|aX;F&B^ zXZXQRu93d0>=K1>t@{;6gOE7STTsKyG%r|oS{(-X zU87+Tl2t4H()9e9%JF6U8{Yt?7nwHPl5SQyjD*F}QDXP9kcx*(nYR0bN3Tb3i~lQ* zizDHPZ%_ZO3w!k#r6$zn41SZfT#nsJe8PO#AvIcaJ6_v-VS)=NOGhcQ^1z{_mw)>7 zjbhsk?^sm1`E+5BYa`LL+k2Qgp&v;%v}O-`yAF}c<}c&>iHp#G>d*E$H)dM*T2o^7NwTm|4WSdEjS&-=rZKgu!wE#@IO8-vsNX^Li{}&pUHx^1BzH%2DoPTXkH5%Q6E7|V z<$hcAh44z{uHO%IlaAmLVlMcrh*`npduFHm*I0yvegiw=D8w75FTff|PY0|wtB zCq#*YIU|EEmps3^I$iD!rA{2|y1A?VW7rdt>qjgsETlah)*V{iop5~`pyJaLvd_wV zVoI zh{e*Jo-9@_mGR{1KWo5T&MDOzMR#mSs?pM^=zm6%Isnr!9n`CUXax73e0@g4(B*8S z$UCUk&SI~+_|jK7c?S3W50{uXqv@=AFNAoRF*V3Om88-a*~HN&B+>e3T`i~uv8Wb( zdkz7|0Cgp2;+L>2Z@gUcLp8tF!D6_jm5(bxdDuWgq~|JeI$=>tF;7xY_~yo+&v58r znTDz+IODD~Z-Gc4ox2a@@rCx!BySAD=K1fI3qxlyoCGt@vR=mMS^&iVTagZ&1}UN@ zJI}b)ge4hBdtxlw>UI4tYCaB&^szm6f7yPZ4ezcgN$c@wJZWbna=Xp3N$g4_vd}`l zf;@QeWjUYH`aM?GT}JR+a+cseF`k0^ao&c={7wood{t#~gpR*b2YwP{1~P5pFrJ1$ zP324v{eJazBTa0}ldcqYmAaz29I^LDk{rT!hlxzLj%Ydh%AbFAIf6TyQ^t!6(TS)< z6pxd~PKD2rqymo*?( zuKoHSwe4;*@t5>Q!zJ$TG4HqD%^uf#7pSu>=ZCc^x1$wNz=*i`(4i$j?E5hf`0qG> z=og5@_@s#6MZ|PUElFpm$rVLRSuM6Jo^>~e2+J^W3c2n8Hjt?sJG9`{?`vl!m2ct8 ziBO2N5nUy)YB8M(^e)Zo%MP6%4U$_Lt&Wh&L}9hT;^zHjYi;Hybc!m~T(-LFp)66nZ|M19 zjloawYEsw7?TIN&x}Z-OhbL|R z_vibmGxkd&?su|Ny4EZr8~UE&75h&N4z;dznD zx;{0&fIs9PS}>nqaILN&q>HaAt~opi-_+D2R-S~%RublpK03(8{(F*{f-vZp>cKHd zg+WOicMlox*~DH)Z2MpqQGwOpv06A#@^i|cdvZ~FJIiX(DFtXjy+RAVk29X%F^`!9 za-<@U1W_ACpYp6S|G9#!Bu!_Whe8Zeeyn6m1BfjtZzzpC%G$<8^#8>_oo_Mt#-tIK z9qlk;*&1h=7E&$=`uwPsvUqcK)$s8XA98(fuaUkXzH##0UF zzkS6MBPKs%9xqI%2R5!VjMyJBWV@cLK>NO((-riw&ElZEb_S2?adG`dVESr$m!1vp zy!WUq-A@`E;!NVJwp4~kj6Y!=QdhlP99M|D++b5B43Jxe^phy(4r0R%Hz0?}D@GnNa^VJH^^I)c^kw=Y!)S z=E$W3=odaJH)?67^)>YuvGi{ba|7pI9!?!(7G)7=pN{sge^H5vkO0Ty2b|);KMORA zEDLU6^zjZ~JB(j@sHnfgdoA+(UPjf_EH~HxPzj0K>relGixN?&`B z=jhW~-r{PP@4rF|`1DrW?R^)II=hYQbE7esuCqp^l@)Xg5Rot&)kbhKTq7rK|-{t7rpT}GqCY~%e*y^z*P%&|2^vcX}lsUIuyRe>y$8#&a$oi zn;Y$}d3^8>Yy7S%=PPD36MIIQ)lIpy{;S#Ca0fKJU zTtfn{q^$ar=|K?Q@%$S0h+qgLFT`w7#?1e?uWuZ8g=7~ ztanvVg4(c})+CHs6Tbe8a=w+{o6tx6UE9#&au0r0pP(TncyA@=ARGWq_+=bsHmDZ! zd>2(~0ZGWm8Y~}MV_N`uBZ6a;kA&~L z4;44T1ZfXJ-^#hXJeyu)ZP@LI-<+inFf2Fxi>jb%uD|c!-d;DoeP_xwGczysCmT81 zt}Uj7H^_!sb->_~Hkug@(>j)(ljo`i<%g7Y#U-g>{u@<^iPZoP?<4O7H!)1dvQH?H z79d87ick}GDn$mr2d>~TGpzK2-o2x&do2y0X%ZUIoXhr)ENr&@^{R=Yh;nIDwUPiD zsmWx_?M#SRAQcG(?ohl7v-g3b^~s{0688T|%59XVAIEnt{}V2|V~G8Qva?^5F&f#Q zH)?AXu2{bwAncxP1(01XPmBWmvg?olwFKU?kk>h`0rhF22g!JDf2w%<1!^qLT6w5? zEyATN0a@-oG`804F}t5lrI{FOg8z|)gohVlC&X9NrAMd#+jeo|f+P|`pJnm+nuHet z)aI(j2P1=?we!~O<*hWAM-0c8mEq#&HRW2|_!W=|nUM*FWs#2kx8 z(hP$1fOU}FI)6dy0;dlO(J5HBAcl!!l6gwANcke0R#vGAa@o9*{z3FPGCu-U1?r+J zLtG~3R}R#%Wkfu`Cra8JZ$h>PUet`96Z^yDMu;$cRDoPpXmG3P9X$l){Q|C!I%_Pp z>KqZZO@3ni_6P3YOc<)Rqs-rABnJxU>4XNbREGO#eu_})b#Tc;=asj-DR3o(7Wszx z2Y)edex+`Ij#;FvM|w**@b~>b*LA3){Y5+ds(s&3M61!S)H6X$(JG)bd~xnhcTB{?Q9=BP}wEu`NEVTKc70BP!){L9$*4gXCKaj$~w z$yL|T)V6?8larqA&$}P6bN^=@`NI?cfbg$1CbANF70MyVD2~|`)FsY}s5Dy|;4XfF z;>FH}BQPSI?4O1Tn1a8ZvM#&1k|G3V0VZrGLlBsvD@#!=$OJ}mtK=uJf>exmQJf|% zJl0%qAkclysRM$oe^k(7Cj?OC=66=Xok_pqpf037>M5W}ppZ|VSvD-o22iCTX!t*w zi*sH7ZVmnS?z_T!*d5q~Lz?vC_w|7Xy$V-_C$s-ffy4g(%zT95v@2DzYWmIy-1z>v zMA*lt9fd1yV;mKU+=0yP8gnClylHTDp6S+5Y+;;Js>s~1DZ8molQXfjubisq!6aYa zQ{K*Nl`^sxc%8pM_Ph8aVq5dA250D_(@R~6fkF-<-8;^qW~-lm@HuEFc9{SOtZjtF z_TCcNK{gyjc$$M1@q#{C)}_A!=R5oVAv1|knaF>lR*M{4@L?E=xG~&;0&$yey9tHD zM*8|{Y@b~9JxW`&o^#M37xu<~8xIYJQ~5Je02ddZQU!x)x@sUgQp?K6)E3vpN*jgp zQ)$Rx!^N;dx@YFrP#(<>0*uh-xU)YWXMH}42mDT2Q@CQ4<| zdVgTn`Xw^&htzXYP!rD_w)}EvCdv>Yp`OVUDfmv+=Oht*?PA?zCRm@W%J@`0-Mrkq zyd0vow+k;1Gcz(XIsa~YxbEr+s0J@wh|*J?9;W5@teZiT{II|ZqM~WtecNHd3sI?} z;Nt#sM^fNKBtSAtP~kklugz88{Rz7K80D^=4 zG;k^K(Y{(!fMatgAj`B$wU-em)2)YCk)m>$6?)?wZy1KjOvXiO(^M9osU`@531XWe z&``UtzcbWcuF#`0e2S44jJnmaJhUdb?vh)?ePXmBl1wWxpV(ys-oJk6BJMT9pocnKSK#Y4C zKtv-e7LK@)uV(Vabnt2JF7Bv*MK0UsKf>a9c|#kZ$?H~Su*neiOGObzvr~x!3(cW*BbQ);7OwF6(dt1qdSTp4Ny2(65_E6}&ooQ4Ir?+nro z@C3e{S1gL3s&C(X9F)ry-#%=sI&DqI%6{EGV%Vmok#!&pu+h^ahv4Wb%%SUAyIv;Q z)!DZ6&y%1G{($`UlO0D!fpk3G!){6i_;Sj+&A0R}tq6W=W0KW8r9xx@`eYstAskbK z_PY#>C<68ttoQp$usf@>BiER%L?)7(yljEo2U)_&-O(wRU^nC_2b)(M$NpnjnrSeZ z!UvdOBL6!S&fr|6;ZZdHY}3chpRampke6i1+CA51ShA=^s+M?2Cchr4uSl?9-{@$l zA@z2o#@PvD8R!dnMaX$Fli?OVOd7ah%hxq0 zQz@9Y5X)8^gIVv9n%?Y0(ki)fTw0I86=*9%s>Y!nSz#HOtgo1#{g z+G6h!Td5IyZ>?F1*jr-O7DDY^YL}o^)GjS*Q=8(;`@Qe?JwKiwd5$B$?)yIP>pI6Z zf^dQ6PG@avGi%7<4F?PGRhm4p`JP#U1R=h$@@~A~V`ZcF@QE|Mv^^E;^(<^4FPt*x zY$@uP;a8Y!Az?z=#0S~=jRu{rC_Y-Fbm@hRhKWE{k`BDB;4_ge=8P7g|1SRA6MvJA ztHHe|#S2aMX~AC*CvWqkHv|wev=)+%r(3xv7n&B*1sP-xup~nVwLoLONaxHFb3)tF{X+rSz`T{lwtE2 zGs>48L+Vw`w7JktZ)iVDv|xwAaom|}5vXYGEiz@E!9r!{pyf6*1ykKp=5)YT30gRwq4)W5iJwqz=@B=nI;aUVM*flVlhh(s;A)xdaJBPl zeCB}Zpk)Odb6V5h6+`rOch24IX8(BYc(!UNN`LgjiXz!FaWK{M;emrijOmk`gny2} z1iClhk;sXe*~AtLevN7A;7gsiX8N1(FrNauZi?&*qXogOpHAYM5Df7C2a>$$dNVU4TN5iu2yJY{L?X)unsF3{;(O`n!N@-b9knC-i2ZvUcWu*4^^r#pB zACXZb51Gn$itub=u@9dwbPSnh=pQA;YeXgIvbP6#sl*_N96xvy4pLDUj4Kl&PYnZG zmd?ADT7mstIq)W}hVqKd!h7O~Fri0*A}cUJwMpP~zkyu|@lTi6wy#mPWk=zafH0P! z)Sx7~LySP@wA+N35U#LyQIGXaO=3Q{*<-toGS*a+~ztvo*=mC!uIRBdjw6+-X( zJszvC59Puqi!At`FbmsPE#=Zoa^wDPUB;V#XQUegjYI}Pg6GpB|WtHERHtzJI-308`V&7C&ROwJ8*=!I99xxsU z1mN=t+wtg9Z{X3%GJB)HV(P^?X~R?Kzf2Ega`mLx51z(&cmhR*2@E~+f?g$iA6YoX zG6IW=kYi~6tl&LRaC;R6iV3S1rk^yu`JJYHaCm@=-e!{SygxtlH(TYOODONS{1XGX zzq>i?4!!Aut;nn_uS%I8)?~Q~3x~6fF8m!Bo<*2A+jQ@@Y_a24z&zMp#ww&@0o3fm zUCa5J>A?i}dL(n-HtI%A1oA6r6w$y8u3v&@AePE>@hAk$IqPWu&c&R!wIR)?I zA!3P@CxO@uE^ws1y&{0UO##02ul^Z5FV5u%9vg^i*0&kqbDWiZht{5*GHFHY* z{l`j`1-54TkXS}=54HRR*4sEv?ZVgO!`;yvwazG#Kah520Z{-%H{?pL<>Ui{bP5W* zU)ecBluk4XQL}Bd)Zs>j+LCzQwwr$Q$#&uWQ;)qdAweS^x+()ycFtLBmW-7wRF6rXl+(byq0VClxZ8^_ zhq7(7n2Lz?N7A6CDB7MctF0dnSGvTeQSNrQIpSNkIGOh`0j;v7L_%9%oCK0lXEBAs z@%B1n&7%YYfh+&HXkoY3)lHfA@ouH}ZG_$&y@ljfZa3#&8ft!=(JpMGbk140vC8BS z3cVnsh3ul1Eov4qwR3l!tNbCKczjNm;sCVncHcehDJ7%WdNEgRWqD&&~fBUtGIBTqe!OoA9_hLFIw6Dd65Tk8_J+oyv&lXH7%MM90uavdp$#+I3+Hr>|7jHloPucKjrhw*`K(g{ugk zcu-3LVOXF#ZkltD(SzB6%(=b}t! zXy`ouq8+QaSrlGoi7g2GL%Y;r7TMw!)}VB`1NjT1(6ki}!h}Umd=st$W$i)+ge>%u zW;=x3cI+t7vNiRZ05;9SB{5zc^KY_fzgg{wk}H6KWSZz}hCi2cvm)WS+yvhUs{p4j zCIR7Edh0C7Di>%EQC-RswRXnkICAD3STsSY)KiOxisnfVGA)k#&I}>&tnm+p6r*x! z)3gS613%fXCY?{LYnC^^Z5*WEA{+TS!$yf%6{5I4An5iZ;W69EtiHxIbunQu8Yd~o zY!GLh8YWlk#u!Y%S=E-&?m|QShV6IZR@Q`SSV;!A48J)#N&Qh*zkkE}I`Emw+Zwo| zuQD@xvTWv|@3OxS)H6p)atSgjN-XzLhk$LYAaL;*?9aj+1s&Bx=`pu!*(wn(p-g$k zT*QBt#o#jkoiHhCf9h>p$gMCRCeT=fgsCx3`L&u96X?%iSXo8^ncMLC{0DIE@9}g# zm=uSACE!^#pis>>aGE+qx1ZG^Oc-K9+K6dEpFX-f`ILb-=r@1K*67eiHSN(oAbi_q zuzq=tY8sADf!7_rW_rz=A16-eF3W(?W0N$PL7U3RY)kz2ip3N;?h9%Uk;^0DOt{PS zzN;BEqiW`f14x?ZnC#{(Th^e=oNv8c$4n3R@9qw!9`&3|?@w#jUqHt|5e3Kk8RXPq z&@zwa<|;zH1bSwTg1RCd^K%d2l&LdHS*c-A*1*}Kia$XH(W`frB<*Xd{>y;xuUH&F z(N=<0_ZyY1XAl>IYIy1mW=5lM{CXh5-TsA8+E3GEuqG8YpdwRn`{M0$*LE{{55smn zpY{*HuNsv#ZN=C*qlxkqc`VOe)BoyCzWJ2$xe2U9lO2lU!d^~*dtFiG2q#6~r#O?) z7!_TBWN!?Sk*7AxTsiYHbGA#ADhbKJS&51M*HiKobJLISfStJL?1v*2+_g67@cjpzH|0d?u7pi1(h7-goAKlipY~$r9!4 z8KG#^96nh$^kb^u$6T8jX5qIm8HGGe_#Ah@1|qKVPk9i|sq^_wv75avWTUEbSL=)ZyVSlj+UY;qdAr#4Z#ZhUXxNMS)#RF0MbCK1 zRN=I&yS1}_aF@83e%O6~RnQr7;(mV{dRcH6y?S%KTMM>}|5Wtu5mFd!T4~x}LZc7n znuaN}Z$52$M0?F;oCFztgnW^rWkBNin%;5H7yg3lx7}@o!(}c`l)!Q`V~SE{UARX8AkZqHh^%L9;h5c5ym+PPgfCRKkTLu1Mx7d z3HIS)WAzl}+ukwQcF?v)Y79Xj1pxPEv zfqiLP#u+6{kQoIbo~?OI=p1bG!gcQ*6i|pM#QhTwOaTcEme?v~Gvm2T*HdCzb+X6N;9VtG|3o<> zjzCY5r_}CCw}wtm?2@Wu0zLYf;`~K;o+^>ANH19BBP+pjy_b=Aps5)(%aM3%$;lwq z2Syqf@dl7rpZRCJUJ?n(Gf(H)TQZOCa{((CX4DX0mfe;-k|Ik2==)3$Pj6WSH`#LH zcgWSrh(1#kUL@MSg1nbFhDw)<|hYhnEd}d1uNb6II=r`Q?eDX3VLwRF3x7|&3-fBl-M(BtS)XRcg6Iu zOF6Q`Oc;{m-A=|+P9J#xy+c&0FZRDk@~>~EO$$6HAQ_sdbbn5E_snDJ&%~9PpJlgH zXt~8-%)s7)sdH;b_nR8C!`r(cS7dXOy8B{tlUvvP^z;d~4R*J2e^y(tb!Q)XetYlL zQn}?=P)H5SxKGMRY#*(`(RKDzC1oNyYj40ys9F1Y0%}zhf*ZlCP9?8*Z8Ss zPZ({+J&YRMl#YvX?TB!fq{uaMV&sdOw4Bos{QojjhM&@}N9lp^5pv}*Qa|YFM7aCI z0rrd!<$hrMwdMgG6K=GkkCTqV9Irori7jlWP-L68Htc<%=||O#5FPCm=8R0Qf}4{m zGi&<9;}*($gSO+D48Jm(s5>Eb1U>zuV3isd8U@0jou%)>={_awQ$x8$L0xY`|5aIb zhhD7pO-GBZcHN#%8}X<$MQk$jr9rD}J zQRpg)RZ+-=$D~{-CIAE!-?3D2Qu%OSr^~~$3_tMf=ua@SnNtyK#_Ex)jS-Zx%np`C zdC6r&G=^ELAgp7eIc+L`o(380@&Q!~LD2L79VBUD&-$eJXWQn}ZIgbt72^@EBlS2Y zP4#$pD7BQ=lgQ*|uRFV-NZH&sy&Da`j4FHeO@e6NuIWm@`l6Td!hn^{vd0mMHr8$9 zqA!#8XfiQ|WkY^9z@CkMeo&&;i{wmInzS1>ZRN(%gg~acc9_+bOTQ-PD+3Dcb~S9Z zurQS^B5^LDLn=S}B*>7uh;!GD)o$$KnVr^ILQ`XGQqMfHit}`pYA1S4L=AIW#rFSku^9d^RKGV}(gX zT#PBm2IWVwsrv`2?~3ZW)GZj1ypL1=BfV} zDnVGovgV)<1o{dZ5Rkp6L#_Mznj^)f^&X&WfQJ+NLYk9yj6VK05(afj$;pnR%HD~m zXT(?^*K|!JZ_iNkRSXl9X7lL*7 zA0OP2ItN>Z2;!=~4L#p)>1r`5cz->xRUp8Q3ul2OsZ>!R7Q$^5*w5KMTNR(z#Td&hXjQ8+uy>1#IVc*Rd_(N11_#}$d0#pwoT=O4ms4It4L^a>_ObQ` zo+a(L+@7P##4h?I{VCg{A9xG4r4zG&%%iNFAZuR;vx?|8{Auf1;uW(G$7-a8F%m z?|R!6pM_IhSypEFyyco$7+z#&qGDnch>jBwSX&!$s4Z-w!3_SWbmxBl*x(0b7LgE~ zginEL0`sr|Pqn31^Uw3H_9$c(`^(GU9=x0JZbu5{9(_T#CDGbfnF{MeBXG+D1#-76 zD{~18aDa)rNsmyNmP`d`Gzs zA;zS@)`{PGn47}zU=I#zKq-Gvf_oU#4i_g3)^F}j`Y;T$4YE2eh-rN&N#RfiqG2Sh zebY8&sb-peAZ`&O%=DnAb>DRtI)=w8`N4~>a+fCpBXJg2K`NvxY8x+}U*N7Jn_)HH zmYRV#{AE?8Lk=2X?CkIFuTgdUDqgU)zrV}>39=ky0+*pZmz!7b@>UIjWcTwEUji>q{DXHbgU{GINMk*VqFh&p zuv0&=vrAl^&yOyTHfSy3CQ1loGo~dj^A4A7GxuOzUwfKd>Z9})U0^btl-gy};4yZ{ z0>^l3xWLn^4RR{fZz`NmQ?Wi|DYl{VcnB6|jz@U004R(1@!=9Hvc6D64FXQTRLo=l zU|fU8g!`K$7E!6np%PRiL?08p$_knuO=XR%%YWqe>7QA$N&vdu2+Tqc_tuh9IV!E+ zSPy#k!dq8%mNb**Ru{Zit_0UiO~@z#`IoQ z!4VdR=fPX{)Z}OJ&_U9{I3Xz$?&q_I+H{v|VxHc1qYUuWoOcR_^!gSO0a$T-p3QF#2-6cM)>okCk}%c9}C< z<+@%j4TW^Q(P`axI>amNNikn13Lw zpr}wG7o$fTqf&hMLC1CyZIG5t0oR##?^x)3bC^uO9TSuM#aGv^k{(=&1}aYEQ*JkM zQdw-ikhLor`YoU3Z0)M{@}FtZJHFa^C_nLrOE6&cqm<+CTmXXCF%dLsDx>bSH< z(#ey#4;XpZTZn%ebHn3HS%3%h{G;k})xH6AcCTlB9vWz(t{*Q;neJA?RYK;7{+3t# zW&ZP_*#SMkgxc*7hZ7;{Qoi63 zeTbPbRv-S`Q{euMcyC2w%#^rsy`JM!-Xf#m@Z{2(QUnL656pXN$o}C}Dr2PK?&DLP zYW6L@UWi3FHp~8fEbi3Nz!+D9zV6;A9T)Y6K98t+(kL}asYdt%LIL`ae}}2~Rg0;? z;kfo55V9xP%u;$8;!D2@XV^zqVh2c)qSA^X2P#(lp*mNy6?NlLk-sP%*%jmv+0_Ba z25CW%&|$= z(4^4-&8BA04EjlM^EhBtaSzJJUV1RCk$a8#zfD{$Wv;v_JNe+p{kM>!KlguGmDK0% zj{!eF`{YT?VLxh)nq6QYGNT4R|F%7EY&n11{ZHn;pykjHr~B;5{g{zu$lVpzKY3eR zYh0DJZDO0#Dz$oa39FK;sWYe?=Sn_(7?^&|4ie-ngu{vD3kixaF}Yhpue>T4zG-TZ zhDTW)fG8@7|GEK&i7u=Tpqr7yYYdZ72*#TP$Fg*s7emjJlqRcm9sEqRayJH&&mJPx z9*pydvH2`%pbb*OXG{#4V*!LLjxyhHrdTMxp1~X5xFwooM%Ix~{fTNtq*e0h9t%pX zAN9t_YW8{WeHfh*=S=Qu8vZQeVWZ~3b@cL9oW8JtU5LH@a>QcF26zV4RTWwIB4h-D zm4E)J3r_mlwGK-m`I85*rCjExP1>H8ib$CPI+o$tAw&(BCpB27Mx8*!9}^=p;*I@S z*g(tmCeyncpU(V3LoYVR{IOAQGLkZ($5-Xy>-DpcGFell_xC4EZY?<#E{g+bz1^j2 zIwoo*Xqf_{BJv@t35M??;>)of%XNZfn-hP;JBuDgQZE(gt)*+iI;rUD^W2#fDR9P_ zYSZI(ZHA_@cfbwB%srL>Zm_w0J`9XZ&qFffy!DwJ(iYip z&9RZ|yQbG` z{gNpJ&Dm$~Y3fvU4b%vz{J87;^)DUN*d&F76HK;CUtKHH)XWxU?Rw$u=h_~&@Q7QK z>Arbz`gol@lJ|$QZ;hmNyzO6pUN+Ob1-%|jia|=)W?c5L+rwD9eRJd65<(;DgiAzK9lo#jV_bx`EDC#9!W}WPD#a0ASxB16c)lb!{%b=z6LP>L=o>qpE)NeI zRvm;eA>4I~dOdKbDvb^>j+i)+B)12>N?7{eb?YPxeIC6STXfGmW(h8qDURFvN1Nii z(sIJwIc$ba&{Gw@-OO>no9({3I9%CJN?HuP=(ykWYOxTQyNQmA$>yTUSFnmytjoE( z^2?EyOs3CT*~Si@02ft5vJWak`1yr$QZj*uNOAPBE z*PY+3u~Hceu4e&q!HkR-);a9bm3E~#WyF^UNnNQxiD=p#&pq(8<37&O6I z<|?1HKE^zo7p$os@(J3ABz?v<%C+T_LiPI;s4eYU;fTKKBtyO^^YXt>1~z~!NqedV zL)oAV{5*n`5s$=#5p_YULJe?TL~PGV=P}^^a!3Xmx_aT>9eUqKrrolLJxjj+`s|uV z?RZ1iBKW2|FpV+gYG<}eTju7p-ZjM}H9SU*Fy3i1y8$k`3u@Z3BYu#5L`)_sY8+sY zUfVj$mQDY4ogPkH^aapP5sqMXb$n*m0#943Fo&zcnA2k$FFr<=ZxOFK&Pp?$^EE;R znutJLxb2Nd3J25U+<;#?VJV=PIX4&&UN};~O3w?pzW(B2<%p2NM%`g_+aC`(#uxQa zLp>|#98z-_T+=5HZymYQQ4+^NRU+*+bG2}js6J!j2>?)HIVB`jv`i)^uP`cj+93;8jeMzQeW+|cGz#9i5O)( zi+`4w4ry%NlZ48X27y(ayIL^UU&xZ^;VAkOgo{cx{-T^g=^1wL1j>NJOrLRJJ1QZq zZymONP&u;U^$fkm;fxCcAzcj{ObWcA8k1!BWfA=k zAFo&JnejRJ`fMG@xL;g6zLCkztiiH| z0$lFP`EH?qhwj(zZ^c3*9(SK4g>KA+oDFsV{Z-r6FX~#vm8S4n;yGO-u6peZ7|+4E z$!u3DwaX;G6*>GKXd5X7nv*PPe zUL0+A3WYsMmhLOBibYrm&=#H+|`7qBj&_#bv^9Z|Y1jvWdL=g$peMPQO{XFmU&4sIH zt32yW!DN4@QUGt%hwNgVbP72>L3iXbJ8Mr=Ia7zQuHll{@17rh1P9as`dsIXPw!`4 zjpfY@(}j$wKJO^Y%4@s2GWciPYP% z2un8Vgel*!Mpc3%AGWIZRi9LLnld>1Q^4m=*qr`fENPLN&pl zR3jz3+A7WP@(20cZ=y3l3QcCJls?Z2&-ya{Kh|7)D{J!qHhy3ImqGma8&&XcTl-7k z?VVW2ud2|~#qP7CqkzyBNOFRl1b^y>S0&_4QGV9N=77BC@cbHiX|ZP}B2KTWYMmZG z#kE>|i4%Fpij~2A~oInE6n>{ zD}r5Y*n7{3PfA7NVVPx%-&VmrwO8Q^kIZTv+>uobEV$n+x&RW zG>mu)QboxppvI*}Osm7GN0i6@n}2!GBE;7hg`7mj41}ky#iJUUcF#l%f4vPKc$VD~ z{CCIz?A!V}XD0JXKAfH&DA^3Q6a(5;a9u>zW~Zin0;S+$hFQwXD`Ksd+}6Z5pSA$E zqh%^v_?>2+ZTdJnpej`ZpkZ&QC%`4fMEn)mX4wd}*t~k3(=y^{S<}M|yHOmgW$Ah8 zSo+obqrQ%dL*ZXRUCo$)FDkq?B?ni{tLJlTcbAs|{{9oQ@7e=2gmTF9-x#Um}#B&o$FtV;NTtFJs#k@K)^C9oD8lVC3{XiJG_+ED(0VC9eBo$M|7{nqt5hT9r z%b8u(e^izAfA9PpJtEiLiHHSvG2qPWWTVu3_{`8ZL-`=8W_@D`4VOr z%D!;qeRvkTvl3n;&;@$R^ShEsRde`j0FQ<5x6ol7#ok_f#x0O=7HKv&J*lXP1QR69 zL))J!x5l_7g{&=#4W5>0Qa~F+OR5#0}{~l5rgw5II@x4ulK-i}_^lPZfi+)~o76qfx z0RJ{~q4U3|cE}i$0qFd@U1^9bq{|fAnl+uKHS3i9TNri*C_PtV8~oCONhY6#KK>~F zOz7P%kmU%B%yzId&JlIw6MCNr_9heWjMj)!4gueC0#_S5!&ymN;XF~zdjF_sW*0}# zar6MYjz}F>fsy0?Aw%xTXyr?iNyWTfEIxovwu<8ZvlH&kO}3(ib1zdm&kp*g?=M&H z53(#n%Ak!_C7i9qFCS!*uoXJd6G3a!X~@8ABIO;i9|^-{q3sibTam-)ywfTVZRX8W z=z2yb1%!XuY`3WXumcwJ^ZXxrViwi1_yf|9;JZ*m3re1NwPB~vbVo)iqvr*3Dii7& z4D!PVF&gqq!SPpX+p6H8L$gB=66&3Zk7xo|HuAK-#_tkUQLy&+M=I)_)@>_9I4PPq z43h{8b2sYop;R55Fw*Y>YC&VB&Uwz8!v^wa!G^fS0I(w;#qj=lZc3PoQ_3e7_J)eV z*G)e^#^TW3SmByLvz_!=x2oLt?+*AWBS)t5e|h5pCc-O|F=j=ov-c(+JEA-07T$a+ ziVJ7$@-K;ROWO9<@ONKk<|}JKU0^CejnJ-(Q9FgRuV1U-^C$al*2)};J;2E5m&KX% zvd#(73Yu+PrD#x3_B%rG*GC-Skkena-Isq!n6XO7gYE5YY%8rhw6(iKN2r3?d@%QJ ze^;#5vRm~h7GtW63e0P>cF*#Osk)3xS!7}UO$ZvG>I?D>3kVDClahF08bqUr9swba zK6Qot_v(IAvC2V-OaT}Sn;wRQFlRYYSCfy~=AtlHPNo5^Y@S51ve2M!Tmxkj_~xoC z^+MkT-y8A6N2rlVdA3}5$8+3`qr^{OIOfSf`i>Hp^fUakKjgS2J`2w+1cO_(?J35J z+j$7sF9xSr(Fk~=I6=mN27;@qMo{_LdtGM=)ttAL6+m)NX%sA;LxhQs>tB(lNvtK~ znhjHfEmeLs+Q513%PT{2tL9&(>eQlRIh} zUD*=qeJW!Qp3>hGG+|B&A0AE~HaKqbFLc>Iuo=(R@-nsUiAFT71W^Bn=qPb|{7ik; zF5|6(6jY9^R$KW)O_E0T%hG0cyO7+LttYkkPHsAaDdL0#BNEpj;8%OZ%dVB>GYkt> z)#a6iF8unE(n;bx7QH{ExM*FI_y1re^qIt5?4RpWAAX#c&||l|&FN{T_uf0^SlMp@ zyZi0Q>a9K2T-Lv*n5at~LuV+DZ`G3b;QLW!(YDYKscypq-CTN|_NS6Y&05R}FSrpp zGic6t*We6yMOs!F1gM12naWY z-_2=>wgwujKZSAR`&8O*$||S9eBg#Os25VO3PW&vn!}?%;vhqKXIO(5Q{%e8tIg2I z8ZhF`c#u-v%oHWunu9#Q82lgVms^0vYp(-dH#g;Aqb}k+H~P|`%|{H<2CIDOjDK%g z*UTOQjoiS51s;$R^ zuWkan%gf+K<2;V%N=P=cB2dbTOm9DUsCV8VQdSZG;*C;%sE=RLv!(KuswM2wTkluR z>xe~xaE&bL->hVBAnfE3@kbtrg2bIcbUf?^a`NH%X1fEPVXM^B=FcPUL9b+8C=*Kc z6CV=AyfC_8?x|V|1TUA*O|s(e|GFNX`kVIRN@F4@KKxYH-;zC=n`8i@x|JI3m2q9? ztN!(R`^F$s9{Biaiw<{>0GiD*bTVs)z+N`~&!bSN;YgC0AHd=xpK1?KHe@>24Ztq!~B!k_GQEMeB;MAmCre3f7t zW;r|&b0OAu#o5%x)R8G#)dE@3DE&U-mw}V6a>a^DBKld^@y{Z%=2L?z{b1PXq@2!JQ4Eq#>*$)1ASoI)~PPo^Ab$Xib5duJUVn4vASa}=U{5Pk< zaF-$DnRdHXq3K$!byx?d6|xKy^w0}Tda=7F$6K;_Cku2lK1GGW$4-aj;`RF6R4lRe}cJhxbiV0 zTZ#?3;O;jkSyC;w4Ssgyq5X_6%c0*YU0_#;&{DvkC;Jp@SJZ&0Gm{ou z8$53;R1q;fo;BOWDN90+>U?H2SBRcaggPhblu2wRp+JbMCFl)-3O-i#C25 z4uwx)=Lf*{KU!@5m8L!AMzLJrYLgP$fjoAcuF7cT_%&HHJ-O)g@QAWaU7utww*yCO zc&@iS(9uw(p{Tqp6Q!5w8_H>*IE7>v7Up`52t=D#oOulbIgQYL^5vDV7zuM8W3$ia z8vzPbDHhcxw{~yIWYKlS2>f1ySqYvmBcU8@Q-K)OB~z3AuYOV650qK#LA~F0cTskP zggQhQJAm~tBz^1c}652fBu(6Te6jHAGZE~%}=@BT6w$f zS>sV@N}=PHc6*48A0jl4*ctfuBHYrML%3iMJ#U)UL?3f{ZPPg!u;O#t|H z0Q#JP<3}@J$aWu}b^?TiB~69NLPJ8FP?e^KI|q%r;A8)YVZWLX)}`fltJt9U@0>z? ziaz6?kXlF02;@PF6s~Ar_Q59(Ou`*Lu`JHpBY5)7&1>89m9cb*1-fGLGq@T;S}_IB z)MlI;k9yQfMC08qh4tw|o|I(PD82 zQn7}kuUp`=UZ_i?wVsoYllIE;QI_4{esk6z6oltT zJBuKvkj>}l@QECS&5-6>-KP-8EMNRQi$Yi#jhsbldjD-srwbitu$J(0r2d zb$5eeEsUdpt;|;&ROQ!W6Rg7`{mjF;y}}HbUv=<7-caQbuY&IO9naLw;1F$?;Lypm zH)h^GUx)QQsX(9+KAv-eF8G38n7P%ZiwMj=Z6B%ak8Z1(n9^j$Q-7&gmOQOI|2=J% z(upvfY!2!(nYpiPn}{0@e^zntfo0iIAZ_v@tNUmeS{%)wb^iaUkjFdbSP4pPp~=4i zk?a5XLvp)yR`7^Z9!RiHeNAnJeM}yvtjGYP=~sgp_&q6o-$4u!V zRM6B|@iKd~;18#!Gd?;By^0=0tom7K<#`#9Hw8a3IwmGo)EUJ&Rqk$P6!F86CR=*T zW!a$mV$gS4Wg*ZOU9SVr@UMKOjFc{}JVWWOA$?1QE+0e%1aY7Xk=}%1E2dxyuD(Hj z>L#ddKU!Q-5AwdckNZ@NZujf3R*}9E1Uq|)4y`cTk1+H$Jp7Sp@lU;P+%?B6Z7Q>64C_@nQ~f2m zuZVO(=(KWCZaWx$y@rw#cr*GPO{WYAWsOp8iZTyAGR6T@I56+&&m}aqth!V*#4p7f zJh-waDHhvAWb#ikF|wD+IzXL!KPIaa;4YIzrWzEb_Iey?@h{NT$) zo0t%5gOb4~m1KN5o3t5+`Vd>03x)g0m$%$^&*8Sq7$u??Bh`u#R-XuGlD!9|-gUf_ zdA=%!=iv7Q7tZ!*=q(!s1nB>&5B1k~?%Hs*`J_@l39gD_VHX8n?ajw+O<0C(y=GdG zY!`PepE75Tt0N`m;GH0bxS}4c0lm>TQlW5uQtH;>T3;&z&v z&zI&=$g9G*@nHbvny>UwL>w-Rt!q#E$2YUp-B~dSUffz)CVB|7VUqs^@h;KX*Q$cJ zx3W{e=518Y!2RdJ0^wR2YMSnwppqk<3~hW&)DvvmT+!;Y0Zx&(Sn>X758Y{6of1acHjih0XXJ(Xu#0K= zqVopw)LSD9_ab+f+)t2~<~TKLP|PEKw2-8tv|(T34P$oU7E>kpll0YG8UQ%Xk!6}wRI$0oaxDQO?V zxGCGFn#n2Fe~cE(_DU|ni-M87ER>0$)4v)Q7}Ef0mB`o%Hy%*0(PFdPXI@i4l@cEW zk;$mHdQt^@h;Pl2pKfKHI1GwvaWmfprRMq~{F#Y9wNFx1f`I(6M=pzo8$l_k!sU%q zxwK6Aug*bdk7&L*)!*t&bJk%N404brt+fe{xgEx`9~uZJRet~C`d8SN)fmOwic3RkRJR!E3_qRA-?Ginyq=#Q3AuG_{~xYeg$S$ z$~(BdSP9(7TO8Ut5$EbMkTg^~d+_DFSFn_*Dd=KrbzqAC!m|GoWpTtLQ3fWFnetfM2M#?rrZkr4*6x zT`CM#g`#xvtDm#09hf4ks+qn-r*f<7a=Q!r8J#77mmZ3{&prATL_={h^1e?ZDnd=M zUT%^#SqF0AfKuJA-0-UoV7BoX_4STQ9NRWXH<(Y^;^4u%2vdH3laVfA=@TfeWv6@S z=}2`i#A;ZP)}8^rlpfsKo zXUz7a`~%MTLaa|I(s~W5C)TPkhK`18GwE)+!0OjUKg~6`Y8OLhWox1f%Qe81Y2ZME zn{d^vqo4i^Ksg|i!8V1_J054MTF$D-I%wl!uDpBcUNB8Qtu4uyyAp2KW5ZudMeTcD zfOVyO<$cpoRH2Iz7A?9oH^3(4H+I}=rt_H9TV#^&@vtnYEvC=r0z{o1S#;E3BG-y# zGV#BeywQR~PqDB2XZAM}i{VB08UM+VAY-@{9Qs$(xiQUZUB93~6(;}fsTUj7_DPjM zckubY`J~Y6`TeU&PNvW;%iB?zch|o|rSsl-?CQb2Ii{*L3%nDL=)ApVfzhVpf@Ur8 zbT_0G8e-Ec*J?tZ8Kgi*Ous?;4GLVMKjPT}eO8~mKbxzfmxdUO&pClpM3_9NhYJ=P zaquBHUd;QKjYTf;D?*K(v0n3OVIUsSV_Xn(+1PjVLi6$R^3qZOzEJsVrU2)yC&KDT4tD4lQY}w`Q3Vtx?M2Rp(k_c`+S>R=Hp)s_q1{ zcao=Y69JQ6U^}0{dmo8+0S%e4vZpI%&Q90Azo9DL92`jBZqwTAEjCNF1?S2}QWAsT z+O1l41sqfSHF3W^KR>@ElMX{T%)4ec7I1^x7ew}pWrnSC>`mJ6+`gEtA z`19lXYeI|2j1-(<5#C^1izYh<3fqtT&*qB{7&2|}AX016tUZiqRLi6Ix_6O$M2-Vg z>d|(`k&3=I$A7b@v;Jg)tWhbFG^T%ozW`mw&|C$AOT!@_sK0ACU{pB^t6?00ZF*91 zcopmr7aQ3e<#ATa?hwtc%80(k=8shi0I}?^Gx2A|!MjvHhv)ys#6(6SvrWOq&KqJQ zBP7!=A2M&wK#dqoD_^qz4v+OJNc&rdeDP4q{`uWp(E>|_`nli2$-3~4oXQ@BQ2ozo z`tv;$yy=Up^w#d^ZoG%LGs->3q{DngNQ{T-9IiLAyd`J@@ z6z;+Dr8dPq)vo2!xi;PLc3z=bc;QODXtGvt>=Jovi$;jiDql&`~ z;p2ZfTLP9}E@keo-9P`jC0o5Mz~0yMmsZa8jl%p=zmp3{_y#t&%D{x|egWyGqeuC( zM(wo3gdy|SP^chf(c|ocG7LhoU7{y707*AH6Aj6aSuusy?Jto-Q zZ!CDeMDcdvo4*rO#~E6r_nfsbF?+b_GliylgRD|3j9pMFBQ}kgLP_aWQ77kVFWA-z zhAa!m8XY|>xJjIrFTDR5kvuOxGw%M{b(oFydJmml3>8sFf6_uO;N`<(YNn6JTOF>bGd zt#v9CvRc`(=7GkB$mI?w z8IZ4Hdndu8R;-KE(iCC7eR%kMoI})ddU5ze!=*QcM}xZ%rcgsxobig6xzyJ)Xn{U0 zn77zkw@Fzh2>JT~yoR1H)UnhT<)t_AvXTY((uI(hy)F(&N{>6^f2ahGB%|J-#gnlY zSYx_;Q%=K1FEuBe&hxU&YkCE8~|6}zn=whcr>Id)}rS7gOnhal#xmu7{} zXhS*tor^1+Y6jU9J{iDpNMsmkkyB>epB;^w*8i(#iSI3_?F0W$&+@`72JyYHp7g>?0xwQdjDRmY0Cus?Im6hJYDn60kmc;XB9XVXuWQeELB4i z5MwM{j(9MR-m&Ntv6G1j@Sg^`Ss}pzX4XpbHz%5!8jOPbWsGxmlo@saX{=7=)3qGk z{w*9sb?41><~8G(N-m`QzG}LEti;xlHz}z;_G9;%#2<{5T{k+eI0>8I^n|KnW-OAK z0P-O{?{TB^ysTFOoFDGcq&mJ|ms~Ir$e)45(`a2XflNx2dB zpZ8gaX8D3(ES*8*KY8Xc)qv7HG^lBlRT7ILAcDB`U$|8eY_ze5y*?Rju_^?x*yLG- z2zH$zTQgw@+6#xPLi9V{*OL>zTaizY*0zT5O^~3&F2eZ>3S_-_`%tA5J|GRA)v74L zQ8Sz<_;~(~rBv0$ycKn^>7*bBQ$nZ#%ai30gYB*iK{p>~d<*{k-uSyy+xS7eQ0pI6 zcfqHYs#`F%^qaG-xmwY;ZVbWupH8a)i_DB#UnNv!Vc*!cPIkRNlSR0*W~O72cVp6w z*SL&sk9Nohd+W8KDMhR@(|Rs`i{#mc@|#?(^*}AVC5~b@QXN+2SOYeZG0wuA5L!g! zOaei@TrK+!A-A#uipP)tp@33P)|s4WIs6gw!SaAGJ2k0If^%nQnFNBGFV+I&^VTX- z1n1JiK-8ANbDZ>%ZYttS8epI8h5Q|-?|6fn_Bk;7 zu$wb+{F*MZFttOf0wMLj>XiF`u>cbJSYlhbZiRnG{vInA$_768IvMg~?ZZv#>6*-K zyt1fh31MVhwjAM*4&=Q=E+~456YgUO4$XXku{Q^fX^m z-z^c4_ev!AF0W+xk6@t|@!M*DKTs;0znhdo%TvaI$=^J{`ZkZHF4Y?Z*h`F4#3CNo>Ahf#*h8OasjL3Xr5W8oIEt@m(_H zJZknpx_B3zZ^byX&arD(F{vs(ibA=dKBi9J4Qnupp7vdy{yn>{#tuHa&2&3G(YQSO zZlinnC8$WO`g5&eBfqb2@Adk<1K-UN)H#)mQt=`koYgbV(J<{yAbxDo+URGDX zHpvrJ)q~zl*0q^5%IGo&*q|VF!>Ea3g>rS?as4{AT1gIId{b%ivAN;JXI;bkUuL)C zIPn$4VagmYJkrsFP$@wY&6Vyaq(jNvmyvpDn7qW|aB=`i;^UTKGhWw#A^FK4?#7>k zS=$UFN(uAY-}6+Fe^l z9~M>&1#dif2gk|EQN|-)>wV6*saqyuK~pY8#HJ9P?NoudT!%~rzPUZJ^Jw!!CL2wX z7YDuLVa^TJUJR)0P4L(IbB6-hg_`>!7;7m&_w5i3d=1JHoK{zIVHm(Gp=krOmU>h} zY9nea$2gr6%T=qufk}57rr~mDH&n+d@{tG=c`&9Pd6tuh-e0MsW33XbG?RSBoos4G_B>#?wtRfpnBnd=wp z#1R1jSsttNOT#lTt~Ebz}*<@%bkGOQ+GiO{&+tQxR!&+4#=S zfm>dxrjSxLR|%r&9ge+V?D|UW;wut6+opNjOX-J&lHq;NWUM;hYddG8^GDPukx0Xy zAVB$TMVlX;J3FodKl~j###sA(A-|7yYk%GbNfffQ2!q<>CN^gstGPmMhcZRqzIw&5 zvA(_zSA!>I+lJ0`QUL6Hx!$IvX(WH@U{ChVR1R>&}){r9AVH-nVa9Q zEzn5{0@(2l=HkNvN?%4tA~;d6x+OpArpj7|lyu7;gcnnku_7J?dqv*GgL}i$_ex9B zT(}=J?jM_u?t;khe=Cz>oA2@b;Y*QW8#CKf4X+xIR%E()eYz5;8s=Q)1268+6knySjNs;bO|KKFE-U}S^A!LTaVQPv`6MU&U4UVLs+K5 zjN@b`ZNyK7v1}&9)dBnHvJxy)Wj`g{5}rP}=r~pdu#_(N1#!0|?k{a?KdCYX`u~~t zABMdcyZ>D6jOLnT0*ujI1-N( zM43~)p{dKHcR;AKsRo~KpYS0^FVb<;EC>EP1WpIY=8L>CpRw1luFN-gJ8olTQs$nf z8E265QTDuTiTn!aemr1k5lf^qAr7!A^UNR_^ZcR`&T0blW&(oB&m{DIv}k16hlLJuLdB1O%uQ0=>0Ld}yM5ecSiAEj~$_UbxrO z>tGbTyDeH{imDZQi?`z~QC;=v0ga6x_=ZCFJ8d!Q9rll&Jt`z=ZCz;pH@%lw*_#tz z(-8_dOLd7&@rb}-y^ET5ZECvOoO@daTx8e_VSWATSu$=M6~Qe`vMfwLPVA(?V9a2~ zT3ystyFe!R*UnW-VMvH?SK#kGbPPiee~lC2z_8%6%q@Y6`?Zct!$ymcgwyprx2$(h z7^N2D4%EeJd4tb7peLLL3(exg%_=gPwr`%RB?)0C!gQyUs6rIt2p9|{q{}oc#ycrh z^n1w;s%s8{H%hVyz$l@T)*&8)0OY9-nMT zM*-pNg+Iz7xJRDm=}8)|0_rRV%z%dSh4T!c8!m;RhGouuLI=^DV4!~TCjG7+s^lwY z8?yl`Ptyxf1g8S&S=I3plzB|@ZBLD1vINDzSCC$LTL$1{D00i50v%15Ju_6>U;u0B zwA-buUo1kzN?7amS1rvMZ;j}tf0++#S7Z4E=zc1PeSJupYAF-SaMPt`ew;wi=p+1g z?CFd`Id1~3&lu!NkH?*cb)bT4St=+=Qg^qQM|jCRG}tnV0Dz_?{bTsD)jFYS`XT7B zz9rPBFrqRg^E!gwNTi(5r`9Mqua3Jsa-Tl=>wa;SN|i{2q^yQJ|J(n+6k;YWO=TV> z{>j=P@IT&-H^i8Zx73y)zxn@cX)~-9bj&z9Cz@*CEniR!Sy>>-C@BX+M1h!`T@@#} znv%y1ClQXE$C`Lt%lE^sAqmA!r0*Z;vnVwD@Tqrk8k~2RS1WVm&ID(S+a$eoLN#jo z1`y`79j0>1PUpeO^-__b5>w`Oz-k<5&a-U^H`|2(D$KW1M(aTh6tkQ=(9g0#sJNNm zD}9I!yvcLh9}32VI?s3PuI)BUF*dp8X1g|5*VL@9N&%^U4gK7AJLQAVYeIY`1onm6 zW^OAkz#s{RFT7H^8RRJO+6>ZKDn1~1xG%mMv9sDZ-mM%EX*?v$WL?wiM!G4ZdcxkO zTzoQ-FDRIsZXXv5DLmWzo_j&(g=MV?8%k)>LdFnuXb7hd(xm3HgZF4M*B*$Ed~KSv zx-4QznakeK6&dLm_nYCYwKo94Mx*cGJasxC%4{zSKI(vDDK;{p;Q+J0x_G+IPF@q)KWk?7 zWE%Y1ILPyzT$2QbWq?cv^RwPb<0YHyinAjh2>*GA|GA0Xx+i=XyF-?4qYk#l-`tb` zGNsFCunBp#Q~!5c_ScW4Tv1GWbDMc8ObD#?=g}D^il`ZD7Ivp*9rmLTX7j92zENtZ9v#&9Zp_WAI#y1Ftd)$s!)MX~B302W_+JR@`{3QOWwM|Va#i9;vtR*d zfv0=ctv9l5vY^|+)xr{gwq#8h0K_u$US)VFruyzST+ya`!Sh7xI`O?|OEVKDQm&b} z1UZL7sdVe6uP@(Dq3JMjmO4I1_1OSCH0=|R(0yImQ=mdK0&+4DT3F3uaPk63%BJ)j z56B2Fc&Rq~F;)ft8H?Q$S#FKaV-1ckO6Y4 zt$z?qjjjgR%N&1Sd;VKq7vgSl;oa2Nh8X239t7)Q*@AxWq@GTQ|Ksnz6y3-=x(#~u zddovNzyPIGp&U6P8+3QLtt@)lbAK|!u1#J|V!@Tv6aI-@u75Esrq<^H<=T5E;-boE zkDdf08A&X?a*rL!HJd}#MPk8v4!$3MA0fRA+XTn}6NaKeRvDHRjK6D>LI(qC?3=iB z)bX|YTPK7db7WaXL$wO93Ym8boG(aI@YUKp=dx=wPq|`vpXo!GGd(y#-hjl6PqhjW z<0)PJ-;H6R&1IjCFD(owiG~o4L&RY=48*9 z<1+1?oTNVFsKe)x6-YUGXXW?4A;G;c)}7Y8Wtnl@#6XW(JK2HK9U7g>P;MRcbT{UG zBRQeViqfb2x&+@y5LtuMXFY>Z{+ILA=Py$MI2xa(=V-YJz*r*dC-$ zbOk^m62!jaS*elWL`<^2*g))mfD(*<_nGX6&;tqY221&U9QWG|OSEjz{Z(V1ls9H6 zMC{ft*!-%M{Tp#D`>RTHn~<;VjdDO}36|lD-iD^RnBg62T>jO%?2*{K8n%jFeTHhv zML=oXm#_2K53#uWSsmy53mO%0Jc!EsQ=x60-erb(4xN(+tq9jSl?!Ba~ik5Z#nVNoF;M~sJT)*J$`W?Qp$8;gAg{}n7J zM#h3GCYMY^ohjb#(cCZIx3@hlOcir_VZg>Xq6WU7-_Ijm%E`&nwjYjp@2(_Ri5n)j zR#{~NQa$q)OvRh~L**4va;cO`yD)@rSj?_X)^s`)`bg(8(F#X!?;=4+f+3PrNC4){ zOA5$F7Nn}X2gn`iM6$&i&Th3jCbgpd6qYKKp5tfh2+zS^FY#Bp#?NcC6>0(ax;_1~ z*)*z=Wo#NcFuBKBGZ5R(+-i|=!ArRzLT&hTo!#DrZ72zs%9R!y-u}<7YfTEvH^0BP z?DNaM&}%*V%r6RKd7|dF-WMF`n~D6_p#mgUQ!MOL#h?Hy|@L^+S0 zIAlOplAzYe;cYheW<3*6PqIOFEVzO{^SS3#9hq^j*8+8A`uER0z@4hcDW2NLS<$#^ z2Xv{H+=D6t;aksVqGsthbd~38(^+M)Dc_s%yUBlS$paVZYB5$*Lef~H4vx4Z@o{1a z^DH7harYd=U-&S*F`#UGs1WjN7BsBb%gn%1k;#83!%*p;&Nx=TjV{uSmG-=j|3M6g zs|QRzj*5Qhs>vm5?-%5b(5T<4<0I7!=oh znp!Bh`)rV_e&-{G%5!e_Gx6>q7m$SI2DzI~&3=%40s}jly{^+Qkykc~I|^Wigh>5? zef=+V9+C_HFH~6m&z#7u{4Ue7&G;*?=kmkv#y7Wr0#8L+f;WboO4+>Ez%L1-;_QYm zb3?GBi3@LjwS4I95)c0I@qXns*%SC6cn-sH9!Zy7^*fKkmK4?sKCy8Les)iC6`#%Z z`1)0RXLOk$a~dh-a?3%>m*9;qM~quxaQ|DrYcMV4N5vcn*v$azX0B%5RGm@!NEO*mB3>Uxw$q)S)?C-MJvBLWep6El-8m*H8 zp$U<;BzuY*DS<{HF1%pLF*>f_PkjLde#cK@n@+vwzF21>!(8fxg$+cf{aFc0YQU$P zhu3F%0?W!eHN*jK7!+tC7VJFh?kP7)OoUZ3J8=WIY|Vo4_krl?lE$ z@Bpu`^#)&V&Hc>epWN4X%g+$!p`}?fl)XRV=KG5A|4Ij+Urd!MSFHj7ucP9ayW?5m}C75+$Bd^@>F`qjWZL93(~+BNtqQWu+r))D8*0R=Zx+&XM+d zzesi^t)K4*CPHlEB*V0SX_Fj-uPNow0%4CAN=hBoZb$oBiUP&aaf^^Ti>XyZWv0)& z84CIFU9-+MxX&M+1XkFjYZ?^R={EVsUZrSF2>oX6xre5 zg5xnNnxP(DJ*-QDaji1Wf=J1<1)(!j?^`i3LL)=R1wiuEtT)Hk2op?#Z!V5tqh;p4 zO9Wx~Id3>gQc{G2x#VNi;>#}k5}V#@x9iPblZOVP4uAD*8Dfz-!nufLK4Acm|64~J z7WqVvN{$WZy4?R^giq2tOx)DI#2W*-`Vi?pw&%As*VdMG8I0(0XXXYZ#5FvR$r-^io(??^KIpbQW8S-bO)0ih&9gebq z^J;ZNeSBLv1RKTd)iSJ!!Y`xNbso(lMT83dp#e$4b7Bu$vgQr`RA?B1Dl$4t1)q%K z!$41ZYrIO(1E1{WDw@_UAQ}%+PP|UQ52rjBarDX&Bh4x>LM;s7QfD=oRtshWT5;8s za80~^MS26WnUG&MdqG}55B6pX|9F4f#(cdP+9PWo|P`uKipXndh@T`J_)fh0rl zposQzj?@tVL<)%33kQEi>J1fHJ%l-yeI!KNiGW}RSJ)-$OU6}q+_|+mM5VNpPnw;m zvY+wV5Ha>h0$xUexdu3UDI*S@tW73AzLH*VvJ$SD{;gD_Yi9W=&V0*4n^Tr8P)gmh zC|Z4e24vrn<(B@b)s$I7&XPuuqpl9SpZYn!crZpp5hs-E2ZH8t8UwjRDmL~ z;G+|`hA<4yI?-fotyLorq&1GpqR50jd29|O7u>%f-BS(U+z756i^JCH+-rP8i5cgdd3&$f= zW1@8KunAAS8NQEsF5(NaF?%B6Iwz5BymL7DWvqta@;baZa` z=8zGH!g+CQxI(|Ms&O@lbk*i-jvI)pNyRW-zbdvK-tBSAZ)F@N>&gy{R2rbIU^d4? zdhGI5x8t9#RO9v8*(+MB#w?pYOVx}we$DR`fd6_umy=vWsMQae(IQ;x#+||`l_gyB zc!r&|?1%XNEyC=_x+Hy3HPV<4 zI2^vJD*qX8=@uz4GU`y0fOqFk4WrzB#w50iabkT0(KBz6-OFIuo^V+uXnlqW^Wv7O zBMIb{6d+I%B3$|x&QfSNoQo7{7w!|1z1h_6lj^!s*YViEDLMy-jG3yao_?(o*YEsd zjNuwn2HDWEH|XqWsMhdwbsa93c-Zba@uGnS&}i`?X;S9R`NiSw-fEq0R=N2em%{9K zY(yC&k@o|(ZxprpP_Ec2b-R?95~{ftpI4sg4-M8Vz|!X_Ay!=3wWE5->XM=~@Jl2R z=aP#@EOQ`4rU4U|-d|c+?PQzSh-bE|$*Fz z45p))^@bKBIdfo~xoLCZJRk5(Ew}%87rTJF>U7H@#NP`-$y40J9tJUxhgOSmo1p`o zmw8H6g6J)Rgl4lT>vNK7dU%8^=AJi)AS)J+xS{0wRujRt3W9r98!uTw5Z>vJTPD7r zZKGCAtR$-@4oRs+L=ZGJbMN?GQ<4gM*kc*Mh6r*e@t_SZZQTK2t9s)_8s>>2-F-DLB10Bm&1?76-4~uYIjjqPdvN0rG&WGkWHB-4K05;9qXMS$^mQC63 zjAFAiMvB`b>nms6$>=L*L@?!fs6WnkRFt`-rc`XwZ}z$o3u+ccenHi>t>0zYBuv3D z3IqSA9D&Qj6MXyR&voQpa5()~UO_c$aAb1AkHcd5H-E0s zD+_KGwQZH!Zn*%~==lVk&)yi^>vG(%5qdd=Mx(cLl||oPdh1OojgSvi)^fGf!r83F zuL7xcs-4xCHFOxz*`zFXQ*K5L`7EQ4U6{(^pn30_6Vi=Xt>I*`0?~wa0xW(=dtliM zce#Ouh(Ik;N2ji23&JqlQ*@=G=R_Bn0Xj{FPx6Ewm@Oa^dOwsKO3;(Il9v^2tJe z3kzQOEa04oK(5tRhxl!i@`QIH0{GpM?_3VMqH9tb+Fw>$WA#Df+x@QRuiF0qZ8Awm zW*BAbgVw&a_gT>t!_Q+@H}O)Dk1tfSL?*`)71T$j-rS67|2<(Z4Egrcu%;oO5r;*a;(5Wx9c-1x$$}|m`!H_p{{MGwg4I> zzy{vS8f|?A$j-3QBFzHmZsWva90O@P(os&RBz${N#i?;3mutv8K;r)Wj|^ z>`)I+2X@ZJ#&U zwpJxd%Bgn5o-nK;-#xebrA$dPv(i<|IIzkt4bmEt7Z^!!H(4aBMw4+e4c)56BI@1r z*#)nIS-`N#eR4>cc&w71v!+IbM%6A6U7c;SYZvqc-(wW9kU!s+S}+U6 z#JTGAMCTrMHLRyA@c#Vr_~+p+#trQ4)i*VNFzMwd&=ZD$`oujL$|khEY3Cf&m|L6a zRa2Oe-U*VJ8W*hOpR`P8Pm!sZgJqt}`FUFItFe~OX6u2ofH)~7exHYr#HYg7K^ zR)6lMcJ+{@hJ>nu3?Ssei|h2It&&yq{AZoT_C;*$I?H>=-9KkA8~8q^!{zc317 z`1|+j!wLXF`dBBZ(KG|EgY6a3$2Zf1EF%`8F`%#2NXL?C*YSkr(g%#j!cSd_8C|(= z(2yE+B|+zB3qfUsb!SwcE(=ML>)mi|eBYAgh$@^0Rk~M$`OclR@lWxEDY2!!Ro|AA zY-Ipx=?#Ui{(nsTS|0AyWo>PwviI4W&Z3`p_`qKucIvl?Z~@hDWNPngEWS)ksp@gJ zzThiS*}Jpa;J+s^r+<#$T-kTLWw=H=HI~JPMeZQ7voYpu&7KIP^^zW-(zI+e&GkwI z#Qd>Az~<4j%-)1ZMkQSrjYJVvy(;WjZ_+5+mf=Mb0s$Fz0yE&!a>Zf!3MG*SwDppA zX04Y*)`{hH%OOt?Tp^bekBu}8K`0>a_^Wy_wI9S=Dk!U>PmbiM$Ag511HBj|v-zEJ zYvzkbNgPo41jEN>J$e>gM63@hHan;7UB_SOvR46sdf%>`(bj%`VmL{v2f`k3m=vMohBLxvTI4^9jfayi|0D=hsq7QyAC!}H-_AtkUsXh%`-jSxL;@Y z^}Syab;Im6!7_!~mHJ8*ooxmgT%KoP@86GOc+Spl&d`z=FYwLP8O|`ffNi$8J>JxU zp53EgcFl7Hi|kVgE;nXxgg^CqdX=NTOhb4NWLQV!tf@ zC!ER}4~Hl=UHAHS7HXxS{4B?U_0t+$L|uBR8mShIBykdk#i|XO;X2FRS+dbQKAH#? zjB?*h@v_gJp295FbeFPRi;J^bM`cW7TsrNf;R~Kn<3k`CcpaZb$ZMtG1XGmBmciVUu5+pG|#ODJOi+m@(E2SVF4e2E`EvVU6RM@mmmsfCB%K3-mN&H@=qJ3i{k z=@DeRTu7#zGH=Tzbgb7seOB6Mx4Gu;DzP}?0B@zM5f0F5`Xk>zV;%{@bG)l5sgf{< z($btDW#6d(5AqO*nfMo+wM-{;XA@$+!^=mFz09WoDa6Fmo$u!IzquOP_*MB~ZN2Mu zU6}zxfqm{)AQkNCls^~8h#Mc|FemEkYwE@|@P}7;yQUPUFd~VdVi#Yc>;3y}wU^6K zR*YOFCPos@+jg4deu4;Gc`RLT&Da;w94)q^bFeXy>W`<(C-z$u7|DJJusz4!pIN%4 z?ETzlX=L&t-z_L<+KBLx<+o$A?{-{lq4p?o?>IR=o74IhY98wGyaH-afN(1S+?p+4 z1P5dXV(B>FuRVW@RW5~yr(Bopx`xDYO5u#fNh%C7vnAj6y%mQFsdh6(YZT3^eB0o6 z+owaS`bJ}A29tf8MK9m704u0e=Zz5ueWxUjaB{EJCt<5n-MSbMW1mJw^U_;l>N(Z7 zZGFH!#?JeW*|cp>b63aNSZ%90qIk5kmf8xF;#-A@sGUXZ@y~-~x*lPH)~?MVlcM&8 zArgg{v`zzGQ%+H|5K=~38befnW)nDT>q9L9s)GA53X>d~o~F@46W?RVXcMLab7h3l zYv|VMSQWy6+8@s;6^&*pBGXts6UZNEl-?&xPQfH+2?nQ7M)z(KWtsQ zdWw@P2#Fg1a3AysBgQZq+Qr@!2AU6Xn8&m8BMnpCC8fl_j{Ig5YOF6`JPgIK@AzjI zWNTRNc}tAX3T2AmOGW+sf&n*0-n@FpL}4ANmtTh6ozePA8SCi}W;?*gcXxCwpgO<<>Oy_B zUTxJeJwt4Hu5sXaz%av%k43b0nJxvZMV)Z2SAbN}HZv4PA>}hGaeBhX(_3U7|CCP- z>aF!bO_x5q1u0J2)AaN5Pi$RYO&r2 zNjKMH=6~)!!KnBYM|ECajDab+X99AQj*D2&J#pLU;|%s9eGGeGV<8L0&vl;1YC_FF ziS2MZts;7M%tn?2;okv#h(`Z^=a)^0{JsQ<`G@i;37`YG7HyWTwN+UnC~;l-$Vf!2e*k#4W=zPEV!Aflqj=XqIsJ1m8G#o%S6HwV7kA=(g)gtB*1P zIaiPnv)l0ixz@7@>@sv2!%(lJk()_<*~yKwg8J0u`Q_MNkGqX>085vxL8vT%>K3K* zk7f!bLZcs#Tdpw5?h3oM%-?S%pdvknBe6q>!A;{K`ZpXmdHSCg4ZuzqC<=2Y?^a8RkhHJXchJ zC1=rVem}DK1QW)MCg!1eUMOAFTZd;(+O6?;D@n}KaMp?l`Pcp$QC0l2v68=_ zKT6}vLQI`#^N(*NLv0qI`QB(B;Ll~w*yA_qk&0-%Yz&K{HVsZOC+XPaz?@ZR@HZ)0 zQVUUXS(k7Kw(bspb@!s);E|GfRJvT9zHz35v5d_`_~+Ue=i}O6)39t}fw1UNenNa( z=lUpZ`iERiJrueYhFzyZV*m98W6}{Hl<)16nqz`f#wYl{92EYZdxP!%^HfHnB!1+V zXj+HSb;U#ZpxYL=kekxK_ik^_m)Hw~_WA$ZO#c0G|HjYD%L#5h9E|FsSIVir7jh;T z^u|eG9w_r5?g^`NR$wfQY=78JP}lX*5T z?qXE*HH|L{59fIVF;Qui+43y7^`=x3fyi_q7^=$pe)7S`y4WMS``z#P?QpKlU|T#A zo5;FBP1xlwp$8>tUX~N-6Y`aS4mj6vuf+I`jaN4f)h9`4xpDjtcLvgi9Hf$WqSedb z*;A!5Zt_x@XC6?b29F3#H!<@4O#2L`?mS*b;{o}?+>18C7dYO-6v{mxQC0h3JX0bR zN}ome=n00CzR#GMQii6uY|kHUKX;OoVBcLG7gvT?0(fFXIK4&I!!;*lK$o;-IEaGr zagZ!`2AryNP6lh;g<_qF3zes_r(*(EuGjy_ep~a+quBlZ=*KC_Wuv!u{h8VB(-X0z z^|BR#xO8h=O(9aESmCBzhuJKn6ieufrZA;`92HVLJm^l6q}b=n;mhWZg$}gT2U)nA zbR)L%imA+La?fjfxczl@wz(if!T!B>Yc9H8Q&W>R(V$*;9M9(%XEdqy$!YfupWS$3 z&#kP^_T}np7vFm|L^r5tJyqO&87WJh;YF{g>S+O=FiI2{dr6%Q;`My0wAX!aq0SIAsSw`9Pj2?r9VYBBhE1FI{hpz+AsYz+b_)%U05hjd~E| z`LyJ)TRbKHiHB5bpiOcS6kqBzui&kK_`%d6-muEMmEAxtaW+OJ!YIbf83V5L3C^({ z3ABcuC!s2zHghZ;JGJ6ILM-MWS$SSX!>WWuHD&G9zQ4uCpIqf8woh}{nB3_aNvfQy zQq3N!GvRB{i?FJZ*%;K$F-fq*o_V@*CiyNt57#R;sHqdlMKgJdXcg;>iZ)QiLr#)d zV}#G~<+VPNBlQY03bw_8NIJSRPX@fe1^nkqsFxi}yJwP~&piuRVp(*_X1V-r%U2E2 z{=U3qHYqLm-Ge{FrRvKVJxVy@JTo6D8y54aHYD?@_VkbYcK6FR6+=1Gx%~Uo#h;O>xGz4ZQzm4sgw~2}fmK_L zc%>S3s-X$7QX}dqqd##x%Bb*k({}!Ns97A)PK*(Re{~lFPx0aRwA>CZeG}2$$uFe_ zknbY1z~TK%-xJu$SXHa_mRv>bV`P%Vl4cxQ38TXIyCx>IbSWUiY332`*&I&Z-7oSB zNLx&J(CGSlS657MG;LelwwU}7cN*aolS#cuS4`;~{LtYvISV`(9v(hN`y>^dQulr}fl&=TK}n`xC+?H!d4--Vyy<3R9YrD4g3MB`{eaXXwURXL1NFI39UcFRt|SXX zqj^flvx%d7sS$lcSp*%WYhNLRxKH2+0SxM+V`{g>NmW@m_y3!FNhQKsX~Wi$NKdS zNv!xj(rys1fEuDo9~k==lhK2PRhjNZs^=lZQePnX+?DK_&o^lL z-~UdAj7zu~Si2`w-a1|EEyTx0%l*4lMCiWBOZ3GG)Lj1k`zKZ4$R>+CYYf^b@~72im%nq=J#AB5eIk90&WtRdRWzDc>afxEPb%PaeE&`mhdDvr!Blyz&lrJ;CsPa`a7BWg{cXq5 z(b0#M_l1ZG%>o)aIzJiN)xO{jN1>c18}`S=xH*M|rePxWzqEAC zU{MWmKV9p{-wFZPKp+q7?8;qT>r+?`y}RGNL!_lm?NSXhcrM?m>n{MReXE%tBqs`JD=fTWbv)Vq6o=00;U zaG8Pg-B{nh7Z=T9KM_S{ZeQmseE0Lkze$iSsoLYiBl`ECNos$4+keFKXR0zwo_A#m zOYrsDL`FsiDRT-AZUmyLyc|L?35(22_2Q6~73Je&;^Z_g*75fC77`YIDzO4A`K(4^ zi;YE71J+IZ%O-&V`PYL3>qMT}pf=rI*4kn92E+_9L4yd=a7L9Bgw4O1M^Av6KXLSm z)VyA(E7tn`5_Rh4dXW8>XB4;_Om%-fy{=i0Kdk1_VEEPs`tQ+b>Gj3M7rrNU>+3S- zWR{k)3o>4w&Cbrw5)u-#PM1G6n^aYqcVU)6O|R$cx`u|LFeCc%butDFo^IQHnOnT97b<^`~9as;V|{#x|_ehDs=XRVf$tLxB^LnQsL$&8y^Yt;NaiH zvfrNIkBQ@tKQls-_7D--ma{xO8|i22vNSY)%LoijS7I`?L@#gb^BJrmoaT5os1IGB865f0z7(qc|N>~Ea*$%cG$$k$rgAYxT@a(0eS{O zlsk@)h-l&X65g^z>2~OS*V=j^W4U{LynlQgME6{phnrhJWOaG@===8-`-a)+X)_p1 z+sM4fhEyTo@s#tdSxUex|^DcKTM)%Fb|9AlUWG2w}1HH z0Xr)zIVtkxK;)QdyGvbt{Zj&hPp}7A?k{6YB4}(<25DN1c%&wMOeA7eDyQ1o+QwM- z0VDbEnSTCTv9HEqaRmq$0+F;51|h=<2zVainp8D0v2d)#y|2*jLxmAeA=~xnmDi|j z@qFg1bJ_J*PJ-l9N#^(T{s#r(ph~y(_U$`oZ9$OLo3$(#k(DMJ<)b5~Z?7ds&ZyKY z7hU~SFztD{W6y0KYO$)onMJucfH1}H5ZZNow1qTo*sn5 zc!uWM!j<7%ZBx_c{poc@d1AhxT_+>{?yemGaK8(C7*YJe!q9WcstZSbL2#JH%e6>{ zL+iH{0nUc&WUpIXNRvHg8_{9WWl>7u7#?TP_+SQO7wAN|oDvuHFW{i6CEi)7I697bBKruaU;$_}eh|wD-RK&($+hQkYRz zVOEyQi(e(`^fs6whksin@N8#Q)w8!BsSd(O50iR>V=j73hTi<|-p`-a#>dr5OQJ9R z(%-)2x2dZhVl>1wAy1l(3t?%sS)?vg`*^Ie!u?36>rm;zg z9vMVs3rqUjdP1QTq-(w#!OEUVgM)*DN(otr|L7ZEGcnts3!sR$_u3g7volGwnV_#N z0{(A10DeYu(@C-oEsThVPcDqy5AD;xKTd*xy}$XbH?98qbCsJWq}M3=ZN0a&s;b}R zm0)geO)a;xQ;m4i%;AOS3zj%*0|R&=lZjhE@48c4ds`bBa%|QJ3jJzANlQxw0OTXj zW~NGGo;`b(lZ*E8X)7;h1=|V*#6(5e!|5GdTn-KnIJmfY`1zj+01wODDrXMSdlh@| zmLcoI7HtEC0Yr54-S)`awvLWmv?hiPKVs_OIc*#=_Mcc)q9d;%@8?7f?+Z>|U05^dBWBG-UL$D`5k0*%hFfs5I5kF8~m_bczUQ`?w!Q1L-nY zD0aTPFmg3`J>tBVw15&5vyWFRKk`qE`+szO1yoc`_&55hC`t*^A&np<(xs%dbc29& zcY}cfQqr-6bayPZAkrWp-Ai|~bnJek_`c`=)jb>zv3vL4nYr^kzj$WSYmhy?V0Qv; z8$B@JV2d~_wl}wkKW7z+Sv&)Oj2bHj(aXr&I<@6qjLh=Z1mfTz>=D5VrEn71Td;_m ziYh3OUM}8w?@jw>%v5IlFXQ9xwdEJm5)u*+xljQ&fCk~_hbg=c-6=x#x>gJdNxHgZ zn##($nwpQlq|0Ps-M=4qBIvLXogsw{7CRS)^lmJhkcs#jiHi?Q&$4oJ7nhY8uJ&zz z_*S!3&g^A3x4J6gbN-V?3Tt(R;?XUt=g*&VabXV8-$bkVCs)5)mOu|+>s#5Ljg)lK5)U4#oO3}7+8hLnpBIWT@QPJ7e z_G)oKn8~I3FWv={oJ7&r5J}^~&IrSKTwUmc9x8tA#NG*X&fXQ%g2h#2&;8>1^9Qs0 zk;I%1;~*uTqkf-cg>zWznN}RW^U{&BcvLHE@!72k1Unh0+S#wLI?=D4{Cl zXXr#^U{=z*GSL|xv6CGe$?BM@MUeBMkqg|F_$PC)Zn$WXV(SOkg+D^LElXEJi z^qv`TI#1P%lHP9mgG$T8|4#XR`;c*9xtcEyVx}{5L{zsXJ+g-TFE)Coqq1BuU4egv z(_LLh`etnb=YM|c=Q~iQ0WR^1A_~C_5~2UvoXE%%AP^K^oY`A&#)&Me+$G%@&=i{nJmdx_%u81H#EA8_wBlB`belpj3T4~;k9dE4z!4lOxhu?Sv zB-R*aLB$B2FK`67h4TW*-D)vHAwf8Qv`cArIW<2${c}OxqIQ-7(g@lvu+CJ5LGJUs;zIU`9^`(PlptG(YzmiG}>q-c!kr5v&;Gd2gpIhyE#vo9l2cL6u8AByA zUNhc$`St!K9~qVsJ~>uEo6(b}Ox?oHYu(JOfJWvu|8rYA(lI6cG0MN;chBuS$=$Mj zf)0m}_*NoZ4kI%Dz8aqQgbG|;o)t>&Ht!QChS1XE;&M2{NvLxkeBUk^8XPPK`(b=+ z{-(<0rPtC&N%Bdw8R4y|srmBdOHuEexYrNMyRZ7>_lLU1^jaHSsgU-I@xiW3fIup zEjQnP7}e#!iSzrW`~FE&c)eTzSOu55N5bH%*?90$UzVC0bm*UuYsz;_QrX<0L&{_0 zY2LQmFV=&8B1zVdOCudgD@`p)RwF{OPf#Ng#zAkU!!QxHh>y{Rrh-v;wlpLW9M^z6 zCl!iyb9SEgSRDkvC*|huHMD4`svZs+7_^(*`qS*)*dyR`g_|(2DWd4v@_M_u{j~UM zV99Uo7ihwT)d$8{MuYv%5L(uQJ#0$MOY3YKI>SHQvx?AdO4jAJ9)BS&*iRa&Pa_#pv%CWN_~FAHV3bM^ zkWblqfD!!Vi?B}pPMH*CL@EI23dzq#dfxEbZL=^j_4W43lSUCx5UglxYN@GdY7UQ% z0)p@6&C95$$V%<)?`-QkFC>AhHgwbC#f$Gt(s+7`n;V-I71*ErZ{=iXKG-Qp^kA38 zC$BK=yFB|xLp?Soh6h^7-u~c@kFGVysTgsC(lvE;m9^AH;PB$tj190*X_`pz{c2k` zGLzExvMjI5`$$bAMMj79aeKUS-qKl=v(GZGLY^v?uBz~}XQD;wyOXdBjWOLt?Hc2b zFbkEOVx1;<)!WTcoBF1U;_Ph6Eaj}s%%?h@Ig%Mv=^FYzTu+{Ky?y3`y29p$u+Y=5 z^aWGKm-fUCUXVl6~hBKU~lbRr6h z<5T1C^`rB?zCJE1VZN^s0|NuNxD>wIE@NSoJPL4RUsexAjo%qmz-?uTOsQZbLq%n` zX3@1sz20#--_C7^HXS?}I0Ie<>gsB0O_$xwY^b9wDE!<^-xvA2@4Sw;03jAGtnYJq z>Od{?>Xl}LyV6_nTgXQA-y^Jsh*3l}HOifto&B}%-10IVBfeo%Lmp5(rrfs1OARw7 ztO3@oJ#T0s(=dq90^?x~uJGIrzD<8XNWP*l(eu-&XnBYisuma^>wK zay2_iYS*BjrHpwL?EY@>AT5n5T==QF zf%3)2WQ}dYV4>vXoR zJ-sW49qj0A)!?aiBXX*=kKA1w$@KP!!bHKN+B43bnyrqJOyA{ZaiDj0V@P! zXAF#Agk@z`9*#7@Tw9LDX5D6YCnqO`FV`~S^v^fJ+3;|2_YVvV>g>+0`h_k+1bH3y z7bLKYPQikQoEKzCH4cl}y*kyG$8awi>K~lg6yA%yJgL4LU8kp~jkcnE?XLjT3K{s7 z$X{02;JuSHQQV)D6n!|GiuEeQL9jpGiR4u~QHO(o+xGF%5wVbGCAx0#KjL3MeES+T zT3TBA{oT6`3cvKsOj-_(2#({UmEI}nEWH z=X0Xh+}sQz;bht3R8!M2RM;!xa=nXT))Rp#A|gV)!5K=I4!V1Jbu}j|%VxZE;O(3lF(M16lz6Fq(K$y%f@h-~Ettl#EVdbW$LCi@{IleDZrv4=QGDk30J?-^_ z(qvlcp=^0Qn5n#if`X+b6Ryo{<5i?=c8}fsGuJK6v-iz!h=lm7E}qt}pX2Nz2e`VkQk;;KqY5eW%rTbznLB297n{3U?b z3+`{S_aUU0Pjv61i|b6apRCL~yM1=Goyx)OF__)-o=sZ9=sZ;IoA1@yYllk2;?51F@-DQ;+p5}0m1Hn3w_GEI=?#~q}w2&#PMg*sfIUQ zHoDE~sj2Fc5t2Gh70KS25nBC$j((Z9a$B5M<{_@lMBNdhze%&&+CtabT0)|&o>`-+ zx{_6^eB9dB_bQa<_mBefFHk(ehuyewW5#XJjO}3@a!|9jzi+;U&$a#vc@al?`1`qn zjj)UeNl;NWgRcX+86S@qFWw1GJ{M-~Gb)RYj+K;>0^^6Gkf3M4xC4t^xKNqN=ju|D zmcG-N)P;ZM)WKNs`~bN}#$#*EkDEYpkzCnlSw%qbo4Wk|{T+PF31kcQuV1H5sO#zJ zS!hjwY4hjGii$|yrs;fQr(_Diiw$#!o73n4oF@=evzu)F!GlB_i7vso=1s_ z!Vz(rPh*irx6O80q|>R!y?Q)?*Uo>ENr8;0V0c5vPVaKp4gSa-c|2u%b=gyrtpG_h z&@?a8Mqd7K+HI(CTrHjfyPr+qzz7s4$tCgIy1TnUSSH8EkB>s`JS8A>T^}KP|1=UQ=1QSAoI7LPbJyDS|;D*8y6OE5Q<>H>xF^)6?ZP z|7Ll4c|m>wo%8{iwVpc|oxIGLa`Uz-(UDwuUJE8uU6ZNvko2G%o;_LAd*eN(pTSIOcU5$$(zXd#J&}7A84ZccdCjyCfNf`P&dB=Y_~02xS5nU@mLg)rmzI~8 zHy10mA=@r4M~+1&Ly<8)x#fd=qy+_|UVf2LQ45QUPt~o|)J9TZUJUYyYnzKSC5g{G zA{oDIlatf6(Rm&3By+o1p5Pf)Okllzn;AkfV)n|XdeU)p{m7F~Q)Jz(*Ql)1SR0*y z6c3M>xOQ>M&JCor?p+HMR@kdcnK|LoGBS~=qoX4!GQ`h{)UB#C^%M*8^Y6e~N=tvG z`kr@LR=Fw`e#Q(o4FSnqt*7rY;gXc3Bv|l&Pf%o!4OMD5Ff$v*p$@Wb)Y>)Qbhs+$ z@`;FmT<`VkHBW5=gW0#-QW6r~ZUP6PKF|xw;{FRtaC~fj?T~J?5&b0RYs_9qgsyi% zKOBAMDK|H_NYmV4tH9P&$mgc5*K;j6Y^5OUnMpcb31Om zA=877j*gl?VOF)Qf)1>8OPzPh1qHq`dWfsXZwEiL7&_jXxd01M73-kRR1}e2sAyRg z?4)+Aq>YrI>4t{U(dzY~>;pkcVq7I1ow$ey4yTn6m7rIiDtW-FlwVQdgi|6fLxStq zP2MqVSp_&=q6asSNE@4NIy$;WJwtzm92#miwvun(zk|F&T}?yEjZ{uUO>G7aPXSQw z>Ib}LeRDiMJ~I>7tboOgkcI#kS4l;MhVbJiTd!dVM>`0r)YQ~O$qfZ#NfQ;bsJVYW zz7#1gV2YJ}{pO9dbkK;UTApgX+b#f0qyW}QyAcr**4tj4(@2Gfk?@u0<*ip#ZGzqc z(8T9xuWt2W-;VtF)r^~Vk?G~>zBsuzq3s_&+^i)a#a&({+!Lh4rC=2qv8;;ggYa0b{1g$q>`W2zT5kS4!ih1^y{x5<5lwr|6myU(9nfM3o%+KR z@i{Dr19@B5x{x-d0kSciry>kiBU<^HAX<{ZVOO`_4xRNdJG;WpRm~sB0Lbp@_#a|o zh8aUk%Z*T;>AmBr-Er$`G(XfCVs&hI_3d=ZbbME~mYzMpA`grsCQ@$|v+ z$<=N}KXU(^6x>)^TG|QRsXtR1Pw~8Yr8gOpYOwdSqCZbHU&Fwo_T&zK@=jh(%H>{0 zc&hJ;RzM3bCFRLdD$-rshv?5^JxA@FvQRWWJ`T#pw!jFP1&h1oDd)9kX0hluylRZV zyJa|0o|WoT?RpVLKBmiw`n*|UP_q~72G=_S$r6~zP=_51b-QNB5e+M@M4MS_gNhYA z56OlpyQZRkw=I$+M!;e%d{#vj)x?k2?`j_}YmknXpr*&h+~!%JazrSEW-ahZgD7%^ zObb|&luzYn;c*+e@8>)4ZEUvm%?&9EUf!~%?UGtkF{Q#N@!9_Vd3$_(0>By? z7^L3NA2fePE*Kxf&CkWo{_Cw}zFjUh#slSok!|wr+772sNn?BaU*GLK562x0D0kuO z^LggaAf%)u|J=OfA_)bkGdK5nLL$9<2t)dpFET;WV2Ckgl~)W!8oYkYh)+dDC9bNf zs;jNeZ?o~dN_)hoFkRP2H-*W;-i8mGDC*YBc<_|@_=ss~CG?s)Ia5(f5XQ(nqM%4g zOr#D1jy|8AZmvZtT#$5~s24d4g@y!bUhPXA7*kTFN>QG*-MZ_v@-voF@G?Ne*&ro8 ze$Dd{uAbL+Nu5+(@s`Cqa^xyZ&Bu2*H#fI~(yOpTG)AWC?fwE?FyRTjvBS5x{&;e; z7^d!9IJ6FS$K2H`02#+g|JEh-ty_YJbN|5HNbxuuPTK#(Xf)@Ief5(IJhNN&BWfB3 zE@~%qpthhHjfbjBTDo8G$~jdamET0>WdAcDH2i$$&yaBQo#|SqddY3fXrDbt3y;;g zR;sZa3-D|&)=Oy5tYdy2LmuaE=4oft?z%N0-dXMAn<;GVbTbzN^PtsOQ9(fgK-no= zR@vS$2Omn^`r+Zi=i|0e^joI}AWy<$kXzfIyz%$x=HO_dqbC<|ZK$YF!MO!`wkwK0 zCDRfpsHHFbCRiAvH)bRb{w!jT=04WAv*Y-zh@XW7`l zrv^G*1uRuZ2ogm|hwyD3H_NNtyKc7}!Y8^OXC|rM=XtAKTLG|ok%@g%-8vrJM-k-)YJdZt!zihV z`d;q4_R4WT@C|6}Cuh{By!97;}coi!dAn(iT3W zX9?8QG+%A5%9Ym@e0MiS|y|!@A)S2|?_j@O)j*&iC)k zCk$VV#PoVg<9W$`+sA$%ym}O*cI%k>aADu&EV>rsMc%_1N8^yP@<<~}1HX)csgIB@ z2Qpmxf$O{wjrRhdV!FC>%`oN>0|vtB)7CVrI>d zVp=n0HHN8b#B#*ah4;v|xFSO=WAyQtYtooVRFDt8;352ssV-xtsj;y*yKd4Dy69bx z9kzJu(~q9HN91^m%O;0g?HC_^^z@ipTJIrfiWFqyJBH*r3fhdGaebB&mx&B)xo$mn zRYt+aPy8^TlYdY6eE*C~g((ycw+zkh8vZq|8UD{g3U8Q7zN+DT1V5~K{sjrvpSx#w z-l=!E3pn(!#Y0b6TpVHA!z2M?;5K;s*Ptf`Y<%w!;`l(``O5R>Eokp59soJ<9mI2c z7qz!_r`Ub%Ws=FCfAKo~mTacSekO4CPkC)mR&5G4k@vCv`Crl_L9FX51;0MfOPTfR z86JNfpQ>SCU{y0GOEgxXio7-90wVkAl0e#Qt7h2}FelN6e~oY&W8lgP=!Gn<@Y zH)`!P+J1g&;r&mQ{BeF{`c1`9C=d((H{}fqV-om(NN;FF53j|meCwxSGU{&Hg(36e z^=!dyD}?D!_*|dMrOxHq;7dqZSrwF|HmMi15WAUq!rrf*eLmM_D{=o<0T%nz(XPV{ zDJq&N929qTu3UUx&m*0sq*IiP70_a=!zj%S88N_n7qyM7)Go>^d(X~|`{$P4tnH1v z2QTur2ND^t)i1+|I8tbo@P#hqINI+!a z+i~A5_P5|VAw*PglAA;v?d%%lfB*5|$5}8`-{VM4M5M_?HZCO$lSopyS17uxmCb?{uSTfSh%t!Q(dY5NSQP6UZ@IYtF zMXo4{10G4$=S#jYqSUutko)ZwU zbpDlF(9SmNa@vx<@iX^(1Y&U45*mNM;8~!#<$=5fN1Uzjo}!A*QT%w1Z9KBIn+3bt zC9%C-Z(?wu#&oQLN5Ri%xKs=MJ`dhN5{K*w`Bml61f9Q^n1 z-;3iD5%GGDmkN0u1C-HIu%lbIRcn@dW_l3@^EwG57dUong1P-ab&2(|7U0Y)^4t{( z7e25zGNQ({ftQ;i4~Zb@8a~L%e6%UJWr6 zZYB;#&8Y{C)amW9-8fA(`}Yv{nXqvj)*Uo1?Y;GUmleeidz)i8s4Oy!S9XLBEWWup z>$io6NYilzhg6?~vJhLFSGAu4G_Lmxxfi9IZl5?E3 zH#H zIJU<}YV^y&j)Hel^g)pq2A>@7PR!1UM|D+t_9iAJ(GUc;b#ySWa=Ug#wly|3ik;|m z5cTx*h$txmj2Cs(fseX< z3021@NgJ063J>_J%4P-^JSS}}2;8$IEq>+0f^s|Z1HZp*&n>6&bMK6&q4P2l>sU!S zHSF#rm9@m$9ELYFZpgQrn;oOyjzOQkL_5^bMuH9k)R$Y+MGW_3psil#hf)L*-r7LdfGrfYw}_mZn;VW+A_%4vxWK{XdBzvS5gQeS zM}$K}NtmO`1Qf*+l=GY8!UWjGt3MtJ;5MXHcmfC1tnXn&Ku|6WM#IB)0{XncYGN=? zC8yg;Dksd<=1GSdFtQGhkLSK-1ggQqhYxkFNJ&VL$Z$Wo#ODsyo^=hGUDmd?wn+D* z4X#vgYPK@Xr)G2wYa1}STBlu>v6oS(u_GnEg*uTKCpPKGC9+o=qm1o=96{1gY21cJ zqT*%+PzEM0QVPT5slux(Y6d9Zi5Nef`U^TG$EQhG!;sWj8#m3F!@IAP{a{dQZXF=M z0+5!Kor$C5>|D9I;ITZS5fvHvQ+{P;)~CZkw>wt}NUxC11wODRHcI$nt2GG2F2iAT zOKS|dp>co&p27_-tK(f1U}@Sr+GadABRe}^ozV%n?VKMJl*rMmh>N$%17dn-Qb$>t zgp!i*;X^s`CmE6>VJ>5N!#GgP!JLUU#C=P+4i1CS#M$`Tp+ekQy=fnir8+A?`R}i0|Ej8w%7y8d{uRIk#^Nazn{l`79r|~ zgD!BE7x;PEtPcuwWM-+Ut2ZLsAs8>?Mf`+uVc8RTC_K z#4?;rsLpXDA4p>INxW&*#XBOXvt2$*YcH?*8C&c%?j-id?BCy7Zj=Fee`|Ghm7o6o z`y1(ufJweMJ9C-+X<79Ux6bx&-rZ)+-qt`T{qR;=zgmEkiOel|COtFBCX=13No9I^M9WCgtvJw!dLd@@N4D)q`m7L7Y>u!{D4pE*?rR zY4j8WZs({&zKAPXTjp79TA#P&e~s=w|FBac9~i%ug%Gg!=8TGO754y(BpW47aT^%5 zp0lx_zF(b;jf{xw&4~eUVxgv{cA^GC#u%F>4jCC4V4|!i2JsjamR48s2D0T16hVc; zN(eEiwCd{Wsxa-HzM7$+&d<&51Oc|UWH&4@a1Vi~KdRONM+G)HbvjTyvcbyq%P|_K z7Z(f+bb3v1n)%MVC#<>8O+FW>=M|~T?)DDPR7XIenqJ3E0x6Kq-QC^I&5yIsu44wM zvRB?^QNov}$HR4Tb)^vT_3lp*($I4;N!7V?`%Y|hv}TbyfV9A>GCkc8K_hiMZaR?u z3CKi1vg`*`M#$>f8KOkL-ZdE-?l!qLfEAFDS@~S>sUW@SDKU4*DzDMOSCJFSBu3P3 zKcx$*3=?Xwzj{v^ai95Fx|n2GSn^RD+>gCIa2#n&nw>RmZkfkXr5Y;RFrAC&|2ehc znI`(Wm(;C8;{yJWE}*tbKU$np>?>msNmgT7?Vu0#ZR6I!-JD8qclU7vONLJ6S6#FDMXDiu4LebJ`T-v<;ngUBO)B?c<|Kz33-n z?9kDhsR>*Yw}GF}_@(lh&L@>Yt1Ee|;i#R6bl5@uu2bV{jKl)^nGB^(D|r)2JFnur z-Ceo=AiAjt96Y$zw?BCl@`GDaQJW`q3>xT!YnR>UU)TU$ZMM6CAv zZS8m9;XO3%OOkdJDrdz~qNO&`2+twrG}GnuL$Z~iM>2a0p{6TlI`}r6`KgUU_GjwC zpTvA|8rBSzlotmTnOy0=EGzQ8Fgw+(hSdvtkA^2!Ww)n8I9z!da`N&lHlo3VOCs|2 zx(V$$1kQvmf#9MK#LTOrtA4M7I+3IOeUHNksXDdcQ6|BTHzG8!T2ryTB|6FO2xJ0echovXS1a2+l# zu30~nn67tHNl8hs3jkmx}{K?kLy1toRoXN3A- zcNEmmWC5unb-nEVC*8~? zwo}KwHT#Psq$Hyy27Wt}0)nRQzAxV^lyI&cWo4Ow?17*EOCX7S_DA%JLCGAT;C&7V zSY0M0EiBw3S9n23&Cv38ONaPC=iQd)jn)ye(&HQk=L+6@I~Z! z|3`~Q7;TwBc#dIYSGN7Y`$9}WkeC!LE-r8CWNb`>yM2K~AHxcjTnv%TUKG7fo8ARS z0bmJO&XOZXP4}=xT3p-X+Ep9MQG^KlByO$?*r6`SxDpm?T3h|W7d#Z^3>O?z0nUwj zYwtHNzF!uU{4n`T-OMcjeraIJ%-vmC1#vHHfOQhru6Ca;ccsv@w=~c_qojYmF?PQ7 z-yH7{U}+4@`?6sa7iYy=kF(UX7Rk7!#VJ{#KXCgalv&0Fv{Za9DseOZx%tsv^)IHF za|WDK7LU7xKV~Y=dVBB1sQ>5NPeKV|B!2+DK+Y&V843XeQFcK#%a;e?93(IY&Hvu{ zM6kvtVxYzSREb^r;_&|AnQ$iL6=C zWH?R{&zxM#?N&sCa#po=k#-T5R7BZI?NdwU4bn$L|ii;Zn8STWt zdtqJM5G|HudKKdruS;ozc**|0^wUl7$|S$uXqgNsR6E1s8P{{}(ZzQ)z>FNtq^9Yf zsbFW%%N~0T_}{EeyDj3NC87U@>Yi+DYzw?(m?v%VjMAOe*XR3809c9DAjU80fmC+( zp03-I%guJz>X5zq?;2Qp15UF(LAzZru8R?uuDnfu-e<4w?%QBuY0dbvzo4W9)MWF{ z{vR&v2k6%{92(l4j+VtDF)ei29!D$w`=p5lll;A6W%mTx*0}V`aGw}QnGzi#DV!{6 zrOT(bSLlb*euiv({WZ+7{^9Z5{lAPVT24>YV$s&mkRNyfPTg)7x7Mkns`x+lzqbBF z%TeE^Z{T(bV>{6oKgbanSg1-T9W`Ghv|j%>bUG^z(l4vXWx4HN=~6q zI9|)ZfRKpDf0y>U`OuOG{x6ovX^q<-mqwDnDyLa-kufFSB>|cZW>5RjwY{YN-dZ^f6p3&dkxPcHr~SHO8%S|1`#Gzz%DxiktZDu$-tDqB^0!u0Va z$gU}egL+1oppNe7vy5ErCX{!f3X04h0-gUbPMy|H&2ue{*c?Bcp zRQ}d~quFaKP}n8NWsg{mE-jG({0GDuhq5x+*r&ko1w5FJDuH_F3Cn0M&{<9k{YjL{5Jhl_>x> z7cfG8mmwT8b*sli{wN#?&!W5>YeN=GRO4`}-7n4ET+vgO#0k5ZO$*u5s?kp}8&jmB?| z*LEA2hF1FIDWi^oZnhv^q{Cw7npvZ){RKE)wXkUuZg*BI4u}a_P zzB%!aqtLY42Dt91vB%f`($4QoCruui*?F2dLyad_JpzujZOMxEFC>A_Igf2d*`%D`&-2L5*Rq% zoK&)OCuSr21yqGw>b}w=E3$WHebv_G6Nf1?_{wWIU*VAS4}pi&YEK!N+CIFCmc_%t zX}&4LICwiV@Q_tm?cvSLuPI;sod>IvYbpCoD`=_i5k+94R-uH7Y!$mte|oL{ynYnW z-gUh8@k_vl`-#vj!qF)e;El#oKx}T|7C>F>l68bqaCL(*0GO${cQ?jL0zmyaN4u|( zvpM)Rl!U9YqGA(X1ZiqQ0eJrjMr6D_S?z;7)A#lD{o$@$^~o_Br~R(s&u79?CB;*2 zhHax!6@F(v9%=M;?k66$SVu%Oj(O#pQFhZIIHF+3SZ)!v@P`Y#tAxNQVUO~)woWPu z_XL{qm4VOl={{a+Z+z9;_41HIXPH1cA7p*n@>ubO;Xa|P|GHh{)o~7s&fd`9x%SPI zd`d4sy*bT)ID^vAD5mlYT~!coPeHwmFWnp=%M=!d%1L3WNFTwUtgw?a)a9N%QJnUMZAai()9J=z^nt|^cvl5G8ivIte(vJ z^?xwhH-tf}ZD#k!4E$KmjLOb_u*H>pm7$HIA3+V#>IG^{F`#pto$bFX zl3q86pg=3vbg{3!{ngxDqtAsezmF%d=ZzKX_1JtT0yc7$964?Sb2GEJxHzf1!~$Rg z_wyt99^h29n7mBr(57wR8*uy#XEI1isFjwnB5d!xN++{QP_DV(&iSMB>f*%4=25gV zHgZ(-=#$*%f1;Vt~dw3%=^Q}Uwl4vV+7>6XwRxzcY`I*eD-iy1ysI!((VFoI3 zGL=kU0c(Uzz4Ok~hcU^X>*XfEIB%!mE*5Y5>)T84^QZfM z=2gEF?=s`|cu9b+R<_^UpXq;bdh81!_at3is~bb zSBOOh1yfTKJ^{W2I|4$=)r}41{@GNV^w;A{D=Y9?JmyU3!omVrf&**_cb7_@gr_mi zfsKlTgO~AclkN2o*$c^~Px~4hTW!`4FWuYATv`H1)q1+}clih{tv?QUKcIc$;^X5X z5HnB<W8-v=ViZxxio_0o5R#pPY;I!J`(cXTw z$s_s1(4W2M@d7Oy)T?6*76kh-GBeO*5P%)ctq^BN{x-y9g}x*6^31V5D5dYc?Xj=j zgR|C_85o%A{gvmVB0W#KN36hTqlrF0J*Q=0K!milwgU=oh?`)4o&tI@+WfHz%+s6x zJaEmUk?z&h-Kvevl8lUuPikO&pbSY^<3>SDsyym&v`D83>G?{t@qBXx3>07C3k0ec z!b}hh7^IWZkElz8ZIC$s1wzYdwQpe41=PS4m0r5OT>^}U=keP9a(R|mz=JafA9G({ zq_M8It!;|tQ*KN_hPa+b7?7l`q%V*JhK3})Bqv8FV&hMrKJh0PPv>u8)c-|4!-gY= z@W@xdD$danM#;v=SXx%L4=k7a6Nm5KdHR3V7xI#nkmyekP-Kc>)u|Itd;K%z>TJ|z zD$b`?7vQO>DX86;0`IF?VV@;+bx?0GTWwPhn3p`&45{#Qs9lJ%jK3KkOWH~7dm?ew zOPK&^Zgp3Q#LLW(PM3=ulhvI2RwpT1`$kjuXgqtf{ox_VixzA+p@WHWDsVr;W|@5+ zabt)EPU?)*scoL!Cvb=kBRS%yb6J{i1>G4@B7(yiQdVsW~Bzo#`jI_zb#Kft^U%J{%iff&PfgvYc1erUi28s(P zGb>9;1~~ELr4ai{g!uUCp1@#clUNN(yF);{c|{u; zJv_{9qYY6%J3k-ZE&m_Nr{0#$JV z5B>8~;{K=0y+K@5)AzGn&X^0L#i^A%ydZ340lk^J`}GT+n{+4G>T=QcgY*rl2-=n*bl45EtjR+Luf&;3lO1jR_w^LnCg} z(2$R>7SsaxA&;O%ML*gm5^x+>6}Ez+7`RASs9IXpaDfDtsPRKsodAM;_f;;0oRcc@DeGx!{;IWFstud!F{2c)@S)$ zRTx<2$_$hWPZ=3stFM)-ih*(2JlFiO(V*US@PhJH)}U!`Vi>W|dG|=c4^|a=#fch= zp%0&eiHv9JT*(F9zgh?ul2}gH?2mI8A5-#{8ZJr#!>h){kT-iyXhMD z^@mig6J1X-JvbLLs{Hq}lCjCj$h7_a#U&+X>U?x;O-8_FvneVXstNh|eT0KJSUj`| zjEPf~wk9?<|Km=6#d$WB`gDZVxfy=~YmPShdhD)K>Ww%Cag~f6-1%riU&}bp7||(y z{xCNAC!DhW`#@h-n2#2q&*(Q|OZ?s`TbQLm?RViYY~iE^`(|(8K>lJC9E`D>o$cSjBsC_=He&YcD{Hza9xN=15olAC*vvY#jR=sOXC59W&jw>$T`egMdg_oMByWzj zh>D7mk&`Q{sQ68mSDEz0x-cc3k}5`@ygn&;AdYq6DyM_WpNJCP&B@onHgVw-G0N3wrkY# z=1D8#&3AsVL}^+X0fB@VH3e5w^-&@G&Y>V>rU)4!nCd7u224KyEa~<8D2;dJ`GPig z?_2aFFtGypS4N3Mk*)oKAWC()S|L?fFF^77Dqk~yh2L}+eQ@Vv^E)Z{9Ijl#B^Ac? zIlgHV{aG32&k3Ir4gR}m8rqv?@SZ<^1>f#}KKyre2Q*FgOyIz}KE8jT`p<%bMj#hL zo%;{bB3OjS$;ruCn?>fI@8z#$+NdL{evD2`Bq(EX!B%cxpY!nx&jMDEtwwhhdV62l z*u*emqV@c6ZxmN?^YYqZKWMNM(exBqm!VR4r1OnYq^Qh5gbtL~9~JA*|1(CVR~2?^)vKYO#akAduz7 z&3+2;yYn9K;m=DRDXShsOla=U{ACzaU#Jv4A9-!~<1j~i8v=<@gIamA5L}zY-re)G z(-I7ow4#fHKq)>c;H;2ScOS*SNV_3Oyv+2?L;mSzp{fj1l!Z%Oo!*dD*^BEdm-~I? zA^VSF*%9}KQdd}{(cGy=DhjdGb#Cy5EqaK}6t7olKE8gfNiRD7`>aI|W2Z7BvrrlI zrF_ZP-Y)r&R)%RIW_g+T+S?_Od;@x3v+oG%&Pdxui97K@g5ZazW zo+jQC7M)jl9xlH0mggeOI8k8ciB+`56_uMPuI;q{GscE}2)K{cK@@3qo9*rED*IW@ z0ueOXh$+ypIx7|AbX|Y!kK0a>R6K9CR%)2jpJeJU(b3v4+2m)czCyE&^cN`@D@+iu zD`tloEq5QKr751?%x9!a*|%##^idMBjb>Kvdt?jylUSK3IpA`df)%%e$_O-uyf#xu z4|6JB{JfvGa$DKOwnwl_Z6{6QPh01D16ja2EiKHwZhv{dfoSZrcAM?Jc0PY`d*deJxTt1OyT3?go8CB%~Fj1*Acw8$=!y zq@=q`q@`OxK)Sm`y1VNv{64?E&mR9C;~(cZ-r?{yp1AM(S~1t0b2YIgHaUDrKN$4n zj{9s?T}uAN6*_a*SqcxeiaPVLOYCAH@I@9y(nASMEA{vMg$s#TM3-0M;e@iQlW9w@ z{`~;wg9#ryDSZQFWgu=SW}fD;s3ghz5woAN+mUfE@1@H`6XRj;qVB0yLaK)F>C*D< zYTm%HDsh+8SQX;qZ3N2B=H}sQ;ZoX~wt-0ao~t1e~ex2b>TE<~*0hrL5_72zEhHxYtbF3O_i zGQOFfuAU|N_w+vxnd~(whB;jbO*QT82NxF?wGtzR(T9f6-hq5!7C2{SW@cKBX%-tq zTKAAhFR!)nVn%xU5!uYu!Rj%%ji{ct0`Kykdmhln3E46Toql*mV>(#06v>`4XT?wX z0IK3g@bR%>o? zQ39nL2KjOzldQ1y#m2?Q=hFT0HmuY>jrTWjhK^p9X1bmnPzdaf1+x;4jf~(RO3X%_ zj#|TjmeD%5y}P?B6T>@IVXMwWSZdUxJL^3SuCdsP8X8sBL%D4cdHDGFeEj^?NAt+z zx;jpS&dZ`FKj|^D0n{1hN1q5{c+F4G>b-1N+(3BO@YL@C(uK?11WLbQOMo6phYIvQ zGO&p7@VuE$enR2SWxg|?fEyAVDy1K|KB4VeJk`KS?V{>iQe^n?CDZ=)E{Cg9sA9c@ zg5?&BG+8w(o`b|(G4m!S*>JiHX`xNWwWruLii%3SZ^nsnaKM@n3II+gV0ePbNOz}Z zC1NO#sAdEjGmTm|*T+U*{QWU0UjwBJs24l)9nQag8c1*A zY;OLDo!qy?^Je_;U~eTVDhfuKDtTI-H*e$H0mh(J`etHkC{Ox9@cKlhb?i@@*&FCY z0>fia$Od6^013&sFCBp=%sy?MHG?Is3x02{nDpmdee3!TW%{r&wNa38(B*%tS-CMOF;FEosXR_g5RKwBXJm2D3;0+^r8{&&^ks_C(H z-^#Lxwq*ng$Td4YpH-c>8=*cwVcQHe#$^9*GVi&l;tKpScJLf!ItOdnt+L-pI9 z4EuUgcq>gnr0K`D2?IR6x;U2HmL zH=LgYsF|wjNIH7A5f?fk69xuaH0OzRkc7+O&uM^nLF@B#q$QKa{#uflf+d-N-7&6h8W&3j3JcTKNPTT%(ROkjzEizgDv zmA5NaRbcOV^otv@lbN2@VLOqJSnc`oiXo>#_RE4QsA)w{5A|FSRe5<9l9G}R4rQL64GHdNBVeb9 zka+3faIiknF8DsI@)ty0XwTbYc!x$uod7hoUg%J-J~l1aU%-Y4<7CD(a}U1PJv6KRbR2~Mvp6uBW9+ESwmV-C^KXe zN(u|njdAKx0127`)C;H;4}eEE*E+yjdunxldQ?~Us6GIIYzk4g*o+LrmoJAQuJ((F zbO{gjRVwy3Tc4!&`9L0g0qa}qk~}B)x!Te4bm@ghf-D^%vR;}nhR10LMLK&TFK#6 zFER>>jXj-<(1w$I4#2;IT~_+Pi{V#_XL?Q)RTpmJO@A6ZXcQqJ^nM_`7_<0zvcJ|> zt(usbtjTM}``FoVJ zryI4_WV}xObWfi?g-`2o?WRU8d3a1r#OKd%sqX*oK*d8KqMaQbOH2lq6L!C4?*G1XI?h`e+0OiBuXl>E&*LJktT2wh#obc43NxK?0uwcN>9YkKHec1c<(0e{7;PL$Qy({Txinxy2iC(WVD>N zE-hAI$RsKvaz5dMcc<$s%ASDZ8SwAA9D>2S;O=;+3c8$i>Wca$eNiZSWtW@d1Jy_Nu^t#)=V$0G$ZIIlHZwH)I%IMvEdI`s7PCSg)E zVQ7V+z2MUTGcYM$a(3M^<5gzHa*fEhR#qgylO4($x_-T%bB_jGWPf&axUQ_(Kl2en zNXWjCHIYI~dhj>)~M@b4liFJ_Wm6h(hJx|l_Am-=S z?I3(eWhT@n7=M|EF*ay1NgO;2h){KeW*nPPC@+7erKZgsVDNdaJ4(&Q#>OHNZ|D+| zF4NG^02*MJ@38V>p&IvmYy76KZDKpRqB8{P^tlOvMY~0T71iVBrbZk@y8C{VYDyd! zI&Ax~GBH6l1jsjlg7w z>WUb}k3CsAD?>KQtR^ZhPE*QCN(N2JG(0j3QB0(5toovLIOFl6KpirjI>ftiQY#)X zR}?*=wC6vGIpPh|rch=8#rIo4<-R@L?hqe(*MG>^)(^+P?u8%w8e^~Rt9e2x7zB; zJOTrq;HjCj!{!CBRj~q856B_z>8;HYo|@8BOCp&qe!=}yqEXFrFsT4ZDGy$Bkc+YG)5zVeEg(NIv9J(^gOgF@ zqEVO{lmsc_nA{{CK`Br91JG~ZP7mcV9pqYd8us@lm5JfPDIp@sKJ~1suD+vZzmd*A zJQgFOnA!h|ZM+Ppr_c}!vUmIfj8v5EO5U31=H~hpfXJxtQE+gGm)X6popeEFd!l(F za7WC^$CKx80REvcEb)N(j=SSQnTufaD3r8y{fJ znpiUQtK@tRo8w12#>U193Sb_`i%RLLwT?$hTIuF$q^qmzFShOY2SxJ zN#bv?7tLMmv~M<=+ER%(RSrGQ(M~NM;(wb91Ir(RFYq-cfYuKEIP`*wii)U|Fh$AL zJmKVI^u@NK<=LNY2}uvBDC2`CLiGGFB{4Cvtn9FWwZ^3WC$Asx-YwlZwGuyY0EySq zVpc0U)S1A7zP0mbnf>fy0nC|edrR}`zLR1gux=Z$p&Z@6&twL5g9gjR{MZIAUI@J7 zP##uCN88FsVMN{cw%5vgr)RLlp!YruxJ}qLDLWpYmpQQ0(w0IoUcc_g9w!TBnb9#M zR3~R=UW-BCfZ0NqCM(@lW=*^Q-NW->0}Ljtt*jvL4z6Ir?Ob`x3)VbMoSq&BTU$9Q zd6QV8xq<%v(sEtHr56ts6>)XiZ3sc|Ux7Z|z-cg=4K4Ty7FiiNVSGr4^HJ+S2!v2& zRQm}KFFpR~*0*Gnqh3lc%(2v$(Uqi)b@zDft(24rLbo@na6wmhJ(Q8UugQS{lNga6xZeY&v)j_v#!Gyt*DMF^jmt_$Da6{zOugn8 z+U}Z)$(i^28U1zSu;iki?T<}UAHErN%t$kah7?+xX=rG;Anfb{l(U?V(js7@ z=YBZdTy}_rgEMq~y7IeGx>)hvzrq;JfKV)5kOVxQ;A^J^YB4>%nUxj6nZhM_K2RtD zqyT*p)UblIw9SKqcK>1@VW6SKo-fggZcK7IcWPXY5Y=l{j+I@}fTplD)4T?iz)DGu zRNBO*&f~|tX4x%ikgVO$kFq;N&7*`3bG7ooF*B0e`UBgd!;=^ua~_$t*WbGLMBj{; zNiq>)-4zfk>%^h@@bS$sHa`C1@-mnwE~uB9Ywyolf%Ag}00NqVI?cvP8E-}^Y@yPD z+zAB-9&OEIlqKM)^N;WY9~Rd~Oe;Q~>ZzYbwSj-W>#JA4V3S0dWuHNg^2zkA4Rkph zk)}qKkV#wtHq;GvDj|B(-ZM`jTCt?4?VNM*Zs-^ypfg;|LgStJswyEb1P(s_aLQ9& zsS!boT7n9lnaYi7#t_xL<&hMnjDRNT`>$I=vB18r%4q9;lLWNIH?c^F3CUTqlhYY_ zYtd&OaCX!T)@n;y_AC!*n{tib#9XdD?e(p6J1;k5MO4_VmjR*&^3|Vn97<8UYdgW? zQg*9{Tks@Hrg4O|I`4iNY70{w;Z>OCSX~R_6p5*^T`2)jilYe>Db`)ZY;PW;rnL_a z8tg9=0*|W3#fyD-wAl3EJA2*lJI$&Yq2l6CEJi9iUa_Gtirw!)@-}5XpA40sKC17< zSN1n`S|VPbGZ9D&l@AUN-`}E5h_s^+F*EWdqy*#nK5#gTi@S@e0|x5}=Occ=34=N5 zvd(4b2Iha&!MdQJ-MP!`Pn&c3ZnqJq(UXKiancuwyrSkIg(887;!Akhri`!4G%K2?#Y?rJF z0^|rC++t740E2~25fe_cLO_T_>c`uwYm+-(hNe|QKcQ}lG%Cn<&{vK;@n$94$IHq8?n`Nt($4q-JtKkA< zG)}3T@%iuGy@Pq^>TtRBYGeDHfN___-ENO)coxp*XXMLEIUv5eD zdv}Qw0DLhg^mw`^x-^fgdm?9tR0U#+YA;YJkqeGEX-J&&>Blkyb-gaWC?Zg~^;40Cn5x_s zve|mvXB7XLob{>`%F%>CDyPFQNyF5TqD%2ZvryvXxks=6%z@%g1KZ9OIbte5Tq%AA zj2m+N0g+nA^i>ieicK$J_z5AHssFzXzEVq>;xi%`cmyi+S9k>C0%rJTD*Iu2uJ30V z8_8~9vY=Z;|BkjrsQCwRQh%A)7oSkHB{C@#9A9eQ`rIrRmlZpiyvBbIP}v?iwf!DI z$Ea}G3fwX5x_cLoL@iDOhvyJ@)%@1YBI4WXlao#C$D zNBb8o`}_4JW?x!dAGK2R2y7zI6}Az5@>RHZCEROZd#pU02sF5F&L#+`WYndKWd zIidUYW0%TglR?2rr%!9z*IKfA_ccnl37=7-UfK8_AmQVBAE~ zz0`I2GrWFy_i_@7=fu8AP*IH{jl5MSFSYs8QlF4#4k6*qMQKbui$j-|{f&$eu}jg~ z);0#Z5op*@C_$AAh}LI_zn{|V{(brWd~I^={m%i8&RvJvg`(4S-9Y?Bt=3YpBqVPq zihLTxW)N=aL$B8;D&+bO+f|5^_f0g1zLb_$Jln}kps3q+3vF8jD}}HVK3WFh-&aMD zUiicr|A&g%fRJAPl~)UEI;3m||gP&m1;!hzOkIexVufT-FLx4T#B|3(V{?s4wA#3pOoqI=;R*G@6pT zzT{eJ3^0WTT(yXvyEB8VdFh8E<@EyUCU0z4e4rG8Y?KmdHeP0Vn6Croc>oBcJoR4& z7g|UL8PB3{$;oSMT5$27=luA4LkBWSLBdx5#5W`)eM_fjr%eHOSLWtacXn_Q>yyKU*U``Gow+vc``6t^{-sf7GIO(l+t7`!-a*utY-ANO%xYMeA3 zI{O?SUt=_l0Oa?wS~^%4_K}pdDzAdM6--|W3kn>gYwN$U>koTACJwXpXXiOgw90N( zrArWYcw5CpV-uh0w#tk&>d-8=3d8O_@ghQUL~&cs=TA3y8OO8|>5tq_5+*1@E6X=3859XU~EtZ}O==N(g&n)+5#YPzKEioe(Q}A=;MF^&_%1jqz zubZs>C(aC{!YO$S*b91>=tVweh5ZK0vm#KN!_b?2JKP@064=BymUd^ zRct6vsp1aWM+&J)I$*Xy9U_HFInxwS4YdP2{|z58@pz2JN@Sp0Mx|t7VS!}t{VBj{ zc+c?lYnK9tAiyOIE}_{ng%lO-wWlbS*4EDUzkk3C5EUKW6y}>s z3fraLw7eQMe&b#+E!CEjkvY@df>EVt1$e$7-@%ERI7(9yJO<3ABUhOP*=uZmv zw)cbRXlb8jF_V&JsrDIQ2~H-spF7Sj_JoE$4^YgJRoO3->FA6J4o+6iM2?4dr=wzE z0Bp-&wihafIAHl>Oa)NNLqpg5zIklf~ zw^LBdYwjv{N#lTLi9->h96GD?7DQVv#u<^lryff_tV%IhntET~eZcL5-Mlz{xdx5$2KgA{g ziP+1|7RAPW^RP_eOlxUneqNac9sDl00E|bxkn;H^3O|jfzD_Q69$NN&I?EiV5M5^~jP0uclPc|GcVy5z@7-4u2`WeRVK@#KH zs!BkNhJ^&sM*thEBZg-vzj5yOa&SZfHc2{<`+nf*1t=76sk)Okv)xh@Tt70ak-Zy_M4S825X_kl!@WQ*Kfq>69cpM?I zft*z1szrl*=CZKX-Ho~N%teJJWN&$(@NyQ*um5p>O;1;MzC8{qQ-Bm{WSlm9S;K{T z9RVE_y>Jpaogb+~Q!YCan`YNl2dN+~6X?d?$4J-1 zd6S&B-upBCt2D{$Gu`58jQ(+j)z)(Tszjn?s>`{sUF=y58}X#~BSNsaSrGZ6ZEkQv*ZJGB*GDu;K&Ur%26% z{jDeeqk^q+^6*e$IomoZ=k$0~w;r#Bj1*q+V!C>2Jzwxzgo}{srswqe+3DsA5iw^! zI*Qo;_~$}F68&FgDv@PnqIp`7N5nm##)Ei4`YoP2%(^Y8Y{32|UfrUj@t~MqlB&P>zhu0j8w{AVPx5r{+!PEhb9RhLvBxm;d;Le#x^VuW8LFg=MB8!MJ<@oL%M$QZi?CK=Xt3h51H3$uJTiBH}HtI_1;2 zD_}G4c#ZM_4-XABbvbOnskb5}z0quW`*y(LzfA$ITuCJJta}J7;d3Y~7TiTMdQ9#B zczph|hl(Sry{jt^x{CWj5p);1RL&eHUP-FG)EB~$n$xBSE7upM&G)RE5Ki0-B zeEt0q8ABXRur}7~BcbEtqg_IkHzKsOG1$E&=3`&GXwB}Koesa5#3=n13|HHw((dlY zqzu2)F0Yhv=^J4|+vVuEINKcqWWFkR-hBBo2GVCB0n}W*>H&|#&(_u-Dt{^Q@)5)s zRct-g>ZO#P9~NzIR%<1Mg=I4L+$Le$EDvXHGdEDIIS3b5LZIL@1?Rob_sHMUQ=&5? z^PnQ9Hrg`u~ke`1> z{okbfD_=Me&>y9d#ck9weG@AC{*q8=1y%L9aP-h zM=+a$F}&k&8_3XcVR3~dy{-Mh;icS;giJ&9{{3;-A22cDxo{L4OO~d1be+TW?b$VnGX=^893uM#%0TwN`h$0A3_T=o#K(W} z<(duKH+i#lpy@ zoz9#xJHnCXw?I}PH_PXj`)pAV7v;JI*NBb{nHa*^tAh*_k>rmP#msYd1px0t3GEe z^{KG1a7I@T4INFML~gB?ilC$flsxuWtWxx7*Z=1~xznqT)xBafq6+(~#JMbbdh2>n zZ*1HA#&i)Ece0t4i3%HUY#eySmiP>N&D-ue^F1S+&3Er00yr2@R_|T$e3TGLJe8{I z9jGlF+SJ!R*`uJ7Rfc0X(a~}3B2=u1Y80pFUE-7P*Zv`gEv%{^lIAF2*<0P&Nxjbnn;YeY!CC`&|AHT?_{EpHVjal})4HGkD3#DcsSxIm#Je%`9-2QVg;MXtkfi zeZO(za`#GNVm!uwNoh=^vIfXugbCjIS#ThcbD`@(#HszIizj^LaKENzS_da55Cp=mESrhne6l~^ zT9VQ3&IY%*Ev=@xVTQKJlFwHVF2GGs_K7!!CPF3U&@b!IOeO`Myc@v62lC zb6%lDDt?uxd;k9Zhue34&&?T|Ov74+<=v>l%*@Q2)srKQY34CJuE+a9VRql!Iy)yT z%+(zZ{ey#Xot;nKIqiuDkWK&k^-AEpIl%?&OEtEtU^UX_-j?}L?u5Hy4N&){Ty{FV z(22N6WEwtTPC;D!{{8#5&Q=F66h7*O1~NdeY|8=YR=wC{0LWTURKT|Gn^@%I8FCbT zK`OZ#j&rR9Im%;SUu4lMrSl02&OA*fJR8F?bwdl8Zuqzd&gX5+Mc~8G-QA5&!~$S9 zsDD9{J3KrLT3PdniaikSLLU8ASZF%%b>N2&9;`<+)lxNRkF?xhRfUVAUZPQMMGd&4 z%h}#?)#+&zrwC``z98O|t(BD;+l70&xk!R=b6?-iTIr-qm6Aq<%TZRI@(T^H!EFOG zJp0w|y0*TZ+6vdEVc=@Q5K|C5^MTG88D6{FD-8+--j15BCQ{H<=l(V<|HMbM+&EHb z2(Xi|kPs*``t!7FdxaX0U|kA54NX&P>sQB}`Hkv>_{vH_%2_DF^qTzGYh|Z5P@0Cp z#teKYDF_G}iDAVE)zbjjvt60r0aRZei^t4b3K1(PMSM0iR5jFyvi0&gDuiyvAxHoK5Sz!mcWt|SmtVYkd{L&J~SDiEJO(v;GH zdxJ6^J{+sXg1v5}@5^j?I=HX&)M0j$$9W`S9nm~tZF6$zW#LS!#{e!|`{$qYH9X<^ z2A}oy^#qsGAT5hBdse+J$Z|}o-(UvH5#@)y-BCIP{Oq*>w=)udCrzfH2M->=#`qer zfar|kR3Coze^SDqz&6aR=j%VaV?h3q?fN3-mo3T6= zo8#4Y(~E&>z{274Yp3*}3=E284NTU$yH8d*iik9M2!WYR*12l#{Z264mIorf=^&H6 z{Q-6ig5BrTtO+b$mA9<4Sz5#GbIah-p1kIotqMQeP29U^|`=}kAoc_qF zK}fZ`oRtT9kw|Q-!_7+xz}M$rAprdR`4fIE8z*pStqFq%c#8x$vtU=tNXGo&!E6JT zDAU=(^Er1Vq18NsreVK3oFLIgnxQmXUL18}$=x%O5%+hh2CYci6T=Y;U$^0|)p{>< z*sx<<2y}K<)o-biOPc6ky{jQGT$I{RU6o-{zxLe_4}qF=aJ!d@PR0zMzRJ#zYpBy^G<*$Av7rpF=J*mK)Bjo+yLY-YzRSQrx( z5>?2koDJyt%VHCPj}82e+p`d!pqP?L`rc6tiR&HDHH`<7Zk#1v>TiIM@<8$varIuF z4Fd?4FQTYkC@Jl*vs?cDfqL=1q=u@Bnug|sV3wL%G!%c}^4Hbgx@=~048d(EPdiVw zy0y0#mo+mZYYce4VeS{MFfjlhNq>KTn9sn4Ymj*+EG%rwm}S7IqM%TR10RBPOGB7ms6a^D(H2~~|KDXLw4>lFU7Z8SZ zNtv1S2qTaj!R+a1bK3KTZ^J)sU#%`$Nf?Kb=|3$Q$!;%vt96G)&)7K1&(AMq<~!<4 z^Gw9NAnVKW?YyUf0o2ho&E>cusrY>awIHB?0qPw37{}syc<*983t@YR-!9QreuKIw~pk*{%$7 zJG(7*C%vb<0?j{+Ex_*KBsT=Mwx+@)1y@QH|Egmv=I!X?5mHI9TAdn*jKIYj5yH9PNb zbavX=l^hnVZ0pM;p{N)fA3xcfCfy9q$)_%olBftsh+pTVMk|E?Uz~%vO*LF0h*Gs=ACGoaa@1ZZC{WVUg1K{YX6DGZPH9O=bHZp- zQGn^er$gV+kd%}ZKx}CV3BS97;rCF$OC9{^pxZZp0%w(xF$<SYm(Cn6XzueeYalnaCg+n+^Ef+7u58?n!OnzCefv#W1@c|0RpARi0e@eGtS$MXFn8~1;Yjg237_uF&C%YTSHq=lE5RPcx6y7 zjzfR3oAQ1%oq6NKw~Q06CnXtO?;GmtVQp>1dHL%Lk84&|+rF>z_)q?F0nT3zQ<^)F zeJRM#ci6m_n4SGhQ^x#j-*Y(8RaI5yV-x&jo#8oS*oYMIfJ+e#d|jtCCp9&-7cau1 zzcOfTC)~E+X1p@4`xvDf9c!q!7heob$O{GCacL&EmzA*_M~-a|lu?5kI= zU^yL(az^_63}5R>C`)nwsEdk)L3_R9A&+uP7;L8k9`nZ@$}V2*Cmp`3~%e zg=NO_^76!>Q3Q2|*Hqig7Hpn^@+AFPRPT9+*8^|@;Q(JtEG#T|%0cAFs!=BIfb!r_ za(mmVqM~BUa*I!K^W1g!OAyuY>bAFcy2K;kIe}iJsE7+80im}uc4Smd4Za9`n(H@j z+8z#P!Rj?wsI{^xB+9US=H*M2Q0oA>0SWmrH9gJInSzsty<}+wk8*a&wy37Yt*;5w zM&N9JO|bG{RoG_pU1%u&BT9KeHPlGB;J|mtjjivB2oL{#?helfJd_~Pg{W)!EH$Ui z%6XZ;$)Hd@P8$5&mTUw>I>9FwtcAdX8|1j4gNkL-srM$l76f?+Qg>>0wwa!uC-ygJ zaq#d2p*4XQf{+TNMdrwVRMpf-$jLz_W{u``X_F5{D>rE*)v@UujD&$h9v>eM6a^wY zJSd?Ova%R&S3XR8g2GPR3qx+s#eP&uo8zLuyo9NF8Pb^h+Nh}4y+HdE78yAV?#2`L ztK%C5a%RxbBdOAQk8sxm3RM$#j*@-FqX;Hya`S+3X+}!p4r9SXK(k``QM!*!R zl2yC<*xJVz9uWu#(00^nB#&uMKPi<&>eWn7PeUPxUGUYwHZLg&_Q?JkCcKR_HZlUT z>m!HDz8~A;fh39len&3hBWx~`HRq64PGUc57T*KM)zWX@xVX54Tt{I5`5I1matz&l z-FqlWz_pEujx-zp^&#fv-LVhN9wfIv&Ma5NQZk?2yVrg4r8Hv!2Leu@t8)aiz3o(u z3>&|Knp(xvgY~}HbSY`+TQ_gOJr=Y)efjYe`-Eybhl6MAqLqM|nOO-B4~gyj0-Bfs zD|Tj?4rsH;1D~cTs+3ib3%a>9YBSy?TfMuw#_fJz0X?G4HeQqhYnT+)Rj6uD<*1kZ zn%w>wLBKd0XsajCs}B@a30*6v1NjOVpmw;hfcY}zB)Z3HIT3N;N@$m`~2O;GIgYtiavV-T<)k%^NMil?O>6mcZo#*Q1>DbQ(&^%Od8~lp&_$ z&Awm`?7dqL^w6Fj8W=u3b(tP#5gadFSzhK*7ymr|V{{Y(7B{WnQ|!raYw)7AH7Jz& z`g8B!_mpmogTNBDyxx@zwh@S{dj;WJs2%yB<$Gdcrcyf0;Rq;ap;v`U1013K{Qb47 z(Vn0%zx?G#OUA6W+uW<)wskzFJqFttAV=rID}&h=JipK&0GB1G?$xtMwyTt(adFje zrx8Lo%wWz2hQk&YEeLF6Mh2}HqRzMq+N@Ie>fng2ocHxtb7ahccfk2O?ADGBup0@_4ZVh8?+BgeWa9JE{FLiSnE)D ze9CKplLYdxJ4<(XfWJ962is-IL~O9ND?med1|qx2;o%zBV?XdNXkQ@n63vF1f}ETj zh~Q8(LQI47*$O>(xpjv3pTmn-gn=)FvJ~}I9atg>=`t=h_U!{#&{2zvi^EcOh{sTV zz)OJa2AtzeD&$v(x8R80{-|eQUg>u2ta@(+B8|%P=g@t)Lu=^pN9aO8 z0DFt!H{mJzJ}|HcCB%D)@Ox#0gF`@q0>)TpFtxOD_RBim0$899=C{-9>*u11#?{q< zcQazY2SNj&T*hKi@(yOizi!Dn3#!+Gr{fr@@A=`ikN;d8>ghZ)Gc$TQjNF=m=K}i? zR3Y+o`1;h;Rd0t^hVaq!*JJtll)1qXv-(76v)OU?a0^=AO$&y7J3BB=f4^$HmbZDI zrLZ1!D8N0q-e(nKT)e)w*wfI~w$c(p`}pJS9N1b8orSpg%^!cp3q1;qvC=idZNH!G z-2Y%vJetYH$w|s%wg`-zyLWFH=o>n(j-7PSNU5`9pRy1T%<)?rTqN@dA-o%=%b2wM z)QS2s_@Ogl5){0J)nsv}ij*%uGmZE4&(BaC6n^@&tG1isZtlP+3Ou5ne?$^s^&b?L zBV{^|Pi~bM85^%p7VjuQ!e3w==P_Fy%G;>Ffqq?-z>Nqb8+EUr3usEQUB#q?6ZItc zwX3VJzj#|~CyQYr5pzHzt0iCTMu*vxlpf$MRl8rD!&9x0*$*8i&;$x0fIX13x3@Pn zUFn%J39f-Zuk*b1XJxhtX#V-&V1h3IH8r(luvt0h=h@_jvuoVSuo%Z7y69Cv&O;fQ z4oKJFEoowE3d>4kItV*I-xo^x(cKM3as^-y)j7z+%-vz$AdYUmL;3jTj1c|m_BK43 zZRh7Ixmt~Fu#j^G&!gq_^70}|@Y2t=wu^^SuXtkov8`-vi(#4hSqtbN;L2fqEal?n zK07^yH|p!_>xvVE>;$8clKohw!xwd$L>L$t(DQNtV}5h$&DNEAH)i9!hoDhL_`!5bAWwavY~+r0w^3Q*lYkckpeD;Ma8wdrD>^)YSH!X zQqxn{0Q12?fB`E(m00kDO1}w(lZQ$2*LfeXb8!L13+Vc~g(J{cnrnuSDRn(YAfSUN zhX&W6RQXG0CXkTucZAGp;Hr=W zqD(73GT2Tl5GMi-{eb*v*Sbx7|9)jbtb1U9;75n^?qX1QI3YH6H&Ye$Z&R-hgFq5) zw7?s1U99cwCc)wA{O+QAQg3H0|Krcj(%*_tGr@f%FhQuLi!~8jjOwFj-#Z>n*}2*4 z4dXu=8*Ph<(b3Uy5YiFnj;F(0VFd-(Zeb8}{ZxRbe`tAod%KZEdUM-Fgo5%1i{VUv zq4)=FtIXwe7GbhN z1G)GS+A9UR(9w!f<j*Z_8BX z=B9_o2lYt3O-g(SXN2#5_eg(HVJ0|#=nYnuM@2_+#o+eJb||9wdI#-Mbh~HEBf=>p z#wX!nhHeBJ%^8g^+o!4SiA`>t2ZIV5dfWp8?s*!SNl5|N$Ib&L(<+u1 z8B5CzbHCa`pkM*up(&7ph>XnYM;{DXjn<+E4tYpnlf+7IdEqZ+zSJl8gAWCGj;~cK zyQrbkx~eEE6ZR{T_-_CWZ9^20lUA#;qh;wEH?+GaK!B<+f z`m3nFxbxY3$5Nk&HcQU~Z3ms(5sb2U&DyYVmCTLe?iqCM&IcP8#kyYQj#$BBP-$nK zYtf$)f)U==uO>)ZO0*h2H?I7{j<#$tVn`5iRh#^+YBTW|1x$vlW`72ORYcjD6R_u$ zoB1v!3J=S=yr?jeXD|+VC3@}_l?a6G?d`#O8pygZ0oC5SKW3Ed9pK?T`7yzwL0Y27 z)J{iJbD~qT5)zzUnFTC*hGksu%b$vF2#RA&TPnh1%);UedLu0taS`#i``;HYN6 zd=8zZ`j{K@P)b@_=9e!oH8i%RO=G|n-M}C`8T-Z!FADWA=>EYZ0c2&my1$`MDk?69 zx_RSZ1o9aU0#em52%hGrJz!yZV{RT77UqQw*FP&WQ&L8zk@a#d`TV@y zk&q6iO{jZyQ}BZ$xUrBBW`+qP+L##`@wDy<(mvhfW8{>Ecfy{74dixK(G?97!cbc? zGs^(Qx$f2M+&rp^FoS_^(}{)Bv#Mc$)Rcg<%*E<#bB&`+7jBwt`r730%*r1=rzM0&tL!b# zEga|)ptpeH3kw4cDoqGpaE$!H83{^32cGL8Emf{3AhdCLqooCs%_DT8P4iB7V_Q;T z6B}{y4|#dova+{*8;>_BX@u_oV}Gu4UcC%G)S9X!L|*9rjg6N=XypKN5f3CcH!uME z8v)e1S~gQ7qhBxIfnDj8`-MMt@6ga?!RU6%7t)fQmE{`{0JVrnd~R|^#!!Y_0u;rr zr-$rdbkH1d*U8C=uYvK9z)jPC&Z_(d0upy^#XJr&I2eu)gJdwKzdvA#7U5S;fbX3* zRYk8?2#DlAp6|smC}gq4bQKk$QGw3}#Y^)K*tq!O$rCR`5`e=3i_;BH11UJ8+5s}@ z&d-O8jr{CcEgaDXqYkixp@S9R*?9@CP+IH<_EifFE(Zy4K$r*_>F5>#G~+AYhkhH3 zQmw45Rhb3>LIy>r83zCQr3%~9RvT9Ww?$RGkjj9W4YC_JYNZ<@o zP=HtyrK$>yYN*yxlHPs)PT+oNadaBBC+e{I3!WR8!GYivpek66P9o|iM2_7*sIMv} zENZtp49)FjB|fty;@Y&Z1JmFLCe`G;JW+^u012GBC@A0{7Gc^2C#fBfm(I=_hppd` z*tan4z)=VcqafQo2OKvl%JKIPAJBHgdaL_LfT^IKf!V$~z;zlLtDx3?#Rirkqfi$@ z-w!1Xc+P@t^2T^M3_ei0tg|ySqkvNaS5M462mG&~rf_z4p0VD98WkR%bC2oviykRh z2yr7~u^wSisPf|Z3kC+ptu;P49SP7+XLHY6&p(4FR8q19T(9Zz(PR-gyPG;t%9@)q zYh|Q=xQT!bVBsv(zy+O#4-M!QXldbY&+K8`5jw2%dvcWdpMMz#(b=Ar?W+0(Asf!%aS|zHyCY)Fiox;M&ox(arlX!vHc^jWdy!rlzK< zYG!Jx7`B*|6&m7;UkCWksoh$i#+u}}gx!fj3LAk5eC7H(H1F@7Yy93mJ=!5+)rLAU zqIr%X>kH_Z?b{c79JcZO#Q|P%K3-LY5*j#0Kxk^hd;=%7wx}d3lDINQ+kR(o4RnN5 zpnvUe@;4_*ZJybR##}IMgUl@?EDT$`0qCuA+_`>Gfa}q?jJBnfNTvl>T@Nf zl-yhqm{#23H2BpBBSTOh27%wmv{74=KPlzGAnTs52~$W5=uC5db=~1i4IU>+XcW z;NZ>=)@7f3Lz~~)1wDQGLgc+{r0<@Qp z!MA3R_sEeyV=eWF(a^GBw9eq+;X(h@S$IDuFHajg1H8RJrKCdaXuPjozwHt~%~urT z!06qm5CH5Gxt9!5xcFi2Lx$x6r}t(Ubm_`HsJNiHU6s9bVWv z9ArCJ1D6gO(1n(oUvFz5?)1bbfjHB@PxPEjmggP5UPf7|Fx3Gvv zSEkWLWN%IF&%HVUzW2FeJc8mux#9W(H$-4mXbrxsXq34zT6&z35>5wMj+E4US~$Pm z%fy6N9R@Xk@p+fj)KL9!`n_NESJUoo-vexOVbLWx^mDd;F%}nq}jwRNwg@uUuGdcG@?X`VA~MDka-Rj8iUQ?FqKu!~`pY$~}Zdc5il#0$T%9U63mZj?DZ=>InocxyZ{_h)8@1ADZ1W=Ai^~~F@ zKQ-XKtHz$^+Uhg}$FNv`<2RM|lJ&_SyMh^bf4M53xpvLUs;c+w_L$NwALLP08hf(x zaLUQb$bPP>f+QY$10pfN8AMn{)eNF96bRM9)OZ-o)zzD7Dm+;!GMvkHxvX=2wloe4 zYS@!ta>I(1Y#}GhGD8GA(#GRKcLGag!lgIa*{hFy70}FrX~~UdBb7_iF){+^AN>|5 z9$mS-NJ(`j3wkk%e@%;IWLb>Z+ak4O{NBA5CAhaXJzA4QugfnG$|;`t%D+?gwHVXmr8rg z_sxk}D!rTj`tu&wf?wobXZ8m3#>d4)6BvWSgX+9=_OGNaNHAx<>p81NN;lDzWO+ns zD&BZ6F^i0sA5Wu)!ia1kdRuNzk>mm4Fwc+>PF-I9!OH{rEmmh-F7Bc75U6|iZuCuT zQpKQ6&x11-UK`iz%xe!SnwO;;rT=<^1-BS^9f2ITcv5`4AH`c45cWMpe)tOfrHX#fBJSxz9uKYuN@-o{!Soa{=(wc+{%9LdBg?9^ z+^b4E{=J@#E@k?UpihHvZs&aq)GT*KGo;oX1Ky4jko>bHOI!a5B81 zbz#y)*^RY4QSH=OSuL#>tlAeJcB@KDZanF)$Ak5Q>-FrsH|o~D)YLr<2xx4WP7Wc)ewb7;_HY?xTL@w@)>;CDX3o0Rp6M2y+DFPy3}`$Ay(x-X^FdKpQS z_eyb(YdA9jbf+3O$7QNuZEcOs=lE&EhZDMtbNQn3zM9^U`H&e!jnz5J5v$tLdP(iC+J=1cl+tQYVC zPNzRj-KTZ4b$Mc*YXWsu|MdU9y9)~?i zqh9KhJw=wPpTpwz^hPv?@hjFw4}$az+y5+=uh-F%ZE<%4vZto6p9UYCrKPBKDY>+F zQc+P?OT8f9`0r_h%7MW_ZQZizer^Da@RpgGn=ddL=p-%^pkS;K>f}( z)25-1&6;H;Q$Y(%ZiMl@|NVx;WU7;Kib{$R@yaMt<(1@4I*j5ZK(SQ@L!HS;SEV1m zgSY*CTU%Qo5Eu>dgUV$!NSmq9gM~n(OeY!W9xU2kmvFc*Mu)R)&wOeArnrA)j$~w~ zzC0dj*y;~NX?0*Ev!K9fWoUVLqhfAoY4G)VV)45WC4H{bq7czIe|Z<_D{@K?9pbe6 z)m3O+wvB})+O3p`t#P`)0%>^cqzi!s_b0mm{jV=4`GEi$=W;$-fuRT6fw`xAde})8cgWx@_-Aweqb%)d{O*JfDdb=)Y|EZg) ztE%dlC^G0}@r_{Qn`?FLaUDJ5A>mqNGHaN4^sh_OQyd$UKK-dC6kYWO;m?%t<}&!1 zZoYH*N84Ri?@j&ymfBrZw?6YaRX2~7gq{x5uEdSLjBi;!y(BJnK+0MOZ5!JjS|+Bw zd$XL{z8iF%Z%Ng%Ffce9qjGAVLwJ87kf)VES!M`;yvkmjvgLJAjQb|s*tGrBDL)p` zRD(Z|B>(;#d_*VPyd=j&#?8S;>_^l5rqlOU%E9}fsMEd5kaI@|j6=f3W$c4HcVb;^ z-Qw&_`U*80{T_P9Kck2Gp5U@lx-dk9ZlK>Nk^pn=g*FIcjVU4EDtI=ARR<`g#FbZ6 z{FB1|}wpb)t^;`zdo_1PW@u+`soPrIj zg2Ri3GV0>Ri`@mcj<`5g3<*anr=`A0MT3-*xRRr+yUUAi&)ig9dk*Z5Kymi%8%0tn zYR}tx>Mm_Adby6j0EQIa|E--~`d(}57N7+5nozDaeQRE$k1l){kPCDj6z1>A$p_Jg z1=FtN-|l?O)PUa_ccUO-Vr^TGVplE8AI8G-NuhnRbHiC1TE_1C~wu>7b(EAWz_i3~a$^d-P-eys$;s9+QOhv?qb7aj-{NHDE?mfR zN*nH%9r2EXkK}_v|cLTLBZ(4ac$2Wnem}|G{?S<>qW7#MCFMZzCq2H zm>DW6K8CRt-2!3ZMk7c|r@z03=*Q|oe{EYPlnidI48-B4WR+XDUQ7G=fy>fdN&Ap* zSveRO5D@VE`9Qj5^so{-N}eM}fG|O=g`(faL89{E77!RBw~g^wpMIsHEjXc>MzriK z;^!9RW-n-JrbKDEp3c5@5GyLnuKsq(e}(+nY-3m-wt&xnHsVZDcH6;IPA2w4di^X z;|V(X(z3GietRDhk}QosSoM~oE5oQ>MMcG*_0eew30?%yqLQv_PV%O_(e;{|n$gFc z9ihykC3+~v0|CBqgFRUO*DZtNNYUBmj==G1AW`fj%(W&F^7QK;O;cHF3+bU? zU}eQH)oA4eyO9ouAHv-9^pL?cUQW2!yY*_wid@_`Fq(hF?U>o-<~#FqCcCgm78au{ zvXc-C*P$MT{TRs$v^crcJvOxo-4%idw0!hlYb>O6e;xkv@cy^KXmAILc;P; z;2|iX7x%ct>$@873a$O0~SzH83`AojD8O2#dkkI5GVB^YV&M&I<(h zG9ADdp#sauwq_&Ym%x1Ln7Fr*p`kez`Qlz>Z5g)viN=jpPmvdOE&YmSnl2V>a#GTz z%j%J%!c9LukE$Cd`qwit`->X<H8smeqTgs z@^OC$RqvposqEzs>zZ3x@7zddI4{?H;h`>@^me<6S4KC#j?AGa?yb6eoh`Fzzq?3#J#fo0 z(c2YH3o2UbhmIUEyWQ3A??D}2hzXLK3C>O^)I=;gc-YvA42A@@xu@Up%11w(dC2x| z)*((#y#l9`x5uxP1R;R$UUqiQ?QRB%2GeT2qH&g0wxynjf^)%-sj4Y4yawN`OS znp5;T*XXjf?2`?ATMgD9R(N{CW{@qxRh;;NmPmu2er16&ysr7{*XLr_iD`Nw>_w<_ za?w@3H|gI-YdwGt0Y~m(UY-MzPTsO{pu~oThNx*STfDzYs>!(+-KBTFaQdh~THN_U zKW1CqBEI3?ICT6ZLQ&OtNBUV^U5idf(e2xp4+nAQbUXo%h6Lu<@$vii@9#JI+&WHk z3?Uc(E=%JtuB8JYfns53;3tSa00ngs$8@0zV%tO5`#dV@m`(XqgQU?FzUHXT{P$VH z{|{}cHnW$8FB#jjr%&57m>;Sqx4gRo5Tr4=B^4FT_>Wu;)}t6RH82(9zQE2fH`SYI zRDx2Fii*n5Z%d^glY7p7yb}gJUB5mJ77R^HUf8}ORt^%VX2Gikd+6w}?QcPXDqr^)Gt*l#R6cx>TOShtGMRerJzL8ru zZ#FhRd&x3yJHfv;bXSLBsJ+zSgOw29rKyXGijQjsdnysKUR7OfZPz_v+o+(VYmuLS z-$Iw)r|PU1P4b)MgQrIaM;wrIc3As|HYdB8sTpv$l%%9l{3CJ&QG9O9yrUiI%fJvc zX$A%cKs|ZR%ORv!q-)!!n$OkFo7d#q^+xHPf1w!SURe0_X>YsTs4z6URnk(s zo-KAGqxQ>}?1F*==NrJ)9T@+$l}@R6^lK4xG6;>>Y8OmP#HI>&L3hWK%p#YTRDD5S zUZi1cOvy@rG-ZG6@tMST@2u*(oB?b>9J61z3Mv4EHsYWUtG@Y2@3=HUjhFsU6E+Nh z!TbUOMHXWr2PYc&H?K|gdEF88zsIV3)*n83+-|EhtS=`@NQy*PW=5-=y&PZDepb+lu(lU;zXlPRT zkR92Oki(kYqzH=b;g;=~j0mI?$mYo91P^^@2zQbFl9ZH$9mwE@!P&ECi*w3#1Qtit zd5Fg4Q@w7gp{NJL!op&u7_m|2n%N=ULf5(Q;loV`Hk@84{q&GP@DbiM^(aBMsaP$%v3w%%EWd&*SdK zEa@^szCFq6=qH>MC0#{LiR=E6@1*q0F^t;cvH8-uPX`Hvy#&HSWvPc=)OpWc2m5U2 zz~`IlupC9zKOZUX%ecyRW0-+R;Xjg`l;B}9)O4}y$YBIrf1 zZBGvyYAxvAT2l1XRRW6bCMD5h7#jY}on?$yeo=iCE*izEIY0kAbSHpZVkxu{>1Wj5qzIOYUZ5Hy0&M%he#T*J-_?rC7= zmTQcPxf9}HlgDPzA1R94%}b5~miHm#xva`cOP9=B==eK22x!lFS&J9_Gp}+%PJ-Eg zWkj6H&}fJvr`5yjJnAp;lS-Yv6U+#J3<+sY7hnH9%pd4aU|+m>*~KoVK$Fwwf@Jle zjTFYydwGG^c|H&XmlI?fUFZG5XK|1q=7bhtX3aUvqS(du{d;d2p&d+A9-(b3k!!9T!CB2u?BJ`datZi`-oj%f&Ly+1z!Rd zH~0|0Cr`#25=762P4|{Y1`Zq?k*ueu#i1!)9-fb#Ba=V8pwxk;fSrW% zs(pUUi-1Cdo|#WYSNE6mxIL6KfY_&Mu?-ekv}@dBYX2;+cIoY3HaRaeW(y64PQR0i zVoE;U!n`ptVwJ<%3WOe@p=gUJOGA}8+>gOHwqjouz=rV#U?xXKpz*_9D#*pP%??84 z%%NJB>6u&5dI3TxnogJdUfLlc!Oni@g8kSu9SNJEA9X||#LplA+T}R~W6M1llaZ|=D7gOcyVJVlDM3Mh*|=Yw znL1zrIjbRnFG&{01U$Ch*7SaI>6Q1T^!38o@7`U>bPUEayJRNkyWmt58TocS_{jA1 zG{yy;p+J3GTT-H@XiN(84m=?&yn~t=O_vNsp~I|(w)T(j-(y!_a|sGc8O@LPb1TDR zpsl4vS-j`KOo680{u1Lz2;E5%uG0e$q54NF-mx(~q0xi`WE@gxv=~Q@9KmtLeKD-n z<^>ASr<^7)(*lq*Q>Wm9gHzGV-yUot*CFS9CvTKvoI!tIKW-lA zJGay9YkbH(Ue7p*{>pByl` z-L-{HhCYsq>k#^^-kOxqAzIq==3iMWp%;b4DqJ}M8x~j(aq)TxuIc&itamwQ-tL6< z#cM;+t+ND@{_TpmfWVj1(#>qRo>`WY%q7F0K7M?ODx&}0%ZP{$d^Eixs)NT3Yg-ZJh^*E$DbgNjXW*6p```kybI44kluuS{jPabNZK9C>FTr|Z^meU0wh#3^YgdO z&2Jvvt8n$IxrN1|lZ&h&7qQBsY+Fp#HZAQ-r9-o!`FU{r2``m-;g~>>QHkzgZLQ)x zhg^6$+`6cViCI~YTWHwpxT&iWh~(0N1AqLw`ljsxu~D$CA3-O0l~$sj*R&8126k0+H@o`ptx(bfLRFbNYNd96@JV37QgBMnVWk*5X~b_t@)R7ntN z8OiGtl-Z!q9rNYFCIRXj(e`vDD?gwwoll(`8m7fw(QPI3P zwT*&JTHgLD`?%12jz6=1d$L{Hl(+ZP6a}OP=t#j>!>p4XVkD%saJk=ybo#zF^&d+G zd3gfS+3`=ww8zBhyqtYqyH)#O?Ex*+CzT)mVkeW(hY=ptqBLQcJ7|g9wk_F9QMwVL zEUWsbB?|pux9%`gtPCwq6o_3+_0@Lb>!nFGcEehfPJqQd*R1%jDFGS9{ztgWW$ z7E3~d$s4?HAA_N#5k%0%$&G=MhmP%i49;w6$+5%;NRW@W_m!O6ze3GO&s%Gmj_+bQ zdE?s4$)0Q7Q3mQb2+qH}ASd^$JwKso&rc6UT*Hpi1OC(LS?`RQx-zn|%F{+iMsX8n z2k%eSqJqAZJ_`kwOdh()M?Gzrk48dsJPu!8cf3NA*bZl3l`9!BH zAZYvuw@gfOM<;{bu50|_3yp4hYo-aI4JbtWbkpRBOG`|sp- ztgLL7h)_X{V}PF$h#q20V{;QbDI)$PO3q(c5D*?=#BkI1@1&oMf88d-8_KWv?4Kwt z=!1jzxT##$jFxct?%iAFYV#i6zLR!qL>CvJ8hucy*5=uk6)vMQ%ecbl#tK!E#@i*G zn79T)PT+lC8O~_V=?lDp=JI2bFbRU%8yI+oS9tR#xtAN5y)*$1Q-U%V=D96$b~iSb z*VN1cqyjTqaOV%qNom5OqC-KiqM{~7)940KJ)f|cP@rAt`ssh5Zi$(RlRP zVMj;(ibKwKHixmYKcGwN*|mG(#NfcdO~YHx`p=%!(9J#7)07+y7BcAnKOABxJHQamL6Or7v3_EKWEPM;#z zn1Tr}FZ7=cBXa<(Q)*L~fe#c5=UOPHmhxcV|n8wEF=B7(zt7 z*7vCfmIhR$rPJcHhafeH_6-$)iWM#RO+&-A-15PEd44Vtpbb-}^X(2!&*j;V1hSSj zCVvHbbf{P7P~UToNaaaT#^RRGd#+ioSF%uxns+=44_`*b%Y3zAhVLu|tv7-Eo3=pN zwWB}id{a_WX$AUNB(J-w(yr(ARk-V67jJoe$EZX{n~S{s(>^Aq_jkPRC#Pk@YKR9K zg`eIDEg-UE$Rreo?34!I#|kVj5*X6CmA8FuEqcgk>&v#s0TA@=gj zjGScj!0hxEQb0jON?1}-VWdTIku$t&`$xy*B=yhhgmcOnvRwu{J#~?I^+0jxnZ$(m zzke!)L*cT8nLNO$2r4{jX*MOr6qD;Hptf#>{A|X7TzYCzBCwu&(SD4xnsI!`VxgV# zt4nXh0@YQut}nibiHU*WaP0g;d1;ChPR!+;7o-PW7Xx$tsFGAJnwgPQU=09rzBO_- z+pwClXNpcPke2r8!VBE0y<6cl&qK~N>1*!n(AF*F_@O!CVizoA=G4^Hpyz-gT{+GN zl`XT>o3ymhpztHlFF+LzTWG3ZDyuf<6&>v0sNEo*pRzxtq53V<{Y(snrP_H-FHSiP z)u*umA&cL14zaNzRLG7i$f5ryzZ>h){I4T7uB)F=C#gUbtSlZG5WsrX53LPF49z!| zse}tF2R<3Q`fLcQpZ)wU70SAy03r~jX;=)Mcez51;Bvf;NuaK_HU+Yqkk^OV1d1#t zqe|Sjoe&XmbadFz+q&7a9E1&l@5X!2$Ww41l6yf+MB1^h!zn4!JMcBe#fhNfEuy}^ z`lG6f;NNd%^ad6E!a~H0W6pW#gZs|87C6#B%H(4sVQNv}=bRnFPAzq3-l&bnN-^vv zw?5srMv@4H~6+`3D!PhYbG2lkF_9D<@3 zKYZAl&b^7j*A|}17sm~=hMEZ5Ug8L7I|Fjb8KJlWvq$KLo zjY6lzQFOmhQ5(A;&E(SM;@Vb00Rh9%(6Q0%wPS#sfLfCL)oTviWPj8%dnoI-#O6Iz z-$u{r0Bpq(FUF=VFTWvUZ2oRqUnwdibTy;=)>=WX-9*>wBIiGGRV#FBPdtyjZWHWP zip#dL@`1=^Prv2~F$GHhgJF=|pIT(_dv z>cZ}e&&=hw$hw%>+?eyC!5Er~^=$LbM}$(*p8G2cJ`fLbD@S$Yn*D*Tru`8U2tig7 zGAQ2x)(CIk)=Lt9URVeRxUO8F1ZbkzPXfsrXOdtiDFZ4wIk&TQvpa3hc_9l245)g|D|=vCQT zmisdUZ{Q%}3L3GSa5{HxYthL_ut_kkpnwCm6&xH45Sv_@lRJTx1V{?vC(7nGv9Y!N z(;LdQzsQ$_gk&?MnD^h|65`!}YL6c|a+HUno=8Qp;goRUdCbJEOQc>?y6`wK=;2`oGn_M*!Xtez_9&fm$QI>d*-=IoV16038UTJY`A@dgs2keh!j3N zC$75;eK9dL6+5*{h63dlh7>Mk)xQ8Wh*Ocl*CXh&Z*$bCYsSW6=EEw?{&p+nJ{1gf z*QT36SU@V%nrkLn#B@X4#MqRTbi1PfS9yXXDvFR)T}M!8fHK^# z@UZ(cpI$>#>s>EbsrC#yZi7~H5tz~#7@5WIDW193gN1X;{2n^9CbO0U2M_AVvV~Jp z-^aFfRbBm)VI~kItSd^l1xTlm>Vftvruy&Lak5NS{lwl*zCX=F-*oiPg;+i4xs!aF8|1^Q{xo`V!Rme$FVYgMd)19Y4o-KpO; zI9NQ~1Xy;ZrRe5!0q(>tjjAsqBBC%-S0`t96mmHm8+oXGH8es(;tgv)@$C7W_udT6 zVpoC7Wk@|Ww38BFwPq&NiPHR`(rgj8o5WZuM1pP5UXD5ykZ?kZjwz-Q61G2V7llsi zcJ>7ZT7HScDZqTfbf7J>D4vT88!Xu3BKwh zR*Y^HH=KDTN6jF%VSrhGRGgC10d2sFB+aJdc(Ic<<l>Eyp>G1+?{WQ<2OW<1E-jEPfOml8{*WW)L)C*okrzvslh*YnO*vSS;(#|6w_L zjqHn2qj{V~Fds1yBjxaX0ClDP{Xck5JVfIJcgFJk1nuLBFyQkyZ$69eK6xzc`IEZP zS2OHc3AU8kX)RG{{Kaoi|N;@xu}pY--6 zTT#nS6 zlc6F`$cjF?*50rqIVl;Nl8@!M*^L_+Gime-1^qMj6rR?9DY3{N1U!5yr)%-#CC!D$ z2PDng=YNS5I%=wGkR+UiZN_Dk4LG6&_ZEAQ+o{MXi3*#Kx~?fM=hX?AH~a{%!eUb~}7KOlq>bve!x9!6TQZ5sf{qc5m`i{A7 z&za;{`)0>Dqy2fv*{5I0k$qfe0Z7Ows4Mcd1qPBgNlA|$KO#mC#crNjb`#|I8^_R^ z)tMzD+Z-S#BdxZk4vm<^ZC|Z`wA8j|4IwX8!n#kUkNEj`%P2{w*4H_#=$DlFjc~J) z&YMmzdb1MPFO+j%An`nlx9A~jzu0k-mTc<&B@IK*>}--{Y%h`rBPQ%qcDBW)HlMua+kVV;?S}+@srf z)}H#oy8hf<+Z^*Q^2)z24MbSWltgW}?G$Xh!At6W7L=6Lf!}Yeg|_e6?afLd6W}dF zF3m1OP@1Kf-a*_X}#ww-&Oi-NDa70Lv3;p?_P*xjTBZ$93_0 zeM0L$F@!5*hSEiQbo1J_lqB!z8(aQtVrqg>Bwvkhh&?_R)3eTj>+8XqsD|PzMukU> zH<>J40xVYwz3CNzmNb`C3e|`qC9@l`W zh;l<30#S|kcXG9lX9XASWS3{5qlvj`(nGqtPopjG@Ce6_C09ztx9zK9Fyo;0uS`x# zdF;FTacFj@$Gv_3z7*NYr142^ReKwD526!&SL~%Xg-dgFUustf^waUF6WyJ*R37Z- z62`{%-xCsYbNlC{!P6I_*`1=xLuknDl)+w^QCXgoB~cga>!dYU&dBY{?Ets;e(6%C z^S1xKRrj2}PonqpAReco^7v{W+!O0V@_of0>i_#E>#6H1GUv)8%G0>G`=&J1Z+&u2 zJ-X(*yyM?LnVMW$XH<>3l(->@eQErkt4c=p(Ums5ZcR$grdMoci1XFP6Xeb*%cK&o Gx&0sM-Ks?Z literal 0 HcmV?d00001 diff --git a/rviz_carla_plugin/CMakeLists.txt b/rviz_carla_plugin/CMakeLists.txt new file mode 100644 index 00000000..ba6c616d --- /dev/null +++ b/rviz_carla_plugin/CMakeLists.txt @@ -0,0 +1,48 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rviz_carla_plugin) + +set(CXX_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD 14) + +find_package(catkin REQUIRED COMPONENTS + rviz + carla_msgs + nav_msgs + carla_ros_scenario_runner_types +) +catkin_package() + +include_directories(${catkin_INCLUDE_DIRS}) +link_directories(${catkin_LIBRARY_DIRS}) + +set(CMAKE_AUTOMOC ON) + +message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") +find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) + +set(SRC_FILES + src/drive_widget.cpp + src/indicator_widget.cpp + src/carla_control_panel.cpp +) + +qt5_add_resources(SRC_FILES rviz_carla_plugin.qrc) + +add_library(${PROJECT_NAME} ${SRC_FILES}) + +target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) + +install(TARGETS + ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(FILES + plugin_description.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +install(DIRECTORY icons/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) diff --git a/rviz_carla_plugin/README.md b/rviz_carla_plugin/README.md new file mode 100644 index 00000000..c1db4887 --- /dev/null +++ b/rviz_carla_plugin/README.md @@ -0,0 +1,64 @@ +# RVIZ CARLA Control + +A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. + +![CARLA AD Demo](../docs/images/rviz_carla_plugin.png "rviz carla plugin") + +This plugin is expecting a ego vehicle named `ego_vehicle`. + +## Features + +### Provide the RVIZ view pose to other nodes + +In combination with [carla_spectator_camera](../carla_spectator_camera), this allows visually moving around in the CARLA world. + +Currently, it is limited to a camera attached to the ego-vehicle. Please set the target frame of the "Current View" to `ego_vehicle`. + +### Visualize the current ego vehicle state + +The current vehicle state is visualized: + +- Vehicle Control +- Position + +### Allows manually overriding the ego vehicle vehicle control + +By using the drive-widget from the [RVIZ Visualization Tutorials](https://github.com/ros-visualization/visualization_tutorials) and a [node to convert from twist to vehicle control](../carla_twist_to_control) it is possible to steer the ego vehicle by mouse. + +### Execute a scenario + +By using [carla_ros_scenario_runner](../carla_ros_scenario_runner), it is possible to trigger scenarios from within RVIZ. + + +### Play/Pause the simulation (if started in synchronous mode) + +Similar to the [rqt CARLA plugin](../rqt_carla_plugin), it's possible to control the CARLA world, if synchronous mode is active. + + + +## Topics + +### Subscriptions + +| Topic | Type | Description | +| ------------------- | ------------------------- | ------------------------------------------------------ | +| `/carla/status` | [carla_msgs.CarlaStatus](../carla_msgs/msg/CarlaStatus.msg) | Read the status of CARLA, to enable/disable the UI | +| `/carla/ego_vehicle/vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](../carla_msgs/msg/CarlaEgoVehicleStatus.msg) | To display the current state of the ego vehicle | +| `/carla/ego_vehicle/odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | To display the current pose of the ego vehicle | +| `/scenario_runner/status` | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | To visualize the scenario runner status | +| `/carla/available_scenarios` | [carla_ros_scenario_runner_types.CarlaScenarioList](../carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg) | For providing a list of scenarios to execute (disabled in combo box) | + +### Publications + +| Topic | Type | Description | +| ------------------- | ------------------------- | ------------------------------------------------------ | +| `/carla/control` | [carla_msgs.CarlaControl](../carla_msgs/msg/CarlaControl.msg) | Start/pause CARLA | +| `/carla/ego_vehicle/spectator_pose` | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | Publish the current pose of the RVIZ camera view. | +| `/carla/ego_vehicle/vehicle_control_manual_override` | [std_msgs.Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html) | To enable/disable the overriding of the vehicle control | +| `/carla/ego_vehicle/twist` | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | The twist command, created via mouse | + +### Service Client + +| Service | Type | Description | +| ----------------------------------------------------------- | ---- | ------------------------------------------------------------------- | +| `/scenario_runner/execute_scenario` | [carla_ros_scenario_runner_types.ExecuteScenario](../carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | Execute the selected scenario | diff --git a/rviz_carla_plugin/icons/classes/CarlaControl.png b/rviz_carla_plugin/icons/classes/CarlaControl.png new file mode 100644 index 0000000000000000000000000000000000000000..4b659fafc804ec2c606f37140d210abf73a38ce3 GIT binary patch literal 16301 zcmeI3dsGuw9>)g?h*1<@+v=_o#n+ry3|M4H;cj%74;m{;wgvKBWm4h?OH5UPQ?fHRa9CZ>`VeATwo4+w)@YX$$=!l z`@7%Y@7~Y--8=W6tWHjv9mJZ%f*>d;K2D<}KiSlOU;z2Qs;d7syvn`=vc;oGHJcDE&XYDr1p zjyp|X{9r#*{!Pw)q!bCxzG{{K^GTuXdHu)~=*!_pu2^eEK{tQDw)0Hebl;Zzuc~GS zy=o}@Yj{v%(T~>BRqSw8*R1`M>fhj(tf+`-^4TZHuBjBz-o^J}RoK~=L7`#Seu^oC zOqZS%@^3++v+w!ybBMqDERC1zGEb#&4{S!`Yq$FSMKJ}HPcqu0M~&O`$BNy%dF#7| z)#*=vW0l)0m!>bj_d-N&jc9a9zWkm$x(K=pkq(j-{p%Y1%}&0k`lFBd$kzPK%A?4MB=%rwuV= zqXb)zW@6ST&V$;|Ic&@r#aSTH^0hWKnuWy`*wK`Nq*Oyewn1j(L@QYer<@F6K?#KI zw3w|9xigC6iYq6-Q_V1k?dn2gM{#1PgzPkJGFy$?QMQC9Wm9nxJ)T2EaX3_>-dFd$EVkZ6 zR!28Gk|OLxY_NdGhX)a9we&KJWk98ah|MKO(mk^Q6FO4!Z78fm9e9r2fX3#cR$|&f zgRu2%n1RFfx(A(w(a@{3<=D+Gz(xa%no$dx(?RM41I~fKOrFK*GX=^sXgbu14I-mF zZkekT+$*FY>rbw>qX>c9Q*qp^bXS?@m>^FHvZ^FJ2|IKFW;Nn@jxYrbiaaasiHB+s z0#%aQNG@N*6^c>?VyYrVlIeVboX__P;_eB=(2~_}Lo}PVU zXtnZqtAjwS1~guyB5WTXj^N%Rq7Az$d4 zWM6r|&>Gy3LsbG9+P(FSxPc7cTUc^agiMCYq!C;pD${cX0yL5vo2{C*1q2^*Flc8cgA2mw(Ttuc9b0bA!AvZEYD&1!x@l@*D%z$8MkY3BdQd6%RJ4VVR)&?D|fQ{ z#@)S@b+c!&L&@7#B>7DB%+afxR~Vx~Zo=&rgivA@Bol>g)=UNLY4qwz-4EpCF-;yB zi0gP1DByl=VE;7gxHadv`bY4o7c8LOyQSW4P?}CJ^>%|&k8++BBb4NG%r#J;*-J%T zV&pE&Ddc?{RZ1likwgK5&7dL~bE4)n4Msj_9n=FuL}qenK*xZ>^udH)j&7m5u)J=@ zuKnX~CGXwjl^^cC^Y`0Yy^pD1^NVLjzh+b*7Lx=3LT@s-==lI%1{VN?-ehpm^8vgJ zE&vF<$>5^r19%x+01$eU!9~vp@G`gnAoM1Ki=GeQWpDvN=uHL}Js-f!-~xcqn+z^` zK7g0O1puKp8C>*y055|J077pvxaj!+UIrHcgx+Lu(enYk3@!i&y~*IB=L2{dTmTSy zlfgyL2k?d;l+l z3jjiIGPvmZ0A2j32326`{-vU9eOTzG}>vu`h!@Nk|^OVw+^{SwYB~b1%O? zri6n;<$qGl2^f8I(bQ0gh*Wj5+UOBVw(8nEX;-YQ!&o`%} zefQvF->~+^5{0k$16AOrnrFuY7GLo@!D{r0AGvw#>g_(e>(r{1^B*>z@}0A7{F*a5 zPIYb2j8{RS231h!4+}0l|8%~iCZT#pQ*mO=%u(VOuU5th=kiUg6Kxk*4|g8SNbt+O zq&qWPU7k4pw6?s-|Kjo^-y6QwmmN?A)FO4Gb>*v5lWLleHGFueG_d{jv2C$Qo2P`I z+kQCs?XbH04F&n?@JC0Z=HIWqSasm*(fG0C@JI#xq5Ea*o*2rE9xX`h+ zj8_(B`sI3JbJ?9KqRHZ~=84`j?2EY2QT<%pR$Ceo@-WITeJPUm&W{;SzfF0hH$IXF zorHd2?Kpm@w0K?P!6!Z=l0GWk^K@BD{??YRB@+WG)UhFDu}_CPStmPwcX?R5|HaN7 zA#1i}PIzPZYgc#vyy3yg%A>2kycfNH*1F2J5uGBa!|&Fv8wbt9sGoz!$0lj2W-TfH EHzLJYB>(^b literal 0 HcmV?d00001 diff --git a/rviz_carla_plugin/icons/pause.png b/rviz_carla_plugin/icons/pause.png new file mode 100644 index 0000000000000000000000000000000000000000..f486019f22b91346854cbc49625332b85fac67ae GIT binary patch literal 184 zcmeAS@N?(olHy`uVBq!ia0vp^1|ZDA1|-9oezpTCwj^(N7l!{JxM1({$v_d#0*}aI z1_o|n5N2eUHAey{7~$#S7?N@C?M*{22Spwi$MAoD*YEkyp>&Jm^DhzRMiI~3AB&1@ zE%)9l%|H-~Y6L@>aEsE;o|Zm@XC{!xW5`iH)|4@ixttDnm{r-UW| DRkbrt literal 0 HcmV?d00001 diff --git a/rviz_carla_plugin/icons/play.png b/rviz_carla_plugin/icons/play.png new file mode 100644 index 0000000000000000000000000000000000000000..070787758f0cf7a3bec112727393c2087c5f5e6f GIT binary patch literal 433 zcmV;i0Z#sjP)}CV><-!_5Cb5C4N#&hQTR{`=oB zvQ6Y#A$V1Q3Qz$mKrjGFmy)(3E6@WTBn>2~G=Q4k#F7>tm;lGNZ=#-o4d7bRSkhYL zLwpFlOX^3n&|h^A?Av~e8l$_wtE6F61s3aRrp9B`i)?!qxuaB(n_2-x_DVmfC+G9`!?D#Hw8w(X4k{#P$29F%@1&9 zdne`asT61(jinUmEE-EF&}lU01V|E%IV|)63{pj7Y6Y%p0l5h*jSS1c00000NkvXXu0mjfO%d=32RJ_7H0;1s^Xb=^VNI?-%P|~M8i6|KwBcX^L->tm|yRs!W zv-WzvJA3w@vCNDvw-0o@6@UUz06N}2=6aE&0k9410|&q!Fb~EHZ z%`B+{Bj6aYCHpZjN?t#~@nJ*9UjrGg6abh2^9;^E_c<_G2>@`I(eeNLVXFWwJKqRm z*=-YB{5LQIzJ>_27Wz2YW?@Y1J(H{e;lRfB{CA*Q;9XT18#@!joB&?5xdWyR&eAl@ zt&L7$oFxH-IPW<>P6);02!!PT@P7TNb6&my*T6r|iSSRf0{{%XJ@3q0&WXsGNCB8Q z(WY|d{Q^#aodp3ZFFJX1V`6T<#(rjIkB+|Dc_H!^(PNL2&VZxba{8dge$j$5K5Zi( z*sHPMwgB+6k&O4sDw5{F`YVqrGyAh(p70#Z6&vGhF}0r1B<3V)Iybh39%}5HUCD`W zYV5mR0l2KOf648Lq?sg>bS~+$q%BDslC~P>#0ej=rKExLA^QP*dKXe60^muB!OF#4 z16l1#>MqOaQRfqyl2Y~}sqaNur5A;*UX&JlQQUn`<#pw{Cw{974wZ}U0#E=7KmkZ; YPkJ<9GN)sk?*IS*07*qoM6N<$f_wk|#Q*>R literal 0 HcmV?d00001 diff --git a/rviz_carla_plugin/package.xml b/rviz_carla_plugin/package.xml new file mode 100644 index 00000000..c1a0d791 --- /dev/null +++ b/rviz_carla_plugin/package.xml @@ -0,0 +1,26 @@ + + + rviz_carla_plugin + 0.0.1 + The carla_ros_bridge package + CARLA Simulator Team + MIT + catkin + qtbase5-dev + rviz + carla_msgs + nav_msgs + geometry_msgs + carla_ros_scenario_runner_types + carla_msgs + nav_msgs + geometry_msgs + carla_ros_scenario_runner_types + libqt5-core + libqt5-gui + libqt5-widgets + rviz + + + + diff --git a/rviz_carla_plugin/plugin_description.xml b/rviz_carla_plugin/plugin_description.xml new file mode 100644 index 00000000..42f236a3 --- /dev/null +++ b/rviz_carla_plugin/plugin_description.xml @@ -0,0 +1,9 @@ + + + + A panel widget for controlling carla nodes + + + diff --git a/rviz_carla_plugin/rviz_carla_plugin.qrc b/rviz_carla_plugin/rviz_carla_plugin.qrc new file mode 100644 index 00000000..1ebe3370 --- /dev/null +++ b/rviz_carla_plugin/rviz_carla_plugin.qrc @@ -0,0 +1,7 @@ + + + icons/play.png + icons/pause.png + icons/step_once.png + + \ No newline at end of file diff --git a/rviz_carla_plugin/src/carla_control_panel.cpp b/rviz_carla_plugin/src/carla_control_panel.cpp new file mode 100644 index 00000000..ce436946 --- /dev/null +++ b/rviz_carla_plugin/src/carla_control_panel.cpp @@ -0,0 +1,411 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include "carla_control_panel.h" +#include "drive_widget.h" +#include "indicator_widget.h" + +namespace rviz_carla_plugin { + +CarlaControlPanel::CarlaControlPanel(QWidget *parent) + : rviz::Panel(parent) +{ + QVBoxLayout *layout = new QVBoxLayout; + QHBoxLayout *vehicleLayout = new QHBoxLayout; + + QFormLayout *egoCtrlStatusLayout = new QFormLayout; + + mThrottleBar = new QProgressBar(); + mThrottleBar->setRange(0, 100); + egoCtrlStatusLayout->addRow("Throttle", mThrottleBar); + mBrakeBar = new QProgressBar(); + mBrakeBar->setRange(0, 100); + egoCtrlStatusLayout->addRow("Brake", mBrakeBar); + mSteerBar = new QProgressBar(); + mSteerBar->setRange(-100, 100); + egoCtrlStatusLayout->addRow("Steer", mSteerBar); + vehicleLayout->addLayout(egoCtrlStatusLayout); + + QFormLayout *egoStatusLayout = new QFormLayout; + mPosLabel = new QLineEdit(); + mPosLabel->setDisabled(true); + egoStatusLayout->addRow("Position", mPosLabel); + + mSpeedLabel = new QLineEdit(); + mSpeedLabel->setDisabled(true); + egoStatusLayout->addRow("Speed", mSpeedLabel); + + mHeadingLabel = new QLineEdit(); + mHeadingLabel->setDisabled(true); + egoStatusLayout->addRow("Heading", mHeadingLabel); + + vehicleLayout->addLayout(egoStatusLayout); + + QVBoxLayout *egoCtrlLayout = new QVBoxLayout; + mOverrideVehicleControl = new QCheckBox("Manual control"); + mOverrideVehicleControl->setDisabled(true); + egoCtrlLayout->addWidget(mOverrideVehicleControl); + mDriveWidget = new DriveWidget; + mDriveWidget->setDisabled(true); + egoCtrlLayout->addWidget(mDriveWidget); + connect(mOverrideVehicleControl, SIGNAL(stateChanged(int)), this, SLOT(overrideVehicleControl(int))); + + vehicleLayout->addLayout(egoCtrlLayout); + + layout->addLayout(vehicleLayout); + + QFormLayout *carlaLayout = new QFormLayout; + + // row1 + QHBoxLayout *carlaRow1Layout = new QHBoxLayout; + + mScenarioSelection = new QComboBox(); + carlaRow1Layout->addWidget(mScenarioSelection, 10); + + mTriggerScenarioButton = new QPushButton("Execute"); + carlaRow1Layout->addWidget(mTriggerScenarioButton); + + mIndicatorWidget = new IndicatorWidget(); + carlaRow1Layout->addWidget(mIndicatorWidget); + connect(mTriggerScenarioButton, SIGNAL(released()), this, SLOT(executeScenario())); + + carlaLayout->addRow("Scenario Execution", carlaRow1Layout); + + QHBoxLayout *synchronous_layout = new QHBoxLayout; + QPixmap pixmap(":/icons/play.png"); + QIcon iconPlay(pixmap); + mPlayPauseButton = new QPushButton(iconPlay, ""); + synchronous_layout->addWidget(mPlayPauseButton); + connect(mPlayPauseButton, SIGNAL(released()), this, SLOT(carlaTogglePlayPause())); + + QPixmap pixmapStepOnce(":/icons/step_once.png"); + QIcon iconStepOnce(pixmapStepOnce); + mStepOnceButton = new QPushButton(iconStepOnce, ""); + connect(mStepOnceButton, SIGNAL(released()), this, SLOT(carlaStepOnce())); + + synchronous_layout->addWidget(mStepOnceButton); + carlaLayout->addRow("Carla Control", synchronous_layout); + + layout->addLayout(carlaLayout); + + setLayout(layout); + + QTimer *outputTimer = new QTimer(this); + connect(outputTimer, SIGNAL(timeout()), this, SLOT(sendVel())); + outputTimer->start(100); + + connect(mDriveWidget, SIGNAL(outputVelocity(float, float)), this, SLOT(setVel(float, float))); + mDriveWidget->setEnabled(false); + + setSimulationButtonStatus(false); + setScenarioRunnerStatus(false); + + mCarlaStatusSubscriber = mNodeHandle.subscribe("/carla/status", 1000, &CarlaControlPanel::carlaStatusChanged, this); + mCarlaControlPublisher = mNodeHandle.advertise("/carla/control", 10); + mEgoVehicleStatusSubscriber = mNodeHandle.subscribe( + "/carla/ego_vehicle/vehicle_status", 1000, &CarlaControlPanel::egoVehicleStatusChanged, this); + mEgoVehicleOdometrySubscriber + = mNodeHandle.subscribe("/carla/ego_vehicle/odometry", 1000, &CarlaControlPanel::egoVehicleOdometryChanged, this); + + mCameraPosePublisher + = mNodeHandle.advertise("carla/ego_vehicle/spectator_pose", 10, true); + + mEgoVehicleControlManualOverridePublisher + = mNodeHandle.advertise("/carla/ego_vehicle/vehicle_control_manual_override", 1, true); + + mExecuteScenarioClient + = mNodeHandle.serviceClient("/scenario_runner/execute_scenario"); + mScenarioRunnerStatusSubscriber + = mNodeHandle.subscribe("/scenario_runner/status", 10, &CarlaControlPanel::scenarioRunnerStatusChanged, this); + + mTwistPublisher = mNodeHandle.advertise("/carla/ego_vehicle/twist", 1); + + mScenarioSubscriber + = mNodeHandle.subscribe("/carla/available_scenarios", 1, &CarlaControlPanel::carlaScenariosChanged, this); + + // //initially set the camera + QTimer::singleShot(1000, this, SLOT(updateCameraPos())); +} + +void CarlaControlPanel::cameraPreRenderScene(Ogre::Camera *cam) +{ + double epsilon = 0.001; + if ((std::fabs(cam->getPosition().x - mCameraCurrentPosition.x) > epsilon) + || (std::fabs(cam->getPosition().y - mCameraCurrentPosition.y) > epsilon) + || (std::fabs(cam->getPosition().z - mCameraCurrentPosition.z) > epsilon) + || (std::fabs(cam->getOrientation().x - mCameraCurrentOrientation.x) > epsilon) + || (std::fabs(cam->getOrientation().y - mCameraCurrentOrientation.y) > epsilon) + || (std::fabs(cam->getOrientation().z - mCameraCurrentOrientation.z) > epsilon) + || (std::fabs(cam->getOrientation().w - mCameraCurrentOrientation.w) > epsilon)) + { + mCameraCurrentPosition = cam->getPosition(); + mCameraCurrentOrientation = cam->getOrientation(); + QTimer::singleShot(0, this, SLOT(updateCameraPos())); + } +} + +void CarlaControlPanel::updateCameraPos() +{ + auto frame = mViewController->subProp("Target Frame")->getValue(); + + geometry_msgs::PoseStamped pose; + pose.header.frame_id = frame.toString().toStdString(); + pose.header.stamp = ros::Time::now(); + pose.pose.position.x = mCameraCurrentPosition.x; + pose.pose.position.y = mCameraCurrentPosition.y; + pose.pose.position.z = mCameraCurrentPosition.z; + pose.pose.orientation.x = mCameraCurrentOrientation.x; + pose.pose.orientation.y = mCameraCurrentOrientation.y; + pose.pose.orientation.z = mCameraCurrentOrientation.z; + pose.pose.orientation.w = mCameraCurrentOrientation.w; + + mCameraPosePublisher.publish(pose); +} + +void CarlaControlPanel::onInitialize() +{ + currentViewControllerChanged(); + connect(vis_manager_->getViewManager(), SIGNAL(currentChanged()), this, SLOT(currentViewControllerChanged())); +} + +void CarlaControlPanel::currentViewControllerChanged() +{ + mViewController + = dynamic_cast(vis_manager_->getViewManager()->getCurrent()); + if (!mViewController) + { + ROS_ERROR("Invalid view controller!"); + return; + } + + auto camera = mViewController->getCamera(); + camera->addListener(this); +} + +void CarlaControlPanel::executeScenario() +{ + for (auto const &scenario : mCarlaScenarios->scenarios) + { + if (QString::fromStdString(scenario.name) == mScenarioSelection->currentText()) + { + carla_ros_scenario_runner_types::ExecuteScenario srv; + srv.request.scenario = scenario; + if (!mExecuteScenarioClient.call(srv)) + { + ROS_ERROR("Failed to call service executeScenario"); + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } + break; + } + } +} + +void CarlaControlPanel::overrideVehicleControl(int state) +{ + std_msgs::Bool boolMsg; + if (state == Qt::Checked) + { + boolMsg.data = true; + mDriveWidget->setEnabled(true); + } + else + { + boolMsg.data = false; + mDriveWidget->setEnabled(false); + } + mEgoVehicleControlManualOverridePublisher.publish(boolMsg); +} + +void CarlaControlPanel::scenarioRunnerStatusChanged( + const carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::ConstPtr &msg) +{ + if (msg->status == carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::STOPPED) + { + mIndicatorWidget->setState(IndicatorWidget::State::Stopped); + } + else if (msg->status == carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::STARTING) + { + mIndicatorWidget->setState(IndicatorWidget::State::Starting); + } + else if (msg->status == carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::RUNNING) + { + mIndicatorWidget->setState(IndicatorWidget::State::Running); + } + else if (msg->status == carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::SHUTTINGDOWN) + { + mIndicatorWidget->setState(IndicatorWidget::State::ShuttingDown); + } + else + { + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } +} + +void CarlaControlPanel::setScenarioRunnerStatus(bool active) +{ + mScenarioSelection->setEnabled(active); + mTriggerScenarioButton->setEnabled(active); + mIndicatorWidget->setEnabled(active); +} + +void CarlaControlPanel::carlaScenariosChanged(const carla_ros_scenario_runner_types::CarlaScenarioList::ConstPtr &msg) +{ + auto currentSelection = mScenarioSelection->currentText(); + mCarlaScenarios = msg; + mScenarioSelection->clear(); + int idx = 0; + for (auto const &scenario : msg->scenarios) + { + auto name = QString::fromStdString(scenario.name); + mScenarioSelection->addItem(name); + if (name == currentSelection) + { // switch to previously selected item + mScenarioSelection->setCurrentIndex(idx); + } + ++idx; + } + setScenarioRunnerStatus(mScenarioSelection->count() > 0); +} + +void CarlaControlPanel::egoVehicleStatusChanged(const carla_msgs::CarlaEgoVehicleStatus::ConstPtr &msg) +{ + mOverrideVehicleControl->setEnabled(true); + mSteerBar->setValue(msg->control.steer * 100); + mThrottleBar->setValue(msg->control.throttle * 100); + mBrakeBar->setValue(msg->control.brake * 100); + + std::stringstream speedStream; + speedStream << std::fixed << std::setprecision(2) << msg->velocity * 3.6; + mSpeedLabel->setText(speedStream.str().c_str()); +} + +void CarlaControlPanel::egoVehicleOdometryChanged(const nav_msgs::Odometry::ConstPtr &msg) +{ + std::stringstream posStream; + posStream << std::fixed << std::setprecision(2) << msg->pose.pose.position.x << ", " << msg->pose.pose.position.y; + mPosLabel->setText(posStream.str().c_str()); + + std::stringstream headingStream; + headingStream << std::fixed << std::setprecision(2) << tf::getYaw(msg->pose.pose.orientation); + mHeadingLabel->setText(headingStream.str().c_str()); +} + +void CarlaControlPanel::setSimulationButtonStatus(bool active) +{ + if (active) + { + mPlayPauseButton->setDisabled(false); + mPlayPauseButton->setToolTip("Play/Pause the CARLA world."); + mStepOnceButton->setDisabled(false); + mStepOnceButton->setToolTip("Execute on tick within the CARLA world."); + } + else + { + mPlayPauseButton->setDisabled(true); + mPlayPauseButton->setToolTip("Disabled due to CARLA running in non-synchronous mode."); + mStepOnceButton->setDisabled(true); + mStepOnceButton->setToolTip("Disabled due to CARLA running in non-synchronous mode."); + } +} + +void CarlaControlPanel::carlaStatusChanged(const carla_msgs::CarlaStatus::ConstPtr &msg) +{ + mCarlaStatus = msg; + setSimulationButtonStatus(mCarlaStatus->synchronous_mode); + + if (mCarlaStatus->synchronous_mode) + { + if (mCarlaStatus->synchronous_mode_running) + { + QPixmap pixmap(":/icons/pause.png"); + QIcon iconPause(pixmap); + mPlayPauseButton->setIcon(iconPause); + } + else + { + QPixmap pixmap(":/icons/play.png"); + QIcon iconPlay(pixmap); + mPlayPauseButton->setIcon(iconPlay); + } + } +} + +void CarlaControlPanel::carlaStepOnce() +{ + carla_msgs::CarlaControl ctrl; + ctrl.command = carla_msgs::CarlaControl::STEP_ONCE; + mCarlaControlPublisher.publish(ctrl); +} + +void CarlaControlPanel::carlaTogglePlayPause() +{ + if (mCarlaStatus) + { + carla_msgs::CarlaControl ctrl; + if (mCarlaStatus->synchronous_mode_running) + { + ctrl.command = carla_msgs::CarlaControl::PAUSE; + } + else + { + ctrl.command = carla_msgs::CarlaControl::PLAY; + } + mCarlaControlPublisher.publish(ctrl); + } +} + +void CarlaControlPanel::setVel(float linearVelocity, float angularVelocity) +{ + mLinearVelocity = linearVelocity; + mAngularVelocity = angularVelocity; +} + +void CarlaControlPanel::sendVel() +{ + if (ros::ok() && mTwistPublisher && (mOverrideVehicleControl->checkState() == Qt::Checked)) + { + geometry_msgs::Twist msg; + msg.linear.x = mLinearVelocity; + msg.linear.y = 0; + msg.linear.z = 0; + msg.angular.x = 0; + msg.angular.y = 0; + msg.angular.z = mAngularVelocity; + mTwistPublisher.publish(msg); + } +} + +} // end namespace rviz_carla_plugin + +#include +PLUGINLIB_EXPORT_CLASS(rviz_carla_plugin::CarlaControlPanel, rviz::Panel) diff --git a/rviz_carla_plugin/src/carla_control_panel.h b/rviz_carla_plugin/src/carla_control_panel.h new file mode 100644 index 00000000..646b96dd --- /dev/null +++ b/rviz_carla_plugin/src/carla_control_panel.h @@ -0,0 +1,104 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +class QLineEdit; +class QPushButton; +class QProgressBar; +class QCheckBox; +class QComboBox; + +namespace rviz { +class ViewController; +class FramePositionTrackingViewController; +} + +namespace rviz_carla_plugin { + +class DriveWidget; +class IndicatorWidget; + +class CarlaControlPanel : public rviz::Panel, public Ogre::Camera::Listener +{ + Q_OBJECT +public: + CarlaControlPanel(QWidget *parent = 0); + +public Q_SLOTS: + void setVel(float linearVelocity, float angularVelocity); + +protected Q_SLOTS: + void sendVel(); + + void carlaStepOnce(); + void carlaTogglePlayPause(); + void overrideVehicleControl(int state); + void executeScenario(); + + void updateCameraPos(); + void currentViewControllerChanged(); + +protected: + virtual void cameraPreRenderScene(Ogre::Camera *cam) override; + + virtual void onInitialize() override; + void setSimulationButtonStatus(bool active); + void setScenarioRunnerStatus(bool active); + + void scenarioRunnerStatusChanged(const carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::ConstPtr &msg); + void carlaStatusChanged(const carla_msgs::CarlaStatus::ConstPtr &msg); + void egoVehicleStatusChanged(const carla_msgs::CarlaEgoVehicleStatus::ConstPtr &msg); + void egoVehicleOdometryChanged(const nav_msgs::Odometry::ConstPtr &msg); + void carlaScenariosChanged(const carla_ros_scenario_runner_types::CarlaScenarioList::ConstPtr &msg); + carla_msgs::CarlaStatus::ConstPtr mCarlaStatus{nullptr}; + + DriveWidget *mDriveWidget; + QPushButton *mTriggerScenarioButton; + QPushButton *mPlayPauseButton; + QPushButton *mStepOnceButton; + QProgressBar *mThrottleBar; + QProgressBar *mBrakeBar; + QProgressBar *mSteerBar; + QLineEdit *mPosLabel; + QLineEdit *mSpeedLabel; + QLineEdit *mHeadingLabel; + QCheckBox *mOverrideVehicleControl; + QComboBox *mScenarioSelection; + IndicatorWidget *mIndicatorWidget; + ros::Publisher mTwistPublisher; + ros::Publisher mCarlaControlPublisher; + ros::Publisher mEgoVehicleControlManualOverridePublisher; + ros::Subscriber mCarlaStatusSubscriber; + ros::Subscriber mEgoVehicleStatusSubscriber; + ros::Subscriber mEgoVehicleOdometrySubscriber; + ros::ServiceClient mExecuteScenarioClient; + ros::Subscriber mScenarioSubscriber; + ros::Subscriber mScenarioRunnerStatusSubscriber; + ros::Publisher mCameraPosePublisher; + + carla_ros_scenario_runner_types::CarlaScenarioList::ConstPtr mCarlaScenarios; + + ros::NodeHandle mNodeHandle; + + float mLinearVelocity{0.0}; + float mAngularVelocity{0.0}; + bool mVehicleControlManualOverride{false}; + rviz::FramePositionTrackingViewController *mViewController{nullptr}; + Ogre::Vector3 mCameraCurrentPosition; + Ogre::Quaternion mCameraCurrentOrientation; +}; + +} // end namespace rviz_carla_plugin diff --git a/rviz_carla_plugin/src/drive_widget.cpp b/rviz_carla_plugin/src/drive_widget.cpp new file mode 100644 index 00000000..2de48ac2 --- /dev/null +++ b/rviz_carla_plugin/src/drive_widget.cpp @@ -0,0 +1,249 @@ +/* + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +#include +#include + +#include "drive_widget.h" + +namespace rviz_carla_plugin { + +// BEGIN_TUTORIAL +// The DriveWidget constructor does the normal Qt thing of +// passing the parent widget to the superclass constructor, then +// initializing the member variables. +DriveWidget::DriveWidget(QWidget *parent) + : QWidget(parent) + , linear_velocity_(0) + , angular_velocity_(0) + , linear_scale_(10) + , angular_scale_(.2) +{ +} + +// This paintEvent() is complex because of the drawing of the two +// arc-arrows representing wheel motion. It is not particularly +// relevant to learning how to make an RViz plugin, so I will kind of +// skim it. +void DriveWidget::paintEvent(QPaintEvent *event) +{ + // The background color and crosshair lines are drawn differently + // depending on whether this widget is enabled or not. This gives a + // nice visual indication of whether the control is "live". + QColor background; + QColor crosshair; + if (isEnabled()) + { + background = Qt::white; + crosshair = Qt::black; + } + else + { + background = Qt::lightGray; + crosshair = Qt::darkGray; + } + + // The main visual is a square, centered in the widget's area. Here + // we compute the size of the square and the horizontal and vertical + // offsets of it. + int w = width(); + int h = height(); + int size = ((w > h) ? h : w) - 1; + int hpad = (w - size) / 2; + int vpad = (h - size) / 2; + + QPainter painter(this); + painter.setBrush(background); + painter.setPen(crosshair); + + // Draw the background square. + painter.drawRect(QRect(hpad, vpad, size, size)); + + // Draw a cross-hair inside the square. + painter.drawLine(hpad, height() / 2, hpad + size, height() / 2); + painter.drawLine(width() / 2, vpad, width() / 2, vpad + size); + + // If the widget is enabled and the velocities are not zero, draw + // some sweet green arrows showing possible paths that the wheels of + // a diff-drive robot would take if it stayed at these velocities. + if (isEnabled() && (angular_velocity_ != 0 || linear_velocity_ != 0)) + { + QPen arrow; + arrow.setWidth(size / 20); + arrow.setColor(Qt::green); + arrow.setCapStyle(Qt::RoundCap); + arrow.setJoinStyle(Qt::RoundJoin); + painter.setPen(arrow); + + // This code steps along a central arc defined by the linear and + // angular velocites. At each step, it computes where the left + // and right wheels would be and collects the resulting points + // in the left_track and right_track arrays. + const int step_count = 100; + QPointF left_track[step_count]; + QPointF right_track[step_count]; + + float half_track_width = size / 4.0; + + float cx = w / 2; + float cy = h / 2; + left_track[0].setX(cx - half_track_width); + left_track[0].setY(cy); + right_track[0].setX(cx + half_track_width); + right_track[0].setY(cy); + float angle = M_PI / 2; + float delta_angle = angular_velocity_ / step_count; + float step_dist = linear_velocity_ * size / 2 / linear_scale_ / step_count; + for (int step = 1; step < step_count; step++) + { + angle += delta_angle / 2; + float next_cx = cx + step_dist * cosf(angle); + float next_cy = cy - step_dist * sinf(angle); + angle += delta_angle / 2; + + left_track[step].setX(next_cx + half_track_width * cosf(angle + M_PI / 2)); + left_track[step].setY(next_cy - half_track_width * sinf(angle + M_PI / 2)); + right_track[step].setX(next_cx + half_track_width * cosf(angle - M_PI / 2)); + right_track[step].setY(next_cy - half_track_width * sinf(angle - M_PI / 2)); + + cx = next_cx; + cy = next_cy; + } + // Now the track arrays are filled, so stroke each with a fat green line. + painter.drawPolyline(left_track, step_count); + painter.drawPolyline(right_track, step_count); + + // Here we decide which direction each arrowhead will point + // (forward or backward). This works by comparing the arc length + // travelled by the center in one step (step_dist) with the arc + // length travelled by the wheel (half_track_width * delta_angle). + int left_arrow_dir = (-step_dist + half_track_width * delta_angle > 0); + int right_arrow_dir = (-step_dist - half_track_width * delta_angle > 0); + + // Use MiterJoin for the arrowheads so we get a nice sharp point. + arrow.setJoinStyle(Qt::MiterJoin); + painter.setPen(arrow); + + // Compute and draw polylines for each arrowhead. This code could + // probably be more elegant. + float head_len = size / 8.0; + QPointF arrow_head[3]; + float x, y; + if (fabsf(-step_dist + half_track_width * delta_angle) > .01) + { + x = left_track[step_count - 1].x(); + y = left_track[step_count - 1].y(); + arrow_head[0].setX(x + head_len * cosf(angle + 3 * M_PI / 4 + left_arrow_dir * M_PI)); + arrow_head[0].setY(y - head_len * sinf(angle + 3 * M_PI / 4 + left_arrow_dir * M_PI)); + arrow_head[1].setX(x); + arrow_head[1].setY(y); + arrow_head[2].setX(x + head_len * cosf(angle - 3 * M_PI / 4 + left_arrow_dir * M_PI)); + arrow_head[2].setY(y - head_len * sinf(angle - 3 * M_PI / 4 + left_arrow_dir * M_PI)); + painter.drawPolyline(arrow_head, 3); + } + if (fabsf(-step_dist - half_track_width * delta_angle) > .01) + { + x = right_track[step_count - 1].x(); + y = right_track[step_count - 1].y(); + arrow_head[0].setX(x + head_len * cosf(angle + 3 * M_PI / 4 + right_arrow_dir * M_PI)); + arrow_head[0].setY(y - head_len * sinf(angle + 3 * M_PI / 4 + right_arrow_dir * M_PI)); + arrow_head[1].setX(x); + arrow_head[1].setY(y); + arrow_head[2].setX(x + head_len * cosf(angle - 3 * M_PI / 4 + right_arrow_dir * M_PI)); + arrow_head[2].setY(y - head_len * sinf(angle - 3 * M_PI / 4 + right_arrow_dir * M_PI)); + painter.drawPolyline(arrow_head, 3); + } + } +} + +// Every mouse move event received here sends a velocity because Qt +// only sends us mouse move events if there was previously a +// mouse-press event while in the widget. +void DriveWidget::mouseMoveEvent(QMouseEvent *event) +{ + sendVelocitiesFromMouse(event->x(), event->y(), width(), height()); +} + +// Mouse-press events should send the velocities too, of course. +void DriveWidget::mousePressEvent(QMouseEvent *event) +{ + sendVelocitiesFromMouse(event->x(), event->y(), width(), height()); +} + +// When the mouse leaves the widget but the button is still held down, +// we don't get the leaveEvent() because the mouse is "grabbed" (by +// default from Qt). However, when the mouse drags out of the widget +// and then other buttons are pressed (or possibly other +// window-manager things happen), we will get a leaveEvent() but not a +// mouseReleaseEvent(). Without catching this event you can have a +// robot stuck "on" without the user controlling it. +void DriveWidget::leaveEvent(QEvent *event) +{ + stop(); +} + +// The ordinary way to stop: let go of the mouse button. +void DriveWidget::mouseReleaseEvent(QMouseEvent *event) +{ + stop(); +} + +// Compute and emit linear and angular velocities based on Y and X +// mouse positions relative to the central square. +void DriveWidget::sendVelocitiesFromMouse(int x, int y, int width, int height) +{ + int size = ((width > height) ? height : width); + int hpad = (width - size) / 2; + int vpad = (height - size) / 2; + + linear_velocity_ = (1.0 - float(y - vpad) / float(size / 2)) * linear_scale_; + angular_velocity_ = (1.0 - float(x - hpad) / float(size / 2)) * angular_scale_; + Q_EMIT outputVelocity(linear_velocity_, angular_velocity_); + + // update() is a QWidget function which schedules this widget to be + // repainted the next time through the main event loop. We need + // this because the velocities have just changed, so the arrows need + // to be redrawn to match. + update(); +} + +// How to stop: emit velocities of 0! +void DriveWidget::stop() +{ + linear_velocity_ = 0; + angular_velocity_ = 0; + Q_EMIT outputVelocity(linear_velocity_, angular_velocity_); + update(); +} +// END_TUTORIAL + +} // end namespace rviz_carla_plugin diff --git a/rviz_carla_plugin/src/drive_widget.h b/rviz_carla_plugin/src/drive_widget.h new file mode 100644 index 00000000..e0a6c7d0 --- /dev/null +++ b/rviz_carla_plugin/src/drive_widget.h @@ -0,0 +1,91 @@ +/* + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef DRIVE_WIDGET_H +#define DRIVE_WIDGET_H + +#include + +namespace rviz_carla_plugin { + +// BEGIN_TUTORIAL +// DriveWidget implements a control which translates mouse Y values +// into linear velocities and mouse X values into angular velocities. +// +// For maximum reusability, this class is only responsible for user +// interaction and display inside its widget. It does not make any +// ROS or RViz calls. It communicates its data to the outside just +// via Qt signals. +class DriveWidget : public QWidget +{ + Q_OBJECT +public: + // This class is not instantiated by pluginlib::ClassLoader, so the + // constructor has no restrictions. + DriveWidget(QWidget *parent = 0); + + // We override QWidget::paintEvent() to do custom painting. + virtual void paintEvent(QPaintEvent *event); + + // We override the mouse events and leaveEvent() to keep track of + // what the mouse is doing. + virtual void mouseMoveEvent(QMouseEvent *event); + virtual void mousePressEvent(QMouseEvent *event); + virtual void mouseReleaseEvent(QMouseEvent *event); + virtual void leaveEvent(QEvent *event); + + // Override sizeHint() to give the layout managers some idea of a + // good size for this. + virtual QSize sizeHint() const + { + return QSize(150, 150); + } + + // We emit outputVelocity() whenever it changes. +Q_SIGNALS: + void outputVelocity(float linear, float angular); + + // mouseMoveEvent() and mousePressEvent() need the same math to + // figure the velocities, so I put that in here. +protected: + void sendVelocitiesFromMouse(int x, int y, int width, int height); + + // A function to emit zero velocity. + void stop(); + + // Finally the member variables: + float linear_velocity_; // In m/s + float angular_velocity_; // In radians/s + float linear_scale_; // In m/s + float angular_scale_; // In radians/s +}; +// END_TUTORIAL + +} // end namespace rviz_carla_plugin + +#endif // DRIVE_WIDGET_H diff --git a/rviz_carla_plugin/src/indicator_widget.cpp b/rviz_carla_plugin/src/indicator_widget.cpp new file mode 100644 index 00000000..ae160a42 --- /dev/null +++ b/rviz_carla_plugin/src/indicator_widget.cpp @@ -0,0 +1,53 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include "indicator_widget.h" +#include + +namespace rviz_carla_plugin { + +IndicatorWidget::IndicatorWidget(QWidget *parent) + : QWidget(parent) + , mCurrentState(IndicatorWidget::State::Stopped) +{ + setFixedSize(18, 18); +} + +void IndicatorWidget::paintEvent(QPaintEvent *event) +{ + QPainter painter(this); + painter.setPen(Qt::darkGray); + if (mCurrentState == IndicatorWidget::State::Stopped) + { + painter.setBrush(QBrush(Qt::lightGray, Qt::SolidPattern)); + } + else if (mCurrentState == IndicatorWidget::State::Running) + { + painter.setBrush(QBrush(Qt::green, Qt::SolidPattern)); + } + else if (mCurrentState == IndicatorWidget::State::Error) + { + painter.setBrush(QBrush(Qt::red, Qt::SolidPattern)); + } + else if ((mCurrentState == IndicatorWidget::State::Starting) + || (mCurrentState == IndicatorWidget::State::ShuttingDown)) + { + painter.setBrush(QBrush(Qt::yellow, Qt::SolidPattern)); + } + else + { + painter.setBrush(QBrush(Qt::black, Qt::SolidPattern)); + } + painter.drawEllipse(1, 1, 16, 16); +} + +void IndicatorWidget::setState(IndicatorWidget::State state) +{ + mCurrentState = state; + repaint(); +} + +} // end namespace rviz_carla_plugin diff --git a/rviz_carla_plugin/src/indicator_widget.h b/rviz_carla_plugin/src/indicator_widget.h new file mode 100644 index 00000000..2d5ea19f --- /dev/null +++ b/rviz_carla_plugin/src/indicator_widget.h @@ -0,0 +1,36 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#pragma once + +#include + +namespace rviz_carla_plugin { + +class IndicatorWidget : public QWidget +{ + Q_OBJECT +public: + enum class State + { + Stopped, + Starting, + Running, + ShuttingDown, + Error + }; + + IndicatorWidget(QWidget *parent = 0); + + virtual void paintEvent(QPaintEvent *event) override; + + void setState(IndicatorWidget::State state); + +private: + State mCurrentState{State::Stopped}; +}; + +} // end namespace rviz_carla_plugin From 8e468ca878de6c2ff740de0acb7d85ba3eaec104 Mon Sep 17 00:00:00 2001 From: Bruno Brito Date: Wed, 4 Mar 2020 09:51:55 +0100 Subject: [PATCH 027/627] fix vehicle reset (#235) * fix vehicle reset * removing not related file * needed to fix the reset * Merge branch 'master' into fix_reset * sensor bug fixd * stopping before reseting * change to stop command * returning to previous reset * implementing comment requested on review * Merge branch 'master' into fix_reset --- .../carla_ego_vehicle/carla_ego_vehicle.py | 31 ++++++++++++------- .../carla_manual_control.py | 1 + 2 files changed, 20 insertions(+), 12 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index a17ef783..bd983457 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -52,6 +52,7 @@ def __init__(self): self.sensor_definition_file = rospy.get_param('~sensor_definition_file') self.world = None self.player = None + self.player_created = False self.sensor_actors = [] self.actor_filter = rospy.get_param('~vehicle_filter', 'vehicle.*') self.actor_spawnpoint = None @@ -138,33 +139,39 @@ def restart(self): spawn_point.location.z, spawn_point.rotation.yaw)) if self.player is not None: - self.destroy() + self.player.set_transform(spawn_point) while self.player is None: self.player = self.world.try_spawn_actor(blueprint, spawn_point) + self.player_created = True + else: if self.player is not None: spawn_point = self.player.get_transform() spawn_point.location.z += 2.0 spawn_point.rotation.roll = 0.0 spawn_point.rotation.pitch = 0.0 - self.destroy() - self.player = self.world.try_spawn_actor(blueprint, spawn_point) + self.player.set_transform(spawn_point) while self.player is None: spawn_points = self.world.get_map().get_spawn_points() spawn_point = secure_random.choice( spawn_points) if spawn_points else carla.Transform() self.player = self.world.try_spawn_actor(blueprint, spawn_point) + self.player_created = True + + if self.player_created: + # Read sensors from file + if not os.path.exists(self.sensor_definition_file): + raise RuntimeError( + "Could not read sensor-definition from {}".format(self.sensor_definition_file)) + json_sensors = None + with open(self.sensor_definition_file) as handle: + json_sensors = json.loads(handle.read()) + + # Set up the sensors + self.sensor_actors = self.setup_sensors(json_sensors["sensors"]) - # Read sensors from file - if not os.path.exists(self.sensor_definition_file): - raise RuntimeError( - "Could not read sensor-definition from {}".format(self.sensor_definition_file)) - json_sensors = None - with open(self.sensor_definition_file) as handle: - json_sensors = json.loads(handle.read()) + self.player_created = False - # Set up the sensors - self.sensor_actors = self.setup_sensors(json_sensors["sensors"]) def setup_sensors(self, sensors): """ diff --git a/carla_manual_control/src/carla_manual_control/carla_manual_control.py b/carla_manual_control/src/carla_manual_control/carla_manual_control.py index 5b59ace7..ebf2dddc 100755 --- a/carla_manual_control/src/carla_manual_control/carla_manual_control.py +++ b/carla_manual_control/src/carla_manual_control/carla_manual_control.py @@ -468,6 +468,7 @@ def render(self, display): rect = pygame.Rect( (bar_h_offset + f * (bar_width - 6), v_offset + 8), (6, 6)) else: + f = 0.0 rect = pygame.Rect((bar_h_offset, v_offset + 8), (f * bar_width, 6)) pygame.draw.rect(display, (255, 255, 255), rect) item = item[0] From 729056aa9ab2251bf6e1571a43ae507091bde114 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 4 Mar 2020 09:55:48 +0100 Subject: [PATCH 028/627] code cleanup --- carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py index bd983457..c7b12eba 100755 --- a/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py +++ b/carla_ego_vehicle/src/carla_ego_vehicle/carla_ego_vehicle.py @@ -163,7 +163,7 @@ def restart(self): if not os.path.exists(self.sensor_definition_file): raise RuntimeError( "Could not read sensor-definition from {}".format(self.sensor_definition_file)) - json_sensors = None + json_sensors = None with open(self.sensor_definition_file) as handle: json_sensors = json.loads(handle.read()) @@ -172,7 +172,6 @@ def restart(self): self.player_created = False - def setup_sensors(self, sensors): """ Create the sensors defined by the user and attach them to the ego-vehicle From 4edcf0e5ff74885af552b4d7970eceb94a74e1cd Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 4 Mar 2020 10:07:58 +0100 Subject: [PATCH 029/627] Fix carla_ros_bridge timeout unit --- carla_ros_bridge/src/carla_ros_bridge/bridge.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/carla_ros_bridge/src/carla_ros_bridge/bridge.py b/carla_ros_bridge/src/carla_ros_bridge/bridge.py index 2b7b88b6..4da77024 100755 --- a/carla_ros_bridge/src/carla_ros_bridge/bridge.py +++ b/carla_ros_bridge/src/carla_ros_bridge/bridge.py @@ -498,7 +498,7 @@ def main(): carla_client = carla.Client( host=parameters['host'], port=parameters['port']) - carla_client.set_timeout(2000) + carla_client.set_timeout(2.0) carla_world = carla_client.get_world() From 1f28c426b3a45fbca16d35d448fd83de16495606 Mon Sep 17 00:00:00 2001 From: himanshugoswami <41889803+himanshugoswami@users.noreply.github.com> Date: Wed, 11 Mar 2020 17:15:01 +0530 Subject: [PATCH 030/627] Include carla_msgs submodule from carla-simulator/ros-carla-msgs (#242) * Add ros-carla-msgs as submodule --- .gitmodules | 4 ++ README.md | 37 ++++++++++++++-- carla_msgs | 1 + carla_msgs/CMakeLists.txt | 42 ------------------- carla_msgs/msg/CarlaActorInfo.msg | 12 ------ carla_msgs/msg/CarlaActorList.msg | 9 ---- carla_msgs/msg/CarlaCollisionEvent.msg | 12 ------ carla_msgs/msg/CarlaControl.msg | 13 ------ carla_msgs/msg/CarlaEgoVehicleControl.msg | 32 -------------- carla_msgs/msg/CarlaEgoVehicleInfo.msg | 22 ---------- carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg | 13 ------ carla_msgs/msg/CarlaEgoVehicleStatus.msg | 15 ------- carla_msgs/msg/CarlaLaneInvasionEvent.msg | 16 ------- carla_msgs/msg/CarlaStatus.msg | 12 ------ carla_msgs/msg/CarlaTrafficLightStatus.msg | 15 ------- .../msg/CarlaTrafficLightStatusList.msg | 7 ---- carla_msgs/msg/CarlaWalkerControl.msg | 11 ----- carla_msgs/msg/CarlaWorldInfo.msg | 9 ---- carla_msgs/package.xml | 15 ------- 19 files changed, 39 insertions(+), 258 deletions(-) create mode 100644 .gitmodules create mode 160000 carla_msgs delete mode 100644 carla_msgs/CMakeLists.txt delete mode 100644 carla_msgs/msg/CarlaActorInfo.msg delete mode 100644 carla_msgs/msg/CarlaActorList.msg delete mode 100644 carla_msgs/msg/CarlaCollisionEvent.msg delete mode 100644 carla_msgs/msg/CarlaControl.msg delete mode 100644 carla_msgs/msg/CarlaEgoVehicleControl.msg delete mode 100644 carla_msgs/msg/CarlaEgoVehicleInfo.msg delete mode 100644 carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg delete mode 100644 carla_msgs/msg/CarlaEgoVehicleStatus.msg delete mode 100644 carla_msgs/msg/CarlaLaneInvasionEvent.msg delete mode 100644 carla_msgs/msg/CarlaStatus.msg delete mode 100644 carla_msgs/msg/CarlaTrafficLightStatus.msg delete mode 100644 carla_msgs/msg/CarlaTrafficLightStatusList.msg delete mode 100644 carla_msgs/msg/CarlaWalkerControl.msg delete mode 100644 carla_msgs/msg/CarlaWorldInfo.msg delete mode 100644 carla_msgs/package.xml diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 00000000..720c0ea7 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,4 @@ +[submodule "carla_msgs"] + path = carla_msgs + url = https://github.com/carla-simulator/ros-carla-msgs + branch = master diff --git a/README.md b/README.md index 5f2dba4c..49259054 100644 --- a/README.md +++ b/README.md @@ -23,13 +23,35 @@ This documentation is for CARLA versions _newer_ than 0.9.4. ## Setup -### Create a catkin workspace and install carla_ros_bridge package +### For User + + First add the apt repository: +##### For ROS Melodic Users + sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 81061A1A042F527D && + sudo add-apt-repository "deb [trusted=yes] http://dist.carla.org/carla-ros-bridge-melodic/ bionic main" + +##### For ROS Kinetic Users + sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 9BE2A0CDC0161D6C && + sudo add-apt-repository "deb [trusted=yes] http://dist.carla.org/carla-ros-bridge-kinetic xenial main" + +Then simply install the ROS bridge: + + sudo apt update && + sudo apt install carla-ros-bridge- + +This will install carla-ros-bridge- in /opt/carla-ros-bridge + +### For Developers + + Create a catkin workspace and install carla_ros_bridge package #setup folder structure mkdir -p ~/carla-ros-bridge/catkin_ws/src cd ~/carla-ros-bridge git clone https://github.com/carla-simulator/ros-bridge.git - cd catkin_ws/src + cd ros-bridge + git submodule update --init + cd ../catkin_ws/src ln -s ../../ros-bridge source /opt/ros/kinetic/setup.bash cd .. @@ -51,11 +73,20 @@ First run the simulator (see carla documentation: /PythonAPI/carla/dist/carla-.egg + +##### For Users + + source /opt/carla-ros-bridge//setup.bash + +##### For Developers + source ~/carla-ros-bridge/catkin_ws/devel/setup.bash +Start the ros bridge (choose one option): + # Option 1: start the ros bridge roslaunch carla_ros_bridge carla_ros_bridge.launch diff --git a/carla_msgs b/carla_msgs new file mode 160000 index 00000000..d38e482c --- /dev/null +++ b/carla_msgs @@ -0,0 +1 @@ +Subproject commit d38e482ce0abe0f1b6d78b3649fd687faee28fe6 diff --git a/carla_msgs/CMakeLists.txt b/carla_msgs/CMakeLists.txt deleted file mode 100644 index 09b17397..00000000 --- a/carla_msgs/CMakeLists.txt +++ /dev/null @@ -1,42 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(carla_msgs) - -## Find catkin macros and libraries -find_package(catkin REQUIRED COMPONENTS - message_generation - std_msgs - geometry_msgs -) - -add_message_files( - DIRECTORY msg - FILES - CarlaEgoVehicleControl.msg - CarlaEgoVehicleStatus.msg - CarlaEgoVehicleInfoWheel.msg - CarlaEgoVehicleInfo.msg - CarlaCollisionEvent.msg - CarlaLaneInvasionEvent.msg - CarlaWorldInfo.msg - CarlaActorInfo.msg - CarlaActorList.msg - CarlaControl.msg - CarlaStatus.msg - CarlaTrafficLightStatus.msg - CarlaTrafficLightStatusList.msg - CarlaWalkerControl.msg -) - -generate_messages( - DEPENDENCIES - std_msgs - geometry_msgs -) - - -catkin_package( - CATKIN_DEPENDS - message_runtime - std_msgs - geometry_msgs -) diff --git a/carla_msgs/msg/CarlaActorInfo.msg b/carla_msgs/msg/CarlaActorInfo.msg deleted file mode 100644 index ede403cb..00000000 --- a/carla_msgs/msg/CarlaActorInfo.msg +++ /dev/null @@ -1,12 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -uint32 id -uint32 parent_id # 0 if no parent available -string type -string rolename - diff --git a/carla_msgs/msg/CarlaActorList.msg b/carla_msgs/msg/CarlaActorList.msg deleted file mode 100644 index ffd61426..00000000 --- a/carla_msgs/msg/CarlaActorList.msg +++ /dev/null @@ -1,9 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -CarlaActorInfo[] actors - diff --git a/carla_msgs/msg/CarlaCollisionEvent.msg b/carla_msgs/msg/CarlaCollisionEvent.msg deleted file mode 100644 index e4af136a..00000000 --- a/carla_msgs/msg/CarlaCollisionEvent.msg +++ /dev/null @@ -1,12 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -# A collision event - -Header header - -uint32 other_actor_id -geometry_msgs/Vector3 normal_impulse diff --git a/carla_msgs/msg/CarlaControl.msg b/carla_msgs/msg/CarlaControl.msg deleted file mode 100644 index 601124d1..00000000 --- a/carla_msgs/msg/CarlaControl.msg +++ /dev/null @@ -1,13 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -int8 PLAY = 0 -int8 PAUSE = 1 -int8 STEP_ONCE = 2 - -int8 command - diff --git a/carla_msgs/msg/CarlaEgoVehicleControl.msg b/carla_msgs/msg/CarlaEgoVehicleControl.msg deleted file mode 100644 index cc55591d..00000000 --- a/carla_msgs/msg/CarlaEgoVehicleControl.msg +++ /dev/null @@ -1,32 +0,0 @@ -# -# Copyright (c) 2018-2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -# This represents a vehicle control message sent to CARLA simulator - -Header header - -# The CARLA vehicle control data - -# 0. <= throttle <= 1. -float32 throttle - -# -1. <= steer <= 1. -float32 steer - -# 0. <= brake <= 1. -float32 brake - -# hand_brake 0 or 1 -bool hand_brake - -# reverse 0 or 1 -bool reverse - -# gear -int32 gear - -# manual gear shift -bool manual_gear_shift diff --git a/carla_msgs/msg/CarlaEgoVehicleInfo.msg b/carla_msgs/msg/CarlaEgoVehicleInfo.msg deleted file mode 100644 index 893be467..00000000 --- a/carla_msgs/msg/CarlaEgoVehicleInfo.msg +++ /dev/null @@ -1,22 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -uint32 id -string type -string rolename -CarlaEgoVehicleInfoWheel[] wheels -float32 max_rpm -float32 moi -float32 damping_rate_full_throttle -float32 damping_rate_zero_throttle_clutch_engaged -float32 damping_rate_zero_throttle_clutch_disengaged -bool use_gear_autobox -float32 gear_switch_time -float32 clutch_strength -float32 mass -float32 drag_coefficient -geometry_msgs/Vector3 center_of_mass diff --git a/carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg b/carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg deleted file mode 100644 index e9770d6c..00000000 --- a/carla_msgs/msg/CarlaEgoVehicleInfoWheel.msg +++ /dev/null @@ -1,13 +0,0 @@ -# -# Copyright (c) 2019-2020 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -float32 tire_friction -float32 damping_rate -float32 max_steer_angle -float32 radius -float32 max_brake_torque -float32 max_handbrake_torque -geometry_msgs/Vector3 position diff --git a/carla_msgs/msg/CarlaEgoVehicleStatus.msg b/carla_msgs/msg/CarlaEgoVehicleStatus.msg deleted file mode 100644 index 03ba07d4..00000000 --- a/carla_msgs/msg/CarlaEgoVehicleStatus.msg +++ /dev/null @@ -1,15 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -Header header - -float32 velocity -geometry_msgs/Accel acceleration -geometry_msgs/Quaternion orientation - -# the current control values, as reported by Carla -CarlaEgoVehicleControl control diff --git a/carla_msgs/msg/CarlaLaneInvasionEvent.msg b/carla_msgs/msg/CarlaLaneInvasionEvent.msg deleted file mode 100644 index bf9e17bc..00000000 --- a/carla_msgs/msg/CarlaLaneInvasionEvent.msg +++ /dev/null @@ -1,16 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -# A lane invasion event - -Header header - -int32[] crossed_lane_markings - -int32 LANE_MARKING_OTHER=0 -int32 LANE_MARKING_BROKEN=1 -int32 LANE_MARKING_SOLID=2 - diff --git a/carla_msgs/msg/CarlaStatus.msg b/carla_msgs/msg/CarlaStatus.msg deleted file mode 100644 index 85249b78..00000000 --- a/carla_msgs/msg/CarlaStatus.msg +++ /dev/null @@ -1,12 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -uint64 frame # frame number - -float32 fixed_delta_seconds # duration of one frame -bool synchronous_mode # carla is in synchronous mode -bool synchronous_mode_running # true: running, false: paused \ No newline at end of file diff --git a/carla_msgs/msg/CarlaTrafficLightStatus.msg b/carla_msgs/msg/CarlaTrafficLightStatus.msg deleted file mode 100644 index d35beb78..00000000 --- a/carla_msgs/msg/CarlaTrafficLightStatus.msg +++ /dev/null @@ -1,15 +0,0 @@ -# -# Copyright (c) 2020 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -uint32 id - -uint8 RED=0 -uint8 YELLOW=1 -uint8 GREEN=2 -uint8 OFF=3 -uint8 UNKNOWN=4 - -uint8 state diff --git a/carla_msgs/msg/CarlaTrafficLightStatusList.msg b/carla_msgs/msg/CarlaTrafficLightStatusList.msg deleted file mode 100644 index 365df85e..00000000 --- a/carla_msgs/msg/CarlaTrafficLightStatusList.msg +++ /dev/null @@ -1,7 +0,0 @@ -# -# Copyright (c) 2020 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -CarlaTrafficLightStatus[] traffic_lights diff --git a/carla_msgs/msg/CarlaWalkerControl.msg b/carla_msgs/msg/CarlaWalkerControl.msg deleted file mode 100644 index c8b4f41b..00000000 --- a/carla_msgs/msg/CarlaWalkerControl.msg +++ /dev/null @@ -1,11 +0,0 @@ -# -# Copyright (c) 2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# -# This represents a walker control message sent to CARLA simulator - -geometry_msgs/Vector3 direction -float32 speed -bool jump diff --git a/carla_msgs/msg/CarlaWorldInfo.msg b/carla_msgs/msg/CarlaWorldInfo.msg deleted file mode 100644 index 8e5a8367..00000000 --- a/carla_msgs/msg/CarlaWorldInfo.msg +++ /dev/null @@ -1,9 +0,0 @@ -# -# Copyright (c) 2018-2019 Intel Corporation. -# -# This work is licensed under the terms of the MIT license. -# For a copy, see . -# - -string map_name -string opendrive diff --git a/carla_msgs/package.xml b/carla_msgs/package.xml deleted file mode 100644 index 79727a4d..00000000 --- a/carla_msgs/package.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - carla_msgs - 0.1.0 - The carla_msgs package - CARLA Simulator Team - MIT - catkin - message_generation - std_msgs - geometry_msgs - message_runtime - std_msgs - geometry_msgs - From ecdc7769aec2c49a7a4bf62c19a474d2a6a44c67 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Thu, 19 Mar 2020 10:14:36 +0100 Subject: [PATCH 031/627] ad demo: add node setup documentation --- carla_ad_demo/README.md | 1 + docs/images/ad_demo.dot | 242 ++++++++++++++++++++++++++++++++++++++++ docs/images/ad_demo.png | Bin 0 -> 277185 bytes 3 files changed, 243 insertions(+) create mode 100644 docs/images/ad_demo.dot create mode 100644 docs/images/ad_demo.png diff --git a/carla_ad_demo/README.md b/carla_ad_demo/README.md index e6b17f51..cc134da3 100644 --- a/carla_ad_demo/README.md +++ b/carla_ad_demo/README.md @@ -5,6 +5,7 @@ This meta package provides everything to launch a CARLA ROS environment with an ![CARLA AD Demo](../docs/images/rviz_carla_plugin.png "rviz carla plugin") +The Node setup is visualized [here](../docs/images/ad_demo.png "AD Demo Node Setup") ## Startup diff --git a/docs/images/ad_demo.dot b/docs/images/ad_demo.dot new file mode 100644 index 00000000..cd97b1ac --- /dev/null +++ b/docs/images/ad_demo.dot @@ -0,0 +1,242 @@ +digraph graphname { + graph [bb="0,0,2381.1,826", + compound=True, + rank=same, + rankdir=LR, + ranksep=0.2 + ]; + node [label="\N"]; + n___carla [URL=__carla, + height=0.5, + label="CARLA", + pos="364.63,648", + shape=rectangle, + tooltip="/carla", + color=blue, + fontcolor=blue, + width=2.9067]; + n___scenario_runner [URL=__scenario_runner, + height=0.5, + label="Scenario Runner", + pos="364.63,648", + shape=rectangle, + tooltip="Scenario Runner", + color=blue, + fontcolor=blue, + width=2.9067]; + n___scenario_runner -> n___carla [URL=topic_scenario_runner_carla, + label="Spawn/Control Scenario Actors", + lp="188.49,609.5", + penwidth=1, + color=blue, + fontcolor=blue, + pos="e,322.49,631.48 92.426,541.3 145.96,562.28 250.36,603.21 313.16,627.82"]; + n___carla_waypoint_publisher [URL=__carla_waypoint_publisher, + height=0.5, + label="/carla_waypoint_publisher", + pos="364.63,648", + shape=ellipse, + tooltip="/carla_waypoint_publisher", + width=2.9067]; + n___rviz -> n___carla_waypoint_publisher [URL=topic_3A__carla__ego_vehicle__goal, + label="/carla/ego_vehicle/goal", + lp="188.49,609.5", + penwidth=1, + pos="e,322.49,631.48 92.426,541.3 145.96,562.28 250.36,603.21 313.16,627.82"]; + n___carla_waypoint_publisher -> n___carla [URL=carla_waypoint_publisher, + label="Query waypoint API", + lp="188.49,609.5", + penwidth=1, + color=blue, + fontcolor=blue, + pos="e,322.49,631.48 92.426,541.3 145.96,562.28 250.36,603.21 313.16,627.82"]; + n___rviz [URL=__rviz, + height=0.5, + label="/rviz", + pos="671.27,405", + shape=ellipse, + tooltip="/rviz", + width=0.75]; + n___rviz -> n___carla_ego_vehicle_ego_vehicle [URL=topic_3A__initialpose, + label="/carla/ego_vehicle/initialpose", + lp="1169.4,526.5", + penwidth=1, + pos="e,1545.9,484.96 686.93,420.12 692.63,424.89 699.37,429.75 706.27,433 842.05,496.96 888.71,477.92 1036.9,502 1129.3,517.02 1380.6,503.05 1454.1,561 1461,566.42 1454.8,574.23 1462.1,579 1476.3,588.2 1487.6,590.27 1500.1,579 1512.3,568.11 1497.2,518.1 1508.1,506 1515.8,497.57 1525.6,491.81 1536.3,487.92"]; + n___carla_twist_to_control [URL=__carla_twist_to_control, + height=0.5, + label="/carla_twist_to_control", + pos="936.56,420", + shape=ellipse, + tooltip="/carla_twist_to_control", + width=2.5637]; + n___rviz -> n___carla_twist_to_control [URL=topic_3A__carla__ego_vehicle__twist, + label="/carla/ego_vehicle/twist", + lp="771.27,421.5", + penwidth=1, + pos="e,847.79,414.98 698.66,406.55 731.36,408.4 787.87,411.59 837.61,414.41"]; + n___carla_ros_bridge [URL=__carla_ros_bridge, + height=0.5, + label="/carla_ros_bridge", + pos="1382,451", + shape=ellipse, + tooltip="/carla_ros_bridge", + width=2.004]; + n___rviz -> n___carla_ros_bridge [URL=topic_3A__carla__control, + label="/carla/control", + lp="936.56,348.5", + penwidth=1, + pos="e,1373.1,432.75 685.38,389.63 691.33,383.97 698.64,377.97 706.27,374 762.21,344.89 781.64,348.38 844.27,341 1046.3,317.18 1119.9,262.96 1301.9,354 1331.7,368.95 1354.5,400.65 1368,423.76"]; + n___carla_spectator_camera [URL=__carla_spectator_camera, + height=0.5, + label="/carla_spectator_camera", + pos="1617.1,315", + shape=ellipse, + tooltip="/carla_spectator_camera", + width=2.69]; + n___carla_spectator_camera -> n___carla [URL=topic_carla_spectator_camera_carla, + label="Spawn Camera and Update Position", + lp="1169.4,291.5", + penwidth=1, + color=blue, + fontcolor=blue, + pos="e,1536.6,304.89 675.79,387.15 680.68,371.53 690.05,349.45 706.27,337 756.06,298.78 782.37,317.4 844.27,307 1045.1,273.26 1098.5,274.03 1301.9,284 1377.7,287.72 1463.4,296.44 1526.3,303.69"]; + n___rviz -> n___carla_spectator_camera [URL=topic_3A__carla__ego_vehicle__spectator_pose, + label="/carla/ego_vehicle/spectator_pose", + lp="1169.4,291.5", + penwidth=1, + pos="e,1536.6,304.89 675.79,387.15 680.68,371.53 690.05,349.45 706.27,337 756.06,298.78 782.37,317.4 844.27,307 1045.1,273.26 1098.5,274.03 1301.9,284 1377.7,287.72 1463.4,296.44 1526.3,303.69"]; + n___carla_twist_to_control -> n___carla_ros_bridge [URL=topic_3A__carla__ego_vehicle__vehicle_control_cmd_manual, + label="/carla/ego_vehicle/vehicle_control_cmd_manual", + lp="1169.4,457.5", + penwidth=1, + pos="e,1309.8,450.27 1005.5,432.06 1016,433.59 1026.7,434.97 1036.9,436 1126.4,445.06 1229.6,448.65 1299.7,450.08"]; + n___carla_waypoint_publisher -> n___rviz [URL=topic_3A__carla__ego_vehicle__waypoints, + label="/carla/ego_vehicle/waypoints", + lp="556.77,575.5", + penwidth=1, + pos="e,662.37,422.27 391.18,630.38 455.5,587.57 615.9,480.06 636.27,459 644.28,450.73 651.51,440.36 657.29,430.93"]; + n___carla_ad_agent_ego_vehicle [URL=__carla_ad_agent_ego_vehicle, + height=0.5, + label="/carla_ad_agent_ego_vehicle", + pos="2123.7,588", + shape=ellipse, + tooltip="/carla_ad_agent_ego_vehicle", + width=3.1414]; + n___carla_waypoint_publisher -> n___carla_ad_agent_ego_vehicle [URL=topic_3A__carla__ego_vehicle__waypoints, + label="/carla/ego_vehicle/waypoints", + lp="1169.4,676.5", + penwidth=1, + pos="e,2017.5,594.46 446.66,659.26 456.95,660.36 467.34,661.32 477.27,662 640.01,673.19 681.15,665.89 844.27,667 1104.4,668.77 1620,671.24 1726.1,666 1840.4,660.36 1895.2,715.05 1982.4,641 1992.9,632.07 1980.2,620.31 1990.4,611 1995.8,606.05 2001.9,601.96 2008.4,598.6"]; + n___publish_scenarios [URL=__publish_scenarios, + height=0.5, + label="/publish_scenarios", + pos="364.63,391", + shape=ellipse, + tooltip="/publish_scenarios", + width=2.1123]; + n___publish_scenarios -> n___rviz [URL=topic_3A__carla__available_scenarios, + label="/carla/available_scenarios", + lp="556.77,410.5", + penwidth=1, + pos="e,644.31,403.77 439.64,394.42 501.29,397.24 586.03,401.11 634.07,403.3"]; + n___carla_ros_scenario_runner [URL=__carla_ros_scenario_runner, + height=0.5, + label="/carla_ros_scenario_runner", + pos="1617.1,639", + shape=ellipse, + tooltip="/carla_ros_scenario_runner", + width=2.9608]; + n___carla_ros_scenario_runner -> n___scenario_runner [URL=topic_3A__carla__ego_vehicle__goal, + label="Start/Stop Scenarios", + lp="188.49,609.5", + penwidth=1, + color=blue, + fontcolor=blue, + pos="e,322.49,631.48 92.426,541.3 145.96,562.28 250.36,603.21 313.16,627.82"]; + n___rviz -> n___carla_ros_scenario_runner [URL=topic_rviz_carla_ros_scenario_runner, + label="[service]/scenario_runner/execute_scenario", + lp="188.49,609.5", + penwidth=1, + pos="e,322.49,631.48 92.426,541.3 145.96,562.28 250.36,603.21 313.16,627.82"]; + n___carla_ros_scenario_runner -> n___rviz [URL=topic_3A__scenario_runner__status, + label="/scenario_runner/status", + lp="1169.4,595.5", + penwidth=1, + pos="e,676.56,422.87 1537.5,626.95 1396.9,605.25 1095.9,556.81 844.27,503 782.5,489.79 756.33,507.53 706.27,469 694.28,459.77 685.85,445.2 680.28,432.3"]; + n___carla_ros_scenario_runner -> n___carla_waypoint_publisher [URL=topic_3A__carla__ego_vehicle__goal, + label="/carla/ego_vehicle/goal", + lp="936.56,655.5", + penwidth=1, + pos="e,469.3,648 1515.6,644.58 1474.2,646.42 1425.8,648 1382,648 671.27,648 671.27,648 671.27,648 607.87,648 537.09,648 479.52,648"]; + n___carla_ros_scenario_runner -> n___carla_ad_agent_ego_vehicle [URL=topic_3A__carla__ego_vehicle__target_speed, + label="/carla/ego_vehicle/target_speed", + lp="1858.3,629.5", + penwidth=1, + pos="e,2022.7,596.15 1696.4,626.86 1709,625.11 1721.9,623.42 1734.1,622 1786.2,615.96 1917,604.85 2012.7,596.97"]; + n___carla_ros_bridge -> n___rviz [URL=topic_3A__carla__ego_vehicle__vehicle_status, + label="/carla/ego_vehicle/vehicle_status", + lp="936.56,385.5", + penwidth=1, + pos="e,697.21,399.67 1361.4,433.48 1346.1,421.51 1324,406.49 1301.9,399 1109,333.77 1047.2,362.26 844.27,378 796.62,381.7 742.24,391.04 707.37,397.7"]; + n___carla_ros_bridge -> n___carla_ad_agent_ego_vehicle [URL=topic_3A__carla__actor_list, + label="/carla/actor_list", + lp="1617.1,601.5", + penwidth=1, + pos="e,2016.2,593.77 1402.9,468.38 1418.9,481.63 1441.7,500.22 1462.1,516 1478.7,528.83 1485.7,528.82 1500.1,544 1504.6,548.64 1502.6,552.83 1508.1,556 1590.2,602.71 1851.7,600.22 2006.2,594.17"]; + n___carla_ros_bridge -> n___carla_ad_agent_ego_vehicle [URL=topic_3A__carla__odometry, + label="/carla/ego_vehicle/odometry", + lp="1617.1,601.5", + penwidth=1, + pos="e,2016.2,593.77 1402.9,468.38 1418.9,481.63 1441.7,500.22 1462.1,516 1478.7,528.83 1485.7,528.82 1500.1,544 1504.6,548.64 1502.6,552.83 1508.1,556 1590.2,602.71 1851.7,600.22 2006.2,594.17"]; + n___carla_ros_bridge -> n___carla_ad_agent_ego_vehicle [URL=topic_3A__carla__objects, + label="/carla/ego_vehicle/objects", + lp="1617.1,601.5", + penwidth=1, + pos="e,2016.2,593.77 1402.9,468.38 1418.9,481.63 1441.7,500.22 1462.1,516 1478.7,528.83 1485.7,528.82 1500.1,544 1504.6,548.64 1502.6,552.83 1508.1,556 1590.2,602.71 1851.7,600.22 2006.2,594.17"]; + n___carla_ad_agent_ego_vehicle -> n___carla_waypoint_publisher [URL=topic_3A__carla__getwaypoint, + label="[service]/carla_waypoint_publisher/ego_vehicle/get_actor_waypoint", + lp="1617.1,601.5", + penwidth=1, + pos="e,2016.2,593.77 1402.9,468.38 1418.9,481.63 1441.7,500.22 1462.1,516 1478.7,528.83 1485.7,528.82 1500.1,544 1504.6,548.64 1502.6,552.83 1508.1,556 1590.2,602.71 1851.7,600.22 2006.2,594.17"]; + n___carla_ego_vehicle_ego_vehicle [URL=__carla_ego_vehicle_ego_vehicle, + height=0.5, + label="/carla_ego_vehicle_ego_vehicle", + pos="1858.3,448", + shape=ellipse, + tooltip="/carla_ego_vehicle_ego_vehicle", + width=3.4483]; + n___carla_ego_vehicle_ego_vehicle -> n___carla [URL=topic_carla_ego_vehicle_ego_vehicle_carla, + label="Spawn/Reposition Ego Vehicle (with attached Sensors)", + lp="1617.1,544.5", + penwidth=1, + color=blue, + fontcolor=blue, + pos="e,1410.5,467.54 2035.6,576.6 1955.1,566.19 1832.6,550.42 1726.1,537 1629.3,524.79 1602,537.01 1508.1,510 1477,501.04 1444,485.32 1419.5,472.35"]; + n___carla_ad_agent_ego_vehicle -> n___carla_ros_bridge [URL=topic_3A__carla__ego_vehicle__vehicle_control_cmd, + label="/carla/ego_vehicle/vehicle_control_cmd", + lp="1617.1,544.5", + penwidth=1, + pos="e,1410.5,467.54 2035.6,576.6 1955.1,566.19 1832.6,550.42 1726.1,537 1629.3,524.79 1602,537.01 1508.1,510 1477,501.04 1444,485.32 1419.5,472.35"]; + n___carla_ros_bridge -> n___carla_ad_agent_ego_vehicle [URL=topic_3A__carla__ros_bridge_ad_agent_ego_vehicle, + label="/carla/ego_vehicle/vehicle_info", + lp="1617.1,544.5", + penwidth=1, + pos="e,1410.5,467.54 2035.6,576.6 1955.1,566.19 1832.6,550.42 1726.1,537 1629.3,524.79 1602,537.01 1508.1,510 1477,501.04 1444,485.32 1419.5,472.35"]; + n___carla_ros_bridge -> n___carla_ad_agent_ego_vehicle [URL=topic_3A__carla__ros_bridge_ad_agent_ego_vehicle_world_info, + label="/carla/world_info", + lp="1617.1,544.5", + penwidth=1, + pos="e,1410.5,467.54 2035.6,576.6 1955.1,566.19 1832.6,550.42 1726.1,537 1629.3,524.79 1602,537.01 1508.1,510 1477,501.04 1444,485.32 1419.5,472.35"]; + n___carla_ros_bridge -> n___carla_ad_agent_ego_vehicle [URL=topic_3A__carla__ros_bridge_ad_agent_ego_vehicle_traffic_lights, + label="/carla/traffic_lights", + lp="1617.1,544.5", + penwidth=1, + pos="e,1410.5,467.54 2035.6,576.6 1955.1,566.19 1832.6,550.42 1726.1,537 1629.3,524.79 1602,537.01 1508.1,510 1477,501.04 1444,485.32 1419.5,472.35"]; + n___carla_ros_bridge -> n___carla [URL=topic_carla_ros_bridge_carla, + label="Monitor all Actors, Publish Sensor Data, Control Ego Vehicle", + lp="1617.1,544.5", + penwidth=1, + color=blue, + fontcolor=blue, + pos="e,1410.5,467.54 2035.6,576.6 1955.1,566.19 1832.6,550.42 1726.1,537 1629.3,524.79 1602,537.01 1508.1,510 1477,501.04 1444,485.32 1419.5,472.35"]; +} diff --git a/docs/images/ad_demo.png b/docs/images/ad_demo.png new file mode 100644 index 0000000000000000000000000000000000000000..3b6a1801beb28beefb6cf14989ae9bdbc5adb2c8 GIT binary patch literal 277185 zcmbrmc{tYF7e4%GlnRwn#-s>E%9ODrMUo^WLrLZ_MCOVHLWLw#g(M*%^Uxqk$dt?? znTKQ^-+SwPJDvBs-uL&%?{m(jC-OXdSbME|-RoZari${R)ig{r6bfav!eKd8{1Hi^ zEc!*g2;Vs(N0)&=mgyfkBuAMi|2@o&4WLjqQxxR(t2u`CHJP}aI6pT(&!=M?Dq^9P zwXNIF>)y*1AC%7<$T2kqgvWa-6D8n?kjeduQ%s28#r&bOKS9?X;ac+sPd(VRO)_OzX0y|#&aq@PH+c4irfgdW8>{(c$-wZnA& z{svwb%x`X@{_pn&c0@B%{pVW+;a+x}|M?CjBPC;R_TS&~$d)~M^5m(7=hCIj*JnQW zj&^i($VVkdM@Q!@JQ*2Z4O4;w0}mGk2M24YsU7ZbYtxTAjz?FQKkbO3qPa*z8tdfb zWM;-p{-z{@-65)Rc9I39rAHsBP;)dkHMzRDFbSJ}@9*#b_KhRBL`q63Hz()&g-m~c zf7wSWyg}aaE-o&XW49?36}~$A`D3(y573@(=gyrMRJ67GzG7%GF)PN_K=LXkB_ab?XO?IY%g4hz9yB~bzeVKD`D(}!R}K9CskX^Yin!E%gY-Y z8cIq^@Vcm|sHEh`gC!N@>!#zTVn3C8H=k!Ya^%RUlk2HdA+OKu+PJE)u&}Z-&7|z{ z<1Iy1{enfGKYwm*ZGHG~bDCCyYTTQ*Z%^``Jagt@%D_sBir#I@C4a4w!lhjuUc7kG(C~?JY*n`%Y)Q4UOuF-NcDA#Mipt@`hmDQ9(pH$96WzJEW=vB67r&8AJ8>`xjP7$_-yk{WMp@9pjF8>XV9ukV)sYlbTGYU=7gzJE73 zf8Hcb%UO+|lao_I;&gn?z2M*@*NZ!bZ`_~`Qe3}b1J}_FT^r9DJSdR3UT3a+Y~eX_ zBt^8cveHgGJWzf$Ev=s~d2)*`W5rTdE~hl|{^#TrgvVpi@&0@EoKVa;kI7+h1_oba zrvi!%9zA-bdO=W9QaeUfArcG4Oq*d=eXb#6~{OVs}XNIayg*>^kR` zE%+Ms_;GaR#(9LoD_GT&1@Y5PoFM28}s)W<&mUS=B$KxZ?EyHi$ zZiV;g)2E`i-}>)o6+e6SZ1*=+0b#*h^yB3v^ zF;N>|79r(4H*+bV_wotA`E#-dp4$BWets8M?N;pf@St$l`eysrnC4#S@D8+_=}&Jd3)>qI z62jwo!`s`m)8hpvrIF*XD2WIEJRUNJaA%1xi#DB5RmEBGq-SGe^ZRztnNv*cYq9;} zG@NgV{(UqO@`nzko7E;BxK0}`Zf{zf7_QCla502p9lYf~o@0(ZzUEntY0^=_A3uI5 zF8924?Y;JTR@R-uLQK9&T(*`S1uX`25)tC|Jrh6M_wL+0$XZ@INrKtRBVk+zYxySw|4Kbw@> z%tZ3JBDcv7#*{jijT^TYvS2mqlg}M`V!y=W^nXobwKk#x4)i(C;Y`6|5 zMM&sB$IDoZhK5G<#EGiPN|qD1aQHX)9Hf4vvOV#rAQsWt(NQeh`k{33$B*K6U7x?b zy-vq2?E;GnQMz~g_U-%kw|lV)Gx?^hT;g%f5*_wD9{kwPXTAt2NFMD~u1gkyzt6b*Dy7k)eCt{Uv-n@Av zm_MPPX0?@)C0$D0%s}?wKy&W&yPNB<_+|Xd$#^}S-kXcSF(0WCe4-l!9}^iVz)H`= z#I%0>de@+8zZ*BK9UL4?zZEonFc!i-j1*j6EHgLJUL3$3A0NMN?OLZ%j6)-7dN5xv zPE9;}ALZ$>-xj{_z#jLx8O}p~eNEZpgL)s$MVy_Sn$O%F$Q?p_4 z4Yt7F*Ed|o-K~jn((K&bpdkB(yck!B>8$-21e5QRr%!J%{yvJ;PqMPK;%n;P`ozV> z@$m4Nn3#x%mzk!~a0DvGNab{Wz;UTdTb$vCkb|Q#JJIe>2Ah;W#~V;w|H`5PBZcia z3^q4aRaMn3T~rY6_j{9tglueV_8671>@oawH1mNHSN7|zEv5bA8*cjh=R5vvYnjoR z5V)nFrB(m*coZ$G_=v+)?*8B;2xh>N@HPd7L61G2X#l{-J=S+`uSH&KS#OPk?N>a2Lf5#x*@FiU!t(v91Qnwhq7Ww?9WyYryPrR+;Ka6W`1tW-eKuAh*V%pI+x5qf9}f); z&CO1a_tqvIiI7K>eroqWq!#bAN$Owk(lE$`O?m7yv05LpwEWNvvB$1ZZjFOkG{S*d$rE| z-o<)zkzCz;L+BXZBYUc~XPKFy5# z=z~$sI0^WF0mW2SKU8q%$-(zF}~8Z(W`BdV*buP&$iBIqPs zU2(@%2?56*Q6ffluT9&#G_%^dx?xoln+G)v}P6mv?eBJ?VFcD8;BAJank&-MdET!Q3&1bDEm> zar#n9mRo0gd3pJ=V)9>;Yieq^k3|ID^{D73bpxT@64vt>decfr=JTQj4U;T zG3gyXd_y-Wz0RE7W$1EzyxG~ak4g({56h=e8}ikehC!A=G#7nhWn;hRcI zN(u@JP2Y`8@ktMur&2yRf~su&=ScI!@27#>|viyXjK0 zY44+7`I+9j+0NtMv!+_a*xpVjDoI?(qF!k8=6$Bb3n1LV=EsJI*UIKhwE0}8Wv$P$ zkC%N!FUzv`LbM-SQg%Kt#JM6rGK184*r9{1ZTrCm9Q;t1kC%695T-m@tLHxSdO6&L zW7|#cEW7T<6~=ulw$jo0I}c>W!i=I0`A5K!a7VffH#xNEV6u-NzadVkin!Ftj$pjK zInE>fmaSXAhZsfFW!f46-lZH_Oo=^v-jtYvu^26zq?mPUK~9dOfIt#PGT#xbmuJ_l zTJ_|p7dAMva=&)-1Bhe04>CwM!NdyQW$q?1%`)P=-HW+ z+}jx?@9WeNq;YS@Db=D`tsVEsM307w=(&yt(YKX~wy=oXk({;X>3%JiI@7d|2D>@r z&YU@ebk9|J|H9_@U9YLQ(|-Sk*@l$7pX3?_Y>nyFvt&2!?3;(<@>4qr@} zVa=bL>V;>zIN0nuGhrhtn*Q$HyUUB0)3S)|;^KN=7eiHGQTVZ%?9XRwbNIs#w>eb9 z1`rQrZy@FAj?~uCDY~_ZGYt{lREVke`Kc3XYDl+tZtzLfbDA93Xz~2ft97i?Qt*~I zPj1uw>1M|U8`1}1P`R)hjsw>mot$Vm5Ky;yie31AgI@Llr^;O*63>ar&dA<8JqL$z zgx&J{f}8-Ml9DsnV~hIKxa?&`66^z8wB&(CK<<}GaPbiYJskF zeBETelmU9ogPZ$Md<~ZM)~!{}-p6CBkhvgEcJIp6W?Qr7k$U{wH*eq!1qwG2a1Ugk zFSfWK;WIu9o-}u?-fZd8rSOma15Md2F271K6J)JN1dHHoUM5O;WK;bU_crg?Py!b! zV%5CE0w9)#10zEYpws>VqnE}xHv97Y(%fXH%>2wR=E1fs?k`>GSpRL?3JrGe&Fe_l zO5o?`hvOO^9%h1Hyu*12Z_rsDDP#6!hmG(EAP#`uW>)sKYqxj~{rWZi_U?OMW>Lfd z4Ag$0@e-nqyXM=~%_gi-oljr+J&TWLE&8q{I!A5FoSN_MFMHz<+okVF7hExh@qs3C zoB%Q$N4hG6{f@`i$PyE)cY1D-uO1)NQ*A6Hs=Ib!4Mlx)lK|m>CAAVnfDn-V#n&hX z>_*c0HQ#jO#*I(0gm2%TJ9o}`q-zZu8-L*@0MXQIiz#Bq&zx!ffQk6Am?UeuO?Agg zIgh!F)@Tgo{8Cm?`Fwy*O32{DZE4r3!+PG!JeJ-32hz|xj}NSu9qDh-s5fuQ8vWT` zgkwEY$f$RC&m!c3dKuQ=E-z=>C~O*7s6SaGGsofiLMuVExzPUD^9n0%?XY44t(OMH zIhTG#OTi_>3C$i6$W_zPaYej@D=B>cUR+m1Q1E9FyL)4bk-t>aeUj>QRmGOG-}~O% zD`DA~v6@)~sjYcS-YlJ2#%qa$b0aKt@d=zJmp4w|Cz$`#$&*2@zuvR&x45caB=w~$ zp4Rrqrw~!AX7{;Yk^K$n1f0Xu*FIrhxpJi!z3bG-3L2U$OaHW!YZ)0GrbfE461Ui8 z=H$H>0$Xc2FF*g6Zo9g=y0LP?B0Z`x1qsrBXli;I(etU=vkh1QEJ%X-k7r?B!B6tF08T~7xTWioGEqYWr+(PXT9#$ zMnO^)w9Grf!Un@lEi5l;y(=6Z?7#+BW2f@J( za4~6GO)#F+RH3V{Tl@QW>VOZ^<_|t}@LksMO^yzBNwjEUGu7ZR7JO)Q?Bk*m6ujRSy|aV%ephW zwlmOxAgVF#-6&Ng7?%*WVjY*5^hypnzypvns;a7vj*b?bmzoybx{bf^)U&JU>FMh6 zK)gsZE?>S3U=2*PI#9`1AR z8~gdQ!dM8&5@;qN@~FkAE?vIdOy~hpJaAqzXYZ5u(DFsWF8sN z?92@ENox#wJ)io-^z?XtgTu!_p31?S?M411dLu$BDtf!VeA`hH4DLj4T#iG|*9}Q3 zn^V^#4-XHpaX6sJBacky&(ArV6q{r}eE2Y2!lB;$6|xx(-Agfg`EH2+&IrXn$|J2r zLak=TVwFNvkwrPIR*xSIcWAyd6~6nt_vu0G~P6m9^rdc?BNj}GMK=IUr`XI<>ia+w@P#5by4 zN^xhj{mrvj2Ee<6Vfb`k@BsDMG%b7aCS*Fuw<1DAd;2N}wA0-`M`to$`ptk(tQ>K2 zg|ov0v&C0XaBgmHAUs~5RBbr3>+3O->Zixs-}^3Jy!h&sD_5>wU7U2Gan*_yHmf8S zQA|(h>dpc5^*3hz>P^b$=i}?Gj46qN_xQl+Z!E-Q6ugY$zVvsTE9ie=P<%IJkI{w= z8rj6g6Tb`$Ng#n?Wihd&9o>3;0o6vRtyj*oMV-w?(>+onkd=>e!T>FJkOB_lCmc zE8kt!&@f#dv9Pxpi|fo^-Mzaus=|182vRceB1n5flwdNd2a;-ogMvboxS}dFRaNzO zhbSiAbyG;SwYP_7K#HjtqiXuJrU$N|!9jd3KsC<1`stmN0Vc}81#ni|u4u>3PrabUc z9TzgS`Nu~`Pi|+pklEPKa5_#6E@XOgQiu7Z8gEcuUS7Jr7=!Eu*50o;rB2P_)G*h1iAj7&XVTRU3Edzq>)Tco}f2 zc(xGb=>pIYJ_(qM$IuYzBaXz(%nZspSK_gXI7{cxccgKX&l9*S2@0>Vk%7jmJwGce zYdAsu_s}WEyZZJYID|c~UA7#hoW$^JV3Ix>yp;E4Le&KYh8R^78P%*CuCWXTIRimd zl!+3>BS+>(liV%91~S3~<^~_pjXmtEq_oZ-0)uHC{46oCthiX=$dMA5 z=O^+g9XnQzKk(O*k^sM-BO|MRKPy(O$a#iB1de;2hC+$$;YaeF&3`e#GpB$m^jv-x z!n~Bj#2%@}vANIu#Ga*EwKUh+Q&DiP3v?cW6b4JYckg6dp-*vfaj<}19@t>z*!XA9 z*2-e}rX%ssTHudHTKpOSFY$q(e?aX^BPYY>5C>Abv~}Ph zCieNWX2O@iz(C@wLEct&2Jva^*x*BQ%B|RI5%Q>e?~#|2d#c6@mujT3`rl7*@B|5B zj$9iw6f78^YLl>OHHe%~S{EsnGL^ny1(UL}rrvn11fd`ao+Iu=Y+0m?)$R}=Haj~z zqtdK)FFr7FGslo_QG@= zRxW%>H#|GxEY|wM?FlmZUdYTrVhP-5RkM&c0R6xs!gRR)_tq3jwN++jCZg0dd=@ZU z11K1RjG2Ua#l`Ef4aO7X-1J;Wr34ri8Lc9X@CHW4?Ck7x) z-}kk=gXnLGMd|&L0E`ZcXF>LW=z?<+uEXfD%m=8twJazy(!CWq-*Vc%mV6noe1(NE zr&0{zWFr}j%&VTPmf60*<}AE%LBHC`lcOjDxWP7&^!Um?a_otVeecKGkY#U%&3s5j z==+QmhV|=Nkwn9mr^g3n90tO`m4FV$zE@yW{5n|xVMdI96=dmQi=<4P?>38_N7^L= zunjVMdTL5Mo1e0JIgHWc7u*uofGlTAo@@ThFzkb$KM}TtEeGf5k2)lX?tj-ny9M8s znd*uH)02~x<@EXCexR4ZrtEZ3*B5mtJyO^;N^GWGcO@y6AW{DQ;SSClzyUxyMj8Rm zc`MW3mH?7=a^_b#sG#{0fqW1}gseg=1}-d1T)9t5o}ALt0E(>AE{;g2Fl$9+W!hD% zTv{(LUq;LFHC{u&Eph3eF?vi5VCbNhTCjp}P%qBDM8IS zcWJezwl>SUb$h_1?7zCK2?@-=zyP5(|2)=v;Jx}l6c&1~C+XFf=XF)!_xe)G5tGHR zlA|lgvECW@;6avcr?N@E3Ao31@8o!@3CM<@`S(e0L`qwWa+T}!#SkSCmx-ay2=kU||=9{(b9$esxt< zV4Zt##iRs>H(kf2MEIwi++1Ru5=>;2M?pBGf=dHg%PQ%p@<>H;X6WrP$)9o{df|D) zbpA5;f=NPR1F9jH0~KxyOB2W$k_EmD*J1FGU?A_;a(>swys4ge7!W}bU@Hk5BJDD< zm`)O9yzc)@-ysZ+AJ_rr#lLfB03HI?KX|ufa)JzI?d^_V3TLZ#Ez-EC-+fXzXcD&P>H2_Hb!eCy*0iIt-LfPI3;9 z%SZhL4>bXn+K)|&37-gF6@JTX!SnukE6P)XrJo!P1;_2$T^R%RR0+H{(gu{%VAUQ~ zqlW~&{8^?nISNygxv`!4%7J!y%yf`;r`@0^A^|fCQLMM@&{P2UpO)T z>@w1uHy6O8SuY~KQfoaUqdO=E(2B)4YVf~=wz%;91OE8$L>C9&z55cMgQe9tdD0is zh~e+Wr4NK{FCM2@@{#xI6@zDaAZ&)&ee3C&`g+cvY#fS3Fx7u&Y3;zn$Jc-{!%3ew zaf02k^)lkX7$}drgH#zuwTWn?l~zAl^A!RhegZeOb=$U`dU@KhRTf`gTsHno8`3&< zVmpIC?nouFAKgrzr!M`M&wrb3%Fc*ih9S1a4R%fD5DBo4x(dcpq{=e&Ljx zmzt`URNFf`g`6C4ar()~F@#@mc{m47xy?j5a_!?sMd0P}pdiHcE`xx9;yguLuqjmhTbjkGR&DOIRgDlDS^JdGA}dSY+I0Y|EvL z=4m(lnS@7u;Jtf4Iy#_%AP)n>VPAstu3UkhgePVD(oG5KX1=x%Szkr(sGrf&B}-6) zf2PKpwiqi@VGQgqw0PTQ9C$$0OP%2k@WR!I2AlR6N+S7NVsQD|WwIX!0ZvKH!lC&R zw~UNCJS3cnWz`ek6rX?91D5Pj6;Br^5bz%_Q&K>FKrDmY5WI}Cva+sjgj6P>R-iU9 z@qP{7qy7mq(0*BN)HR%#>JJj2SAp3f%SccU1zQywYUZD@WZAN7*RLOvlaoU=0bk|h zJn>g~c`!)z8olpzx*!|??^rfJ+cFO`&qYp#fGIS8Y0)SvSzSIDF+7iePFCuR7uEmfgBlE%k_Bd*>IKiI_aE20q;o!;fsvN1|r;t6!QU4zC+&z$GpcZ%v@87xe zsHz)vI(7AXLTjSzZiR-Ph6D-Aq?Pc+SV;B4aqm4?t7XfVXJ=;a9p|?`p}Av2f;!(e z);+s-S5{R)=Ya=G6(j_n^st+;=yQmaK+?dTCqUu#y|GydTT9Z-C8c$!nf#^3zM>!k zDui5nujOu`Ew;|{!eaTL%Nk4cAyS;Mqj@TxgIjMfj)0aHBstRI~%54>aS0;${oE|sDBBR zBiFGA6o3C-DJC%p#BgFBJm4*TbN|7E2X_`8)Btu4_YMrO5v^RFairhz`jMd_>x+{G zk@q4Z=D>@AY)<;kxA(!2baiz4+uN(4A_E*i+B-$0SWQ`J&>E)j6|zr*1N>1IK27#) zUU@7SNg%@|cHgPv3h(+747Q##RlSdt3bOzRewYwfH}~TSOhbqo8N0lb+`j!oo!8q)TlFT0Yg2eI&n%-k0ycyBuiMH z&(BZoG1B;x_IXT2qpZGd+d)+HjErKn?Yk?tU46aT6S^NdIy#LwHPbZl_xsh<7;FU> zi9&!Gp4S6J2H%VIL9+gjY7U~Ti{O}tTdG+fKYM11JOZN@+_(x!p<8!MFwy5?OUQtn zI>3zJ=hI;HrpEfGznr#8BMi!Vk~S7t+(m5!Nc#Kt?{LX`v+sq~Uf4@&w zFe4M`9V@qfsyoO?4o_sta2Kvy}^u=E<6g&imkv z)~;Izcc#^_o~iQw%(qe!%_k1P;~<71rNU!EtEi~BAo@s9uRSa%4~FpibpR-dOuN=Z zgJew{YBM?s-8`2%!xUlEz}9W1+q4sb9L zCA??0qUPAZuPt`5Pcx5~h`=7^-IsBn1B(J|KRqsRUL+I_$ZA)y!@B9*gHW@{NAc{~ z@w~skap)TrEFXt{U6yPc1`QNd;azECK%RF)c|fEO=bK%>Bux&7vi z8=DKMg(v{;#F-%z!#2<0yhA^XNY7vx4Y5#VqIaSMyguo=Tx23CE-4 zA){eK?G>(UKpd{Dl@`7fvGzHUpTNo>fH-#eu=T}*WEMl6@NiGCGB|fIWYLZ*qW8aN zch5F&N#E0?srNpbRx9C^`}`cT7}2#IKvZXocRvv zgTw=3k&il?EYQk-CnAD>8!IWb4m9rNkV9gC^zhDo@@!;a_};gOIS&#sL|aHjpF!z~ zF@h)wAp_rnlo7J}0LYFJ+04!RZm#1774&O%yk(sQ8HNh`|D2OU>YQGva!WKA=#8`hhj3Rc@^5vA2`NP;DJBz{TBoaktS z-^3YANYZsGmA;Jx7bH2#%4M+n7&FLvpW%=IO*;K56-DOdD}S!Ze+72I`Z0_FbTQ%< z*7^{_flFU<5q$QSXoYoFR)c^m%h?>ypkN6oc@T~r%5V^?$RQ`NlbH1&m=U;bRO)6i zAt>yKy+c@cP)?5CV#xp-PBj4bclbZJr_&&-V8D3CR&aHYchb?)T2@9EBcn`*6+u5@ zq)~qcsnK)IWPNa+m^a|h;N5LUP<8=Yv#xzXMH$$r9&Zo-2`3+?M&J=n$NwDfmj7@0 z+AA;_G#tp-&!^NOD2ED}Y+;R3<2{{fd{!hB{D~3jGM<{?j9@ijPKFdLR_vE$ENl)yf{t5P1F%%~d%VW?a3<7io2f}&4y?d{W%Go&NKv?z1 zHdwv#tB4omO0!oxrxd-<2>7nlkWWB>ZpDgA;ESW(u`Y^AO3$4=;c0eyin-6_Y1NtXi!i`dpoD6W~%XVC#NY0A-O!ez9zS) ziJGO<5&E8 zAnhPE1U~iW6Tow@h|}ny>8q!zmI0#yEEyqqP9DJ){7Q7o18(K83{cTmt}HUrsNHo^ zU7cSy=WA6}3P?aq$^PQr0-ei2aa66!Ho(+S7!XMrYUvn;0gVj?MH#JseRVn5$NRy- zogE#cut=P*5=079D4^&cV3bttf3yf_9h)4TB--0;(^T4!@@oxxJFsgi1F(~?JPSJ z&{9SI?C$+(wYu)JqbTz2&EE2m!`Aj9qVCybO*n$wOxsQovoC#!`L%O<7Z}N&aDO}|ZhXr?!`s<7$o3Onwjp(YCiOacJnaDUG_<(VL@8}Q)n1}6c<>rRO&;85u zQ*EZw0zjS|9Q(zkK_8J`rSa?A5Ed*^>cCQ=+2t1!p}7~=m~*Pc<;#y-u%6V=knp={ zP#LX&xj>)!9g%^6&@->EK-!mqg+eppSXHm1kN~_6=x|hZ0T=uox<0?IsTs}MhBfAp zgQizEiP7C&t#=4=52Dm2a{%~*Gn|7+&Yw+cYEYXV(|7P^nk;0BMBIZ+O1!eX{FwJn zC>F}XB~WSbmFM(g>YWhZKoPs68b{7l>+7ptq~J#&3d#r={532z^aSHw6$d`*g3(Yi_5%3x zd3H6VC#BW_6yS{nv{JiJ3At_fS-tJR4?C(AU3VQz6H{Xnbo5EAR zK0bRwl;8oO+KWi#=HcmvYj#J<2jOHn;v&5G*RPsIC0txwWXV8#CU*|O8W+TTlW*_3 zxVjekGN)rsw{G1+rD^``YEj2noT~P-Y4!{#vWaosz0T&eT~ZS0G!upjDn4@8Sy`-R z1mZcO&{zMs_6jspI<~#L2`efoEp-L_F^kV3ooW@xn{ih2C7=2Iqc*ffUj@46rXhYO zWvFj&uOoJag7ctI`joh!;L!zlie@z5?~Le$6J|P!6fbwD>&x3h9!^k9`EC@12x5)w z4Kyqe3WXGIn89&Y9uWW?3Y3|T(ihIjTxg3-4l0xf`_cXa*$pB1{>jN8d6CH8{_xQq zbch<&!W^QAS$Q$)THD$>Ll%6|ELSsEOy>||=L4N=-{^{(C30M!_Ag5e6q%dfm0JbbeI~sa2 zv=Y!r=_@RjY2@ylG=^zf(Y95Ku-zp%|nl_P~oCx!qpK z5a9V68|NmR-ym6oQmGs+mBbL4=ldZFvlGwN6`0-nP(2=kz?jn_8&}bIfhaUftH&X? zQ8Mi{e&e~qul$W=#p8q6ulGp$xwg@^x3?pu16%`J+7QDbSCXW^--K5~QTY$B-QaavSMNF$d zpv#y|$?iK=YGA;!B}atn6tIA+u(tOR#r?(NH0u9IoElnM^!S61+&SbW%TdT~);BUb zI{NDu><9TOs7-g9TVOhvVNurBLlE^1fI^-wL;O1$DLsqy4?bH;Gyq=E5?4 z^w=@tjYxe9SOZ%31ITZ&4-B$>(B8+zM%>-tdJp1x!aZVvmR&syvz(tDbVrK?(Gs<{ z{{o@cJW(kN^LK6c6dxzhvLl|N!5-I&OIx7n(GDt_;iDOddWezHe@?((536Uv*lts6pl zW)~$ABLdcoZ|CLB8gQ2MDcr)^*VeX{Vc}t6VF4NzMqw-Ugz0U)B_8z*8#WAJuN1{m zTS6d3Q<)W7$L1%BWTG{;XY2=G0_H>a#hLw}o$>P+E5k(-(}c$9KbNezK|pr~DKV4`1QS)VJrfT4JWU^_i9}JG6s(UQza#Yuzty_&teujO_}t;{j*jzmJj<3Y^}2RVaqy=s ze4VUpba+n1B9G8Ekhmn>hO8FM3{uY~P?pfdT4OCyDnh(3OH6blO=y70sQi6N(vvax zKyMVhSZE1hlSK9+)PfJ^*UQTRjtSOv>Xug*T1;uonD@_}zGc=k*CONgm3cqaiW3Pm ziRv~Q2^neLiw}iAwLiUnecC`pJ+ES~F6##FFDIA38t^?`{p?1)w@)s|*=<|rnLBG| zCLgygqHXQHbhSu9tX(|W-ji<-mn~#~f`Wtz!nSw5IDi@wg2%Z6fYP%vGLWl^qw8Vs zUK5!to%e=a-U&rur}`h%x5)$jROui2e z$^gya4CJiafV9JDtZx$&)6}yl8b@{+Ny*02(uCV5?wNxe6W+c10iZ!Mw+WO46c-hQ z$1zs!I}`5%x1)*#Sso9MLWBONapl0Yv@~DeqsTS+W)5XroI4lgT8Ys-V_xDxr;aok zDw8=R0f29NpelR)`rE?mU*+(%MGuZA1>L#xt+#g?i3F%55vVkPaC+qSb<1b3p?HU( zwGhQG)GQiMRE9t=0d+i8?nNG|0^Ho4P_iHm13R)BT~EPYL8<}g zk5&Uti>M0J;d(x73sjA(R%a`82tx=>9W7!^*JGhGv9ydxr{dxFwSbpKoIiW^=dd& z1@wPSj#3U6S1qDKb1F~&r&eCT7)*Vi{SHN{`ipO}r1(=F>{bicq4=REDq3%6nydF4 z<3<+}1B?+hNnyJ#mAH0F%=&(L3LJWnDP-O#1D-M9q~wI6b?F!Aec%WD`uJc=d1-0d z%a_CW_R!E%jid5Bo&%YAQpEPOAgUgXFka!4Gb#Tj$9p-2OgtjsQ)e{gd znz~e!W>3W!8q9yi3jCHibOA^nLPAcVVSq4^UpB?7#ci>dXAu2))a7UA5(F~jfRISG z=_}~Z9&g+~qp&ZJ)l+hC)F*qzm4~w?mp4-4zGql@ zcWWzR({lRCrS0-Jof_cj1L#iU(a2HXcokXhohwT?lnr z=(X}l@-N}=DlIKYTx-RJuFo8(r$E|>j?k3HqC>BYQTyURCbb%6a#1T?=&V6pfl-c8 zUP9USKr0~+1_mzzAYqGgp_lAgGqVPuHFQ^@5$O{|%}ci&4|_+oLN)gH;A5^~J22g9 zfZp4hYHHPB^XOQ_tcSlV#HiK*FhN6ya;(NPHH9AIZEwIOzyq+dvE>1?04yr9F5iBX zjOi>59Uc2_gAYJ!sARTwb{2h*r#J=yutPu3w)et!WWUg$;`ESz!R!nFa9f=9_ZaZC z`GGdS447*KDezw~7%A}T5CG)nPIezd{TL95aNelh3TS8C=BFCEMn3dW9a3&kL1s12 z)^FUXnPPYp2Wa2T09;fs)^{qo+7Sk{Ze0K-PnxblA>eX`yMKKu&2`l{qM}Cr16e8~ zGxO;v`PIokx^P>Oy%3KD2r>MRw6+Cs58gS(Z*kzFRMfWV(cgLt3j>ZADLEZA^_ev% zDIfUI4Gp|ZRB8F{?znUaZjW4Tfd3JVv@|sjhtvL<@WF!#>ZDN{6ar+3&=EaC-asfh zbQViV0inkzb6*AvGX^H%*fAm#hTFI&PODN`ftuks2F(M*U}X(Q%^}siPPIpjqN2K$ zi)#RP4zc*m*TKvTp~zs2Jf91M?a_B4sRs9vrE&AVa6%c$1pa4-1(na?Zssju+vIFpHJCS>n z;I{?AZ-^fhfe>y{F|B!K(URAM3$C!-n>Ph1lDrNZjEM@M0ttVG?wB4#&gA6ezn5Fw z)60u=17IbPjN%Ls1rd%C5(CuxqW#oUk=1tg_v^%|#sH;Bh>0D>xw3(Y7c`(lf*E-! zLK^lo-=KIc?k9>{N97@usF$CIIuUesz;KATtKmtoUthj_QSJOAMcZd$4v&LJ-b5fqEL;;qP~1E+LO3GUsS zi4lOOYkp;M8Vf=W)n**3)}sjsoaku4uEXyHBqSu@GaqI^R(%$~jv4IUy_={`v0>2k zZn6JYPZf9`X(rlF>(Q`}=4ix1gpB-&ww2u6+;O(+(WWwqYU3=5A-J}PBx5*6s-Iy{ zwV-d9A)CheXWXH=%l3y7D=RA&ci&HiW5?)dXmGJn6OKQ85dwA%4mGa+`fH}G2hdy% zfAj)A8`}UJ3=+>9WOiMh0&Bu9)X`8-E-f#&LL?VjN4ZSS&KI~EEXaCx_Iwl?)uWaT z?azcO#rhy#fxySGeQ;((O{)+0sQhn9DHGPXGz$W6vF+Qtu;_|0FF}yu|9*@-B&0MM zFX7(Cx~q&3&~Wl#xmyY5r6JmM!E^7?2@1OJE%GqpCs?5B!_l9{9W1)&N5tGvU}uta ze1S?{b>^QB^_b@jE&*yd*lzi=JC^-EHQD5LEpcYmGay9eD zjAYcVum&Dm;M22F4aG2c7`)-$KH=(?rY4=gmbM_&3EVauG$|z$bH!1@9sX$qOZj?kbQ7Cl(6*3;Ve* zP8~Hc(zL1FqtNdK+Z?Xt+=y$Emb9E-?=fEFVK=Bd~6eK;y2xO$$Dm1j= z#v0CLbZqA5&T-l&iUx&;OQFdEhy%5lQk3C)#P%gW#%^BOObs!5H=H=;i;b6*l#KRU zOgY#A6ao1X`dn1;nGgpxpw@6Wd_ncIFwgC@Fl^|-st_rlip#d|6#=S%`wsNx*bLgE zw$=gB0XhjZRs|xUwY|l~5t~sYVJFo=GAm znf|Mrmu3NgLABZj*&6a602XARosjJg4k9cI*r(QhuBp)h+<=f7cTc3~7t+8s3a?+} z^q_kHQgwWM5J8V1TUH6eNZN0qY&T%?HNdxabH*1-pYnYpXr~pHsPS(fjxB zVW86BDsh$oFs7jdKmtz(5gz)TRS!A)q74C(Q_}i?D6MKl<-Gzq1v`JHb~A7$eu&mL z7w}TZTS)pVOJFB_(r8!3+nO3-At5`U4U8gK{9mQx=3JB?&{`zI%WDd({q5T~(!KyX z1r7O7Pe=QWDMCA<3x7$fX)q}J4G+cOVuvnIfm;V+2RBfMcmQXhOI*+gs1b;O5VaDG z1g%jJ?|_v+hKbdW{>;?lZsDg-=Fr9=azOT;aryFV*dO@}V4m&ZkD_uLA)*Gq0zIE9 zjo$=4`9KbFxN-20fKW*~**|cpojnU>yAqres0tI@0}v8Y2ksI*QnT3gBdq`SRcx<7 z)!Y_J6%dZ3XAvu8Yhx249??X%u!Udd2 z&?x}L6q-_0GT~K6@xzvE2P>R8oCCAZ4=?{cL)CT|H_^)i%RpFzdzLN$eBpXLkPLCQ z9kpPu3JMC~!;d}?irXp>vpR>Hb#8ju&^MJhH6ot}nU#eLjzAvbv{Gn}g1AHAM(y}G zO3hI2kX&9Pm@fIxno1#|$y29KA7Sm8mq5OY0uS)m1pa{_W$Af3@=>1P$pOK(pz7gTE0va4b z5d+++F;fLnp>hf5i_d{_Edz@Sminp4zY(IaptAD9+{`2(E6xpc%x(xrXkbRkIJ#^b z@|m;n6`)lS@XuAVeq3va8I`C%*AzsR6hJmXCtDqtqT;L#>7uBIjyC)*M6!61uC-Gn5wI*L;1g%8q!i>;nBkI!lqO@oTQyQb_@@kIeYfbcu^75 zx@c6!Kg3sDLCN(-^9i4#<~*xtQRQoSR-T<#4{1Y`zMXn27MD}*oI&H`)@ zcoa?Izx^=m4HL^lIB9hyya>=Av}A}qVL~Q%k(XBA{NE@k%{R0XFg{$cfi6U4;5G$? zua1jtOn&tt0>L@{zWO90Rl!4cfA*Sv zn*t*u$UR#aD6ShK^$CJC#xGzipf8Ak>9Xx2EMX%U9 znyACsvu&OS(a427X5~sBkYFH5@SvK5$GZWGTvb!EzG%DFsZ-ruUH3ynah1poodd}Z z+anIKWZxhBe#rrRB0>OCgF(`yJUM{+8g3=QId~EibF=Ux=ol1#%5Hul1+=maR$D>2 z?%a8_5fZscehaJ(N^Lj*c<{n(;lXP&Gd^je1k2lhcRO>UZmu{)t*8*tZrpVSh<0pj zZ0)rbt5&fds;ZUX6M&yd^d98jw(UH006;mUj|?J1 zCK2=P|61bEqYuT!H_?@d26g0Setv#8Z>~9g3%Qj39YLrDAb1`pD$nF(9>gysfC=-z z+FpS$($owb`ankg(TLCL&sObw1ZL@>5;7NEcyUl?VE#Wj z?xDog!>{0mk!n->eftXFuS(v_;0oK{&%R<53)gMhGzkm_;|h2lKpN6l z5VxB$=npLNlC%&)(~G=Q(c1b2mWrH3Rw>>V&uRxxG#RmBPNRPJ`q!jDA!|hm*yzqEWUF`$#bTwg3|^^?Ew7}bS&bS zBzJ3qy+toSC;)P!2=4gkX{Cn94LzqPlgoPE1Y`u?Jafxs}R9-fPkytErk4+8nHmGb{q|MoFdz5%w#P`=Ad z^41g?WNVTgb96s^S*V9vmYoc}UNBe#9?cFdx-&R4||@ zz@2+2WpcQ)E>~efi5+zVWGxAxG4TOuxDWAPC+HCfx5qByw&T^t!lbrFX?P{-D=6o| zl=1KIyn3^pRzLd9#O0C?9~_4wL2r}Bd&i;8a98w8;P*k#q4Dy^4|Tv}@G*jtPaTnX zBhj|N_+ZMXa2atxzzG{&odk6dnM2_HV5Gz&+vqYmx)blD&*b|9B_djCYH}S9`XPzY zC&bnCAbuf1BnJ~35;ULxHSm2u;hCz`H~zxF4_*hchVm-!tN_p&?hFD28pM$G84Gem-o1M-LHB?JoVTo_ z6|IQ4X&n&@1T~Te@BXac)}8vXxEL(=2W%m7nd)>aJz$lB)3}eU0%9QHYru0=avchZR^uh3-mu{!5-51+ z>t0@v5aVVGq_9|KQt<~y(eDMW^v3W{08`-BbX;4ehJC=g2_cXB${!vPF@Wmtg9l7& z*S-3e_^Bdi=)SQ0JM(bSj?@CdzBR(3YxK{C>GWF!Bxa<9$MB@J$t z?-zRyf4H9>W?Q&E29~P^M`uG%yk1yX*!@CklbGmeP-{RE67KV}=^1yz!gf$!iHbT0 zX8~fd6RFC#Z^x0F-;;KCN6CZ+>Bgp!U==i>rr zq@fQ-6qJ3>=P2O@aIImaP4LI#m@`cD9eTgS?p zuv6fNj+!{`_+IcAprn#B?*}7cgyN^V?y~4Gq65l0^g*OiH^Ao%{nqBPz68w`dBt@BuztYnFH8U5T{?jih()&bxtvmhM4$ncw;O8YBh*g z@#qd9CcYCj6?V6Yvq(6A@5zOkNQ8O*a)-B3_HntovGDq(|A(pbfXli6`uJs&orDre zrOaexCL>BlMYI$Nh0IiF*(xQK$Z8uUBMp(Vq9H1gj3gN)T2@xi`u9LE4QwckUAvE)gFV zP_p(F0iA(DZy<)~6wz9iEu(!G$3@diryV`Z_z3?%Iq`Skk;7>(W@VJ!qD^*k7xcy3 zvP;u+qhTQIhnL+73Jl~-C|s;?0hRG^n29LYtJfnQFfGTTcICv;yTeB;)HfJMXFtN| z+z?Ir`BXGCF7PuM>+*53xYF2m9CFx-Y;e7C}1{a?S-53)3E~)MUg{>8Xoy51yaS@khQ{{Z^u>ZbgBLgN{ zgTMUz+&}lNU4kR^$pMYgqn*~RJ6+coFNXHn`Ddi7%Ue{>jW&Lf?$HQuNtY_hB*H6G zt_Uea37*|rq8{&l_N-Y^erEA|r}hRU4K#_7L8XC*ibyNNslOukh@gmhlRds9dOE{b z>Zq^d(89$D4hv-jZ>fkCS`qUH@>f(>S2J7W1J-u|SN<0(!m9MJ5{c%PcMm|o8NPt6 zi5w0n9NZ{n+RPIezc-)nxcBY%G_|4$IJlJVKsMe0hJ@O&PTBB=U(m4%bIQf&wql&< z(MR_;UNKnx5A2F?0rG}L89+Ou(Oh2u3Ue)PadyqI???4$Ueb%&Rpo_QqS()4>~JFI!Q(10;1RYS|Z*?^yI=INfZBq1-PRbp?&ZI{Ay#MvPzz3LR@7(VNgVbe;Q^zJTX3 z+<-JJ^bXK1x&O!YNynOnC6G3ILQ8TP=!_7o5Ty10ig(3p;8rdj&=p_E#ni*jN=u!b zk}g|t4(bo~Q0U$JwsHSe`Yo27m>x+Yr^!RK>q4Yrc(9&0@fw{XQ4Jo9Q7i1_L#M=J z_=IcZMnDeVKPu${UB_@DD1ma}8RIuN-hR1uQ|TxUMj>Zf%uR!fgo?(!CMY7SYS>JU z$K#@+m#LdK3Lc#M`S+z$OLc3rc{s>eRdxC=IgSDC0rK)k{r$sUJfwEP-AJKVTx@1x zB~x^8^r%q>Yh)!sYW%iM?r@k|zEl)!Y#m0ImgnAXb#_(Z>3*B8+iUB^pQ6A`B$eyNMnFYHDia^vOgNngh-NCPkPND?`YeqJb7HvW8(I zAs_#F%buF5+&+k95;w#~HG}mXEiIpODRH`9KK0jz04&|HV=70M4^;1lEhyltl_Y2! zbvw3h=^Q_9Beq4Vg{JoS&#NEB9K=<_S5$P*F!@^jvijr4 zYsg}ZoQN1Rsb-Bp)a#w-ms@<@6E#mbfnh*Bi)aw~zyMU<4&3~R#n&YusDEBHPSkG{ zCA=We3F+aX;58F^bl=3JelLij(L|2MBRW;`$7DJrd}ZPu1!fZ zaaP*HKS$>fnF;UN4NwX&9UtQw51$3YFsiV+!VjBoTlOUh_ zosf005bp{t1~=T$L!vj9f(3v+^s@((y8gbRln&**biK*(ytnl%gB6>p=&nzV2nKP_ z|JGKLX%Lw&0Il$5b?)1#T{}k7Lj6!I9AZ8$sjIM}Wc&0;GhhJ)J0slEVV*e;J<75m z21nEU!vk~YbL?_4Z#rg*(Lh|`LZVF*wjp?2dx=arM-*QjEzZyv{A;Wm|Gc>{MI30e zW4vKH*IJm~y9;9;v$dr}#v4N)u&xoo04acRFmV1Aq+P%aJvAsSCu!2HVMsJ{goPc0 zw6n`)IekGG3(52dlZjpCwoe^P$)$XW{0R^Y*e|Qtek*UBA?Wq8#Q-HSBds44nNhTnEXY8rJ;bSO@(~( zyb+UgmS&Z9=NV#w{iKmuz5vWrtW#Z}<5Mrp`THKD)}ypg^ZC-@ z1;Z&~^mgdhXLs+Of-FvN{Bsp%@4x#Q)=%fYB>E*c$>J1h-GB8F=R5nkK!j!^c3P0NsJ`Lx^Lh5;!6S%wU0g9 z$Tv!YcIA@tT|LUrR}b3Qe61gfeY<1K=OSbjeR_@6}6R;p0KB;&8A(Zw)#EH^w=``@N*43pl-^$VgDYF*7NM!*`93JFkVmx#yE(1}${(a5#=ed+OPD5nY)m2HKMXoLpZ!+VAchkTv~doEAzZbU0fARW%DWr?@|Sfxdq=E=v`Dkv41my9>-PSIKB(0 zNeoQ1+Yy=PX*OQxeJ&tnlP1Y>@+0jG)!tb`38Am>XqeAstTv!!Nf)wSMkT0;YqAEa zflnW@y>-}a8f$qfD_}!l)&c?MfSj&K5n5qrWnzit*4hs zg5;x1y*b7pFVUXOsHOQFv?*iz)u;+sqK$NkX1a-ZOUznjXQw7O$`rm?1`_C=na^mV z`h^?+c|yx{xSW4M2??|0O?bUYPc)j6NVwSguQK&(0J3)J1bo#;Zq1Cv6kdMVk4-Lr zPLY_1z3#VEt@~Le@8#;jXadU8VtfkFN@bjzA59lN&ff4r+twkw!Xgn>_P+Y`YGO=`g7W@1mKeKkt>Gv57Z z6h$T2sK3W@@#bO`mPdFUT5ZFo(p(iWvwTdvQ32_2}LE zIphSNm@DVoXY@axEK7wA4P3Lv0ld$bxA>ahm6zLn(;`bYy{NAJvuqzXX8p`7DLK(S zV%xW_*y!PU_|k$2?S^x{@1C7DC4Eg-_4`h*<ElXAl{mjw!sVS`HY>#XVbV{Q!c{z!RHdW|KOT{iR_Gt9yTX(e z0k8)dFU0W2hPq`)Y4{^BSNP1Og)<=`0r&l!g$uQSm_!(02g_jQq{Y6wM8M||(14wb zCjp?*z2y=vsi2LZD)6gFWh%Cv0_P4A=E*W7626{TMnBuPs^X0pOBoxC6ev?u`DWhr zU3F=y=dTHvvjSTYkNP}Y+(34iIv=h4g6oO@rW-xW)Z5L^eJMDNpAI`5UT!%^bi!rJ z$(MOLU@V4g8=`X29u2|C{)TH69;Rw<=DiM~X1}WDJyaz~5K>ZVA7*?-#$eh<8C5j;$(rTMgPrHR@@Z3&<~IK2rdE@CGT#FhpF&ZwExiqwiB}*y zG;2=6L}WaI3h+&+Kxh@PdAIq zouNko-8A5R#(oCm9K)K-$>JFuL-?jnY-OEu`*yjBQGM=V$Bi4idDQo48IIyi0U4i| zI3%F4i&5Dkz8oGXI1)ZgxT(iGoh9{*4zL``LoX%m3Q!GYdF{cO!j+8YD&p1{2;;z% z#678wXWqN!OvfmE#7D<|J%|7jiAWuC_^>E$IqX;k>9W6~*cN=n?+EwSnEJV@fq2Ij zM&{3tUGP!RwMuo!H~i?_nKR>)k{+KJv3BYwlQwU!eS(yS5IQ!@l;xS+P-+ zm!p;+IH%{mkDPyDw_*h-HysrOfR9L$a{2P!g}2)bVzZNQ)gV$56v^{E>*utaw5zup zd8Ac)SywVHY5yl(CxpqD4f8?&Oj`m#j{&p&Jl4i#$bv;J4d+uXgH|AVwxaxsAgszZ z3mhGs6u~iZtpCTtW#NHZ@9-W``Fqn#koP&$8L_kK8$EUpu4*LEECXz{?tQ~<@nXeS zvzw_oa)@BpdlZF0kR~X$g+44xhHBZ}p_kH{xkpCovoZyf7a}?)Vi8 zc|Em=E3s09*ATykgjGdiyAq8pl|19i^WDHkttPi^*RE^Jerq4ju{^S%_Zd?Oq8Oz& zggaBxGihW6@rkD}W@^d!?k%bMN3$p?LqW>rOWnZIDVwbWwNfU3bjGy(iB&1AK-*m; zGGK{vjAC2X{yo5;x=LDF&ahyJ>0{k~&?0rP zDXAmkkDz=IgT<-3fT;f!P=-4pYN;19p4!k-b9u326Sr~pGBZP>UKGPJLTqsMK<%Il zMv&zs&q+9bd{MJE%93RVjn80%{{|V9u?L64cEt%yWC)zAot6BKnoqcZ$xsBJ1(tUk zI$ryH-L(iV-4z?IsC~@Qf*wD5q`-CY^2&mUCJuvozcbMg{c>KHmKSG;_ysfJ_0#9I zy_8k3`AGhFm`rg&sb+bYTO4+4r9NzKbuHCuQ#jt%)bm*uFT%bLAz*8zK9--}y=6FD z1$4M@pVLtS(OoN=$NEgTTspO;pN6L951OZh^d&S0dKvj?uJ8%XW!Ye|+p-&mQ+Jv2 zC2r-JQ;+X$#eJmkD)snT5( zRO2KGGR2vRD-=8%Tfi0EU{>oPoVA)v@wV38>rkJ= z)mI2xWFop)Y0BynDopH9DvUVyXX`TYiV~4aI;7fu($A_(LY^PzsAutq4y6#qwj5D6 z2W6C0Vzsco5C{2EUH*FlSFcr0LD|guc_j5wNAH)FlpSgBtT)9qkEmo#?)-rtdvQ*Z zX%^-FSJPfVVk8Kje6cr`I*YJ!6aXZGF!T*??(j(a0=_n%#$kP^sM1_&BLLj|6l=L2 zka$v`Z6>Wd^JGXF5J9){^DnNO+FVJ2`4*d6OP1xL=LZwpK^ADGddFKyti(!$oSYAQ zPui?M+p}lSe|5QxG7KFBH^3IEnqO2WU8Z1U8FlQ7mrtLXs|MosgOp6YEH=bY@x1yd zQM-m9f|=~1`|mA6Vw%SDl9AHomh)|?%bsOa`ziEWfL?I06C?q_4eg7XU=gGBZrlh5 z5`pQNnLvS5rVkkkI|oT9)3s~Awl@tri|J$}*o2~7E}q$?w`5GQp9Ex2K~fF7$Ul=V zT=-7^EHGIW2MG>VJ(p8eTH1xBz9sRNLvbpR$oB5rH@Ngs4iC0+3UB28&s9b> z9r@4dsfS4cWlvrR4*=yQmfNz6e2XGEetNO>Q6dg8tL}+hVJLlmXQPu7is8L`gPB#! zC~A7Mo;;zVwT7BE{PS#Takm~l*l6_><{WDW9fyvcHsNZ5D$N90X_IN7qi`?_y3}CrqdUNF+#14y{U3o<6OKmcZsI^E z$5>i2MvXGLdg3NUR8q1*rQye9S}x%iFmRy1 zpFV8>LsdMP&F95PAozY@RY_i+=*Zw^AIH$7*cNOo!13jPcmlG}REf#(k;1!$WR?$JPUDlNAtpI)rU6 ziW2>4ljo~|RHa+Kg2kj;<2zx%%Jqwt>ukuf`bC+Ag`YF5eVVVS;RNwX*mokrG0`7y z5*Ien!_@AXZ>!V`=YQ&D36o1>{*oE+@d-zq7wy1LU5 zNe52Xci+CKYyBl^S?-J~*txUiMQe8FVO^s{83k{e>NcZ1nuS=OKUWr=_uy2Xxm0?K zp6yzZNDyk!UBq-?K0Ddc=VRr6KApojBsd#<2+}x15#FOs)D0QhIdu|jr&KP17}-@5 z2SRNNEs0?PBJi|3G8+i#-Mx@`7*%Yp{s3}|@tA*|u-BgTtRnU@mQeH#WTf97ojqE7j=LPX zzq4$G*SYzh)*U3q$bgud7z#C>M*{x(j|2;94upNG8&MzE3oY$8ZQ{|!XI>OPeLC)? zQvT*-Bql=LfLGTfIw8zu>)yNfFZN#%7iU)a?Ag7WwR;baYMrOo#rV{q^| zwP~}5dh`SOobD9YCZ}~v-1pR1jco70cOQ5D{4iLb%wb5Xl%t{(o4UA3p!|mm3Y(Uh zoh>||DC4Nfetxot{Bb2n&(OeV%|0XVt*F`Fk+MRuwf8}yqpE~sLZ$l^obau=L~rKI zBUnX*fE5uz??`V21p=A)T*9dpd2kv&eZfPfq%?39aq;o3{_0FuBLI~v4z1+KY$r-! z?wRp$OVQ2`T_Awx~e$FN ziLD7;JNH%Ogq9c}lA%+h$kX)FIlaG&J@a0r!yov#let7ycet(xSiJahb0?&h=KAKJDms!V0&-*h7=SW zUfJ2w}MyO6v00;jLO;G406FqdvD3Gt8qw_D0K9-Oll=x6s$A0z`;3=~s)%tAA9*~xJ1H<+tT|t}(zP-e zF`5+o4;)y}bxvN?!y+;tX61{pX>G1oZA_0e6b&bz*l^xt+I!E@iCGXQjHj8y#*cpn zV&ZxOi=)L1I9{H{1F)uFUF}GxZIh3Is7L#cx%mYvWxH#j1(6 zyELX5J#V2q#3U$xT>ii@=HGNI_r}^Ol(tSB`uxc_^W?UAAYe${lQ`G<~$vaAn-Zg{a#LH(+p73SiALvP-^ z3EN59UUg4%0sgm&w-PZIa_s?!oobuH5bgEua~@* zDF_^8UZ1xsZ#LS}Y}qP{ZUI%MR#x|4*Iu?Ty;zK zt_SZ>#eajk($OFH?|(4E;VN_tr9Ul@j9-sdx7m@@qL_|wbr#JHhlLfG{;1a6Vmhoc zg*6txGFDfm7V`goIY;~q)s&09qw17GCLPJJSwE(CK#p3-k9pJ_TTa*or0ZFkH(j4q zIM$PgNhGtqZ@tn8xkpi(HR*79-?^RkuscfG9z)!CF8a9RVjTAJ<>G%*c!f-x9u%`{ zzi#EU;GiJ?pc#GkFT|y8WHdQIQNKX>P!9f&A?oS}ewEj{6pS}wHG;lJP`P&Y?7ge6 zcyEzRLmmV>GNY5`Vi`HPag35YImX*`FeA(XoZl%{Ck>nwm6YT}GGtZ@y=%{vPh z&Xb8|@NU7?H-C0`&0lM`VCAY+`bQ#_UmB_YHd-ECexUXCS)N0We^EOgHRyPf&%-|2 zGicg^K|~KJd-duf)dBUFR)!I+D;H3kaZ+$kM!CkKs_-wEv1o_%FuQB_gsz!uT6*pW zTWd1y5f%ho&fIrhariTz!ry?gh-B0-kyWPuKJu_ur_Y>GA2=|e&^o9gBs6rGjFi3s zPlAWXoBuXo#| z@hlIDzqeS!@J4&{L7H8Yp0CctF#(_j;qYSAJCUivQh`4pW!X%XOgZJr+nZx)WD2kg zwp_S;^eg)nD~jIlc|s#QwFR7vc1(xIU}ri2*YSCQOQW~wJ>mlzCjz^&3+Y4F|Le)3&*IxO~jacjMo(aW`E#YTg#I zHQxmq+w7P9z4lY|6GO^R5gMd_w#p_h(NRI$?#fPkE@4E1H5>h7MG<-oOxQ-8G`PPz zHqLOTodv*37ig|>J>7e}Z*?Q6B;|+{C2369%-L09eI9Opvww zaA~{o{&ZD$RO-@}mQ?nFux@#=gF{@^I*G&jgVS7Vr-Tc2y=bci=FEAU3pB8bRZOr@Isyn*MXN>HXq=K-3`o*mck zsAanQ3s&O7@-eQ;?zY}P4?PnN0q(d64=BAG%kDOpD2mZ7EC<=(n{Wg_-UJ#nx9jmzp;mdYvn%H_9+=oQxRy1s#ALT>@X z5nYf+5VUqp3CECyIv~2CFRhpxP-w@_nJT?zVe4gj^ava&W(?4nKrZaGr@vVy-^B#A zDMmrGmFRC&?!3qUt}fs!6H}L;^!Vm|-%u_B#(zR?3%3_r5TUT{Jl%-Bjv61H)v2~j zmyLhBS8H-U;3tuxwQPF+bHP_5sZzpoEE#|l(3ImzpXHU6F{e&3H6d1v>gRa;eT7+l z$?YqkI`lQ&yGKYuq|=<^6P_~rsh~jmOOIv}ZP~yqNaiI?o`suKfOPY~S;O_^(Z3y# zBQ|^7Ietw>V%~*ml+t}wdievBAdz}^+B3m{qp4>=bw=+Yv7;_<&MAX*5HDde>>LUQ zgPDmB1Zn;gZjM&=8is&Qf~8xyu!x@8$bLV`anvD+moCvhXl!I;AJp@oG^Im}KHmq{ zW;q#|C=sS@xlSawbz_cUy(mj@{r6Kw^T>b|P$v{DtTW1Gx$x?`M=nlIqYve%mB^LB^T*;G2P4kw^*kA#F! z^{-;Crf>W+d>SNWj{Q%3_Z`(ML;U?~@Fbz}LPM$eN=usZl|+}hSDz{?$1$-6ZeDFX ztK!U*4rCS;;W!vQbm)E7?*0$GC3Hvm-t=KuKq%OqCfbprY_)Jb!0g0l&m#XQNp$9+ zWYF5gtAV4&uxg&fv6u4LuQ?F$En0dm(5ri;0m6M-zvORT&&5eZZJv2*a+@}7vNW}O zx%c85rBMJX&UxcTq3IJ5v^_!z$@R=AqEiQY0AXy>6DC93awg$QDrmfU*H__bTU$nL zTw|v;o#J-OmUZveZHH8WB(FoO)~(Sz#=wU%(Bpq$I$u04yw3u3CRDH$1mMOSfm@G{Y~eXN?#h)T^Eb28h2zQ3 zb0X>6Aqh{K6qMWucjVQ5p%@^TqIQ5ScXVA-|s2V zhnvExm@#A6-sXOxp(Pn?Fs-Xxg;f?3as*jKn~(h8pC-^CgI<)E(EZxpC#%JXFE)_o}K& zIQ$WY+~2MbZ^Dh4{bYSG$+&Z@ku4nAJluq)t}q{jv3{neJ+;65+Xbd(XkwzGepPLR zkz!z$Oxu=Gz0_~0h4eQ3af-%>m>9;D_vJl9kc<9T=EC5%#1n*#^b=X1NJf2C^ZF9wihz1xuGSY=~@iCuEn^H$X}CLThk->9#^(lRSy!NY_65 z2OO_f%i41G+_{r#GZ{01K}vZ%P_{TL>kJM^E+D#7cBfP`iUl4zEFf`J%;kYx9Z)S+ zt)i%)!}6|CPNmEP8qV-l@?HGS+OuPHb5YBAOdwE__QkY72>l?1_7cy*+M(4I6ynqYEt1G7LhgNm_QfUGJ(lx>wil+qA!bT`qy)*$E z`J)di#1~vJJxjvpPOV4g!?To_knk(vH@9m!oq!!$zvgJtNwP3+1JonZ>-ArSHIqg4 z(rAqjnPktO+M5x*^m{hJzJ{Ma#R4*#$1)E=C3YS8$h63@qx%;MyT;}k{B z2B6O}FyJj8H&lztx8uYEkE^~|3452h+g;w+_n$u@sl~uO@>uBC&-0Nr(2nqTARchL zDp#pWdjXDICRk0G()?sqi&g^9Hg*nuK;SNIij^1~n_}ex+9#=QaI;r@{22GYs;rVN zge3H30X?#WXNl@lWGR&_p8~Ue^mOpO&-{on+SPtacnwuCUm~Znpr|MmK^sLB7!y`? zSt5DbQad!1UY6kCui#2@wCFU$Z$o}%k_6{U`K2&BL8BL8gmStt8`wOMd3AhN+(wg_ z+;pn@0@p8>2VSkdWdS z27$j3{3&J|Ojd%MbZy4^SKI**i$K=dxI*;xUu{SkDHlhn0-4P_cV54~f)6$5&$}P| zmzb!CN`fcA_B!D6XMT%mIUwAZz;Kya4Zm>;(7^bW^MQKNkm?`)XbQ}dp^Prdq#X;3 zFtL5Etu<;2nxL0=Wo4T9U{Fqy66>n}{an)kW5BQs8&;QHDyCZQOCe9&G1iZg|~B;`tUc`BuIz00pt|bX6FXRi^`b%!Uw+ z5(Mi%v^aonP?#xXxee>qukV-T#~TmNx6AfR7~XEzP2d5cgujmYVjb85v-Dd{c~&=i z#OV1aRXqB(?vS4H5By@fN=BBJmV@MV>;`lBB+&c!X`sVT$d|LQ>Ep6MwoOMl^5#Zx zTasbbze6z7l*0`(U#(-4#?f3L8n1pS`_DX$pqoN z_!^f~K7+7L@Bn#G)|gt@5Vh``yd-QHsdx5YgFllv1SF4%;Wn|{?*m^r%hyGJ9~r)Q z_~=fIgC^<&^^n&Ya=2*W!f%nI(+T-hg=ml-2zoyPdQjd1J;kI$5cwTWsyrt(VG|Y$ zev)Qd_7$}m7|~2;V}Ds6CfnEWA4f$gx84!{Uo8=)OQ;tpVnD!h&5-8XJevULz1~A6 z9&qH+9k|JP4Bdb06((L{coZuOsh!Yks*28s#_wn@@qD1tr7fZQ#Noqw0Sf3O%s9n~ zWcl&~Fxg=4oy)YQ(JF|>$Z-b;)EYfQDc(v$4vjEBSW`FO#N)*~Gr?MzWP^h%KYU=S7diS1=}Byu4F9qP`#G};>60CWPRXuV#yIa@`;!w4 ziPDIM3S2mJ^nKR5dLquMB}=+?>(>88SbV(kj2Wl8M(hdhK*n=8WIFf{s+&;Wn4N%I zKy5tAn;A+pse(I#l{VzR_~N-dJSizSY6!_dbJxhgEMLJb~){B3%4!=@>AVIK@zF%HJgBnfpFzWw)Lrk>|u=b|X0PhCl*>-_ViWbE|@tDn33rWQpPegT#MS?(264 z!j|4s8gfl>#DN3=ji_GYfttoWn@Mz1rYYrvW2qy7;SZPG+RZ|BS8VZ@i#kg3?qC`z z;kKB?r(6B&1$gPv2t)V@J{Z=72Rexe#|L$1_1zGahwQNRAP|z}>%M#;=$yWIaeWId z;j};~?%kzJ4I$KE0oi)aVGSy$8+mye8X5$hK~b z)N`~jlOR{|7cYvp_4-@aTUdN}_38i|Mo^IL;>BVAyNmilQOdQx$F;{SgCOQ$Yur<% zJ*Y~pl&q2KZ>WZTa}ycsVL^dtsYNiRTo^cB4Z6$e$!f7!kgNcb#gY_9H-A$cH>7`p zy8P`Vg?fS}-h>RBTDVi@`O05@M8u`>ySub>JoX>&h&~fsG#IQ#cH%Oy;(9~MbBY}c zQ&T|M;Rv;DI$`WUA-3S59Jyp}Sn*V+{yG-Id5eA5x7Ucbd?8KG)K8eiFr-m65p3uE zhi7WcxYLzyhXoWz3*0ULmz6|{Amc5g>6aB%oYGYv4AEx6h+f3z==iT{4aX1p=} zGI1qw5p%a5+9lBML~kdrD=8^wVq*u5*J)rXm2jQYtV1D$_a4S#q;0G?kep_^+{Erd zl;&2=w;8G>Bqq9%$*Ju*xbsX+)zqJyKY3ELl@Z6amQ4yv5ufqsyhV%PsH{N|#G(rg z?|!z>k$0q`#72WE>qJoeA6F;G=E5Vn%X7+y0e;aYPo6!yFCo96Am(Vg-l>P!1BP$n zh$q;ABw>o$wr|fq2Ml2r3`{2E9#mk?UxME1(E^WQ!JwWZiIQ))FT?|0guaDNjvHw5 z5sWGTiLlO1Ta~HGG3(gA{U9~9E-arous1>tClnDBYvV%XhO-AQBqw`t5(9U38q!ik zSmE^lMK=H(DoCIScE;n&9u7?chNxyc#ebFj^+qEqSza`{9zRafhjinG7-l+nfxdn_ zdt`EkR^45!0Uepue8-IoXcQMO<_l8h7ZAdCj$)T%^bGPrdv{s^j)FG?dS-WG;-9$} z&V2Yb%BVV*R01H|w|S`)Ox;Dy}tM2$ziI2h0B_=M@=-Khuz79mx=x$!quq$A%-ORD!3lyTVD3HK0 zVVg*%P{RA51iidAe}3Op*N7TcOl_iZfj9+xj;NBTdq*%W_)~TD`Iwk3Ww+Z=_oq1A zwpkB&!#t?H@&OW9&rvJqFTLG%h_rZ2{zP#e<5^~Yv8k&`-5QQWD7LS_%-oo$$cON3 zo&DfJI-v)wE{K3CQ}b~6(UcL>KqGqR(Ek;+lyXNqT6YhwuvOa9*oAdjn{Q?Zbv^(5fehE2a z(tsqoQpDq$;F6b>RY7$ZdMS4Ko4~uN7u)W-Nil#sv%j`>T2j)2w~JD4og4F(-&;ge z3PszdZ(rNVefVWRu5VR!8;^{>Ti0kc4!3_1(K6XbWp)Xk=7@6vg4|G3GI31sq!k4a40gtHs$o`y$Qq|Xcf5U{)s*5x?qwn z|9tOw1$kc7A`-i&y&}oe~68U z?~sHvF45exhI`Ba;RejAAFSl42?#|CjEuVaWFYK4Npri(e$Cf+0z*Q^@>3XPp;6H| zjRRIf=JulX5pfexdS!nG4;t!x5mUODMD&9X{?Xf8DyVklC2{6ex#(MfNwj4+J2@?A zDpQbDq30~wh;jI^+PqNkp+sjW(Oov^K@njPX{%zq1`rQ;gDAQ@vMPNU2IA~{_lUVa zc$Y`)8aH{YFVJ>+(!Kg)Df9ZxH9K!2M6y|v6nBqkRVBN-Myx1E(9Ps@Q1VMZyk*c73wj_e2;Me z-0|&VE;Valv%DYNPY3=3T=DIV*%PqYoRiFL=sR)C&O)(m$gaI`B;t$WKB$lP5BANl z@$ED5N}Abf^Wn!PZF0MRc;pMO!sT=Ge=OF~CdqltlIp)X>(x5Fk_%vHTUi9$6??uR z0?Az~XJ(I%#q^o8Fqh|Ezg`Noq$)F+kUt<{45U$gP0jaTGE-@!0^>H&`EC9E^6V9` zD-eIpw}qvN;rt7KCEo8LA2_UU<$%6=V&5;iIFt>Z3dDz@5Wx4Qw$Ky9`C$&lnl40U zxEfS7*s4dOBzu}TNPi;$al7&7o~FPOz9B zNX9G3LM1Vkj~fa`G7-#ZyAdJxsMfJkIzS97FT_a#)Z%xPu3pT&xnh{-f}s-y)lxxd z$C&rmZ9o_QDi|2bKY&5gZ%Oiu!P0ibV7P>m3rlve+-U#ZNVOR52@i&E=p*y1X_4Zo z=qlxd>}ctKOnt~|b>`7B3YO@1l!2(HPoL!gRec2MjFcOqq%=iY8bZJx$QBUadqSVJ z!UYF{BE#^-qe9MjTr@FwyPX)twxL`Pn@_9p*sQ*N`Lc*3z)_}j#O9`?^}V3LIOKTI z3&YwxrUlI)*I8RP66}Ty8YC(uzBAf6kbl(0NFdn6NmOHQTeTUkOLgt-JrjOh-+bKG zuV+u5d<(OPpB3)A7);LI2m&n(X`hK(@LBKboy_kr!i7#-LWOXbDHi{7poMKY${)p3f;CPN3#vB81t9^>xuBW7=M8%9WsOHU=^5ojqN3>Dx|a^jy6Te5oEF5wqg!8xM9k@VOzf^!9kT209g3ZZCGg z)ScLVU|}ir*_TEAy_fnwd%4?sfu>Avy)Cn3J}>&zN6uZz=!>=WhO36o4>q((-*zZz zn#JYi&w?Ol@Mi$6!O3)9<%UjrnUfPsX-?@#_5yR&fBi}z+caxd2VEn+E{GYXli%dC zff!9p9-%vd8DY2- zZ67=f(X89OyMBp{Mo$ru{`^W|Rt5IhBS++PjYi5ja1A)8BS(Jbfr4smf72==uccw9 ze_N8brPd{tQ$aGEzi{Cop&pGL)7y`6ci8F; z%H5c_I6(e;9{e<=1Ezzu*O#@_HNxw1XzN*kqP|PHdZ+lo(q26~++os7_v$HgvqM?4U;xip_P)&wK09%u zkFF61DmOd(2cJRR8~xVv`9qzd83*=e*k}&$i@NsNpw6c~%Od^!z&qF-hWbv2%Qkxv zX>fP&xpzC2x3=%p>HfWY(DJIfMkv5a4s!12W`<7Mprt&(iiG7moibF~Cxf$iN^K>s zd8Cut%t2wLa%YCMZuQ%t6xlBGi-O+rS(P8IZl5@^e40|ZRV%40ir3!#XgvuFWtzcN z?YN&u9O7_BlUGEmF9)1ebqzm$jH7Fh88iiFfV{Xw=s9NW8mb*)s~jHjuOBV6L(f+| zp|XE^n$m}@q6Ui=xiNmSy#K_6nM}C~C91S(R9$(wwflRA&#y;!t&o=st;*S#b*Mw4 z5yR7xiqrS&R4`?Fa$TzrICP0^TYi3ZnAclt+&ET_nwpzqFuwHZDzOB5rM<3E`PfHf zj{{%0bcsnxC)Kj)-%*d)F58T1DXth&77l)dre+YQ(6jfH@H{RwN1%MwSPrGNG^xh&no;=Nu??qe4c1nH{X*bX0wTwQ||GmmYfQ$~ghk zOpN{4(w@9w|Ipv@pW3Mx%jt zBCj;F=v3OOX_GsA`Lb~NWf{v>1-bvm(iKC69-5(!=f?gZI5p;9hO4clp0Um45t6{rI!-FKt~<1d1;Uu& zz#vfaxF)f#?waz7_`^E!ew$Nc(((g)b!&C};6DBO&L%@cS_lq?JkX(aWK@(b&nIAP z$J;iw7-Ufs)V&d486(4s5ExoBzSVbI%DJGBE7N$uNBsQmi)MmG9a0_@K2;3HsA4WF zoy*MOnq-%!$TtXoM>1p2q-fY@<{B>zjl2gBs*kQs>(|+Wr@y6%o9HAz`Ycze+$@`j z_E)0^b`*v8!Fs^EOLPADx#G3uUC;;?Kwh{gc~MAjC29~i!0Z7}XpxmBJIKk24I&^N z#JgI=E*KvQY^n?1Ba4J@jd~VUzT$Orok8n(!{RWfY=|b<|0UYEb-V*DgbhKE3wxYS zjuRF`L@AucpXq`o+k2*^xg$If#^2n}nYE@wm~S6b_Aw*Gk=`CSTHZFWvJ$ZHqGQ(C z+YsfcXoL9nqSR*IxL7%k+{zRLy=@6Uob-$e*<<4}p@c_C)Dy-lCY-gmn(ih)FfZDm z2lfrVRrp~=Y8y3~x`toiJW7CSA@9sNZk)P;C19)t5O`HtdFPx{Jc+Hmi}E3w%jDH( z&M*o}PIjhEYRi^!dv1lRc|Sj+j1)b^sE`h-%H0DtUV8N8$rx52?>HV{WUbt>c!Bgg z-Wp9*Go^E6Vz*A2SrXuQ_ujpI_nLh+dKUxWSv(b50x-=ojE#H>Jh?KuxIgB}bnnq) z#weHa=ts`Jt~KT7pIP^kI@jD@s+00WRjD6;jEd~t2=*PTwwK*#ER7x#H^lN%Zit?8 z*}5^5b4}Kaqgl2ygHc#w5Qe1H{lL5Za$)=J6XUn4Hv^rYRBze6HA3vr6)sD*p zBM5s`^W}?))3m$<&aTk;S{O9nwwNQpLqPwcpd3r*AJLd>t-;Y?9ER64G4!Zi%jWFn zqqzUW|2@ph6GOHcZp7D0n8j4K8P870@1hs}zx0*dEWINbtRs>`pKd?En;b$KMHrRI z80IcLdmauAU5odB)vBwI$n+`lG<y4S2)Ca|1tNVzLSFPx+`kc9+!jxvKkq zh%YyHLgA0;rf+r7GAI42X>lkAu%8EX!+TC~a)s3e)Xw}N^hZ_FTtKZw<#AH2@}c`F zNvJBR7(KKWB{%J72DshXIT4QGrek{2jPJJcGo z832u1`LZ9#kyZc(EyHS`jEJzYwVh@ZMB33`!tjUJ>&8&D_Q4hu94u?EDDB1QQET`} zSg`nRB%mveH3L<#@()+Y(vfH{5t-?0VoIU$ETZw3IB`TZ} zQdhYPH5Xn&v4QDOV8WDuVv^t&*3Lf0+L;uO& zk98CSPjF~pe&eyCUoS=bU_>YY9}YiYj{1{&N(rcobaZ$AdnPi_agj13{9%QRE{veR z{4P4>NCo}Znwgp!%6!RKQ*5Bra5_%UpF7icwb{3w$C#4p<~yn3m(hh+m_wm*=-i{D z_RxtFY1F7pZS>j_diAS)|6$+c8lJR|8`^3iajBECj8yd9oe`&h{P@!lZv4fPn|t$J z2lqt|ACH)LGif#;MNha5Af2(rG_0A5i5ccCY6ukq2Eyq98Beavpo$Mmyn>iPgd+vA z3?~sUbKU6<32O+RgBajw?|`obmW*hrwEqKx&V3_J)0uH3;xuIeOFE5YbR+ZWZ?e9& zB^tJatWx)$HNf?xaBA;LO0(UY_8&cbm{vw!{klD2XAT)C!)CbtDS3v@Fl{e$>O5!x z!I(_)(6(nw#&oGY3_F2koi*75raYZ^N<9JNdMx5JvRqwM;P#%G8`u~?1p-5V=8XM@ z4Vq@^zqJy#=LeoF)hSq7aBu3tNtZWuvZbtXaG<4PP@Pr<%*h3sBnUa#FKPlkxLc+0 zy-El4K3Uk#w2MdV#!L?;=K}$9Y|YU>bCf@V(EayK40v=3K{YyB*NWf$zz&6#D{1PW z_sd`APG^3)tkwl69B5@`X*p}<)qx87uC&m+s&4?5u`jpb7uS)TjM@#33wUEja$>bB zpohNgtTrmiW>MHmDg1dQtttY+-}~GcaCUWRUgAu_OztB403w0V_5ILElc*Z$DEy5aN;evIZkRn~2SEiYC@6I4qUhY2YsgnC zFh9EuJ^qJO{Yc91naXW3h%aaB9UrHYWT6WVZ6(cG61+$HKK6TSVqw>OVxboWW6(`@`YufT< zBlI1BCpae;E==BbXG&hhvo6`@BjdzFpL{BW;Od5kkoJ8dX0VndynpMQqB9G_s!R}*#4rOrMq+y3uYl@ z^;X3CZ=RmnA`wClLg^lekQ2oOi|en};c4e~-+Nd8VSMmDj%364?|OfXW7qDH(Z#47 zeCQBe8a-rWsFaOm4&uBx_3%UMxqVIq&-!Bga<_MSXk@+}Tm~ZW#FX{bKn{jIFmfiO z^39H|R`f-|frQLj4o_$6G*m_^>r@)yh|w&Z_&~Xxgf~8EGAfN)B}6509qul;*T#x- zU2T8#Y*K(9gZ!|6;Q(sAV98necDlk`K;n2#)Z`B0qB5E{Z>rIJ`o9hx>XBk(VQf6* z(|o4RuOMHPuj(AKw!s#D5=nAucAd$Bm?J}Bae^d zU1=#xFWi6C&S=%Yaq_0~U0V$=EV5=S>~6~inma6CZUg;C-<>x3W%r#=Yr5%wGSQ%c z><2~qii{oBFVhXa*!M45Ju6ba=wC0uYn%m3E)`P`_A<_tD_}4AlO_>HOb`PhVyom; zzG}y?nnYX_617&L4_G>TmoUIl#3wYK-esgPYd>gk9g{!1=f7E-6h7MMt>J6gpL<51 zrg5&picx@pS+qi{rtAyY(}6=*;dq78g9d7jAx(iCyYtqo3&mB!|BDJnjL55StjJPnTQ_%Rj%sVq$8Si) zgk5e&cBhsSoiw^M4^59eK4$%t;%%ZPXg}SE8T^5tbKoYqYJae%0Mgwt0h$gbyng=r zb@cGz7ZVab*ViK-m)5#Ke=2>O3Mq49!e*sQ&)9oLM^lzTpZ&?pbL9&74`0wx$Ydfq zb>o^O(oH~iR1SNyZ>9xTH*MGuQSxpG+ec=mo4o7(fJc{YCbClEnfH$eqy<`;J}e1 z8O$1x%y-A(xVtv3VYwK;j)Vx9q%5iQ+sup;vy%8_26PrtCS~Oi&ym98%r4!@&aM>u zzZO@^Osga9HEYotM#Y`MPy+RVUE#?{8rJjX5q>5vzjv534_^+hMIVG-f2`mn>!Y&q zMCLJn$|s0;<&F%Zqu3?_X668>!NDWTEe~$}Q|MgAzK@*ei7eLc-@@c&rk4M`QA%2^ z59mdOrNe`COgUS5;@O57XFeTPd%xA~)}xwkXVPNB(%PFXhj4A&(Kz(csZG|GLL)C< z{*ILx`~|JC*3i(O##O>GT_fc|VkrRqgI~U|h?>>!!eE8(g(FSG;>i$;F?A2XhroJ&i;@uM8U;_N{kJUH}8BA7C?Cds0r- zf*T22K8UBU97MD<2K?j+my@^=NJyZ-8#a4@Xw###liON+pp~Ei5%}T0rnG;T`-CdD>@nT_oHOWn<{qWnVMgu!;i^~v|a6E$SA`t z0N)66L8W{8x|63_-raU{1K$8dbB)UcXJ_Y%h$^lLH3rufNfq@G%_Qf+1KOc*#8Fxk z1?ccExHJeh`N^|qSPA?h)KcWnv8{yCGvM{(!a~?h3Z|v75CzNLQb|&qh#7?d@+_dw z6-_r7b4D1@j$~{seI~9?&z|3DW~Q;LB1^3jRaB_(a5dO@zU~-qYGHwkl$y-=VCbAv zDB}S`H>OxZlHeS*xhS*m#OK3>&WhyLikG?@JDF^$dw(UW^E9LR*kUkjt9UFK-m`+ zPW!h1oT409QBUh;QKtkaKQgMHTx*7i);wa=Q$$tmAw@d zM5c?4bA++g>qcMh>7f45EDL-Vv~L z@VbZT1#d{7XIBBxW!wzBoh&rsr%yvuzS1xt2nw3aAan4Ciftgsn9aB86xUA4QI(M* zvEL_G+;vrg8=aDObFuok7Nuh!)H~!u&QNEe^em>N679)}Cgl}EwBFrQ> zPag=ArZ(T)+3v5y%6znD+;l{l<8wqK2Jkk%e?Whzb#4<@6A_4=mjo#oy*AL(tEsPt zSY|K>Cz6W0pqdAckZ(|Q(J=UJx2zr-gmsDlv7sCz70+KrccS~RF<{3rV=hA&W&548 zPkfW6Wq9e@a=f}x?T5$Hfkup+rz~wGLo!!cv^O8%keZO3Ojh}QGaq!Q)1DDJuim|L zM)sxN#&PygFmqj-scp~xEQ#yh5IBKZR$w8VgT$Dqd#4zTfe1)3Q;hWYwZ zV*rE6CA>?|9onJjrrl%q}Hzsj@zG`h; z?^W)jK6EH^*;5cvj^=*CstLDGEFOW1pR`UZb;!4C+c3Jo-s%k)HWLe@zaTaWvV5fZ zf3v%G=I=}B3c*E0#O%Ty61LxCVwOYK>up%Y9>>(B)2B1p*%@C4|44JF%dhY2-7F5Q znEYm@fq|Gj+kZy!*Tp+u1zs$!YAgXk4N_MJVM0(79AhtC+Q|1H+)9v-6Vlt{N*&F0 zr`MAF4+@$g8xtD~FNSO2<1Z_IFil5Ul#m@yu)GVO8;vwro0>|gkAu_rMpv5*iKmX!d$L;qZ0=LP91AP80qYfgt`CLm^%x5QO5b;I}CF{_y&&Pm6(V-ccR&1jh1g_O9&xNN)yS`BT6MgRH8wH zp_DX8#rHdJJ^%muzO}x4y{lI}xbN$_&U2r8ANx3teG8C;oSs*3u>3{C!Cfi*EI#G8 zq-EK%d9y5)GenRxXMQjB3h6_VS)3t6$9(j7PxNCDw$${{B`!d z#2N3`YAq^xevjV<7FMCTdD=C2H@zr1U%t$JGP{L_1;{#wmT-Ha z@t^%_Jf&w<{xhe)nc2T)!SjsF^NkvM8BbGr zx++*kRmCK^nep_HRZ8)-gTkEmy!OcMfM!|q!;tv;!+G%`c?Z=8RD|YT4-Q^5GwU2d zj_nxjA1xDWGe5XCuutOJ#iy3Pd9KncA^7&Riu_>JMbm=^W-WX(UUgm8@sDqkG&D45 z&TJmGTx&9>Cr8PS0aHloEG(i1-y^Si@!~~#dX)0h@R9sn8`(9L@IV=BDoc6dS&lRrUo767}Hdg@Hj z@9P*JKW0(s~EK^oE8kQEcW z7`t0uRVDthqQdwpdwANx*7hA$rw$mfH&``1*k)mH!Q#s88&$JTA5dLB{czU->x{)+ zvCs@PExKqDiSjo%N5PZd9C+#7}6ni;{9jfa|PO*Q;P>c^&> zGH`$rH@?p8Cbxv9CvB6JYu7Gz7SmUSf!R&BageohbH%7upmnN?w);*rPg+3b&x#fk za;ZHLv2pTkcXJzPa;$(-Jm6U;v7CqQm_%z9xQ#<}%Jf++BpTWP0Hh@f(5G-V{_ilF z6sn@_J6cW6zw2)^Ft5bKAX*jRzRdcXxklK*=bFp5+zG|Z1&IX*gcv6WKZTQ4qd9Ig z)MVk|OBMxC$zN2mFb+~xncg#X+G4Dz3J#x*JHw})!h$om4UV3{2MKfyiGHHWcZ~}I z_N2LiZR;ANfo%uH3^vvq@HAkj%JjCAwWe3vP=rv8KJb3$9etn-!V9)##!-*F4PKFM zlQ3?9oo8$w6&pL~XrDfku3cnX3hPsrrTD+sua`r?1bIR)6SDfFm*78|3vXr8A!8$> zay)*eqKS2wJaQYcvtZDlloH9+O3of~>aJqE48a5|t6O~Pj^WZX`J3RdQ`?DLBrp)0 zg2d#>Ds#n}ro^ZdIvkYt!_x$el#oQ<59i(+^B-;`Vw<{QUIvbWR*r zfssSYIt}O!G;i=9_(NX}Q!yHHHI0eR;TvWz>d@n#k*V`5Qm0?_j+@e9blWH0ruq*! zWO?Cs&*94Z1`dtele+BI;GtUmGxzO&qN%!Xc~p-D`z~|^xL)?_X1{lv`!zS8V>2nI zu|*okkloT&y&jh8a?#yeJ55gM9AS}6RuZA_#pc$=m?Zgf zO2W-^KXe~^R;pC<^r-y+u6B5s5EVgD%(4dbF6*@2PWQ~<1qV}ZB?lsT- z#skzr8hA7_B}lG6hjDk`Hp;Lz*^?ijTT!auR7+esUL+ftWr(#FUAm}^a ztgZg|^YJ==QYUhF2o&ZF6u_~711I~2ZmW-mo)2RwoB8-+BnUjT5=_-g{jzNZPuJB| zkUy*cDs96aC@l0NKPouB#2e38#ZW`40IPA4B76PkP9*NJG}!292}&tYYUv|=UzQJ% z6<-{XSmBn+iiR2h3_5)1(AOKU7iamd+i@6nfx{d!)orQ*NWosR+W#?d3Op+H{<<7I_XO7v3#68C;%w zLxzTkXi_Y>c|0&sscYMbxeN3(QNv$HemAl4w~Cx>>9rl00mR0>2O2x3WAMxE+Y5af zeE(zJ0^W*i(3i|?O!UfaFoS^{2iM?)-gffm8P0tqp4y=lSL{?ohkSr?W@Cw0uKsMb z%=&Jbn1^j*n98*=|>jX2CAp;&sfq3tSe4VyDcHzTF2W-Ctv7{p}z^g$-a zY}T#o*Qd|(-}=v9B{Z%jAPs!Bgw&> zw@5s%@@_EtNKVWK&oMXu!ZaL?T8R6Q>u_klf(;Xfsrx@K{0X^*6~*gz@UevBy5FAby6gfzl}wot&r`Lt&1RrzL)a8j5fu#LLo+m9c1 z>PN-L@#-K}%uK$Y#+x7uu$=QSu6>zZ=hi^&CJsB(<3`R+E*YL%@V$$En^7OPtsZ=z z-N4cMK3TLEVe0~Xf%2UQrnGWPf+4Aa>A*#s&^nf zb%3Y+y~gaWRtlTDY}qUBT3q<*+#oKrRqNLDBViC1WoFtkO6*%WllCI=fyQAhZgzHF zlDNE;h$qLA(EQ7IZ9q(r>?J-q5p_~QbY6!y_{lWN!>Pic@pW~zp8M~ul_PJ_Sm;U`bjGhkO-OHa%9=i4sdc6H-x)S6e6w2 zu=JCB-T+_tFyF`Ca3aV21K@(7@3H=AfA2s(C~tt+-&gM6SL?wPP6P!-CM5hqx8_r}E!wJMnD$&(b!50C}O+O&JEh6EX1TU5>voE*lgt zngEC+f)5<%Dkry|2{C8^(du1GNkM2#B|LTELU^@5$xc`6wmGu}EYt)U`mg~}G3_Fu}%URF5kuwk}Eo=ycyE#Y4#2#($9Z1?v>;j|mP5y`W z>Z0M@kqfZ!4&7SHBK6VuqqFKyMxH$sH&Rt>qkEHic~nOlOCmxn8QI2xF>hY?5`CUG zX=}{MlMuJ2I}3o1oqvVgy9SU2;`nyT5%JSNQz`_A({G5Z{U*3V zax6C$t)=`Q1&Pd|Ihec~$u59fjvQspn&HZCd`I34tR9h?X}fq(2fc14VSBdFNT#xbH*_w| z+^~O8(&X#%lG1!Y9Qe|10FT@h5v3xG3C%e zFXbR3Y6kWd@IYbeHfLIXyvP}oLz+vRrm&U$u^?ldrS9Fv6cRS#4+#$#2b=XKfty{; z#*sH55v7@mQ?q8}3EbTUfmVJm0HC|OUU<$R@3A^MpeFQN!F-JZhG3soUVh}zAw$_! z4tH#CY&eWo67D0Z!t4&?4fde1Cn@pWm2|2(GMsu6mqjDy>+35I7?44