From 864997daa550106b7e5f12818941405d6ed015a0 Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Mon, 12 Dec 2022 21:47:10 -0300 Subject: [PATCH 01/11] :sparkles: Simple probability occupancy grid --- package.xml | 2 + turtlebot3_mapper/mapper.py | 148 ++++++++++++++++++++++++++++++------ turtlebot3_mapper/viewer.py | 55 ++++++-------- 3 files changed, 150 insertions(+), 55 deletions(-) diff --git a/package.xml b/package.xml index eeee586..c30bd97 100644 --- a/package.xml +++ b/package.xml @@ -10,6 +10,8 @@ rclpy nav_msgs sensors_msgs + rcl_interfaces + tf2_ros python3-numpy ament_copyright diff --git a/turtlebot3_mapper/mapper.py b/turtlebot3_mapper/mapper.py index 9c348f2..8094f41 100644 --- a/turtlebot3_mapper/mapper.py +++ b/turtlebot3_mapper/mapper.py @@ -1,12 +1,18 @@ -import rclpy + import threading +from enum import Enum +from typing import List + +import rclpy import numpy as np from rclpy.node import Node +from rclpy.parameter import Parameter from rclpy.executors import ExternalShutdownException from sensor_msgs.msg import LaserScan from nav_msgs.msg import Odometry, OccupancyGrid, MapMetaData +from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult from tf2_ros.buffer import Buffer from tf2_ros import LookupException, TransformException @@ -14,7 +20,26 @@ from turtlebot3_mapper.utils import euler_from_quaternion + +class State(Enum): + FREE = 1 + OCCUPIED = 2 + UNKOWN = 3 + + class TurtlebotMapper(Node): + + def parameter_callback(self, parameters: List[Parameter]) -> SetParametersResult: + for param in parameters: + if param.name == "min_prob": + self.min_prob = param.value + self.get_logger().info("Updated parameter min_prob=%.2f" % self.min_prob) + elif param.name == "max_prob": + self.max_prob = param.value + self.get_logger().info("Updated parameter max_prob=%.2f" % self.max_prob) + else: + return SetParametersResult(successful=False) + return SetParametersResult(successful=True) def __init__(self, node_name: str = 'turtlebot_mapper', @@ -23,13 +48,64 @@ def __init__(self, resolution: float = 0.03): super(TurtlebotMapper, self).__init__(node_name=node_name) - self.width = width - self.height = height - self.resolution = resolution + self.declare_parameters( + namespace="", + parameters=[ + ( + "width", + 8.0, + ParameterDescriptor(description="Map's width"), + ), + ( + "height", + 8.0, + ParameterDescriptor(description="Map's height"), + ), + ( + "resolution", + 0.03, + ParameterDescriptor(description="Map's resolution"), + ), + ( + "min_prob", + 0.01, + ParameterDescriptor(description="Map's min probability value"), + ), + ( + "max_prob", + 0.99, + ParameterDescriptor(description="Map's max probability value"), + ), + ( + "prob_occupied", + 0.6, + ParameterDescriptor(description="Occupied probability increment"), + ), + ( + "prob_free", + 0.4, + ParameterDescriptor(description="Free probability increment"), + ), + ( + "prob_priori", + 0.5, + ParameterDescriptor(description="Priori probability increment"), + ), + ], + ) + self.width = float(self.get_parameter("width").value) + self.height = float(self.get_parameter("height").value) + self.resolution = float(self.get_parameter("resolution").value) + self.min_prob = float(self.get_parameter("min_prob").value) + self.max_prob = float(self.get_parameter("max_prob").value) + self.prob_occupied = float(self.get_parameter("prob_occupied").value) + self.prob_free = float(self.get_parameter("prob_free").value) + self.prob_priori = float(self.get_parameter("prob_priori").value) + self.add_on_set_parameters_callback(self.parameter_callback) N = int(1/resolution) shape = (width*N, height*N) - self.grid = -1*np.ones(shape, dtype=np.int8) + self.grid = self.prob_priori*np.ones(shape, dtype=float) self._scan_subscriber = self.create_subscription( msg_type=LaserScan, @@ -43,7 +119,7 @@ def __init__(self, qos_profile=10, ) self._update_timer = self.create_timer( - timer_period_sec=0.1, + timer_period_sec=0.5, callback=self._update_callback, ) self._scan_init = False @@ -70,7 +146,6 @@ def _update_callback(self): self._map_publisher.publish(self.occupancy_grid) self._update.release() - def update(self, message_laser: LaserScan): try: tf = self._tf_buffer.lookup_transform('odom', @@ -103,29 +178,56 @@ def update(self, message_laser: LaserScan): x2=xy[i,0], y2=xy[i,1], ) - for j in range(points.shape[0] - 1): x = points[j,0] y = points[j,1] - if self.grid[y, x] == 100: - continue - self.grid[y, x] = 0 - + self.update_cell(x=x, y=y, state=State.FREE) x = xy[i,0] y = xy[i,1] if distances[i,0] < message_laser.range_max: - self.grid[y, x] = 100 - self.grid[y+1, x] = 100 - self.grid[y-1, x] = 100 - self.grid[y, x-1] = 100 - self.grid[y, x+1] = 100 + self.update_cell(x=x, y=y, state=State.OCCUPIED) + self.update_cell(x=x-1, y=y, state=State.OCCUPIED) + self.update_cell(x=x+1, y=y, state=State.OCCUPIED) + self.update_cell(x=x, y=y+1, state=State.OCCUPIED) + self.update_cell(x=x, y=y-1, state=State.OCCUPIED) + else: - if self.grid[y, x] != 100: - self.grid[y, x] = 0 + self.update_cell(x=x, y=y, state=State.FREE) + + def update_cell(self, x: int, y: int, state: State): + if state == State.FREE: + log_prob = self.log_odd(probability=self.prob_free) + elif state == State.OCCUPIED: + log_prob = self.log_odd(probability=self.prob_occupied) + else: + log_prob = self.log_odd(probability=self.prob_priori) + current_prob = self.grid[x,y] + current_prob_log_odd = self.log_odd(probability=current_prob) + current_prob_log_odd += log_prob + new_prob = self.probability(log_odd=current_prob_log_odd) + if new_prob < self.min_prob: + new_prob = self.min_prob + elif new_prob > self.max_prob: + new_prob = self.max_prob + self.grid[x,y] = new_prob + + @staticmethod + def log_odd(probability: float) -> float: + return np.log(probability/(1.0 - probability)) + + @staticmethod + def probability(log_odd: float) -> float: + result = 1.0/(1+np.exp(-log_odd)) + if np.isnan(result): + result = 0.0 + return result @property def occupancy_grid(self): - return self.numpy_to_occupancy_grid(arr=self.grid) + grid = np.zeros_like(self.grid) + grid[:,:] = self.grid[:,:]*100 + grid = grid.astype("int8") + return self.numpy_to_occupancy_grid(arr=grid) @staticmethod def scan_to_distances(message: LaserScan) -> np.ndarray: @@ -140,9 +242,7 @@ def scan_to_distances(message: LaserScan) -> np.ndarray: distance = message.range_min else: distance = message.ranges[i] - # distances in [m] array[i,0] = distance - # angles in [radians] array[i,1] = angle return array @@ -157,7 +257,7 @@ def distances_to_xy(distances: np.ndarray, x: float, y: float, theta: float) -> @staticmethod - def numpy_to_occupancy_grid(arr, info=None): + def numpy_to_occupancy_grid(arr: np.ndarray, info=None): """ Source: http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html """ @@ -167,7 +267,6 @@ def numpy_to_occupancy_grid(arr, info=None): raise TypeError('Array must be of int8s') grid = OccupancyGrid() if isinstance(arr, np.ma.MaskedArray): - # We assume that the masked value are already -1, for speed arr = arr.data grid.data = arr.ravel().tolist() grid.info = info or MapMetaData() @@ -223,7 +322,6 @@ def bresenham(x1: int, y1: int, x2: int, y2: int) -> np.ndarray: return np.array(points) - def main(*args, **kwargs): rclpy.init(*args, **kwargs) node = TurtlebotMapper() diff --git a/turtlebot3_mapper/viewer.py b/turtlebot3_mapper/viewer.py index e82e240..86cb261 100644 --- a/turtlebot3_mapper/viewer.py +++ b/turtlebot3_mapper/viewer.py @@ -25,51 +25,46 @@ def __init__(self, self.get_logger().info(f"Init {node_name}") def _map_callback(self, message: OccupancyGrid): - self._init = True + # get occupancy grid as a numpy array int8 array = self.occupancygrid_to_numpy(message) - array[array == -1] = 57 - array[array == 0] = 127 - array[array == 100] = 0 - input = array.astype('uint8') - # Applying 7x7 Gaussian Blur - blurred = cv2.GaussianBlur(input, (7, 7), 0) - # Applying threshold - threshold = cv2.threshold(blurred, 0, 255, cv2.THRESH_BINARY_INV | cv2.THRESH_OTSU)[1] - # Apply the Component analysis function - analysis = cv2.connectedComponentsWithStats(threshold, 4, cv2.CV_32S) + # convert int8 array to float32 + input = array.astype("float32") + # remap to 0-255 interval + input = 255*(input - np.min(input))/(np.max(input) - np.min(input)) + # if it is unkown or free, mark as 0 + input[input <= 150] = 0 + # if it is occupied, mark as 255 + input[input > 150] = 255 + # get array as uint8 + input = input.astype('uint8') + # kernel to apply morphological transformation + kernel = np.ones((5,5),np.uint8) + # apply closing transformation + closing = cv2.morphologyEx(input, cv2.MORPH_CLOSE, kernel) + # get component connected information + analysis = cv2.connectedComponentsWithStats(closing, 8, cv2.CV_32S) + # unpack information (totalLabels, label_ids, values, centroid) = analysis - - # Initialize a new image to store all the output components - input = array.astype('uint8') - output = cv2.cvtColor(input, cv2.COLOR_GRAY2BGR) - - + # get RGB image to show + output = cv2.cvtColor(closing, cv2.COLOR_GRAY2BGR) # Loop through each component - count = 0 for i in range(1, totalLabels): - # Area of the component x = values[i, cv2.CC_STAT_LEFT] y = values[i, cv2.CC_STAT_TOP] w = values[i, cv2.CC_STAT_WIDTH] h = values[i, cv2.CC_STAT_HEIGHT] area = values[i, cv2.CC_STAT_AREA] - (cX, cY) = centroid[i] - if (area > 100) and (area < 1000): - count += 1 + (cX, cY) = x+(w//2), y+(h//2) + if (area > 30) and (area < 300): cv2.rectangle(output, (x, y), (x + w, y + h), (0, 255, 0), 1) cv2.circle(output, (int(cX), int(cY)), 1, (0, 0, 255), -1) - # componentMask = (label_ids == i).astype("uint8") * 255 - # output = cv2.bitwise_or(output, componentMask) - - # resized = cv2.resize(output, (500, 500)) - image = cv2.flip(output, 0) - rotated_image = cv2.rotate(src = image, rotateCode = cv2.ROTATE_90_COUNTERCLOCKWISE) - + # rotate just to plot equal gazebo + rotated_image = cv2.rotate(src = output, rotateCode = cv2.ROTATE_180) + # show image cv2.namedWindow("output", cv2.WINDOW_NORMAL) cv2.imshow("output", rotated_image) if cv2.waitKey(1) == ord('q'): sys.exit(1) - @staticmethod def occupancygrid_to_numpy(msg, info=None): From e7a05d8a292e09765439f24def7640cb05d1b0c7 Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Wed, 14 Dec 2022 21:30:29 -0300 Subject: [PATCH 02/11] :sparkles: Change repo organization --- package.xml | 5 +- setup.py | 41 +- turtlebot3_mapper/mapper.py | 338 ------------ .../turtlebot3_explorer/__init__.py | 0 turtlebot3_mapper/turtlebot3_explorer/main.py | 21 + .../turtlebot3_explorer.py} | 35 +- .../turtlebot3_object_detector/__init__.py | 0 .../turtlebot3_object_detector/main.py | 21 + .../turtlebot3_object_detector.py | 138 +++++ .../turtlebot3_occupancy_grid/__init__.py | 0 .../turtlebot3_occupancy_grid/main.py | 21 + .../turtlebot3_occupancy_grid.py | 493 ++++++++++++++++++ turtlebot3_mapper/utils.py | 51 +- turtlebot3_mapper/viewer.py | 92 ---- 14 files changed, 771 insertions(+), 485 deletions(-) delete mode 100644 turtlebot3_mapper/mapper.py create mode 100644 turtlebot3_mapper/turtlebot3_explorer/__init__.py create mode 100644 turtlebot3_mapper/turtlebot3_explorer/main.py rename turtlebot3_mapper/{explorer.py => turtlebot3_explorer/turtlebot3_explorer.py} (85%) create mode 100644 turtlebot3_mapper/turtlebot3_object_detector/__init__.py create mode 100644 turtlebot3_mapper/turtlebot3_object_detector/main.py create mode 100644 turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py create mode 100644 turtlebot3_mapper/turtlebot3_occupancy_grid/__init__.py create mode 100644 turtlebot3_mapper/turtlebot3_occupancy_grid/main.py create mode 100644 turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py delete mode 100644 turtlebot3_mapper/viewer.py diff --git a/package.xml b/package.xml index c30bd97..6180884 100644 --- a/package.xml +++ b/package.xml @@ -9,7 +9,8 @@ rclpy nav_msgs - sensors_msgs + vision_msgs + sensor_msgs rcl_interfaces tf2_ros python3-numpy @@ -19,6 +20,8 @@ ament_pep257 python3-pytest + ament_cmake + ament_python diff --git a/setup.py b/setup.py index e2e828f..ef4b3df 100644 --- a/setup.py +++ b/setup.py @@ -1,3 +1,5 @@ +from os import path +from glob import glob from setuptools import setup package_name = 'turtlebot3_mapper' @@ -5,23 +7,46 @@ setup( name=package_name, version='0.1.0', - packages=[package_name], + packages=[ + package_name, + path.join(package_name, "turtlebot3_explorer"), + path.join(package_name, "turtlebot3_occupancy_grid"), + path.join(package_name, "turtlebot3_object_detector"), + path.join(package_name, "turtlebot3_mission_controller"), + ], 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']), + (path.join('share', package_name, 'launch'), glob('launch/*launch.[pxy][yma]*')), + (path.join('share', package_name, 'rviz'), glob('rviz/*.rviz')), ], install_requires=['setuptools'], zip_safe=True, - maintainer='autonomous-robots', - description='Simple implementation of an occupancy map using laser scan', + author=["Luiz Carlos Cosmi Filho"], + author_email=["luiz.cosmi@edu.ufes.br"], + maintainer="Luiz Carlos Cosmi Filho", + maintainer_email="luiz.cosmi@edu.ufes.br", + keywords=['ROS', 'ROS2', 'mapping', 'perception', 'kinematics'], + classifiers=[ + 'Intended Audience :: Developers', + 'License :: OSI Approved :: MIT Software License', + 'Programming Language :: Python', + 'Topic :: Software Development', + ], + description='Set of packages developed to explore, map and detect obstacles in an \ + enviromment', license='MIT', tests_require=['pytest'], entry_points={ 'console_scripts': [ - 'mapper=turtlebot3_mapper.mapper:main', - 'viewer=turtlebot3_mapper.viewer:main', - 'explorer=turtlebot3_mapper.explorer:main', + 'turtlebot3_explorer = \ + turtlebot3_mapper.turtlebot3_explorer.main:main', + 'turtlebot3_occupancy_grid = \ + turtlebot3_mapper.turtlebot3_occupancy_grid.main:main', + 'turtlebot3_object_detector = \ + turtlebot3_mapper.turtlebot3_object_detector.main:main', + 'turtlebot3_mission_controller = \ + turtlebot3_mapper.turtlebot3_mission_controller.main:main', ], }, ) diff --git a/turtlebot3_mapper/mapper.py b/turtlebot3_mapper/mapper.py deleted file mode 100644 index 8094f41..0000000 --- a/turtlebot3_mapper/mapper.py +++ /dev/null @@ -1,338 +0,0 @@ - -import threading -from enum import Enum -from typing import List - -import rclpy -import numpy as np - -from rclpy.node import Node -from rclpy.parameter import Parameter -from rclpy.executors import ExternalShutdownException - -from sensor_msgs.msg import LaserScan -from nav_msgs.msg import Odometry, OccupancyGrid, MapMetaData -from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult - -from tf2_ros.buffer import Buffer -from tf2_ros import LookupException, TransformException -from tf2_ros.transform_listener import TransformListener - -from turtlebot3_mapper.utils import euler_from_quaternion - - -class State(Enum): - FREE = 1 - OCCUPIED = 2 - UNKOWN = 3 - - -class TurtlebotMapper(Node): - - def parameter_callback(self, parameters: List[Parameter]) -> SetParametersResult: - for param in parameters: - if param.name == "min_prob": - self.min_prob = param.value - self.get_logger().info("Updated parameter min_prob=%.2f" % self.min_prob) - elif param.name == "max_prob": - self.max_prob = param.value - self.get_logger().info("Updated parameter max_prob=%.2f" % self.max_prob) - else: - return SetParametersResult(successful=False) - return SetParametersResult(successful=True) - - def __init__(self, - node_name: str = 'turtlebot_mapper', - width: int = 8, - height: int = 8, - resolution: float = 0.03): - - super(TurtlebotMapper, self).__init__(node_name=node_name) - self.declare_parameters( - namespace="", - parameters=[ - ( - "width", - 8.0, - ParameterDescriptor(description="Map's width"), - ), - ( - "height", - 8.0, - ParameterDescriptor(description="Map's height"), - ), - ( - "resolution", - 0.03, - ParameterDescriptor(description="Map's resolution"), - ), - ( - "min_prob", - 0.01, - ParameterDescriptor(description="Map's min probability value"), - ), - ( - "max_prob", - 0.99, - ParameterDescriptor(description="Map's max probability value"), - ), - ( - "prob_occupied", - 0.6, - ParameterDescriptor(description="Occupied probability increment"), - ), - ( - "prob_free", - 0.4, - ParameterDescriptor(description="Free probability increment"), - ), - ( - "prob_priori", - 0.5, - ParameterDescriptor(description="Priori probability increment"), - ), - ], - ) - self.width = float(self.get_parameter("width").value) - self.height = float(self.get_parameter("height").value) - self.resolution = float(self.get_parameter("resolution").value) - self.min_prob = float(self.get_parameter("min_prob").value) - self.max_prob = float(self.get_parameter("max_prob").value) - self.prob_occupied = float(self.get_parameter("prob_occupied").value) - self.prob_free = float(self.get_parameter("prob_free").value) - self.prob_priori = float(self.get_parameter("prob_priori").value) - self.add_on_set_parameters_callback(self.parameter_callback) - - N = int(1/resolution) - shape = (width*N, height*N) - self.grid = self.prob_priori*np.ones(shape, dtype=float) - - self._scan_subscriber = self.create_subscription( - msg_type=LaserScan, - topic="/scan", - callback=self._scan_callback, - qos_profile=10, - ) - self._map_publisher = self.create_publisher( - msg_type=OccupancyGrid, - topic="/custom_map", - qos_profile=10, - ) - self._update_timer = self.create_timer( - timer_period_sec=0.5, - callback=self._update_callback, - ) - self._scan_init = False - self._tf_buffer = Buffer() - self._tf_listener = TransformListener(self._tf_buffer, self) - self._update = threading.Lock() - self.get_logger().info(f"Init {node_name}") - - def _scan_callback(self, message: LaserScan): - self._scan_init = True - if not self._update.locked(): - self._scan = message - - def _update_callback(self): - if self._scan_init: - if self._update.locked(): - return - else: - self._update.acquire() - self.get_logger().info("updating...") - self.update( - message_laser=self._scan, - ) - self._map_publisher.publish(self.occupancy_grid) - self._update.release() - - def update(self, message_laser: LaserScan): - try: - tf = self._tf_buffer.lookup_transform('odom', - message_laser.header.frame_id, - message_laser.header.stamp) - q = tf.transform.rotation - except (TransformException, LookupException): - self.get_logger().info("could not get tf") - return - _, _, theta = euler_from_quaternion(quaternion=q) - if theta < 0.0: - theta += 2*np.pi - distances = self.scan_to_distances(message=message_laser) - xy = self.distances_to_xy( - distances=distances, - x=tf.transform.translation.x, - y=tf.transform.translation.y, - theta=theta, - ) - xy[:,0] = (xy[:,0] + self.width//2)/self.resolution - xy[:,1] = (xy[:,1] + self.height//2)/self.resolution - xy = xy.astype(int) - xo = int((tf.transform.translation.x + self.width//2)/self.resolution) - yo = int((tf.transform.translation.y + self.height//2)/self.resolution) - - for i in range(xy.shape[0]): - points = self.bresenham( - x1=xo, - y1=yo, - x2=xy[i,0], - y2=xy[i,1], - ) - for j in range(points.shape[0] - 1): - x = points[j,0] - y = points[j,1] - self.update_cell(x=x, y=y, state=State.FREE) - x = xy[i,0] - y = xy[i,1] - if distances[i,0] < message_laser.range_max: - self.update_cell(x=x, y=y, state=State.OCCUPIED) - self.update_cell(x=x-1, y=y, state=State.OCCUPIED) - self.update_cell(x=x+1, y=y, state=State.OCCUPIED) - self.update_cell(x=x, y=y+1, state=State.OCCUPIED) - self.update_cell(x=x, y=y-1, state=State.OCCUPIED) - - else: - self.update_cell(x=x, y=y, state=State.FREE) - - def update_cell(self, x: int, y: int, state: State): - if state == State.FREE: - log_prob = self.log_odd(probability=self.prob_free) - elif state == State.OCCUPIED: - log_prob = self.log_odd(probability=self.prob_occupied) - else: - log_prob = self.log_odd(probability=self.prob_priori) - current_prob = self.grid[x,y] - current_prob_log_odd = self.log_odd(probability=current_prob) - current_prob_log_odd += log_prob - new_prob = self.probability(log_odd=current_prob_log_odd) - if new_prob < self.min_prob: - new_prob = self.min_prob - elif new_prob > self.max_prob: - new_prob = self.max_prob - self.grid[x,y] = new_prob - - @staticmethod - def log_odd(probability: float) -> float: - return np.log(probability/(1.0 - probability)) - - @staticmethod - def probability(log_odd: float) -> float: - result = 1.0/(1+np.exp(-log_odd)) - if np.isnan(result): - result = 0.0 - return result - - @property - def occupancy_grid(self): - grid = np.zeros_like(self.grid) - grid[:,:] = self.grid[:,:]*100 - grid = grid.astype("int8") - return self.numpy_to_occupancy_grid(arr=grid) - - @staticmethod - def scan_to_distances(message: LaserScan) -> np.ndarray: - # N samples - N = len(message.ranges) - array = np.zeros((N, 2)) - for i in range(len(message.ranges)): - angle = i * message.angle_increment - if message.ranges[i] > message.range_max: - distance = message.range_max - elif message.ranges[i] < message.range_min: - distance = message.range_min - else: - distance = message.ranges[i] - array[i,0] = distance - array[i,1] = angle - return array - - @staticmethod - def distances_to_xy(distances: np.ndarray, x: float, y: float, theta: float) -> np.ndarray: - # N samples - N = distances.shape[0] - array = np.zeros((N,2)) - array[:,0] = x + distances[:,0]*np.cos(distances[:,1] + theta) - array[:,1] = y + distances[:,0]*np.sin(distances[:,1] + theta) - return array - - - @staticmethod - def numpy_to_occupancy_grid(arr: np.ndarray, info=None): - """ - Source: http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html - """ - if not len(arr.shape) == 2: - raise TypeError('Array must be 2D') - if not arr.dtype == np.int8: - raise TypeError('Array must be of int8s') - grid = OccupancyGrid() - if isinstance(arr, np.ma.MaskedArray): - arr = arr.data - grid.data = arr.ravel().tolist() - grid.info = info or MapMetaData() - grid.info.height = arr.shape[0] - grid.info.width = arr.shape[1] - return grid - - @staticmethod - def bresenham(x1: int, y1: int, x2: int, y2: int) -> np.ndarray: - """ - Implementation of Bresenham's line drawing algorithm. - >>> points1 = bresenham((4, 4), (6, 10)) - >>> print(points1) - np.array([[4,4], [4,5], [5,6], [5,7], [5,8], [6,9], [6,10]]) - - Source: https://github.com/AtsushiSakai/PythonRobotics - """ - # setup initial conditions - dx = x2 - x1 - dy = y2 - y1 - # determine how steep the line is - is_steep = abs(dy) > abs(dx) - # rotate line - if is_steep: - x1, y1 = y1, x1 - x2, y2 = y2, x2 - # swap start and end points if necessary and store swap state - swapped = False - if x1 > x2: - x1, x2 = x2, x1 - y1, y2 = y2, y1 - swapped = True - # recalculate differentials - dx = x2 - x1 - # recalculate differentials - dy = y2 - y1 - # calculate error - error = int(dx / 2.0) - y_step = 1 if y1 < y2 else -1 - # iterate over bounding box generating points between start and end - y = y1 - points = [] - for x in range(x1, x2 + 1): - coord = [y, x] if is_steep else (x, y) - points.append(coord) - error -= abs(dy) - if error < 0: - y += y_step - error += dx - # reverse the list if the coordinates were swapped - if swapped: - points.reverse() - return np.array(points) - - -def main(*args, **kwargs): - rclpy.init(*args, **kwargs) - node = TurtlebotMapper() - try: - rclpy.spin(node=node) - except (KeyboardInterrupt, ExternalShutdownException): - pass - finally: - node.destroy_node() - rclpy.try_shutdown() - - -if __name__ == "__main__": - main() diff --git a/turtlebot3_mapper/turtlebot3_explorer/__init__.py b/turtlebot3_mapper/turtlebot3_explorer/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/turtlebot3_mapper/turtlebot3_explorer/main.py b/turtlebot3_mapper/turtlebot3_explorer/main.py new file mode 100644 index 0000000..3f8dc6c --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_explorer/main.py @@ -0,0 +1,21 @@ +import rclpy +from rclpy.executors import ExternalShutdownException + +from turtlebot3_mapper.turtlebot3_explorer.turtlebot3_explorer \ + import Turtlebot3Explorer + + +def main(*args, **kwargs): + rclpy.init(*args, **kwargs) + node = Turtlebot3Explorer() + try: + rclpy.spin(node=node) + except (KeyboardInterrupt, ExternalShutdownException): + pass + finally: + node.destroy_node() + rclpy.try_shutdown() + + +if __name__ == "__main__": + main() diff --git a/turtlebot3_mapper/explorer.py b/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py similarity index 85% rename from turtlebot3_mapper/explorer.py rename to turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py index 483d94e..00c2b23 100644 --- a/turtlebot3_mapper/explorer.py +++ b/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py @@ -18,12 +18,11 @@ class State(Enum): ROTATE = 2 UNKOWN = 3 -class TurtlebotExplorer(Node): +class Turtlebot3Explorer(Node): def __init__(self, node_name: str = 'turtlebot_explorer'): - super(TurtlebotExplorer, - self).__init__(node_name=node_name) + super(Turtlebot3Explorer, self).__init__(node_name=node_name) self._subscriber_scan = self.create_subscription( msg_type=LaserScan, topic="/scan", @@ -82,15 +81,15 @@ def detect_obstacle(self): _, _, theta = euler_from_quaternion(self._odom.pose.pose.orientation) - min_ang = (-140) * (np.pi/180) - max_ang = (140) * (np.pi/180) + min_ang = (-140) * (np.pi / 180) + max_ang = (140) * (np.pi / 180) increm = self._scan.angle_increment size = len(self._scan.ranges) - start = int(size/2 + min_ang/increm) - end = int(size/2 + max_ang/increm) - + start = int(size / 2 + min_ang / increm) + end = int(size / 2 + max_ang / increm) + # scan_range = [self.scan.ranges[i] for i in range(90, 270)] scan_range = [self._scan.ranges[i] for i in range(end, len(self._scan.ranges))] for i in range(0, start): @@ -103,7 +102,7 @@ def detect_obstacle(self): if self.state != State.ROTATE: twist = Twist() twist.linear.x = 0.0 - twist.angular.z = 0.25*self.multiplier + twist.angular.z = 0.25 * self.multiplier if self.count >= 3: self.count = 0 self.multiplier *= -1.0 @@ -122,7 +121,7 @@ def detect_obstacle(self): if self.state != State.ROTATE: twist = Twist() twist.linear.x = 0.0 - twist.angular.z = 0.25*self.multiplier + twist.angular.z = 0.25 * self.multiplier if self.count >= 3: self.count = 0 self.multiplier *= -1.0 @@ -145,19 +144,3 @@ def detect_obstacle(self): twist.angular.z = 0.0 self.state = State.FORWARD self._publisher.publish(twist) - - -def main(*args, **kwargs): - rclpy.init(*args, **kwargs) - node = TurtlebotExplorer() - try: - rclpy.spin(node=node) - except (KeyboardInterrupt, ExternalShutdownException): - pass - finally: - node.destroy_node() - rclpy.try_shutdown() - - -if __name__ == "__main__": - main() diff --git a/turtlebot3_mapper/turtlebot3_object_detector/__init__.py b/turtlebot3_mapper/turtlebot3_object_detector/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/turtlebot3_mapper/turtlebot3_object_detector/main.py b/turtlebot3_mapper/turtlebot3_object_detector/main.py new file mode 100644 index 0000000..457079d --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_object_detector/main.py @@ -0,0 +1,21 @@ +import rclpy +from rclpy.executors import ExternalShutdownException + +from turtlebot3_mapper.turtlebot3_object_detector.turtlebot3_object_detector \ + import Turtlebot3ObjectDetector + + +def main(*args, **kwargs): + rclpy.init(*args, **kwargs) + node = Turtlebot3ObjectDetector(node_name="turtlebot3_object_detector") + try: + rclpy.spin(node=node) + except (KeyboardInterrupt, ExternalShutdownException): + pass + finally: + node.destroy_node() + rclpy.try_shutdown() + + +if __name__ == "__main__": + main() diff --git a/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py b/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py new file mode 100644 index 0000000..42d43d8 --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py @@ -0,0 +1,138 @@ +from typing import List + +import cv2 +import numpy as np +from cv_bridge import CvBridge + +from rclpy.node import Node +from rclpy.parameter import Parameter + +from sensor_msgs.msg import Image +from nav_msgs.msg import OccupancyGrid +from vision_msgs.msg import BoundingBox2DArray, BoundingBox2D +from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult + + +class Turtlebot3ObjectDetector(Node): + + def parameter_callback(self, parameters: List[Parameter]) -> SetParametersResult: + for param in parameters: + if param.name == "threshold": + self.threshold = param.value + self.get_logger().info("Updated parameter threshold=%.2f" % self.threshold) + elif param.name == "connectivity": + self.connectivity = param.value + self.get_logger().info("Updated parameter connectivity=%.2f" % self.connectivity) + elif param.name == "min_area": + self.min_area = param.value + self.get_logger().info("Updated parameter connectivity=%.2f" % self.min_area) + elif param.name == "max_area": + self.max_area = param.value + self.get_logger().info("Updated parameter connectivity=%.2f" % self.max_area) + else: + return SetParametersResult(successful=False) + return SetParametersResult(successful=True) + + def __init__(self, node_name: str = 'turtlebot3_object_detector'): + + super(Turtlebot3ObjectDetector, self).__init__(node_name=node_name) + self.declare_parameters( + namespace="", + parameters=[ + ( + "threshold", + 150, + ParameterDescriptor(description="Threshold to binary image"), + ), + ( + "connectivity", + 4, + ParameterDescriptor(description="4-way or 8-way connectivity"), + ), + ( + "min_area", + 30, + ParameterDescriptor(description="Min area of each connected component"), + ), + ( + "max_area", + 100, + ParameterDescriptor(description="Max area of each connected component"), + ), + ], + ) + self.threshold = float(self.get_parameter("threshold").value) + self.connectivity = float(self.get_parameter("connectivity").value) + self.min_area = float(self.get_parameter("min_area").value) + self.max_area = float(self.get_parameter("max_area").value) + self.add_on_set_parameters_callback(self.parameter_callback) + + self._map_subscriber = self.create_subscription( + msg_type=OccupancyGrid, + topic="/custom_map", + callback=self._map_callback, + qos_profile=10, + ) + self._detections_publisher = self.create_publisher( + msg_type=BoundingBox2DArray, + topic="/detections", + qos_profile=10, + ) + self._result_publisher = self.create_publisher( + msg_type=Image, + topic="/rendered", + qos_profile=10, + ) + self._bridge = CvBridge() + self.get_logger().info(f"Init {node_name}") + + def _map_callback(self, message: OccupancyGrid): + # get occupancy grid as a numpy array int8 + array = self.occupancygrid_to_numpy(message) + # convert int8 array to float32 + input = array.astype("float32") + # remap to 0-255 interval + input = 255 * (input - np.min(input)) / (np.max(input) - np.min(input)) + # if it is unkown or free, mark as 0 + input[input <= self.threshold] = 0 + # if it is occupied, mark as 255 + input[input > self.threshold] = 255 + # get array as uint8 + input = input.astype('uint8') + # get component connected information + analysis = cv2.connectedComponentsWithStats(input, self.connectivity, cv2.CV_32S) + # unpack information + (totalLabels, label_ids, values, centroid) = analysis + # get RGB image to show + output = cv2.cvtColor(input, cv2.COLOR_GRAY2BGR) + # Loop through each component + detections = BoundingBox2DArray() + detections.header = message.header + for i in range(1, totalLabels): + x = values[i, cv2.CC_STAT_LEFT] + y = values[i, cv2.CC_STAT_TOP] + w = values[i, cv2.CC_STAT_WIDTH] + h = values[i, cv2.CC_STAT_HEIGHT] + area = values[i, cv2.CC_STAT_AREA] + (cX, cY) = x + (w // 2), y + (h // 2) + if (area > self.min_area) and (area < self.max_area): + bbox = BoundingBox2D() + bbox.center.position.x = float(cX) + bbox.center.position.y = float(cY) + bbox.size_x = float(w) + bbox.size_y = float(h) + detections.boxes.append(bbox) + cv2.rectangle(output, (x, y), (x + w, y + h), (0, 255, 0), 1) + cv2.circle(output, (int(cX), int(cY)), 1, (0, 0, 255), -1) + self._detections_publisher.publish(detections) + image_ros = self._bridge.cv2_to_imgmsg(cvim=np.flip(output, axis=0)) + image_ros.header = message.header + self._result_publisher.publish(image_ros) + + @staticmethod + def occupancygrid_to_numpy(msg, info=None): + """ + Source: http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html + """ + data = np.asarray(msg.data, dtype=np.int8).reshape(msg.info.height, msg.info.width) + return data diff --git a/turtlebot3_mapper/turtlebot3_occupancy_grid/__init__.py b/turtlebot3_mapper/turtlebot3_occupancy_grid/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/turtlebot3_mapper/turtlebot3_occupancy_grid/main.py b/turtlebot3_mapper/turtlebot3_occupancy_grid/main.py new file mode 100644 index 0000000..bda35e4 --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_occupancy_grid/main.py @@ -0,0 +1,21 @@ +import rclpy +from rclpy.executors import ExternalShutdownException, MultiThreadedExecutor + +from turtlebot3_mapper.turtlebot3_occupancy_grid.turtlebot3_occupancy_grid \ + import Turtlebot3OccupancyGrid + + +def main(*args, **kwargs): + rclpy.init(*args, **kwargs) + node = Turtlebot3OccupancyGrid(node_name="turtlebot3_occupancy_grid") + executor = MultiThreadedExecutor() + try: + rclpy.spin(node=node, executor=executor) + except (KeyboardInterrupt, ExternalShutdownException): + pass + finally: + rclpy.try_shutdown() + + +if __name__ == "__main__": + main() diff --git a/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py b/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py new file mode 100644 index 0000000..4ae5793 --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py @@ -0,0 +1,493 @@ +import threading +from enum import Enum +from typing import List, Tuple + +import numpy as np + +from rclpy.node import Node +from rclpy.time import Time +from rclpy.duration import Duration +from rclpy.parameter import Parameter + +from sensor_msgs.msg import LaserScan +from nav_msgs.msg import OccupancyGrid +from geometry_msgs.msg import TransformStamped +from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult + +from tf2_ros.buffer import Buffer +from tf2_ros import LookupException, TransformException +from tf2_ros.transform_listener import TransformListener +from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster + +from turtlebot3_mapper.utils import euler_from_quaternion + + +class State(Enum): + FREE = 1 + OCCUPIED = 2 + UNKOWN = 3 + + +class Turtlebot3OccupancyGrid(Node): + + def parameter_callback(self, parameters: List[Parameter]) -> SetParametersResult: + for param in parameters: + if param.name == "min_prob": + self.min_prob = param.value + self.get_logger().info("Updated parameter min_prob=%.2f" % self.min_prob) + elif param.name == "max_prob": + self.max_prob = param.value + self.get_logger().info("Updated parameter max_prob=%.2f" % self.max_prob) + else: + return SetParametersResult(successful=False) + return SetParametersResult(successful=True) + + def __init__(self, node_name: str = 'turtlebot_occupancy_grid'): + + super(Turtlebot3OccupancyGrid, self).__init__(node_name=node_name) + self.declare_parameters( + namespace="", + parameters=[ + ( + "width", + 8.0, + ParameterDescriptor(description="Map's width"), + ), + ( + "height", + 8.0, + ParameterDescriptor(description="Map's height"), + ), + ( + "resolution", + 0.03, + ParameterDescriptor(description="Map's resolution"), + ), + ( + "min_prob", + 0.01, + ParameterDescriptor(description="Map's min probability value"), + ), + ( + "max_prob", + 0.99, + ParameterDescriptor(description="Map's max probability value"), + ), + ( + "prob_occupied", + 0.6, + ParameterDescriptor(description="Occupied probability increment"), + ), + ( + "prob_free", + 0.4, + ParameterDescriptor(description="Free probability increment"), + ), + ( + "prob_priori", + 0.5, + ParameterDescriptor(description="Priori probability increment"), + ), + ( + "rate", + 1.0, + ParameterDescriptor(description="Update rate"), + ), + ], + ) + self.width = float(self.get_parameter("width").value) + self.height = float(self.get_parameter("height").value) + self.resolution = float(self.get_parameter("resolution").value) + self.min_prob = float(self.get_parameter("min_prob").value) + self.max_prob = float(self.get_parameter("max_prob").value) + self.prob_occupied = float(self.get_parameter("prob_occupied").value) + self.prob_free = float(self.get_parameter("prob_free").value) + self.prob_priori = float(self.get_parameter("prob_priori").value) + self.rate = float(self.get_parameter("rate").value) + self.add_on_set_parameters_callback(self.parameter_callback) + # create 2D-array to holds occupancy grid + N = int(1 / self.resolution) + shape = (int(self.width * N), int(self.height * N)) + self.grid = self.prob_priori * np.ones(shape, dtype=float) + # subscriber to receive laser messages + self._scan_subscriber = self.create_subscription( + msg_type=LaserScan, + topic="/scan", + callback=self._scan_callback, + qos_profile=10, + ) + # publisher to send probability map + self._map_publisher = self.create_publisher( + msg_type=OccupancyGrid, + topic="/custom_map", + qos_profile=10, + ) + # timer to update map + self._update_timer = self.create_timer( + timer_period_sec=(1 / self.rate), + callback=self._timer_callback, + ) + self._scan_init = False + self._tf_buffer = Buffer() + self._tf_listener = TransformListener(self._tf_buffer, self) + self._tf_publisher = StaticTransformBroadcaster(self) + tf = TransformStamped() + tf.header.stamp = self.get_clock().now().to_msg() + tf.header.frame_id = 'map' + tf.child_frame_id = 'odom' + tf.transform.translation.x = 0.0 + tf.transform.translation.y = 0.0 + tf.transform.translation.z = 0.0 + self._tf_publisher.sendTransform(tf) + self._update = threading.Lock() + self.get_logger().info(f"Init {node_name}") + + def _scan_callback(self, message: LaserScan): + """Callback executed when node receives messages from laser scan in robot. + + Parameters + ---------- + message_laser: :py:class:`LaserScan ` + message with laser scan received from robot. + """ + self._scan_init = True + self._scan = message + self.update_map(message_laser=self._scan) + + def _timer_callback(self): + """Timer callback used to publish occupancy grid. Only starts publishing after received + message from laser scan in robot. + """ + if self._scan_init: + self._update.acquire() + self._map_publisher.publish(self.occupancy_grid) + self._update.release() + self.get_logger().info("Sending occupancy grid...") + + def update_map(self, message_laser: LaserScan): + """Utility look for transformation between laser scan frame and odometry frame, compute + laser samples in odometry referential and mark as free or occupied. Note that when it finds + an occupied sample, it also mark 4-components around it as occupied. + + Parameters + ---------- + message_laser: :py:class:`LaserScan ` + message with laser scan received from robot. + """ + if not self._update.locked(): + self._update.acquire() + try: + tf = self._tf_buffer.lookup_transform( + target_frame='odom', + source_frame=message_laser.header.frame_id, + time=message_laser.header.stamp, + timeout=Duration(seconds=(1 / (self.rate))), + ) + quaternion = tf.transform.rotation + except (TransformException, LookupException) as ex: + self.get_logger().warn( + f'Could not transform "odom" to {message_laser.header.frame_id}: {ex}') + self._update.release() + return + _, _, theta = euler_from_quaternion(quaternion=quaternion) + if theta < 0.0: + theta += 2 * np.pi + polar = self.laser_scan_to_polar(message=message_laser) + xy = self.polar_to_cartesian( + coordinates=polar, + x=tf.transform.translation.x, + y=tf.transform.translation.y, + theta=theta, + ) + xy[:, 0] = (xy[:, 0] + self.width // 2) / self.resolution + xy[:, 1] = (xy[:, 1] + self.height // 2) / self.resolution + xy = xy.astype(int) + xo = int((tf.transform.translation.x + self.width // 2) / self.resolution) + yo = int((tf.transform.translation.y + self.height // 2) / self.resolution) + for i in range(xy.shape[0]): + points = self.bresenham( + x1=xo, + y1=yo, + x2=xy[i, 0], + y2=xy[i, 1], + ) + for j in range(points.shape[0] - 1): + x = points[j, 0] + y = points[j, 1] + self.update_cell(x=x, y=y, state=State.FREE) + x = xy[i, 0] + y = xy[i, 1] + if polar[i, 0] < message_laser.range_max: + self.update_cell(x=x, y=y, state=State.OCCUPIED) + self.update_cell(x=x - 1, y=y, state=State.OCCUPIED) + self.update_cell(x=x + 1, y=y, state=State.OCCUPIED) + self.update_cell(x=x, y=y + 1, state=State.OCCUPIED) + self.update_cell(x=x, y=y - 1, state=State.OCCUPIED) + else: + self.update_cell(x=x, y=y, state=State.FREE) + self.get_logger().info("Updated occupancy grid...") + self._update.release() + + def update_cell(self, x: int, y: int, state: State): + """Given a state observed given laser measurements, update occupancy grid using log-odds + and retrive probability to be store at this position. + + Parameters + ---------- + x: int + X-axis position in occupancy grid. + y: int + Y-axis position in occupancy grid. + state: :py:class:`State ` + Flag used to indicate the status observed at this position in the occupancy grid. + """ + if state == State.FREE: + log_prob = self.log_odd(probability=self.prob_free) + elif state == State.OCCUPIED: + log_prob = self.log_odd(probability=self.prob_occupied) + else: + log_prob = self.log_odd(probability=self.prob_priori) + current_prob = self.grid[x, y] + current_prob_log_odd = self.log_odd(probability=current_prob) + current_prob_log_odd += log_prob + new_prob = self.probability(log_odd=current_prob_log_odd) + if new_prob < self.min_prob: + new_prob = self.min_prob + elif new_prob > self.max_prob: + new_prob = self.max_prob + self.grid[x, y] = new_prob + + @property + def occupancy_grid(self): + # copy data from grid + grid = np.zeros_like(self.grid) + # multiple by 100, to give probabilities between 0 and 100 + grid[:, :] = self.grid[:, :] * 100 + # grid = np.rot90(grid) + grid = np.transpose(grid) + # convert to int8 and returns as occupancy grid + grid = grid.astype("int8") + return self.numpy_to_occupancy_grid( + array=grid, + resolution=self.resolution, + world=(-self.width // 2, -self.height // 2), + frame_id="map", + timestamp=self.get_clock().now().to_msg(), + ) + + @staticmethod + def log_odd(probability: float) -> float: + """A log odds in statistics is the logarithm of the odds ratio. The advantage of the + log-odds over the probability representation is that we can avoid numerical instabilities + for probabilities near zero or one. + + Parameters + ---------- + probability: float + Given probability to estimate log-odds. + + Returns + ------- + float + Return log-odds of a given probability. + """ + return np.log(probability / (1.0 - probability)) + + @staticmethod + def probability(log_odd: float) -> float: + """Retrieve probability from a log-odds representation. It will always be a value between 0 + and 1. + + Parameters + ---------- + log_odd: float + Given log-odd to estimate probability. + + Returns + ------- + float + Return probability between 0 and 1. + """ + result = 1 - (1.0 / (1 + np.exp(log_odd))) + if np.isnan(result): + result = 0.0 + return result + + @staticmethod + def laser_scan_to_polar(message: LaserScan) -> np.ndarray: + """Convert a LaserScan message to a numpy array with points polar coordinates obtained. If + the message indicates infinity, set the distance as the sensor's maximum value. In the + same way, if the message indicates a distance value smaller than the minimum distance, set + the sensor's minimum distance. + + Parameters + ---------- + message: :py:class:`LaserScan ` + Message received from laser sensor. + + Returns + ------- + :py:class:`ndarray ` of shape `(N,2)` + Points sampled in polar coordinates. The first column corresponds to the distance (in + meters) and the second column corresponds to the angle (in radians). + """ + N = len(message.ranges) + array = np.zeros((N, 2)) + for i in range(len(message.ranges)): + angle = i * message.angle_increment + if message.ranges[i] > message.range_max: + distance = message.range_max + elif message.ranges[i] < message.range_min: + distance = message.range_min + else: + distance = message.ranges[i] + array[i, 0] = distance + array[i, 1] = angle + return array + + @staticmethod + def polar_to_cartesian(coordinates: np.ndarray, x: float, y: float, + theta: float) -> np.ndarray: + """Convert points in polar coordinates in the laser reference to cartesian coordinates in + the odometry reference. + + Parameters + ---------- + coordinates: :py:class:`ndarray ` of shape `(N,2)` + Points sampled in polar coordinates. The first column corresponds to the distance (in + meters) and the second column corresponds to the angle (in radians). + x: float + Laser position on the X-axis in the odometry referential. + y: float + Laser position on the Y-axis in the odometry referential. + theta: float + Laser rotation in the odometry referential. + + Returns + ------- + :py:class:`ndarray ` of shape `(N,2)` + Points sample in cartesian coordinates at odometry referential. The first column + corresponds to the X's and the second column corresponds to the Y's. + """ + N = coordinates.shape[0] + array = np.zeros((N, 2)) + array[:, 0] = x + coordinates[:, 0] * np.cos(coordinates[:, 1] + theta) + array[:, 1] = y + coordinates[:, 0] * np.sin(coordinates[:, 1] + theta) + return array + + @staticmethod + def numpy_to_occupancy_grid(array: np.ndarray, resolution: float, world: Tuple[float, float], + frame_id: str, timestamp: Time): + """Utility to converts an :py:class:`ndarray ` to an + :py:class:`OccupancyGrid `. + + Parameters + ---------- + array: :py:class:`ndarray ` of shape `(N,M)` + Two dimentional numpy array to convert in a occupancy grid message. + resolution: float + Occupancy grid resolution. + world: Tuple[float,float] + `(x,y)` world position. + frame_id: str + Referential frame name. + timestamp: Time + Timestamp info. + + Returns + ------- + :py:class:`OccupancyGrid ` + Occupancy grid message. + + Reference + --------- + Code inspired by `ros_numpy` package, a collection of conversion function for extracting + numpy arrays from messages. Source code at: + * http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html + """ + if not len(array.shape) == 2: + raise TypeError('Array must be 2D') + if not array.dtype == np.int8: + raise TypeError('Array must be of int8s') + grid = OccupancyGrid() + if isinstance(array, np.ma.MaskedArray): + array = array.data + grid.header.stamp = timestamp + grid.header.frame_id = frame_id + grid.data = array.ravel().tolist() + grid.info.resolution = resolution + grid.info.height = array.shape[0] + grid.info.width = array.shape[1] + grid.info.origin.position.x = float(world[0]) + grid.info.origin.position.y = float(world[1]) + return grid + + @staticmethod + def bresenham(x1: int, y1: int, x2: int, y2: int) -> np.ndarray: + """Implementation of Bresenham's line drawing algorithm. The first point can be thought of + as the source point and the second point as the target point. + + Parameters + ---------- + x1: int + X-axis position in occupancy grid of first point. + y1: int + Y-axis position in occupancy grid of first point. + x2: int + X-axis position in occupancy grid of second point. + y2: int + Y-axis position in occupancy grid of second point. + Returns + ------- + :py:class:`ndarray ` of shape `(N,2)` + The first column corresponds to the X's and the second column corresponds to the Y's + occupancy grid indexes that the line covers. + + Examples + -------- + >>> points1 = bresenham((4, 4), (6, 10)) + >>> print(points1) + np.array([[4,4], [4,5], [5,6], [5,7], [5,8], [6,9], [6,10]]) + + Reference + --------- + Code inspired by a collection of sample codes for robotics algorithms. + Source code at: + * https://github.com/AtsushiSakai/PythonRobotics + """ + # setup initial conditions + dx = x2 - x1 + dy = y2 - y1 + # determine how steep the line is + is_steep = abs(dy) > abs(dx) + # rotate line + if is_steep: + x1, y1 = y1, x1 + x2, y2 = y2, x2 + # swap start and end points if necessary and store swap state + swapped = False + if x1 > x2: + x1, x2 = x2, x1 + y1, y2 = y2, y1 + swapped = True + # recalculate differentials + dx = x2 - x1 + # recalculate differentials + dy = y2 - y1 + # calculate error + error = int(dx / 2.0) + y_step = 1 if y1 < y2 else -1 + # iterate over bounding box generating points between start and end + y = y1 + points = [] + for x in range(x1, x2 + 1): + coord = [y, x] if is_steep else (x, y) + points.append(coord) + error -= abs(dy) + if error < 0: + y += y_step + error += dx + # reverse the list if the coordinates were swapped + if swapped: + points.reverse() + return np.array(points) diff --git a/turtlebot3_mapper/utils.py b/turtlebot3_mapper/utils.py index 859946d..9e1f91f 100644 --- a/turtlebot3_mapper/utils.py +++ b/turtlebot3_mapper/utils.py @@ -1,27 +1,38 @@ import numpy as np +from geometry_msgs.msg import Quaternion -def euler_from_quaternion(quaternion): - """ - Convert quaternion (w in last place) to euler roll, pitch, yaw. - quat = [x, y, z, w] - - Source: https://github.com/ROBOTIS-GIT/turtlebot3/blob/humble-devel/turtlebot3_example - """ - x = quaternion.x - y = quaternion.y - z = quaternion.z - w = quaternion.w +def euler_from_quaternion(quaternion: Quaternion): + """ Convert quaternion (w in last place) to euler roll, pitch, yaw. + + Parameters + ---------- + quaternion: :py:class:`Quarternion ` + Orientation as a quaternion. - sinr_cosp = 2 * (w * x + y * z) - cosr_cosp = 1 - 2 * (x * x + y * y) - roll = np.arctan2(sinr_cosp, cosr_cosp) + Returns + ------- + Tuple[float,float,float] + Return roll, pitch, yaw euler angles. - sinp = 2 * (w * y - z * x) - pitch = np.arcsin(sinp) + References + ---------- + Source: https://github.com/ROBOTIS-GIT/turtlebot3/blob/humble-devel/turtlebot3_example + """ + x = quaternion.x + y = quaternion.y + z = quaternion.z + w = quaternion.w - siny_cosp = 2 * (w * z + x * y) - cosy_cosp = 1 - 2 * (y * y + z * z) - yaw = np.arctan2(siny_cosp, cosy_cosp) + sinr_cosp = 2 * (w * x + y * z) + cosr_cosp = 1 - 2 * (x * x + y * y) + roll = np.arctan2(sinr_cosp, cosr_cosp) - return roll, pitch, yaw \ No newline at end of file + sinp = 2 * (w * y - z * x) + pitch = np.arcsin(sinp) + + siny_cosp = 2 * (w * z + x * y) + cosy_cosp = 1 - 2 * (y * y + z * z) + yaw = np.arctan2(siny_cosp, cosy_cosp) + + return roll, pitch, yaw diff --git a/turtlebot3_mapper/viewer.py b/turtlebot3_mapper/viewer.py deleted file mode 100644 index 86cb261..0000000 --- a/turtlebot3_mapper/viewer.py +++ /dev/null @@ -1,92 +0,0 @@ -import sys -import cv2 -import rclpy -import numpy as np - -from rclpy.node import Node -from rclpy.executors import ExternalShutdownException - -from nav_msgs.msg import OccupancyGrid - -class MapViewer(Node): - - def __init__(self, - node_name: str = 'map_viewer'): - - super(MapViewer, self).__init__(node_name=node_name) - - self._map_subscriber = self.create_subscription( - msg_type=OccupancyGrid, - topic="/custom_map", - callback=self._map_callback, - qos_profile=10, - ) - self._init = False - self.get_logger().info(f"Init {node_name}") - - def _map_callback(self, message: OccupancyGrid): - # get occupancy grid as a numpy array int8 - array = self.occupancygrid_to_numpy(message) - # convert int8 array to float32 - input = array.astype("float32") - # remap to 0-255 interval - input = 255*(input - np.min(input))/(np.max(input) - np.min(input)) - # if it is unkown or free, mark as 0 - input[input <= 150] = 0 - # if it is occupied, mark as 255 - input[input > 150] = 255 - # get array as uint8 - input = input.astype('uint8') - # kernel to apply morphological transformation - kernel = np.ones((5,5),np.uint8) - # apply closing transformation - closing = cv2.morphologyEx(input, cv2.MORPH_CLOSE, kernel) - # get component connected information - analysis = cv2.connectedComponentsWithStats(closing, 8, cv2.CV_32S) - # unpack information - (totalLabels, label_ids, values, centroid) = analysis - # get RGB image to show - output = cv2.cvtColor(closing, cv2.COLOR_GRAY2BGR) - # Loop through each component - for i in range(1, totalLabels): - x = values[i, cv2.CC_STAT_LEFT] - y = values[i, cv2.CC_STAT_TOP] - w = values[i, cv2.CC_STAT_WIDTH] - h = values[i, cv2.CC_STAT_HEIGHT] - area = values[i, cv2.CC_STAT_AREA] - (cX, cY) = x+(w//2), y+(h//2) - if (area > 30) and (area < 300): - cv2.rectangle(output, (x, y), (x + w, y + h), (0, 255, 0), 1) - cv2.circle(output, (int(cX), int(cY)), 1, (0, 0, 255), -1) - # rotate just to plot equal gazebo - rotated_image = cv2.rotate(src = output, rotateCode = cv2.ROTATE_180) - # show image - cv2.namedWindow("output", cv2.WINDOW_NORMAL) - cv2.imshow("output", rotated_image) - if cv2.waitKey(1) == ord('q'): - sys.exit(1) - - @staticmethod - def occupancygrid_to_numpy(msg, info=None): - """ - Source: http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html - """ - data = np.asarray(msg.data, dtype=np.int8).reshape(msg.info.height, msg.info.width) - return data - - - -def main(*args, **kwargs): - rclpy.init(*args, **kwargs) - node = MapViewer() - try: - rclpy.spin(node=node) - except (KeyboardInterrupt, ExternalShutdownException): - pass - finally: - node.destroy_node() - rclpy.try_shutdown() - - -if __name__ == "__main__": - main() From 51e1b6521d2d7d49d5042f60263e0d84850bd936 Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Wed, 14 Dec 2022 21:32:15 -0300 Subject: [PATCH 03/11] :wrench: Add rviz config file --- rviz/config.rviz | 268 +++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 268 insertions(+) create mode 100644 rviz/config.rviz diff --git a/rviz/config.rviz b/rviz/config.rviz new file mode 100644 index 0000000..dc8b8a4 --- /dev/null +++ b/rviz/config.rviz @@ -0,0 +1,268 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5323529243469238 + Tree Height: 719 + - 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 + - Class: rviz_common/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +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 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz_default_plugins/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 0 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: LaserScan + Position Transformer: XYZ + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Flat Squares + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.699999988079071 + Class: rviz_default_plugins/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: + Depth: 5 + Durability Policy: Volatile + Filter size: 10 + History Policy: Keep Last + Reliability Policy: Reliable + Value: /custom_map + Update Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /custom_map_updates + Use Timestamp: false + Value: true + - Class: rviz_default_plugins/Image + Enabled: true + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /rendered + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + base_footprint: + Value: true + base_link: + Value: true + base_scan: + Value: true + camera_depth_frame: + Value: true + camera_depth_optical_frame: + Value: true + camera_link: + Value: true + camera_rgb_frame: + Value: true + camera_rgb_optical_frame: + Value: true + caster_back_left_link: + Value: true + caster_back_right_link: + Value: true + imu_link: + Value: true + map: + Value: true + odom: + Value: true + wheel_left_link: + Value: true + wheel_right_link: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + map: + odom: + base_footprint: + base_link: + base_scan: + {} + camera_link: + camera_depth_frame: + camera_depth_optical_frame: + {} + camera_rgb_frame: + camera_rgb_optical_frame: + {} + caster_back_left_link: + {} + caster_back_right_link: + {} + imu_link: + {} + wheel_left_link: + {} + wheel_right_link: + {} + Update Interval: 0 + 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 + Covariance x: 0.25 + Covariance y: 0.25 + Covariance yaw: 0.06853891909122467 + 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/Orbit + Distance: 10 + 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: 1.5697963237762451 + Target Frame: + Value: Orbit (rviz) + Yaw: 4.713586807250977 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000400000000000001560000035afc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000035a000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000025e0000035afc0200000004fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0049006d006100670065010000003d000001c90000002800fffffffb0000000a00560069006500770073010000020c0000018b000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002fb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003c00000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1920 + X: 0 + Y: 27 From dae1b8da2e22390328d0583c620166b82a6d62aa Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Wed, 14 Dec 2022 21:41:18 -0300 Subject: [PATCH 04/11] :rocket: Add launch script for all nodes and apps --- launch/turtlebot3_mapper_launch.py | 117 +++++++++++++++++++++++++++++ 1 file changed, 117 insertions(+) create mode 100644 launch/turtlebot3_mapper_launch.py diff --git a/launch/turtlebot3_mapper_launch.py b/launch/turtlebot3_mapper_launch.py new file mode 100644 index 0000000..39157c4 --- /dev/null +++ b/launch/turtlebot3_mapper_launch.py @@ -0,0 +1,117 @@ +import os + +from launch_ros.actions import Node +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.substitutions import LaunchConfiguration +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from ament_index_python.packages import get_package_share_directory + + +def generate_launch_description(): + + turtlebot3_mapper_rviz_dir = os.path.join( + get_package_share_directory('turtlebot3_mapper'), + 'rviz', + ) + turtlebot3_gazebo_launch_dir = os.path.join( + get_package_share_directory('turtlebot3_gazebo'), + 'launch', + ) + use_sim_time = LaunchConfiguration('use_sim_time', default='true') + x_pose = LaunchConfiguration('x_pose', default='-2.0') + y_pose = LaunchConfiguration('y_pose', default='-0.5') + turtlebot3_world_cmd = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join( + turtlebot3_gazebo_launch_dir, + 'turtlebot3_world.launch.py', + ), + ), + launch_arguments={ + 'x_pose': x_pose, + 'y_pose': y_pose, + 'use_sim_time': use_sim_time, + }.items(), + ) + nav2_launch_file_dir = os.path.join(get_package_share_directory('nav2_bringup'), 'launch') + rviz_config_file = LaunchConfiguration( + 'rviz_config_file', + default=os.path.join( + turtlebot3_mapper_rviz_dir, + 'config.rviz', + ), + ) + rviz_cmd = IncludeLaunchDescription( + PythonLaunchDescriptionSource(os.path.join( + nav2_launch_file_dir, + 'rviz_launch.py', + )), + launch_arguments={'rviz_config': rviz_config_file}.items(), + ) + turtlebot3_occupancy_grid_node = Node( + package='turtlebot3_mapper', + namespace='', + executable='turtlebot3_occupancy_grid', + name='turtlebot3_occupancy_grid', + parameters=[ + { + "width": 8.0 + }, + { + "height": 8.0 + }, + { + "resolution": 0.03, + }, + { + "min_prob": 0.01 + }, + { + "max_prob": 0.99, + }, + { + "prob_occupied": 0.6, + }, + { + "prob_free": 0.4, + }, + { + "prob_priori": 0.5, + }, + ], + ) + turtlebot3_object_detector_node = Node( + package='turtlebot3_mapper', + namespace='', + executable='turtlebot3_object_detector', + name='turtlebot3_object_detector', + parameters=[ + { + "threshold": 150, + }, + { + "min_area": 30, + }, + { + "max_area": 100, + }, + { + "connectivity": 4, + }, + ], + ) + turtlebot3_explorer_node = Node( + package='turtlebot3_mapper', + namespace='', + executable='turtlebot3_explorer', + name='turtlebot3_explorer', + ) + ld = LaunchDescription() + ld.add_action(rviz_cmd) + ld.add_action(turtlebot3_world_cmd) + ld.add_action(turtlebot3_explorer_node) + ld.add_action(turtlebot3_occupancy_grid_node) + ld.add_action(turtlebot3_object_detector_node) + return ld \ No newline at end of file From 54e3c6e8dea3a08ee07d663f10973807b3c656a6 Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Thu, 15 Dec 2022 22:10:53 -0300 Subject: [PATCH 05/11] :truck: Move utility functions to utils module --- .../turtlebot3_object_detector.py | 16 +-- .../turtlebot3_occupancy_grid.py | 122 ++--------------- turtlebot3_mapper/utils.py | 123 ++++++++++++++++++ 3 files changed, 137 insertions(+), 124 deletions(-) diff --git a/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py b/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py index 42d43d8..a274b0f 100644 --- a/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py +++ b/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py @@ -12,6 +12,8 @@ from vision_msgs.msg import BoundingBox2DArray, BoundingBox2D from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult +from turtlebot3_mapper.utils import occupancy_grid_to_numpy + class Turtlebot3ObjectDetector(Node): @@ -25,10 +27,10 @@ def parameter_callback(self, parameters: List[Parameter]) -> SetParametersResult self.get_logger().info("Updated parameter connectivity=%.2f" % self.connectivity) elif param.name == "min_area": self.min_area = param.value - self.get_logger().info("Updated parameter connectivity=%.2f" % self.min_area) + self.get_logger().info("Updated parameter min_area=%.2f" % self.min_area) elif param.name == "max_area": self.max_area = param.value - self.get_logger().info("Updated parameter connectivity=%.2f" % self.max_area) + self.get_logger().info("Updated parameter max_area=%.2f" % self.max_area) else: return SetParametersResult(successful=False) return SetParametersResult(successful=True) @@ -88,7 +90,7 @@ def __init__(self, node_name: str = 'turtlebot3_object_detector'): def _map_callback(self, message: OccupancyGrid): # get occupancy grid as a numpy array int8 - array = self.occupancygrid_to_numpy(message) + array = occupancy_grid_to_numpy(message) # convert int8 array to float32 input = array.astype("float32") # remap to 0-255 interval @@ -128,11 +130,3 @@ def _map_callback(self, message: OccupancyGrid): image_ros = self._bridge.cv2_to_imgmsg(cvim=np.flip(output, axis=0)) image_ros.header = message.header self._result_publisher.publish(image_ros) - - @staticmethod - def occupancygrid_to_numpy(msg, info=None): - """ - Source: http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html - """ - data = np.asarray(msg.data, dtype=np.int8).reshape(msg.info.height, msg.info.width) - return data diff --git a/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py b/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py index 4ae5793..b990330 100644 --- a/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py +++ b/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py @@ -19,7 +19,12 @@ from tf2_ros.transform_listener import TransformListener from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster -from turtlebot3_mapper.utils import euler_from_quaternion +from turtlebot3_mapper.utils import ( + numpy_to_occupancy_grid, + euler_from_quaternion, + laser_scan_to_polar, + polar_to_cartesian, +) class State(Enum): @@ -192,8 +197,8 @@ def update_map(self, message_laser: LaserScan): _, _, theta = euler_from_quaternion(quaternion=quaternion) if theta < 0.0: theta += 2 * np.pi - polar = self.laser_scan_to_polar(message=message_laser) - xy = self.polar_to_cartesian( + polar = laser_scan_to_polar(message=message_laser) + xy = polar_to_cartesian( coordinates=polar, x=tf.transform.translation.x, y=tf.transform.translation.y, @@ -267,7 +272,7 @@ def occupancy_grid(self): grid = np.transpose(grid) # convert to int8 and returns as occupancy grid grid = grid.astype("int8") - return self.numpy_to_occupancy_grid( + return numpy_to_occupancy_grid( array=grid, resolution=self.resolution, world=(-self.width // 2, -self.height // 2), @@ -313,115 +318,6 @@ def probability(log_odd: float) -> float: result = 0.0 return result - @staticmethod - def laser_scan_to_polar(message: LaserScan) -> np.ndarray: - """Convert a LaserScan message to a numpy array with points polar coordinates obtained. If - the message indicates infinity, set the distance as the sensor's maximum value. In the - same way, if the message indicates a distance value smaller than the minimum distance, set - the sensor's minimum distance. - - Parameters - ---------- - message: :py:class:`LaserScan ` - Message received from laser sensor. - - Returns - ------- - :py:class:`ndarray ` of shape `(N,2)` - Points sampled in polar coordinates. The first column corresponds to the distance (in - meters) and the second column corresponds to the angle (in radians). - """ - N = len(message.ranges) - array = np.zeros((N, 2)) - for i in range(len(message.ranges)): - angle = i * message.angle_increment - if message.ranges[i] > message.range_max: - distance = message.range_max - elif message.ranges[i] < message.range_min: - distance = message.range_min - else: - distance = message.ranges[i] - array[i, 0] = distance - array[i, 1] = angle - return array - - @staticmethod - def polar_to_cartesian(coordinates: np.ndarray, x: float, y: float, - theta: float) -> np.ndarray: - """Convert points in polar coordinates in the laser reference to cartesian coordinates in - the odometry reference. - - Parameters - ---------- - coordinates: :py:class:`ndarray ` of shape `(N,2)` - Points sampled in polar coordinates. The first column corresponds to the distance (in - meters) and the second column corresponds to the angle (in radians). - x: float - Laser position on the X-axis in the odometry referential. - y: float - Laser position on the Y-axis in the odometry referential. - theta: float - Laser rotation in the odometry referential. - - Returns - ------- - :py:class:`ndarray ` of shape `(N,2)` - Points sample in cartesian coordinates at odometry referential. The first column - corresponds to the X's and the second column corresponds to the Y's. - """ - N = coordinates.shape[0] - array = np.zeros((N, 2)) - array[:, 0] = x + coordinates[:, 0] * np.cos(coordinates[:, 1] + theta) - array[:, 1] = y + coordinates[:, 0] * np.sin(coordinates[:, 1] + theta) - return array - - @staticmethod - def numpy_to_occupancy_grid(array: np.ndarray, resolution: float, world: Tuple[float, float], - frame_id: str, timestamp: Time): - """Utility to converts an :py:class:`ndarray ` to an - :py:class:`OccupancyGrid `. - - Parameters - ---------- - array: :py:class:`ndarray ` of shape `(N,M)` - Two dimentional numpy array to convert in a occupancy grid message. - resolution: float - Occupancy grid resolution. - world: Tuple[float,float] - `(x,y)` world position. - frame_id: str - Referential frame name. - timestamp: Time - Timestamp info. - - Returns - ------- - :py:class:`OccupancyGrid ` - Occupancy grid message. - - Reference - --------- - Code inspired by `ros_numpy` package, a collection of conversion function for extracting - numpy arrays from messages. Source code at: - * http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html - """ - if not len(array.shape) == 2: - raise TypeError('Array must be 2D') - if not array.dtype == np.int8: - raise TypeError('Array must be of int8s') - grid = OccupancyGrid() - if isinstance(array, np.ma.MaskedArray): - array = array.data - grid.header.stamp = timestamp - grid.header.frame_id = frame_id - grid.data = array.ravel().tolist() - grid.info.resolution = resolution - grid.info.height = array.shape[0] - grid.info.width = array.shape[1] - grid.info.origin.position.x = float(world[0]) - grid.info.origin.position.y = float(world[1]) - return grid - @staticmethod def bresenham(x1: int, y1: int, x2: int, y2: int) -> np.ndarray: """Implementation of Bresenham's line drawing algorithm. The first point can be thought of diff --git a/turtlebot3_mapper/utils.py b/turtlebot3_mapper/utils.py index 9e1f91f..ce8f813 100644 --- a/turtlebot3_mapper/utils.py +++ b/turtlebot3_mapper/utils.py @@ -1,4 +1,11 @@ +from typing import Tuple + import numpy as np + +from rclpy.time import Time + +from sensor_msgs.msg import LaserScan +from nav_msgs.msg import OccupancyGrid from geometry_msgs.msg import Quaternion @@ -36,3 +43,119 @@ def euler_from_quaternion(quaternion: Quaternion): yaw = np.arctan2(siny_cosp, cosy_cosp) return roll, pitch, yaw + + +def laser_scan_to_polar(message: LaserScan) -> np.ndarray: + """Convert a LaserScan message to a numpy array with points polar coordinates obtained. If + the message indicates infinity, set the distance as the sensor's maximum value. In the + same way, if the message indicates a distance value smaller than the minimum distance, set + the sensor's minimum distance. + + Parameters + ---------- + message: :py:class:`LaserScan ` + Message received from laser sensor. + + Returns + ------- + :py:class:`ndarray ` of shape `(N,2)` + Points sampled in polar coordinates. The first column corresponds to the distance (in + meters) and the second column corresponds to the angle (in radians). + """ + N = len(message.ranges) + array = np.zeros((N, 2)) + for i in range(len(message.ranges)): + angle = i * message.angle_increment + if message.ranges[i] > message.range_max: + distance = message.range_max + elif message.ranges[i] < message.range_min: + distance = message.range_min + else: + distance = message.ranges[i] + array[i, 0] = distance + array[i, 1] = angle + return array + + +def polar_to_cartesian(coordinates: np.ndarray, x: float, y: float, theta: float) -> np.ndarray: + """Convert points in polar coordinates in the laser reference to cartesian coordinates in + the odometry reference. + + Parameters + ---------- + coordinates: :py:class:`ndarray ` of shape `(N,2)` + Points sampled in polar coordinates. The first column corresponds to the distance (in + meters) and the second column corresponds to the angle (in radians). + x: float + Laser position on the X-axis in the odometry referential. + y: float + Laser position on the Y-axis in the odometry referential. + theta: float + Laser rotation in the odometry referential. + + Returns + ------- + :py:class:`ndarray ` of shape `(N,2)` + Points sample in cartesian coordinates at odometry referential. The first column + corresponds to the X's and the second column corresponds to the Y's. + """ + N = coordinates.shape[0] + array = np.zeros((N, 2)) + array[:, 0] = x + coordinates[:, 0] * np.cos(coordinates[:, 1] + theta) + array[:, 1] = y + coordinates[:, 0] * np.sin(coordinates[:, 1] + theta) + return array + + +def numpy_to_occupancy_grid(array: np.ndarray, resolution: float, world: Tuple[float, float], + frame_id: str, timestamp: Time): + """Utility to converts an :py:class:`ndarray ` to an + :py:class:`OccupancyGrid `. + + Parameters + ---------- + array: :py:class:`ndarray ` of shape `(N,M)` + Two dimentional numpy array to convert in a occupancy grid message. + resolution: float + Occupancy grid resolution. + world: Tuple[float,float] + `(x,y)` world position. + frame_id: str + Referential frame name. + timestamp: Time + Timestamp info. + + Returns + ------- + :py:class:`OccupancyGrid ` + Occupancy grid message. + + Reference + --------- + Code inspired by `ros_numpy` package, a collection of conversion function for extracting + numpy arrays from messages. Source code at: + * http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html + """ + if not len(array.shape) == 2: + raise TypeError('Array must be 2D') + if not array.dtype == np.int8: + raise TypeError('Array must be of int8s') + grid = OccupancyGrid() + if isinstance(array, np.ma.MaskedArray): + array = array.data + grid.header.stamp = timestamp + grid.header.frame_id = frame_id + grid.data = array.ravel().tolist() + grid.info.resolution = resolution + grid.info.height = array.shape[0] + grid.info.width = array.shape[1] + grid.info.origin.position.x = float(world[0]) + grid.info.origin.position.y = float(world[1]) + return grid + + +def occupancy_grid_to_numpy(msg): + """ + Source: http://docs.ros.org/en/jade/api/ros_numpy/html/occupancy__grid_8py_source.html + """ + data = np.asarray(msg.data, dtype=np.int8).reshape(msg.info.height, msg.info.width) + return data From c96e0e2c0e64ca8d9700418771fcefe502427fa7 Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Thu, 15 Dec 2022 22:12:35 -0300 Subject: [PATCH 06/11] :art: Improve turtlebot3_explorer node strucuture --- launch/turtlebot3_mapper_launch.py | 23 ++ .../turtlebot3_explorer.py | 281 +++++++++++------- 2 files changed, 202 insertions(+), 102 deletions(-) diff --git a/launch/turtlebot3_mapper_launch.py b/launch/turtlebot3_mapper_launch.py index 39157c4..f6461c2 100644 --- a/launch/turtlebot3_mapper_launch.py +++ b/launch/turtlebot3_mapper_launch.py @@ -107,6 +107,29 @@ def generate_launch_description(): namespace='', executable='turtlebot3_explorer', name='turtlebot3_explorer', + parameters=[ + { + "view_angle": 30.0, + }, + { + "min_rand": 10, + }, + { + "max_rand": 20, + }, + { + "safety_distance": 0.5, + }, + { + "linear_speed": 0.15, + }, + { + "angular_speed": 0.25, + }, + { + "update_rate": 0.5, + }, + ], ) ld = LaunchDescription() ld.add_action(rviz_cmd) diff --git a/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py b/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py index 00c2b23..a1ef30c 100644 --- a/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py +++ b/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py @@ -1,146 +1,223 @@ -import rclpy -import threading +import random +from enum import Enum +from typing import List + import numpy as np -from enum import Enum from rclpy.node import Node -from rclpy.executors import ExternalShutdownException +from rclpy.parameter import Parameter + +from std_srvs.srv import SetBool -from nav_msgs.msg import Odometry from geometry_msgs.msg import Twist from sensor_msgs.msg import LaserScan +from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult -from turtlebot3_mapper.utils import euler_from_quaternion +from tf2_ros.buffer import Buffer +from tf2_ros import LookupException, TransformException +from tf2_ros.transform_listener import TransformListener + +from turtlebot3_mapper.utils import ( + euler_from_quaternion, + laser_scan_to_polar, +) class State(Enum): FORWARD = 1 ROTATE = 2 - UNKOWN = 3 + STOP = 3 + UNKOWN = 4 class Turtlebot3Explorer(Node): + def parameter_callback(self, parameters: List[Parameter]) -> SetParametersResult: + for param in parameters: + if param.name == "view_angle": + self.view_angle = param.value + self.get_logger().info("Updated parameter view_angle=%.2f" % self.view_angle) + elif param.name == "min_rand": + self.min_rand = param.value + self.get_logger().info("Updated parameter min_rand=%.2f" % self.min_rand) + elif param.name == "max_rand": + self.max_rand = param.value + self.get_logger().info("Updated parameter max_rand=%.2f" % self.max_rand) + elif param.name == "safety_distance": + self.safety_distance = param.value + self.get_logger().info("Updated parameter safety_distance=%.2f" % + self.safety_distance) + elif param.name == "linear_speed": + self.linear_speed = param.value + self.get_logger().info("Updated parameter linear_speed=%.2f" % self.linear_speed) + elif param.name == "angular_speed": + self.angular_speed = param.value + self.get_logger().info("Updated parameter angular_speed=%.2f" % self.angular_speed) + else: + return SetParametersResult(successful=False) + return SetParametersResult(successful=True) + def __init__(self, node_name: str = 'turtlebot_explorer'): super(Turtlebot3Explorer, self).__init__(node_name=node_name) + self.declare_parameters( + namespace="", + parameters=[ + ( + "view_angle", + 30.0, + ParameterDescriptor(description="View angle"), + ), + ( + "min_rand", + 1, + ParameterDescriptor(description="Min range random limit"), + ), + ( + "max_rand", + 10, + ParameterDescriptor(description="Max range random limit"), + ), + ( + "safety_distance", + 0.5, + ParameterDescriptor(description="Safety distance"), + ), + ( + "linear_speed", + 0.15, + ParameterDescriptor(description="Linear speed"), + ), + ( + "angular_speed", + 0.15, + ParameterDescriptor(description="Angular speed"), + ), + ( + "update_rate", + 0.5, + ParameterDescriptor(description="Update rate"), + ), + ], + ) + self.view_angle = float(self.get_parameter("view_angle").value) + self.min_rand = float(self.get_parameter("min_rand").value) + self.max_rand = float(self.get_parameter("max_rand").value) + self.safety_distance = float(self.get_parameter("safety_distance").value) + self.linear_speed = float(self.get_parameter("linear_speed").value) + self.angular_speed = float(self.get_parameter("angular_speed").value) + self.add_on_set_parameters_callback(self.parameter_callback) self._subscriber_scan = self.create_subscription( msg_type=LaserScan, topic="/scan", callback=self._scan_callback, qos_profile=10, ) - self._subscriber_odom = self.create_subscription( - msg_type=Odometry, - topic="/odom", - callback=self._odom_callback, - qos_profile=10, - ) self._publisher = self.create_publisher( msg_type=Twist, topic="/cmd_vel", qos_profile=10, ) self.update_timer = self.create_timer( - timer_period_sec=1, - callback=self.update_callback, + timer_period_sec=(1 / self.get_parameter("update_rate").value), + callback=self._update_callback, + ) + self.srv = self.create_service( + SetBool, + 'enable', + self._enable_callback, ) - self.view_angle = 90 - self._odom_init = False self._scan_init = False + self.count = 0 self.multiplier = 1.0 - self._update = threading.Lock() + self.limit = random.randint(self.min_rand, self.max_rand) self.state = State.UNKOWN - self.get_logger().info("Init turtlebot_explorer") + self.enable = False + + self._tf_buffer = Buffer() + self._tf_listener = TransformListener(self._tf_buffer, self) + self.get_logger().info("Init {}".format(node_name)) + + def _enable_callback(self, request, response): + self.enable = request.data + response.success = True + response.message = "Configured" + return response def _scan_callback(self, message: LaserScan): - if not self._update.locked(): - self._scan = message + self._scan = message self._scan_init = True - def _odom_callback(self, message: Odometry): - self._odom = message - if not self._update.locked(): - self._odom = message - self._odom_init = True - - def update_callback(self): - if self._scan_init and self._odom_init: - if self._update.locked(): - return - else: - self._update.acquire() - self.get_logger().info("updating...") - self.detect_obstacle() - self._update.release() + def _update_callback(self): + if self._scan_init: + self.get_logger().info("updating...") + self.detect_obstacle() + + def set_robot(self, state: State): + twist = Twist() + twist.linear.y = 0.0 + twist.linear.z = 0.0 + twist.angular.x = 0.0 + twist.angular.y = 0.0 + if state == State.STOP: + twist.linear.x = 0.0 + twist.angular.z = 0.0 + self._publisher.publish(twist) + elif state == State.FORWARD: + twist.linear.x = self.linear_speed + twist.angular.z = 0.0 + self._publisher.publish(twist) + elif state == State.ROTATE: + twist.linear.x = 0.0 + twist.angular.z = self.angular_speed * self.multiplier + self.count += 1 + if self.count >= self.limit: + self.limit = random.randint(self.min_rand, self.max_rand) + self.count = 0 + self.multiplier *= -1.0 + self._publisher.publish(twist) def detect_obstacle(self): - # unit: m - safety_distance = 0.5 - - _, _, theta = euler_from_quaternion(self._odom.pose.pose.orientation) - - min_ang = (-140) * (np.pi / 180) - max_ang = (140) * (np.pi / 180) - - increm = self._scan.angle_increment - size = len(self._scan.ranges) - - start = int(size / 2 + min_ang / increm) - end = int(size / 2 + max_ang / increm) - - # scan_range = [self.scan.ranges[i] for i in range(90, 270)] - scan_range = [self._scan.ranges[i] for i in range(end, len(self._scan.ranges))] - for i in range(0, start): - scan_range.append(self._scan.ranges[i]) - - obstacle_distance = min(scan_range) - - if self.state == State.UNKOWN: - if obstacle_distance < safety_distance: - if self.state != State.ROTATE: - twist = Twist() - twist.linear.x = 0.0 - twist.angular.z = 0.25 * self.multiplier - if self.count >= 3: - self.count = 0 - self.multiplier *= -1.0 - self.count += 1 + scan = self._scan + try: + trans = self._tf_buffer.lookup_transform(scan.header.frame_id, "base_link", + scan.header.stamp) + except (TransformException, LookupException) as ex: + self.get_logger().warn(f'Could not transform "odom" to {scan.header.frame_id}: {ex}') + return + + _, _, theta = euler_from_quaternion(trans.transform.rotation) + min_angle = (-self.view_angle + theta) * (np.pi / 180) + (2 * np.pi) + max_angle = (self.view_angle + theta) * (np.pi / 180) + + polar = laser_scan_to_polar(message=scan) + mask = (polar[:, 1] >= (min_angle)) | (polar[:, 1] <= max_angle) + distance_range = polar[mask, :] + + obstacle_distance = np.min(distance_range[:, 0]) + self.get_logger().info("Closest obstacle={}".format(obstacle_distance)) + + if not self.enable: + if self.state != State.STOP: + self.state = State.STOP + self.set_robot(state=self.state) + else: + if self.state == State.UNKOWN or self.state == State.STOP: + if obstacle_distance < self.safety_distance: self.state = State.ROTATE - self._publisher.publish(twist) - else: - self.state = State.FORWARD - twist = Twist() - twist.linear.x = 0.25 - twist.angular.z = 0.0 - self._publisher.publish(twist) - - elif self.state == State.FORWARD: - if obstacle_distance < safety_distance: - if self.state != State.ROTATE: - twist = Twist() - twist.linear.x = 0.0 - twist.angular.z = 0.25 * self.multiplier - if self.count >= 3: - self.count = 0 - self.multiplier *= -1.0 - self.count += 1 + self.set_robot(state=self.state) + else: + self.state = State.FORWARD + self.set_robot(state=self.state) + elif self.state == State.FORWARD: + if obstacle_distance < self.safety_distance: self.state = State.ROTATE - self._publisher.publish(twist) - else: - twist = Twist() - twist.linear.x = 0.25 - twist.angular.z = 0.0 - self.state = State.FORWARD - self._publisher.publish(twist) - - else: - if obstacle_distance < safety_distance: - pass - else: - twist = Twist() - twist.linear.x = 0.25 - twist.angular.z = 0.0 - self.state = State.FORWARD - self._publisher.publish(twist) + self.set_robot(state=self.state) + else: + self.state = State.FORWARD + self.set_robot(state=self.state) + elif self.state == State.ROTATE: + if obstacle_distance > self.safety_distance: + self.state = State.FORWARD + self.set_robot(state=self.state) From 101d1f9e39c4ba96ffba19bbaf1a0908205ed900 Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Fri, 16 Dec 2022 17:17:19 -0300 Subject: [PATCH 07/11] :sparkles: Add mission controller and client --- launch/turtlebot3_mapper_launch.py | 12 ++ package.xml | 1 + setup.py | 3 + .../turtlebot3_mission_client/__init__.py | 0 .../turtlebot3_mission_client/main.py | 59 ++++++ .../turtlebot3_mission_client.py | 85 ++++++++ .../turtlebot3_mission_controller/__init__.py | 0 .../turtlebot3_mission_controller/main.py | 22 +++ .../turtlebot3_mission_controller.py | 183 ++++++++++++++++++ 9 files changed, 365 insertions(+) create mode 100644 turtlebot3_mapper/turtlebot3_mission_client/__init__.py create mode 100644 turtlebot3_mapper/turtlebot3_mission_client/main.py create mode 100644 turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py create mode 100644 turtlebot3_mapper/turtlebot3_mission_controller/__init__.py create mode 100644 turtlebot3_mapper/turtlebot3_mission_controller/main.py create mode 100644 turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py diff --git a/launch/turtlebot3_mapper_launch.py b/launch/turtlebot3_mapper_launch.py index f6461c2..8258536 100644 --- a/launch/turtlebot3_mapper_launch.py +++ b/launch/turtlebot3_mapper_launch.py @@ -131,10 +131,22 @@ def generate_launch_description(): }, ], ) + turtlebot3_mission_controller_node = Node( + package='turtlebot3_mapper', + namespace='', + executable='turtlebot3_mission_controller', + name='turtlebot3_mission_controller', + parameters=[ + { + "free_limit": 30, + }, + ], + ) ld = LaunchDescription() ld.add_action(rviz_cmd) ld.add_action(turtlebot3_world_cmd) ld.add_action(turtlebot3_explorer_node) ld.add_action(turtlebot3_occupancy_grid_node) ld.add_action(turtlebot3_object_detector_node) + ld.add_action(turtlebot3_mission_controller_node) return ld \ No newline at end of file diff --git a/package.xml b/package.xml index 6180884..1dd8c26 100644 --- a/package.xml +++ b/package.xml @@ -13,6 +13,7 @@ sensor_msgs rcl_interfaces tf2_ros + turtlebot3_interfaces python3-numpy ament_copyright diff --git a/setup.py b/setup.py index ef4b3df..9474787 100644 --- a/setup.py +++ b/setup.py @@ -13,6 +13,7 @@ path.join(package_name, "turtlebot3_occupancy_grid"), path.join(package_name, "turtlebot3_object_detector"), path.join(package_name, "turtlebot3_mission_controller"), + path.join(package_name, "turtlebot3_mission_client"), ], data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), @@ -47,6 +48,8 @@ turtlebot3_mapper.turtlebot3_object_detector.main:main', 'turtlebot3_mission_controller = \ turtlebot3_mapper.turtlebot3_mission_controller.main:main', + 'turtlebot3_mission_client = \ + turtlebot3_mapper.turtlebot3_mission_client.main:main', ], }, ) diff --git a/turtlebot3_mapper/turtlebot3_mission_client/__init__.py b/turtlebot3_mapper/turtlebot3_mission_client/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/turtlebot3_mapper/turtlebot3_mission_client/main.py b/turtlebot3_mapper/turtlebot3_mission_client/main.py new file mode 100644 index 0000000..85acf66 --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_mission_client/main.py @@ -0,0 +1,59 @@ +import rclpy +import argparse + +from rclpy.executors import ExternalShutdownException + +from turtlebot3_mapper.turtlebot3_mission_client.turtlebot3_mission_client \ + import Turtlebot3MissionClient + + +def main(*args, **kwargs): + parser = argparse.ArgumentParser(description='Explore enviromment') + parser.add_argument('-f', + action='store', + dest='frontiers', + type=int, + default=10, + required=True, + help='Minimal number of frontiers to reach') + parser.add_argument('--width', + action='store', + dest='width', + type=int, + default=8, + required=False, + help='Width of map') + parser.add_argument('--height', + action='store', + dest='height', + type=int, + default=8, + required=False, + help='Height of map') + parser.add_argument('--resolution', + action='store', + dest='resolution', + type=float, + default=0.03, + required=False, + help='Resolution of map') + args = parser.parse_args() + rclpy.init(args=None) + node = Turtlebot3MissionClient( + resolution=args.resolution, + width=args.width, + height=args.height, + node_name="turtlebot3_mission_client", + ) + node.send_goal(frontiers=args.frontiers) + try: + rclpy.spin(node=node) + except (KeyboardInterrupt, ExternalShutdownException): + node.cancel() + finally: + node.destroy_node() + rclpy.try_shutdown() + + +if __name__ == "__main__": + main() diff --git a/turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py b/turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py new file mode 100644 index 0000000..c74b3ff --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py @@ -0,0 +1,85 @@ +import rclpy +from rclpy.node import Node +from rclpy.task import Future +from rclpy.action import ActionClient + +from action_msgs.msg import GoalStatus + +from turtlebot3_interfaces.action import Mission + + +class Turtlebot3MissionClient(Node): + + def __init__(self, + resolution: float, + width: int, + height: int, + node_name: str = "turtlebot3_mission_client"): + super().__init__(node_name=node_name) + self._action_client = ActionClient( + self, + Mission, + 'mission', + ) + self.resolution = resolution + self.width = width + self.height = height + self.world = (-self.width // 2, -self.height // 2) + + def cancel_done(self, future): + cancel_response = future.result() + if len(cancel_response.goals_canceling) > 0: + self.get_logger().info('Goal successfully canceled') + else: + self.get_logger().info('Goal failed to cancel') + rclpy.shutdown() + + def goal_response_callback(self, future): + goal_handle = future.result() + if not goal_handle.accepted: + self.get_logger().info('Goal rejected :(') + return + self._goal_handle = goal_handle + self.get_logger().info('Goal accepted :)') + self._get_result_future = goal_handle.get_result_async() + self._get_result_future.add_done_callback(self.get_result_callback) + + def get_result_callback(self, future): + result = future.result().result + status = future.result().status + if status == GoalStatus.STATUS_SUCCEEDED: + self.get_logger().info('Goal succeeded! Result: {0}'.format(result.frontiers)) + else: + self.get_logger().info('Goal failed with status: {0}'.format(status)) + with open("results.txt", "w") as file: + file.write("x;y;width;height\n") + for bbox in result.bbox.boxes: + x = round((bbox.center.position.x * self.resolution) + self.world[0], 2) + y = round((bbox.center.position.y * self.resolution) + self.world[0], 2) + size_x = round(bbox.size_x * self.resolution, 2) + size_y = round(bbox.size_y * self.resolution, 2) + file.write(f"{x};{y};{size_x};{size_y}\n") + + rclpy.shutdown() + + def feedback_callback(self, feedback): + self.get_logger().info('Received feedback, frontiers={0}'.format( + feedback.feedback.frontiers)) + + def cancel(self): + self.get_logger().info('Canceling goal') + future = self._goal_handle.cancel_goal_async() + future.add_done_callback(self.cancel_done) + + def send_goal(self, frontiers: int): + self.get_logger().info('Waiting for action server...') + self._action_client.wait_for_server() + + goal_msg = Mission.Goal() + goal_msg.frontiers = frontiers + self.get_logger().info('Sending goal request...') + + self._send_goal_future = self._action_client.send_goal_async( + goal_msg, feedback_callback=self.feedback_callback) + + self._send_goal_future.add_done_callback(self.goal_response_callback) diff --git a/turtlebot3_mapper/turtlebot3_mission_controller/__init__.py b/turtlebot3_mapper/turtlebot3_mission_controller/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/turtlebot3_mapper/turtlebot3_mission_controller/main.py b/turtlebot3_mapper/turtlebot3_mission_controller/main.py new file mode 100644 index 0000000..93ed504 --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_mission_controller/main.py @@ -0,0 +1,22 @@ +import rclpy +from rclpy.executors import ExternalShutdownException, MultiThreadedExecutor + +from turtlebot3_mapper.turtlebot3_mission_controller.turtlebot3_mission_controller \ + import Turtlebot3MissionController + + +def main(*args, **kwargs): + rclpy.init(*args, **kwargs) + executor = MultiThreadedExecutor() + node = Turtlebot3MissionController() + try: + rclpy.spin(node=node, executor=executor) + except (KeyboardInterrupt, ExternalShutdownException): + pass + finally: + node.destroy_node() + rclpy.try_shutdown() + + +if __name__ == "__main__": + main() diff --git a/turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py b/turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py new file mode 100644 index 0000000..3032a68 --- /dev/null +++ b/turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py @@ -0,0 +1,183 @@ +import time +import threading +from functools import partial +from typing import Tuple, List + +import numpy as np + +from rclpy.node import Node +from rclpy.parameter import Parameter +from rclpy.action.server import ServerGoalHandle +from rclpy.callback_groups import ReentrantCallbackGroup +from rclpy.action import ActionServer, CancelResponse, GoalResponse + +from std_srvs.srv import SetBool +from nav_msgs.msg import OccupancyGrid +from vision_msgs.msg import BoundingBox2DArray +from rcl_interfaces.msg import ParameterDescriptor, SetParametersResult + +from turtlebot3_interfaces.action import Mission +from turtlebot3_mapper.utils import occupancy_grid_to_numpy + + +class Turtlebot3MissionController(Node): + + def parameter_callback(self, parameters: List[Parameter]) -> SetParametersResult: + for param in parameters: + if param.name == "free_limit": + self.free_limit = param.value + self.get_logger().info("Updated parameter free_limit=%.2f" % self.free_limit) + else: + return SetParametersResult(successful=False) + return SetParametersResult(successful=True) + + def __init__(self, node_name: str = 'turtlebot_mission_controller'): + super(Turtlebot3MissionController, self).__init__(node_name=node_name) + self.declare_parameters( + namespace="", + parameters=[ + ( + "free_limit", + 30, + ParameterDescriptor(description="Max probability to consider cell free"), + ), + ], + ) + self.add_on_set_parameters_callback(self.parameter_callback) + self.free_limit = int(self.get_parameter("free_limit").value) + action_callback_group = ReentrantCallbackGroup() + service_callback_group = ReentrantCallbackGroup() + subscription_callback_group = ReentrantCallbackGroup() + self._goal_handle = None + self._goal_lock = threading.Lock() + self._subscriber_scan = self.create_subscription( + msg_type=OccupancyGrid, + topic="/custom_map", + callback=self._grid_callback, + qos_profile=10, + callback_group=subscription_callback_group, + ) + self._subscriber_bbox = self.create_subscription( + msg_type=BoundingBox2DArray, + topic="/detections", + callback=self._bbox_callback, + qos_profile=10, + callback_group=subscription_callback_group, + ) + self._action_server = ActionServer( + node=self, + action_type=Mission, + action_name='mission', + execute_callback=self._execute_callback, + goal_callback=self._goal_callback, + handle_accepted_callback=self._handle_accepted_callback, + cancel_callback=self._cancel_callback, + callback_group=action_callback_group, + ) + self.cli = self.create_client( + SetBool, + 'enable', + callback_group=service_callback_group, + ) + self.grid = None + self.bbox = None + self.get_logger().info("Init {}".format(node_name)) + + def _goal_callback(self, goal_request: Mission.Goal): + self.get_logger().info("Received goal request") + return GoalResponse.ACCEPT + + def _handle_accepted_callback(self, goal_handle: ServerGoalHandle) -> None: + with self._goal_lock: + if self._goal_handle is not None and self._goal_handle.is_active: + self.get_logger().info('Aborting previous goal') + self._goal_handle.abort() + self._goal_handle = goal_handle + goal_handle.execute() + + def _cancel_callback(self, goal_handle: ServerGoalHandle) -> CancelResponse.ACCEPT: + self.get_logger().info('Received cancel request') + return CancelResponse.ACCEPT + + def _execute_callback(self, goal_handle: ServerGoalHandle) -> Mission.Result: + frontiers = np.inf + self._send_request(enable=True) + while frontiers > goal_handle.request.frontiers: + if not goal_handle.is_active: + self._send_request(enable=False) + self.get_logger().info('Goal aborted') + response = Mission.Result() + response.frontiers = int(frontiers) + response.bbox = self.bbox + return response + if goal_handle.is_cancel_requested: + self._send_request(enable=False) + goal_handle.canceled() + self.get_logger().info('Goal canceled') + response = Mission.Result() + response.frontiers = int(frontiers) + response.bbox = self.bbox + return response + + frontiers = self.count_frontiers(message=self.grid, free_limit=self.free_limit) + feedback_msg = Mission.Feedback() + feedback_msg.frontiers = int(frontiers) + goal_handle.publish_feedback(feedback_msg) + self.get_logger().info("Frontiers={}".format(frontiers)) + time.sleep(1) + self._send_request(enable=False) + goal_handle.succeed() + self.get_logger().info("Reached goal! :)") + response = Mission.Result() + response.frontiers = int(frontiers) + response.bbox = self.bbox + return response + + def _grid_callback(self, message: OccupancyGrid): + self.grid = message + self.get_logger().info("Received grid") + + def _bbox_callback(self, message: BoundingBox2DArray): + self.bbox = message + self.get_logger().info("Received grid") + + def _send_request(self, enable: bool): + while not self.cli.wait_for_service(timeout_sec=1.0): + self.get_logger().info('service not available, waiting again...') + request = SetBool.Request() + request.data = enable + future = self.cli.call_async(request) + future.add_done_callback(partial(self._callback_set)) + + def _callback_set(self, future): + try: + response = future.result() + except Exception as ex: + self.get_logger().warn("Service call failed: %r" % (ex, )) + + def count_frontiers(self, message: OccupancyGrid, free_limit: int = 30): + count = 0 + array = occupancy_grid_to_numpy(msg=message) + free = np.argwhere(array < free_limit) + for n in range(free.shape[0]): + item = free[n, :] + neighboors = self.get_neighboors(x=item[0], y=item[1], shape=array.shape) + for i in range(neighboors.shape[0]): + coord = neighboors[i, :] + value = array[coord[0], coord[1]] + if value == 50: + count += 1 + return count + + @staticmethod + def get_neighboors(x: int, y: int, shape: Tuple[int, int]): + neighboors = [] + if (x + 1) < shape[1]: + neighboors.append([x + 1, y]) + if (x - 1) >= 0: + neighboors.append([x - 1, y]) + if (y + 1) < shape[0]: + neighboors.append([x, y + 1]) + if (y - 1) >= 0: + neighboors.append([x, y - 1]) + return np.array(neighboors) From 2f53a5a2fbfd3900a752aa517c0d453076e12caa Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Sat, 17 Dec 2022 22:49:33 -0300 Subject: [PATCH 08/11] :page_facing_up: Add license, contributing guidelines and copyrights. * Add Apache 2.0 License; * Initial contributing guidelines; * Add in each source file a license and copyright statement. Signed-off-by: Luiz Carlos Cosmi Filho --- CONTRIBUTING.md | 13 ++ LICENSE | 201 ++++++++++++++++++ launch/turtlebot3_mapper_launch.py | 16 +- turtlebot3_mapper/turtlebot3_explorer/main.py | 14 ++ .../turtlebot3_explorer.py | 14 ++ .../turtlebot3_mission_client/main.py | 14 ++ .../turtlebot3_mission_client.py | 15 +- .../turtlebot3_mission_controller/main.py | 14 ++ .../turtlebot3_mission_controller.py | 16 +- .../turtlebot3_object_detector/main.py | 14 ++ .../turtlebot3_object_detector.py | 14 ++ .../turtlebot3_occupancy_grid/main.py | 14 ++ .../turtlebot3_occupancy_grid.py | 17 +- turtlebot3_mapper/utils.py | 18 +- 14 files changed, 387 insertions(+), 7 deletions(-) create mode 100644 CONTRIBUTING.md create mode 100644 LICENSE diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 0000000..bb834c8 --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,13 @@ +Any contribution that you make to this repository will be under the Apache 2 License, as dictated by that [license](http://www.apache.org/licenses/LICENSE-2.0.html): + +~~~ +5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. +~~~ + +Contributors must sign-off each commit by adding a `Signed-off-by: ...` line to commit messages to certify that they have the right to submit the code they are contributing to the project according to the [Developer Certificate of Origin (DCO)](https://developercertificate.org/). diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..f49a4e1 --- /dev/null +++ b/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. \ No newline at end of file diff --git a/launch/turtlebot3_mapper_launch.py b/launch/turtlebot3_mapper_launch.py index 8258536..9649836 100644 --- a/launch/turtlebot3_mapper_launch.py +++ b/launch/turtlebot3_mapper_launch.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import os from launch_ros.actions import Node @@ -149,4 +163,4 @@ def generate_launch_description(): ld.add_action(turtlebot3_occupancy_grid_node) ld.add_action(turtlebot3_object_detector_node) ld.add_action(turtlebot3_mission_controller_node) - return ld \ No newline at end of file + return ld diff --git a/turtlebot3_mapper/turtlebot3_explorer/main.py b/turtlebot3_mapper/turtlebot3_explorer/main.py index 3f8dc6c..6fc7d6f 100644 --- a/turtlebot3_mapper/turtlebot3_explorer/main.py +++ b/turtlebot3_mapper/turtlebot3_explorer/main.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import rclpy from rclpy.executors import ExternalShutdownException diff --git a/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py b/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py index a1ef30c..65ed72c 100644 --- a/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py +++ b/turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import random from enum import Enum from typing import List diff --git a/turtlebot3_mapper/turtlebot3_mission_client/main.py b/turtlebot3_mapper/turtlebot3_mission_client/main.py index 85acf66..10f7750 100644 --- a/turtlebot3_mapper/turtlebot3_mission_client/main.py +++ b/turtlebot3_mapper/turtlebot3_mission_client/main.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import rclpy import argparse diff --git a/turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py b/turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py index c74b3ff..4e7ba6c 100644 --- a/turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py +++ b/turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py @@ -1,6 +1,19 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import rclpy from rclpy.node import Node -from rclpy.task import Future from rclpy.action import ActionClient from action_msgs.msg import GoalStatus diff --git a/turtlebot3_mapper/turtlebot3_mission_controller/main.py b/turtlebot3_mapper/turtlebot3_mission_controller/main.py index 93ed504..3aebc0e 100644 --- a/turtlebot3_mapper/turtlebot3_mission_controller/main.py +++ b/turtlebot3_mapper/turtlebot3_mission_controller/main.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import rclpy from rclpy.executors import ExternalShutdownException, MultiThreadedExecutor diff --git a/turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py b/turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py index 3032a68..d530ba6 100644 --- a/turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py +++ b/turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import time import threading from functools import partial @@ -151,7 +165,7 @@ def _send_request(self, enable: bool): def _callback_set(self, future): try: - response = future.result() + _ = future.result() except Exception as ex: self.get_logger().warn("Service call failed: %r" % (ex, )) diff --git a/turtlebot3_mapper/turtlebot3_object_detector/main.py b/turtlebot3_mapper/turtlebot3_object_detector/main.py index 457079d..adc50c9 100644 --- a/turtlebot3_mapper/turtlebot3_object_detector/main.py +++ b/turtlebot3_mapper/turtlebot3_object_detector/main.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import rclpy from rclpy.executors import ExternalShutdownException diff --git a/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py b/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py index a274b0f..5051661 100644 --- a/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py +++ b/turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from typing import List import cv2 diff --git a/turtlebot3_mapper/turtlebot3_occupancy_grid/main.py b/turtlebot3_mapper/turtlebot3_occupancy_grid/main.py index bda35e4..13497fc 100644 --- a/turtlebot3_mapper/turtlebot3_occupancy_grid/main.py +++ b/turtlebot3_mapper/turtlebot3_occupancy_grid/main.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import rclpy from rclpy.executors import ExternalShutdownException, MultiThreadedExecutor diff --git a/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py b/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py index b990330..8b6c354 100644 --- a/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py +++ b/turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py @@ -1,11 +1,24 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import threading from enum import Enum -from typing import List, Tuple +from typing import List import numpy as np from rclpy.node import Node -from rclpy.time import Time from rclpy.duration import Duration from rclpy.parameter import Parameter diff --git a/turtlebot3_mapper/utils.py b/turtlebot3_mapper/utils.py index ce8f813..94c2465 100644 --- a/turtlebot3_mapper/utils.py +++ b/turtlebot3_mapper/utils.py @@ -1,3 +1,17 @@ +# Copyright 2022 Luiz Carlos Cosmi Filho and others. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from typing import Tuple import numpy as np @@ -11,11 +25,11 @@ def euler_from_quaternion(quaternion: Quaternion): """ Convert quaternion (w in last place) to euler roll, pitch, yaw. - + Parameters ---------- quaternion: :py:class:`Quarternion ` - Orientation as a quaternion. + Orientation as a quaternion. Returns ------- From 45318918b207b75064b6efb90aea5b00d8c7d6ec Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Sat, 17 Dec 2022 23:03:45 -0300 Subject: [PATCH 09/11] :pencil2: Fix project description and license * Update license in setup.py and package.xml; * Updatat project description in package.xml. Signed-off-by: Luiz Carlos Cosmi Filho --- package.xml | 8 +++----- setup.py | 8 ++++---- 2 files changed, 7 insertions(+), 9 deletions(-) diff --git a/package.xml b/package.xml index 1dd8c26..9a18ebe 100644 --- a/package.xml +++ b/package.xml @@ -3,9 +3,9 @@ turtlebot3_mapper 0.1.0 - Simple implementation of an occupancy map using laser scan + Set of packages developed to explore, map and detect obstacles in an enviromment autonomous-robots - MIT + Apache License 2.0 rclpy nav_msgs @@ -17,9 +17,7 @@ python3-numpy ament_copyright - ament_flake8 - ament_pep257 - python3-pytest + ament_pycodestyle ament_cmake diff --git a/setup.py b/setup.py index 9474787..6478773 100644 --- a/setup.py +++ b/setup.py @@ -24,19 +24,19 @@ install_requires=['setuptools'], zip_safe=True, author=["Luiz Carlos Cosmi Filho"], - author_email=["luiz.cosmi@edu.ufes.br"], + author_email=["luizcarloscosmifilho@gmail.com"], maintainer="Luiz Carlos Cosmi Filho", - maintainer_email="luiz.cosmi@edu.ufes.br", + maintainer_email="luizcarloscosmifilho@gmail.com", keywords=['ROS', 'ROS2', 'mapping', 'perception', 'kinematics'], classifiers=[ 'Intended Audience :: Developers', - 'License :: OSI Approved :: MIT Software License', + 'License :: OSI Approved :: Apache Software License', 'Programming Language :: Python', 'Topic :: Software Development', ], description='Set of packages developed to explore, map and detect obstacles in an \ enviromment', - license='MIT', + license='Apache License, Version 2.0', tests_require=['pytest'], entry_points={ 'console_scripts': [ From 0c3e3afd174468ab6c642c0ec94b6f00425ea324 Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Sun, 18 Dec 2022 11:12:52 -0300 Subject: [PATCH 10/11] :memo: Add initial docs * include rqt_graph * initial README Signed-off-by: Luiz Carlos Cosmi Filho --- README.md | 62 +++++++++++++++++++++++++++++++++++++++++- resource/rosgraph.png | Bin 0 -> 200292 bytes 2 files changed, 61 insertions(+), 1 deletion(-) create mode 100644 resource/rosgraph.png diff --git a/README.md b/README.md index d3dc0af..99de693 100644 --- a/README.md +++ b/README.md @@ -1 +1,61 @@ -# Turtlebot Mapper \ No newline at end of file +# Turtlebot Mapper + +The package's goal is to use the robot [turtlebot3](https://github.com/ROBOTIS-GIT/turtlebot3) with a laser scan in a partially known environment to count the number of obstacles in this environment. The proposed solution aims to be as generic as possible. Given a closed environment, the robot must continue exploring until the number of frontier points (intersection between unknown regions and free regions) reaches a threshold. + +* [turtlebot3_occupancy_grid](turtlebot3_mapper/turtlebot3_occupancy_grid/turtlebot3_occupancy_grid.py): it subscribes to receive messages from the laser sensor and updates the occupancy grid map for each message received. Initially, all points on the occupancy map have probability equal to 50%. As messages are received from the laser sensor, occupied points will have probability above 50% and free points on the map will have probability below 50%. This probabilistic occupancy grid is published at a fixed rate in the `custom_map` topic. + +* [turtlebot3_object_detector](turtlebot3_mapper/turtlebot3_object_detector/turtlebot3_object_detector.py): it subscribes to receive messages from `turtlebot3_occupancy_grid` with the probabilistic occupancy grid. For each message received, the map is segmented into a threshold ensuring that only points with a probability greater than this threshold are 1. Then, [OpenCV's connected components](https://docs.opencv.org/3.4/d3/dc0/group__imgproc__shape.html#ga107a78bf7cd25dec05fb4dfc5c9e765f) approach is used these determine occupied regions. If this region's area is between a minimum and maximum value, then it publish the [BoundingBox2DArray](http://docs.ros.org/en/api/vision_msgs/html/msg/BoundingBox2DArray.html) and an [Image](http://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/Image.html) with everything rendered to visualize the results. + +* [turtlebot3_explorer](turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py): it subscribes to receive messages from the laser sensor and publishes velocity commands. If any obstacle is detected in front of the robot, it then rotates until it finds a free path again. Also has a service that allows to enable or disable this behavior. + +* [turtlebot3_mission_controller](turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py): the main service of this node is an action server responsible for determining when the exploration starts and ends. To do so, it uses the concept of fronteirs (intersection between unknown regions and free regions). Through the objective sent to the action server, where a user can specify the number of remaining fronteir points, it will enable the `turtlebot3_explorer` to explore the enviromment until it reaches the specified numbers of frontiers points in the occupancy grid. + +* [turtlebot3_mission_client](turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py): action client responsible for sending the exploration task to the action server and saving the results to a file. + +Below you can see a graph of the entire system, +![ROS graph](resource/rosgraph.png) + + +## Building package + +If you don't already have a workspace where you want to add this package, then create one: +```bash +mkdir -p ros2_ws/src +cd ros2_ws +``` + +Then, add this repository in `src` folder. Note that you also need to add a repository with custom action that it is used here. +```bash +cd ./src +git clone git@github.com:autonomous-robots/turtlebot3_interfaces.git +git clone git@github.com:autonomous-robots/turtlebot3_mapper.git +cd .. +``` + +Now build all packages: +```bash +colcon build +``` + +### Running +For each terminal you open, remember to run: +```bash +source install/setup.bash +``` + +To run all nodes (with the exception of the `turtlebot3_mission_client`), run the following launch script: +```bash +ros2 launch turtlebot3_mapper turtlebot3_mapper_launch.py +``` + +Then, open a new terminal and make the environment exploration request: +```bash +source install/setup.bash +ros2 run turtlebot3_mapper turtlebot3_mission_client -f 200 +``` + +## References + +* [AtsushiSakai/PythonRobotics](https://github.com/AtsushiSakai/PythonRobotics), python sample codes for robotics algorithms; +* [ROBOTIS-GIT/turtlebot3](https://github.com/ROBOTIS-GIT/turtlebot3), ROS packages for Turtlebot3; +* [ROBOTIS-GIT/turtlebot3_simulations](https://github.com/ROBOTIS-GIT/turtlebot3_simulations), simulations for TurtleBot3; \ No newline at end of file diff --git a/resource/rosgraph.png b/resource/rosgraph.png new file mode 100644 index 0000000000000000000000000000000000000000..2f73ba1a9166cdefc31ab30eb362c91d5901d96b GIT binary patch literal 200292 zcmeFZXIxZSx;>2AwprUO251$zU|7xM7%ETNqE zLxqQDSpg5v>?`ws#ZN@}m!HQU3#?CQ*z)i!eNX;B%WL=24Lm%*^HBaceBLpjx7q2r zPrIAQ^ti*CU)R~!pY>k1djFR6-RpKAo1=L@GU9H~M)6qP?N?)iBs%sNO8li^E|XEU z{h^>ma>xFAexYam(+iAaJ|8>t-~-R)KMWWK!Iz#-PEQYfXX!t`q?bDvPDFhBPZZ z(?;o*M8+Ha!fRa>VH(k~v8O}M>=+K-h&A}XuLK|QRkyy+8p|E+sWqxkG|>?Yf^m+9WN}NO4owva=htWcKGeWnU2Lujn6&O?kNCfTgVuE6~KO zHqK&f%MEd}nk!hW`lsBAg|`)U3eoK@x)-}MTXHJtRPIP$;{kDTahH+K#WSv@_wgB- zfp4kyeGNhv5?)kwlm|0<9c>${0~^guO)H|+<5eCz+a_dcrCCZh6=dU%-_>M=VAXqS zVt3DN*D^D!i7ARwjZU;_|5R~*u|(SH-DaUB}J)Y*Ud>Xt9b6mz# z=g7`Hw_J$h*RQHVYm%-M(Mo*9BC1-PIs@^I;BZH2FTXagDVpch)YO#zZ=4pSuFQsG_BdA`Rw+hwT6S=3rtK+8@^?( zUcI`jG0lox$>BeLH5mB%mRI!3iO41E_wU#wb**lh^86XsG*1B6l$VOz!Fgim3?T68 z`bV*HrS=n+77FIdVQf@!dVO@m8aLOE*a+*J-#Eqzn7b2d(T!R{cDl+!!&;D6peBXfo?S}pcdbbPK~S7n4x18ynN zq%vHsa~yxIUs~_aA_v&DYuA|VXaYAzD^1uccha!SV7Zu4SqYx?aEHHDcy4ZPwHe8n zCtHsjzQ4PiSJLLnu}2$yw>~o4{O1gd8J2v!w|ci`NqlT<>A<&q#m$pA zX@@>P>w>AN>8CUQ7NYw@94|5(5-uGHR|@o7tLM7!si1OMvPoqkLUzqCe&gh<=2lO6 zxvj?^mAonB^T&cd3o$+DxaxiZ66*K(?4gt4%E7u*lPxaHl;>Kis$Q==<)k74Y)&5Y zbTLz$D4PqT4?ZkW+l?xwrW|guR*c5!KY_Codyfm4u8KdV%U&uVq$D;EI~pr zEHLuGyssWhH~FC|imEQ*mn-((Q;g@(AS5L3GS+L(F*`(e=bW51NzO7c@GTP2a;|#D zLjI1Eyv(re?8xX0+I{=0QOWZ!y{;i=J{HQ2y?L-+eAlbvo@GUX!2$WpNM1LDo93hw^|IY>0E@8WM6WnsPo8=fU6&PB{?IN=kOJNZ$`{a z{I=rWyi}{!4-bFd)%%soZGQ;{ecWJ`jZ@=pY`P;O469zBYsVepWO&>Atj?ke^~p?sN$``~@UthZ|y-VV4{ zLE)9QH~;WxlmAmCshz5-ss=G@c0_Db^ltMt3MzW4Eaw{$bU9%mhuWSh8zO*A%*{{H&a0~%VW~3OXo@y(=dKM+O-(JSp8db4 zz&F;{SKRYh=8u3dtO%tz4ZNKv<~B7_G4bR$pRb~DhQL}~$4hsX@dw?zcTZGp!N$94 zv6@~+K~CG3$+NBbsO-V2>gsKi7w1hb63O1{qw8!^CfON)v-)HJdi>*S>F)}I1DDR| z=>=1sZf{3ol;Ri8tmofvd}g~+!1KRW3U;KoK2k(~*7wSLOM049@0&tVlZsH8(W-Mu zfD<&*WqtQvQi#hLYuM;E^2H!-#XnBKbA8VBGcp@XyhZea@FWEplVuKx#$R3vP|!of zF1@>TD&XKgtbNq)G706e7v5}<=X5EHk>igy*`jTnq&+~_J-~3aEt6xJbJxs>sf0ZW zgVuZfWL@n0vxm!?92jo(C=ax@CfoAT(OSJ=K#XuS{gTzQ`PEQCKaSJ699O0bqnNf$ zktUGuv8?>`f#zqp$#8t(Q~$i~&mZO&&^wGdu4(nY%^kY#Umr6(cvJKeNXsf60NLkM`e=e2g6VBEmbP z-CJu&ggYccp}qZcUT1?@d}%OuGB^UgrhU)Si_-TBE{C7;rDZX5rR67!lq>4$o}(4D zJ(BMKSg=+vKq2Hz|B4w4vO^@q@!(_e{rlUb8IwxW{mf}$;0C2&Ik%ydc(*<3+E}NA#L8vFuzU^(Dcz1w|6B*29b0kCGn^qGdI?!mUNOVa z@bK;AiI88v*58!T6gI2(NzqfmPI4e~b_8ar~KCY!t6qNWM5aCRX z7Kc)v4h?!zvvJ0M9x#C_e*Rh3?2DZ_to|%gt)>V0x%*_DM?O|6%LgK|7rbY_{P5ue zk|HcJGO{VG_gSMAUG}!ZX57XwUwn$|)GOCdKcow7m%W?kF zwxXv57xg|IPbHlsBG6tFu+E*+qsP2`vYsCub*M|3DutT(soh5}h=87w=ldpEbS^7r zDCeJ7%JVgE^QvX@?lQR3e`RT`kt~9q^6KoDCaiS z7W!1_6G}nCadDZ!_bVsKM+J)bIbZnuzG(JRH%Z%a?+ZhAz7U7m<$Lib}H>TpU`ak*5+3f=Sz0cgaoN+4$_mDGnX5(_Wx$y?gMjQ0w z&SnQjDMG{M1Fuo29^JjPjB%~HC#Lmp}+UZDu5f4wQBmn)OjWTVLE zI&k>LgzUhNSDxNeSOcBzo}S_hrSlF?l%n^((PK78o{MmE_uLa4pE591b7MlDQz>6+ zSF7WLsv{B2Bq`rr9qkZ(N4h_KD@FA3`@8H>J?^Mw?BT|}2%=MgQsM-(_0zf2P4I(-r2^(WA%B)Oj*~2%{T%px(1bg$N$ZDBh3I zqbh~o>i`Q(W%u;-0JvAg>13(Zwq%#pbf#s;y?L|Giq5gub!zuI^I;u{s?seD6 zvfr~w{rq|JVckaO)LLDaJ;R;l%0LL@dPlme%{*#x3E9(AJs27sL@(xDf3R*JL5tGa zhGV_;PQ#@KDsdX}L(CqQDdAX-xVX4$+B!OcpFVv;vt?8GTzcO$xek|3Hqtqbq^j)a zlE*q&$RCVB<_fB%uauoBnm}(L=fufJ2fyDnZ%W?>>}`TZl4R>I@pDoop)BCU>Pr*D zG_>mP&M(>a_=unEIMDFWSfiEE*Ss5&9nbYOIWc~Ieky2*m=hvizHHAjLb(NgBMY+0 zy(W48m5-0v>`wXeA75VC_Qa-jRGm{UMHfBSpZL#5z*FbZyK0$5owEDTQyEro60eM- z^>kP8H05{qWt^#6dKpGCnm}`=U2%*?l1(eJYUM80*O;b! z`t)gCDra;}PYdD?Wr~6yke*pFF`he~Q(;FPTuXg|wAtv?_Qdz#)yw^;8+e?8XhrHK z(J5r%2iAHYQ zbhXfcJuyf=X^Ya+{&pUJQ-^rDJlBF-K>SdKO0(gfmaX=zPOoA;dyo;ojO-}^i&Dhk!`Qd&?~z9m3+7+tznkLtF5 z{rXSZ%V#`77VV5o@>yJWT8pz8tqlXpDO^#p_Lmz>BYBoaBz1bSvvarJpNUH_Fm2n==F4#_A`#)#-kA zJvAu@xs}1w`wRK0u4{y~>$*p6J4%WaMRKal%}L?I!x%=JjxAvGb0-QVdt#FOWNW?0 zrMg0&4gs2NqwoP<_0zb%AL-@)!Eh?_;`IFb2@#}pH87^+f}Rb$~s?5BK0p~#Ffe}q&9tbMSVn? zBwotDBcz$UgY@L#ygAGEyX4B+O}6`3jkB-Mnq$-MrEd7{)`GA%n8kgjwjO)%u~Tk5 z1JxvaKMHbM7&ss`S%8%+yG<0}WH-SycF>GPvmS`t z>fdzij4pie1jY04hSB~k=61@RrJFQ6PA*+az)>XkFJ;%41xp864FF&*TYjSp1|jbV zD@3vR{+FP{qW6MDWO`mCoc`h(`_u0D()-et1D!WzlOXK8Jy ze?ku#&ONbVhg^r=_K#`x=jBSCpzpT7R%+m*qP~6jhZ_k`TiXX?xt!*oR(UJpA zXQDzd*9!(%D|E3t)(R(30fl#x?hQ~t@S}~-oPP#Jp4^sI%UpM`dyV9GkD^1<8BA*1 zljHr>qofU}P{A;eq4oaQM60JyM>c1yaZk-U%pAWi-B@QHgN2twVK`a%bL41SMx8if z(#sw$w|Z0KJ&R2WnNM(MQZUE-k=)b|QitcvTWUU7adUTkcA~}-m&QW*=|RIA69T0- zxun`?X;+3R`l#sb;QQw#@{9#W*{tPBw*36!FolMZ!8?OChY=uYI|Sh3^(bwzHB%(V zd9)$A$0BF<*g0j{l;%nKiMPvas#Vp+H-OjDi?&@RJMx*p7z*K5W3)3wLA9QuT|>xg zTyRawUn(6_6)fvA_K5%D?)*DTiorgdl@eZa-|5@!wL=Upi(1Z}98Lm_)dbX(fqvoO z)ED>#9b}FE>eXDXi@x)Ce@^qTot+&kR5;bDuOY?vfR!%TAWe?gjDha!*NYL3#;?kx zdSV2MNVg{SGsACABN~fZcd*T;ouEm%x;k_uw6zlWLfxFsICnw0(MaXKv7FS!RI6g| z(HKCXG-iqhh#3$EzE*BMT48SpZuYEge(F5t9XOerU_0H%nBD_qGWkk=>Q&%W(2UEl zzL-3EeT zbTlDiH#+|a+4Es7X(McqkzP}nj}(!*gt3Uh9F4^<2lS`_n`oh%bikpP@1XU?NIGcT zoYel@DlA}CZLQ$sS5~6Ii`)xB-t8=#y@YimSVN!)bwIPjbVexD`Itv9v^bADSI-^t z5-56jpyfFVuTRFyIhA1Xh7fx`kJ6SFjHBLEF;Hlt%@*^?q*v*IxW7M4XEihJvvLD7 zsAecDXS?IUKK?mxS&O0Bp5KB62ovbS%&9du|MK!E!FgR1=nE%kuE?yN4>>?#B&_v+ zHWm7-PA$UE(i^REM%5ze2lB^Q6=S&~_t)(CgsEoC_UOC_7LzWIL7MA}+w7nz3h#7~ zoN+I`N6^Ra=v@19R1%PlFp_Oi(Q&4BJ~pXV#R+4_<)^+Z-XIZEKM5u|R6SmoLPPQI z1byIkU;NHuUX^Zn0HxA04tSrEo_Kn0ZElt+>ODI3-1oQ%fxEXZ&bvMcmzJ>&akjLoYzoS@`%vmP$m^(_J z_PNLwb{_e1T#-Y_q}vK11p!#G_$qmzXd4tP!ylhRGR7Lrp1LMvu{%EZDO0B^U5B0q zmw2h``mR(uxEW*XBww||r=1bcrsz}E@f8>X7K6;=XVn!Bfvd3?&IIP}Sfn?h&^7V$ zzA!!*K*QW7bD+ghpX4jz=pZto6iXe1VF0xo6S*xesngFau4sW^z++U|*Vp>de)k%t!HB?WY8f9^ZKN4--LFkgSV@OG|2RIhS3o$SD@i5(=Iki6DR@ z40zaSsw<-SLjBuI0AZ3CQ9%j#xwh}tGa1`7qxOIOdS11E_VvCVv}i)t0ZwfH$$l7> z1+c%)lRsf$VUeL|HVk+|h(m8O!7;kCNxhjIr*g;1{7Df7wJcDCv0^BY=_-iIRLbCT z7(ZEO58k?3{HFr3Z1j>PM{y;k=GcbYT&`N*>NkxFHe+xP2J z2@eelT9Jk!b~mAQqK8o+y$BI7iAvlkN7nFUkQmu4f;h}`JV!-T-j0pO4Ab0Q~;m`{*F)dBr zr%&9^2G>C-McNhQP}nfHmCE*9Gu{iij?eMy4R$Gmefs`r9O!R0reZD9_`f%SNEz~H zu(y+VOd2HPGoj`PM~R3H-LHH0?31K2sog}{0Zz(YQ)?jsDnbVHQO3mg`&zPeu~c@i zGKLBj?m+%Bkx^y2$+k7Mn=nmHZnyob|viC@_~Z?(^7};d=b<3uo>im<1R0 zlRyVeW0_HGniQ8i)$PhOKb7!P|l;BZCBie&njiSPt^AuGOyCgoq=p4-e1;j&HI%-_`z0Z}z{24flzB zez41;dfchnVRbMivj=B{9zWj_u+!HGJ6w8z5x@kSNTK~t3orlr_RnIi3mdK#?@1#q zU71G6I?3S@v10Az2}!s;66HJe*x%QRQK#A6dM9@M%L_2lQ!Dax`{_>vzuEW@`@sKx z-)CE=CO4qN=K@E!^Mo6CqLmrfO4m0xCtu#GJw(8H$%gCXhv%4Nh)G zRW&soh$}-RK+3Y{%T_L6)@&I`+?Dq{=4fD? z%0-*+u;PwcCE+lHoJec7*OD9dEypuRY-)e2n{v6}9#IUkT$}m1gZ!N&;^wV>lU9mH zsWVkwMgda&ELLU$;<-6ZR1rwU& z4afgoPx8&>2*-nWvoV=Zg3Adif&0VyncZ5wS znyc@Zvl6!0tGl_m@!{YEyMj_vrwPCY@ss}BV3~d?P4DK6bLAb5I1FN30oH{w(5YUi zks^R`%CrD9tBh}VHi+8y)}2>V^UhHCns55{=G;j-cbwaSt1kLqL4$-Eq0))+6!+Ud z4}V?a7!Ga-f$$^g2Gj`;>c^Ky@8goDMv72IMX!E;AK=_gp7jn}h&`4C_f~`Nai26SXcEq&U~#1)(yVXTOx zgnXPIHroYClGzYg)1T@VavW5_I_PIpqn!K6}f@IV3`e6($Tvc_cS`7b)(JQ`{i?!O)4UeQWrnJ1+G zgxP|f77TK{OhiivSsj1@O6VKB(Q`kU;CU0IF^r#ebVUT0fg(}tG&M7`9jiC$ytzpD zOe_O~C3kv2mrr|?SrZZO27&dDs z1&9eqNwWRfPfZ(&FW3!loZ2f=^P(~)GJ}p1->~10sb^dUDqjW#1@!mPY1e*h*7}RV>^GL zLRbyQV7GYnjM{o=1#Ayijl}kF+Fxy95vadnQt9qHA;l%f>h%A1O&EgUBumR1b?49H zU`sJH``>0n;A8-4ssHD82y!;v`HMU>Hj=&Pm;Q4xd17G)7|S8*6*OyKIX7orx6$fT z;Hju+b($s7Xaa-`Mk#v;$HN$3zO0dgb zx(fSj+CFZyE!hWZd*_kS8D~zY#DWf8NHJCYNvFOWA`ga1<+8xwL{?AYB$jJvj3)Ws zgnX5=XWs-zdvJ_Esrv#?!eBxg0Mw0C=hN}JIiffVgoc-^u5*7Jm-hoc;%NVyk!0V$ zY&b0#m{cYlZ2cu|4Qt}{7~SHaQs;z7P>Cr z$PGX(hxzVhuTU2hY92sEo*tC}9lm|*50DthetB8OU#T(I%rTFFq3_e(=pNg9wTCB)eMwIXGI+okqs zrNS;#1V+Szj*xnUbTX5Vo^i*JL&%mjLKhyZMyvHz zX`;FkuNjWzqnqO#2J2a)1%9S5GVeJiV?s+1V+^WQl6ifiT4TrWY?PKHG45?OHMMXs zT0f0y%lMjv2IQc=5Y`I92;;vR!}2X~XBz3&mrT@|#3fbNEIU=Q=(Yli(^=;mZ_zL-OzB`Kc=ujB1jm~{qO0$V?2Kx4 zeG~G!ZY=^l7?+kdznp12Z@82kxZVBM93^-(yV_@I(a&5gUb_fP>^3BpBJSDmc5{|p zkKu8L8Fy{$0#jzgOL#t2&bSxnvB&Jy8AItQwlL>?M4s52IgIZqTy*=LFjJUr7Yz{$ z1Ef~3D?O)m4-2r#e7PeN^A0%R4DOE^2fm)8_;1`J&vl9Dke5xXXMBu@Cogq=!Hf#Y z!}Hk?jb`S@{@;)OwI2U(CI0_e301Ewp6jw-P~VXZ(4yZ|rOLH9n^%UPCMpYzj#_MU z3v-8#-hOA~GrU8@&GhDid5z|VMuu(L`5mj!%AP2Me14fCkxTDTJAWQCk|+>fse7tK zYHYBJSy_#3bW{`pk;rNU=B zKySbvAytf)3vO;4i9frg7sfGr?Qk*e(~cK|8+9GswJuHR1OmA|g;$a|v`ZUm^tJfZ zRh`miA_JE8pJ!w?Uc^l$fp&y*G_H!26SR!9`Qgk{j&4SC`Yluq4BGAgq&GG=xwvGx zF)38#+SkBZJ;FWGVrhH&FVfpD;8ZwCh@*SA4`1g%uS=a@k+vp);cLxF?EncLk(=x8qZ|GPGT^gT z^}BG?sT^|e$z!*yi;s$GV3yBNpz`b&6da)u>j8{aW#|@!;Zva+eW;1kX%zaHi{$}| z?W=UwT4axD?P_pejW*U72X&h|m3PCy_5xM?=17)Jb~`;%D|cgPNXVsNIdzEQn(W2~ zKs92CCxKLR!NMYzDm|l+j|H5OnHLAE8XkaU#Oz+_g{if*wan@U%|)vH51StVYE|aC zxolSadL%j|Bm^L%BQ`I=To zL8P(C>Vu?cwJ#Na%}L$rg0Rd)5DHySPvR&AN~O$CR998)^UCC@qyFuh(7e?F@uBg1 z`>w`rE2nIHHb+ehwZ9VBZ4ERC%h*R&^~9Y4>8#dt#%`ki z2haYT*iCk6Ems|m&l>mhTYuv)&sY?J5IB;@x5-Vnd(ra(r>3Tw;|Rwly|~<}$2CGJ zkjl3IqQelQr)~&~%eF%)qG$ zvI>LqNTU^kU4&r6cefX5B^TUZ>odC_vDeZ*D(%p(y)Y(a&E-bt7;w+;%z3PTBmQ*a zwS<_LIwcwyTWH_eE`_H@OfVqU_qy{H_d_cfG3|a|GGtsMhd`S*khM8 z%jR3}2o8W-Xw_pqn6IGeCzmq3P<`m<%*d009i?$`DL;mMUI<)ECEI?JE+@Cf<#!q1 z#D6qpg3HbES5Q!xf2(D|t)(F+JfeU9eRf5!qsaW1J6_zKy0P0aQvGoJ?1d7CLbdm6UWe$Q_3n(Y%f9;ucEXfz^4Dgi{lh&w_Z|R&7 z1?imS_vjjTF74R9{n**FXMHUZHKjG5`sL*03=^6wJIr^hMm=+Nb+vrkj09-nTb%zH z_PxZ#rP7VinV!YkPO(_gDq$ymEm!Y4|2Q~UPmaMm;{-qda(%<^tEgLxii$dRG0Xbi z|FzPa^ZxyNq4IC-?O_X7?|O}?YnOVQc6i7*!Pc5PftXI8R8q2ERG!r@O>NZ4b)CG^ zxeEXup9(Os&i&)B6>Rqz!SMGvht`HTdgO;-66=9CzoTQlvpn>MCFN(qlB!0X-&vV= zKEtNHt-alDQ9mK*>g`6mRRd+5Dn#p_^!#!H$*AJ&?Cjk+Fg%>Z?q9TIiRy(5&*AI{ zLDAg3ckjTO<{75YzfWpiJ7sq3`;z?62%tT09XjpXK0XmrcOD-aQkfiTFMVC$-UJ+qp45q*7mx2~ zymkX$4~y|I7r%wtUZc-_@#1&Ifo8i!3l?M)kTdbfD4srD4HB(HwOuD|rJ&NsZ`SFX zT3cIRA+`NCPyV`O{SFx!?XZ(xyRJ+BeLFM$Yw6o4xQaUX{b*lHPUDK}j5MoYEKSqY zufP84cj*PLu{!eH@k^I3?LrQiOK8n{K#T?-Hz1CQRck4qjPazKD^?Y}mTved-eRj( zobff9>(Jof&g)HS#Q(J?(r zEp}H{v-|zyB-&O5q^BS3t4}Hv{i_P}*lK=$W(``XI=oq`n1`xg9$l1TUatb*#uFbO z^;r*QZUp&xzv(+C`R_R#+(>#EIcur^0W-iE>}w0wlBZIsm>4xw&sZ9VJ3%mMS~={`PTFDM8;cvS%< zzXq9;VpzIfC*AsOg=JFxDn7orREtIgxSA<|-n)12E@Z60Z+)CYRwc(J4gVOfN9Cwu zcUl!1#~wFx34g!+CNF{ZUSk|JZO%+#v)K!cvE%UHzYc{DZC}N|c5Q^$ZgpS)RalKu z9&MDoY%)GNstU|gm1?0SHotr!xy8KLOY80|-FWZ?&Q;wc8n>O<*%^VgA?N6>2)mEV z7W6MwJG6BMkN@`>Ph~7CD186k7>uT7w&NRk2qQy71(Npc*l_{`uIQ10)BX|$)r9c) zDq%C!Mo~OLHa~ff;hG`=0dQy^&1B=vS5lnrdud9EFMOg@>02?dj7|NQphrs;khQOIfFsm1{vCiQ9IZDt*51$dNmX zcYb}+qSNBevf#iFUj>T*;gH)>wPh#pIkGrgwr))^D(6Gkh^Tj7J-G2Cg;JENU-nRNg*{Z#k4xnF0ctTz6L!x?#B;f zubtwmQ6NyZH4JO$4QKcO%C}v`6%8+*;r=F^ev~IILm}tkw!Xz6MuhGeI zRt4NdXu$-(lCtX#-E#C^6K(k%4JY6@5J!A( zZG|g!e~L-vF}N3metc_Rl)twsUQd3{g@io)#%5#SQ(WVd3}$wDYoTW}BFJ)7(r$9d zfIKR+s|tvh5qWue{u>5#-ih-#p_bjgb!*jEV;O%Lr$l(N>?kV8^idFPof8`|TSVz( zrEXi?U6k!KT!pCcv;Yb68I*5|U5{E?Dl84%N#%0q0O(6Ip}PNwO>3z@Ep49i+$61r z%_r*cy4X4j`id<+66`wk7kJ}K(^FH_YC`}iJ?o)H(k;&`D3?G0s?tjC9u=5#v zl}sXS4{r1mHMlp;BQ5gGuy`t5o@DR z+FWwG7Ms?@L}Go?tKrMhz^0hb;J2eN`W0EGnZbk-rIBQqTDF^lI#mUwxr76QLNtaN zOAd`j+wVMLeA-vEKt&HsEm<|3tY}R9Mz-PK`Ooh@aaewO;uY*Um#4GHRy|qRYq~2V zJa7K_=OV|@e}CdUJQIsP%B-?lcL%)uywlJ39tNa+c1>2O7RJTVzD9Mhf865O_YWJj zPMvyi^4X3{{Z{pfNB{hFi3%F10IBw5^XThu?f#J792a*07V2SNs_^yY?eeu}Tt~aB z?Is2;Q7SM?R)tblQfR@!!AKulyJ>(>6BwRpp}B4>Q{qG1+btbzc4F$2*Y1T27w*dY z;@GkN9>1(}@-&A@#pA|v*rgV8A$7`mN{|StzIU>9SkPjXkuc717!v!e5KBE;?KDEQ zH0iJTc$^`ys>=JO(jmJ~K}l-rhKnm2(W8gCsCcAq#kP|_P&GQ-(cvLdZRWs1<;ypW z+%dzxOYh8Ew|+sgT$s0vuVf@0xYrnub!cda7P>KByKidJqB&EQ-)-ax_6aja^={niri; z2iqBc_SLaSs2Ou*6#nxOH5I7z@tOgvD$8?1G229;>|#=l&`dRtgc_vXSr%9crd|(C z^RGiPmeQyyV#R3m2sB^BOo3XgFsp$ZS4W;R^0fURATLbpRV(f?8&aYnfT+qs3o_Jc|Kzo& zkW>=<139WopEzjc`j`!pHlb*BS0wx41Mu1Q8v~KMWRui+%yVKr$b*;A^)x>8bq(8C z#z9Ee_eS!E<6$~3ey>=oZdv}Qs_MKfbbrfHlyd86l%R1T<{3{uS!_S}O_2c_`UkYI z`b>$(j8EQsqSbZZdgMp^%M0Lil(^|pX!g5KSWiw(bt4K?&<@C7;ed*J;qjj!^m^8_ zZTlRj*-oQO24nF%+=K=;UMBw1e!a08n+Gp?yNvt@85y~zm@X+PS>H51HYPDA$;8Cu zABt%aTc0oRE=LiT2_CPn3y88Xr?Af!=W42R`*KJ;0x&BT_TiX@e6g3Jd zX!vcR@y=)7-r=~RT~bn-K>z39e>e}a-LtlA;*_v<`U{jV6O>tiVgG(imD>abiw%>C z0PJk~5gVwzC87%sU%vd(zP~B5uI>WRa%ZDyqJ5SQS}5A4L}AcbZS4TSo0r%Lz2o4) z3z(kOjE!Gsyi3mimXLkm=>0X~<9+s7u5ND4WxfFcF}Rj)NHq%=FFudO6V)-15f@hl zt{55~etK!0l+#csA=H4;BLQGFa+Q@}->SVaXWla`)aTD<0EG)%7uI7^+_&$nySsa0 zW8XbbPx67}OZmSd4Z7-$f=j<#Sq`!9K60oj=*FdWCr_RfW#kb2TKDFNkBFX{*Dlqn z7l-E*PhfZq1qo90&H6O}LcO!vQja6j_Pw7W#+?s4xw;xXurT^&XAO>@*gOtb-o9c` z@m1pts@0^lwCh9yHjjqE)uBjhmvw`XJrYmlD87CB*032)-;&3pkX1vVwI8z2YIK#L zC31Ds<9HYuwnm@{PGJ%6T>1f7um){<8wLIGoR6?hNiM^k6$`e*xSxw1Zr+S}!R}L$ z2>Vb-L;iNSK7@Q{W&p`bteZhf2za$lg;tNw4f2u{loV4e3%5%RUB`oX8zgZhY$n2Pg;DADU zkfP%1nhm7);^W5?Vd3GZPa1yMxB94Xc3TAI6EwD?sIZmToe{J1T(~j3LfBcF3Zp{^ zdPGYi)A&DYBm3w&E**es9Rfx|fEWD9epEPzIqByF1O(PWNyQIo56b0OB|=82WHvtN z&Q8yuBFWcdt4O>S9Sv>+P{ZC#yPl3g8JHFK5+|fYIJih(Hw-{+_S)!n59GP*%D!}@ zg+3JeJD#4Ng+1t&Z}%?F{{h9>dweY~ugSVQmqH^VHUI+VE?>2(t;Ptt_c0X}TKg21 zS)x%Z#nj;1kI!%W(y8oLe!~n@@nhE331PAV0`Di_A$UNJKJw#>W#Iv}_c z_!7PLSz6ffKE=CML^t^X?q-Q0A#)x8z@=|GU{tm-|C_aAHWN`%WDM%OaUUAS2b7<$ zHH=9)*2Kg*lnXm)Qd89*1!WDp&YCsr*vXUkG#H5G;Q%;Ru4XA=xV!o_Z&oYO+<{!0 z8-SuHTO}kUDvd@VzHcB~BR8JI772YY0+#v#2(5Y};@!xUk0|yL(TelZnYVP~Ue7o6 z<{tp)tsEcZf7^@Q6w><8OZgfrD=HoUG7o2i%CU5_8PXNlzFjkSw|dNlOD53ua_T!; zTlK+|7MQzWcXnwi+5X=75W!wl?}Juhr!muCHZ?Fbd>u0yOGUD8-l2~Ltl3* zaDjCdl}#=!U*q$44*T3m-ur?n!qqTv1B1*Waog%wrxkziiam84@#;} zJi2@L8xWSxznG;<@V^g4&H9Ox_tR^ zjOX4beT4fYj!`hFKFP4jeA<&ViJMQRa@`eKu!>Zrn5ko2+kJfe@dkjRO6&y(F&rku ziq%N^Amq?haTIrd4#jJ%zd0JFBWIZphDl`lC5JAw7ZDL5GhLJN$&-o6og+DQbSiyP zhxfPNUI0zh+MI&pw6q87??+vRK2GMcdM37fcx+tiks;-VtSTJjKWLpNd@LuhFC^wOl2X0(0H+owBmcebUXNSzD8spB}*8q3`W7+8suiN*0F43UrD6SHJ(E z8mBF()oJS$6cmRy5qxNh*GLLSZ4m3DTQo`}HD%hFtrpR3sz9T0NXiEDl~%qfy?KJg zGDD$ic%$#ppV7%jhCZzJSsNRh!^{2)Kj^T41uyR?Ot+w?jDg#oVa{x8Z9Vt7b+%0# zUO2M180Lk?*eG`vyGPx;<#2r}C=|F3G+jYi*!KC#SA#df_M;y#m}G&siATIYw~+8Z zjcQjzCM8%9pO2zw*1SIZ%JN_tOn;|Pj#7TPh%RpBT^p-KX889_)UP+@2~fa|oCBA$ zr*plueT>$R3MVSElTMt37A@KJD}KSi5{9ixQK;*FcIZ@9aKrnyr}tDvz9QE^9t3Q< zas;HrmSgAEfhD}6??t!QCb+_9D}L?A887gUv{hhYh_}Y6+5g*ma}JEVWXQCo!wy0V zMJPYNRE1zTNyC}C?S(sSEh<9)f+cz_rB+bHdWk8LoU>l^%3W---Ivr4n~-;TEd?l}MGaDms;#19x&1{1F=R*yg+8*WXYrU&9}+3pqy( zqfAn-|7t5Mrcfh6jA-MTx7`BKZ(rfvKE5pI5#n>c_~Jzlf9X1Yn+uAnGzLcDPMeMW z<&gveMX4%o-n@C?qD7Uc-?B=#5)ctduKi7t;^uW{Zrr%>6DR`lf`QOz$?v`U;6d`K z^s^vYlLGw5zhlZabOQuXeSKzg@o08VPBoB_ErZuo-lpyDw&$`=Lsy)foFXyflOg@y zT9G&md>M1AbUd#v$;`5ebuzPB!goGNI&VyjNyveuhvHntz{1w{FFRwg6U50^>j6_8u zR7_}3w1!dY`lL$i+=uwVW!yi=lo(5Zb}ZRZqTlW}484*+FN{M-~TfT8%wxn%fM=F$Chxgk{!F6L2DW2If0urMHUy@j&)TY2W9fO*-{u4Ec7P3neLT3)Utx=GUJ4>;s&G3TUQ>r$CJZ=Sye0bj*&yKhJ%S`|^=KEnea zjjaNscWO_bII))-hv(}rE$^_?fmr~Kwp3qR{e{Eo6)P@#2R;=`Z}AtvK1L&N&cuY{ zLw11jnNh8!Yqf*F7H>Q(6w@NOw(yWGUrIoL0JJW3_( z-nKKsl=z%6ze1KZq0Dw~-h7yL9%e*Lf0K6#uhar>h+lp`-(_@&;JYsb=8_R;gDy{kQu)2Y5#?ouQ$*GTPzR>4R5Z@s^1*~ zLX;^(8c8MwG44 zp51=9faX>wQKc1+zu*-R`V0EKcd4GloV|CP;lh+H{!|$kT>|(dsx@wtq#aB|OM`WH zGMEt3u*)Y3qg%Zk12RakExVZhEawacXV>uY?K;$29s1K$D@GjXz~-iS1cMWkY!k$r zmcZf)P{3oZmvKyJcLmpKn1PqIc&8>O?@v3FEdUeX5x&9>Q*g(I89=;4V`I7B_SJ*y z$KF~E4B3jbUFToFz{uG=kly6JG%xTab_I7Z!iTxy{|P>?`#(7lx%UN+8yFzNNtmh= zemP?M5+eeR@whM*FO=xPj><2@8z^)9+O=d1^F3;Mv6|v(nV2m7+cC6Zkkt#6va3J_ z?e22^OhA`2l4CTD&N)pi`CoE2$vRgFk@;oCCocg#Jw3pvqX10a*WBis*IrK)xPAL} zBn+Gyx)Hc)OS`ylJrBzB%gf7!qy^`Ew8E>LuJeA{u;2J`i`%#kNdDu?kBUS|F|oi~>YuC;w!J{-t_cacaBIL0wY?0Hv> zP}+p{M?fzrt)V>(Gt8bz5YeJQ1oxoCdk<$SV@d~SfDgmo_^h9c3as`{z)uOC}3sT z@8-vF1J2<1t=8T3X-iGadfIc3u2iNPAI43iIiZw{Vw0NhC{S=U;q8ISU*pLV5N1$4 z9FuLq+QnxnegB+fqzoRms0n53zJ@!h|0woX`m&JL)#SSS4^L5_ z?g)@^QUTGmzh~Z(^`StJ!1p?Ypu+xbgH*zw6kXfq(s>~ep=e z7@A%;-Xqb`aSintUD`L;$x?paSEZ{kj_%P&{DaoUrv4Y){?)J!Yp8>cXolCBX@a~v z>^bk_69^GMfVex{QDAM{g!%dTJx6gt)nJKAIe0hIIRco$IVZzHZ64TYH`=-ZVCJ6O z^n||W+fr<%dQIYOp|w$`AK;TvVL?GgiqY69n=OLlL3%)iDOZYCJmeMoU{Np#-VZ#| z3G&Xsu}SSSC{rVpkry2P)j=uz|Gz>KR(Vz;!Lc?CE zUC0N1+%lWN1$W$V8c)? zM%!d}jTu86TB>wb-`!L66HAmS02de%b3YAqu{6*Mc_jGE8cJ zOBICDSTveqsqPy)n>jVzQX*Cs31Ta$x3AB_o4|E%v0uN-R%gYnv0QhDNHhf3$GG6# zGozqfon+K48APu3w_}Yn3C4pwUXlrl{^%cnq&J^~n*^*2@A>il;U)d0U0^-cplXux z4esSNhK-@o(UendUl-S8#RauM)JUVuBC`p;!y;ymIza6gwLLlo$S#YGZhWlvW9ZV4 zJh6|#8zskNaw8b(t{N-wPaQ6X5ct=u@n+qao%R_sGZC828dEKB7O!^c|B_$0#pD9v1k%#+1&m)b$|`nF?G2Xs_? z&Vu`?5nq{p4!gt?7|1yJz|Rmpqy}C=r7F;V0$lm>l_L5h0^)v)-^1% z(WKTi9&hRDwrJJpaCrV0C7-R#K!TjZE5WY8W~7({%L@u%2Gcbzj#-MH(WC$})Ly(e z*lo;LYeJO$d*_Q>DMHPHhm@>2)ymxA+f2rZG1xyLpDE6uE z1ie)O=AtweR6~b}@dUQx_(9_WuVNT^VDS<7)M^0~OQmWZLNM$9&j^qvqM7{Bh7cSj z9Pl0RTH-y0W_X>Cp%yeYxX88??;7E4AIpJD4UH$TM2_Ee;KrmjYzTO{=fzY42%rax zj)U+r@GgA7s~>koSSR>(z8#H5XqR?Sji%_6-b`f*2Czg|56p;#i$B-E1r(zPxQI<& z`jTV7-YKpTS<|Ibfs(c#hIFK0gh-P+@CvkuCRkU<*37GBE!i3M4xl(S5oFLYf2Wv& zJeiCGudi`hT24+EGlb|kxYeMD)?bGzkUIOpa;QeC90g~52hx=jAc@w&2v zxQSH;+#+NEr2=gs1|v`;sxF!Jx8?bI5#n_B5r^(73PxWaWD#C&95~P6(kSBg2k4?2 z(jc%_ukk@LPhtX!1Yi08vG*o^J?Cxve>27m!{9O)YZzrMTMUU943eEB6=N$zQPM7B zW*8)V@M%-FtdSwKsf;LmS|~KBgf?l@Mp}Q*v$?PPcbU2F|KRI!UypmJKE0RM>wKN( zaUREUdN;7!d@fZ=j3LE7q>%`=LY`tob5Ag5IW;U|M9HmEEA_XgGcnGs_8QUev~^+PYJ} z|319s=byhJ$9;%oN8^6ZXJ6=!rspBgPf-=q)G!w(M0bBa}srV7RIcnMORk-0B5g|U-bLMozG!st0Gs1 zW>lkFUQ4a52*mnyrXUqG1v$9vpmlZGia^9VMHK6yX72o>Pq6FrvvYf6k!7l| zZCWOZHXJNhG7e$AKCXb~L&?+3Q9uyPGp+}yz7rf9&iJBKp~apN5&b4yN23gMb_nKJ3-cQR8EhP%_n6)4 zMfb+)JNCa8W^OXi$}$4ok9SV%d@b#w$tsf-&(;xBEPlVS==_3OG`^Bi87d^w1&^c; z=plHsABxZwE9sW`@m&?w4Sj$?;~YECI89yM*H1&5csZ8BZk* z1E?&uK+fae;o*1QWb00s%9$1gcKSbO-YX8NTFq7$F#fbPIKOZ;!(+s?bN^lN%BNbF z&B9Yw9Rt3lWXm=y$y$dml!U7fV+tZJ+!O>cp>@}z*#^N^YkNq)t=qk%5*NC$di%PL zm|S+V(o@5yDK3&s!CPRx^Fx+iI~V;SzlVMCpYs(`kOH9HNjXct>^pYz$_9k^L!xk*Pj8>;sQ&stWJoCZO*9pk3mXV_FWxA3Z10f{l4A#j4fPo=590CMw} zj=%hu1lccL#|msrwv6B^5T2$aPk4V+GGAPIUjuE-qkAJfK{t#qIgy`T>Zx;_#yy>~ z2bsxQooraBAcj`(AOv1NeF>hp@<|>9nf&seKkVuBi1Mczo09PB6F%e~QZ^(kb_k|^ zH}$u2yomTh5lE|X$?c$EiTNA>5V2xcMV>9s*zldSPoUORJ0?(7UAN7f$+mLrX=Ra| zOG9FWinOls&v>VXi=X=YWEJfT3rMv;ZJoC1npFcrPzcPw&PtX;L^==)Ca!(hhYOy` zBDwNdZ-7p#cI}>mMV)~vB+QDEo8N!`y|fgFuW^enHV zX}NBl^(@DYa6X?5=ZZAco}#>*uzyv;CDM6EGoMKEvccFnorw?M)_;zVn=)9sK&p^K zfn?!U(zgv-8#$-z!L0lJMml3ip|i2gmtUp`63#vjVr5!G%P{A_OCc4^n*68c%)u%A1D`;_}D1Ia?xlc#f{mH%04b}53bDp_~DelTV> zPOl5qIvBN1u^?7;*&?y#? zyI0d3SVs&Mt|B0MKQe}C*e&$w(EcB5al5OfPTSaf)&(psiO1B{Colm1F?fARQBe?y z*}wU%w7>H5@{ZX2{CSsQ%PtDlBSL-XL})6-?`9P^-qRthN?-1Xx3{G5ODF&7B;-;s z0b`Ij$QB&8Mx10YVhd`I0u%}|Krci#(Ro@GgO}ZORQIfX=O79IxXObf`K&Jy3DBLW$XnVn51!)) z<4L^<6@0`=lE*?C5dveqNxSSGdnCqYF}b`@c0dk?aIr`x=F#cZJ~U&sCVyqlgfST? zTkI6YWcK6ixBGJQqh=TyrgDgH0lg89?7r@!AG~YmrSH0g1)$i!f9{Rw_Jp{Tl%D3W zBZX>2f zTW={ef&ZTat5QO6imIY=KSzSva_r21yic|ImZ$Rvb}Ac;fJBgf@>%>+zSPvz^x4RQ zolg)H-u3m38H2Wj@ zv$;;obzDIN0)x{iZO#L#gs%Sd+kalht)Cy84GZbsv7_L#=Q%xuokWHLwQMlztflA` zo&t;smB1j)SV5Qmd^d#+g()=8%HpAK(^9XjntnPkkRGkn=Pf7n%=`rs%q*EsvDF=F zwIqGeGm_%xXJtu=2mxVsyIuV<;_>+DCue8H=0%HxzrK{KT+vk^J=j!-OIGdaH0UIK z0#oX}n8KnKw@U5|Z(EWblihL0ep2tMa#DB-Sle9@eDknf1lU|-jN-e8TpZPWtS z#dD61Jpl&0mbfVVcByot&Ly6KcjNuZ2R6b5RtRA3gQ62^VTpO)ZSZQp+}ynz<>E|A z=km>=6+ZM4qH3vlH4GRpu?J#ARL^5M5cVz*4m|f45fI1`y>fEYUTp2yqel=6OVZVt z#@ZmrQRkpa8}{ZvqcJ)iBy=9DP!a_ap3V<{`)2~beb(uG!-3C_z%cup_#o2Zvgt(r zP`l54`SPXm5{KUh-SKKIwKzJ<%gc4gS>RUSi@lcqzSpH=pcYDJNOxQuVTqmoVbr${ zocjx*yb1k65_}SEUH$2>;&|waoE!-opf>q6W7P(>g1#k*I_2gXRoIs|HCnc8d7h#} zkO?7$a>tdX%r5%-ABP?F?eDtCV*uBYE)&d4KU6SVYOB`mcOy$J?sB;OS6>~;vW~fX z>hlA=gV~83W@{p2LPJA^+gH>%zc0zOnEpcBNZ0SLr8SFi@?q?S`pxWUf1KGe8d|hy zVFdZawdcRoa-Xxtnpr3{Zj|Ec1H1;&Yv7ZDTl?XjZ$0?%1(4T|7mbij;S2US%V)aNCiR#ICU zk^f7H^*_~G=-Z+E=D$Q%vN@3ti#-9SW`5bDzi4~T7F?<@Zp;fK#M}8h~^3*9CN6+KO zkI!mRdGR|=?oBR)-3zAo=oxHdy`MgN*3zjR*=FUK)ukvOT8#P zeE4u6EikCF&oa&4&-EX7nuiL`_WZ4xV5M7Loq}&rUiV)B#e44jMglOYx+30anz^xG za?+}I<>m9qZgsv&6kVL?I`~^&PL5rhQY7Oq-u>8hr*ta2Y<=I!mCC{PMp9u}*|9Y* zqG*QD>6`a|OB#m+1_pWuCE{VyKednX*2P1PXb>7%DUNLu^qL?N7#z_uS-_1R%Cb%_ z(EALXlmDGNQ_XKW&X)!KU4gqbpU{>fju9d=OaG^UxntE^NN=piq1=m$NVPJ&Ku zKzU5S8zA)%w{7n3O|yP34VHa+=+l4x7Bz?Vlgk}W(o`j_oI`4)KBbC;{|TpZrg7Uy-7n^TsWwSpG(#+( zL~V+@tH;v25Szoo!g?;h%=w`_;1YM=e&mhLxM&~$FN(kI7d!0P#aTpwv-HeQPIK+4 zE5oA$;6_k*g>*ii9L7&BTDEMNljD1WR{*+;kj^XLFFNM!?OjwT+xq0LuI*d5 zK6v@Ejr#MC9a{g|SsnIFS0`ty?0QF)H1is&*6{OI-wawXl^Xz+dvNWjkzYu0K|%cB z>uTG_3-OFZSma336(sg2*v2&^JV??eflAAHTV0)KtMIwl|77b{tzKkL|69zEzqZ^r zZ~T{w>9?|keS@CZU}}`NX>7&no;>>WFOyvcfARU}gZuQE1hIGVq)FSs2cVuE8j$m; zTIRUF$lRQ@`N{(ae%$#uq{m8!()jrJg7iOOq1bh@aLDqm`KLln?N%?(dE-mXI8)is z)g?+ ztu5|(2#MIudXv>5=~`c(cl0&W)U%hAk)p0*gV}$%*G;<^L^307iZWpFr_u9|HxlpE zW0g+Vceq*bYbJbN2#X=Fpup04%(LVXIq_NTYOtp9QmFY^Dj=Zgwo$nA6HBpou^ zJK+f%xXV2^%GTVmOUfX!Ug8l9NONmdlw)1c_SjiMglU}HT+=yqtGmoe9(-$AhlzbD zytRI+_W1gj%vo;i;k=R(H&xj`g%4_K2Q-;g<{yWy_1Ap=x-nl~wXn3$PpHidF5c?m z8C%UuhT@=vr^_eOkBT^|w0YN)Xu$u$xw`6fL3L3-rmp+W73qX}Q*(>z(36(|x>+yb zq$MVeE;@NP$Hwow{U+ekx1mFX8aE*B-iC>h@s3|!g$De&myiE{*hW^)$N%*2zh(Z@An4y;vNpxN2u*I&{wTfumkXaY zO>ERRSUr3|exEaaW>|TgT(ra1Fme64#X)wh1G+W&i7|M4u;IxV$s$poyLppk8-a9l_d zoZ1h3hN?3(kE30cx*{|qWCIO6MeeItioBPMmEG9ea+jZ(Zy~!f)P+HqdgnL4{nVh|d32h0FTdij3!U-U*~%E*54Y3j|4;Hs z(O^5!#o4(zl9$K^a_`3B0Kv4~W>aU~3ENa%{qm~%Y>U)e{Y}i8&S^&m&cD5`crias zEBaqCf7@}LmYrvVh6QnU6oT~Z*}Hck^)?EOk+VJT4PN(Z>;1u3o~5RyUj2F*pxDvU z172RWH%lJ}WDWhPu=S^*S2J7}PhY?O0!3l3t#h_4_VTNR=|HMu(s9*DC58_+s^sj% z#6-pFgC-TOakh}U$yQE{T=U=@*k(ml)lF?HIYUZE#SYgh&mgC{>hWZx%i8pkS73!5 zWPI!_&H=$c(!#W(v?pwf>@~t{&Z|(<-7l>@vu%5Xu6e3dkICv8dfLmzvR>);XQD}c zK6W6cPyep-C)jlQmN#x;J9Tk9iMqByr>&6<%7UTuPfk7K{u=afv(AXyCOf8D6a)kW z*lyl@f0yy+p{Cqi?9hWgnh!0<$AD!kTkFZHxp@P|u5aruQhNXpYZoMWQq5h7?aRGb z2O)a}OtkEFIm`79$(LdMVuYl#4joR-3H7*QGUwIUSD}&e)M%zC*Bw=w%yOW^#DdUG z-8CFVVs^zdxi{OxgN^pQ|64Sk^o~%wsV=bWQ%7j(pbbx7j-{zCoSXhLa_!?|s8zi6 zLI6pFK!0?f?bC}27IT$P##!&p&CQ+l_0W++254w_x1Ium8UZmTxBw64(M_`tQ%Ui( zg$iiYOmN?Jm@2ijv^4akSZQw>GotMj*6V}K^;@ZE#wVhU-7N4WKosT}_l=4dW5+^~ zV}?u42iNzv_SI+yIVPHz1CZvu?C{}VF>5?BtUX^+eodWu8x~)uexf<#?L)56Z*19-p|iCUjMPj!*yZPY;-!Uh=NzzM}m6GvZo^hpCXN z+GX|Hev?SZ<~KWI@J+YQ6)8WQ@>Z_K~b23HEbO_qGL!J`yX?bjb{ZLdzL-)h$uxzp(l@q?B}-_#_W#)~V(Pk#qp4oqDzev`vY z1A|AjuaDB>rmw)PndGXaB;B(PY4W0TX@H1R#2=BLyfuchJapMj?=>lRY4@PP^)2j5 z^w>P(@Z5=rs#Ps0J#U#0pr8@Pt`=9xJo=(QnoURz0gX_H4WjZ_eSZwOaj= zz<8S^bywv!0E^YmQ6$i*tDPv2fR+OOe(>ZDP`vu-b}<_UrAtUpuvxm@irk{o3zdPtd)!~azD%ro#*)03oxL2WQ=mstutFev za&G<<_LoC5V%AfRG>iha{FW`WsmQE=LVE@|w`<>W=KgGM!tIMPHMNVZ48dA;mPP9B zG@Lanq3RjOj*3qf`x|IW-D2tU?ES|rv@|H6v|ZwuCu)c57L4KrrU*yQYg_Uu{ud6ov(TD5I^7>Wo>z4WcQ zT9_$a6>eCSnz|5RM2sTDvIZ~T!5SL5Oj!HN2SZaj=f2=Vk!L=22#3G$1|Cqm@(g;u z{_h+%Z$8K;#{R5I$q5xL$4fo6?WUGpcLM8ZZ8nXwrL&$|G=9Q_#4r5Uc)WxKG3W0= z@akli(*Ss!<~+j3P?@#wV}EgU)3a>QHMYl?rb%IlnnW!GP4kQ_tCvq&O!|Yah%tbx zW@~ML=z|9j&Z+x`GgE%xYwb^4w0Hs~16;GT-Q}K>R)jiLTEKoaR0y?^27|D=MrGKH zUj4xPGk3sigiJ4$adfSYNxKV93XVQ2LPssO7Lb+^8VAwd%b;YN){P8Ze$3#C{&VNf zjlyZg*3M4lwfU#x11I0n%7R@4lI&`00}KTmNC ze*_^ySPu%wL4y&r=q``LQ|q`0c@0w7Nzi)kxpw>J-XN|U@O)Q|K)dbSva+%g%{_J0 z>Hi!K3bOj-qPkkCI+@&@oKOJLvkmmB*6+^t9c^`n>>}%>(Z}WX_Q`#Yl)T^W3fu|s zzNY`&V$?kl{1$NLPRT~)EG<5z|7BXe_pQCv4onwKEp6(@I7}J3@lBfdU%~8#pAafm zJFt@1gPJLg|67e_YaI?D!akf5L(l&lE%^LL*bQwB`E$OP^7g`EU{p6jTIkDw?r@Jfa~Q8dGT>XrD9vWK$1uLZPeSr6H0( zC`N;!l>ncu4$a6bEc7Y7jtF-gE(e*JnU7)O3bk`x3>+3x<@>CHt5!Fg@h7E}9GRJ- zlw*SYK;(H$px*xg6~XYQ?CB$i53ddo{HdTYC-(_Stf)w_Xc2iP+|c>bP}mxoW$mMv zv-D`9TSKiq`_4@E6{pe2*&5MKX5W1CO=TvNm)5;%BAXH)p&`)v$gzazM?Y0r7)320 z2@h9Hy(F7~KCcmZPS5CZVSW;!SYuc3*bpq+H4uv|;;ex}<;O{B+WdG|?d|)8v;Zaz`TW2!oLGWT(N0x7J~h3)2nTTf8Ramn0RmUgt$VX0 z?1Pv@e2E`4dBZJVknS<7 z5F-vZ;yI_lCe2!@V+Tu{4o=>y&If3OpG7+W&)=xsM&6z9T%`#m9Te4OY3jk3l0^j- zF@>-7s+BoCc*Tb%WW9hN@GZ(B=&^%RH-}>Ig8R#ih%1rrg_HvSXk1kf{F?Bq>BVX^ zc_S<=iP8|I9m3AgO6MFqgB~>?FY09}OhAk-^>wyoAlCpN*LH)0x3+ZnQS}&Imkuq} zj&Hicc!rZg2)zHp>#!W)>KrdX{L!FMESwb7 z@__Nq73bKV%}g^PoH#?A7pnCHM%XF06^eVCu++v`pwhU8>iY>qXn88 z&U_;r4%^@hM3d9MWE>LIU_!!Lj5tJY8d6*b18^NAx^zz;C7+;A z(u(ITM2TPDn%`N z;5aQ+yb?h+k;qUXmTYBZmpQl$#wfBxoDUShNS*ke1Ki?2Z0UCBRcgV3qXX`??>c-E z@kZ#8(nvN)fn{?Z74lMw8+bLxh}emZWR>|7qypuTAuBy?Ti?A31EtJIQABG=g0|I_ zjNza);p&tcEU`HvEya93h?dLJU>k`38uv3YOi{|tgH>=H;!j8e(%QqMFq}HoL>#|r zY=OmwN(^z}n3ycP?2*%jW!*!3|XF#O5hc>kSkC~PH?Hq$0bv42ZQn&7b4YBVfE0!8!~Ft zA^@O{25;52UtHs*LB}Epn#2W6X(2d#)w;{1zSS%{A)G73CTcAUL2-E9f_h}3r#aaS zMPMQf1u5qh*t7KIaL?}PLa1JkElMD-?ASQ_nPibl4FCtR{27_Smd(r0?{6UPLnu-- z3P~iCcN#N=kWHC0urO}QNovxB8z|s}LMK816C$dWh?*6F61v$sH$2{pf(bR2{3fm~ zkQqY08^t$>$?lc`G-56+xw29bh|YQ~taL>n2$9^Fax-(D*w}iNu83cRrRLNq`xb_F zvlYQwI5^L4I)%Um(liiBC7(?v*J7C+?w-(fmh!5pycvFWG5O&K|G#1Dod%z;|Fw7HR`f)d#Dz{6 zfxYt&&iXnnTe;T=M9a!M1si-lUouTSI0yoh&jCt6k-dB zY6Q=q1ymLSo1QMC_*!A0NPfUoB~~D5(BjiaL0Xr2%n`PEd*sTwQ0Z_M`Or8DO@J^M{YO#*3zYgVf#IkcOoZt3|O$Qkr=2J)A5amK^c~ zzn%Wa)zq9;B5cB(WczkCi5)~d5hI9RUX}sE_#+I08zLwg=bb3^d27i@cP4$Z2j@D- zdkK|XilxhJ5*w3J3^b>>z$r-#tf7#}TR(vyV0%vGeVlRU~4tqUZR!vp&9 zX~S=L?*?Khm0EV5W-%h|Srf4`P&NSLdF70FUzTm7ocJO4>jpw(J2x86E0s)Un@b96 z#-iD|LR=)NMMPZJ34RVE_6rG}yLAQH?texY=-d7B#k^?SLa-8Q)%G6Da;g!k41ye@=!BNE|AJB0nclxlg;)dV2OAK&dUS7vlUF(oIf&3qg~VO*59U@iy9JRx@U#>;P(B(X<%%XusG}@um%wPc=Th3z*$M_$2CNSf69E zD})hpOQfuCy^EzgKm5d7m}#>T_2|%9^YcqQ0pgvCAm~MXYJ3FbqZJrHBAu+hiDy~ z)j40+eWSJHI2(EpT$Z_3lN*1hf<%ubS{PW0#xRNx?AoQlIv+?aaK3lv+osej~&4*)H{!N`v!T9xKeNq8H#sovX$1tGae?5D518zy0d%M zeyBd80JCT!>6KBC@+?@RTJ6;s6VWVvFR<@hMp7e7loe(OII##8rIa63B>wttOTljD z+ksBsY&=l}Q7Shl>p-BQArL;$hOg|AP=(Yb2mCu+a9;?sD3g7%55iXt+VYLPfG zfXF-QsMaQaGdgNI@er8^XoU^>9mQhpxX2dnH<=Vln02K1elDunM@5lrE>Z zjY4vbgwVhUch7CbckTNO48+Ct_L$qdE$P%2Ha(*^)|%~d<&cZv7t{T<8HN50OEiGd5V z2=yS#y9fXyP3j|V>UsI~t~*b_mp?BCDH@kNs5>5{6d*ZEXe^?Sh#DCG_0FZYst0(O!TqIIr(EIQA>8W zA*JYNXDpM-m%~Hb z?CnB8l_ngdxyOWCVg};j#TIo~LR~~l^9D_pG35<{zaz8K@U+znspsKPe$FH`&Vwy3 zD-;Ah2u`)dF`|SZeckn4!^DgREvK&?ibFtP{P7W|Ek}bHEKF}sP%Atiof)nuUIum- zJ*?tNge}gloh=q8vGiODT79>NX3PVW7w)7qbOAR2$CqUO7$y?+euWKo#mC<4WFi?|y)-eL|0%999{ zHv@YZe9gI)=(QO)Jj3CiJo5NfRJ=KSi{mU%H ztX)1%!iz@biGkBSdp?qUlbL$OHq#V)RZSE6fj(H}JC5h zZT8G;5@czn?24u=c?8Yf?pj=oFHi9TK4+3_aLhf9ad(&OH@g7ne4hkA4y5z!9YGQ) z^t{R{Up&>&)GWkOWJI!HYE&WF%J7kKD?})xZ5LR_`;^>sh5{X!jn&nrMDqJ!T1bl( z*9e@hF58~~sf(%N3SYU0OujJ6nU_i?n~0cu%dpg%YR)GH#L~Y z9YlQ1_dKOY=rz6Uu!mh_WMuZE@Up2Lt>WrPLAI{ttS-|oAe|M{r_pFwRK4FOBZJDE zJ!}|JMZ*AO!zmzsMyO-?N`nPhPzYFTsy-~o3f_yIDyQ?#@Q}LjoKn!hlXCOoQH}sa zKuf}8Zqb}mx3V9Rq$E@jqczCOcIgA?Yr*$f`b-QZx#yWuUWNseiOb1NJHkJyq^zv0 zO7Ev#yQbf`f3I8br>i*GxPaM&3%1CODpjIqD9ln{M#P@U-kb9EO;Qz$^Ws%D%B^eSsK_6&S9N}0S~7eY1&#LZH)Oe?*XAM%6z?J6z_sV+y1$-F-6BFdEM77Tog3=w ztFT}xq8pm;%A&G+W~>Oh6XhHmI`dwGHTSv@u_j-pM%sL_R&k4M^0rd zNHNa~P1}v*UcYQuJ!@PMgC4M1$!lM8h%T1hm@#AQjFUO9pmfao`Y`!wFn=L7>plj^ zHHR=nt3(L(*rp1KAo^XV%2;G`f|@>k_3~w3zeMG!I=+cae<4{na4Wmph_*scb9Zt` z34rVrW6l`6YdR~b$fZF*)l2DR%D&v}Jw#hOv2WqT2AVfULaLUURJsdjdN6PPUE?-9 zTajAI^V3*I+;w{HGl8Bkgg2A^-gv{T<(&#sn(fn>0^LAin1&o(e9DKn-4%G3`=Rl3 zpE?LQn)VMgfo7%S~DNADMA?Ok|c@$a)g(G!*ogS&sUu5m$9MTKAEt!Mgh&{1!m#ERBGBFp3J__uz$d z5n8FgRKhM;N4*uX>E#aE$mdXdh&iZ`V{ElSW3WPdxc!qBBTE+2xDg4V*bj>@1Ntd= zBhrQzL!OJF;MQ`aM%PyuHjrnGv&;7wx;$D7W(V!?1{=>`n4F5`PHcYxWF@7Yd#4++?bPy(|og|QuE&F zIa)(W8-g1GEq`FdyNkF_7G;LVI-7uu?CgmdWlaLOkzGnmV|2-^Los$e($18&319MW zE&$|0QE%ZpZf0&S0#w)ZCz;lvLoh~W>p-89FR>hQOG+-0)voE5d^Wzs=epkB_d0AD zs*DuQD8Vo(aqqa6*xd%%$1~6*NdyPj5h5iLt+bGOaEbF>lj#mqM4Tu%Q6mZhT&^}` z90V#Hixrz!S{f{BN60C2>Ymp>yAv1p2C4eeD=U8`^H&yhRsSIKT&Rzqh!C3` z;5_+WZAoahq^moY{muTyVPcE0HYi{ppvRv^iLfu*y(#Lr*Uvp=N|y{Oo1*A@-&+Px zBo$M!j|3sL4iKxJb~ylZk2koJfG5_H(#2jZN+zdM#DVx~ zc#{|n^uuZGWi5-U8-5#CtD^9SJ)O+O_X_TTp~XQe-m1|a9v-8}P4hO*CLU|sp~dMc z%eA6$8}hius^ryKa!2XNliDw<->V4dpqi0QOn~qL*$CMagj&2-_;nD7y zCRDg_bXMCMOd}NF4xhVYS;tMr0)_RxFW-F-najEiI&S4SJ(=k1P=PF*G^C~VWg>ar zYZqHK?mkkW9+F0uTh0X)f!n*@(b>5>ESH!>haIM9S+vXVP}Xy;9@GH7_Tr-u>vD>u zgqw*&kuC+y*o_mByT-bL+77Q9kF9LGw6D4jza`wu)a(8G_wNoQwKePvz(O4ECmXR| z_i>A4G3B|`VNm#>+Um&BqZ^u^gV1O_KP2gu;i=OVU;PKRrL0hj{@AhX))63Uu^AZ| zC+4ErkBvEor!MVaG5&cs+t5%4x`_pg@X3j65I&n?vdOgf#{i%WcM@g$-e1dunUeYD z<;xXf>>0=Lt(_*~aLPka9 zn6|M?5b&p4zPR<1MFY(b|D;u2camVPsA5z{VG(Rb3+7)Y6=#5SglIR^{ScQUwhlzR z7geKY&7M74>;g`)8QZ0CY~2?R|1+0o6N~l%SdKM|FUz>C$w}4~BQ>s>E-hYV6E=c>q( zS4S#oC9k7sY*+MPmbHFIyr4K`65bmwZm=EcK#-Lc7g?B0pb3%bM|D_m8Ey4@_k_`6XLBmImNYy6~ zttF*@!VuArp~Hti%$%>U!;$rbgh*S@g7-R`dMiJ;B1yKBGxq-)Spj8Dm_w#{bkn(7 z;&mwekU}A&TtvN?UY4_e;!}zujlB8*;3+~SCQ?VW>Pi`40&OMT(w3s(-@p#FEjrtZ2Ca)#Q*LgRg+Fs9O)Jf^x?}3{Fe8y zlqL+=-q?)l7fFyV1Wc07fvn7*+v^W}t@&~HWz!f#`$4ZetEKzU9)sK<7XBSymC1N} z9ToM`lYaZhpA=PfZ|Vq1TF7V?k$*x!a5t>O1My&9Pl2$nMuBv(i2`H83R4QKX`NG8 z=4izW;!S&x?T|)vy~GJG{umYwIP5SBN13;Tlll5hFFLVcN?L};uoJzj=+J~wNg*z} z^8r#4BKRQzz$rciD$nelZ{uk%0iu8BiA@Ua-j(>J_ipiq|ym zyk})WySb>@+663!Vsx`}1FP&nUJY^Ui6A^Ae<7tTmoyG7%`C^+Hp<5CGO>#DbX9Pv zB}883FExU>DP-)6Oc7IPVDV{?0w{E>Fq2wFa3hGs>(;f$)kW3^e)p#OeO#Towu#u7yw3U~f$Q$goJ3+}kiyMz4#MkY&c z4f(WGAMyoChb=Sm&6$BUC0o}nKXY{J@|1nakFX2ZkB?_`o0fs|q^%Mnz{Z5{!VI5O z7VR~ww4sJ8i!dQQMLG!==0FE`uX|l1?P=1hvRybmQg{ZPdiK1CH=h|Dp5b4=in@7I z#x@CERg%Ij{SG#OhN-^$;7UkWesO3jT6RFK>s8{MsolDq3R|EuErTq9s{k)oDs7bI zbxm~YLd;SVWqyvqZ<3g3NNYB~d&;4h)R@bChfww0^_(}YCwP2iklYJJ$t%nuYX!l&_W4de+Ia38galP zOW+|@-H=m$y{FoRu<c3Cr_PZCZ0~;=XdY^z>=_keJJba z1OY0=>bIIE-%J`Qx0Ynj#rw<{^ zglrT$wgxdTZ1$pdik{9dV7>UP641EW+Q4K^Q}v|%84RkqQ}Xu=@a=VuPEI~0Oj#I{!Fm5a( z=7p&=hex_qS*J*Iunu|Jxa(z7Y24QUeHn?m;P)nMtg zl@KGQiFfD?&_X21U8%{G?<>FywaU|Zs9LK6#%{j-^16ZhM9Z7)elnMvs8NGPTMMjiwlKN!1M{U&GES9aTDucq&{ov;BTYD3}InYtL3ZhOz`sp0#1fg23O{pc5*`hrXA8 ztS-&USm0GY!GWgBO)XthdW1SE&;+=r0+KA`&Dd4Ds3=r-uDCb6E!1W!BCYR;RXZhM z$y5_z|E0q-h|*PeU~S|lDPYAh3~WdE&!;s6)&X1}nGAWipy&R5JM4hq3>3JR_3=xL z`{R#;?WZ$UM#F$(?iA595QR~v8edzN+`AyKCNGNe2YR1kH-C5+E(3Z|s9^HuoImGz z;W49unL*T*9f|&U3P@s zVX`tvcu6Vy%%7z?ybT6p5wI_0KT%RMz#DEuxQp91fg$8sw6pt+UJ1FIu6lB8Y;1jF zZ>IVP9aNA%Z0W=od=SjX;z)4#p8M&}w63)DRksQctB1HiYxk;zm;k2NXvVLy%qLYI z=`auRj<_?2XEe}D#CtQ&G@#!p`sfcxrBe1CYhv}~!c60&so@(cM_I=mE2n#=wGsVS z_u)TohY(X-^-O5LJfG3YR%RJ(-miUm8#X4+hq)<0$eBHDdx14*kUMsCN zE@W>Y@LA}FXcQB1RI*aQ0IP~F$INWj6ATD&yj{P_$v|?y*s){+qgAXV)l2jG-VlDp zQp)1wEi$sii4VN2>mM}`?a5ajn(g=ZDJ~TQB#i7XCLNo28Ku{2Y9^T%>KPXdVRDK; zBil@(%?-+Bd;veFX&^lW87)U56U5;u14?`X51I;s6~MaFs>?ij{NNEtCf*3&9O?6= zpO`!6c?_jmO_2%4sV3IYLir7^uN@01%j~x5Aj#{WCmLiBpY*oxcW=KsxA>Fw+;A#x zrZ)6@ezOS>j1r*mx>*inQI@Xv?p(ShGDkdBw^Ej6E&X0i194!NnNB2QVl^fY&@NLC zi*vHC2Z{r3AyvDQ^6pUEC)%QiR}^Iz&Br67+JHCW&RV`rTmt&IyiZ7SYcimKFVZJpMfErH6OSQ1LHzV(_ zC6=FP<*5^497w8fmEb)hzm}gH1r^2Iy`dU|loYGWQDwmJMz9&GzFr<}J+Am_jZ$wp5r&405B4xa|TKPF8_M@L*L zvo^&t_Wa8f`AlRMw)=E36yDcM@5Y@Sjt0tI*N)_8ep;JS+C;3)y81=&WMFu%{OFBH z=iWnhM7m!6HfanuX1CL&aKnhEI5iKXe<2RGLr=?TvLlU)CyiVAQ;f zw6xI4$tD4xer6EyYR{0NuU$10^^FrooGC6YZZqzfhD_3CpN~pI)@T%*-pX*HPue2o zl_5X>#SuBjFqVOR`~GniPWB8r3lS+UIg@-*L+D^~xTH-d?PXfuG#Rf!LV22VBEa}) zUPC>zN3sg+)ff4LXv?r7_$fEWCw!{5{X#Px3j9kdHUR;obHq1kx(7|;;?I!w_!i-n zz1ihr(8+?7(%4>QQ+W8v{cc}97IZSXfJEo!DM`VHTDEk@OVd8h+~LTF#)F`!z@qNtLBQL5crtpkkQqlM$CoWz#U(>ox8#_N2S*IYJseD{- zFE^F1JoU}49ZW|U$LtStlnJHMwt@v{5BJJ>T+ff6|Ao=L=YFAfI3JBxsw`0&f9ptF z<%l>tWpeADmfeeC>q0G_AKVC%l7BU5*d0uR>+65ko9mg@0lfmZeZ=u*q)(AJKoTHT zHy9-7t0H75HKg2@T&}r;J|}0jrKMj;Y{rHgwlQ&~@H3DO-O-wnoRF|ZH?rZwT1xKl z;y1n;MOO38Eut%-WC$aHG;9Wa|9PZdjdj^g>#1cGfdZ9CcK{H5W-n=V=2uX&YPTPB zASvlvcm19dd(*?-+&%3ejT*hm{zKbA4VP(j8ig_`fJXeTexItD%>f3tPn|tx9T{|O z>aj)*P@J=?tjUn0Fm)DFY#9YGsP^vNH9%VVwh#_w(2;i!=E+iT0a zfChSyPrn+IIq%I9D6l{4PI2YNMzJdmS5!k_Odc{VzOIQU?RzC0%C6jX<+!<5*waIX z4Vz2LNm&y7JpTCcK6a+xfB%!}%FLXh$F|r-YJ* z+We>ux(-(VP`Zw$*5Rig?^x}qTs6O*x8eUzuglD^+K#S(_lbF+17{nsOxG{_bEaOX z9$3&wFSZ0ATM&puI&0$Kw{U%oR{i-t)XeY4J!$6C`Q^)Yds_pCZEH}~+8 z)tl&VsoIv1TUqbdzMK+VC|29qWt?-wg5$T7N?yB8Y;l@lqNG?pGSW{zu{mA3T=U5n zr~T`256!m)&eE!5yp>Qlyb6YH%#@l=<>TYSbb?KF>9c3dINOLs&Hrj$OG!5EFM zpX2j#X?vMHM;&y!)d>v>OfmTlZDc~}@^z!Qjjq`0|e?Qu^vxoIOFqYBK zkyvs|-U)q_y5Ly&bHeeL{(o!$Maq|XD;oy+lDl7X)vafpkvh!%)j#84j+KnuxNjYL z?EMmv-q57>|8f!^Jl?erHGW~H43kcEc~SF0E8y4P{{)-K`>tL5W`S0v%6=DWl{Tk2 zes0W;Hm5kdk!qO(k|d{Jrw$!9eSf+2;JMb;!Lqd6z;H-JQaLvI(L|lQtEF1lR64F} zxj?iCmz(|jX{}M8&+}<|R|UIKJ`hYy1Xvv{FYL5D%Dpi=;k&ftvjev=?moYQ;^{om z)w@VkpG=in5uDAs8ya83v({=qX9W?d*k0z!pMv%-K?gwG*P)NWuiso@wC7tJlP`$5B4oAt}Dl@ z*{A(AW*Y4Vv*>rfw!=*-8xz|CY)B@&`*YQraoNP@BVJwu4A8Tsu#2tr`xHkM1&7?c zkvD>TMjBa#qqPSPd%db)k0d>pd~RWZ$rF zVSMR$$xtU6>t|O5N7t^G7pn-A!%xP(pi_`Y321tb-y)|o?0H!%VzK`Q_zWeId6NDT zb<%rjqX?_0xOf9-kz|jYf`X$;85dqs$J+G!p`L_V#(jdyjp2XB4B1HolCV_QgM2-K z8IMEb&r>dyVgXK`^r!6vAy0E|28QUwf7NsB!=olwD9a+iu^Etf66G7{o4Fz>sl!;d zjGYH01YeaTv*K0@Xp6GpHImR&*y|ep+P~KjkL_8NL7-v6-IaXXaK!ahpBVlibag1z zRcxo3<4iRsI#;a~6aWTo8s|jfs-_CBm_@I{dr3LO%|1v>e8SO&aMB{lQ-*Gu?s;!m zNsne7?UkjVRpO!xP&$y(7P0EJgguUTI~&g!XWCZWZ)sP;#n~uk*JOe)VXL64y&)qX zRhK~eCB1%52}WL7VCQ~sV^65|^Z0%d56XZ^Dz^LrXB1_ER|xr07K5VdZEX7@*4JWw zbWw=KY)Qe;!HtSP43cER zjh$p1;^7KvRz#+Ok!URu5yQQ129{;Jc=cslkHQy~EKd;#_U@g*c$HJ2MKeS_B13pz z+ql>HX%v#T%B=d!G|EM{A_;SP@|8)^WR2v;i(#_}T@V!m%996RR?bHoVW$k_Ze>Goh9om55I^Ud+SoY`j05$JNEFkLQ3*UqGD7M>B$WT;M> zmi~JJfvSF7*g{n6S^R_$$TWM)y!#I>g3Yif*Kv{z*3w#pQtS!h3)B`D?^x-l@c_k` z9i%{}9!T=fh)S>J`ejy*f~8x9(~A>A0g|aAP=JSgqoy==AQDd~v#Y7CeS~4Ow>W2! zpX6^fb=tJ<3J;*IZlEX?TV~WWu{eI5F;b(O%(YXkg4^R!L?t~w=?d9;B6v8C7C);R z3T|+LemRJ|g7V)H^wT$bu)1|1UYmJh+p)$Cgi0CBDd+0*N}3#)w`?Z3j_j2k>0r}u z*sx^VV6^RBIf^yk)v==dgOklYPOhHRN$x#lh+7SE@{Y|MC0X z1>1Pcs)lsw&qr?ExI3pymoD8AVp#da3I8d4*%ylfZr`4qLux%5kr^;6@bNw}p})>W zEQY$%q#K22_m9nxH>vyJyz#O*S^Fzyj10b6F>@8Kv;P#`aT|@H72#72M zbSdRtYKkR}QJMjD9DqYoiylFIRfR$J8?-s|t=cvo-H%s}ZopZs0&k`-sdA8v6<3YZEo~wIC6*w- zh?9lBC7OCnU}>_QEp<+}?qcP9Pfl_VC__^ekDy}bfQ|>W`&h@h-OxaP;f7Psy3xpI zSk*=1l(aCBt3D;S+31tk-DsGeo@sO9(91H)j^HUeo7p}ie*l}hTHJ%KRx<(M8G?GY zv`u<%#Q)tw0Wk7ynf;KEN1q^aUkD8jAzU+KN@h{p)k%}uK&XDYXEY>s$+}x;c2`Kh zs32t0twICUnB8&!!9<^kUNV zJxcngdA3loj>ZiMn7_cbaeSt0WukDV*cYqPmpw0n7oJ8eAL3O<46EWGDnx{EWkXD9 zMA5aaB}>g+O0HK_)W%HwLn!VVg$NIad-X!pSIEG!;c2}l)}^GU$><@O%mQIBv81_d zWg5Jps9>KneKb_(v6LO$-9i{gh7lVU9VBlT61^xuG~D34$TTh*AQO6aQ+u&sK4Fe& ztcyVV(g-~lAVnEHa0-rkw^U~GNcU7op_L{w`uB=3BvQ^}-td69@qr`(+dTWrl*PhjUue3_AT7-yn&{{LPn7}xVXF1 z<&ZItn;~Nx!T+-k&+DT4j#VUtTamdUi&?Xrhbbq7xl`VeId0Zb)r;-2%6)rXUO`GM zg8b7qtZN~aLoYH=mUudySY=%}HXz4IxQwCiGbmwFgt`uNW9OIS;_L1G`f>aSWBdAE z<%m=Tp{C9ZjWH$Xcq(ToB)gdk-ty~_7G^zVI-H2ANx?$tLddtuVTrj&K)a6(6t^4h zN!)bt$ImYOi$t5Nc`c)QDL*^?>t82g>hp$C=8pg2XZ7K55rjXQl771a=z6T%l_po{ zSnG)IGJT55ZOH0`J)016h`R>otc>IXM#9u((fSxzu%ZB_3H=5<`1JNa{K=xl*@tfw zjXIr1*FP>#p$4HBdd;D18LE%LP$xO+=Co{+cf{X+qyC2Duna^Pq{^r|B>Q52wBC%1E zB2Rb>SV28`R~_^CBFTslB>rL#AycT@?_M9f;IkHLlk8V_-6`n)zbVm>--Nh7;q9#! zSPs11;^-w^u5*Zq6oC}<$Zl>|{CK*OqfXEr;RWMy&*q{8UgJ}-Hz8qGvvxm8zmInR z{%0QR^Mg;=%J6LGhzY+8M}Pr8^mX?KgU5_97A`5kyvBL1lrrtm{{6{L``3kL96_N% z(`pKVPG~hl2OitRbqd*;jXRU37UKvT1>1V7@N&iIc%G z7!1j*V1DFqkuN>bVDcmQpG(n)$F_`WEMQBga?lAWn9-LPa&y)E$ za0epbNI^acYZFl3c8y2?s>`yMr=+JpSnl|;W&7#BTo8AK67)BcKT6tcuz+PC=v4dZ zpPSW-p`MT^ahUQY;Tq7~1?oRH;38a5m$Bp2)CMn}Gsp9}bCI^F?H@dNumCF#IX~!v znON9P%QL}L#2jWa&KfdR`F7z<|q5M|fx4aO6UPNEYZk?%k%zTol^0*#vkZbKa z^|7tg|Hsvtfc2QRZT!hT*;Cn4mY5VNWGy9yEF-k3DA|)GYm&-NStH4sEUijtv9(a5 zkfJiOq@+SrQYiKPZu1)Eb9~3~&ilQl{{QE>?`t{F^E$75pRrSQHM_xgJfxBf7Sk&u zT*?DfOT9EA9-{pj?2x>p<%zFt&ce#mQ2OAg5j19W)5D}I=9AwI>^2gAsGubxXj96~ z%$#lR#eFP64{A!=;9uKHS=WjlJ3Kjfc?g&Cs9;qmBir8w^EzEZ=J!G?VD%y+fy{-#65v`EL-|ydcJW4QrOYWJ9zRSNB z-J%^(;DX*`izx8#Jw$Dj=60QHCq})ob{QY2rtG(uqrlkF`fs#|Sh#DNTqSD_MvFOf z<$WD2ix|)%-cJYURqd;*Ys<$C`jF7zPFvtQ#6Xfl zt!B?YRgZqAlwogS6x93p_q<_jPK3I!;DS^w-x4QJn3)7xthP2`Vnuy}p-M74i@S>L zYMTOOG&S)r5tHX2spk+%P4uBgT$S2w?Lt~Op{C`7{^$GUUo_+lEDn!oL(mqr?l!`V&ceRWti;_K5pjlqlzrDG!1D^f0N-{~i`F4D7V8BMUQ_WfoT|v1 z&0@LNU?Q{FZOFaxIfIaRF?8M4vY0%efr3|RGE(_-b z#%u@|JN;dz_NeDEh#l?xKE9?t)>X*o)GSYm&V|AhseQIMCDd$|(^eT|r>CW5iIhXF zCBXf(d-o2i3UwGdlE>6r?6!R)e)I2t;`+hMq~C%H`LRijda2U2<`8Xp#>ut~Mep(>30Ku#r0*ssx4%2X67>xKm*7Fq|JJ*7gBnEX1u&jKDKn zqAE^Dzl%bzu1&y-x4#7A3e}Xhp_BWD3TQajS zC$-Iw-@@M~A2@#SW@d~`G#Hr^+FtKQqa-P<2dYQ$1H~Mg7*_T0-mych6&LSz=7!JN zesiM+N&zbvaOEb7folHpMP1L{BSu(@M?^UXgAwaE016x%hJl8i@cE%-nC?!{%BsZRe4mn!u<^7tRD>8BE6pwEmj4P$(o%^2n zU0^XAV#Qrpe@ zH4H`sHiJSbtGug|WV)XtEF7rlIu_I4{bgM4BW7yR#n^24RyCFHkN&Ud6yHDYI**() zD+nw>EkOZ^xu2B@d?C>vy;;Wlu%L~klhW;^BLxJ4E>eF8q+x#jnx*aCsQCMTwV?{t zmGA%Gw?AwO&vV{XD=VQZIbw``Q}{!goc^hgf%f>37YE1Nx0E_2Y}(XFK+3cij|3mY zs3)OOIAR|v>@sv|ID=-v!dQl*!Zv0-d2LBjGa=}TN@$QrEkf9XzP|H@i`9a}rvp@h zPH&bGajQ&|CC`iCC65Jj`;3ZmwU`q*c=YJv;hG5Wd=e_OCjR#mhw6D1Z2W{drr1qL zz?(!nk;7*?KEK@|AyKvQdQBJ)M&Q=gsFk$u3~z+4EPa}kKye~A_pUewPcKx{w2{J| zM&xilc=4%V87XnA8Za(DrT^DF1X#!Rc< zHt>_h%-^HU>NjrOxL;Qm8Wtfc5(O2NkK)Ju{>PyADK+Kb77!kUWU+5^#@s7>gL!l3 z4(pZ&L4%3hEWVBz)V(+d0taK1s`38DiD%!Th83EiJc7P36yiu(@4563Ni}@BlYp9N z!az!0)K=iw`!|s8{krpUXM=)9b`ypZOb!U${rttx;>tlOF zmJ_cehO^0l)5FG7|69>`svAw!HJyR{oBQ40Sdn?T{kUK!k7AH%2>{ z776EJs^O-?FWMhwmjb+w|If2&3x#hb74MyljEu&XlEi4Kt;Z#r)A_U>Q(@#V)#7htYh{B%*iRb zLJPt;fqqv-yM(~Da?|QtO&NH)CzwY ze@xMbUo4ARM!&~A;~7dmYp<6a`SJD5q{Mk@`ucVhU`z9elEU5GFXjCQ*}R!c((m6_ zXsFuom2bU5{oq=2UAwFpz9O3QI43c0agm@CG@#?JFRD3?FPc5o-95hg!}G=d8^hv+ zTPnlKOI{+7qId1fcnrt>FMWcp27BYxuXmCBWa+%fUNq*6Qhy(TN?_hP@ejznb~fx5 zDzNEOt(?90?3sUv-(^}xCP4g?u}HCqxD@{=6&YkC{-@Df@D&WSMO*P19Xe;>4%pqPFW5kdC!YUf|EJw@y z$}44VHN!t}71w?>Xp&mwQ~A#84YSxWF7f@0KMSMn9Xo{isaSpb@uS_ms9$l(K!+}C zd5H6|t$#-;bhJaVc<9MX8g4?EruQ3fzc~&L_Xgxjac&ftCA?V8mVLZDDD?bB{8ix; zT&y@*wNIacUDet77fux`<`*?pT!j6@v17;NYFWbz6qjB$CIgsOP%)K5^9PcZ-W^Oh ze)JZ!qwk2n;O(ZrTJK!1*tzqJrj}Txr!fdD63n#6v!3xhi&oTLIUnf#gv@}A)?2eq z@1Jmkg|}BsmRH_$h3lW}Po!H?7lv&8^uc|EreD$MwhG@Byty3{PhG$E=EGs!m1KAS z<`4QKTKIMN#{)UmZrdncKd~OEg;~Kcro%zw4v~IoB>Km)4a`DZ>{Y9!2jiwr-7i=i zy2cU&3?o*&-jR3c#EDsNUHBUqV6Po{bP)y@d^D@3mXtN7H;6El_;JURejF|e(U7l4 zBO@cHpLnCWy_ZL0&86UulwBIr>ltLRc5A>R@Wsc$OEiLN#qzX#4e1YHHA?Sqi@{RInTu>caoLYxDe*#YsLlz@lTz z)~)+Tl?1|m3Z{vFl|1xin!KqD$CX}nsr!tJXB>8tT0$;dxG<^k+qZ8*>#OPg+&h*L z*z)y&7pBIj-tN`ipIK2yUz4Ug3rBSSPqDz@A8I{i?HPgmYU3R7Mt$!{kW2qhLm7|} zLkne%(>XpM!FNAW5Siau8hfqZ@&O?wdLu{HUVosVr1XA;Md`(eLGK2et|s=Pvc0$6 zTE1hN-vYg%Lu;--=+?gdtC)o^%)MEz9vi#1X#$7r=O5Ggd|S1IW5<+Y?H-I;YqKtX z%PTg6;7xexPEWQWEP8IvV+~6VYpR>7)ryKiovFbk8k#4TJI$CeqiDnw9z=Rz(8`v9 z@Pn)uFgL-*RPszSJ(l3xdwcrbyL~^!kQv9^N3S`Vq6b#sW<>=X~ zaax6L2`y&z69Ta7j1x=)l_flYUA$TIx3kT{g=%*4edy_83{SabEG8B%!<@ea3 zrc&27jX~71_vs&GUyLy{q&Qdq>L_Eo2Tl#wtB`5l#ocUJJC^qCvk&|QMbw!_uF7|Q zL1h6-YOE@$pimj`$jLFqE={dIYu&m9+RLd6l9#j}`;SGLJYL#-%#~LzewfS7#aw81Clyjoz=G(g_HQSb+T*&Y@B z50#^P6l=2E!gtXm#Mv}LQ^z_(fB!Pdtlo-!uUWH) z@@;xg3f3jBj48%QX7}D;5jP`YUl~W2Og!SF#WaswTExfKF?`oUaS3NEOicso>fD0n z$L0-iSq~hTXIS&e|9)gY_GI*LI^u)!_2nNf&e^ynA;IHpvS{(l*zSGM-+$4%J2Om- z)AppNyz})>pw^D-A28s-%e12>eRG0_d4z>4MO>~cGh7k3@>6W(nzK?&oh$bSwG$ zO50@h#hT;lE%Xi^O7ML=L4A4K7A-_67;r?Z)fn1;QJ$R@g^Q4ZP&`iT)=O9S*%Ie@ z&Ku9N5mLdnwPgDOsoaDO`%KVd?VQ8lPY8BrV(kK;f$&kC$OQ`x4Ey!2P4DuqJ<}XI zZQ~U_Q?$iE|H|?H9}V-qK6pIqQ0GQVhU7K9KiJM%pN||nsNbydEnBr(HRG9br%rd? zx91Ba&f`^_zqmr|#QVf6@=5jW?J@GDQpCl|p`5eWwi=``DZg?mP!NUraE17eu|D%% zYpSa)$bzG}msnLN3F#ptzSOT^a76j1za&CmS$ z*xAjEe_Og1idF)C!W?pbdS)$s69S^*m}NxW>9gnX&4qm#cCC;W*JLA`NcqCoTx^6E zNIpZQBfn3+`{2QvyrBR^r5{aTn1sLK{KLPh0nJe)0KV-%e}Z)x^%sQcSsH)QFD|WR z3w3%?csxWURaEfJ5*aC*O`pOkV)`jJUK^FtSqSdf4Sqp$!=oVJy==;xnA zncu&ZrY&t5tif@wmyE#|RDMCABYf)72I#bW;q5VPRSPNDiIu|>OiZHgX(eo^T|-Ns zUDoOo?9E#BL(9N)X&S?Zx&Hk5QvSs;Q-3Yf^Snsp7Jd~pR)X{tSPD%5>mh1wl~uqw z%?zGEkqTYUkfZ0lPB)hVgsdqTWo3 zqfob``xln@=mgptwU#`KIs1#?tDoYZ_U|5GE)~{(f97>=;TgkJfFt>yq%{e}6{=5^Y}8$Tz^Vfk$nCQO*d3BB@?u`v{xQ~4Q>@#qm#28c@p?Bm+#XAGoi-4oj<@d{kz_8|HB)C#2+#g%NDooG(`#TJL zPyhDPfC;E1BJ zOJBJj<(%ODg(iXDQ)9nHk^%-&Lh#Bl2&tY>G1(7A|2NcmGTPphcNHtE0&g;da8>ifV%4)Qk!h@ zvG9~Gg{PQGWSh0FNP*gMA&Ma~)8|z<9{=x8V$=Ubj21lfNy0)>L^9@p*{)`tflG$S zO~4*u7K(XS)nk+3LK)BCU53|8&y6Z5Jm5m-^rGZX+xi{IzVYtxS~PW z#AEJnG7T-4<`*|HJEvL-x0DMrGr;A#53#3&sg1`_6=I);Un-lqO0cCfgV|GH96|qk z=@em3B9L3?_Q@DUlJb1J1ZjX-YpEDMM3p?SMnKI~aGevxsHbV)DBsuoJTb2R8QqdP zeaW;8-=jyvP?OK}sY0G;TkdkAer7)l0B{sXY-a`n=Hs#s!JWnVW=M) zL67&{kzhn`X5)3pjw8xmgd^|h9L<#v6n<@eOReGwTwPk5Aj9FaY=8|O)f44r+Td~l2?K-cDlZ-f+Ok?Dxs_s*U7T385qg_VLh-T1~BH$C)JXy}BJ z3IGxH=V{@*_4H35Iv{mRfET`7Hc`{Bc*XS?KB-L()3~DBU8zTm!awE0^>{GeoH={- z`j`mO7cvQ3N2jyEHjnV?5KFeOL=6TNc~fgE2T4gWAm+uORE6oDZM;5=^8V*b{cz1e zM3Gk^hSvzN4pq$zl*0V*eb5~i8bZ($U{HZKEGu$X-!ATM@* z#E75Nwvm{c5<_)V8)Cs02}~?ByYfj(P%KrUbTYNURuV7n?wMl0;J-rXi4H2nZMw zfurU;d?|W4VN(J}ZWSYjJOJ*5K_3Aij0?QFG|N~B4G~>v(weFvu+@#HzJK$TZR0R+ z=5KX`D;^$0VpoCSM9E$6;6zR7N5rl=s({!HLHq+qgsAbvv<;kC5b7UCKDp*zAlh7X zbE2+goPQ?5Pz%5su|5lm`_YOBF`>pR+?#Jq^4wcYL-u&)+ULC~V>@qS@Kp>22RRg? z`OmQBhQ(6NOn>|C)n8=cS+1qM#gZas#6@)Hk)Pu;+&~D^`$7J7W;|9SXccBPAhaT< z@>EJ0ZjXHwg+C;)k~#VnF+v~o9W_*zPOj}~oE5}Z5Fe2_AmKp{$(5$nDrgjUQ7nKG z50Zzo2tN=(SfXeXdoXd|F&46Y3LG5-IG0`$O7G?7u{To;tE{`R2G~rjT@qF|?iM0+ zAeQxe@)0)gM_EFA7rH|>7Kkk+g!s>X33VycoMs(*nc@JPB&<5c;xkrEO%tCD%L1zF zvkZFAB#&tpekF5>BTkbM=Fw1pl_!u*$VDIbR>*YdBbC>^ZVx^F`28hl<@DleB%(Ss z{ES5y$w5t;@j`T5%I(GbLFw;`@qsXBD@Jl1`StIT|FQVu=|C|vwR$e%>RWZhdZ(P0 z$%ZyXfT52+kGNApPlxgTJ7kc92HpO*#|*H(&^e;MDbU6L{uuan)^oiqBytoSiz(iF zKX|ii;y8L6G|{Kvv?lrpM<$WD&sL8_Z#J)bk!8c{cUI3n#J$W8uPln9!xJjCl%hGe zcV*&EGyj7f+5^s~O+hCDdoG`7%F6G|=kO%FC%o^#HVXQRV3@QwF{rggfrRpp!vO6vN8>zHl*Fz2YF5?`pH(QNF343Qk}Jfs#{TthTdM7oVyXtFH!Rs*R6(cX=`<{lnU1n3aApaUz}K(PO{@_|m&R#DUXWOyz_^821^6Z-9Sm7CQ=IDiWzJ$o zn^P~}rHeXxoo`HQeTJs-8|IEl85zm)+%VNrynkcm-<@2{i4{!;>i{2|+;{Nc8Sawb zuxk95#DwmlE{#J^aRKc6Apb4-kGDXs$jpiZHF6 zN9V8n=KGtz96sDhXj#Q<$|Gk!r8xNs5vn!B7!#F(n0gTvKKXLa()Dlr7YN4+ztpzMx=(CJ ziSv2L*+lqwi5QQD^hllvjlA0NBWjP}jdq(ygwwnu&Q@Xuqu+Ok;$x%QW;NV+V`=NW zmC31D1)r}BWFlI{vW+H04K;E2hVn|XE5-g*!Y0T`)D3clH-JW#V4)q+85M% zRUv|(aMN4QYMqH%mw`BfOU_iI{#HdYj(xA&?K|h;Fogvb!SN!xGoNAWQ-xUUEovR* zJ-@0oHUGUq|K58^(p->Yyvw6D?vS#Edwv{QN5(53+>oXxt^3)ud=?Tn?m+ykG39dyPerQxapaY z;2pu;tGA8SwsLs?JbB?`t7*HsoObAEGFaOoP$fY-O4Vqxwqo)&hrRYYTd2#fIrGQ( z4k3dwRCHImuRMP0Z_`V5i|-e_SpPt;M(@@=E!kS7!$*%=F22sG=%J_AP2%D-rfzFQ zBh}bc`5dy8niL&gn5M;Yk7vB0iRx6Z@+WW%KTrk%7>SLVx%rsIY_X25dcg9dxJtp=PxfTYHJN5Oo%O)MxIu$dK3DIAFLfct-{rT&^_UsvIoEE@( z61~M&U<5-Qr!Y(Y%c=0dB_Se>&rs zYkS?Ly}{QB`Dqs}3PJy=prGc`Fz13MA70!Db3R5{Q}Xt0BWcyDRpoT$J7cITx-l2( zn{(>hckwfgyDJBOsXc3J+)WaeM2b6_ds4O*^0qf_-aO`Pu7@0Ri1K-G|MDAG2Gm_) z2&GPiQP*b$fv|U(uddeSH-;=DowNTlN_~yfb@Dnw!?&u)+RB^@-S5Yc*qr zj6~7XzGKHA=VKU&4s6$;a;C2C)ClJ$;3oh6$xPp&k<#Jc|0@3BhCR(3`z#wvow{`C z*}Z%I*4+G8uPP>`PH%Q&W2I>wMs7V8S*po9jMUa{Ps#r78@cu`xh@{h3SUM7Xc%Wj zxY~8-(BYJ++Vaw@-X>)Oj#SpRU3lVP0KctE#`GJJ01gJQ|JDo}8b)!T%N%cvGD~gE zdgM+HmhSpeJ^%qr*4x*jdVy08t{h=Lb;DmYOn=Zm`CjhYsZ#)<`U}=^G6y~M=?*kY z3yX?+_nFiE_aofXwX?ST6!aV}A6_O5h?zcpdYElU9fxQ+PKHXCVq-1efgf#%I_~4sC_vYiFxB&h`nYl9 zqK@y|=gAc@x6UXewr@sgy8~l-w|;i%Qa1`&Tb}eswEly!n%a3m4iEZ0_8-6MV6{*yQu5MOWkBt~B<2yRw6X zy2-9|HH%zko;P)yoccU|!^o#GOEjuaX3zPenh}z!r+g-;VGn0qQfttyyf{rwUQJzn zQ%uZ|RjXHry-yI~OhsRr$!0~NEsXxdYL+DhNl9Mp09d81$eP?ERDV6iz}!6+OFA0- z`vm!iD!U;lzokU>pqx^?a3L>U`m8^fdoaC7=k2nkOY4(! zL;orZ{rtMPSid6r;I7@f+bb#ULf(O5fP`EzEP85fVW_M7!fC|d1+!AUr#&j34_$LI zJ#O!mrRCwe-o<9CH{Grhb4?!Yx^$5RrD@ekD@ZR!DttHO48@DCT-QmlVmCvTU?~Xj(IP)|k(_ zUArDt4~-m!n|{=B$nwHZCymP#&NqrIjmk2bGNmnC1IR~X=@?~0mQasqX>0Ef?{nhV zG27V<#m3QNC+|J}_Pgc0B}@9pvG$WJ5nA{@TQK=m2L9stgb1HGq?%!v z=0916vgz#V$FFPWIXcQpgprUl)o)$0iVyTj`>5Z2!z{59&Zuym&Xvf}$kb5B$h&cA z1_^KHbn4b^=6TO0=BtB81wr2Lf#)|_KYMl$WH#Na7t5)g%Y8)Kok@$1vdRIy=iwns zte5ziouZb~b**Y)@OAxCs*YJDpW%Cx*BI+xo3#ZcvwCeEaZp0)BvGeS54Zg7Q5#hi z{Qn4;e((N$q0)p#?lEwn9EejYEr{c_ey)F+jj7;qPG4M8RVAM%sOgqB8fUc&clk*a>_Q9$i?<_^RS+@`P-jF``5P;z@P3J1H+ z&zv#?n_^xqBO!hJ0$8Y8*bhP{JW%*|vk)lwc`Q}fE8rBLPt5Q(=GZS>ytt5%>oa7l z;YM6qWYAwIrhR=Atpe)MR1lhcHNC~6y%TFe}_l0#T3m!J>hdCvJ5xUcuVxr-L{ zrONE_l#OYvMvlBT;hpJscU+x1073XvU%WWb>FMP^2Ku*ZAL`lf@GmWZi{;P=&Fp=}m@90hsoC+J#piC==>JG*SV8{5N(gn4 zh=;AKRGmBUN7Y*qI?Frs)iX-hKPWRn{@mPj#s9QvlO*8>i1AVn&q{?036L$(sj37G zShpmCm5f*msy3 zIb_kfzCM-TJE?h0VH>pk(8*MNqF_-}+(wG-(YJ4i_2;?s=NEvg6RU;_v*01K5z0nA z$;r+2d)&h>UFP8SSDa0(shZ&czB_lSnta@vvM$KQmUH5wO$IA}wBh>Q_V`lX16zJ? z!6+>@gkW>SEK~-S)3DWVHb)-`LAP%$2Q=+4%eaqvR~J2-~UPRe(hI-JN@w z(pk82#P|%mah2Hy)!9Y7oAw_pCQO;)7jCfB!J$#}=FLk=O6=)hN}fh*u$pBryU%uv z0yi0LV)BPr<{Z5^w0?qBp93;qJT{J)j4RhjVMOu%+SRLumX;lf-A}Hp{1b3gb5jlf zRuUx&-}fbK=YX3JrFNYub zAdaHA${a%57|tfl!Z}vH6v(@v0^c`p)+~@tJV6Lj*iiF`BW$+^-Z~<#RQ%})9I98NZ)!n(b$4Y`HM^-Js6Gw8);xdtQiTE{P>&*Y>C&aVSvt2CG!Mo{E3eEr zo?AfUbO9heGYE}Cd3m{KRFpRAyY|3OPoOt?vEi&(PP=5>uP`uh)Nc-_y$ckiO?7p(l=d=JjMtf4y`=x$%v2tL%^Ig>3xuf>#82I-T{$GAAdeeTNQhW2UnMGv$p;M>*dG z?Ct%X{~06ER(CU6N-n^*7hn%r|7N%1IuRGMm`(&DSc_d^Rdm)1yf#G7>{DYBP0crS9s(*nZp=LEgtlPNsx~1LU!41?K-STx_vu5n1Nv-bPyBGRC%!FLQ*zn+pei33N8iSK#9>+WV zJ@DS~k+Eq}+>U-Tv~L8O($DUDPge4s(+1GAN%Y6(*T{4u^2Pt_#2}E-el{_!q;{0H zVqNZMWZ$DX!M?ecu%+JI4^g1{R!?u8(m0XGp8xUVfSb_@+FDxsnmC2I_D5HJn&!x7 zr=ohGTYq(VSz2@%{qI%Nqcg6!RP?-lku3Hn&33 zl5ZHnbGrr3Tkg?N;{hVF_0pw5qybTDXRldgj@wTYRwf}ZnjX}Kq+)MxFY)k!M|un% zd^t^<^ba6df}_#xlglO$D97-O5Oaop{$z5>G$1^@71-!)a+Ah;tf00Mu1vJt`D>y~ z@y#tqs9vcz7Kr85&8@%?&7?07cYU(HP}*tFy|Yg?13ghHA3Zv;&(+Li z4hi#T#6}s@`b$?J%Y016E7yFf9rW8#o2uixFndkY-^&`Kss`$fU0sK^L7a7Xm~&5* z$l7>T4;wjh4t9a#O-w?{NS}wTo;mTz7k}n_0`l?H3&Kt+@!B+tjmw+oUYC#sjM$$BfqG zGbb1+P>VAMdUop6Y5Y?W6F5Vs=*7Cc!_-KD$-HgYDtOIFODrKM2b?`y|7Y{DW5@Es zx`-ty&Q46EKB0d^5zxOhY|*^ep@)wgDF8q}%v8B`9ynyr7!{8_WWb(7hA0Zb!EI;u zVSB=DgiSV^n!Pyl*)t_5pX7hAnxLo`7=Dg7jH9xGkL|^G)`?JReK0{^Fuv~*_$U$7 zQbcI#a7L|hEq@J%){gYcr=72JG7vu6R(``DtwSE#$}SnFEpx$1w7|1j>nkzi3n?Rm zUT6~)`E|LCE(YI}nIK=bqXvjT%cOfeQH_u?&G$fafcc4))&%T90MI>WMAy*-SW}vTTHPh9i`3z}1#FpwCV_6a0; zIhrxNZNvm8Zv3-+i|5Xp_X+{R==t;eI4xO%R&af%u3h!bzpuEWMAMhT88WrD_Chw1 z^ypCs(AFtB9|}<*II}ix?%cTn;06m{#_O?rCro$BDbsv#4yeCo0OZ@DTZ1R7Ns@3P zZ7~Xui0xkxWDMTpM^GeyP)^=t=8g9E!o`cBm$y-wC#R&mLO`N5c<`3Zn;Yxu>IR%X zJ$?83`YQ1YKRg>Q-?8H@V5gj%oa_;iz$6T6aosnbJ=+`BO={kJyW@G;nf_T>)7XU6 z6ibG&l=1lm1&#jvGf4eq5LB!;c30wuBqho4d#C7>8qS)fOo-fyOo&qD6zaU5yCy`& z(pCW4%pp&Su2eFxvr_?;xCMgE^R!G?usCUW%77YY-##2EpIlzl0k479S8Vs7UU-G? zwUqYfa~2u(AjhKK%`YwO>u)gr$~3q6^UuB3bAVIm1X=q8JJ-0w{S0hux&o(ZarvR+ zMcp739WWP}Xj+i1=61q3eV!yyuiV5uAi4G~1;VQjA2h$&fjwYtkW6zTdN9d=qj3SF zicXz7?{w#2e1QTwb^7#XioqVJ9j@;I%A;97Uwt?vLO#JhsZslz4X_I-M!oqdMo`%< zd#`}jqPI@&1g5d@ad3O7bOI(S)p09|yoP<`o;w6~V3S?N2F{V8l~pIno>H%ctgPG| zKVRS3{Il2q71!+d@ZI{L)_+mBD%l--_omWnZKg0f9T(RL$oC{e)=6-T4`K3x+N{d@ zghFyJ^)lMJrf?)|rqcaWC!iScqgl8fJQ%(!|6EL|ZlD#OSv}QNbKPmU? zk!N0-R_SnV!GGZVz@RLsq&k##R+ksH7nY=T0OoP)KJ^h~1yAMX^XJ_tt5SFesyzm} zt|I~zat}daH=a15+_)lgBb9~&nmLC+ueU5D@5WePwNh9k>VfS<*RXCXh_6@PSUOo; z8pfrwKMXiJY?gq2>E)%oX(aoDS-D&Cu>T_EgBW_ia z(Ih#qDHA4a;@Tl(;EJI^PV;hX1jln*h(Ic42-IdFdAfR zZQTW7_kQYd2H++vLtdjsHA;1Jc4+_p{UI(wpI22?CC8jP)q_Ymd;WZjSNF5B!_^+K0a4-qE3LdHpG<5GzOmg;cdh4h}sr8x#xjP7}U64RPuOlps!Y zy~_KEMx2bNPoGB5Y^K)>_0~-xK3VmEGk0RW+9;B1*%NM*{h~!*Z6j?u9NFY={x?py z)(?G45(2qA9LE&Gk9a@a^KqAFSX(=wNa=*D5%uTdsI&zOP-;6|LjdP65;p}Wws%e` z(76naT$iZWB>|?=5z?jybf(Fqs4Qeb0tVnMUMm-u**B!;l>cSD6>M-I`0ek@rdS_ zE*4#BSY&d>=3zCwN&6+hs1c*zsUnq9G=eYb{WQTTw5p*@_D=&+AUqNM2`uItcjL=kk zaRnt*A5+RnyAU0{^~Mc7iUy3wrk19aojZ5VA$o1MZr$#xm#1yuKh@-A@1|7%;5z1^ z5HpXMMBv@XB&~QaL}*?XKQ+9({>js)A_4)46@+cy-W-OBQl>my#r@}dcD<|6vEyml zNB;hnurLikfm2~&HhJ?xOr}gprPkO_NkP9Xw{6?D=$Udi&P|#$Negd}R-FenVZELJ zV!%1u0KK$B_avyJ3KY_fBt{(i8CLQFGUFW7+M8#H{u?~(6g!8W77rUfTrbrt&Hu;| zE=biCyW&OfpI_@pX8aM|Na|meG2UltNRoUNDk_ePRd1Vg~4?Po4hc zTK{(jVJvwKaq(3_LC@;4_wSRd3-`8_4jw!>-r|7ew3(%DpenRY5#`?~u)0{D$~9VT zi>t5``-*SIQz`G+v&ZKfWdKOuiM+JZH*el(4IMge&6=1mdhxVvXQtrY^CTuJYTet# zIU&=Vi&}w>6C3i)z}a*PO+~hm?j6x-DNKl8*G~BDRhxB-EMAtnW5+CQUX*BYK%SPf z<4K@$G_pkM+$VO#78=?D3+OL+1Mj29k9P|{e_qgKwr{g@a@^02u0l1)QSsV$y>iXF zoc^{6?%l-uoj7p}v5}ocAr{_2L4R6bUMPdCtpW>-s~O?!J^AO4>sNu5m?$oL7FY4i zP<6^;ygGiA>;`ZixZgzTpx+!b zabin42!ZiXksuCQOka~zJ+r&(JlaN3lru5uF1Efp~6ZZQT>%fsnFe&z`X)dv(3kCr{$CMyMAS z6l@Z8gmeK}|1K7XWyM3GM1Ak~(l7e*<^00J#m%=wN+w-BUyc%l%Jn3@yl5R*M_(yC~(VzKl7C9?%-zgNGa7>^&T@& zIX|&z{kYu?wKQK}Jw3e&j2#2coN2yMD#9&n(Mae!?VsJie{c}juqLrtiS53u7fG{z)ASMzOom~;5y(LyNP2V zY80!BbN|4+w}t;CQm>NGrxnIg94h9C?h;kqW)lARZzw++Q%PbJ+8JS=iX>`xqgp^T zLA}mcbOZY7!lg@N939m;MeXI}HW6z~;+HXtB_sgtyLR>FWs=5WxJ>KZ*W(M?g5~HC z)Wa~(Zo>E5zIAI;y30nwP?j~ktwSo+)un6@!MssdZ{{n;Spv39Xn2Rrri+F zfMT>~3y2%sTANrm^?gfTg?TN^<}i9jbM zrl+@@KYzYL^#DpZh=5kDTMO9&3%*47;$JVXs93k?&&e*GIe)K!MutIrif$1#6Q|oK zYaD$cJ`Fwr*C`)7G|!APGBTS<7zO1Vvuf2~NU+V!_|esl*7TeBt#j9|ry0)a*`ndg zg1CmjpNOplEUU8i!?UTi_oBG?RfzB2^ItndKZ(u~S*&X5`cH2rN2%8#59e_9e2UCD zlSFga-~Sadm=qqVu?-kN)#uNA{`{h%tw2FLW4N4#l+7&fOhnCi0l6q^j%QpRx;Uqm zI3K%rx8|^?ye*NIvk8Eq>OVSa+InKNF>L9=g*zy)lkVRAgX|*s9)JYtpvNI_kz4H5 z^AvE#vBFocWGHUG)Yi_SHx}(K5*Qf?|JnBeJKJk>5K)_?6 z6;PlE>l*JEDpgVKW0LaF>LnjN6Kh~%b;$YpuPzBPjhjgl11c4`u!dxpy?L{Zd()FC zzZGsg^-e>VDoFw8V?}edyrF(W=2AyTFMa`kqXo;wlF(^v1X#)ZP*}K`op!DHpCT^A zr(x@nc=Ki>?gFQb7DN#Fsv7_xys0t;9F)YmGcU$HO=@{y0`xMu)0f*u`I|(R$ga1G z<|JF)aMcm=li?>0A0{5Q{YRrlAz%_9rj)JX-G+mU+;6v5hswK0pFU$RdYvEm{!ALb znb2AO>C+f0m4`Tz^KG3QHR{>(TLw!Vk{M-3D7BsLrw8~y>)kC|E_hc`k_dKJS69Wq z#TWlNGA$LlOAZQ9^85ij=1<_;5Z2|stDo-TH9$?xfXZ(>NtIdbN;KBKOUQa%^CW1#%W0|z#P;=p*C%;|;&kpVckw20wC zcSNVx5z{Knx<%(EXz6H~eQs-V&V;Rn>k$KxfLFL1AJhnB_opHuQ=yubKlR&@T6=xRx6&TbgZZ9i zix!0_YFcLHqvOrCb;@i$g{-vVX?!tD?X#&GlQ-JKn7 z$D6i+SZc*?;CU%idoI4T+$364=5fx*?j zU=ILY+RSv_El%a6du2ZmSlF>+t$Ow9l{w4GYDZC)`SC$NwE*dUa~SwVXLDdzNMz(* zShOExK?m)bpo&!SV`u4yX4b90jvH9@fk;n6kN)G_!CLZI+{)rMpbJsV|1r5gay%Z8*Ys%} ztggFg@d^>$8c9=%@E*r3aGK5rI|FTKtZ_7f zRqOXQS8IE3C`O z8sfhss82rig$7Sl2goXit*;J$T9^a*NyBH)99+-fPs~i(!y@_WJ?pYaHsvUk2nLy( z3{RQbR47Y=IR_k6{qxT`{B21>uYz1hCc#*7_i4KZuw}pwk4&{uB~kg>n)TR{|H34b0!wOU+mPc-3u4xk+LpThGSx&-JM5*44|2%!$>VaC|l z)P{W6%o!km2+W&m8(qD&vlP_*T7VYP+(-8=2 zo;03OH-eHv90u;YJur-=r6tITcB|i|no~B@-UJ@GiiAOEGwQg!0<83`%+5#F<;4^g z`*d1TDVrVbeSFqZumzzMzzED6E~p~)=!g*`n2;E%#TpK(sg6iTL!KM{BwOkWu}JRm z#}d`vy-!i(h?OWQ>bv3jl8AQpR8il2eSKd6Vxi;cLMGVC@zkHHCI}`$n@imhPJtM- zXTi-uds@SV><6`-Ia5Xwpc??TBq1V5fmTw@HJLmagye>hjCTkdrwD|>y(w^Ia``s% zyi)M?0`!Y1vOd87KDBKm@gfjg^R7oZN)hz_0{*6sEeHAqkL?=owNOoo!{H zC(mIO704KxY~DKTQpe~fO`8fJUnf4nOb-+j70Jb?vR98-_*!P==5D9$r!Z?p7uTdo zlf=~2ak_r=aVMI?Br}T1RVbil1EUd0C3+~qNWKD4?~<|7*?BaA0M(%c+%4O-_3Yoj zHG;Z=#l$|UqtKZLcJ4HZZd`?XRL0v=E+NNo;0b>?3cu)RlYrkK*BvGL=Z%75G`jb6 zRRFgVb*CtiQ6otKZnqmy*9e*n?8Wo!*?IjfO{UzsbEgHj4*j+fu$QREMJGe5eR63* zThSe2aundvQ11f2`4FK0FSnm+SF@IDK0NCigHV$787LiTgHkHQ^4b3K5$DhE22L8q z_?%_n6!<5@Q|%h2oCyo_hMBlFwoojdaazkzVUvQ5mD#WTAT5Db8>zL8*BDa~iifQ_ zB(eR{rENe$l9Q7q38G9@pxg^>fgRTCgvRy+)IPZ7FcX)(Pr1zNt}M+R=&vg8K?{WI zz8n~l>4PF$(iZ5B=xpg0M!UL>0BlvgJ^e)3T|i%>xLE{(mu{bS2hZcubA9GVTedrU zL`V|=A0Fb)e7AxaYkPIo9|BnAS@c?@p{{-tTLS0W>LnoPDhzrxl@cMr>4X@2*M=$H zO(mTORL4zrj9f;EGg)4?DF%?n`QIy!uE^>&nXd5h&5sn7@L4%eJfIA^>;;1i+ghZv zwfIq1mXL1!(;Awsdr1jlJU;%Sbc2*F1j;p@H=2;nr`p=?qGpBHe!OP*Zz;>D%14y= z!Ez!~0{TVqrL?_0km_hNmLqglM4m7dwd>FhQC)66c~XTDx{YA@_GC>ix;_$OFZxuM z_3H~oTO?Ak*X*CaqN*-r+Z~YV<`Vh|-|#9l@Ug{fzSDq#xX4O^3lOY7c=l+tB&ayr zqOt3;8;?-67@qXx=xQ_}iTCccqDhWhU!%$Odu-9nJmOmf&d-ya=({FmojZTNHJ4c6 z84L>0Dn86yS83OIor_E2)2CN&zGJR#dXoZQ(s;@mK)o|%)b+Oor34%z8;OU}xr(?0 z2RcBFs-_~(5NB3N-(5*s&QhUm1$J66MWT}xyn_C+``5Ua+$= z=klUQ3x@Q#is}j(_p3K=EEef=?`iGS8&{=862tC1cyOEAJ&YD1Ez~+JBlo;bO~|MY zqck|Mk!Jf&{(g~X9ediaM6rG5#B)eXz>ix{HxnsjBs9$k5C%fMw^+Nj#yVo(ELECJ z@txpuZ{l-yfn5=G43F;EwJRC3ZEwaIUxA~f;2QDj{d?QIqMu~gjU2kx<(N9o& zj2I``Q|SCLSAVfkqKPh%SlmeB;%q_lESR?oQBg^h-r9`gJMInY;e@)$P*|* zWu#}<*L5HR9=g2v$mOY5T=k^g2iAvfdwg<;e1mGP<&pvF>T-D~0F%Ixrx)q?zWkWV z^O#atAv)Qz$B!SYrv?dhz@yI&j7UGx96ek7r$B{X!Lpvl-YwcP5=1q>vuHtUh zt`@l&_wNhcNQyg+4}Z5Y%#BcU!oY%=yN6nbtkDZIz1~N#*h`mcV(DmXf3YWI#PSs@ zHeu6t`=J|MQ=DP{_L(iqOEP=4UuxO7{6klhlx-2zL8VoY;dO!h}?i@3C;OI@{i;=+B2)%bGOm zXZrXNQzD0e%a-UPi?FANV?R0Dcnc&+D5;RwY~nfRu2@}lv9hX4WG94?UR>0|^Z^OU zlz!!?34a`HU@LG~)4X~A9&C#>@1OLDAyWN$Q-@E<$j?|rp~R^z;x<}t8bXPZ$02bn zqb!Xqw`Jd_8)iUO42p^VldK_fFl@Rc-tBePM!@BquN)P!Z3|U@SPl&`%~8MVut9Ia z)Tz8Fuq01nTlaqbCdmb07vI{Zr3NH!j*aIy(C50MJr` zo=eLvhGVgxKmWF*_mj^P|7pG>p|fgW!)3-}>_KovsU+F6uTh9PK}sF340JW8-I>Ec zxC>q$<9ZwJyo{LDt5ylEN23TK`82{&AQN>D3d_9^qDeuKj99d>|nF>Lp# zE?%q)Z7T#@CbiV3$#2Ucf0nOW6@D?o($_H5?`l-qKyG15h17ub9G=^^Zy$EZ z-+w11o%aUJZx>A0GM`9|FDl=qaAX<%fxcafAq(z4g2a4S?#+yJLF}0C>WJ?HDs5p;WgCnng&rfR135vXV*V~Mq-?H;D zOLv_iL*{$_K6z83zm1smZ3=cfDI}kAs#eCD8b1YoMd+v)ZQJ=qD4)Cndk?Y4%PPTL zPuwAf^P5rPh+LsXFJ3?OrywPBIvFUD8e9_7h{za@pV0%)-%=x;72|?WsztEIqn@q z$A`4_pYq&xV5R|Dan#r+W@a+_Atz{hIXBB2A@Q0ge6jQqFB2(Bc*Pa+0a^6I<;&sa zYa0;;Kt$brHI!f~y6fw!2v!c(wd$&%a4%kz3;S%bYI+%lzc(8!`vexFW9~I_WLF^a z0!~ohzdh=zc~@%kUXHt$IXYUG8udtvwOgS;q9!&;Yhet2*8~?uou4;nVX!fLytn8*ed#Wsz zAd`%Vs|0!ooR$PZ(G2pM7>N^%uqbn-L|A;(R6ke=w1|=?@V=P!a;Yk5kAu4P>~1tj zEyXAWcs$&<-q z2Re7|%~;q&L2@|PbC&A{w|zA+gC@#J1)Q3eawGLB`vz5CHiXg^BvPhvl=~o2-3>?P z9fQt5|Iv{K4VWQMq%4bD-N62?Ib)j&Cv2e2z)+L2vlWoF3B43c!7Ghc17bU%$Swc; zdBe^1)AZ6&lib_`7@p^`MvybZ37w=*np^asXa?!hPi#w;$}y| zn7QFTRadCxswswTDH~d;j8YQf9Hx*S;zchCa@eH8(2hT=cpXzF(2;fR{LYOF`Ru%E zl@T=`x?QzBAtz2xfU%LZ7@H793);cauuKGZ(|P@wesiehZo=^dSf502Pc}gzz-t!( zCUs&nQ)NxTQb~e?Vg~#0&}GVEcm_d(l*r&s_HA1LZ{!du^}-l!(Q%sn^OyC|9%faC zf{s``Rqoo=W>GEZddQl4V7Uy!wtLke&|NzEDP}K;w*oD@8wD>J2%0-(@QZg51Wh5s zr0N{J?WKlI8A7O2d@-N=Yj4jJvwX52;EwC4>Org?%GNeH?P{@=h zl1M}<(IonQXP))0_5arPzH4pU^HBGFUFUfW`?2r)A#+xE)ZJqjjpCfBwPveV6NkK_K5~8T8-&kAvOlM)2^K$Cp8hF5_4LjgV;;F089nK;wBXL2Gg&kLG2KA! zq1bTE@RuAo1eJ-0V;JR=(O1WL!74`!P2JEVN4z{6+m@*;PpC$)qOkbXsg9xVmz3v_yt}n{NT<)_B!(|aIGRw zUm|GgKJU@I+{RmC>cj}}z01hL+d=Z*>`aXTpRujr95V>nM9bA%Vh90(6`IQ_5oF}# z0*~9;+3f>)6I7{#@0n?c`8-3*T@ij)uWs3G$3by9Gs=J0u3azZyEq?WY~Ak~@Ltpl z)>#h|Ge*gP$v?r@1+_uM836X?;Ty1-6|J+x@ZGF;wAvdT95QH*($#zQ>Lt#t;>7J+ z8H?F|MmX2+!ym`WqzREp!=`-m-}9EL$~Nvy1atlPU+^&6<8;JqcS?MY)56bGM=xH? zAAM8bjLuY}HJb2TF0}8duN0&xBi$L?fNV}Oih>AvFdz|Dnkdfd&d0>$1WZgCOGg4$ zBeXzhwzQq=4A+_0o_9`CO_^WwXK^2-uLtjsP?ftjtYG+v5vR}Ioz(rb`LVLnz$^+1 zlBb#N&wBDJgD2&|gWCWxMP6ymxWgt&XM>g1-MrraQ>Z-|qijOL$sg(A{mBU#ndmK6 zH@SU%vu%mVnx;vA%w=}mFC4AkDdI*%(F@g)yKbU8WD?pl1K&D5@=?l+0iD~5p*E8}=t!r*AZ;R_okYWjp@T$7KD(i8fS1*x zbC)jfK7I0rXp}6kG9cZiBEqBMr`e8e4i58sImaw5Pf};rOI9*39V<9AA|kd^d_17G zzTa}c)9jr!oVjS}ZfkoJGc&Wmnwi79Rl6rrC}b7!-(oDj9HbWLPABHue6wTpaKHal zw+NgScJbmxU48vltQ@Y7Do#vToL=9c_l=5UZQ1PMoSk}Q1$%>tYj7zHcC{X);`w}^ zx);pq$w5x`*TD-sCLb^B*V$*8mDO1z_ri>fY308xnjh`|{Z~NuuK3<~a_UhO-x_teC?n}hKg2&d#5^9(Sx5@14lzn#F_WpfO{IGNSi?6P3Pi-hG z5fglLN*79$4jew`FyxQeCiBgx+UQb^g;rf*fK5gGu8Q_iHHC`UP6A=gzZp&R6~b>a zL->^&-PjgT>Fx}*1El0jJDEK5uD8Oc)Yzltx%iK143-tl^FDq49DbtbRf|n0_V4cy zIAd`>{W%kD53Y~pg@_)Ixxz5QoKjOaF0N_3td0@uLSJe*y zs7i`D*ckaWLD2TI`c5(T==EXL>8P5*fUx}l6-o*xIrsjZx(=v0B+($)4Wj%H- z9}D=?Q{L z;fD51IVpnMqesz&W!2m!j=`zgg`NTP^;KCZb*2U1y>Vhngj0IzA%!+(5pP}`Dlj!S z&l~S$x(2-eCzSztzrgo64_wjm%qb(tF9xWU1g@&jwu>w>B5jW}LwL_st zgoUd!uUq2I6B3pe`Q?TaZOnI=w@djaF8|hw%HIp;@7QpOacD7#6sAim!wWGoX;>br z(bH;*wk9}FgHt_gE6OFg>AXrINVrR8!?AzLEUUe4Y1QC{z4cTOpi|j}j{O^Q&$SA0b3o+xahG0pY1aaN zQdzsWy!a&+7W*S2RP91lou(<={T{!oI>O^ed;#HSISPI1Ssh87vxRFU3pmQ34ftT) z{DhskNJn&BCOA|S?xW&YA-4l7Y4x_`UF~60qA{MP z8ySVO9vDXl|CP@z(TW=$qZAzzW4Wg5_m2w(ciXGdZEvVk zm_vQ(nv4a3=4WFzxP_a_9-Y(LXR1e8nT>1YxVJCu%dW*lL=^8Dc(JGMA8uzqbxz1P>lO}!W8nR1D$ zie8mni@J2lRI75Q^Y(6Z0cKt$nm4H^cR{hEv{-I!-Im6y;Z3OaYz5!Jp4yf|#K4oP zL;sHYmcHbfL$FM^@b&Qq98RUuCIM4Jz2G1JCwuGNlRJm_1U7Kb4Qk!?k{N6D%)d|weT zV}SPKXvf8ti^)ZFxW|5MiDM_t36&M~Yd$sTmD?Lo#3^XIN{z~>D>X3~WcIEBS(MJQ zT@k6hc~{38>o;(KWU{hLzu4M7JKx@=ve*5ax zLc7X0j~?w$Zu%QVN08YUCcSg2e;yE_PkS+Ixs#dHb}cO}Vy?#f9@j<+g&`u5Ck*KY z;hwvY|E;sp*~G-&j3*txe`w2=gREt`J(DFbMo@qNkIOt-yl|nl1}39k(WQSsS`OCl z0}&(&ZaHQ()lTUp{7-*1HUBoR5!?2%4<$%xpR!%PJhjb{?IBsOa;(1X(N0mcqAD`% z6%tc%ji3N@>U_$Fi#qLR=IhtT+mvv$kt4}b$-{b=9prTE@9gW?rzgr$^1F-Ms^sh; znu$R_hgMi-!~(_JZ3{PI9O;8jQu<H@5gh^?t3 zmJdy9hEq@eiv7k5Xf|1MrvemvfC0)b=63g88_wSwF(P-!ON$*g57JWz9J9<$_L{I^ z_3E0}O*@o7=qoq5%}@&9B->6<3q5(5vS|45;mhpoqBaE-W@X7z(V4#SZ~hFDi%yn{ z;W3PU8NL1{I)T*MvyqXJrY;E%18wZDgT9^4dE%*Yz}HuH@(hcr`DTl89rpQWF{!0h z>6b+SFzda>3|^#n+EMRb^}D@l$+wxG?dJ<4FHOw#H_eAyCq|wUAuMeKIHdS{X523Q z!i5WW)6?~{C)zY4BprOoVwxTHFIuob#-rTSV88s+=fqkZqa2rEjU|sS5iF(1 zZAJbU+7Ixa+7GhJUG7##3zHodn_i`*d0O0U{$z`KWGE6NK&5vwh(xt1^Ra6|&k2sl zlapPOa!=dY+0~cYaHPq-&vwkxTQnYeM{)5ArGsSj$Ssn65V^E5czo2aO$2E`fIOtB z#`&8pTy0mZcsggztdQoD8)Zo^z&!B)GhS#(%yuGEX{WC=x|9BXr>C zovlju2hL(#XVfDk=FMt5yEiL*)qi|@(~CyZCJ*BwIbq5|sh_7hrD@(23%ls#jklb~ ztEt6I&iqGR{ax+>&8UOx$R)Tate#+{C*yRDnv$oaDf>9@B$Zu8trdRRV@Fx;pf&lp z+v#uF_oTJi@@@8~YuQt`Z@)Ew=$clg`F4!o6gCd_T+8I>^r=&)3M&&6qg14q8#^YO zoifx`Iro!+YF|d@o{-Ti%gUl&0V#Q)>uw=IZ7F7asSR9u5pL18dHp4BD|g##WMtsFEPm)Efw{w$z4b;3>Imz+xh8^qN8gu|KE6|PqWPO` z;uIp2B4tx-7nLtHt2+^q)TQ|!KTWv5ax~{+>RE{kuC*Cv8`4*ZF;H2QP6fIFn)}ti zmmodZjbD>(+#4YKQMf~J#{OCC7P8phUQ@7Ina72F2HSA9cqUi5GbH5#e5ItFvk^=X z9*u7hm`)xvRn@n!IGLY1%O(e%skQSuszOvKcVE5gK{-fbpFjTS(W9F0dvq3`E6xJ^ zo1{YGE_nvB(K4GD*0T?L_vY9wFx3&G2~z25ond-1Py8ZwPI~^(+|+dK);XMiAk?;l z5K8E5u(LDBJFC%Gv`&js@HQ3#nskn^`l>7iyKNVqaIW?Mlu1j(z=0XB^u_w8j)1*& z*nzgRlp%kerEe6B1Bry`g3zp}1kKu1SGinp{JDr8zXY-^WUzpJfxPF9ANF!qIS0m=(LGGsokRu- zx(DDg^~H;8lWTKdQ)rmAe%d`5>I{IC5r*Jh)85si+t7Ax zTyQq84c1OU%bn7dlOP%;jT8yt!_EE&W{9b6*r{92tP*;!ub8W@sacX*lb|}ltyL7@Ba;X*U3yP@9J8eW7Jz6J08RxncbcE#=}neu z+#8_i6%fJbC$^s`aAlk$xbT+q+oeb1ODMdRQvKsVVE=X53v)=}z*wPh3OO-VPV549 zMiJ}C-u5bC-I4#T!~eXPeP<#>tCn;+x3KGf6E$f7T&QDluKDidPJ5JvOn#EgmKQl74Aiu)*KauxS7c(oGMIi5Y;#N3Hl4(c^-;*`QjT?8dox1VB zWyHWuGY53W5MXHg^Ts;@f+(%F`!gMo!{l(BmeyTnA87Q1_0FwZTHv8Y%nSuIv2lKL zC(z!6R*Z?Tpfmy#Od(`}T~#tZ63$4Yk6wE8+iu;uLwAn)W;3vA$Ow`Z#*c|x`itNw$*Yvm)Y3Yn2DtugbMXS zNL1vRGM)OEK0!t zEz61J+XUBh+&D0n+VEd9xq9gXV?LQ{4YAbHZlVI8;NQQqPtn(}52k#NpHfZWrF+Tw zbZLfd|G@j8AFVhDt0NnP4q*kL`zKUd&}v$4*;2jwW?y|cT6dvDR({V`qY~>);r!4w z^e50G14!oMQ8mBcBY_>|@O1&ytp2dACKJAjA&+`Q(t_!8opq-7gKfRA!?zx$c!*M zazPxz_(1dLC!uw)jp|(aH;sIT6;+HTB@%&E3cbC=9fzHFU}LQfP1?Fr>1hAJf7+Li z^WEy+lq$+7=s9Ub>?-UiWs`rP$sWcSQd%N>%21Ex*7&G<31UBgHL;wxpg4Z>0G-Cl zDeGR}=p+%vqhNoDp|oN3&UHdXDkmqce5uGnOQCO{KKp=!|FWBy7**Lb(-!_=lP61& zNig-0l?WCjCQvN;o)spfBurgfOOD`?ekvtupL5(c*pF=gGYlhF{wFA%u`i2A%0@Sn zIHA_utbD0O)&CU)dKN7~O@DfomY9%#1K+||Ose928KXCoa*vayvn(*cyg_=ep|DzUxdFMp;vd^EF^CPqs z-2OB=Dfybm;gYO`R|A={7%R5-(k<4#N$3hsS|1mYj%jdZTfv?#{sr_(N8r1s7#id* z)D@?5{~WO)n}Y?jmQFPNRJ8w3>Ea|MCe(=hSA7yO6v)k{Hq55tUqIAY@QsxeVj$_Z zh2eTvPDx`oAy;|8fRun%FrLt3nu10cyQ@{!z@m{Mt1<< zKMi3E5~oL_&E_SpdPw4q$Ku$6-}j`e zBqYff>uS%=aGf|>A|&O3zb<8CV3>k*Py~qR>pIoE8Tv&SfHf9lSGJAvCtuAZke8yZ#fquCqk?JnU|TMl_P3AHG&Cr zX_=Y*F>ZqJ>x`SJ+0CRG13b`;DA$clvEQ=A`|o+i*$>o|rN z-ySLslAsGA7^QO=R$f|G<_on*ZV>BcO25ayuh;6YCu1EJz2v6oTBR>KZR(}%I7*^C zapH*$&oE|3>?~XJEH_sl#tNq|Z0iGjcjkoZ^bvEv>g2wYT!$;Ro%f9)gfJwr{DWP2 zUB_tZbPqKL$i2}&q)Vac)FmdU?G!tWg6uH5=8j3}8ZLCj0c+OIT7GIOJY<#+=<;qs zX+rm=cK*L0#fMY zE0-}QomEc7keC(V>^>&_@hx11T)qJXeSgh2iP|E63?mndhx61mLSe}Ae&Iz3;~v-+ ziOVK|T*qyAYcX^1-p-Y(ZPS2ibt(~rx#-#4iqz917+^oFONeljINK#Y-(u>BLtW9{a*fbV#Pxv?feYjlX&0 zMrA!MoaByS66koA6|VM&Ct1*|j;N6fZa8%K@EM{5vj@}3|DF4JYRmxS?0A!&CeOV5 z&AofxdtTe_c^jUu^=~%QUd#)8xOs_F*E9L26NND7_U%&(zXeiJIaz=}3d!Lrvo#rt zP;rsHC?CO#elOO&O8X-p=H>>aDE<2N>nveRkj;~m|6Cn6@M+6)#^K72qp4&HEvSlk zhLqSqF3O0Z82CZ+F-quGBOo|!TNtU>(1J(xV&IhiEX&4FQam1@l%F( zyUW`}<80H$5~xR%)D-0)XYD!BshWwBSl8d%1tq|yqRYjb9qMVo@C`@(Fc86x12#wq%#!=etnj#IM?hpw@=4eHDcDqT>cHiEqlE3z;%P~D40 z0zrv~dPb95RK*4$FmFgtXQ>xqLz`<=x~qPFe1%B_MD5cxPO9iAAGXoO4{S1}re?%7 zRl4oJl<7N6lfXIGBKp|1tAbJBGC!jk3A-5p-9Q>ig|P{%6*9Ln!IA;~tODQk6&(B1 zlnfraXZG%uYp*?>NRf(RqySO)d{+v9Ayw{#w<&)j986{;h-}Ewdei|K`Pj!~HR+F#2^YB!t?c3%_tQv%ieH z4!qCi;!DQ5HPx_i#&K}yw#2RN^CdZsoR6^Ejoe5_%@m$ZRr${!KZ>BaQDc6;kEb0N zSWZKncWd}Qj;Du`cZC#(kPd<>wt!GcwPCn{fo0p8V-Ruh(%p}?vAYl{p_A3IRA3 z)Bbt<7MKq6q@cV$!NI}rK`NaWR&BR6fMO)Wdrl)_1I!Iv@DBzvl;H;~LoKkg4i-2) zl%A#5Z~F@>54`eg~f5=M7r4GtL-NsNT(mLIA(4B%9bU%fE@_ ze3@-LlG`v#H+{I*NurBFS6Dz&GYsuhd)8m)4!v;A|fqG zYs2dFPb`qBpMZv4r>XMYl%QXE(XG{jW>wKfR+r#?cIV;4eQJ@B`5m4+tB*zpguIzS zOqMH;I_y9t<`OMgSbpDrzr}@Un;o1e>^N1|nrP2+8t4QrdM-7IP4oym*v`sB-Xh_h?-KQ)TJQ1@ zR=LYFUZ?_|!7oGVV%r!N5)3WB4l0j1+$3#7%L42UC6d0*l~NnfXn(8*BhyxB0@Hla zqg^4jv*<&qTUz}!j@7ELv?G3E>oBZi`mn+^7z!#Y#3&w#vBM@-pwRH!Q>8Phj-8Vt zmW`J*6EOLpfKov(PK@8;Rm(_U7S*)Tjz_ZcD;Qy zDDg5ssf#xUP1Mn`uukC-32qnGwGlKUm z^!`h%l2@e5(xA*L(Ln%qhw^n3@*+HEe6NF@SlxD)nq@XuY8jcvzNY)d`d+H7i+6@J z?LsQ!Ly;h&KA4Hb=Fc>-VmIH4_1rzg7vn1kIH`a`EHq|8E-fV>6EvDB@;+0c%b4wG zr1TUr4Ugfv@O_g?XM}hGiW5IXu$4)!DQfRNYTQdHm*RkqMkt3id%M{y4 zL_2`wF&01Opx;cc9oe@=Id!{0u#rIWhuPUeJ?8R}%Os*F!u06u=b>A~LvPnY^4!^a z;NXs4!@P=x^B>vDxKgiY_wJb~!@KNFpO+ha*j?RAz(W$@F=BJ`pMRS_aXZF8kNzKG z*MA0`6t~?o6cHeAtSZ(QK3ABvO=l8wLi)_BmoJORG#SKEb!=fRJ`cXkP9SB;%&C)2 zH@XX?EoyHw6x4=ZT(D&dEpSI=+NE^RA0GpHcgo}gC<0|>O@OdRhc7(T;q~o-JZ`9; zzs6gA(2drP!hHBTY-qvq!JF-F8!f|jX>@1(vF+gTY0D>L*Dc&8RQGz_zx#%npogwA z@+V4&R7J6V3S*0*lA=r@?eBQFSI?ejNCr2ye(sDRVBIyePpUbStF{-zTb-<|LlhL2 zk(4SV$PTAI_IyXi>`EFn`E`RO49i}|E=NJ~J~yLdp9!9XU?Qi?H8bZ+&{l&YcH|Al zxFfc=yu1Y2ujDo`UENzNbTEozR=0EOEiCb6(l7}=gC{P!lr;J_#}tH}!f%a^Z|TNK z*w#C{0&30rZJao*flS3$;rd{j@6Cs%T^u&+ z`&0XMVpIW!;03!vq8YP?*8IIxJwpZImCLyj*-W^{OI^G_4oXRJkhz6$m>{4;ov=Nm zNF>sk?(BIxSCX8UEv4 zto+o$i3-ty-1iSUe0b1HCCTi0^VW<$>X(Gr)}sbe{EJr=Nd7AANXc2urCWZXgnz~U z(}$8+(orD}6$5XC;(?U>4gW6>0YUO>Xkm^VIM8VW5~)dVr>h2C;jnzSuSl%kf4-y3 z-YuBVwRT4sI6B-kqWs&x=r+B5zy(u7!`q;uuej~^h4IE%jCQ&yD5QZ#9s#v|x^1g( zAV0Xey4s3!xSIZY85P?~j)N7c9$nd-f(z6BMG4Mz0{q&$cdyl?#!BfO6jetFcu!09 z4$MfS2d>{t6o18wd`UssGOzjOe@JJ*dVhUk;(gaY^=rmbi@m_2V>RI94;_K;weLMH zz=f3{U-@`O3DJQXQGh3MN=?kSG8C<-uRLnlEFTNaI{7VDkS)J-AF(Knxk3*sKPIW- zXC;55ICK`CKb1AO#PGKmiF~l*gqf9D5x%wHAP3%G$s^=Y)QOVK!;ZP-EA$3gP=*{A z<7-`4L!M4_LBo>hg5IdH&QJXs$2a*Al{C{GekT9kquL^N+0LRxuNXyD+w&f~{V-4s z8qH)c`43s)XVXp_C!`Kw;+m%18ss3xz1m*4fOvJ+XqK&Ycr-x(C3Q{D)cT`*K1} zq8e{%y!36%Yj1O_Tb0_s&uE`o_2CN&?c5q8W*qzJMZ7J0)j4v$6@yM5jbs7cy_unjsjIP;a{rQ7iC>zW7_^+SwUu z7DP{Y&3EZ&Aa6jvOjX`xGl_e7&90Z_A4&@nh}3h_^`QQP#b`@{M$G7h3uym`YHkS3 zsZOTb-PrFgs-W=KI%CFk;SD=eQ78g#M^yijKn;=LG**<&_Q#;2ZTt8v#hgXqkcoS+ zz#$;8EdD%B*fwxCg{V*Ll@Jru)N7CpnGUp;080%q)5`P2`bg1A;to%To>~QXn95r4 z;ZU~Ty-pM7Rz-^>Oa_R#5()jdbA3thti0MqoGj}54IABT0%r^mf)z{93Qac)i4fXV zp=<01R7J&sqgN&eBWQm$cGkM)wN3iFMRnm^o~cRW4f5vf#K5WNPcw_QN)nwvbyk#- z`mwH<=Ln%O^jvw2$iXjXgc)PjQ*DPIc1PY)@;WdMasK$AoTCDNL<|Ii4+U(dvv@om zj6m4r0tf7bm1q(%|nH{l$17ntLDO~tc$le!Ma&%6tZ@a89#>X(6$?G|2& z^!g0Y?&AB<@(Xpb&=FvWa(Z5<&W|3)Nkmdm1-&4LEk}1Kkz^>cC(s`+Ky=aVni{JC zqaEEDTQ4VdJO=!xUIY5vPZ&H+ihX!^?^#h-=Z?|PNE0S{I6C)66(>&QBC{iPB3u=| zeQQ}+a_~6j_rjb+M8>i9-E({P=pl8n{>%&|-yDJfW6iR!nW#8|^2KV*%>`i5#Y`SW z;l!-jp9tLIV*Ti8RdPD|9A9TV8y8ytCMvXQ1`90ZUEmvt%^XgaT~q1~EJp1@Eo)kH zIt+M0n^@6?lp@?T{+EhyPY!W~;i^y2V}FUws-&&lZ?+JmaG_!jNA3P+qSC)TZ9u7< zRXggGyA&0IZ-OkY2d#jI9fqn;5RdDChN&+7QVbJbXp>*rQ&oG$jRt#fHt4&)!5=F= zX$heICd?c~eJ%n5-5RTYc2m+i!j5+i10ecnu1m(zN|r+NJSXq?6OFI%N@^)I`J z=$Xb#AEpa(PIhbh<54t5GWp_f23Ynrr}4{k)}c(KcM-e`VQC<|M1jHVICFVIl-`W%>5Hqn1r6 zue?@lH4#q|1_93t=9wv4E#QV>MPgLy@Ll3cBH!=@iPzN*s!S}iN(teSyi{ zGR7O2oJpT**uD;k7llyUd<~Z+MDa+6Wqb1R=B;Z4L>lIJ`~x?v&e_IBRg_&RQ9~`d zs{t5gl$sbDOC&TjrFPV-M)_-aG(CSh5!XFd!J9(b#?lZR@4QGd5>4qzV!>|8@0!IY zGEIMK_h2o-wBO;`)MKOALO!i;ss3T~UQA1iNm2xa?(NntTe;Fx6ey1^NWN=tZx(Hq z5@;c5fsvzF`2#hrO1N`!D{%HeD*IvAo#+LZTOb3Mk(Iq;8Mk%hpB@)41=E#c;xyPw0tZ#9s zg_)R8{U3UPRe=?;DN${+KpKe{!0jW}UWX@w>Ap@~k#v|^5Bym!L&b{EEnl2~7F)1} z{M5x>ISQNqoloA|G7oed*wU^t$)O}UpBo_N$)oGO!At5s@88O{CLEA z8#j)^j6*+f45{oV!$-NP6k{`8tcosi~(Q{qzlbW5zC|48o8fRK)MsD7LIP zXA*Z<#_zGm_QKp-vW!Ybc#~1;NQu?4LO~Cp_n0Xc3QdbuKR4<7R&29vQ{45}zzeF0 zQ420Fo?Dfeot@q4i$+pmf)4dV)IY3aq)&5?^*&lWUUScjA2+h@7H#%j?qEje7u2Hm zXLz>rft~`iY&N&Lc5JeDe$H3a~Bh#$yp*4H{4RO3>OTvH#c8+rCz&b7Q+EJ zuI+SCE%Mjso$6i$1C$6u%uHi0T}lIjt-Hc{!qAS;k9bwWD~(Yob8eyQAvh5j;)})! z+e+t3TW^%&LX0COJp>6@2T1UNqoD{iyA6Pv_~>x1>eDB;{lOYt7uq=JOViA$*?5ALtuj7ui$@uE38UraheL zlg*t}di^Jgci#oZgw>(QDWF9ZFYYm8G&RKvRP1rq3KJMA-Xp;2{hdvdYVP zwF@8GdUgoQkq}WB>$tvG@n`xyi%3Suu5j4p3^+ z=hjf|FG9cEg?h{Rrpjr@bl0_KXnr6bSwGgH2iUyp+6L8>#_xNT6u4;5Q?$ZpQ+PTI7L0R`oqa_uOHAuOZrqJmZQ_~3>sf5& zyeqP7fk|jb>I%k;g3Lw|6;^pdWe$*^$|z8TB;k4l%|$!crCH1L`qPW3Uc%=J2%cp_ zLIX3xHEkB+9{L_=e`o3c34xJW7I$9C~vq?FHX5o(o`v*Yq3LYCi6KND%)*6l?jsHDi zt>F_n)>WR)FS<1-w=lQW|A5*7`RsVy&$oF;iQ3(CdR%;bI&(;DhskfYiiM{KxL9;G|v>= zUPynleqqt`p_*xk>UG+%qUwD~Cl_B1af09El>5uexbc_)#>zt_DWF(kE($T(^R+L0 zWPgEqdeL=sowTx=h31 zwG94@ghw@G$PnhZVfik7diRz{;3k&ZQRrphXv0UA0(Ex90J>re)H-jJ~Pk1~BHXGXPR zih808w)!aLMVw4DAjOMW;!R8u_e~g_Zs=^KWSc%Y3Iaf@FNFG70MjrR)H@GK&z?Dh z9$z9Sw|7ECW>%JO4*iMs>q*%2=m_o!z#8wZa%_g8V2cFD*WYMB(aW`$xTEpfcPEo5 z--m3RMupdd4IYcV>1g>MGxjgL@0c+spY<=_}yZSWLh~^&xzsY+8E@ z%X~qU7iebdiDKrwNFLGvJ+s&WFUXq0h>=`e#MQ>PsJmDB0eeW42ILlWlj1TXUZIqtYz<7chK$L{J}s1RDr^<_E^G>b3Mw@h-0nh ziAV_-6p#O(fOG0FU_U&jb7Zp#sZ`UL2Zxf0)G+6?<6*MboY`y>oA}xruw9uH9 z56mb+V2^-91P1(N2a2dHtcc+#0yv2{E%Fa8WNe($(WL})c5xXhKaYvQbF>eX%`NGE z>4g>+yfKrTJvTaof|>SUPFrrcJ4o0h`M6HOFaby{BE($JIh` zsp-zeiBs@)+c_%3kc$9fVz*7dKY)-Yz$alPASfvJ(|eby^zO7sLXHq}YMa6IL4g7x z07(*SyXaaw3TSnGxII|9V$YsqU%l1uLNW9hEjb&I1e@x<%fa*D)WXRe{)$*O7`vWF z#m{6fN6_Kz(-+-h1}`kz#9GG#m}W!rSOHQ&?IMhLh3REk z1-8CL$#_(IK|q3JcT3B{sU+yaxT`%WgeXmmviG%3$NTVP4nqss7g1QumFPfOCr3!T zhuFL);?MHmf^jjcq5Y_7xXJfivDV*bx$WoApTcA)xiPe>baQkg9W^&H;L}TjRBU$o)_Fg1xK@;8uFr+tSicsSU?lGBx zOspad%)|srIl1e>83RE09y|P_VZ3mm4zNM^{73>b@bZ3TYs-} z;lac6hIbQFEzB?U*f<1-WgnkI?1cdP*oD&tRPH5Bwb6du_9=J-tm9p^lT_E%uE8rT z&mp)caWfWd<|=sSRVY$^BbFu{vU{6+f;^{wbk6zmZwFdqcC(JcXwL9%V?b>j81nqD zWc%DJR#04F4iL*5kEM#df^}{z;2Po>t@9TyWJ)fc0P#Ocrk3l_VYQfd7sM`?*4qAK z$SqF5FqDlo;m{A9yqHWLp%il4$M@cI?bf-cgosu#tD1AoQlw+AaNAEMF7}X|XQqc6 z&nu>7N2d0B;!x{-m<{BClhml&(;1Y$q=w5LyZ&|EgP3rVwT)I z7{ew)%?*7)+ctm$tzq6kYh3sOYtkA}(<}Zu4c|ud z^A#M699BNnPhh_28j4k8ak-daK!RMdv5`6T63Gc81sb#0@F`o zd8lerlbQ2tNi2}pRqAPRG)8AAG8j{|+*X{{HrWyi!?F~(7R}F%iz1s}lDXXPG8JN_ zgPWUMSoNcvoYF5Cbll~G@F|PzsGR4h2C0@`hnAQ85Y)2e7X+Jf?b<2)u%=oPaQ`}z z-vd~aCGR)0%c5DOb&Mr`i*IZ^{dCJ<4UIz;wY+QD7yJ57I+>zoejLG4y$;L;Rkv-& zHEp}ev2HQ0yfA5TiIem)(%ed6LVp#*g$XYxN9tVTL*>}eWd#Vn3}kX;OyYOnqNaH_ z5yDs1K#3Zap$H{BplF;ReP!q5m^b`dYeGOAHe`t7pxS|f_g~V39>Ee*`ZkcsD-hwP zNi~nOM*6=0{XSIsvwn!oeBbt3XJl4X_;#MEkXEQ~6=UQ#;P8NcJqOmT{d(r5oT~T5 zA!AKryZFk?GCDU?E9+r}|F1XB8*aAtmbWjA$xD9u=I9A02Z!KeuTJDt2QYCko&DQS zZ8o(=Y116onpM@+{pq9zK&Q!FpM&w)eRA?WVr1C<3V6dy!d$-5r#-#GKdF6HGE^|O z(%2Fp1Y|bbsoTXaoy+m@K@Ck?FlB0*X?NJM=}ba~-l|`d-}Wm`u}x|EbL;u<+)Zz@ ziun;MnSCF3Re1kpsA86P5>~WcvExuE7%QHTn@XD3dmjgzQj6QE*)i}NG$LB6k z)=FfK;9c>lhDaKjdlGVm>T%BzBYh`rEV{iWZ{dl+WMI}ICf@qq9|mk)xL4!ya)bWs z#Xii)q(>Ba^JkxUJG$88C5Om#aZ>RaM*{!T$dFvz$2hJOwWDSYzez_-N-Tf^^sIqS_p^70Zp zWqzJa%azn+B@^bdBjC_$?c#z}6{mrX?nenB*#IPFA5)-v8UzmVg^+dOb3dcRx{8++ zSz*_5p`yQug=;=YaZ7J#+P*jxIRfP0z@MY|PP_Y+Zkvo6p@L#N_CW(x%ceupc^q zEMGQ+T;nzN{YScXZ!+kX(ii_&BdeO+=%vT^i7*CKaXRihC*6wU=idB^j#fvLe(}U zdQXCMDUND#wEEaUD^ zEd8!0!&{UZF$^xYaOGwMP=%=0r}|f2Rew5J0m+lghYlwZ_62?dxD#rr=QW*GAQhn!wSeGCik`tu(I z`)Bq_{zA2V7goPbUmr8&)$JM<0o}O z6R|ak`J+G=OUKcv3QDMGWMF-McGc9>WLLI+*_IM?@jUp15r2k5Co2Xrt*oi>5}D~T zM_X)-7uJd4HNI~bGgo@I1jgBkK^9o6DP?}ERcv< z6Ysc~axM*G!skEaS~ek8?|r#oA&_FDxo+j1lHp z65;UA6gRf#)hUf957&-3P-TzXz1YAcmOmpVd&zP$Dl80Qv+rm2{~9rdTq}8UTVvQT zIlwTnksFuMXCY(vR-I6mmx<*{3DYyC<1phh2tDJ}^#7CU|HiyOa%fSCdFQOT4o*1K zH9si*`ExXC-8%1u#ZdMlDm$%Q{K>lEGAfuUT?pJvz!T=n67J_6fs+$JX3a^6TzYG) zc-;g(T{bz0#X(eN&~bH~-RblPrvwLgr-6}^;5c|X(706#DF}>0R5r8g5<$(NjJ-{d zS~AytlfAvZuC8Rn7MeqWThQK*ug5c~ErW$eo|!OYG;E&BxNqzik&rL}qU?B~JMIXC z#ny~8Na^DO=fYvzhdgHVL&*f_r&do0@w4F0mvs~V!%4DGl5oV z{%;`xQ$Bu9W;9Z^wG?3Ycw-u(jIDtZGG>NO+%Xm) zIrC^;wy0>lH0Tq>q!CqFA67-52`pFiy8=l-3G(S*p}rUzu+pu33nAQS`C|T%VdVS~ zk~@FqLa3Yb#F-q8RD0l{H^Fa0;YZVz784paZrL)$+IlDyZCT0M+=#A>4L@DRKfI{Q z@%Wz#KCAeOJ`HVE92p?d_~KjUD;CJneHph}U;Il(h2)nfZL6yv!&TnAqI%_wVS+?l8$6*C;9rF3E2GAEA*1x=zW1Hexv$temco zau^~)7&BjcOrvEBDcZ@?(a{~4o72uokqy9ub%CSCx0obx{8ckTq$N`R)=!TopFiS} zQ@Shj{miboc97RR$;#X>(C}35%lWzqWM8q#b@psTN;-@#pRf(w$05l4!lxy$0)4r} zx+wg=X|iacRcOv0FR#{)+Dc6Ps=k-Zu5{Ff?KL+-@#_|pMYjpGn4j$v_YAD@+wYop zciX`D;R9qRU65LT3(dSxI>8QETbMY$=h$^aHZ9>{i%spS^R+Nv6svM%S~)<#m;BjQ z;hhijR8Gw@c`A4r(PTdj^V2KY1vP+N`ivf%_d#r3;mDheGUv&z@EhtX+||W*IefSq z-VLi{_w$ZAS;O{KoTWfu$|r#j7OP3p}8ga{0BLv4D;vGlUPnu(Fg~f zmzMW=JfN=u;CS4{&AsLCQQ{SmkQ}Q&wg--4Zten4%GE)u$vj}&QZ`+QkVQ|#veui% zO(w`Ock}ARCULY@_)VJ)Fz0xi0#ECxcP5UYUrd^he1Ag{{Rn1P!!Mr_;_9x(d$ER0VK-e&XoSnZFWw6~;~fj7rvFHZG>5u%Pe+?+E)+7jl!-DMd@|)f1^b z8>d57=})E{B=M%YTL=*JuDV{+uG{-wrQo{kZa67X#w>g#@Z34psGonh;{RG>vS3x8 zz!N77c%XAcOGE8 zN)Fs@&y^bXK)SJF%x~bXl8?PK*2b^^8>$Fbthdw#_|(OA1AH-D&_n+(>TKEVo4B=*3NZBDTBFJcP_=#xtfd2DO>#=}&%hqx)ehG|b%6Fb?`cp!}V3 z+dkTkhG+f&`~=W$&glL2%BtC$OR~E9G!{EiTdQn(%^YY|^59uBXR5$H?3_t1+EmtA zre&H4*Y&Mhwj7eUn&H;zdd7+hAA`Mgm6hQ=wUnrj9Xp7C8yLHaerdq4VS8a-da}e+ zx1S4gF}xCwm_(Dw3{qHZG`JkpW%RE%jI{=g858)?VAiaD+<@R$b9pgmov5k}YQ-qC zcnNa(;r7GTw|tyKi*on=vEX3r1-HsbDAu}!=h;)(ntgwS&+cK&Xl6`IA>#+oGHv;u z;_~Y-h7hwp*dZys=};arwZ1rS1z^uqs^~3C;7i=&%vy_j(D;^v-ObukS~{7~oWYcI zEt^kIRb^$sz3V`rve#XVjXN7$kBd9^3%d7bSF)T>HLG;HEX1bA2y>T_$}IOBJdHp%!m>sZiN8;3or>B zpX0R(XI8P=drm(2f7AQ+Nm~$v_DTS|AxB#*_9~n zQ|;&PKN!mesNHH?&Lj}7uE?64ZjH84(7!oq8dXJ~)5N8WC z0F!P-DK@poA>%$PbYvteY;0x`b=#_(^VauWGfMGoS5Nt`1=l;$?TQ6Sr~||ZmZ4=5 zpqaB3pq~}WHBqw?Ye%t*1C+iG$1K|V*?&rYzX~tD0oA?OY)pDRZvRB=!600lXB$(J z=uw7AE&X8UHaFx`P+$MdUHoY(q;X$XU61S+h3K0RUie{s1B3QGd-gOmH{U}AzO?&q zGZPc5Cl`CX)#L~`)_&{5r)D9p`Mb3h80WyZIMlQ14eovuEk%&Is4iBAW1Ax_X{fF6 zhZW{7??HtrR>o>r;#WRcY<96Tvue5_a|+@5bjMVRFfbK{Chzxgeu}z zeZZhcP$@i}Pq~rZB~-_4sLX?V+AlpWgk~_qQ`tiDDfx=Y*zB6Bsh@?02Z%r?d$peT z>lsz_yt|POzaHJ9MT@m9*Xg>N&gjG}UX0tP-kCjju3*+76I-POH$z33$M-7^9_m zm_520LCotpbV*Mj1tD*j+-9)Kn{284YWn=GYFJb#i4fPRP5RlO?7OfDA=ZTd&`K8= z1rjFNYM(P%0|yPdQ&^}3G&#DO)O@^pj<2PhlXu1*AW9&+@Yjj_>FJyjkfHwngpw41 zq{9l56Au*Qzb5!`L^{*e6G@0-@@SJ6-Ck11kVhRE!Ofb?w6sIRwhw&&s|eM%U}!Ve z7BX^ylboY**79< znW<-%-!UdIy95gu?kt6HV8~#qJ$}3BS4i@ste>9Ci91wfIjwQ=U2u)AH4~-YDLzh1 zYsn9lxRau86C?vK0Fr9t|Du*ztI*gYzCmjZv@W)r2GBV?jrUOnXrV$I!-}9(1}~759_bu!25`k3MM4DST;q~6Y|DLC zGRwzgce$3GZ%)JY?84&r@_HCqEjsNZc`Hi`-}`i;Mpfb&7qABQlpMZwF+BWomD1U1 zkoQu_MPagUyL9f%n%v>l3+NVwmnrKA^cvT%UOjD6@6jTvS6NPR9(|9AfJArP>6uI9 z-7tNk2idq^#2e6{nuT2~s0ruhl_L04fAWdX5947M4+pGBju@%Btc=sanNT(QNHO}U zfix#p7Up070hkDNRw9$GidKy+HHU`?w>o6I-A^b`tUv7ZeDB_0q^lYkT@cO-`j_~pk8b+T zJ2f6k@pJ{t!(ak5a4m{tPYLmwd=Ipl;wYb=NC``z(XH%H_a^f?rK5>(LnEiFmNtHCySi)%x{bfHqXj=9GHDDW#ALWGB*D=`VPGhK z;UY>IL9{!!=*=0ik3H?!{r=3l>{V1O;c9mi>y|*TQNYv-OHD#Ls8C4K0f?9lII;N* zx|kF1;29&UM19X0&>1>mtbdb49%L=AO&J12HA~nWy5 z_iq~t+{iKVQA6Zk4_iGo-?nesrky;v@4CV zXwvam><|YPkJ3-f^b2)aW(G)dWHbo`2#{b@`cUoLBPokyhNjDx*Da~ckEfD%CX%Hn-sL&@;RGYO$rJOU_pQ(^Ei?vvhH~74T3J|(C6Vx zG*PYDs)m2t={8jK6wujP;D*_`YCkTxjp*2FfK^}fpctp#on5TDi|I zzL$QVOqjIq8EI)_ct{HljUC6R-r+LokRsdMzh3qRSMxd8XPXOb#Jo!A9PuIqUPRDm zl96$GR=iu&G&I3;Z?0~P@-4D>sbSVuu0CG4)M^|fGRPTnW0hXNMEkIb9-sDh9l>JkvmghlXX z)V0mpww-WrL_p@5-Sta;deS84|2YYt1OzL{ViQO7Q~RgjYV^mut2(r)@c=AD$`Sy3^_JTU=wzZvi&SW- zNuV9Fc0}wYIW1fRjz}J8^~hCfPZ4!uiCSChw(g@k$;?y)rvlzZojPTkc4VAb$Pne& zzaH@)ogR@c*dm_@0~n_cVxp^a$J{i2*1u1`(W7HuFPmv@zN7cr7f+rXE~JB?ur_a# zH`i*d+ct6p&rTcs^P%C2)(w`N9QZ3HM!CGUw?e`R`u9J!{%F6_^xiA`(%a}5Z2xHJ z4V0Ri->0l=)pbxG2A{X*eo?7gmX0Du9neTHGi(9eZoYuLda`BW_Jn zyB*x)^-beXRx>IdAGsyBSdM*HZS7{<&&S@dP!;-JZYUX;o6Z_D;#=$k{jjkRf|kT< zcByb5wdkVX!Go5*55YOdB5i*sw!Gt=bQV4CK*=s6vk9BkpEj)p-CAe!$4Gy5S3|y9 zn7h-k>h78hpJQWdyAgG$BCf%xus)k=SQJs6t)|85uM_ZmP;76%>KdRL zfLZ9MV>+Cf)Gw>AzcK0vdtkt{Kp2{a`kzeR^X!flaGS`#J-EdZzYUGClIo`BWM?ke z3s9t{_fuLZ#FVK8RrivTBwcrKyMx!_eJ?hNqkeT_BJ-n?C~l*V^}K9xKDVvhKzsK@44w6)obfZNLTj+ z6&j)h`9KMvxR%qP*+s(=@%BQ(d|FMs%XpXmUw@aQz}ntxlLXX6#pfb_5VbMv*j@17 z3yV@aQuEYS)jO!BEyR_cOTgn=uMn-Q>Mv?F1`jqt9hkr+dBXWJN8F@UwL2T+J~M5_ z)wHvBlXHz|q9Sv0X`m;~<(fD&#Uq0bFiP{!$?>a-Yje0iAnd-*;21 zrpie_?9`jdq&;2TklQue6Jeiq%h#}nSNW7fYD#n;K@pVKk!B4e0dE?vy@e6o21SIF zB*avLMvR3#&U>x#=qwV(C(BF92l75OMMjF%?wEnyX3+Mdh3qxiEQiCxYw1^fJx)U^ z?H}l^SSAR{7R zeh))2lqd_8NE%Tjq4a5VuiTWCkVX?B*AY-d!U>Dxjzp1&eUj^{dVZ%9ZL*s1lH=G7 zlAhG1SFZ+u$@_GjyNmy^TiSG~vZb)!l6n+Sanq}DajR!-zC41|lj$pVX_lOa)){}T z|76Z}1V*Oe!`>IyTC$^SY<*=7j_VmcLkCnv7u}AD8FAgLBTT0Gv}uMT(`VGh3^}dy zfaN=ayElJ6=)(7mc(#O&!5XIz>&6|q72NXnrNza6Pp?+Z!t~QoCbnB*GGeDOPdE0T zKkT`qg&cqPIIKv(2?T|lNBv3%adwK^5#xOdJVgqgp4kl`Zu%L+9`1?v?oABHzUfk+ zseO0s;0blMZ!xLm7;ywN-bqtuTD>&G7E698=~LO}y%-?kDJ`VM*VQg?$kQoyovy6e zyj~#vU8mlg&IRaik;jo$|45b}zuEY=pLQENx1U9AtztbJ>$f>Gdv=Q}10JD5m~Gc& z2mq!N;*uM;oN|nUlxJ`|v0-FBN-gCclQt)O#=;o;uU%`GW06+ZK8=*DM$a%b_`sbtp*kMB8X&?S{Uy*9Hc9J?0; zx11oL%hSoxSFRjA;_5cEwmw9HW&U^R9C8i!w!T%fYwzf8-F$QOCo%&9Z`>4DrUMB* zyrKrrQ)qD?S{^a%ibM#|78!hq+9NAz|8$#uHPp0MJky>zuCvdR#hWy5KD_-M$|=uq zXX`726s)YB&dZ?=q-{*BM1Q)o_a z28}$hDsJgf=58M|3cgS|)PpT8tUd z*`+Ll_~OsI`;nX+cf{4HM-H!W``XDaXp+<0>3QqlIUy33X{t??v;H7}@CkZA2(ZSg zEd|BJscw_ec{D~iBq^7$RDhOQU)+uF)qJci%^GjSiG-H+ZhhXU4vKjS#dv14=^T`$2aM&_iYx?vbn

s-@EtDKA|(a zo^0LV^Ek6!tay4iZ<5p}zKWnQKtTR0r5(|qkh~n+16z~e$wY>W4LVzUT};bNR>|tq z{L8J=-wuvj2ZqdvX!I&7R5M}yKy7=#C<{fIjPw2d`?o^bS1mI$ldiPa zOc4~hSnhp?NhGomO1^nP`fba=@}|7lyknaiF77>PR{MnHjAzewJGSb4s+w?`G z+NqfXP$o^(dHOlyT&Jx@Iz(lmBWNPW0H1)aXztme%-o1*vXe#M6ji919{4yTD>xw( zUWM-`{qDeq(Wy#E{Jp1H;(9a?C|?c_r4OC{L3`8JOC;$$`2ortq*kk$>HfhxbiO*L z)>YNprMhOZVw&ljV1F*@CqINtIy9^q+dsUJXWv}&5UkmG2j&0npxzoIN2>o7Z)In> zpWFUm%uYu2tme!AgT@!wivQyR*2!8Zqi$hZJ+JCqKb>ReRp@^G^w@z;^%JJr`)Sy_4^2lifmeHRpNLy(9(&fP;!caheVosV!-XTS@p#Vv+ieK z8T!TBQ&L^sABa(f&h*9g|M=bA?G2O}Sd*vnCb>V6>%bu`&(b;1UKwH1=k-GK<82#N z1|*atPMbdUkZZ1+Q~lO??;byR5MI@L1EL_4yD@#WJzhmcX7#a)xV3q6R?BhgW?ER} z1Y{=q7WaKU{BH$O(*>_0Wnjb`YrUn)8it>%1)Qg{ry|NTc?(T31Wl12b;(N2ss~3# z%&%Rdeb~6Cd9$Un&rjL$i;T;0bxQ33@oVErq+B9(-OF#UcA&od755l+$u`Z{+qI zh;08tbrxw?dfl|%uk{9f#F3f-xBGQ;Iv0bqcE{Oa;4X8sPPRC>89+^PAglkZV>s`7 zj^^g`t1rG`a8^SF8i$FYW2ayCaO+tWV~tL5MKyN1M(u}gxpeMiO?~a#%MEMRplV;^ zYi>lPzp-T1)ak{CNUfAy9amS^JLK(yu#BfmqndeiByoMbSXa)nsXFlI=T^5rd1HN_ zm7ls9n1@wS3p79Cx+G{ldQs8RNZPYLpzaz-jj?FHxOQU_sWk*b7*{6kVgQN*n?U5D?M24PN|2fvRor>==L%{3ru{GoYcY zLVRoRqkm%$Y!TdWfbE`h{79iKQOAJ9kb9ccuviD*EbkL#^{+wx%j9Ly6ZFB2wu z@u(6}NxwCg>^Yei4x9Tn7Cn*m73aoF(qyx>-1@VBf6ql}neu+`_UuHqz_h3p%)AS1 zq>OtZ&9|M`+y>wlIKei1dC%nrZU1VV`*D@3 zs;YXi{!oCbQMHOok|M90<}jtW@-ytQIF`I*sRLCXuXlQ(dt=J+4|Jt2H&2c$xfnVy z5MS-oqpM~-Yj6&e)Avj|sX&kEe?|wCd|63cwNyXE;HVs2DYZ^cRU(RZ z`C_!1I>omERvO}%=xceS1zG9m#x!he-Q4N8vvpj9(hRM8D?rVT7M^T!JlRebr?gDc0HN7594?j3ykLV@3T51 zBV)kK%VRi>JR+FB4PuN}C!UE8Zbu z+2v!WYxiqs!0=%BwW)2qXYbt@j!bnzO32QS`;2314(#6D)f{zggQQv00Jid8TUY@x z3lxaGP!U(t*jkA{7Dw!MifRZ)O$rzkG4(okh$qWzi(V<9-9}Nwa%qSrk*^~r07_E^ z&mb~~2eZ?gKiy@y;_HwzC+#DYoi3~ew5(Ix+n{~~SG&vU9$)6-ozbzqvw!ud8J5cj zcz!|76bRs-oO0^ev3nghY4?6a*(dr$7y@Kf4_e&#cQ-}C*howW2d~{@J1Np6^MC_I zrizQv#;QwO>ri&>JtgM#>(|X6Usr_ZWL>1%P3u|W zrPXtzYh=;q)i>TonRmHSePzoze8eImU;}m0)T}LE57DbAG8NKBLVt3#HC6nVQG*b1 z?!S2!{-nexKtyY=udeI?+TQ)rC`L2TK-E^Y3PWD$ls?+?x3T(bx}k;ut{BC+BU(-snFY6n4&u`=3jX+)7GH>hrrNiV#ca%ZV*-AK1VD z;=fqVJohnN_mE76(aC1p+YMZxJmZ{IV}%Y;gfeYQ`))2jL@H;rP)f9Q(7jJD0||yh z(kpywccUaYvD(nka2}Vw2%VaBF$^g0W~jCS9kN+DsOtyVyU@V#EFt0fREZc;R3LD= z0F3<0V+pHb+O?-KZq6u%EN7^B{9t+l#9e)E5(9jQSl|kBL&)K>rMSrJy@=D9U*bpU zp?HswtV69iuL|$|Ei#)@_MNEWWjjHR2;dHg^NEZ>fM()A2>i$IngMx8`E8uc4dEC+x%JW;jd~auA!PmsWH)B(Z{4W# zZn`g`MK&jYvV{ue2+vW`x!Hv#s(STsTlzA{LOvXDLM#@PqHP0k*ub$Y~R`utaqk+lEliWTB z8}V5`l^=Te^E&B%${4ePo+j}z(|$<5FlWwz?^_8|QbAxF`U~b>H|x2fS#YxR3Q_7p zs4jTy9k_Mt(L(Dt6~r#K<(C<;8ZIzf4lrAT&F*zxeO#8xIB{jcHHf2%z$6KtR-`B8 zWbalF)*C+DIXyASm7^KjA-+g4kD@n# zTyXAKa(?_lRh|yK6%%uE`BW3rJ2@o)%U;}7N~%WIs~BAZ7YMsJJ^UhSwG9(?b=N@5 z^wdux;;S;n<(pM2&&d!tV4_mzl>I{*qVka%7*Ie9a8D*`@fDIN+wcrnH=Z%5x{xl_ zxqJ8|wM2$nYY>Ly#gANsa;#DL|RxbAMN^W z-VIVFJz-?(QMu*iR-$RNv9t5#YEHY*cB6Smva|r02Y!AcDJuU!>^AHzyCqAT+r<}w zBu5rw!RLI)k`cjo2s`BRzC%SRR#+J_^0es!_gewO54P8HiAoqTykyi*Iw(fw^w74( zrwC{0G@Vw~^dj zAZ0#qAV4%F%cQJks6uSHYX*CODuSMTtPj`mMRGYK%j; zOLo&Ew@y>0PTfG4f8!m+lTcF}OMX|b3?Wqgeq~m-N4i)0GGx^oEKWh@Zz&g}UADbYtCK)HF2mY z6r-yvx}Ydca2he2h!m`ecaxIp)A!~zd8^qFX-w};O&c`W@#}F=$*NswVIWf_zJyas zLflq0iu<>_pTK5k*73YWi~Jwe%-LS`pBCW2upIsc&N)M5Mr=iYKG-}q23uzgM}Hb! z401AICOZt6wB_>{TsA0e>X3=IigwD&Rf1_QZk*$p19-A#er$&0+DMNnwoB{p1j9jzq3B$0DZcsIW6ig z=&8Y)S#&~UiNw;}hKEp284j%T|CLkY0u1#yA&kz?4;dmh;LleEDN<%h1Q%HyzM4HEeWnh>`M+b*K9#xqz8W zb7kg|53te9*Q0hUHu8~q!>M7`1*P(xOMZ0jgBBA*(4;OSt}ITg&28w)X~qGK{fgA< zf;Jv~c$kh7KzweDYcq(B#d!Kx-5U&y6Qq2tuVm(b+1ydjMVU1|hVZ^LUQNup@+L6+ zgNu>HvCaBi=|D`7NMd-F9lYZSd%0Jz@#f8&l5pzvB;*-*UpU!f_ z&w@??1*%A0pZvK~6Y3QB`XmheC*)Cm`}GSyd2$m#uWUdst(E)vR&Up?C#Yq%CrcP_ ztW36yJa#ObLSb+gZ?Ry=nI^~p^sCAN5+oH96ZjJxh3>z~8eqHQf@-G-SB>Og3)SAs zOOgSjXlIavH=xs2_&h#O!&dp~=Z~-N4xD9eWHCW+L|IuGcFI5$dAseaXRW&IK`E-` zR=Pm1V-frTZ}ADl*JqRd$OsgU7*Zxazgtm_{x6O^M>)lq9C8OmFV$Kc8Wa21gJs7& zQ$Ti$xsuaWbjg9`6)o)$^vg6F0`x`hPq322HIoLuuH~$hs0I{qPSwBNZdeZ8Ftl@v z7z|Hs0J6rQl%w?c)MgD~fo*8x(I*7ZsMYs!G-=VXV-qTP0U~ocoE}(4Vk<;F>EP?u z*@Em#%Y*AOshPtp^pp*urQXJ_@8tDO-2&uA!j|x)Q=dH5-rv`JMCYP%{2{~@wE_to z4`HdegSH*-Z+Io_`IvDfi~}$Pk$^tgLJ8)0uT(U7M;3J4R-ZGz17{#|;QmYJus|P| zpXQXi!vJ8~n~kg)ne7m`J(CiM4B)8HGqaroZZ{qRCdx_fMXC{lUZoj?Qc=WRB>*#? zwIn()sU8Kl;VIe7pTB`$`<^9w*(A+%ZYxygGLndLT1CH2xQrWk^5n@Kl*cEWztXqZ zFbH`1`t*SUSS0m_YYf^|@-LVqpYsMatx5)xk*OTHRG=uzsW-O*d7=jP&0MEAFSk>% zTg#*D)Uul=5s)7ONf7wx^wk+R3;wAs|8@=lD?vxmcp#?OaQ>zp}7YiuF zx{e%q@FQ6%;-cGqe>hj?az0{f z5+lJj_7r9c@!8LrL)j%ZA|fK?28+rRQCQ^O@yZ{TNurhWGPke;NPyF9AMVO}{MhWs z0L=ZIh&9qFUK=Fhze(iC(s{nyj%NmMGjwuc~2f{)FbJ^SJEVRm+T zDp!BisIG64+Yj6Yv!c~)_X!+|xgY}sULSs z&yNrKroTzPIg=446X-P_KHsak;N8tF#Ro7GUnG?@or`GgddgEj$RB(bqWm@* zl1|Q!yJC&J?7Vmebb>-@<5`V-tt+CqMUA@Kj?zeg-zEtfSu<6LX zc0KL%_5XQw{6vZlba*B){pQ zgIP^(PHJXjo^`Hp|K?XAg9a_~vwZnZw_MkRn(9D@&6jVnvmRGXAD4Q7`fq5Z)hbSn zM{6C{k+8D5eL>#Nb)!p7V6wm7MjD*r|dXI8x0VskC_IE=kf z#w1*IMqi7M>gGEW{N-oUW+9SF)4l4nzz6>50Vv&c#~T%@#|8=JjW2bvZajM3#B(=k zs6CYO+CWx4R;rFc$r9@mz6iZlShJQewU*`WUZ>E-!s%~wrk(M`y#&zA$`P_AoA}` zX97Evl$OpP#mI$)bY&(u``-Fl816OhIv)#D2uGrq#!Gr%s(31oyOn z(1!;AOhIUr%~wB{u^9%&O1Q605Tuco)$Ai0O*;e`4><3%nN+%@tl>Z?uw%dkDFk@z zW4=03a78v?ZV6nt_Xl6oWIXO#rf^Aemzuizqfi~E4U(rj2!0<;r2mEU=NFgNU>saT zA<-5c%11K%Y$;z7(fDh_3qK3j;A0%=n%>xv&A1N{OZVtz%5_W#`&47Fk8pSs%*+;o z|HhSS?g+RJJD^5zF5;Y_*K1HabmywTAKK0tRaEybT{fzvdz!;PnsAvoLzs5&+4IxZ zQq3Jrcy~T_fFU+ps94^&l)}h7BnMus; z9thQK;^{eR*PcCzd}S@vdh)c?I(B?4pY6KihuREQY5S2XD+Q`41O_^!L8C?sNXWS> zBCJ`oDwl|fUdSEzXsJu3<}Qx%?~EKD#K4Hj5yk!P7aqNOb??)EeskTbB)@q6{O=P6 z`_oBPFYx;b0~~5}P~XG00?PB!wxh#GsWfb88+;C1a@viLxw%?+AV2ze_h2@jR-^a= zS7WOrV{V3>CxREW1L}5uf2Y>t?^YMj^6gXTzk6MJL>6g_%&-S3DGNwY>2+x<{nT5n zf$`63Zt1M~+94+|FY(n!8uLc+S}DkT_W?sZIK!a!Arc}r?X{3}c$%**6AAQY%d{Pj^ug18%=e9EcI06yrcr$;iodpzr zi=-y$Wj%Lp%B-xHtJ-VL(;sy1s^Et!!-na5)Nd49Q$74RBMwf!t!Y3*n?hk>_j3Tz zhOU-v{A^%VlFmx6rkhHs{=ns1OBMzd^M!3$Zu#oI`Q;bSdRU}BCn0qqSJM`vY*L&k z;`TwmXrT^Y<~A|b7|D;F*ysZ8W z_fcUXs2J5cb;|0W)MLOl7yqeSZ;f8q#t($gF4MDWxe;C0J2^Ot)_UuAj*kBTFmmxb z)kSDkot=3U?^`n+Fk+_=lC)q{79*#%(DN7NkbnDd*&GI2F>%NG>!Q|NItw{KLW5e5 z-_qvpS?h}n0#g)YfT9<1e|L#KWDvexGVUTM>6}l~JN9wkI%;iMKqWJ@b;6oFG(-B!o(aEd2eIRxK8NNKvpTDODF z6Ro3(UhRJN;(Su8Q%KEv)nv@k9w>qqf+Z9!noGM2R_{vmu#UQ$+g`An8 zP1<)Yq`t_#n!59J#?z;}u9u_Xzl%}c@9C0Y8a@+$)ks@8ToA+O-|WPh*_}+twC<}$ za6(JI^Gq5V0Q@@ei8AaLisJCGV@Ah9L8AecfB+TLoIe)<-t*_jeD?R5OcV)6q^<=3 zeRG^(vu5?O$c&4t%^a9kLVX}wjo`qhW}jy8=-=~k?3F85j7?3)F?sp_F&vn1^gj&c z)jB#lzKQiPI(hg?+yi~F^EVhgS3o1{;t^H_`2XyDikW$u3tw( zReMCoa|cs5@MYYb8I~MDsltdz!L-S0k1FcDqlpnwM7ttI_+*}FUTMZ6mE;wVJg z2E8#L?~f7BgKs6_Blh-%O`Nwy;A3W95WYEYj7|U?%o=!_yPCfZis=X7iDO?0saf}E zm`MYWLy4h5uaCC+>M!{`5+4py?uArc;1PTKs)@Ia+WLw3QgSmm{0JnFAbSeZmC3<- z_Gm!Bf~*NG$ZLb?wEpy#8xqY%AXvwz&!6K^C^M+#%*dm`5-);^i;C9^kqhB30;l-q z(N8&=Fmlr&xV4Lp9LPkcGXXmhN7U0{c!^#gDfwg}_0 zLIK_(xvMCY>Ou^4%h=8_a3GR#)2KDa&Wt4GD!vB%PSR7*zFeObX7gq&?rw2e5NnLEK)yOMQd3VO{A&T5HW}~+gy?zy z{z>iyhU&=ohJh3l84_eJw2xreOj9rxe{JF=HsvhTVbLL1yzR00)S~EM8sBBD*-x&5g_@{e| zDGbUm&{Kp@2_T+X<`Ysc74g8kMvov?h=reuLXW=Xl3B)N{g{*ED=_W(Qf#Yi_D1xCYR`hUK_NbTgFaV$){QFf_zF6)llns%a(1So)F8o z^zZK`eL75ECrk!;J_1Z3f||B^50ClsAl@dbGI8e!Huk3SI`2`YO`vohyhwkp3KQ#$ z$1_aW3ocs}z;u{@crCrwEO1-G6Ckl*nQZLzF-DSQJaM7{@AJ)rNxY8X26M;q z0gGy)xs+uTI=@BzNc5t=KfVEw3W#{L>&>8N3HmpjBBu0=?5wGAPS?+7fx$=hFHV#6 z+AVR|+1YK<#*fRd|F)}nS53Y*p4H2(Gc&~cvfY-{UkGKuwZ=y z$;X)yX!#X7mojBO3t_A0)gE66>yE$%!ip@jthQ%SbO2x)&o;Rf4b7WKqjKVlNgp1g z4Kfejr2WsKz(;rBr{A2P;nVY;RwH>2^u6!7?cjdrWi)O(unwJm5?9llbk9)fYf5`J z-<-(syk>0j?I9t7)TSCFUZQq3qS8i?O(v=Gg?~;LogBKED~Avt&ZWm@Tmmxbr2Pg= znC7d8{Joy<*G%r&0&`7UHcruQ#_p~uTf^-U^6e(az>tnz_+_&}3FnV3P4}*3NrYTv z8GZs$Byjo_HLytoDfsEEqcKz<;kugmW>sYOdLV9Ncm-HQHc1ebwdfevm}EySl3OS66W;mVtu5+G|gI%?r>bZlKlj2*6A%b}~o`HR^Knh`CHa zU@=P`yJ+2p8>lOwMCUOdVkc<^SFv-VAYeOlUjFsv0LgPJ|l-)g2-8A*be9aq6`_`0Ed}CWI1qc zc*5-FrN6}Y#1>A={z4QvcC55|L)JPoJ+VvIu91mv((>)o54G_dLyaW!nZf^jo_d?o zRD8Qzztek;7N1L(zHcs)aUiOtH#jNf0V|c7ZhdRTc+{a?rwpcEK|tqhv?JJLr}@X{ z&z=G8zWNkZ#bQkd``;l?r z-bg>!mVK(l(b4U>4B<0x;%Bp+>?(Hq+nZ~ouoZ^Y%Ic8GEH0LzowE?tm3?^=T)jpn zokYH){oquHUOdf~gLQ4JfpM2Me%|!T#W%11%ujwf-nsnMj`2FdREYN)gbZtRuus(m zl%(&fW*k8|JfCQwN4?+hBf*tgBh=l9RPEHZeyYmY7`@3Y)#%wXK&`*h=kal+B_-Zq zd_?3nq9R&*R`p1o0qKr0d?Tz_R_&jEdStU;K|;ZZNZnC?$}G?vMQ>edc>h2In+#Aj zL9~+ikkRfq>xHH>i2+zq296Ny1F~%xc%_^EpLLUV7(Y9!704FyhM$H<@v&- z9rN1M!>JZWaKYcaQF`#@o+%$0*TAABSZ2N5_%oKUj*=lk13aH1>EYQXUNytom7Q|8 zd~oUng^pB13|5rpzH)s&RVwYejMSu!ujir>xd#rfu7g8yD~Fk+99mdB9U7H(AO`_v z1)az281-=h6XpP|iuOyjLx(Li2ypQi3xQsQfC0g24D;&nAnIG`-!eh2a9&T%wtxB> zxx0@b-cBl4ve+a%XC{Le|u z&rPBLD_Ge1@6UAW@}S|~=tcT5Lq=QM?R@-Xk9yykW&3L9NA{w+PUJ7PJUfiZ+w>Vy zAXA55Sz?J!pWGN9@FNl#lmHMye^A@ljV&cv-f`8cqvw@1z8t=KwG|Mv!)iA+AjjNT zOUql0?SCw!92KkUeoHI#whY=n9J|#g#)}vrT9fk{6#(k2z||w+n_07EXPtOb9pxWfj=fEE<&xrH*1v*G-^F9MxrR25XqZMF|L)3-k{CBRtRRqA%nkmEe#x zVCEI8dB7Kse^B#r&`EtNJhzon?vH6CUP?g$_b=8^%F0NL6gu>zg1%evsnKUrhO z*MyL`e|g=KEr8A`DJied8#&bTvvCBv<9Hmh?f`4%?*02wjqS%}8d9#|!>}3q4O6Ed z`!9n|S4b}oTh@9_a?y4_Ia2=Ky;LmyDcjMi8PWWmoqJtVZ38duFB@vUjONuJ`*WWY zSNZGr3z^^5g{nhsXY88dLn)?xXcRI2-c3zy%G<-mH)HD7e=mzuMtxiL8QHn|$eY^_ zO=lqz~?so15)XhAGdxqLky1;1O0|_Yst?AS4W$zX$gfIzL zBVJZOSHhyTk8i&M6dSKYox#_A`AOQ>Ghm+WmA|=U#6;*CedRn;-j3E4j4AHT=_Q ze3Zpl7-YNQMxs`bY|Y2Ng4%2v4Ufi&kvyuEiZ9*hqs(fl1L@SrEwgHhvN%`C^keu zv>D~DBMmp}!+hgE{Pf&zOd*irGic1T?O*g&{OB@$Lc0fKk!I7+p*k4PA%PgV0aP2Q zbY6`gl;dj}*QL+j^|F1hZJT4yy`AiQ9~~WU>-zkgYfO`7E!OYwNLzf&r{^~Kx8cQ9 zI#P3Ef}H4(a+dN5p~Yb;&3`U0ZbktQwexcOZyhtr=hS@ zI0()CugJ1%f0{yxkfdt_;*qvZg79W=()2Ty*8gb%oQ!VQ{X9PQ2RX|ByBFvzKRcGU z)M&N&RryAR3?01sz=@z-Zf0+O?FXR#6}xN)FQ5&>w?N*3M6Z8YnQ~0hd5V5BUL-tW zf6o~f7V(dh3sW$(iF;G#T2UmtzO+?c?`(1uWj z_%h+-cGcJ6XuaP{xH*au6reIZw}XzO*O$KG2$v=F8P)`CNXd&i4v^wwA1oRpeZaYg z4<~Xrbs<3=JS7g_;(~gXm*}avrZ^OQsVZ0MWi6dFcq*ay|8C;a{kCny-Yj9$vbwNq z$Vqq$B_Z|fy?R9y=soK&Aj!u?0m?$@V#sEfn*b!aveQ{q#r)LyoX8@b9kN9xNg4ZV zsCNxMJVtlW$N^6Iwym6KM7wEt%OQak=Ps z!`IhT;{miO*WeuK)M*<{KC_+rEURHLm|IvV!Sh`|cyr|X>JFgdlAFcFIdA^_+LRL4 z?Ep}q2`QI5w@{&DZp6tMqJJrOA1J`ois~!mh{6Oih}wtV4CJfjYT>`?``L&c9H0#Y|ZU{ZU=|`xLL;wjNmOXAoK_%)fobX zwe&1c|5my8z=6%ooI%7J_u#>aw8Gx4B#hJ>eoAo%ka#P_@})uqo)WXm-6>E>O3Ic& zQ~dwwdrt-)qBE(bkfb|te<<$ce@CF!-Fd`>KZy3hqet==TV&ked-6~v%~v8=O-*f>a}buHr^BN`xKyWp{T!f40b>{>e_VhycKV|R z59iFDonE|`t!_V-8wPcLbdp=c`GZ-4_GHe|5$9agn?Orl0;zY{XZE`!2X()mb8+Na}mBz^o{ z8W;oP?}3TgLmPTU+g*#fke9Ar8Pf!mdw5Y)?$$rK-z%SK?cxWS3rsn2;{1({q_mOA zx~px2Rthv>arJT;q{9QMO*d<%vq^TQI&;4b%*>i_MOOx~-GUGl?+5^fc;qY#Ms0z<(?QF!S$S~=J9cWY`Xif>o-7qo=)^gjRXvv^i z09J7vNF8Ot_)X7i&iO$pSNbEL*+0a7!J*jZJgh{H%a$F(T>9>8(kF6!qN$nL-d>Bi zh`6($1LY1xo(%39*nFvpTnG?E91CMWQGfy+iAj4)o;%AqbfwffT$fcfkAZF>h}1u1 zcJa;rTY~Wqw`WXPv7*0c)t6xcW-zy{XeGCd2%;zi?;?K=2hEF_D7{;*3=!3kq0nL& zCyQd4k}gsgRMT@~OrWFSRG@CMtL@%|qI~StD!73B-03l^{G?TtGzMSUBfSnUqXBmLcH`4QluI)Ra5^P1@QbBxD1a>`Fby z?Lp_61Zax}d!YAJw0}dpO5`3zjjc>0-zOr6*$v1_sW6&t#3DC)yiGOgCpVez{OMSipYZ# z>faweQ4w>c%GFXScX=~~L$afrMe-7#m9m`ka=urJ34}5ir+K}@qXJ4$Ob+cF78)vv z;)v`tIq5*#@ZIDUA>yhJg*wp2jUB%SB-;elF(Wp+4IFeB9)>c)aYarIYT8zPH_j1k&KIYP=w|Gz(L5* zHa%2}i;K6>0|35AZ6G`j{DIf6)xFcZSl`5&&L1-RLIA6qo!p8CkW-Q37K1j%tg|O~ zmdsg)ihK2~f`e9$9<=s7WBQ|H_Tn2$P*PASrii6LDjO}D!mR41lJC&-?Qu=k_^p%+ zhy-yfVm7KNU&pWbYi`0!|>h#cE-JWHS5FmCg73;D$85|4p@Z( zRk`e9W!!>huhv&r`X3CQn}PJ$v33b3>^R0|$}(pnC;PbpVK4w1TW@(bPMw9MoF;g| z@Il+ph5>;xqHBCuo>V5qW&$-l0W}|CBwQ9IF2t zd#8*H;+RGGR#z&gD_55PtTs+sFmIk0qUDR~-dc?|!l^J7tf5c@_s^d{FLC~%sULQx zmNt$rg&i+b*W+*vHiFQRX4n(+Vt%8u-5(Jq@h7ZngS%8SR~?Sd@&5mM>^@BVXeagp zm~U_FgNh%+?8(^OD%1d%aA^B|QWLv*$Z%gKqQ)^h+84}J>@=eF2S)!p)S53LLp;R% zNpE}Ou9>o1j&>uZ@G1BG&KzCed%wfifp$d}<^jJ~HQBxGeiklV32UFR&Ob%1L_Y1sr>z2*ZrM;uyf@GIaV=y&iOwSe) zcPlK~FYr7$;p$E4^l+%Qb}faO)|?$^vR7LToO-KHyq0uK!*{L$7$x7U)-(UIob2qw zM~=kpP30mahKgtR?vwVUi4!p@-x)3yr@o^AQRs8_74^& z2}4|F>EZ4!SR$3MC`xX1S2)6D!-cic|5LsNOWe}zhxgl2wy=`OMh!wOWv1g!c`I#* z*RL#lidI@k{NQm7a>9@aLsEVy8paVB`{!qSfPE!cAS^=jDYg`!<1;9=bdSeO>A8DO zEZge?wY6<0rW14`j7!_=SE>r~A@QIqp4HFkW>e~C7B*@t8jxC1v1c(H#UnTe>@xy;8ly#!QxhHpCapwdX*aQ=`fwo1*_-_eVefU}DQ1VHx8jkXpvYjADvslrz}tn9rDQU8n?tpF?! zpE}i$I|3%v+;&QOxCc|ZE56<=KJWQwtuPs{-Y_Myy@0~9Z9y}y*ff5SywJg68>OWU zRjRSE@f|9WAj;mlG8BztP|~kB^Z4b~ucmkNanawoBk|4fC+{-vuH0c9Sv2Y03ccBK zxgAsJN|SH=v}>(3(u;1NjKhLZ0=u|U>0ZCRuZ8is^O`Vl{?PO8@lRq79kN;%+Kzvd zevI}QrJPRqnu1Ck=tj}SjHWmF_Kx?>Ar^W^OGBht5Lr+w)e zuYnW!I;Jl!g=0amMZu}?Ldz_Qd-6WVtypo^B)<*f1hIXs>!|M$b=#(MM+MFJtM{wz zNs4GW`Ot`33YMFbo(|=TBptt+@|(k5=2S(UTp2NrCUK!siTcDP~!$vnfTvGU% zuE6j4(Xc){A1ikSb9iN@y5Am|HE_RT3Q2Rg1jNM72oH8zXkjNN1h;M--0Dm0(RPPA z#cLJW@8&K%tKoL5#C60^hcK6XW$-h0!bhJx&aQ8y7z#+e{#0c7(=&61$-rMWxI`ZE zyEts*JQr9K>|$^_xK7MH^d3Q60YfYLH;6rc^eFT2rhHhK^^Xrx-OX$gfYnwCs~-xQT(*|YeoPR0IpdnOC)BNz7lZzE(p7{ z^Ms9@wk%{PZsg!M>Vf7|u8{ z#bLEb7OiuZenj_s>E0n%s>fYj@?})}hQStILS||B43J(nUtEXgu7X$%01Cdit%u3J&e5TS#HLjBDhLV$-0F5|E7;ZW8VXW! zn|h!22ic&VsI8Ew2o&1>P@D1phL=z!FG{{~{dzdpCA&)$Fn}-+--CHsjktcinfOE)*G~%Tc&!fqM8#xfuv-jXkmoo<<(6h)z z#5kB&i*+YB_Cj=K`QpX$QIY2gX>b-onjDjxMrJ92}Skq$dto@*O^Avlo@4T!DqV#Rl1C2$muq9yXH zrBp9wug2i?fiND74jd*}&@3w+99?zDog8*4?Rk8!IZSH+&_p(WUa8$;d;9o*rAHgV zSY=f}Pei|QqnBKA5Jd6kpc7?L#Vl<4+3>j45=2oog>?)R7JA65pIh(gZgX}u}rn;Qo3bqx$FzVBn+s&N7JH4@e;L6pPGop?&;St zN2Oy<9uQkc0rz=n)voTA$6t6}?|y5*x^-1EzMRq>Rhg^yn@dyi*&%Zq5qp^f{41d74&HOh2Si zNaQmlCgKj$SI@higTZgK!#Kh3#DU=x>Yum%`Rv8rmElvOijp(WMs9rmP&qIsSAz98k=O-OKvBEfZ~W|89|2@HfA#yqCG{LHj(* zU&GBF+<&|2#iVVE`=!=Ymyec{0gZyfiz7;`v|!=BtQkqcI(Pe*3YZ2$o;x(Lx*xvE zvt^YjyeR8zaP{#n7nkiz|F9hX^SWKvaM#1PznE~p=oU&s)4Jk zHUfNt4+X&wZ~r=8wJo@b#Qm_x7hR{IK%K{Zx{90A zPk4Cz;G8O}>#V~SK6GRcUfmCr0$l!#W)Rd0q9q@~$0+&mCnL_%Q#dSHQfY8d z<<<&OOZ~gB)u$n4r<0E=X?hpGq&Bv5#MTmaC)k-5{u{fQn=gm|?ZY}z`vQjVj~VlB zFZI^TO21oYqldT+n{7R`;QOwO?epL~CTSHyi|TtgRDv3F7_NFVW8d~x z;>4nRAe8KaL)Iun9WDw!BrhS3_kID2ULt&W?THZNa*zCK{{s0!{F~nI-(`B2?lt?8 z77*1X`+KE&_b2c6{y5w|>VI3*4U32k#KoFAQ~hkXl)DZaJfMN*3}6bhkSL*4w$T92 zTe|f10#~ds(fuaxp>nFik@b@YgT=RuGcT$jiw{F0*M^^^wfnH0!K756WN4>A#~{+b|52(4Ro+*=%U# zP!9mW4^%2pMGUl?b?S3pkI5*UvweSRXn36AOl<1x{C%NApD*A_^rO*Po(&xw91ve_ zNXikqjtXpTxJPWGFCLbu2Ztv;Mo1A4_~n7La4U;u+3U*D}`-@$(4QqFTYts{pHhbatI{ug_boH~^Szn#9%nH{3oZ zCe%_8Ar5CUd`_o%w^81~qOC{4OF=TM-KJn-AP@iB1%uqj!E)*rl7R)ZpX8T&=FAyn zSMiVAw`nt_eiN$BMmviQ+Bdw#PaJxqDMg`xqSTSgzFC$&y?4*=qLS(1DgW_SF8UH| zD>cC1NUk40rmye~NXLZTj6=s45fK#PM&gB^1gkqJ3ff-~91;}mbnuENB&t8I7Yxu3 z^#cKv`*mh#RsFuLl1~R)J=SVOD8vn^>FI{3r&K?uhvnR}EQ!TNk7kKtaPp0Dx;?qTdBmk#8(hCE_)EqLT zCFdKuV^T+^{4=9@D~3v|DGsA4g)kMVFR`YV4h>*c3W^PaCKLTwRAxOI@NyJSKHcV2 z;e;6et7!B5Hjw5c^l7^BswYh}XkDQFmjbTX}snWcYa>C&j=*yB&pdc6v zf(a!+L5+e}^xUo~((Q6Bi+b4K-~Vk!L$_Pf7Lz(E^dcD|zSLQO;Pv69Xbv4#uJg0$ z+-mclj*n-|*f;ma-Ny$emaZ?gGfl7cWv`k0DC-aRKMv^g&*S{>z51H{?^shYjw@o7 zVyumQJCHZ2GIq<(6U^f}*kY?r(`WVVDU&z|RMgaV8RY|>nS|wo87gtN7!aNXCBej) zm!I4jLLH}dWH9swirzb*njEAk-wv4c=mYCiw%*&NCqJ7p2R5B1Z99La5iu+O+;-QM zh<q8hW!$0gn~ zdW(xrRzgDL^!znHi)O99JtRXs#6`amr$~+W^8(nxO;fJDS8fH)OB*`)qCFAq zGV_wJe@7?y%v@a~_e$d5%0PrI1ma#Ao%d+iko$Y!BTVwUq^s{lNS(gu>5Ttx-)k9! ztHSxr>jY|V(X+bo71$fO6G&ted_g8`+szETypetR^IoSZ>z`h?QJ(p0VJM6z5*a6A zuww{2R(P?VZNWH09~?d%@}Cx9xokfgO2r)r9}&_i6#eI3^Wvm!uh8=N~*EV5L7w!=hm zzhA~&_Niz~V2t8sjY6J89uLs&*o6mRNBQ6LNwF9>Y!P8sf}-W1PVmPi>h(+Ox5Uce z7jatKtN!P8p;i~>*Ci>Z4rrbG_eaBCGR#mRbRc+3XsO7^Z~yw-Mxw(jl=<5^f4;yWru# zMjMe;c4l_~mW-P{`*p*2%3A^g?!fN^((kR@i*+ffBDSV#wBkpG3*{ZC4PD=GfC!#w z15{BVhi+2=O4dB*_MP~6C5oufA4EHf{D$5_r}0BMX7C%d$_R^DiyB@Of9{oe!7p#F z82}mrq?6nrrjN>=*n-IMjc5LRwqL(;vk5iL;E9U=bp+d6A$a_sP^RTx_zYCG+uQF8 zZjw&nb}1rl7+#IK922H~`Q5&!XT`!vFB!#2j?%Nc($}2@v~iCzqq)V{GC(9C*(~wB z7GL>uRG3Cof+I4HBB zr9#LGDN;#Rr(N1xX($ODLeer)TGCKG4N6uNCE5c?OFPZ~`^q`r-#NeE`Tl!(p>tBt z^ZDGL`@XLCx=zb}DA06i?sf!|;Datqd8B=vD^|0a!Wo=MDN&9yK#EXzj|#aMyz6;z zRw*Zh7cHn$hBgV~s$V(nA`c~(rKyPtbO5bBZ(DIEVIMLS&5)S8%1ty4yYx*vz)=?! zG;;cwv*5gWDZQ6lwx8a1q>^-*Xt{5u!|^rmru}aLRi^8=+Sy5im3ggf z(Vo@w)0JW-pm{5X&ZV)n^+lZk;Bdd-;5{KNH6PRP_t3|pQf1}tsI;J`IFA$sswH4B ze9xQPcWTxa78z71luro0;t3pctDXCdp%Y+bK+^Tw+&#LtCDpoTLs;#5@7}%F&!1sC zMrpMbhSr$swr}5-ahB|Oi$5QI+JI7T2e5lcO(eWK(XH?Dtz80R_-Fjli@Lh+P%776 za!pJgAoAC+P@<7Jq2jjZE9B#QZG!yQ>LDKv(^C-MB?Yxk!PXnG ze2d&6K(iOrUu|PQci3i8RuoP&3}5$~BN94&)~u~Sbbf%>ISO%Ddk=IakmNPuLA4n? z1k?^kv>LLXFnQ=V9D5YjMKf(AS7F3D+8sbdNT)q>Itbh)`k;3s@SCp`4hS`nLeOm$ zrk^z;+lPt{c(oYc74{^jrZ)E_OG%<_!5co9=dN_`Qb=D(3(oV$)fSj91o-!+$OsEX zi6inOu*RIx0AU~b9hVw|Ei}N6_R{rtHxQ4AA!CgdwHx2!Y{LZF4@6(mA$&28#|>DT^aN)o?GQ z^?Cd_ZJ#h^To1Q2iC(QF_SsHs_BqTCo18rrz9`(GX9=g1y3;>~ z^%TI7QZ^#uJFV2ZIG-kWTw_Gy2`8B;`iZi~r%xe*E9m_Or>75t=7IZx(|RE!(F+y? zK{slI>8_B@i6j^>Z%B^dtb5M6taSD}^HqQcOCbais0#)1A-o)U(WeFv96lVM99{_m zvm0Z}ro?tJD3y!!f%nJ+OluWu4#w)!-!a4ZfNOt+PKomc0-7M8#H@oYIQ}pY@%4wm zqk?bj!ez{LQ`L=iaEhJf3ce0Qlx;grUqb`kfEB$O`JJKkv|PE861?OsU+d{y7=OW$ zJbkpwOc%MP!A|LUXcvUTgZST}=Mzmn8TDtBucTrrrGz^4PkpSNVa~C zIa(}=`lg++W%Gu=b<^kjxRL-R+X$6GFr$bGVIZ%m-9;CGYYr7yl$FQ-6x(HhdNH?U z6DlZ+Lodcp+t^@YCl^TO>#J1mfS>ey+d>TkDskG>uwXzX8=gElFy+)9&tYMg%a=m) zpd#cb%sYB}f^Fxu)hr-}HbI|;1fvqE(9Vu5ko5?v`PzOAruiU|W1xnE5=G%gp1)vn zG7zFtv`;cW4?%MTN$Rec5rig-F6F65LJNV-c*X#%Lm@nc@!)Ui828ee>@p6zXAV$VSBLbqp2Puc=0y9fYF2R zB4`t_Ei9g|M|`lkhl7{LfLFlH?!W~3E5dU`92G@KP=&e%$Xx>j21RfT-k2}>3+$$Y z?zR%h2w)3pC|K^!+2e!`_Lj2Sa@p1OR+!Gs1M>)6htKfN4r?W$v6EI%u{1WGj?UEH zq+MAQB*b*QPSo6hkI0||#~8K&bL~=n`N)s6v8GV`1o>9q5zUZMiTo8}_nY1-Y?wf1 z=3KQLN=2tibl|RC=6weND&8!G{&O0!kZj_piIzRzqPuh1TpO<{XuPzH%sugTX_PL7 zC1F50fwhnbAWz>~{UEr=SzsfcU6?eAQJ`_`Kw2r!7nyW688EIF zg14X^gW(C(4zC1rpJrj`2A$PFb{L+pwKw2PZVs>mN7;&Y3`92vo&ySxc<*#(Jv2xw zG0YS?2Nni-Szze#g2$I0+MjM3?4OUE?Xz2e=;oaYsfdYVrDfC5)inzX8|aTXLeb6J zNRJB8g5e2}JDWn@Ft*nVr6Pun%)ul34Cqk`(K3@IGu|OuEP|iR!lpRg?&^Y;`^od? z)3JSlSlt9mtuL}=OmV&O zJ+YoAy#Zc*m)}-GdsY&64-E};lJAZ?*5SpW0RzEu7QGB}Li{t|QfPA_OMm!qElv!C zfn~l(c0o-aD1U-=S^Ica)c;^c3pt-YuQ|)|9i1$2bF{gD87_XZz+gRe#SN|nu=NKb z7;+(UwC|3B%1y!0DfH!DM+MROEd>1lvUlwX_#G|)SwcYN)~_&ucTQ!vqUX4|dLaYs zKqJn`UA~LYJpd7bYAG7K>=2s3EBXuGU7#R^$3JO~D|tTfXgB5LLS|Zd(oXJ|wCu^D zbdL#l*WuQCjPFNatsK9)6`IzC3q9R(kj;&K_JUF<3M+~YR&h(}#ZD9Ia;ykOap-*@ zTV{E>n)-G?$lMJ23(8;sK(NddvgJZ!dGU`w3J221Af2FBMSLyv;XIh>jHZZkzkouS z-D8DTn#1z-sS_ts`mYp&mFvps-JP1aYZKn}Ny|jE(9NL1+EdVgP?8UZXfHz3hK_m_ z&7H+I-h{-5c4gq2zs)I!UsGoHO}R4;^=<;x1YBUJ$!I{oF6>uETtA6gzLtzke9Z10 zlK4If-(}73m+ua;Jes@gi?7Y1(14nNZ_b{}zU|@FR_Q)ycS&C*C4PFWqiB5eviN1o zXJ$suZz>X7ZZmhTag?N_Pdf6)*KZB`IaapyYuN8^(py<_ZUq-BetrFU-TU?16?%tr zPRV?ebEOa{I)fqy>`F2JfaLq+3r9_E{eGA1cKI_uTkl1z#`Fg3Tp*bUoSw~E6X7;+ z{cT_`HKFU?DlW=>0~WozeE*(v9acU~`blC8N(o2fwBo*@p-fo!_xPk})ZBOsiYG=q zCiZX!LgZ0>`LsS5wYol*NY$=d(4>zKmNC)80>AhC*jR)o&^u166vHPG!M?{vDnUEG z(mX+Xg@{|39y-1S01f)|7R{f&P-(zs*t{5SDv?ZQ^u zXdrVEAv3U58^tn}-{Vg_9>!L}pKUe(hQ_p-Iku-n6AdrtaSw)t0fpJb1^IAaR?x!f ztFP~L-_(o7iAqoCl33ZY&^|9#{h1ZzROt$%cf7n#xs5wq&1+N=D%+Ied|7!EqzAv$ zI@I@P*YUlyYgwW4StNfHL#Vp(HeJk8!6}0h+c5ymULf|3U~`NFCV3WPqVim}ECecY z&;SRM8Y&-(Q>FAn2;jK=ZU87i>uC?q7N^vMD=)w4vCM2_%L|_M8Q-^9p(|&ReJt;{ zmWG~Z!j>e|FuLM&q-6v0eO1iuy3y+dRNCnuT@xvDt!veK1#lf`xwUiH#;_cm&3YTW zXGNpyZ5qXR;nDQGPUdnPftOuMri52!O`EA_;MRYjdzk3C?zbM}2)~)f@Wdn$JRYpE zTyYT);y@!byUVY4z`0uj+H|m0agMuc`mfI@XX~D(ny>Fr>(g?}g&RHYRK^P>MsDT= zCrE!VBhj9aBj@q)MIy#HRz|q`n|@P0gc!$oz62QPm6}_ zl-TaKt^mTIfp43i*5{0j+1hp=TXqXAzrTMhA1t_=F$h`Cqt>pHC6?>yW1ZB5Hsq}o z&)K7R2J|W;f8%)fth{Of*YmIg_%57IB5yJXMO35PpHDhgfHxO!-drh#6xK*NeOaDa z45$rMNl<{?H{iL&E#ogj+Qi>s`*d0}y0*D)rYk&!nqnU{g=EaGZC#kV29Y2|f%Pcd z;03z0xTYTS;Sk0m3LouS&#Ia4>n{9+`fc_qo|nhhD)yJ}Cq^78Jl!~<0uE%?y0p0W zm2F)jP=t{?KL+zA^xJ2+ApuPgz$f#rN@zbG7fdMHS&l3URurF6zf?lP2tg8# z?J32K^7JuZVGELD7Mf%CXyo;0_XG}Qh??)dJrQ43bsGk6XH zdy&p?5a?Rx;}%SL-?55$Hq0Vx#@g#UN7*wO9` zke27794kvSBto{oV<`ecvILUR^kdU1cL_0874>qsBcN2z;1o= z_Bh_(x%X(3=CXD(O3_Cs4mEf?w%!RH?K}pKUp0>niHZK0Hj+|;j)$)jTr4@ouOY3% zjr)w$WW5R`f$CMirv-ueIQ;0t_S3}|#}P?}UzaCVu_N1t10ryi6{|!4_`|>PK;_4i zsprHzpOu=VUA~x8W_)({J#T}g!3|SW4HC3vgADX^{69ZhuZd}2Tx$X;Omp? zP;vU8(D>L)an* zvL39`xHB8&;xxuLTY2lpE_b?h44kIngp$Qc)!01*x?T~A&!(|0q@;@pRt~_{;Ov%* zB6$I7^({~kdQQxAs&v~OnXWMeoXi^7ZQy}&{qyRJ5Z!gorHiTa&=q)!QF2YS()P}l z1n6=AnTCD5?x?4Cv(mJ!KdQo{yF|9WA*EQPcX}9>-8|I!d{5uu9?Y4%8NiHav@YD= zjb#Oo)uKo%lZ+TM>rYsjUa;ed0iDGe&KHUSZ@{0jJDsG3f`$->++Dh9RwG{YV4WX_$2TN7Z}pojN|!t7Zz51MkG%@Ux0$764vNMn>dz z7O%I;Bb|)I-Re@Ei zJcN~i*2j(Z508Glr{&9+MvU!b8N5^3b_vpJRQEfcCAQway%_h66S`nXC{8o0Z$R*e zO1K$&x>-t>U1C>^dQ6!m%WMakuw9%lM`o6WUcDM{MmP1-%2vggTwD3@#mhvI1?pW; z8kwS-aI(TV%XqpM*`cnLoJ6lu?xII~XL_|+x_a7DadEX#rSsSog{&No@XwjkY@H;k zZ!q*8{{tT;TWVH0>N|b8;vW=L1YwHQj7+e^LYVJLF`Sof+*m#Um{aToAic{Sh$LTw zqJpNY0s95|#XRn!^EOKg80=PnBf!@RJ%(FaTAI%-z4aq=+rCP~;PZfo1VR)b5CLn! z>}0=_;&ExnRrNg(B9i$J*GRhCb7cA8YoON zPyx(iVNOnfeFY@U#bI<=bu{4rWq$7H>12=NmuI4`LW@9wp(nC%_~Wfq!WWJ^?4o}r>gQ~P_h*{wQ(6E zMid=7Z&rT6LpS(s=i=qdHE!CYOp4gcpz$!k!KNx+fPNgOZ)?$5e@rfMHM}F-}_&qcm-~cjW z&mB!2PX1(e`J!uWN}gTkvG@v(_=@kn6Zg38Xf5~VsPOagQH`$%@K%qx^qM_;XH40T zXD8zXRCx?jKNZ%q#8(Je)m6#>4^*924a4k>cE>(v=Hl0#9CIr4zgh}=7v!t#o(?@X zCf)L(H+9cg7gl1Vf^N9f)M^|;Run(H_h!wPYjB7_5pA%d1XD3w&i6aJEt?f~qX1=b z(eFq2(t(=$L)$o97+#&~3?Bv7icW*?gmjYQSXtZW%B-Me7Kx?-eEL75h zK5QUtXezrO=Vi5+b8eF)_o10g4CEcg@9zfH7q{BV6DS7r z%Hj(mN&zUgVk=B&0b@-L$QfMU>D!i={ibb<-*Ye`1!KfHl}CSULN4iS+L=7mk+IfW zHRCCw1Orb+xP53D?}QGf#%-{+X|#TPK-StB!*&c5tRhf4ldI;}@GAoNQNL2)4kpDj z-3?wGUrTFEIZ&REiXhp#`~bccB>aF3G78H9UN`Tz>Dk1nW54cwtPEy|1}6wx=A6OB z!4^jXIGjn2aQ!HyN1$z|>=Lx2ct60n_;F<^Jle>p>BRf8*F|qk(wcBD4ZJ%OTOmb? z%w=7EMFUs*Cl?d8LbiVW1bo+ij-o*%2!r8xhGu@%%gS5oF{*%%OL3q_iZ)xx2Y0{3>AB<9_a%L!m zzqy!p=+3_F^4F{)xF5YXUjNWhutIp^^tQ>RULKI?*Q76yL+)VfPuLrk;%GFh0Ds^# zz)uWMz7^X3ZFDJvm4~p*}pvyGY#-JNo6B`$-CdY{3}} z5{Z$wZ0nEs*(nPIhkwdNwpSq`Axa|6?q#>d zq8xRSI;6Z7l6M-KL0>^ROs+c-v#Glvy|$v+xwb#I++jqsdq59fwkBJkXW-Wi*9%R0 z^{%a1)S&D(wja*0567;Lv=!T(c_`MRCJ}NJa5xQQV>FNh3e|ElXoK#Sq%va){D~aU z33XXkR~?kv+44FJTSjo$j!}>n59B&J<^!Qojnc%aCh^Vf-JM3jf@Iug;}pza-u>4` zQ=$@6=FgWTq=8$vl0SI0+ot6@mHIk>97A4A4S6y5NzA~WD9x#yZ%os4W3`qqyP^@% zd{=jA=qs_17YjpQEqR~&j7wj~LHPPkHdI2YJd2N6zWScJYjtoElH8s)s@U13$=OF( zw96lYI(9e|L>p2M0K@y4VWL2!J1N4vcO;GLFr z>$^BA1o-&_#FEf_PIGk+-`%oqb(c`~U5JQte0AT%Zie zY$#?PEDMjAZnlf`9P6*73FT9_gCrH{@vC=@E35 z9F(3~We^2VXszy`WsT;__z{QX5uVo%hZW!SJH+M{SY)u*NR(dkkz4J{_hE*?(eAXufLl*ge@J`Rh_1-1d*}?AAOP6P*t< zkj^2)ESG5~LS8J^zQFE@$;~cjuXD1o(rorOdEL*19h-w>8RgogV_(B8NtK5#V0+hH zZa-F<;Eur=N>!jeG}fT0F!(VKVsmJn*do)1PeUr}r8uV?bE#8=x({12eSprT+lIu> z1KG1{)GatL@F||DO<5iuOz&*Rwxi57->bunBLi=rnL1n?=i>76)hpqCy~LIsNF+d0 zOmsTK^RrTB?nuwla`RbN3=MP&9v)l?NFzWFhO>h;r{5~UwCuI-ej&EEABA)F4ApMk zKXDq6hGj9j^`F;EyjFZnl*NRo0Hdb{M<}jSgh_tLDM}PNI7- zJF)hdJ&;%6G-z#R_TcRlj&ds;P(HO50^TReZAlM{N>>eQqh@PAfP!Oy1y#Ft+}EPs zuVnT~%Z~BxV2_5ft)f19Qm0N;mzynLv0{msgGaOB@@&?$g6|j>w{1#iomv+cQ}lKe z=Ik~&j1k6)F$#JPwRW5_GM+mnywMMp8E?j*8R4{5mGy5DFXkjQff;QC1!nJ4r*rxvu!P-NV10lV6pj+yA~Cv1auD9J|1L4ghz>{ ztJ3o?HV<^uICS*w_^>jmgWMs%F>=Ry2q6kv(L3kX2{3C}({Lk1+5!Utgz7TcY?7*! z4D%Tft=6@quf6`dEl3o!70=Xy=B8b$s%PXn;v#GB?_WBK^)bo8A~JKtb!V+zP-9&u z>Rh&t7_@FiMI)eRg99b&syge!m?O?dzGo}(+^9U@?w(t`wlZZ3&%}&87(P-mK4TxD zDHfN7U*hD;j;xx0-uLFr$n?rC>`OCA#mJyZKEyB;_EYmBTyqzN6OCkLcp_A5n|#=P zO9k&n_hSz-A^;Tg#upwriK6pZu#zw4eNq^Zae3SIU(d0>zZBQn>zqPCY}kWrI+E^# zY0E#EI*qf`C4OaRyu8!0j2U)(1BMyaV>@qT?_=W5?z?{$zi69rIn4h$%P`%VIX*h= z(-n;+n^bJKUw-w)Xj|>!?kNsl3qgd`m>#TiYri42eEDqF!+^F`)3)AwFD5T9L;+a= z0X^3S(pTa$oagPEpRhmH<4(}7epixdHY8uk)w;|Xh=o{(%DB-p?sc(i^eSpFX&z?G zCcE~y&Q6YOY=Du2Nobca;SEjk3pr%@&UOwC3NpVEaUi#IY(Aoa&`Ef~&-uf}YDMFC zM(W6zP1ILg`6UI8mIY2n_+GY2#do>Zo``x-+G%;cEw{i|`+CybX1(whoM)*1tgEVB zS62@?pVv(o5I(6BUol!M!QmO@IN1+HYa`rnED862Hh_?CkI}GF{itHTtef!56-hZ$ z7>=JWZT;~%WDm*PuuC>IdnHUku!c7nFC&mHEE#Fl9R{J*a z*gl)l-WC%mj}W-?Leg<}!nW*!2aOGg6Msu>J*yr-%EJ8QT8qJ0j#_|2)>UK7{3R<^ z#20j&&MPaa9PyOxlsyH{_M#Bn!SIPj#-*@u@Y^1K52DabJXFzwvrdd4zG1QI^E~YL3 zwF=)}0NlWj$3L{b1#?z{hhRy$+w^8tiJ%px&~!R7*qWDIplK07*4^WR{U`E z*xTg|S`j<;*(+w@bmT6m=C^QYgJCRcCCU^ANY%k%Br2M%ncF4eFN%qWpY0ADK@2!K zceof7Hb#K(i(znt(vJ0Y2r<&US(kE*{pRjdA$Dpi2}dBoAy6O(B>=qH#b_0zeoAfq z&xU++E{D&-pfG>`DS%(_P~a_3#UzXQRxXn*`d3+%E@dgWwI(au0yqf2SID3s0FeX` z#v{tv*ZlqlM9?&&C+&CUR0x&mSv-9Tkjl4K*-0r+8)GYb(WyCcWi4I2*m0+d<1X22zAGkF72#`b)sY#DjC)!iRoNtXtH4P5r+|>mgKWgYd9v}gP z?;eN?Q&_hBE51Vdcn;#WM+F^iuom4;;1669D_n-to2KBV0jgwN zoi6EF_3|_NK%T)3KmcEKn}2#ZO{L>;g0MQ2VN221bfcDNf<%z-ZG8M#uwswD+(x9} zdbSjW{kH#Z18^ZoOnY9gn1p*S+Jghd@z+^4V4B3_$Gce10LrbL&pJ!7p^P^lWN9#l zI~>IY0om!5NnGDEEV3Y20d}MlyHC9a7z{+y?(NB{LZCeMU5>~Bqp$S+wEBB!!BQ^f zB;AtEF^nBoBGCg%G?sGTC;D&?{Wj1yQ$>CJ9Twc&y_5pJ(bJ{x9Z52Up26sp zFi}hf9%FVj9us2>lla1H_YbzM2q$?0vraN3fM_ad`WuA1hj+*Z{&fc6&l~AHn_ZfWP#hc@^a@RnOd*XjnCL)Gwtzdqbxk7vO{FyK!BY8n||;9O#;p!rl(3&P0-2775ID7%}= zZbJ2Lg9~WL_~dLZ8UsH|c}Qj7&vdjtu`T1+g$rAEg~=QR7SxneVPgJc&0b@2U(sfQ za)D;ULRv%!v)~$|&Gc|QKhPn}cor<$C2ggQ%5cqGkB+p;X!O^b%jS~EQW=mOL31cZ zp28r8h0JY;=!|bzoOHKahoZ&6;(8SpZiaQd2_lWn7y<_9aAC-cA4Hot)L8pf7Qgsn zgO{<5bLPh3Z!t85jUK0q7d^3@HgU$V=98EdP=D32jbN()uxFwYwFW*#V%w%HU=7+i z4X2@FjX{|whr|RJkIKNS)!0{?1He9*Z7+#ll0g%7^3y5}R&2;vmGff?gKSies3syS z+j#l-e88+t0inh4M9DD=x13Tr=$R(tQC-d<*NLliurqUMmLR0YQ~;k$od@02vjq+{ zEIw*ypx8YZE) zjD%$%D&cWTa zNLg8g3L`uco>kxb6PxiM&C*)VH=mn5cVgV-{QM2Gfnscdj5K$sDUdB($Ah|(TiH}d zLX&{oJr!01(qgc6=M6Q@+`i1Y&KlnPP74C*MO-nSa2 z9281Ba^#V&Bt4oq9i}iu92;2Zbt7TVaik+7?DK~Ec7R?T;e@6cn{X5vVcHXsVo*QFgzR*5<0UjEbr@eJo!Gr-iNqO4ms~KMb1TLy^7)#ohXVp=B zIRGv5){{IwXF*Gbm2h#Vlbz)IPcAm^#UDkCwn=dd|xyi0B}_L zs2I3h{QUUZ9IS`SgP%|#Hl$Zu%u$#DQ~UW$i=RDT1W~d;KXl4EqO;7o0>)URcqSuWJHbm&N`OpTLYNn+XV#1AhBBani{}NYGxBjd_+n3_ zQDqEIQTHJhNX)&92T+HIi%O$VOF#1@%MJluzjU}H4KPqEF@`{pw z(l$WS)CTw7o}SS}Bp?lDxne5KP|L=Nb2#`JG~%ioyu~zEWkzQ61%<^?Ls*b%NtNvV z2R#g&zVJb~qcu7S2oloDqxL;8<9=8|j@QxKx?L-{XtoN@@RM z7jNi+M(J!qY?G{R>-9oD(|ir+g0kbr|AY^d)=pp z+3R$av5Pq7H`{H*)ZWn_PiH~5lPEZ9k8!f11bt)J+VdDLtVJ~Q|DOPp(TbU@COBh)?=oD*!$4FP+jt`iZCrmN;)K(m-%XM>s zNd&6+d5)0YDGmI-T5vVOK^1@GvobuvoYPG6KXH8}wMv`E^P!$xg*UxYimYO^|B#^@ zyy~mk_;OYilwwSgN-o(NPlU_oo5=*eN__lPC}*I`l$=M$tMRa^+}YO%UifT<318@n zD;m^*;qF6I@HQEzNz6y`MIDpi@**lih#B{sEA7=@@fIM-*GYp ziBzvAz``2SX=q!RG!tX~5SF4LwCb38F!Pqv*Ljn*2Sde1)d>Zf!Cve5!-3$PhDXPiOqTnXB;XG8z#wrv2DYdrCAqFs(g#h1_&eP!Wv3OL8418(p*NU@J3vZQ}*_?0U@ z*qg;6kwx*wDOk!kl?9?f{`hx;zkC)ZeNH%5DS{f~XT2f%rZ5O#^g&gp^t~36nU-Y1 z3#U`fhgUu)xdYG_{AeMO1Ctwtp;ZS(D}Q43+T8*noio`sROVkU&o9gAx|~!88*-M#G&@gD0R>Huc=Z zD5`0|GiRddEJOPb{>R65qI|7hmk%XS0X1a>;vbpreHPH65qK=g8nwTz+vpD^CsU>6 z4;}%7@Ni(++yFM8R=0%Hs~)M^Zg}{~%-y@a|GItGXkHY(gy?9YxhBwJd1~C@C^&?1 z-OhGZ}R>X0%VYw#(m zo~X*Uu++!p3~aa(lt{#YYGjrb!t2wm0{w-OES6F0ZPv&yT?g$y#Z%+8Pr+iG8=5VD z=l7M_wFCly7{Ov@g>Fs_#sKPf5yTQG=E|Vuh7GOsTg&YoD9QL~FdFG5<(&IsGe@)9 z5})EbUcl3n9`I)0-wsuODR%qp+C?k7INoQ?>J&SCq^;fFWn1;#_pRR-+^%fvpFVS@ z_wIWk=WFkMv2of~z5TQJ^eN=ksjmMK zH!Ydr<%uAwH5bPtCPvwDB|^+-x*YN#g>g#tWCa69X(aHs%=nL$6ZI40ess%G+=&Fw zQ?Oqt;`~ia&!r=cL5wwRpC2==V~%G7&I*W9XV7DU_J*--Qx|#(H1G+ZQ&0vYie?&P zzMK^UwQ9eU$ny+J4uT+r)8sG|f34OB@4Y{Y_Vt>Kxez)5p5%uzY4a<$n2w*9;=;YT z`*zUG62&|mduQQCSg#**;}f#U3ct68YJlC^(t?4MM*$Ryvxrj7c^0IMMaTF`JjE2+WZprEuPtLE_7ACN{bJ{`^h)YORH(=C!)YQY|P4 zD;sh$7;eWhj;4)#K)fp(V0vgR=Hr^9_*YvCMw2YQAhOZm&N!4^VUo7hs`l_TrE4dI zf_%?V0~>v}NK?%lC=07w%|g5=Eq)hL!`vffrdjKoq@ACH|k?v@BC7~3_8Q4_ke?qN8^2z0bqzn?K);5|CSU2QJYFZ}Q;}wHrMc=S*3N_7 zGZ6JA<-~%1maN(Lw;e*<#2mdDhy=Kj9H#x@7DRf3ez|g7D?@|$3bh37O?UQ9ljeRD zq!#6gUwTrOeIM=i1ZS|QFt37IL2jDMg8AHjZ|&;RPs`1}tdgA(W$~@nZTbmKC7uNB zwsp4+B6zY_Jl{}rWQr5Ck74RM#mPN8KhGOlj^s+SXdXb_ zR`TKf&aW|i=|-%yWHTPNE*?@ozL8X5uh7p*rPVMVpQlJd*Q zFpBkuuYml33pumCAgf{Y%t`T66?hDJ0PG(#;U_DG6380Gs&zPoQ4pzEq17k(59jcR z=-*eZ{;kh8j|Dlomq6f=rn^M!r=eFLSM4*4jHmc@e63HPT&z1-LbO!)g@zTsLmqTH z)$18IyyXzN87L$X&Jz8Kb;V!X@oJrbVK#xCmeY1!=zMflqzS!i`WZL9_ECnva)v?>f+$a*jV1k_5r5K6e3`gYn=O z_G3-K3nH-b9@%W}?EB;;DM3H+pC2atf1PW*(pMKwPliT!wM(sMc1C{o2r9x4W*rOQ zD8sn$V9=U;sQn;oH=0(3S{I=N+a9`MEEZA*&cmO04C((A(~PveummR7IB5&dp)Mok z3%?(V9u%>g9_l+gX9;?Vq7CnJcAJ@Y?eACi*WY7{R?pq@tNQy47IE+1vdGohrn$%v z+iQ-KWfQ<}*c*#*EKiXML-k;0+_whI5Xo53LP!D4YC5feAB{JE47D&H}Yhluk2a#(?xnKTZ6n9g2V7HL4}%GRpTI*Qb)~*ED}l{!)+~MxDx%Bj_sb{223>| z*Z47rDM#CXZD9XcP(6h>MlLCUm%zw9wwUkSCsPm2HW}ozP0HSNEZ%qDd#Vi}L7o13 zM7XWrSujX_P0m+k{ITrH%d5&O@n{ELuC++gIWUk_eXZoHx>6o6-;K>}b51%;>^`2> zyYnwCK&e(eD~?Q(_c$x5M`FMW;?HLJFuK@ zF2|PVahcgyv!7^1#mXOXaDvR__B*C29%X}2_SB$~lf6}E&X{KXraYzJnYr~~T|I#i zl$r%x8hya>E6YEd<0Y7wcrDB~Nt0Rjx>HyCz=4Wb8C15O1$G{dBuaVyrH3c{QYnN3 zrEUGH=3&5V(YiJ#d5oDdz59Yrq#T5Ak7X1w^rZQNmYXVnY=^<-Uu-tOPNDRq2S&?L zniQF^577tsiX{bum{Ap(nfbA803ws7mTF*YYY=k)m+j*U_xgqZ_ad2m0XB~E+bAXS z_U+A_kJ;CK>=;m2x(7+*JVWkTvqH~Sx3SeQCEvH&at=IF10@?5r!o7FB;lKbGL|x7 zkcD-oZSq0#iaL7-h$kMzCiWqgcAAeGZ*(fU#LyKw#cBoGCWGmKVAjWRnWPC}&*?o%?wkzRnO<`Hx->`BQQh-Q}@90FqJWTZy#sg zVEd>2^NWj$q))f~(g*xwhm-mp`^DZ~)D|?&44T3=JGiND3R+oiE7F8ML%R-{tK0|g zWOuF&Qhz^n>#k7Nd+&dnF_&!}oB`(+Y(#5SuAl{s50+s`-_J0Bl-=DWoU{pr{fc+I zy!z3oVMtAK;C^kZtxO!3e0bvCD^+Q_=KgP<-PxX0`P3+7+tuIGbZY>Jl1Lco5tV9^ zrh;K5zO+>XQNJ9J4VpwbZx%|s?P@(>M4D`2U{v71vl$6wSX@EjFefvc(w3Ds`jL9K zuao0RhI#eX@O07%{;v;dC7f@|)=yPcadLY6HZps}aP4)kx+IA6pu85eNm3}+7l9up ze0Sy9ts3RFK=vRymSFp=AHFG*&GHpGX>aa#Kuyp`4sn)b`+`J|)ryl)))g1GX|a+k zv~pg3;8WY1(9lrXEH3q!HL-E+xl_7E+l_Vqs_Kaj2F_9hurde{IQ$lej1OpQH=(&l zFOa!aGbJ|mc}sJ-iL|`k_s_gHx_~lY4w>w{x|hLfLEQ*~NfxbI^>)$dEi|=IdPW2v z0K4)rC8oG#I{*l1d)V#Q|A(*rb#~G3wRM#j1UBP{2Y~DCoh%+Luf~Xdlx|1u&=j z9Kd9~s~fS5&Z0$6y5a`BtZgs_btZ+q;?QJr13w7;vSEpMmf#_%cD{TOla;M(qogBL zKE2%#V76~tA}P6RwkH?|C52&XlKd_ zl4K58;MRM0ZkB|e1BsZWriOKHgah2%eXrha%hs(fQ@_--H-hGMfdh8Rc zP!phii8wk4Sr=SD>@|Dv({ZbDC7XC%_h4G~)@A>5@BZ^Q0a2`AsimmTX(9y@ehHR+ zA&2*Jrj8rwAfwtBfMyv927a5}U?q1kBBHBoyRXZsd1szP04T!_N~9rB(8bNzz;ktY z_HNsNZb3_HecV15*i2)pA}dT-@veNTpFVjqRJW~sGoE3Ha$J2^AeM)MDm+Kl2y#*d zjvi}CbJi=ASYn~C!Wy6Bv=%|H2b^h+!m-nKAGIA^>C5Y1p=~$1cw)d^&!x4qqE9CkXF(w$rJjwO}UfHhJ*;z1%%6`+m_tL#(JbO()b6ow& zQ3Ahz{_(XxU0t=b{-{ibB}iyR@@)OPupwfvHb~Ow=SoCTh+A8pJc&4ERt2`KAA=7<{msfhhq^v<=M%oBR4!iV{ zzn9>y;PG9AqI{j`G+zBU0Q3!Mr!PQGK(W*<%`}?=C_L3hn53tQ0eeJO`hGd5yCJ)_ zj_Oe$Zb8oOkd4NaeQeO^z^o@MhcJW>3;C?(xFe&!DGK?W#0h4>I{f3+#G} zt_NSZ@O6ZbS9%^`uwQO8P}ZAo4#?tEj2uYVcOL;`-_pE!2CZq#rttrIrY1kNq_-;g zr%UoOgR*cjR-n~x1hO~Bvvp9Ic_Ft;TYPae|B~rbNQcV%$40;&;CowB_Xh)7>FcaL z%=vNE3}~cg*Dtk`UvPZwp*iyy|CuBSQb{l%P+g*-%U+Y{!WVKc6q4&TUhEK*VN{u}4E=cKk8`?ZT*2H)FBG z2VVDDa;dn9A|7e5zkp0cjkYetT~|MO@@{2vj&6cFzI=)5Pte_{m+nr}-BWHeDQ~sV zx?}J6v@BKz%BkQ|XSd~Ps6u_E&wYE?9H)Fl_K)vL@~1J^4ayv5#4Bd+CBwRiwl}H0 zywP7zWK??(i?o>L0%B8r8((39v@L<;X0E|6?XH*p&$9)!!VJ6}$@>t`V?TWgJfDQm zJX`g{BQ)Jq_x32wJMeVnYz{2X~-!Tmvy89E9kq@7=zg z?7Wpr(whA8iy9qhdV(w< z(&SwJy3-+e7_R=& zwcuYKx2$sPlI2<`M2IgXz=Q55yhWYXA-2fhqC10*D6skC$B+CbYk13wlF+fyTo~MQ zniqQv$Ryr*Uu<+ZxClsl4gUmc0F50==v#X-O_#QRNmH}_+N>*zZHMpI8n1`=_3Sq@ zY;;a>5Kpf-l&uqCX?&vnnY;Z5zkT;P1#f~M)x58TJqN!lvwO68yFHi$r3Bco@BC^f zU+S9Nh6Vq=b#AfUy-jIvq`R!-a5^E2LvnZJg3*Ndx5vz7!s=H83*2>a^WxCgpcI zGwUo*%^Ih1BHbh521%!4!~bPvZwrWWjMl``p}cF52fmc_058y`v#ZhDprTyL*5HS$ zf}N*V;*@x_#7P*iL0$Tb{RFy-iM2-_?gDN=0~0{(7=gG#)nO6!VV@g-mB6BXNkAZ+ zfIXm_xuUV%|9yG_>4eq2S*dO3OM$^ZU;2)xu4cUGs^jB*jIR!I5AFt3yJ?8fU zH2ar!Ai`y!vo;V+A~&I2c(scslWEyLZ^cL=?EGqy%)UQQ^VofVffRrif9;)^-Y2#U zWwSQMMdf;=h(&NC>?X-ZL(JiJLb@{9mh(5NPwmv}{^!Yg5kc(frO z=GH-4QG|V!W&$7$GoWoQ$K;-Za;6EH&s!k$Je+(dVGjs8Y9I9O*B)ORm2zY&7u%-N zqxP1)?T?Tq^zR?B2Y}o!;{n$IB%BSZ;HTihkD$O|Fo5OJa`0`~dR~x)X;A-!Ud}U| zk2sNyRNS$ZlR>KzSzyONrNHdE95r~kmn0V#ROhQRJ6F|o4(pjM`0U9H`BEvWsbp~SWvNXN>Iuc)GfA4Ac8osaz-sg>avndzq|HLGmizZAf~Hk0Tb zJU9qCDHRHOlV1;-XQbODkz8ffT$`$gCxdAJxa<`Tw%CuT!= zNcoX9V9;>~raOC_Onr=|uEX9X=EC*_ZFc=Dwbg5x2D7k~VrBlNHv03d{aJv$8mDXS zXwMGCiP2sX129yQDvv=OV6???^7bqikN$wd=ornWBjXxrs2EVYSwXr)6ClYXxiz^~ zsRmdS!bsl7%6zlUQa@l)X_6Kt$M=sr@sCe-`9wKpxgOBcG6c&?%pSM|xP1Y_k?xf) zGpdS7#xCm`Rcr`Dl&7E~SQnv&mkWR68N5y?h{d}t_sL|b6<<+eMbVG{y< zcZkM%2IO)YxIq+})cB*9D@K?u^liFX=K%ikuDiaI46)rWS0pW5v0^6U;?=9ZWC^Em zCX~2>X6PVL4oTJ+{mbd_=RMXAqW4F-DY&f2U2Y~Lj4HjmGH;v@2)!tzTe?|J_-W_R zPZxm1_yMr_7`ixyCsY=V^eVv@>1Nvfmp6p}EWqWLbLX&1`Fu)Q_|tEU{$drgZ#Ko! zUbnFenPPKE`RTkiT zn72yI{+EjG*MHKVD;RKZhpv;;28d425R8n5cBs03+!y$|5$woB#nk4!`hXk{)&%XD zLF(S%C(&=uB2_R{a10b|?H!*GfoXy8i1s>Wb=xpxB(niiFg(F0-79-L_+;iP1_R2u zne@Jc>LNCREhY^iX|YgdCsor*#=cZvmZ-1r$h?{#*$+?Pw2xO&kS#9E{2!-8NOq1xFF+%M7^*T*sprElun$g8?jnE)THx`zYBW*dF^7Ans#=VOF@Uv zL+M;_c9KdMyTSQ0Lo(u+?*#E2gK=Lg03ar)xO4rxckgyc+qf(Idfm(KbwWFC4>0Xc zpI#TY5%$3XXQ)^WT)VgA^u61`R=*Ao$)|A#;yd-Wp6gr$O%EwCsmt*6oD9ju6^Cr` zYUjVTCBGK&-Y{FsI|}E7AgtzvF9fGFiI5OVdZJZoFL*{X-d8{n&w6`%t6Ei~n%09N z3RpkG6H;KDJSb$gEuJ0ItgWN7DM9-wlC~mqI|m?Dg#3d{78H_&BYS0f8WNPg1)`GE zsv1h!L{a2u<-p$-V606+K|#=spO4W|6bFm?Z5CI>d&Ha+;hK979&iGiP($N_EL6k? z8QDsy@^B^=zk0PpFLc{tgwU%)wOlxi2M#We8p8>~fhUI?m?5zr!6zo(Zl>I-JivGS z;Gl(VlLq+$iR9`G1&@k}Z^#noL@YJJ;1B`r_h|rboKtUZszR=cp;8z?esaJa4oh&L zuuiM-Og(<;R5O%p$c&sxa1$m5ug?|*GE11;n>W5lKm|=R1v!QxN2+%*WnuWmFN8oa zE&^af*O*^Y!Uc|kKkwf29>ms=i+~PqdJJ?Eo?-vI(RbSKpUdZOpM7)BFXu~J0e;^R z0V7fS?k7X3#@19FSrs(|mCjRq7*@jsJrh_ms&*CZZ&ahddWE2FKD?i9oPNR!_TSl8 zfGApINIOze0`(&_djeVch!drJEX0i)!6ZSO1x;!PDZbb2$edeAhZL2Rgza`g{#l5F zrUAnNedK`h2*v8^ldlEOBcfn|ylp;+S-?k@58dGPB{3xCi8Mht zwi)0qGK7&QYHFM4C*nLEN0>k*jn?e0f?S1Sf^j8b)x$lX(w*PYFp5-@#fj*=)_-?j zzXbt0qc7&H(cbt67CLjc)!&Utb}ROa$Q{gwKWnif=OpMFANx zEX{>_0HIUdlqm+vh*$`y6Y!E%P{#v5=c-x?pd(6?#*N`yZpFexA`eV)%w~s7SkFXK285){NGBIp}AK&T!*Hc>D~3dA(SreQR6NUbh)9-M*nXz<JaB9Ty(vgYnl3dG`!Yq%D0)cHczNfJpIV(8LKW zF9KiK+5Ol?ejuvR5IU}=VLUdaaM?Q#9)iq*Z2t@ua5exdtUw&6c3@Z<4QsXjFhpak zaHSlXEkmd~etbL@ES)6^%|2aXd|&1Wxdi<$T(J1S`~*>{2(FIvAd4q-%tybxyuy_p zlih-eY~SEKhggCPKd>w7X6^Xzm5aI0)pbStvo9f52NK5_7n9cJjjy;BJ5D@=G612qWegwRi&S)AqE zzZ~bhRAO~il@Zt)lGGF}+`ynHB9t2aB5hFnt(|@pbJWR9v)VWnVUOM_qcl+zWti~m zALB5YA}EuUQMfw&ej7~nNo7o^?7*Po7gQE<)=g9CflN_eyY^w7sc{^n$n(zTj`X+r zfthdi5ir1*HP6g3)K2TJy%@tinfnSOZ<{=Uv+v}|0DY07i1aG_ObD#I@iQq>geRjm z$7v3P>rTuuJW9*x2T&+sl%L2G2*#_vx#Qr#f0#G5Nfdg0Qmm70iD&-&l@@>$OLArJ zp7r&msvM0|T&6ipA(?O|Ge^p5E0``0q?qNI8dZ?A<-a}<(IY`u?kK2~W4>WMT#bQv zFT$^dcAIbQ;IYS^gYJ!R8pVN+$0(12(EuV}=7!q{fSm-JalAFs9Vb7`8jI;dQL`1+ zCB%v`7&w-9$yXv0BJzDJgMqO>P~9jrw6}9IN?UCymj$0vdMKu;om-b#X@}+6hvWvv z4`j4a;3&hBe0r8S-E31>Suyb_0CKN$BjhA;{CfQqgMp$K=NNxi7v*G=xs)a$!#dlI zhKhxOs?8flktgl_WT`+Lj_l!yjJ&agH5qrx6crT2s;sgxs>GlPTl@h7AL@)He&ARWhZls#uI!XB?P0EgZsm?6 zOgn|DYIw3!Tz}dyGV&_x+y?bSMlPM8#7P>5NqT4W*U#S7{?|@Z++>~He#JE5NgW|_ zyz8GRiS0*bF$z`>|2D|~vfA7xEtM*+rj&kkaJ+cqxENd0nQGP6sx!?9?|J`u&B?d7 zB$!ifqz)-AgG%kgN9JAVqEK^JbFI@)W`P$jurW|jEZVT)Q)~pL3X(p&ApPz@GhA>2ZH;CjJO0uFkX$?l^X_0l zJ>J;u%@&r4LiHdQQHXMP}0O*1Pipo;lGy;u_gHW^3HN@&wbT| z`Qb&dGOz*T$#d0t+ttv(*t6%Yw!$rqJ8B4f$Q(yd2Svk58$)xp;%dpXi-;rGX%Ta{{fF z5jNXh@+Xf`aPu`K7a1_EpJb%nQc_bl;rxa?cq$qt^lpTo5#mGIw)}h*?=cg9e(ad)gW31Th;cqBvccx|r?v<2zYX4%+COG*XUF&IKT@E7 z>E+6pUbKntUDw+Kv!P_ooV8HjOB!vEkr_ywWq`WDPg}_VN|6F*BpjmiFi(bsLHB{I zfXV>Q%c`#kL%(V|Uus=)XSl^C&3^@sG!pE(m7MGCFgBL zxMxW4;Rv$CVV~>w&1DfR$B^Z!NDCakr1qgyHyqZB;CFnGZP#{HwK^*z2I3vza$20~ zEi!{?@BeTwA9r3e_%l9!!{A*RBxJ^z?`xfK?||(>I!@Gfkcw5fw=fi9onXG_-|EPJ z{`H$X!0t3*)Hi-mxuIJ&v;TVhAtyWyD3vCkFO!PqnO>!a!jJXp;#$hv`gfVszf)xh zrFwKIUkMG(_~x45q1jJECDC>;GByS$Z1}br)fqfy%M&5ndP>9Ft&zPqe}m0r+3;eF z)YceZs|c5ex*afO1ddDvjWZ*%HR2xP=;oQPn|y!k51j7WW$xh8FvH|Ax#Sq6?>m^e z^#5}v2madmK_HNCrV(wZEUCQUw>T43Dr1DWvq{wK&l-1ERsFMP>MO%I@{s|S_Q1PD z(}BMeJ_U>l8x7Vvof;G-l-~%au+ig_5?Sa}sogjabdqRdKvO$pa(Y zr!#(_FmJ~3gDEotgHFg~?MAF#ZTlL?jAKq&TbgVndj|Q8Xws*bw|AS8#g0y{+AxYj z!_kNqjEosqJGpt&#Bc)ayZ@+yedxdKr&*y^cO6Z1VEy34YJGrtZ7`iZvUT`2kwGB{ zim4Tu@W%&n7yC3SVVb*ICQojT=*K%l@j6cQ{fEGGpp ztS6-SQ?^4=Svoezl$tyb4~B2l5ae;S##SUW5U%kbDV8SeV~{a|!Y*9~kgb%wc+9M#S7@ zYYKZ8j5f^Qe6XXsvY}hIxvrE+Ljy?_j#w&c)c>sG%GGH|Jeo1+#BhFQ*gE|4IryK? zRsv=-(LoDJP$61e@Vb5lLozBnQ_)r)&_l|Bw8{QC4Qv+dPukdW&CSd(CUr)GJwqA7 z0eV{bCHCB^X&(m|e69tdm?}uNi5U!+vyMK9mm-61f$Mvkt|S%w=Qexc(u65KqogTF zZ>-0lQ~{27B~uyR9R_Jm3mMeac4Hyym@S$|=P(Y^(Zc+U~Jx1_SZgtEt18lTtnsI@QZR^9Tg0WEs_Txa3*>LeG^7t{` z-Ozabjgz&)S+ZZgel@~9Be4U_yTPys7o&5DmVpMECJWE0#NbZJkN-;lQaShPp-JY9 zGUf?rE-5eo*@~0!C9(nGJ@8VCO17=+-0}bDdJnjs_x6wflaU$9-ee^sj*)E2NLIc!nm}-BF(8<4M-0cjeUS++}|MqR!3Ikic^g~jiSJi`FjGVRvHsjA?D+veF3~s6k$r!^ULs- zOGFgAj`~1R5RCRgp#S)-lm1s^)O%|$GqVlIk@GV#|hN5wfN(af?qR{ zP+W=nDoS_rXm_R=^MI~8el0F3iRV8RfrC`KJSgltlc{l+TK+ZPeOm15B0u8_l&`f@ zL?K0s+H8rFh>RJ`gsc;Hq9nVYr4d(;(@$kx;l~v}Vv%epis#67zU$aTDi#!QP&!@u zB|jlv2TfZ#03L`_(^&Hv^Jd04KDG40j$fQ|aB^1^s2jU>?V4C*BN0=M;CT3sA7#CwL?Cu?X86uvzpcb++89af;G^jxu& z7eC%D;n;u)2*r~8MoeSH6C@@%B4|&xTC8K;aqYDch#!DJM$Tj$LMv92XnYK_0oY+e zIHm7hxRV7QZvRE}p!jcM<=&l3eG;zH#4`Na2(tgQyw{ij6KqFd0qgrGy`tMDKn>^B zk*yEemHb~>eRIE-ox^949OQ@!mV`woLI9Dmh?QhO)GCXhmhZO`m0uKy4&WbL!!7?8 zSD&?7-Mb4uy|G69?WGX^&rfTGlgTuQq&*^Ix?`*kC1?)pB4DBh5s)0~E49CyMyzAM zm@J}HZ`so3^D}Dqc$&l=63zlyOInAZt(*2!3Jd^YA&m4L@S2us=jhkeS`c* zC~H2^QA<_F(yDm0%C7uS>SF>PKb~cs%Fz~rl--~K175UQkuei+bhM%2deRCdtG4RF zZs&lh`D7!&q>1bDYe|{9mo4~b5do6Wfqi%wx|b&aX+dnG)2~ULg;&LijOTNjLpqZs zgtBbGRD09at3#;t=k)0E{fHlyM;{({KwljPA_OL`=Bo==2K!{$=t&37lARpY!U*%= z1mexjgDWNSFm4Rj+V%4ATG}oeQL)_P#C$3(9Z3WmXKrs_pcX!ej~kEHQ2Y#)IPuZO z`(>Hx0?ofZAQ0inHA+R*{;Hs02YRB$BvQMW^6Z?P8$i`cv!|^tw{-tSC-{j;RPu`l z2?^C8(62vw^yp<9@;qjFmY-S(V$R>W<^LJQ|NBp4AN|!}!dFkUv9fVO+J0!M)K_v0 z?;qBy9~&FHufRNN1xO&LwKiUeX*HrH*vgKob*qoa`k-|>Bc{rFtjt|tY0gF1EU$WA#X>bU|rZp|m0deVw&GP7fH-8fJgLoQX?&lEyNyx6BG zwp%_}Z}=?c5@a`wB;!lD0kW|`Ry+aP%^@{>L%Alq4?n()tPj31_XSwkZ@fq$)gbbj zHe*KR9(CejKlqbW6)~q@y=Dy-1}X~lPY|=0j=Ed_dpQ31yMo5GPdL!{so8xW}j5jkMKB6|{K(1t73 zqsQs({G4tweU;s1=PhELo06eq4+0BN2PzSZtXV2i7(d%_7Q9B)*Tw9!2e}VQ5_;23 zDjY$mWs4?$y)rDm`JEc4UGLrvT<2)5<;_UWuDzonQvv9lN<_8Ppg}JN{r^A>@~@2B zEk4&Zy|SiJNJK;e66>u3KO^s(c4b9pG}Ida*%}2$f38V%+9EzmfTkOc961sYWt7}; z;MbS-lnovMQNxlK3V|ApP#ocmd{|rAHM;$>6)QHfh=okM3E=L=)29tdeOV?B>GAPZ zN%MzC__~XHJfuZ~1{*oml@vhqoB86HPsaS$D?n=MYxfH%CmY{ezka=Eotv3gR@P$V zykS`Dv3C*^`$Wc^3=WUHa%Jl~+Q$DVn*KjwH&G7zS5CJSfdfC^ZYRQQDTC;V)x|1F zAXw?}fO+IqQH<8DR;`+m!@=8gMQ)0+bXahzuH#XDob+q0)YFlCzan1Etv9$&pUG#N zquJqS*o-5aAJ-c8foh4`Zl1yN<)?M~Ew%M=bE|y9tb>q+`Cu*9vG|YN|wo5Jzn{LQL)1Na_A2+1r>`i3|Qdd5JpA;bm6ZZ zf_IGQ&~c@T$L+L@wevK&vku_|mSFJZ+fV0?{PM$^$He;3p4qY(v2d zLt!7b~Hi)Wu&B@Vt9F@Jyp zBPx; z0QwYLJ(+LtFvYy6_8oat)SNdVAga9d9Vd$r;TPUKHq5Pu<)b!u7amz!&{6Zs4G|%_l`wC9V^?UbfA+8vgHlbb>*dTrM##)4p3osFq zI4r1f1!3pT*~DC1WB=mtks~4vaUSd!C4?>m%55c%eRmAIdIbK$(9P|i03(YiFn?Bq zz{o3^L(eid3U0EZh+$vP23N6HLUJ{m@s{AWpw!^+l@&0OcCv|ASj=dK6jv(KSCKis zoXVSZhx}M}O6Q1s;N;|iK0pX!#rJ9+r5iu!ebtwV-I{scdc6Osw$<>z2uY7;E&j{H zU~bSDv=+N)ZMXhol9f>NU1g&5eYdfcg#C$Xk#evz{Oy1c&mx9ee}DJ_{v zQ1bAY*k9E*xKgPt-1GsUVaAuu;zJl$=4@Dm1Gt+`~zZekolJ^4O8O7}dLzO&0=SmUKv zq|E*_NW6b=2}(X@lmA`D=@SN(n7So&@+;qO9y|(7p^yQO9^DDI$bXrW%eyPVkuz9W zb1fsoytY|#cSh0v2OlPSHxC=veLqL=^yG!hgJY6krhZ?zZ)tAVFVoLmO6oPI??N9W z6u37C2CLdZOGjrEQ}8ou$E(EA)z6=nG4nZ9lkh)ip1%zgFZ|@1!Uo_Q6IR(5(qv;= z;-++KopTj0>;BMjouz9ztN7#6+%=gm?|<-o-hDrQ*8?-Xnq~x;bZ)OvqslPLWedwr zJ{TVSk>tJ6zROhU|BVvw0;4!%x+M(ZfeZ6s?BcVcyN4CDHiv;e_jY=+NpZAA81X6m{o$IMt}odYSzv!PXjfEFK6S>q6{7;f36lQD zq9YZT{DACm*C3UK)Bk#=t&l@V?P*4d)~;8!!3{%5)Foa0-`D#0Un}uy_j&vHSl8Pl zS|(!3_O$0OUbNHF8eRKNYFDwCf8R$vDLvrH2N|!*wAqM7?d)Nn8|s1>h)>#f^DF(~ z!<&rks6^;bmY;8XG4F8hwAgI_Ae%m|@vYzXz@k@|#rDHXXn$+J3!euZ!^XI3%IE+S z&U751cK!^;E=-ujAnD9gfulba7rPBV9{9Bd)F24A;(_!x2(gIOg9n$)pxokD9cMEW zrGap(?{(khp4JeF8*M4-OaFIVen@eR+zRNb#tn{TAwv@_AQzkDu^D|91emO;cK$$G zebxd9x^uxfeR-l|qGHs?0zbDahB>m3Y4k}vA^fHGctzR%VJ}%>>IesDBy9#2Q&Go0)yug)Fy;-xG@K&n$sdf363n0dw7(#`t z*zf*+@MLpy+rK`VJ1qWqe@A%bYbzH$?K^puy}k9aU3E2$Q0>zJ<5k(Q`V@=E&Xx7$ zebv5S{_UIlJFvFpjV8%+?8|%?Ra4lUuZNbC1u?Dg-(gmKKl4#mc6P^o`T6;J-`b_y zQ>8GZxasP=cI{d>Be?ATzd9}^qo>@L!vxq1eFAdC*&oa2W9EYcNz87D|Y_2a<~TKEF5((1CMu*3&MKYRjX2^ zO}~EAYR3VQ%B04*xN&+fJ`=a(P|MT75Sx?A7{4{+?_bx(JS@M?Z^4=SUIZC(iA?s#CX7n`$reAuwa7~QskjLh~@V7@#{Otl()wt z0}wpSG~5z6j8ZMYg}M`;nz}z&ba4gqxN4UjOHM!U(5cfY;{=+|PhiT;@0S21SBqG_ ze0f%{A-kL6)}Y0z03sKswnLpU#!mIN9tsEvPQbQD07TsD_ih6Q{MC5u9|=CcDaY=s zHrIpR#0}beagH7LKkT@Phe0LqM7Lwkb-RbRPn*uaL`)s3AdB$pDTdiKsdJkbSpZrHU38F$w`HUGens0hJZc|3f7A*=MH&jn=%{ze4khnS9dLIePanT_! zo=|adujYrKLCmpao8S9ZXfz4dxoRXmJJ`+^b&t0`%6k z6H{kdZF#?x`M|3XYWe${vj?oqt+HrQPSi4J0ss4lLlvG$z9$GM{z+pu8wV2vS7rAM zGPPR1P=%U3WQn!4)BfPi?rE}ZgxSkMm*RIA%@UF3u3E>(VEg*k%J#{vj=8CH@k{Ac zy%NP!v)T`Q&UES0#X701Va*Y46q~J&96l^EiVx%KsfX9)1quuVqN28sywoLxocMgVc8`AY&}6{+2zy(j&2vgvTH}xPk&=&UjIP(ulw|Wi9dBNkIes- zlw2{yGbW~D))kFEZk*r3IaKV;y!}j*FUCR;c^J)|XKbTzmS|TcxJo zD&o2CLB>3JCC zue5)6XeCwP;G^}D1_fa(F#l5p%{p}Pj$e%lZOK7<@5DI`9jf$S^|3ljruGMKbT4Rx zbPIH;X_a@@)pGKh_XAN*)asha!w?&&nwzq^n^y%9E1yb-^kvg!KT_}y*%9u4zS7XF!l!`RDhWvQz^~|7Bde& zLhKzZUQAp=wd-fZfO%}ksBJNw{G1HoB*5C(uKH5c^AZ_dz{td@8gfKiFhyc)bv3mS z6zY1nRe3sg%4?4yHTLYWeIP z5*Qldf=*S9n%0ZI8MtVvxC1D1@xcg|NposlgkX?tIP@#4jjSLu-Z0f-&G z-F0`jeYgaSc{7AN1l|~}OzWCDi$`l__B?AXCL^B=N#rlLS5Aqepv*aC=hRjY*C9|`UX_37PMouRmaDV) zslG5yWNw+I(V|6dUe?d9e{UH0=K}i;SPx`oHHbXod1%uWCVxo@7cX7f{C5{{^O$pf zeDbPT6`z91eCfGyF~^Q6Q2$l81=)D2U8(F!fgV%YB)KaTLKGPepT^MRwPJ@*-_aHp z7h+dEe_7jb+?;vyp7_m<@%L}HXkEuETR7CvHnK2aoU8n#DYy)?%yJpY<|v$_bv6;Xy`FKl*6zvLOam@sf_cfL4tO7cEfV{ha`d>X`&CNB2T z(>hA11aXLO>W$U}W55aD%F2rR3|3E{gjpKzK&1at{8o0I8SDJ~ZJ`Y~pj*>-SWEE2 zudmnt!;>a3KmtHiFvThL;X?gl&h^}H5qe=!Y0sXy&soFo^*=a0v1*c4qu+Jtp@M20 zeoBRr>+gNv$GoB_FXqC93wM@&_a5C|)lEOSv7>{%y_>0ajQ-RK2FYuKOiz#8l#_R+ zSD(Emll1!ayQnpd*Za`5TT)9C@E>uUfe_t~y#<2lgGl+W0*aqI@nT0MlMNny2ibQ~ z-`yGekSy2MeT#4X?_N+QV+xpO2myHOo6v-axz%qLyjb4iSd!09=f4Bso$vJR8<~H+&ZuC{3{yr%wWW+Vc0Fyhqr!`bAudV10 zi==CJVs77>8@`v7$w>q~tgrux8RCytntrQ{&P{nkwKRA1PlRdWgp=gDg)Rz{uM17Q z7=tS$f^Nyyew#goM_rmxGsS?@a)&E`aFnfwiSL?JiSY|m+h`tATb7vG_D=j z8aPX)LpC7XjGgMSGHLTGjw(p|lH=y})x*1?aK%feP5X85xR5_JtEiiZPO0`CVHweL zUkD2eoA~gLWBR^T9Ij&FI(?3Z9oi-S6aI@no;M@=p83iHx=Y+ecS6JYajuO``ddd< z^q?5#PYRxk7w1Q{sm?5bKLs|r7rsAx34R7-wkuTTZHL^wq!g)vyvd)^7^?UuhhGc$xlE2spph zkyqEIA7ibV$myB)HEIlSP^)C0dtg4P0G<0SI1aykN#J7oWSm~%^+%R0C~ab zn60>NavVE9kO?};WUgx-6fJTc{9@!;Sb_59D>2{@w`ZmnYH6an`YkF`1(9S99!I?^ zd@Il{aKn4YDi{e%Y5?lnxN#$Dr{otC=$atWXF=7eUc0sd!F@)Ht&OXwScOmjF~DCB z=mn`LP5a1|eTGz~$gcs5fZrQOmJ7u5e12y>x)9HVZ-uD=tw_^w*kHA=hil)R7lbcC zqxana@y;=H!Xv9*wbq6JoVK>-hp}pJ^Q%|0xjFctwi4zZBX!&3t^ODi7&jLmIb$1~ zyMSyr-LZOD#oS?4(V@`Do%C!D?JXyCo9eV|!=dH+tpPBo+$|e?vR}S@g9LD!PVnfA z{E@-G=-p>pX0wOAL2(yWF79)6Li6vpo8}dc6LmF*zUSH>t7SJP&vIYE9y0*9XAw(V z!(H}d>e&|4;$s;vUd*U{wJz&381^javDrOvH~osJ(R#LD2X+fS8Didjzf7dz^IxNs zp(DMUSw5dd+h?zVek(FNfC{wrTgd^GGKg>M0}c01(}9j50x+>JC8d(mAWe$f40SD& zogS7$aGS;&Rad5gg2)0{HcMUy67R2c-0rOpI+Pv)LKR99skDDg80}(xghK( zRs^V)aL_@4Fr!fUZA=WeY7^Q=0HlzmnS;X;R;^fJfMILD(HidZ`s2NQZA?Cs;fMSC0tQxGmW4Npr6T+OtXZ!VNXq9NR;*ZJERC7(agULQV3CTf z#y?*e1hQpaCib?rwhrfp;CCzaBWGWReRdruE5!U8D6=qSXaa>!3UTMXfO)h0OoC(= zJ>zUyx$(Qu?GJMZYU-Sqm+i##Us}dmrCwni}U&9E{#= z&{3u>!31eNyd1pzWG9G5#6w6u?B=LMehWWO{Uei4;oVSMZ;@s2514DPA*jtr&t{u2 zWg$Xrdst>*U~^#nsT&BHWCaf+s4V0cS*`=)eyQrNVY7oMIKhmjU5NPO4X$YX9~Qz_ zw7&3nJg~XeDA&n% zbtMt>gIsreW@NQfxJs~wRTM;H%komXaoJ_W@ePAU6-A;crNtadkOJ9`AwzPC6X9SR zYl)cV8&l}lC~*||SHswX@}o?2xNW@0w5?u=6|t^Fq)G}>2@f7O`x4=A;Q5&DRk!4*rs@;&Ckc*H_zI2hQ?^;KAo&_Oj% zyT$j}JwtL$VesALCIO_+5{|0419$ z;yQvEDf^kRy`sX;%KS^S9tB*z&FfPC;15_GrBMG}U;33#NIYATSmQ}*ovhR< zYp1i9En;^y7(8{ScBdCp0QBK<)Vy^3e4RAm7+F~;yQc*HJ+(lbyR%9`rTo{Io-CjF#N^R;{r1yC`GfsYVNFu;KXsJJqo zV^Z9c@QqL~bh7z`dg{h6OhN16zRtyqfgG{_THyw6nXst{p>JLPbO+4evhP>L-;JtY z`S`@zg@C5?g^Nq=fZl&2uV-~|PiF$lBwffd2k-gZyLId2h~tiIKz;V&Me`~l(~WSV z^MB!sXWg&DUll`y2r5(qVHv?U_czQD{h_RV>tme)u3`34wvykhSobmA!L&i@i)x<= zH7B$Fqn`22O1Cy_n0;+SrP2)}+i7b~)9`H4bD#UIR`sK9`QB`wVtJv1hEse-$nje{ zhSX|Pb3>aWYks|2mf6zb!z;hCwGW=ZdD;KrgYL^3ugP{?a~yYzz?qTD*Joq!o5(&7 zk-bCskv&y2udJxC?q^vi3JEELn0Pnf(HH>U{dR$+1~gcEGATg^>L%1ozmEt$+E_<;q)ZIK=EliM%sW76ath)M41TFU&-@h=6H}C(*c@Y# z=5k16sSesRkr|E(7~}njt-i8A4ZQ78o&T&P{hbN7x*Hb#6Jj@=ICoABH&$$g8Z7o@ zI^$gKCwOt+12S+jUiQyX}M{*%HOl|d1%k& z-tuNH*u3Z~q(e$g15R>J0)i-P`}gn9PcXO*bpCpIooCIOC4Klm?*Ztd5C zSt1#yJQ#|p<=uVVYJrtYsmJdg(O*|x-P?Bh^y!xASNcqku=NxMr4%KwBgLAXbw$;M z4vM~@Cp-bKZZoDldHuNBY;H!@Wx5CL0U?d|E#KfYCoNOg#>R$qRI`h+;+4=<+fq|f zZt)mY=I1ZZqykAA(ypEV&|;@GYZ_Wy_+so>_PK*Ftb_^+QlTi^5cy1;`^1ukJd-b( z3oI?&>Gi~3f*)C64-ZB}tZS+-x^>$4-+;t)K*iQ zV`(`p@Q6_uZS5P-)2e9!=IK{?ajQ#m8&b$l-v00}>qW_ItCAu%a7ILTQI4@8Zw?kK zyV}>7eA@JyC>+VR{&VBE#yi?-YHC+p3=e-zB%mCX_yM$bi=bbG>5!;8t5>fcM?Eoz zLHLJ>K@G~ed+{NVV*B+ah$P&N3ctGauC6L<_k(GJ;~O58SgW+?F z{;mf+UAg7dJi?5T<^ayjYy>D`d2;pY)g?#3C;sP;fW~|OsfXQ1KT1j2?BQX!dvDcA zCME`ZesDcrWoJ(rtN!yUJ1(bw9B;LB=}u~$&7Eup#m)g8Y{0TxO;WOm$y^M@jq$Uxhhz=4xOcJ#9Q;&6L&?ZnFd0GzfVl<2Am(Z+4zXK&pD11+A*ah~()FYncbMJ#$5@nn$C z4EGS~-R7$@HT~}&+V3v*ZmIlc`>CtDIPnvEGFAGmkRk+D**G-}jHYtqTu1({bZ-j)eL7D9vcTf5o^HPP(a zYES#u5TB)8mfD#as7sGvW8-t|(S}|~Q^IU2c|||dt){`|Eg3)DUJ7E#MhcXi8* zXuaY3`h8lq^8Sk*Ga3mTeel~&T6wv-e%xNa7EPK2eje19NiFyp#@Xf`@#Gf$i?->_ z6y!#(D6fmcph_5aFpCL9VK_NgBu8e;2P>FOO?hdl326vcph?rOZ|~HnE%v9B49Lyt zw0K{8L$TqQZEY>vw*1C;YfE9>YOu5TCjHgcoKtJE>(HUoA9{R##~>|m@|i|lRFJi; z12bU~RpO*pBvu6_aU!UB+AsmRr&XODq3`}!voz!L5pjah^vl;5U9I+nWmjCBEn^_ zhYxi5-T(>fAZ0dT$MV^QwxsqGuiyX9lK=jnmhRYpYFJG_jfSmTTfEil+O=yBoI>G$ z$d)Pu?>F{zFj`ieJ?`(pmtPajfDPbN8;S2LR<2an(Aa>-t1vRzWB7P<)@VjGqJklR z2HDiDS#vma*$!T#`v1!Xfcyi-^G)-p&Vc83iHG{Qdw6vI>>TLiHI*v`r(5>3V%c$s+l5a9W-eLs(WxxsTULB6k)FXRwd5*HP31 z1jXa0PHkZ-@rG(w77M5OtdFh>=IeIqR42@3{4Z7Tv9I%0RAgsr=g(y#idLRQ+IQlN zO?q3leD8q+T6=CG7zn!bkU?S(Dh|_g(;M#Fx6hJvPuabh|M@wWeWqROuTj6gQSS$c zb1L1wGRO6E&e4yB<>Z8skhYfGC&w96r)_UNq?Jgu>a^(RDvU*JU1Si*4CNDCWO3OO ztd9SBtaQ;*W2{be6jzS(8?owm^o+f14IR6>V05e2bIs@Zh^$*%I2Tn#h)o~Ye>Qw9 z#7apkR{u{tH!wJ%`s>ife-7&y(>Z&x8rH0ONO$QDwLFo3O}F^Uw}X{*6-a1`=;bi``fOUZj}x*Rl~RcZh7Sww)X&g0*e zg*wD{>rCITQKKpRU!LQsvlU!POMc27Z>S=r5fl>uETn!|F4a8# ze4}|tAw+E=uBC_j*;Nu_ECLhxObtTfb!LGh^vV})`-@qA*J&3N5I$vBiOU*twBCb* zsr}#c%_1>_T8MF7E(!B_VdRY1QUZ(BWvEff4?@1%Z4snb|J8Nzh%eL zVnv`wh!uje5(lI#G>dQ-H8nMrq3uIWKFGfp!K=~(u@deht*M&g*NV(l#JQLYZGdV? z+TQ{tph5YXz}f8$WhbhE9!;N=-Q+8k`7RS~FP{2ok6_9?cIEaJ^(p4M)&MX1A--3a zJP(cUpBaS{ik59!L&{LO#a31%Yvtp8{e{yw`O*B_HT$GKi`vo zFOGVQhOaR}nr&lq?!%{lW7_Y(j;`VG-@xXbd15swlRks9@H38cEz)IixP;pZ@gE6dr zu}!;EoY~(Li{CQynVrKnXr+}B99rm=1TSH=;)|~YGiSQPhUF9!V2lJy0RyH;lhPhF?#Gj9YqW0&?qTHC$#k#6 zdsc+BUu0iN0f=ogHzGVdp78YPeNwyV)kT%44)&zax8cF8{`RRY-1&_VwWBjT?b-%Q zQ&nLNRN%~|!$-E>3EC%6Hx#>D{PstuCwC$0&v-KDpStGnzwF*qH!rx-KPTh8+uj)_ z&Rm(Bwx8%6wFf+yg}0b6W+}RGG}y|IwSUEBue#3%T(4|4pl5Dw?&mw)6=GgUf~xn9y@cU76afUPTI=eOP)>i>P0%GwFwDZMBasy^?7?Y0FKVw8EsIm z*_M{ot5vHO{!r*_H8*J{9C^WSz#pt8KTlDKj-dvX%rUxTx*tHU*UTR27br{xYB>G| z_V!3iOD&GShh*ZUq@D@S2(7z)ee1ZmxQyPjQI^HwmqkIXD|diN)9vr(JX0Qno3C#x z03+s3yWd3LwWx-iQJ#Pl@#vp>yv`mJMmj}JD`>HR-Z73P!UfN`*Zqv?cdf#W=WX|| zUH~{P&y$@HR993vO08P8sMPMoPC#e!?#daIXu5!x_DiJFm^g7)T3>1}uHrmAtAvU| z@sUe>(;VOkMK-6rWAC)Iv?jW?Eu^?$n4Lu&d6bm2-qTY}BnwyC_-xrS%6Gt!z1g$S z+3nY{xJB!jbjfCh#7+u|DNZ+hqvgXAh1oY3M~q`#Q=EqTftp5Z&K08S1Dn1V`!hT| z{OS1;`|0-<-6KO$GuN(N+cf3--4Zg3JcZK2%(~p`i zsW#~psWkFQ_1Er0%{G=GM?MK)*e>euI&Yj{Sw$z_>m6tl6Yh zZar4g`o%l-Bi=K3y+Kam0{-6Ag$LIGJ^Pa%U3>?1FAp0to;#p2G=Gtr;htqV4=@(} zq|gk|td5`C|8#X7Q|sSpbYK;mXBUQ5YNN7? z;_n1o^2SbQNnZnX_1$@w5vPA(+2C$vG=*@5)7E{T_u$@4BV`nQ(r91T-Bej4%+lq{ zo3IvFYiHA5BNt@gi)d7H)9^}d;5c}EXN=kN0XnZ-9?AI}$FBglT@3fMAIBcsM#WJw z(C=fDX1c(cD}Mq-K+qSkfW|I(D4zbymTu%R1<+IT8vvo<^LVA*^Ph$2r$k`&5IOiN z#%1ry4jsXg=}Sad*uAiIwrGt4Ff<=SlWFV`pO7$W>y90bT;Nl6NkbQM?ysp!mYki> z2T<8HcHFoCz9^q$F`Luoz9hC!e(>hqyAC5pjy!#T5g7gV=<Y;$QAmNs#e`aRN;F4`=7oEeAGSQ#EH=~B1h))EgsXoIDFt5g{~<~kLr|`o}L~+ z{0`b4W%p*}af{a4(Qs!*t2OJrOBqeZNLkVEL|f|DEbAgl-a~b^jGnho$HF&wir_r zK0P1RwOh9UM2La%Wb3;SB8q2z)!w#q=l&lR6_amGn>H;lItQwzS6;DCuSMg1gQr5( zf4|h$)_2jbmuPPcDOya-^6EC}G4wI2ig!$IdY)uvsi6dM15HMb+`Iy$s8Y=4!oh^u znk^ilOI4_f~2ZfGPWW4otZ3$LBn1Kfhf=I*#Mcq)C`e3#JFlDkK{a7E7a^@Rw! zbueYt{`fNR6(gE&?Hp#*2UjpSsWikv+l*VVR~gMiBuei&dE<}igQnq_$)hzQ{@w27 zw`Z@H*G5ixOMYqt3};MNRZF}h19cYANxK2^TQx1;XUuqh&?TKd(?1`FAQideLt1zj z8ORctJ+3&c>rg_qp2eLpUM%hxjGwkP2y1Uh!*`Rcq$u2)YdAa_lp|!?4jS{ee**7( zfeT$DBNgww17fd9H?}YTSS#RUM0;8E{(3vg5neFNR+KWw%$$M6JI`!x^^b2ol{T81!#^hbLJ6jl5OtK^gB&Ky6bxHG3ns@1D5u#C zI!ZB%WmwxaVK6dOA;3%gRhYuA^R>{SM3?PO_WAl9-taptlLOUxBg?=h3slQmxBs0* zKfkOf(J$uViLWxA9S^@Yf!hIMbhe7W-{U2qU{y10u8>y6(iK&#xU;oL{UKc{5Q3=o z0WU-PT@RT11vDbWR>hS{+GFMX@pQdHhn^93HEJ;Zt%0}pWYaXkq>%eaEV9nFfX9CZ6MEY`%|;2G6mWMwJgvG_6HBVUbAM0 z-pFS5IzU}269-yX(7D6`P$?6+sfep`^iK6BYKWsNHRaKP<$Mu8CIN~<6#%bIx$XE< zdRAr;<-_9@g+eG^Hfta2$rrqns^^{hoX8kYuDAaZ!Ie zlxHm6igyS_2W}&ODYLmnB#w@>B+Lgrcw2g@O(q=fx1NNMQ#SK`1rK=?t>dzf&w4&j z?fysEw|Hz?Lh;mD|Fn{(+D)4@iObBqI&_{$R~<{Nl(@rs_6O=&Y-M$bQHzMhPgMDU zBe<25_jC%~dlYYF=|{3CP5jQm5s36{=d@(J)zj0P7%Z~+Rh^*zaAmZQ&y4f-6sku1 zKAO`Wqati6a0$Pwh;vX$fk7*#R)mCi{TP?%$TvsBuEa@K%1Ct{N^ZZ0M85eoie#e^ zzgbZ0jhi;%Z^Xh_!H>?npVBegvY z4B;U0wmKWRF9pFv)+B?R-*gNa33AuA-fX&(z=DWn1GyF%?U+?hYB*lCNY|pC@v{t6lR#saPJkMs& zzTJ5kDgX_YF(Fq`(7aU#BHG(QkBWchzIvH3LEA`C?)D7uPVAamBF%kGe4u7MZ0TTUcc;Yh?Lu&d(1$BHM58E~WQoh$g9na|Gcu|rcnYiP z|L(!PEFvfn2Cn&R5Rmxzu?BSW&J$lU`Pkdx=Ax@hc{bbVd@CjP!8@A4-y3e#H>Nua z3d<=eD=D-RH`9I+TBOTi%KzTs%`LUv^@0(k+g_4c)^n$LyoC5KGz?sLsYPASK0HF` z?>_OR>2jtEAz+Zb7eB5d79SWG9b@1kJzIoG*5y`z< zgB`z&z6d+%jHeULtKUNaOoIwWO5Jm%lHtm@U*cuodHQtn#b1ck{SsL|*C>@^G2#V9 z&jOnXz5{o+H{8Qutpk0M@l_5=&yJK*pFe%7X9EpF-G=nlxJ2rW@*kmaXm3BLC}2?D zJGDr!Ec4gTPCkoxzM-Yu6_37nH*{u5OpzkvlKJ#gX^303P^laDP4((LX}&$J-sqII z7(pjBYSv8KI%;jj6-%0bMD^1?OZY>)=7NSE+7e9*}63SC|j~(iZs4{QQvS%N-xB zOXZr?D)BY`%4BAbSOaX@ym<^4e!nsrirk^KTfN+P#@kYDF;4NzfDoFzl<&IW@aID@ z)I!>_^}{MP?{3~|#e|Kmr_whVLmhC;|e^%?VYjS^kb7<9dS-K{t41mv&5MmZO=TP z^XI$g5@`e1uuWNK2PTi30nP5F@dP(AU#g^_XO&(IfMbw$;f2e@eJBIt zQ}N@+`~l|uaTUP$NBtcU?rpQL$b0Od2q{B1)oci4u9e0JgRjj$N5M9_{2}w z5=IqG{Ao6&-k}{nbrT20!o!^*5%`^E6CRVK+}FN{YKP+bYkKamYGUb zp%LYxYx!ts>6)RGm6uZRlbjdpU@^6khQ=Q2D7=i<=Tvd!dJ8#m=#-D#7Qb^Q0b{Dy ztf`$G-65Y+2hl);md^BxqtE6eSrarm+uE1p=Z93kEcXoEJV)v-g+${7?ggEqo7SSQ zjDqV$B~&&$I>39#lS4i}^Dvn4JN(3HckfQ+Ia5k=X8w1G$KO3ZoK=3N(!c-edtlXS zY&_#=9HUn&Ecrosy(uKbE+p}5?$a)28eb#^^Gfsle~c<*L8{4s2~5>YbJ4&V3^yqC ztilveCym3Qx@ov?Z5X_@0kDL62ThYiKCJBXyINlk%gNiLMfGd2oaDr!4A~JyL|LC* zC3MfdFpOfGGoCW}V2|~M-48H5SR<81S>?_{o&&NP`jhIB9TZ0AJthFXO$_3@+yHli zX|h*!rB`qyt{8;#PS(0TdkzDH6luK@2Pt$m%+kCkya(^pF=dVdNk9skqUTV0*!BC@ z9Z+FbtXQ$!^C$`Cy~}gv5ZrJ@5flw)sm#1GN};;YUFQ1e2xDi7ni5-4Is+VjXi6sv zkQPInzfH^^2=;81$J48-Twd`(!}aXS`IopUr_Z*|dwOOI0Dx5gOeqk-ZM=J>mkunO z2D&9<5E%0>&bq*qV*$y6_1UIt>kLhqUY_o=E1bGA&OWy8T{|f3!cltfLpx z_+RMbpJe(U!i#Cm=V@t`Zo8yfJN}}d>#(Cwh>PhX0q znAKi+w?_Bp9v|-3NCOeMXLtVNWm;}m!R?zpiSlyLuHs6Bnhmi}>_c789_h+GuBoqo zqf%mdLAc5Iw26yACPKg7re-qTlatWw!@rgU-%iP%!Xea zaqFFa>CM9N#e1^lzd&-89Vp-~(%C+CC#p1fVOzvU(T7nZBS^6%%yceRW9lG0=SKH_ zm^x?7%Dd{5JnQlO`}eo5jHO4sdl#RUhvDnSd)&@VIYaZ8)o(!0S!<%N^y#{*q-0mj z;20Qv>-T1Xcyu;$TnA$UtaT&IEk*gqV&15O-awtZcS>^Sa^%owsgP1?_FiguuZwM) zyzskSI>#O>jNy4*qo~F|PDNRg5#5v!1UdhmcBSaHeL#hMN3 zd!PN-TnvI1_xn@d_xSM&<=={@(CT?;2ap^YqGAj>Zi~JG0usi{+21Y2Bf#aF#f4`q-JpWvq5u*_}T z;qJ=@nl5M1FI(OY`1st2k00^m^`B`p$L`eXf8w0>O0d*VOy{M~7M%pcuxATAd&@>g zI>KtZ!fROo@z?AfONErx&#Bdd!UEr~g9SjJvX)I*=kIi7j%1a0bdZxOC8Ak6nJPYH z)26D*F(R{H_fzRLy%QRyj?bcy2s8=UdifT?uk)uCcT?}82t*zAFeDg!b;+niMnuN} zp|mT6mC1FxqcJ8!2x8v-SElyu)L~_!cd!U(M`(uk2hZD`-*HSpDpi>H`%?Cue70(I zN6qiST2s%rka;CP{(rsoSGR zy@XtiSG-Jhl?YYy-U9xHpu0>X^Ta{PTr|Ua#Jo8?&xwpJQiYy zC|g>!s&j0aZi|QS)IPS8i2^|2N}$}6d=1{ z|4Y#d_I}QZJ5kF;EX}-Y`>0;?=3RV(!8gks z%{RrgGIi|GzWp&y%j)vdZnDb3sj!~|*PSh9KZ=1AWGou21?z;vpz z0tyd0>Q?FKFXoVd!duQ3z~jn##(d8;cltU>zz@grF&m{0qp&%3+UDuGC%$O-bXwL-N@kSgS^j&Yun!x-EZ+cqk5!$@#kamkF*rbZ=>& z2ILSqoA6{5*-6sKhG!KTd-rHdEY)T&Sm2$f)-3Rgz=!}43^ESndA|Om7kppwx{>w2 zg|fD=DumKXC9p*{kAMk0T`~HXnUqTSv}-vzI-dRl^LfI}kmY+uUjii=Hg#%aMa&M( zmS3kao2*f-=5_j@j~AOThd>YM?1|e-XwF}Z)xBHRgA*nrap+2Bp&p@3E2RJRbB2M4 zmF6(7t1PWkhKe{ez`G>xGAAhuL_^($nqt1;XOWP3XxvRLWjF)@V(*bmA_KGv{QIs` z&@HfGPl<3qSVmk;37mL*`0+jKrSaGyDUxm@=u4#2*X|8!ZaQ1YUjqsZ|dUSOLq$eKdKs!LrrD~OOHfU9XsrDeobDkvBS70WVY>5Y>>eEs~ z-8d+Kij?`4P@0jvQ5ix#ni{K-rE-j~E#7jJS7NpV780_t-N|UCe<;R`A3U7?D?Qwk ztO)|F%bL0NKUk(m6IkyHgmIXERcNXer&I6z~jxIF3^W zB+vp0d%<`x7Q>Wa9qvMO@1VrpxS`+v6C-60pP?#dsjDeB{RVO~y}C@T7b z>5zHq%TL2S8<{!G!+}}|MC{%@1|9PMg>+Q^FU`v2KF}&8l8r#ug7VRvHnMaWs@;ly zr?KHv@FeXhzshEYZJrZyRJo+d=Vml!TrJ~p&dlg0Dz3Cy;#n$IROEswZ<_$^cHIF- zwmKP2emRBd{gsD5+b(6sIa2u2tVXMYgU{)xx6o5j-gQU|w&FkUQ6NdFe?!Dz;aX zc4&XbRbGaekYd-rk%r{w&+?_u9|Rg0c*Xxilpw^|5iNufN>#S$&^@-&fiFVgx+Sh; zkh<`GZD4=X%R;8e1P~19uUrwg?J=$2mHZ+c%$_qxqQdoS*HkFpswiNGre7APoNdbN za4V(S*7nDivKw6MZ#zJ+9rp zU0tTJA zuU=s$6-}MxtwVS%A!%-gy2|BsjZQGt2__j3d}JPCfp z_Lc)0QD+5C3-Pfy2bNEfC~r-@h=PU7q2`I8fnPY z^}>zi1Y)P>&P=N#mW-ve1%`wT>_0Fk;^IXw)<9_bOo$xBmruqAZw%U|`zvD^)*7*@ zXYPG8OCx-UJ!yF`JhWFLkGDu|SMDNPR*Z8#d@y^Tx?wA$p&xDe{)Wm4;BtCd!$WmE z+yhNv?j5Z%^z_Wg(B8;gK2VW#SndlpZ3xA8uBU}b&heKnsEX#gJf`1hQC?M5_4KS9 z8U6D-K0lEKHe0uE_d3#roffAdG4sS&q3E6S6;IoD&(mPWpANwl8j$P}$|5*MEhbr`Y@ z#9Sw#AO5|0&hcvm7@k>2djl1{5r@dj^=zgQSKYcl`kMdwV~^3h@&D>cOmq7HXVXXy zqY)Mc8K0rzuy3)(1~UZWqme$J`kgE$N>Id9kj>yzeRqrQ)iacFE?wN%IycaYFX(=Gw+tB-MV%aw-p45MhnJ*%6+1Gzq4w`efB(U<7wcfGkMBY zK9gW=GF^>`h)DZ(#xzLGL+3CPdh}TPM{s3kjIzx|G-QvSJejmumxMtHDgN$?D?}OB zv#HCNW@tw(r3e#O4X-eV9aDw9Zo(d-O#qju27^4qsL4X}&ckh@T#~gaR^<~gDPbV8 zJ72>BINR>*j|}6J{CA!ig}}s8Unkw4{-btoT^;J6Q8jc`iw=qSyvd;E6@)(|n_`?! z+z`&yN&R-3+6@Uq8_B~I=|V-NMH%mL_!Rj8CzEEvZAkgX6n{ANr^n%)$-kS62R7$^ zv4x}!+bSkZ!LXJUENDvHEX;=%0CZ|`W^fVbRWi=k<*Y}H9aE>7mOBK$J+0Fp(1_dQ;gPLSWn;-D@q+UiDlYIVE@fqlf zLhhwW4G6WJIvCnqcv|{<%+8Jj>fOB??BVb4e>V8@x0mK$e|*REo@FtP&&z8l;Cu7m z@d<-k{wlC7%zfK?72GH)m8!c+4ij&dAC}660x#@i*yd3B&ezP~3?LDH-o9n)RQOY3 zOixjh#bl&OuZ6WA934^@5)#^B%gRs9qJ+*Sl}6c#%;q237tx+zQ=cTY zX2&)NQ4p1(t$F^Y&D}Ut3>Zw8r!FuhX+FMFN=Q2VrZC+n7+JVeDAVqIMG5&Hcp0 z*UT>|S{v&vgvtaLz%Cs-H)=_>mMxEHJ{%X{iH(BTa*Jay`o~Hn<{zxe()O5+J_uxI zqX;#Gze^_tw&}shxD~ix*FM%acRuAFOblB%&X~PLyE+_cJO%U|`lSjqnAaqtB`^A;l3tIKp3middA(on*ZcdUOLntP zqOKZ3&j~(~I@bZ>kU2>6M+}}eG#tDOF6Jmm*NezYHpbr?JkTjb^m&NtKUxk8sA>wn zI&mW`o*{1+|8o|+&c(AsR{rlAj0(f@iNTN%dXC6z0v+`c4dO%>zJNBK{pv13n-tns z6_u6lk1sTh>l8F&DBG7lPagI%FMJdr(3%6Q+vh^X6k`L{YRw*+4(~4l6m45Uv@||@ z^0aBGAVLEC`W2kw(K95r`hnWJ3fn{2MEB7Fx-zIP9u-v$n0?}7Q=>Z46yS4<>&N9v zN@H@$MS?(u5xPa}$Yi+qG~ARre1l=5(r<8J^@Fs9Zh{OWg-KcftyEs~0BwdaHKw2& z4S8eh%!U8h%DW@~!g(rELB!MrhDi4M_5V8dQ2b-{QmCi#$nFykEw{BdOJ1z=V;$!Y ztDWJXrtI`7I8p?F%|yfNy>OJ>B(OY1P>b}pY{6w=(uFe(;+e92p0%>{S(P` z%e;Q11r>0ZsPd?OI(l`bHcSle=`g$VS2{PY#nb^wSbdw8NV6#oT8MNzO{CXBOdy(Q z6fK1^i$nrSyN*JO(2siej|r3&scu&;SN8f7r#KdbBAuux305+88U&>;hLRZvpLxW$IVAONyu6S z5KM}RqCj~}7We5**fDAZv~|H#r=3I$B7CnALi}HmANeKu_AA&pB@CYdgm|lq3;GnH5;Dd^;H(+^3SH@v(_*LRQ zf%Y#NFZjvRmI=!ZbOG}ZS27ati(@Qk3O$Kr-`1K%S?F>=-PbN`7%e)AIACIO zj1W$N=`V31CV9q;@l;d?&^`)zHtrvllz^iT|8}3FV3w?hY9X)>CVh92&}S;R$P_0; zg4r=zec*$h8gBB&@X`bUf>BVMi*Axt^k$>C1*c<9dxJJd!160C`YpEtf`|q%(F)8t z7qlq};VP{t-@{pzg6KTXC_3cu7_>eD2xb&JzHDz z_3|vrOZHE6J&T!XAQ7KqeDa-ZwUQk7i47Is0pRKVhVt=$d$~*g_8nGYJb2pgc&`mK zBXc$fSP|PT67ZIrBWM|fXq6Gj899rQ1YFER;`!NF7(#Jd!1_Sr=EF9~g2E@tFq6e5 zoIqXRHL1lj(7a!;kpoAKQhp3=xVWmS4{W^~%z?th7?%$o=)N8hPZR-#2$~ozfZvA- zGqi?$NIX8}lS8D8f-rsX!Jxl=iGdFsQvB_{xcG1a5R?c=a3P|oGX`;U&fqoYoSeXS zGt|_u=Q3~i12_ep?&8Z8-#3S7C_A^hq5?lEX>Dzd?eNkzq6>EI#*N*`kVnYKh}0Y# z)>iUaWdF!d80cWYyJ}1%<=(1Q; zl5inha2+9JUorz=i7}63w!3mYwoW$u;)~Xwm_#91(Lx1I{62a4=rLm!h~F2R&0!TM z2*A-7viL7Yzdzbh0IgdHh{CJuL6MA+N=ILojpb>P%UJ}5CI+tIYJHM@{=s5x-M&r> zO)1Tj^1XNN+-XO^M+NjX-R}vGZwF18G6gP~zNW4Iq%;&bkTQF;^4UQ@C`f}|xSuL@ zcO_L3Hv<)?UrC`LMh@x^?PK}e?!rAySVZ(OfXW&{)mj$lhI409NFrZRJh~w%7JXQV zV(ywT^^1#+B%!~70`DY7KaVUX+0hw=U)T#@;57t72McLXX!c{{5TuAeFn$5}YCi`0 za+jWwk6yE7hu}G^~tw_5%eW;(p; zZ1`Ys`KhBo7@yN-`I@y9{}BE7Zpj|~6?Xb_1X782?CX>?b<^G3gW?e@Sj}C^pHy{s zRzSJ!d6V3noI}ykwn?`3nOoELYP$7_y64z5hIyVZ4Z{--I_-DGlm zvrcXb_mUk*Y&MDDk@oO!fBbR9$qX8baXDweCPDJMinAg@lui`puGzwaVzKTHD&>Hw z3{e`mx>A&gaPs%uiXo$Ja>6DF?H3kR+#*tWfX3`^QiyeZ2GJHK778CHMjh1_B?doa zfW_i7^2}{c8M%Joz@cKIte9U2UR#1S7r$njU^luNR7ghXPOz?93Zj)58?qWss`R3N z>J48WAOaA{=M;7bN9~|ly?jkdu;wksqq}DwWdM17h~mF+NQNqQm^ti~`%Kq8+^H?_ zyQM)>2hJbV>*jz@4t&#Pp82nzPZ%-((#6nm2Y-Lw?dW<3r<>1;g729R$hLlI8yEfX zSXT?hFRm}0HD%$6sSCd7GP=v4`Aa_k?tb9ieVsc>_Z-vdA-_ug?f%@y!A)wLeYBHL z{klq_@#SY_!}f%4J+wQ%Fk|VK#us~L+Q410Soe0?JNgUCUUb*}QuQmZJAEe(J1+B6 zb2isd`ADiCQirB$ss9vZ&^eI5f@iIO-{yW<{-F1#``tYoHtrIk{vszNG+fP=P_N9KoXZh zS}h0`m(sv_&TRSj$BsS32&qynkd~Rc5Cf&ZcCD|+gr1T=Us=5d9P61in-8ky7iZ$* zxJ&_D)CvwBSkEJpUW72F=<4WX@B1via1u+x=Zv2^^`X+s{pNFL&o&0b8(v(yW0F*A z7D?Ug!==GZieD~AvpuZo@@Fe4Yn1NzDjTD7^S9r|0WR@`)8DZS-7fMBo=2I)&<@*? zmCYuaa6fxC0F$UQGLNF>&0DuTN52&dOllsY(%bjJos5j>sdes33JNz%{CCs(Gr8+4 zNG009dM&f1BwL0cb9>s;)8g<8O70E>;`d6D6|Qf8S|oLcV?JT}bUhmXJaQ}==a))$ ztV7J(f(vfmlK5r{Q(hh$c%@&V_lRt5)K$pz$=J@F z*0vvr)o?+bu70OA5zvWXmm`O1I{LvpEFr-d09zNbU_RB$!suyJr=q;2Q*8tF>b^_c zx%Ya?Q~W-WNHoTnk2s9Ijv@%QqTiI+vsv)`+`;UuLckBjRKLS7FxtTcG`FAaxSf`k z);FhXiZklB_&%q{Xeqso-v%dhCatbf5up5la`6SfjiO;q3uf?ewz{|tQSvO3>?o$S z3to^Bt@}B*m^0s4@gP;|ZZoIJ!_+|%yu(2=Wb?ZCQtL{3Q4xi7fWQ!648Uf1xSx3yh7Hz8grxSy*a|*#g4C@ z%)jkE?*-ox1la(c}`tcbx$R%fZiHvfO>$h`YQ$ zt|2&zoX>T%2Pl{L8cIS$b$fn|t@4vD%yrRSz1oksC9eCTy|qsQxhW294%wNRD+!KQ z^S*oTD0tjZU%Y71lqt%R@Ex(nOINPU<7kT0HV59u1OyRFI^zS*w~d)TJ$Db`bE+C+lIGHl4P=e1btCI zJ8qig*z$9l@-oAT!+?iqlG_XS8WM=tsiMS`J^i>8m6P9@guM z@9wAUX<#E+K7Z%V2z1hdIfoo1FITR@sYjI!b}Lvl6^KcZjo^5g!nhQ7&Y`a#g#_Kc zVI815m~S)C@)*NV(XK=+lb*}$!N{ke-t$8=2J2~QUF0|rG@Yvmw)DzZioMY7&5DfQV7ub(dM(&{${eVRXCHWs9pC^@!aJ?>` zMVqaSil9R?M=!NDKk_QkQ^G2>VkZOzA16B}8?Bn7ps+}6Gm3;kq9Ji--#el;3VUiA z@F{ODeY14ec+TR6wHtrsrl6(8vNy_yRIzuBO1h97;F(lu& zzU5{pETp*5UFz)SuXP&gY8O_}0C)D(azU#G!D+tn_-pFO6bbzS)ll2jA|Er4S|wca zMWo)1yVTzQc^hkv^r(e8^?x(W{%*^DM=m{1DlRVWyXR|-dWL8DQC(1+Hcgv+A9FDI zovx9sZM4NZvsf_fDr$iR{=;>RICQ;!?IOuqB6HXep*GorKa+aQ1eOWSV{n5mS@)2k zLpMd^|6;AaUbH9>k*8~hp~EXOBulh3HNR(aYgGi&TAuBESl+%+AhhhS)E2Y;+4PF{ z-SPFGt09r>FcoeW5bPS=cZ)^aBxHhY(wJbUb@9OG*3X(LItU+;RQHHSy!5ss1Nk@^)+P2?xm-P=GlX|T@S#Z4#73zwL!5KN9UN$?p4fbcil!lC|a4!9J?qQg!iZdEO_9kiTBY2C8 zxvv}{2a!rHE@vvo+FAVVpyOuBa4m#pOL7el$D^{qm)oNN~{fHX6%CX zhL^VSqL)(~0$J6iB!XYc_m@brzCmH}tXWog;HHfmb-cC&jul*i!ni0IH`2)Ps8Moq z84fFruVYl1ZUJE`jJ@&t<;-JLpWikn?I%5p>OD5&yd9d^ZdtP=l9qJD=}@55Enk|Q zpPwHT5D<{3s`#{CAE`zQ-84Xvd+Q_4m&bRP)x&@xTYvi0sY_rlrA)!dM^SN&)$>=L z2BCWJO>?c@^jhUstn7KErx|*>kXV<-@3Ob(DhvNX(anl7Suk^(?dPMR4vVh8vQoovzFdM?~ z-3`fAw(mn6WhEu`;Bw0c7Z0gbF4(xy-zX)~!jhH{u(HfYCYamvpLyK7OzJ6{T8}p_ zbMWWjUTAC#)eAN=##(UdJX=hJh-!B>qJCSG*A zxqdZa%G>h9=${?r_EvaW$#0%J@|PI5=1a%owaXByFz3U*1H z1{O>N;JCF!10|Q;C%wFaxtm+TQCo?yqX3>_N@!h+9sA8$UpkR-8a~QfIi9|YF|4X# zzE0-B#+r587WB~NROE~}+rM8wJp$!?aghr9NlBdss$MrzIXEByQ*yFT-@dxEtull@ z(yYLC|Nf*j7Y8_2iTV}|zgfq4otn;$pZ&IZno(&7NOXr(7fe+s08WN(WN^~c%sY3m z?+?_}ujW{UPEi>(XpmNolaq#qMwHX$THKX%!{B)fCQB_qN51S`TaZuhpy?~$DbDSC zUS<#RmdCx)nOEc92a*msdT(Wl@8=5oU;2;_2TXPtw$>XvRCQr*(E}#_Tm+AgcUtWa z@vSWA0r7Ilz4;o0&zw6KD0;Mk5FZUUbM&Jq?3E^Jn=LJNg*#HE(O55 zax3iO#reR&DhJ=#gqAs#-7R9}qzzre!?&OKWuI62Sj6C1yK}Cpjn(mjWJ)M%Zh6!y zb+XRt)y&+x%+%&c-NLY%vsbOIJ_@9*it)^U{B}5lKsKZ#0$RKx zbJ|O}5hH#tZsfbE%pe%C4&Lry=ocRiw>Y<0bxmll?1F~rUg;(8+JkDgH5-NI&U~7g zcRf71oe#IJD^ySP3EygF@=oz-s=k%((}K=3?M$>%?NOMino|3Hp>_Dq`G?q~@^A0D zIIs$(<>h(BsvnG&B%==t*|~bvDqq(*txITqy^_@SX4&pTNvJ=az=k5C7gy$KNh#|~ zW&J)WBQYG;_tl#N>Sse0lfc?dH5Gpq+@<|%*hgy zDb&Lz8W<@mDK$1(sX7chezPRV+a`*{({*$+{~lY9Bi-^MD5-94q;67Oc-#TIP07(t z((1nq%ea8{T7f*7t73qa8PeD%=Ixzd^Wi9DRSZ1V({mQfPYACizCj1W?78zx+=hJm zX$Ul(>MLH>4~Z0np)nrsa(p?SbWTUhhQ#)!f>t_()7x>kxlnobRENggeYV3cVm@zQ z9J4#tII2gPqSsa3Ea!U>k!wN|lM03%zdTRhJKV9Mxp}WqW0FPZ{j}CkXYE$a2nyac z_1Q4~UPcU4x?KI<-fiyK9JZ@yfK%$^{q;dLsx>pDN<#F`%=OBt3=Xq@y2>fOuy#tZ zbxgsz`y9SMU&RCwzOiK4KXtU`C0B*U6p5Hi{*Fb|ggJ9eV~Xs9!I^M9iN*>px4s}& zgRdBk5SxhRm$lmHrcukP%9vG`4SugIG9CTif4=qK{=4NnvY7OAd~xIbX_*y;d!M>L zsyr>v$=QnWihFi=Bza?5X`e1C=7-l+z~aa@+Mam1xyWH9?!wKVlw}KD<8d|71w#f5 zC@!7ww*&Rpr<~};H&Nq~Q+bR!GjYvDVcgzt3Gm8Ru%4w&-OkM zsD`qBFW*=SRS$vTgZs~E(U|11%r@Qx!Mbefq@-#ICUXCNXZ~FLd=YORMC7iD4qvEQ zvZ^;)8MUIdX)>(C_IREAk_1vW<5Y!z*Zq=2}0bmpzcan>Xz4N<*rz$AF zZujW%kte=!gW$u{jikr|it|jnSH1@h9&DW3SwGiv+U6hI+S(FKWF>Z|-P|tH?zI(; zl$$?v4HHCo^oV*q6hC;Q4{vTP&mmbpk1Uz`{+z@&cNO_d*73_J?db?_Y%C+mPM<6# zIsyC7e&vEt-w+v@Kp@Pm@Gpuc5wrd0MUX$IC`^(PtG4UKQTo6dSh)bwA-b%>8{n`G zJ{sN=%Zc5XGUN8mYVs9XWElXfs8M8AJptC+3e_yR(%9Hw*zrYqrVgR>1_=t$rp=oz zDXQ7m#+J9#iLCM8ug~Yd))-@pk~n9)k^?O&@Bj?{w6NR7hb&$vIw%c8uNBmIq8<`+ zZ=Q4#%EU~u&~&3iWv^cOeiZZ{L!jF}b9m9Z$ovMTGj2r^N`w|v?W5NI^2veM|Ncz= zoOK`LBpXN;CZc*Wk)=zPtU~6JLUDqL-lYi0Qjy8)Z}w5vJJ5;<5KE&CGNY@fXZ~ZLy(zIWaie8IG>I~QgP#jcU6*1p>E-euphC|7GChgd za{B~5p6so?hr9b$ATB|m*@KpHA)8-bTK>BZ#^mc!j<3F@OEw(kcq5+T!DSEAs+w#6 z-gNQj;Ug5;`1`DoxK99KOK7GDnR4{Fr>=>@ezFeg4Jt9G+}woyQ2Vr>iA|2KIEOs? z&;bK{tHa_~2;(Z*UDHPk6lh>F!K*?g>Nf z9x25vRQYvlH9JhFOG9;{*} z1YZRutLF0O!eQEzzsVzz&9i6dMeqrqshf@=BfK%nP?cIX5Eh}uN`zM)Ea|so(pvyI;^2^Jif@Le`3b|Fle>1oiwjNKYwaoq+do9?xo%&OV0hTptn z9(l()#u9m0>oht|{HV~2TsaOi32#pxxtb+Z2Mm)OW2I7ej1;%pE4-O{)r-2iaDY16 zY1i04|NcwXAWt$k@rsqOUKM^vbPNrHI$Og#-`J{sY^#-j9YT2frIOZGDCk1ZTYH~-Dv`xZO5m5kan;xG~p;WS7jy@xnRxEg_ts+qbHV6zRx zK@dho68B^V=z06A)c)lJrc@Q9N@68OTC?%3-<#38(b)t()tt@h=%OQr^UfaKS@00Q|y?YBIVi^{@SV#~7 z_NKRE&BYE@g=~f0Dco$qu}0nH=ce9N+T#txPb7Nl$qFI_tC&J_YvywbZAVXahiD2M z>Futw-yEd}ZndRSOrfn8Zc9!CUnsO%r@^QRfbdQa#Tp9=FtN^%pYPIeTt7#hgxV8< zrPvw}FYdtj(W9S*gsYMurXwCo2STn*p2?R-QrF3OP1$f*Uc4QWPScy65y`dABNW@7 z@cM9UJDauCO{ALybvafqX%AB&%%OPl+mmM2z6z``Dpw6ET{=U7AR|6VB=Xa1{@oZJ zuIH&aI!R+cvdS)HmlhQ+kQh%C%H5b@OM(E^9s#T4IicAvn?ZCvjCXzSZ>Il4xC#`h zcItdW)IAn}$ISWdJ+o|@1~iioSE34Kf)-UZiY20Iq-IO75=VTX&@LM-zDHr0ZVs&q z*%aC}AM$mtV!=Jr2$+2#ZSKDOmLdZE1N+?kA!%)a!S3b{>*-$Qo~3RASs~UC0D&8Y zF>ytqQEp_8=KO6S5@}x<6#>VHPx8+~Fc5SK? z!9X0zgSu(Vbd+qu5Li>zL{Q{{=$<16Tj3@QaYa~sZBU*~M@MtACH}_x-2{F2@Vm%t zk%i_FCyv(?hKOo?dI>z$2k>&_+h@jVl=}A$Pi*p3^V1+EX=GN++3@4*Mu@OPFT`N9 zreXB9bEbCBy1UwRkoH4{4$M>krH}&|wWm@`kfw_!b^plr?D#f9Yj)OAFct&1`=8Iq zC_+amy(22mRIxH|atjN3zn!=)WY~I+`-2Ux>Q{tUaBCowxJ`&>60b+KCx^*jzCvmT zUHs%ZZLb#8CxC{GS5ivfphUy-jIOUAhJV`>RAg5oJ51aN-fI61rMi zUuYsGE8;^1O@P(15l2#2hg$-qSwcP*QA^dQ)q7^D*Txjo#c1_edo?hmd z8MmS~>7BK()x>3P`%T;(DMPyLcM1&-8|!oC%oVsRvf(CFH}J!;p<_FZs(*9V=_m?r zQ}6Yktprw><5(s4N%4BL6E%nIQ4Gv~=l5o?0?o zRz!76keM92;yj|?dX=3Wb)DDAGzhP^eDywOzV*Z#)s=kU5+vcw886S4c(&7MWJokV zJ%(l^r+)6<7jTd9R>09Kl?=1ng4?(0DMBv4knh9a6(=aB1Q5YCF}ze0ejx!DGqb~h zvdF0@VBWR5kE_q9RI_*pFphg$RF_cyqkQGL&E5}4yDj8=rdxUDH`mu|(?9Yyj`k$I z;K(3=E%Fr~k2tSjAjCvg%*~$zntw0nV_$WWiXK_gIWl=2(mIh}Qdf?-w^fC-kJuj* zb*FpSjpu#p4anN=cZlk-0IwT~c+H#O!W90f+apx@J3>*DU3V19Y>BN&Gc31x>rD>V zv}!gmHV(lF_-NPQ`ei4tb%|{!>xlbohSUPS@XV{_0qMd=H<>xqs75;99I7wK{ni^8 zS+u!{_C3pX8PMhPF`iz*bK5Idig*K!+CSnAQI7ieE2TT&_m+*gd7JVJdxLy^HF!JS zHEYhrEVCHGAP1`^+P##)5_ivJh1X-B+)DIFgDLRn7R<%FTf7VE_+b=7vMzkJ^Vgai_evkm?RecEbJ70p zX{U9|danq9t7Xov|ADL^3RRr#9v?#sUVS1m>;~cok*2kld2Qdrt+-dZYhS$oanE%l zto>Rn!xN()pXGsmf1iaCn&d8@QRok0sXEtayDldkVXR<6AAGg+Nb?_)pC41)ld0ZZ zL71v-XV5t8?2W`ATnx+Q4R;;1xq&akjTY zJ{4iL%KkPx8mD~cStK)GCkIEPDR4DW!ktx@piPTtxznyLq^_9NbSu&VpD;RiEH-RT z_f!D*)qIS;3L`&4*_(74DM+lb38!VQtX#6>t8kkcUs6?jC_UrJ=YSVr@M}bv9JB0i zwZXs6h~2!t+lNbvUv}@-tpd@U+@k}>2;f6;)+{4|{}X zJwWcxmbAI|<2dyVB2U{_1cPPd#{2YlUWY5b+kph=J)9jzF@zPmAnxhzr)0e9rjb=a zZ=N!_@PcYeBvDZnXF`txm7IOW=-m%L>WAu6MWCJo*euG0w9N}~RS~ywOMq#PYvt%Z zPy0bej84!Uxgo*;8TP484G+E+yrHye6yr@X-5&C^%qtY@hfCr)ics-z%yG%90)hXK5x@a(69<=& z&5X-^X%64v}Mn+TRB`O&v zw)vaDWw&RwX6DjEED#V1X-oSZSpaI&M_O9_s^ytKzzhgg+N^Un#FMuzDs2f9SXmwF z1OSqPqlHITZP~5zU0a(YCBbC?1>zIG`Q`_nvZm&mY$9wAk$2$4;;40rsFu>sN`Z`C z{@9sGxO#ro?5u7KXtf~hw`ZE7g61^y`&qQBXTyU~*0f{E>Fx8ZabIC;HHR%-279MU^?TrO=oi^+`v}NhF$VeeeQ}-IpoVXWm z%Q7}Bx^b3PlC2baTR|>Lcg0c`u^|DfKKZrW$<$}BZ1?^3IUjy-Ij*lpT|$Orm=2&5 z@9Pp22;bKw#K*xs*5&vo8jp6l0`hJ_d!F#GFghl_uS}J1QY4-%>Jn3?NiCp_z@C~@1D>i9WA(nWQo-QrY|QKbqp}h^ z6XKLe1VwNqr26DJcqY5kRYiEJijW(jF2x_;2zcZwSptZMX z-&Hcync}d2Je0LXpFVQ2i#Ou?mjU)43Tj$K5vs5X%5rU-)sgYh5s{jZ;V zdygK{KP3{$y~KC5@vVq@hzK5dx84A!tI8NcKFkv53jAyuG9=|KnudYS?bT+&xuLxi z{*M|mfxbZe-dBV~4f#K>Ef-0x0*oL92@50=X;C)CuI`&CFTardB?rnaaLHAYpg})$ zmyI}o{!@{m2=~Plt;>-A;y)V&Yvg}rePM^+5D{oy{?A8I!8Sht1uwE>SF9*)0KDi3 zG67NYlOKChJwU_(1Q0v&URTX4z3j3@m+VqVQjc%!yhJZhfZ!}aJFT%J6r=2MwfEq$ z6`q!1g2eO(_u}85>3i;rA^nS=2vk8-`4CR@1=yQFuKNe^rQfGp!sL;z(Gd3~(9n0^ z?wJ>$?XIQ*BJVh|d zNO~^W9Nty{-t|Tl>hQ|CQYy>cyR<+g(iE5q*5o=2W!5+TL|#`(j5Q833?GO-=O3K$ zJFo|~fy=}BiPhM9==f^VJ^>c}@Pkw&Y?U~x%^NoczyiswMqn!dogwSNbZW3pzsY~B zUMguj#+NPggKdpYQrNIF4A}KW76|SZWRqhv!#70c-!FEAxCE(e=)i$~+yPf7XXnno zJNAAx+&wt1{Kbn39E)JYrR`@RxcIveufwZ*bnniy2Cy7*2kXB1`6CN0(MY7GEYaLG z^Mas8M&%@-IrTi+#K6E#FHf36*|4+y`}Wm_h))S-{T%x$AnpO4VPBF05!*pDsfIM7 z+N6HyDP!5eTdUiR*<);*@Xf#f)p_t!yYKa^$6BXfeyVr%N^AV55gv=Bs@g2U@>m+s2Rr=U2y zR#{nDABX^YsgAL+qh33uLCC{8eG`Tc9eUxB}gcP*m4AJu=% zd%4(;8PZ=;zHHOcj{845V%b;t%&8ex)pR{*AIVP4cE1O-039lL(S@08Ij!ymn|l<| z!ovEL*P!wBk(W0mW0&LZSO`IseTAfArS2&8n)(I0Ve{7> F_&=Y4`CkA4 literal 0 HcmV?d00001 From b9985fedc8b234775ee86fdc291caff4ee9ddaea Mon Sep 17 00:00:00 2001 From: Luiz Carlos Cosmi Filho Date: Mon, 19 Dec 2022 09:25:12 -0300 Subject: [PATCH 11/11] :pencil2: Fix typo in turtlebot3_mission_controller description Signed-off-by: Luiz Carlos Cosmi Filho --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 99de693..9e3c94e 100644 --- a/README.md +++ b/README.md @@ -8,7 +8,7 @@ The package's goal is to use the robot [turtlebot3](https://github.com/ROBOTIS-G * [turtlebot3_explorer](turtlebot3_mapper/turtlebot3_explorer/turtlebot3_explorer.py): it subscribes to receive messages from the laser sensor and publishes velocity commands. If any obstacle is detected in front of the robot, it then rotates until it finds a free path again. Also has a service that allows to enable or disable this behavior. -* [turtlebot3_mission_controller](turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py): the main service of this node is an action server responsible for determining when the exploration starts and ends. To do so, it uses the concept of fronteirs (intersection between unknown regions and free regions). Through the objective sent to the action server, where a user can specify the number of remaining fronteir points, it will enable the `turtlebot3_explorer` to explore the enviromment until it reaches the specified numbers of frontiers points in the occupancy grid. +* [turtlebot3_mission_controller](turtlebot3_mapper/turtlebot3_mission_controller/turtlebot3_mission_controller.py): the main service of this node is an action server responsible for determining when the exploration starts and ends. To do so, it uses the concept of fronteirs (intersection between unknown regions and free regions). Through the goal sent to the action server, where a user can specify the number of remaining fronteir points, it will enable the `turtlebot3_explorer` to explore the enviromment until it reaches the specified numbers of frontiers points in the occupancy grid. * [turtlebot3_mission_client](turtlebot3_mapper/turtlebot3_mission_client/turtlebot3_mission_client.py): action client responsible for sending the exploration task to the action server and saving the results to a file.