From a81021cd8679c7142063c8b567cea5f3cb278a00 Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 10:34:58 +0200 Subject: [PATCH 01/12] Add manager to choose right camera adapter, add new camera adapter for Dragonfly-s camera --- adapters.py | 496 ++++++++++++++++++++++++++++++++-------------------- 1 file changed, 305 insertions(+), 191 deletions(-) diff --git a/adapters.py b/adapters.py index e13dd86..56ccdcd 100644 --- a/adapters.py +++ b/adapters.py @@ -12,8 +12,13 @@ import serial import pyvesc import re -#import RPi.GPIO as GPIO from serial import SerialException +import numpy as np +from abc import ABC, abstractmethod + +import gi +gi.require_version('Aravis', '0.8') +from gi.repository import Aravis class SmoothieAdapter: @@ -907,90 +912,66 @@ def __calibrate_axis(self, self.__smc.write("G92 {0}{1}".format(axis_label, sm_val)) return self.__smc.read_some() +class CameraAdapterInterface(ABC): + """ + Abstract camera adapter interface. + Defines the minimal API every camera backend must implement. + """ -class PiCameraAdapter: - - def __init__(self): - from picamera.array import PiRGBArray - from picamera import PiCamera - self._camera = PiCamera() - self._camera.resolution = (config.CAMERA_W, config.CAMERA_H) - self._camera.framerate = config.CAMERA_FRAMERATE - self._raw_capture = PiRGBArray(self._camera, size=(config.CAMERA_W, config.CAMERA_H)) - self._gen = self._camera.capture_continuous(self._raw_capture, format="rgb") - time.sleep(2) - - def __enter__(self): - return self - - def __exit__(self, exc_type, exc_val, exc_tb): - self.release() - - def release(self): - self._camera.close() + @abstractmethod + def __init__(self, + crop_w_from, + crop_w_to, + crop_h_from, + crop_h_to, + cv_rotate_code, + ispdigitalgainrange_from, + ispdigitalgainrange_to, + gainrange_from, + gainrange_to, + exposuretimerange_from, + exposuretimerange_to, + aelock, + capture_width, + capture_height, + display_width, + display_height, + framerate, + nvidia_flip_method): + """Initialize the camera with configuration parameters.""" + pass + @abstractmethod def get_image(self): - image = cv.cvtColor(next(self._gen).array, cv.COLOR_RGB2BGR) - self._raw_capture.truncate(0) - return image + """Return the latest frame (as np.ndarray in BGR).""" + pass - -''' -# test -class CameraAdapterIMX219_170_BS1: - """Buffer size is set to 1 frame, getting 2 frames per call, return last""" - - def __init__(self, - capture_width=config.CAMERA_W, - capture_height=config.CAMERA_H, - display_width=config.CAMERA_W, - display_height=config.CAMERA_H, - framerate=config.CAMERA_FRAMERATE, - flip_method=config.CAMERA_FLIP_METHOD): - - gst_config = ( - "nvarguscamerasrc ! " - "video/x-raw(memory:NVMM), " - "width=(int)%d, height=(int)%d, " - "format=(string)NV12, framerate=(fraction)%d/1 ! " - "nvvidconv flip-method=%d ! " - "video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! " - "videoconvert ! " - "video/x-raw, format=(string)BGR ! appsink" - % ( - capture_width, - capture_height, - framerate, - flip_method, - display_width, - display_height - ) - ) - self._cap = cv.VideoCapture(gst_config, cv.CAP_GSTREAMER) - self._cap = cv.VideoCapture(cv.CAP_PROP_BUFFERSIZE, 1) + @abstractmethod + def release(self): + """Stop acquisition and release all resources.""" + pass def __enter__(self): + """Context manager entry point.""" return self def __exit__(self, exc_type, exc_val, exc_tb): + """Context manager exit point.""" self.release() - def release(self): - self._cap.release() - - def get_image(self): - if self._cap.isOpened(): - for i in range(self._cap.get(cv.CAP_PROP_BUFFERSIZE) + 1): - ret, image = self._cap.read() - # rotate for 90 degrees and crop black zones - return cv.rotate(image, 2)[config.CROP_H_FROM:config.CROP_H_TO, config.CROP_W_FROM:config.CROP_W_TO] - else: - raise RuntimeError("Unable to open camera") -''' - + # ─────────── Common utility ─────────── + def whoami(self): + """ + Return the readable name of the active adapter class. + Example: "CameraAdapterAravis_ZeroLatency" + """ + return self.__class__.__name__ -# old with no shutter, gain and rest camera control -class CameraAdapterIMX219_170_Auto: +class CameraAdapterManager(CameraAdapterInterface): + """ + Universal camera adapter manager. + Automatically selects and delegates to the appropriate backend. + """ def __init__(self, crop_w_from, @@ -1011,69 +992,94 @@ def __init__(self, display_height, framerate, nvidia_flip_method): + """ + backend: "auto" | "aravis" | "imx219" + - "auto": try Aravis first, fallback to IMX219 if no camera found + - "aravis": force Aravis backend + - "imx219": force Jetson IMX219 backend + """ + self._adapter = None + self._backend_name = None + backend = config.CAMERA_BACKEND.lower() + self._backend_mode = backend - self._crop_w_from = crop_w_from - self._crop_w_to = crop_w_to - self._crop_h_from = crop_h_from - self._crop_h_to = crop_h_to - self._cv_rotate_code = cv_rotate_code - aelock = "aelock=true " if aelock else "" - - gst_config = ( - "nvarguscamerasrc ! " - "video/x-raw(memory:NVMM), " - "width=(int)%d, height=(int)%d, " - "format=(string)NV12, framerate=(fraction)%d/1 ! " - "nvvidconv flip-method=%d ! " - "video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! " - "videoconvert ! " - "video/x-raw, format=(string)BGR ! appsink" - % ( - capture_width, - capture_height, - framerate, - nvidia_flip_method, - display_width, - display_height + # ─────────── Backend selection ─────────── + if self._backend_mode == "auto": + try: + print(f"[{self.__class__.__name__}] Trying Aravis backend...") + self._adapter = CameraAdapterAravis( + crop_w_from, crop_w_to, crop_h_from, crop_h_to, cv_rotate_code, + ispdigitalgainrange_from, ispdigitalgainrange_to, + gainrange_from, gainrange_to, + exposuretimerange_from, exposuretimerange_to, + aelock, capture_width, capture_height, + display_width, display_height, framerate, nvidia_flip_method + ) + print(f"[{self.__class__.__name__}] ✅ Aravis backend selected: {self._adapter.whoami()}") + except Exception as e: + print(f"[{self.__class__.__name__}] ⚠️ Aravis unavailable: {e}") + print(f"[{self.__class__.__name__}] → Falling back to IMX219 backend.") + self._adapter = CameraAdapterIMX219_170( + crop_w_from, crop_w_to, crop_h_from, crop_h_to, cv_rotate_code, + ispdigitalgainrange_from, ispdigitalgainrange_to, + gainrange_from, gainrange_to, + exposuretimerange_from, exposuretimerange_to, + aelock, capture_width, capture_height, + display_width, display_height, framerate, nvidia_flip_method ) - ) - if config.APPLY_THREAD_BUFF_CLEANING: - self._cap = VideoCaptureNoBuffer(gst_config, cv.CAP_GSTREAMER) + elif self._backend_mode == "aravis": + self._adapter = CameraAdapterAravis( + crop_w_from, crop_w_to, crop_h_from, crop_h_to, cv_rotate_code, + ispdigitalgainrange_from, ispdigitalgainrange_to, + gainrange_from, gainrange_to, + exposuretimerange_from, exposuretimerange_to, + aelock, capture_width, capture_height, + display_width, display_height, framerate, nvidia_flip_method + ) + + elif self._backend_mode == "imx219": + self._adapter = CameraAdapterIMX219_170( + crop_w_from, crop_w_to, crop_h_from, crop_h_to, cv_rotate_code, + ispdigitalgainrange_from, ispdigitalgainrange_to, + gainrange_from, gainrange_to, + exposuretimerange_from, exposuretimerange_to, + aelock, capture_width, capture_height, + display_width, display_height, framerate, nvidia_flip_method + ) + else: - self._cap = cv.VideoCapture(gst_config, cv.CAP_GSTREAMER) + raise ValueError(f"[{self.__class__.__name__}] Unknown backend '{backend}', expected 'auto', 'aravis' or 'imx219'.") - def __enter__(self): - return self + # ─────────── Automatic backend name ─────────── + raw_name = self._adapter.whoami() + self._backend_name = raw_name.replace("CameraAdapter", "").split("_")[0].lower() + print(f"[{self.__class__.__name__}] Active backend: {self._backend_name} ({raw_name})") - def __exit__(self, exc_type, exc_val, exc_tb): - self.release() + # ─────────── Interface delegation ─────────── + def get_image(self): + return self._adapter.get_image() def release(self): - self._cap.release() + return self._adapter.release() - def get_image(self): - if self._cap.isOpened(): - if config.BUFF_CLEANING_DELAY > 0: - time.sleep(config.BUFF_CLEANING_DELAY) + def __enter__(self): + self._adapter.__enter__() + return self - if config.APPLY_THREAD_BUFF_CLEANING: - image = self._cap.read() - else: - ret, image = self._cap.read() + def __exit__(self, exc_type, exc_val, exc_tb): + self._adapter.__exit__(exc_type, exc_val, exc_tb) - if config.CV_APPLY_ROTATION: - image = cv.rotate(image, self._cv_rotate_code) + def whoami(self): + """Return the manager and its active backend class name.""" + return f"[{self.__class__.__name__}] → {self._adapter.whoami()} ({self._backend_name})" - # crop black zones - #if config.APPLY_IMAGE_CROPPING: - # image = image[self._crop_h_from:self._crop_h_to, self._crop_w_from:self._crop_w_to] - return image - else: - raise RuntimeError("Unable to open camera") + def backend(self): + """Return short backend identifier, e.g., 'aravis' or 'imx219'.""" + return self._backend_name -class CameraAdapterIMX219_170: +class CameraAdapterIMX219_170(CameraAdapterInterface): def __init__(self, crop_w_from, @@ -1205,6 +1211,183 @@ def get_image(self): raise RuntimeError(f"[{self.__class__.__name__}] -> Unable to open camera") +class CameraAdapterAravis(CameraAdapterInterface): + """ + Aravis-based version compatible with the DR-U3-50Y2C-C3-S camera. + Uses a double-buffer (ping-pong) numpy architecture for zero-latency capture. + """ + + def __init__(self, + crop_w_from, + crop_w_to, + crop_h_from, + crop_h_to, + cv_rotate_code, + ispdigitalgainrange_from, + ispdigitalgainrange_to, + gainrange_from, + gainrange_to, + exposuretimerange_from, + exposuretimerange_to, + aelock, + capture_width, + capture_height, + display_width, + display_height, + framerate, + nvidia_flip_method): + + # Convert exposure time from nvarguscamerasrc units (nanoseconds) to Aravis units (µs). + # Therefore: 1 µs = 1000 ns → divide by 1000 + exposuretimerange_from = exposuretimerange_from / 1000 + exposuretimerange_to = exposuretimerange_to / 1000.0 + + self._cv_rotate_code = cv_rotate_code + self._running = False + self._ready_index = 0 + self._lock = threading.Lock() + self._new_frame = False + + # ─────────── Camera initialization ─────────── + Aravis.update_device_list() + if Aravis.get_n_devices() == 0: + raise RuntimeError(f"[{self.__class__.__name__}] No Aravis camera detected.") + self.cam = Aravis.Camera.new(None) + print(f"[{self.__class__.__name__}] Aravis camera detected : {self.cam.get_model_name()}") + + # ─────────── Binning configuration ─────────── + try: + self.cam.set_integer("BinningHorizontal", config.CAMERA_BINNING_H) + self.cam.set_integer("BinningVertical", config.CAMERA_BINNING_V) + except Exception: + pass + + sensor_w, sensor_h = self.cam.get_sensor_size() + bx = self.cam.get_integer("BinningHorizontal") if self.cam.is_feature_available("BinningHorizontal") else 1 + by = self.cam.get_integer("BinningVertical") if self.cam.is_feature_available("BinningVertical") else 1 + eff_w, eff_h = sensor_w // bx, sensor_h // by + + # ─────────── Centered ROI ─────────── + target_w, target_h = min(capture_width, eff_w), min(capture_height, eff_h) + ox = ((eff_w - target_w) // 2) * bx + oy = ((eff_h - target_h) // 2) * by + self.cam.set_region(ox, oy, target_w, target_h) + self._width, self._height = target_w, target_h + + # ─────────── Flip / rotation mapping (Aravis equivalent of nvidia_flip_method) ─────────── + # nvarguscamerasrc flip-method values: + # 0: none → ReverseX=0, ReverseY=0 + # 2: rotate 180° → ReverseX=1, ReverseY=1 + # 4: horizontal flip → ReverseX=1, ReverseY=0 + # 6: vertical flip → ReverseX=0, ReverseY=1 + # Other values (1,3,5,7) are not supported by Aravis. + + flip_mapping = {0: (0, 0), 2: (1, 1), 4: (1, 0), 6: (0, 1)} + + if nvidia_flip_method in flip_mapping: + reverse_x, reverse_y = flip_mapping[nvidia_flip_method] + try: + if self.cam.is_feature_available("ReverseX"): + self.cam.set_integer("ReverseX", reverse_x) + if self.cam.is_feature_available("ReverseY"): + self.cam.set_integer("ReverseY", reverse_y) + print(f"[{self.__class__.__name__}] → Applied ReverseX={reverse_x}, ReverseY={reverse_y} (flip-method={nvidia_flip_method})") + except Exception as e: + print(f"[{self.__class__.__name__}] ⚠️ Unable to set ReverseX/ReverseY: {e}") + else: + print(f"[{self.__class__.__name__}] ⚠️ flip-method={nvidia_flip_method} not supported by Aravis (only 0,2,4,6).") + + # ─────────── Pixel format, exposureTime, gain and framerate ─────────── + + if gainrange_from != gainrange_to: + raise ValueError(f"[{self.__class__.__name__}] gainrange_from and gainrange_to must be equal.") + if exposuretimerange_from != exposuretimerange_to: + raise ValueError(f"[{self.__class__.__name__}] exposuretimerange_from and exposuretimerange_to must be equal.") + + try: + self.cam.set_pixel_format_from_string("BayerGR8") + except Exception: + print(f"[{self.__class__.__name__}] ⚠️ Bayer format not supported.") + + for (k, v) in [("ExposureAuto", "Off"), ("GainAuto", "Off")]: + try: self.cam.set_string(k, v) + except Exception: pass + for (k, v) in [("ExposureTime", float(exposuretimerange_from)), ("Gain", float(gainrange_from))]: + try: self.cam.set_float(k, v) + except Exception: pass + + try: + self.cam.set_boolean("AcquisitionFrameRateEnable", True) + self.cam.set_float("AcquisitionFrameRate", framerate) + except Exception: + pass + + # ─────────── Stream & Buffers ─────────── + self.stream = self.cam.create_stream(None, None) + self.stream.set_emit_signals(False) + payload = self.cam.get_payload() + for _ in range(2): + self.stream.push_buffer(Aravis.Buffer.new_allocate(payload)) + + # ─────────── Double buffer numpy ─────────── + self._buffers = [ + np.empty((self._height, self._width), dtype=np.uint8), + np.empty((self._height, self._width), dtype=np.uint8) + ] + + self.cam.start_acquisition() + self._running = True + self._thread = threading.Thread(target=self._capture_loop, daemon=True) + self._thread.start() + print(f"[{self.__class__.__name__}] Aravis acquisition launched in {framerate} FPS ({target_w}x{target_h})") + + # ─────────── Capture thread ─────────── + def _capture_loop(self): + idx = 0 + while self._running: + buf = self.stream.try_pop_buffer() + if not buf: + continue + if buf.get_status() == Aravis.BufferStatus.SUCCESS: + data = buf.get_data() + np.copyto(self._buffers[idx], np.frombuffer(data, dtype=np.uint8).reshape(self._buffers[idx].shape)) + with self._lock: + self._ready_index = idx + self._new_frame = True + idx = 1 - idx + self.stream.push_buffer(buf) + + # ─────────── Public interface ─────────── + def get_image(self): + """Return the latest RGB frame.""" + with self._lock: + if not self._new_frame: + raise RuntimeError(f"[{self.__class__.__name__}] No image available.") + frame = self._buffers[self._ready_index] + self._new_frame = False + + frame_rgb = cv.cvtColor(frame, cv.COLOR_BAYER_GB2BGR) + if self._cv_rotate_code is not None: + frame_rgb = cv.rotate(frame_rgb, self._cv_rotate_code) + return frame_rgb + + def release(self): + """Stop the capture process cleanly.""" + self._running = False + time.sleep(0.1) + try: + self.cam.stop_acquisition() + except Exception: + pass + print(f"[{self.__class__.__name__}] 🛑 Aravis capture stopped.") + + def __enter__(self): + return self + + def __exit__(self, exc_type, exc_val, exc_tb): + self.release() + + class VideoCaptureNoBuffer: """Minimalistic layer for cv2's VideoCapture with buffer cleaning thread ()""" @@ -1238,75 +1421,6 @@ def read(self): return self._queue.get() -class CompassOldAdapter: - """Provides to the robot's on-board compass (some old card, the first one, not sure about model)""" - - def __init__(self): - import smbus - self._register_a = 0 # Address of Configuration register A - self._register_b = 0x01 # Address of configuration register B - self._register_mode = 0x02 # Address of mode register - self._x_axis_h = 0x03 # Address of X-axis MSB data register - self._z_axis_h = 0x05 # Address of Z-axis MSB data register - self._y_axis_h = 0x07 # Address of Y-axis MSB data register - self._bus = smbus.SMBus(1) # or bus = smbus.SMBus(0) for older version boards - - # write to Configuration Register A - self._bus.write_byte_data(config.COMPASS_DEVICE_ADDRESS, self._register_a, 0x70) - # Write to Configuration Register B for gain - self._bus.write_byte_data(config.COMPASS_DEVICE_ADDRESS, self._register_b, 0xa0) - # Write to mode Register for selecting mode - self._bus.write_byte_data(config.COMPASS_DEVICE_ADDRESS, self._register_mode, 0) - - def _read_raw_data(self, address): - """Reads raw data from compass""" - - # Read raw 16-bit value - high = self._bus.read_byte_data(config.COMPASS_DEVICE_ADDRESS, address) - low = self._bus.read_byte_data(config.COMPASS_DEVICE_ADDRESS, address + 1) - - # concatenate higher and lower value - value = ((high << 8) | low) - - # get signed value from module - return value - 65536 if value > 32768 else value - - def get_heading_angle(self): - """Returns current heading angle in degrees""" - - x = self._read_raw_data(self._x_axis_h) - y = self._read_raw_data(self._y_axis_h) - heading = math.atan2(y, x) + config.COMPASS_DECLINATION - - # Due to declination check for > 360 degree - if heading > 2 * math.pi: - heading -= 2 * math.pi - # check for sign - if heading < 0: - heading += 2 * math.pi - - # convert into angle - return int(heading * 180 / math.pi) - - -class CompassBNO055Adapter: - """Provides access to the robot's on-board compass""" - - def __init__(self): - import adafruit_bno055 - from busio import I2C - import board - - self._i2c = I2C(board.SCL, board.SDA) - self._sensor = adafruit_bno055.BNO055(self._i2c) - # turn on "compass mode" - self._sensor.mode = adafruit_bno055.COMPASS_MODE - # sensor.mode = adafruit_bno055.M4G_MODE - - def get_euler_angle(self): - return self._sensor.euler - - class VescAdapter: """Provides navigation engines (forward/backward) control using vesc""" From d8470cfa631ad5561459f258f317a0e370bcda85 Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 10:45:03 +0200 Subject: [PATCH 02/12] Add --zones to basic serverCamLive to avoid code duplication --- serverCamLive.py | 220 ++++++++++++++++++++++++++++++++++++++ serveurCamLive.py | 164 ---------------------------- serveurCamLiveWithZone.py | 180 ------------------------------- 3 files changed, 220 insertions(+), 344 deletions(-) create mode 100644 serverCamLive.py delete mode 100644 serveurCamLive.py delete mode 100644 serveurCamLiveWithZone.py diff --git a/serverCamLive.py b/serverCamLive.py new file mode 100644 index 0000000..a952cf7 --- /dev/null +++ b/serverCamLive.py @@ -0,0 +1,220 @@ +#!/usr/bin/env python3 +import cv2 +import threading +import os +import sys +import numpy as np +from flask import Flask, Response, jsonify +from flask_cors import CORS +from config import config +import detection +from CameraAdapterManager import CameraAdapterManager + + +class ServerCamLive: + """ + Camera streaming server based on Flask + CameraAdapterManager. + - If `app` is provided: attaches /video and /info routes to it. + - If `app` is None: creates its own Flask app and runs it. + """ + + def __init__(self, app=None, port=8080, use_detector=True, display_zones=False): + """ + :param app: Optional Flask app instance. + :param port: Port used if running standalone. + :param use_detector: Enable YOLO TRT detection on frames. + """ + self.external_app = app is not None + self.app = app or Flask(__name__) + CORS(self.app) + + self.port = port + self.use_detector = use_detector + self.display_zones = display_zones + + self.cam = None + self.detector = None + self.thread_alive = False + self.video_frame = None + self.thread_lock = threading.Lock() + self.capture_thread = None + + # Register routes (always added) + self._register_routes() + + # ─────────── DRAWING ZONES ─────────── + def draw_zone_circle(self, image, cx, cy, radius): + """Draws a circle showing the undistorted zone.""" + return cv2.circle(image, (cx, cy), radius, (0, 0, 255), thickness=3) + + def draw_zone_poly(self, image, np_poly_points): + """Draws polygon of the working zone.""" + return cv2.polylines(image, [np_poly_points], isClosed=True, color=(0, 255, 255), thickness=5) + + # ─────────── ROUTES ─────────── + def _register_routes(self): + """Attach /video and /info routes to the Flask app.""" + self.app.add_url_rule("/video", view_func=self.stream_frames) + self.app.add_url_rule("/info", view_func=self.camera_info) + + def _unregister_routes(self): + """Remove previously added routes from the Flask app.""" + removed = [] + for rule in list(self.app.url_map.iter_rules()): + if rule.rule in self._registered_routes: + removed.append(rule.rule) + self.app.url_map._rules.remove(rule) + self.app.view_functions.pop(rule.endpoint, None) + if removed: + print(f"[{self.__class__.__name__}] 🧹 Removed routes: {', '.join(removed)}") + + def camera_info(self): + """Return camera backend and adapter info as JSON.""" + if self.cam: + return jsonify({ + "backend": self.cam.backend(), + "class": self.cam.whoami() + }) + return jsonify({"status": "camera not initialized"}) + + # ─────────── CAMERA ─────────── + def init_camera(self): + """Initialize camera with CameraAdapterManager.""" + try: + self.cam = CameraAdapterManager( + crop_w_from=config.CROP_W_FROM, + crop_w_to=config.CROP_W_TO, + crop_h_from=config.CROP_H_FROM, + crop_h_to=config.CROP_H_TO, + cv_rotate_code=None, + ispdigitalgainrange_from=config.ISP_DIGITAL_GAIN_RANGE_FROM, + ispdigitalgainrange_to=config.ISP_DIGITAL_GAIN_RANGE_TO, + gainrange_from=config.GAIN_RANGE_FROM, + gainrange_to=config.GAIN_RANGE_TO, + exposuretimerange_from=config.EXPOSURE_TIME_RANGE_FROM, + exposuretimerange_to=config.EXPOSURE_TIME_RANGE_TO, + aelock=config.AE_LOCK, + capture_width=config.CAMERA_W, + capture_height=config.CAMERA_H, + display_width=config.CAMERA_W, + display_height=config.CAMERA_H, + framerate=config.CAMERA_FRAMERATE, + nvidia_flip_method=config.CAMERA_FLIP_METHOD + ) + print(f"[{self.__class__.__name__}] ✅ Camera initialized using backend: {self.cam.backend()} ({self.cam.whoami()})") + except Exception as e: + print(f"[{self.__class__.__name__}] ❌ Failed to initialize camera: {e}") + sys.exit(1) + + def capture_loop(self): + """Continuously capture frames from the camera.""" + try: + while self.thread_alive: + frame = self.cam.get_image() + with self.thread_lock: + self.video_frame = frame + except Exception as e: + print(f"[{self.__class__.__name__}] ⚠️ Capture error: {e}") + finally: + if self.cam: + self.cam.release() + print(f"[{self.__class__.__name__}] 🛑 Camera released.") + + # ─────────── STREAMING ─────────── + def rescale_frame(self, frame, percent=50): + """Resize frame to reduce stream bandwidth.""" + width = int(frame.shape[1] * percent / 100) + height = int(frame.shape[0] * percent / 100) + return cv2.resize(frame, (width, height), interpolation=cv2.INTER_AREA) + + def encode_frame(self): + """Generate MJPEG byte stream.""" + while True: + with self.thread_lock: + frame = self.video_frame + + if frame is None: + continue + + # Optional detector + if self.detector: + boxes = self.detector.detect(frame, True) + frame = detection.draw_boxes(frame, boxes) + + # Optional zone display + if self.display_zones: + try: + poly_zone_points_cv = np.array(config.WORKING_ZONE_POLY_POINTS, np.int32).reshape((-1, 1, 2)) + frame = self.draw_zone_circle(frame, config.SCENE_CENTER_X, config.SCENE_CENTER_Y, config.UNDISTORTED_ZONE_RADIUS) + frame = self.draw_zone_circle(frame, config.SCENE_CENTER_X, config.SCENE_CENTER_Y, 2) + frame = self.draw_zone_poly(frame, poly_zone_points_cv) + except Exception as e: + print(f"[{self.__class__.__name__}] ⚠️ Zone drawing failed: {e}") + + frame = self.rescale_frame(frame, percent=50) + ok, encoded = cv2.imencode(".jpg", frame) + if not ok: + continue + + yield ( + b"--frame\r\n" + b"Content-Type: image/jpeg\r\n\r\n" + + bytearray(encoded) + + b"\r\n" + ) + + def stream_frames(self): + """Flask endpoint returning the MJPEG stream.""" + return Response(self.encode_frame(), mimetype="multipart/x-mixed-replace; boundary=frame") + + # ─────────── CONTROL ─────────── + def start(self): + """Initialize camera, detector, and capture thread. + If no external app, also runs Flask server.""" + print(f"[{self.__class__.__name__}] 🔄 Restarting nvargus-daemon (if available)...") + os.system("sudo systemctl restart nvargus-daemon") + + self.init_camera() + + if self.use_detector: + print(f"[{self.__class__.__name__}] 🧠 Initializing detector...") + self.detector = detection.YoloTRTDetector( + config.PERIPHERY_MODEL_PATH, + config.PERIPHERY_CLASSES_FILE, + config.PERIPHERY_CONFIDENCE_THRESHOLD, + config.PERIPHERY_NMS_THRESHOLD, + config.PERIPHERY_INPUT_SIZE, + ) + + self.thread_alive = True + self.capture_thread = threading.Thread(target=self.capture_loop, daemon=True) + self.capture_thread.start() + + if not self.external_app: + print(f"[{self.__class__.__name__}] 🌐 Starting internal Flask server on http://0.0.0.0:{self.port}/video") + self.app.run("0.0.0.0", self.port, debug=False, use_reloader=False) + else: + print(f"[{self.__class__.__name__}] 🔗 ServerCamLive attached to external Flask app.") + + def stop(self): + """Stop the capture thread and remove routes.""" + print(f"[{self.__class__.__name__}] 🛑 Stopping camera stream...") + + self.thread_alive = False + if self.cam: + self.cam.release() + + # Remove routes if attached to an external app + if self.app and self.external_app: + self._unregister_routes() + + print(f"[{self.__class__.__name__}] ✅ Streaming stopped.") + + +# ─────────── Main Entrypoint ─────────── +if __name__ == "__main__": + display_zones = "--zones" in sys.argv + use_detector = not ("--no-detector" in sys.argv) + + server = ServerCamLive(port=8080, use_detector=use_detector, display_zones=display_zones) + server.start() \ No newline at end of file diff --git a/serveurCamLive.py b/serveurCamLive.py deleted file mode 100644 index 006be51..0000000 --- a/serveurCamLive.py +++ /dev/null @@ -1,164 +0,0 @@ -import cv2 -import threading -from flask import Response, Flask, request, current_app -from config import config -import detection -import os -from multiprocessing import Process -import sys -from flask_cors import CORS - -def generateGstConfig(): - aelock = "aelock=true " if config.AE_LOCK else "" - - gst_config_start = ( - "nvarguscamerasrc " - "ispdigitalgainrange=\"%.2f %.2f\" " - "gainrange=\"%.2f %.2f\" " - "exposuretimerange=\"%d %d\" " - "%s" - "! " - "video/x-raw(memory:NVMM), " - "width=(int)%d, height=(int)%d, " - "format=(string)NV12, framerate=(fraction)%d/1 ! " - - % ( - config.ISP_DIGITAL_GAIN_RANGE_FROM, - config.ISP_DIGITAL_GAIN_RANGE_TO, - config.GAIN_RANGE_FROM, - config.GAIN_RANGE_TO, - config.EXPOSURE_TIME_RANGE_FROM, - config.EXPOSURE_TIME_RANGE_TO, - aelock, - config.CAMERA_W, - config.CAMERA_H, - config.CAMERA_FRAMERATE, - - ) - ) - - if config.APPLY_IMAGE_CROPPING: - gst_config_end = ( - "nvvidconv top=%d bottom=%d left=%d right=%d flip-method=%d ! " - "video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! " - "videoconvert ! " - "video/x-raw, format=(string)BGR ! appsink" - % ( - config.CROP_H_FROM, - config.CROP_H_TO, - config.CROP_W_FROM, - config.CROP_W_TO, - config.CAMERA_FLIP_METHOD, - config.CROP_W_TO-config.CROP_W_FROM, - config.CROP_H_TO-config.CROP_H_FROM - ) - ) - else: - gst_config_end = ( - "nvvidconv flip-method=%d ! " - "video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! " - "videoconvert ! " - "video/x-raw, format=(string)BGR ! appsink" - % ( - config.CAMERA_FLIP_METHOD, - config.CAMERA_W, - config.CAMERA_H - ) - ) - - return gst_config_start+gst_config_end - -def rescale_frame(frame, percent=75): - width = int(frame.shape[1] * percent/ 100) - height = int(frame.shape[0] * percent/ 100) - dim = (width, height) - return cv2.resize(frame, dim, interpolation =cv2.INTER_AREA) - -def captureFrames(): - with app.app_context(): - if current_app.thread_alive: - video_capture = None - try: - video_capture = cv2.VideoCapture(generateGstConfig(), cv2.CAP_GSTREAMER) - except KeyboardInterrupt: - raise KeyboardInterrupt() - except: - pass - if video_capture: - while video_capture.isOpened() and current_app.thread_alive: - return_key, frame = video_capture.read() - if not return_key: - break - - with current_app.thread_lock: - current_app.video_frame = frame - - key = cv2.waitKey(30) & 0xff - if key == 27: - break - video_capture.release() - -def encodeFrame(): - with app.app_context(): - while True: - with current_app.thread_lock: - - if current_app.video_frame is None: - continue - frame = current_app.video_frame - - if current_app.detector: - plants_boxes = current_app.detector.detect(frame, True) - frameFinal = detection.draw_boxes(frame, plants_boxes) - else: - frameFinal = frame - - frameFinal = rescale_frame(frameFinal, percent=50) - return_key, encoded_image = cv2.imencode(".jpg", frameFinal) - if not return_key: - continue - - # Output image as a byte array - yield(b'--frame\r\n' b'Content-Type: image/jpeg\r\n\r\n' + - bytearray(encoded_image) + b'\r\n') - - -app = Flask(__name__) -CORS(app) - -@app.route("/video") -def streamFrames(): - return Response(encodeFrame(), mimetype = "multipart/x-mixed-replace; boundary=frame") - -if __name__ == '__main__': - - use_detector_arg = True - if len(sys.argv)>1: - use_detector_arg = not sys.argv[1]=="False" - - print("Reset service cam !") - os.system("sudo systemctl restart nvargus-daemon") - - with app.app_context(): - current_app.thread_alive = True - current_app.video_frame = None - current_app.detector = None - current_app.thread_lock = threading.Lock() - - if use_detector_arg: - #current_app.detector = detection.YoloDarknetDetector(config.PERIPHERY_WEIGHTS_FILE, config.PERIPHERY_CONFIG_FILE, - # config.PERIPHERY_DATA_FILE, config.PERIPHERY_CONFIDENCE_THRESHOLD, - # config.PERIPHERY_HIER_THRESHOLD, config.PERIPHERY_NMS_THRESHOLD) - current_app.detector = detection.YoloTRTDetector( - config.PERIPHERY_MODEL_PATH, - config.PERIPHERY_CLASSES_FILE, - config.PERIPHERY_CONFIDENCE_THRESHOLD, - config.PERIPHERY_NMS_THRESHOLD, - config.PERIPHERY_INPUT_SIZE) - - process_thread = threading.Thread(target=captureFrames) - process_thread.daemon = True - process_thread.start() - app.run("0.0.0.0",8080,False) - - \ No newline at end of file diff --git a/serveurCamLiveWithZone.py b/serveurCamLiveWithZone.py deleted file mode 100644 index 9701de9..0000000 --- a/serveurCamLiveWithZone.py +++ /dev/null @@ -1,180 +0,0 @@ -import cv2 -import threading -from flask import Response, Flask, request, current_app -from config import config -import detection -import os -from multiprocessing import Process -import sys -import numpy as np - -def draw_zone_circle(image, circle_center_x, circle_center_y, circle_radius): - """Draws received circle on image. Used for drawing undistorted zone edges on photo""" - - return cv2.circle(image, (circle_center_x, circle_center_y), circle_radius, (0, 0, 255), thickness=3) - - -def draw_zone_poly(image, np_poly_points): - """Draws received polygon on image. Used for drawing working zone edges on photo""" - - return cv2.polylines(image, [np_poly_points], isClosed=True, color=(0, 255, 255), thickness=5) - -def generateGstConfig(): - aelock = "aelock=true " if config.AE_LOCK else "" - - gst_config_start = ( - "nvarguscamerasrc " - "ispdigitalgainrange=\"%.2f %.2f\" " - "gainrange=\"%.2f %.2f\" " - "exposuretimerange=\"%d %d\" " - "%s" - "! " - "video/x-raw(memory:NVMM), " - "width=(int)%d, height=(int)%d, " - "format=(string)NV12, framerate=(fraction)%d/1 ! " - - % ( - config.ISP_DIGITAL_GAIN_RANGE_FROM, - config.ISP_DIGITAL_GAIN_RANGE_TO, - config.GAIN_RANGE_FROM, - config.GAIN_RANGE_TO, - config.EXPOSURE_TIME_RANGE_FROM, - config.EXPOSURE_TIME_RANGE_TO, - aelock, - config.CAMERA_W, - config.CAMERA_H, - config.CAMERA_FRAMERATE, - - ) - ) - - if config.APPLY_IMAGE_CROPPING: - gst_config_end = ( - "nvvidconv top=%d bottom=%d left=%d right=%d flip-method=%d ! " - "video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! " - "videoconvert ! " - "video/x-raw, format=(string)BGR ! appsink" - % ( - config.CROP_H_FROM, - config.CROP_H_TO, - config.CROP_W_FROM, - config.CROP_W_TO, - config.CAMERA_FLIP_METHOD, - config.CROP_W_TO-config.CROP_W_FROM, - config.CROP_H_TO-config.CROP_H_FROM - ) - ) - else: - gst_config_end = ( - "nvvidconv flip-method=%d ! " - "video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! " - "videoconvert ! " - "video/x-raw, format=(string)BGR ! appsink" - % ( - config.CAMERA_FLIP_METHOD, - config.CAMERA_W, - config.CAMERA_H - ) - ) - - return gst_config_start+gst_config_end - -def rescale_frame(frame, percent=75): - width = int(frame.shape[1] * percent/ 100) - height = int(frame.shape[0] * percent/ 100) - dim = (width, height) - return cv2.resize(frame, dim, interpolation =cv2.INTER_AREA) - -def captureFrames(): - with app.app_context(): - if current_app.thread_alive: - video_capture = None - try: - video_capture = cv2.VideoCapture(generateGstConfig(), cv2.CAP_GSTREAMER) - except KeyboardInterrupt: - raise KeyboardInterrupt() - except: - pass - if video_capture: - while video_capture.isOpened() and current_app.thread_alive: - return_key, frame = video_capture.read() - if not return_key: - break - - with current_app.thread_lock: - current_app.video_frame = frame - - key = cv2.waitKey(30) & 0xff - if key == 27: - break - video_capture.release() - -def encodeFrame(): - with app.app_context(): - while True: - with current_app.thread_lock: - - if current_app.video_frame is None: - continue - frame = current_app.video_frame - - if current_app.detector: - plants_boxes = current_app.detector.detect(frame, True) - frameFinal = detection.draw_boxes(frame, plants_boxes) - else: - frameFinal = frame - - undistorted_zone_radius = config.UNDISTORTED_ZONE_RADIUS - poly_zone_points_cv = np.array(config.WORKING_ZONE_POLY_POINTS, np.int32).reshape((-1, 1, 2)) - frameFinal = draw_zone_circle(frameFinal, config.SCENE_CENTER_X, config.SCENE_CENTER_Y, undistorted_zone_radius) - frameFinal = draw_zone_circle(frameFinal, config.SCENE_CENTER_X, config.SCENE_CENTER_Y, 2) - frameFinal = draw_zone_poly(frameFinal, poly_zone_points_cv) - - frameFinal = rescale_frame(frameFinal, percent=50) - return_key, encoded_image = cv2.imencode(".jpg", frameFinal) - if not return_key: - continue - - # Output image as a byte array - yield(b'--frame\r\n' b'Content-Type: image/jpeg\r\n\r\n' + - bytearray(encoded_image) + b'\r\n') - - -app = Flask(__name__) - -@app.route("/video") -def streamFrames(): - return Response(encodeFrame(), mimetype = "multipart/x-mixed-replace; boundary=frame") - -if __name__ == '__main__': - - use_detector_arg = True - if len(sys.argv)>1: - use_detector_arg = not sys.argv[1]=="False" - - print("Reset service cam !") - os.system("sudo systemctl restart nvargus-daemon") - - with app.app_context(): - current_app.thread_alive = True - current_app.video_frame = None - current_app.detector = None - current_app.thread_lock = threading.Lock() - - if use_detector_arg: - #current_app.detector = detection.YoloDarknetDetector(config.PERIPHERY_WEIGHTS_FILE, config.PERIPHERY_CONFIG_FILE, - # config.PERIPHERY_DATA_FILE, config.PERIPHERY_CONFIDENCE_THRESHOLD, - # config.PERIPHERY_HIER_THRESHOLD, config.PERIPHERY_NMS_THRESHOLD) - current_app.detector = detection.YoloTRTDetector( - config.PERIPHERY_MODEL_PATH, - config.PERIPHERY_CLASSES_FILE, - config.PERIPHERY_CONFIDENCE_THRESHOLD, - config.PERIPHERY_NMS_THRESHOLD, - config.PERIPHERY_INPUT_SIZE) - - process_thread = threading.Thread(target=captureFrames) - process_thread.daemon = True - process_thread.start() - app.run("0.0.0.0",8080,False) - - From 4437dc5113652ce7450c5672f1c98ad7d8a20a33 Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 10:45:53 +0200 Subject: [PATCH 03/12] Add parameters for cameraManager and binning for dragonfly --- config/config_v20_defaults.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/config/config_v20_defaults.py b/config/config_v20_defaults.py index 9f16a35..e49d4ce 100644 --- a/config/config_v20_defaults.py +++ b/config/config_v20_defaults.py @@ -1,7 +1,7 @@ """Configuration file.""" -CONFIG_VERSION = "2.2.1" +CONFIG_VERSION = "2.2.2" # ====================================================================================================================== @@ -623,6 +623,12 @@ # ====================================================================================================================== # CAMERA SETTINGS # ====================================================================================================================== +CAMERA_BACKEND = "auto" # "auto" | "aravis" | "imx219" +#- "auto": try Aravis first, fallback to IMX219 if no camera found +#- "aravis": force Aravis backend +#- "imx219": force Jetson IMX219 backend "gstreamer", "v4l2", "auto" +CAMERA_BINNING_H = 2 +CAMERA_BINNING_V = 2 CAMERA_W = 1920 CAMERA_H = 1080 APPLY_IMAGE_CROPPING = False From 3575fd09710e42884c2d95cb97d1640aac78f516 Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 11:30:14 +0200 Subject: [PATCH 04/12] Make little change for work (test without AI) --- adapters.py | 30 ++++++++++++++++++++---------- config/config_v20_defaults.py | 5 +++-- serverCamLive.py | 13 ++++++++++++- 3 files changed, 35 insertions(+), 13 deletions(-) diff --git a/adapters.py b/adapters.py index 56ccdcd..5b57ed0 100644 --- a/adapters.py +++ b/adapters.py @@ -1282,15 +1282,15 @@ def __init__(self, # 6: vertical flip → ReverseX=0, ReverseY=1 # Other values (1,3,5,7) are not supported by Aravis. - flip_mapping = {0: (0, 0), 2: (1, 1), 4: (1, 0), 6: (0, 1)} + flip_mapping = {0: (False, False), 2: (True, True), 4: (True, False), 6: (False, True)} if nvidia_flip_method in flip_mapping: reverse_x, reverse_y = flip_mapping[nvidia_flip_method] try: if self.cam.is_feature_available("ReverseX"): - self.cam.set_integer("ReverseX", reverse_x) + self.cam.set_boolean("ReverseX", reverse_x) if self.cam.is_feature_available("ReverseY"): - self.cam.set_integer("ReverseY", reverse_y) + self.cam.set_boolean("ReverseY", reverse_y) print(f"[{self.__class__.__name__}] → Applied ReverseX={reverse_x}, ReverseY={reverse_y} (flip-method={nvidia_flip_method})") except Exception as e: print(f"[{self.__class__.__name__}] ⚠️ Unable to set ReverseX/ReverseY: {e}") @@ -1358,17 +1358,27 @@ def _capture_loop(self): self.stream.push_buffer(buf) # ─────────── Public interface ─────────── - def get_image(self): - """Return the latest RGB frame.""" - with self._lock: - if not self._new_frame: - raise RuntimeError(f"[{self.__class__.__name__}] No image available.") - frame = self._buffers[self._ready_index] - self._new_frame = False + def get_image(self, timeout_s: float = 2.0): + """Return the latest RGB frame, waiting up to `timeout_s` seconds if none is ready.""" + start_time = time.time() + while True: + with self._lock: + if self._new_frame: + frame = self._buffers[self._ready_index] + self._new_frame = False + break + + # If no image has arrived yet, please wait a short while + if (time.time() - start_time) > timeout_s: + raise RuntimeError(f"[{self.__class__.__name__}] No image available after {timeout_s:.1f}s.") + time.sleep(0.05)# wait 50 ms before trying again + frame_rgb = cv.cvtColor(frame, cv.COLOR_BAYER_GB2BGR) + if self._cv_rotate_code is not None: frame_rgb = cv.rotate(frame_rgb, self._cv_rotate_code) + return frame_rgb def release(self): diff --git a/config/config_v20_defaults.py b/config/config_v20_defaults.py index e49d4ce..01fe4f8 100644 --- a/config/config_v20_defaults.py +++ b/config/config_v20_defaults.py @@ -91,6 +91,7 @@ CONTINUE_PREVIOUS_PATH = False PREVIOUS_PATH_POINTS_FILE = "path_points.dat" PREVIOUS_PATH_INDEX_FILE = "path_index.txt" +PREVIOUS_GNSS_INDEX_FILE = "path_gnss_index.txt" #Cyril covid ORIGIN_AVERAGE_SAMPLES = 8 @@ -629,8 +630,8 @@ #- "imx219": force Jetson IMX219 backend "gstreamer", "v4l2", "auto" CAMERA_BINNING_H = 2 CAMERA_BINNING_V = 2 -CAMERA_W = 1920 -CAMERA_H = 1080 +CAMERA_W = 1920//CAMERA_BINNING_H +CAMERA_H = 1080//CAMERA_BINNING_V APPLY_IMAGE_CROPPING = False CROP_W_FROM = 0 CROP_W_TO = 1920 diff --git a/serverCamLive.py b/serverCamLive.py index a952cf7..1a81255 100644 --- a/serverCamLive.py +++ b/serverCamLive.py @@ -2,13 +2,14 @@ import cv2 import threading import os +import signal import sys import numpy as np from flask import Flask, Response, jsonify from flask_cors import CORS from config import config import detection -from CameraAdapterManager import CameraAdapterManager +from adapters import CameraAdapterManager class ServerCamLive: @@ -217,4 +218,14 @@ def stop(self): use_detector = not ("--no-detector" in sys.argv) server = ServerCamLive(port=8080, use_detector=use_detector, display_zones=display_zones) + + def handle_exit(sig, frame): + print("\n[ServerCamLive] 🛑 Ctrl+C detected — stopping server and releasing camera...") + server.stop() + sys.exit(0) + + # Capture Ctrl+C (SIGINT) et kill (SIGTERM) + signal.signal(signal.SIGINT, handle_exit) + signal.signal(signal.SIGTERM, handle_exit) + server.start() \ No newline at end of file From 1f29647efe25aa5ad978efdba6f8f1902c4780fb Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 11:40:14 +0200 Subject: [PATCH 05/12] New adapter work with AI and serverCamLive can show zones --- serverCamLive.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/serverCamLive.py b/serverCamLive.py index 1a81255..659d6a2 100644 --- a/serverCamLive.py +++ b/serverCamLive.py @@ -39,6 +39,7 @@ def __init__(self, app=None, port=8080, use_detector=True, display_zones=False): self.video_frame = None self.thread_lock = threading.Lock() self.capture_thread = None + self._running = True # Register routes (always added) self._register_routes() @@ -130,7 +131,7 @@ def rescale_frame(self, frame, percent=50): def encode_frame(self): """Generate MJPEG byte stream.""" - while True: + while self._running: with self.thread_lock: frame = self.video_frame @@ -201,6 +202,7 @@ def stop(self): """Stop the capture thread and remove routes.""" print(f"[{self.__class__.__name__}] 🛑 Stopping camera stream...") + self._running = False self.thread_alive = False if self.cam: self.cam.release() From d0d62d376709dfd438a322469ee2809e0bba9596 Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 18:12:36 +0200 Subject: [PATCH 06/12] Make little changes --- adapters.py | 107 +++++++++++++++++++++++++++++++++------------------- 1 file changed, 69 insertions(+), 38 deletions(-) diff --git a/adapters.py b/adapters.py index 5b57ed0..b63eb9e 100644 --- a/adapters.py +++ b/adapters.py @@ -1242,11 +1242,18 @@ def __init__(self, exposuretimerange_from = exposuretimerange_from / 1000 exposuretimerange_to = exposuretimerange_to / 1000.0 - self._cv_rotate_code = cv_rotate_code self._running = False self._ready_index = 0 self._lock = threading.Lock() self._new_frame = False + self._framerate = framerate + + self._cv_codes = { + "BayerBG8": cv.COLOR_BAYER_RG2BGR, + "BayerGB8": cv.COLOR_BAYER_GR2BGR, + "BayerRG8": cv.COLOR_BAYER_BG2BGR, + "BayerGR8": cv.COLOR_BAYER_GB2BGR, + } # ─────────── Camera initialization ─────────── Aravis.update_device_list() @@ -1267,22 +1274,53 @@ def __init__(self, by = self.cam.get_integer("BinningVertical") if self.cam.is_feature_available("BinningVertical") else 1 eff_w, eff_h = sensor_w // bx, sensor_h // by - # ─────────── Centered ROI ─────────── - target_w, target_h = min(capture_width, eff_w), min(capture_height, eff_h) - ox = ((eff_w - target_w) // 2) * bx - oy = ((eff_h - target_h) // 2) * by - self.cam.set_region(ox, oy, target_w, target_h) - self._width, self._height = target_w, target_h + # ─────────── Configure ROI ─────────── + if config.APPLY_IMAGE_CROPPING: + # ─────────── Centered ROI ─────────── + target_w, target_h = min(capture_width, eff_w), min(capture_height, eff_h) + ox = ((eff_w - target_w) // 2) + oy = (eff_h - target_h) + self.cam.set_region(ox, oy, target_w, target_h) + self._width, self._height = target_w, target_h + else: + # ─────────── Full sensor ROI ─────────── + self.cam.set_region(0, 0, eff_w, eff_h) + self._width, self._height = eff_w, eff_h + + # ─────────── ExposureTime, gain and framerate ─────────── + + if gainrange_from != gainrange_to: + raise ValueError(f"[{self.__class__.__name__}] gainrange_from and gainrange_to must be equal.") + if exposuretimerange_from != exposuretimerange_to: + raise ValueError(f"[{self.__class__.__name__}] exposuretimerange_from and exposuretimerange_to must be equal.") + + for (k, v) in [("ExposureAuto", "Off"), ("GainAuto", "Off")]: + try: self.cam.set_string(k, v) + except Exception: pass + for (k, v) in [("ExposureTime", float(exposuretimerange_from)), ("Gain", float(gainrange_from))]: + try: self.cam.set_float(k, v) + except Exception: pass + + try: + self.cam.set_boolean("AcquisitionFrameRateEnable", True) + self.cam.set_float("AcquisitionFrameRate", self._framerate) + except Exception: + pass - # ─────────── Flip / rotation mapping (Aravis equivalent of nvidia_flip_method) ─────────── + # ─────────── Flip / rotation mapping (hardware + software hybrid) ─────────── # nvarguscamerasrc flip-method values: # 0: none → ReverseX=0, ReverseY=0 + # 1: rotate 90° CCW → emulate in software # 2: rotate 180° → ReverseX=1, ReverseY=1 + # 3: rotate 90° CW → emulate in software # 4: horizontal flip → ReverseX=1, ReverseY=0 + # 5: vertical flip + rotate 180° (upside down) → emulate in software # 6: vertical flip → ReverseX=0, ReverseY=1 - # Other values (1,3,5,7) are not supported by Aravis. + # 7: transverse (transpose + 180°) → emulate in software flip_mapping = {0: (False, False), 2: (True, True), 4: (True, False), 6: (False, True)} + + self._software_rotate_code = None if nvidia_flip_method in flip_mapping: reverse_x, reverse_y = flip_mapping[nvidia_flip_method] @@ -1295,33 +1333,9 @@ def __init__(self, except Exception as e: print(f"[{self.__class__.__name__}] ⚠️ Unable to set ReverseX/ReverseY: {e}") else: + self._software_rotate_code = nvidia_flip_method print(f"[{self.__class__.__name__}] ⚠️ flip-method={nvidia_flip_method} not supported by Aravis (only 0,2,4,6).") - # ─────────── Pixel format, exposureTime, gain and framerate ─────────── - - if gainrange_from != gainrange_to: - raise ValueError(f"[{self.__class__.__name__}] gainrange_from and gainrange_to must be equal.") - if exposuretimerange_from != exposuretimerange_to: - raise ValueError(f"[{self.__class__.__name__}] exposuretimerange_from and exposuretimerange_to must be equal.") - - try: - self.cam.set_pixel_format_from_string("BayerGR8") - except Exception: - print(f"[{self.__class__.__name__}] ⚠️ Bayer format not supported.") - - for (k, v) in [("ExposureAuto", "Off"), ("GainAuto", "Off")]: - try: self.cam.set_string(k, v) - except Exception: pass - for (k, v) in [("ExposureTime", float(exposuretimerange_from)), ("Gain", float(gainrange_from))]: - try: self.cam.set_float(k, v) - except Exception: pass - - try: - self.cam.set_boolean("AcquisitionFrameRateEnable", True) - self.cam.set_float("AcquisitionFrameRate", framerate) - except Exception: - pass - # ─────────── Stream & Buffers ─────────── self.stream = self.cam.create_stream(None, None) self.stream.set_emit_signals(False) @@ -1339,7 +1353,9 @@ def __init__(self, self._running = True self._thread = threading.Thread(target=self._capture_loop, daemon=True) self._thread.start() - print(f"[{self.__class__.__name__}] Aravis acquisition launched in {framerate} FPS ({target_w}x{target_h})") + print(f"[{self.__class__.__name__}] Aravis acquisition launched in {self._framerate} FPS ({self._width}x{self._height})") + + self._pixel_format = self.cam.get_pixel_format_as_string() # ─────────── Capture thread ─────────── def _capture_loop(self): @@ -1374,10 +1390,25 @@ def get_image(self, timeout_s: float = 2.0): raise RuntimeError(f"[{self.__class__.__name__}] No image available after {timeout_s:.1f}s.") time.sleep(0.05)# wait 50 ms before trying again - frame_rgb = cv.cvtColor(frame, cv.COLOR_BAYER_GB2BGR) + frame_rgb = cv.cvtColor(frame, self._cv_codes.get(self._pixel_format, cv.COLOR_BAYER_GB2BGR)) - if self._cv_rotate_code is not None: - frame_rgb = cv.rotate(frame_rgb, self._cv_rotate_code) + if self._software_rotate_code is not None: + code = self._software_rotate_code + if code == 1: + # rotate 90° counterclockwise + frame_rgb = cv.transpose(frame_rgb) + frame_rgb = cv.flip(frame_rgb, 0) + elif code == 3: + # rotate 90° clockwise + frame_rgb = cv.transpose(frame_rgb) + frame_rgb = cv.flip(frame_rgb, 1) + elif code == 5: + # upside down flip (vertical + horizontal) + frame_rgb = cv.flip(frame_rgb, -1) + elif code == 7: + # transverse (transpose + 180°) + frame_rgb = cv.transpose(frame_rgb) + frame_rgb = cv.flip(frame_rgb, -1) return frame_rgb From ecbef00db942c91331f8ea0f98cb4e35feadeaca Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 18:12:56 +0200 Subject: [PATCH 07/12] Put default value for dragonfly --- config/config_v20_defaults.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/config/config_v20_defaults.py b/config/config_v20_defaults.py index 01fe4f8..085a081 100644 --- a/config/config_v20_defaults.py +++ b/config/config_v20_defaults.py @@ -630,22 +630,22 @@ #- "imx219": force Jetson IMX219 backend "gstreamer", "v4l2", "auto" CAMERA_BINNING_H = 2 CAMERA_BINNING_V = 2 -CAMERA_W = 1920//CAMERA_BINNING_H -CAMERA_H = 1080//CAMERA_BINNING_V -APPLY_IMAGE_CROPPING = False +CAMERA_W = 2160//CAMERA_BINNING_H#2592//CAMERA_BINNING_H +CAMERA_H = 1216//CAMERA_BINNING_V#1944//CAMERA_BINNING_V +APPLY_IMAGE_CROPPING = True CROP_W_FROM = 0 CROP_W_TO = 1920 CROP_H_FROM = 0 CROP_H_TO = 1080 -CAMERA_FRAMERATE = 16 -CAMERA_FLIP_METHOD = 0 -SCENE_CENTER_X = 1000 -SCENE_CENTER_Y = 980 +CAMERA_FRAMERATE = 30 +CAMERA_FLIP_METHOD = 2 # 0=none, 1=counterclockwise, 2=rotate 180, 3=clockwise, 4=horizontal flip, 5=upside down flip, 6=transpose, 7=transverse +SCENE_CENTER_X = CAMERA_W//2 +SCENE_CENTER_Y = 1944//2//2 ONE_MM_IN_PX = 3.2 ISP_DIGITAL_GAIN_RANGE_FROM = 4 ISP_DIGITAL_GAIN_RANGE_TO = 4 -GAIN_RANGE_FROM = 4 -GAIN_RANGE_TO = 4 +GAIN_RANGE_FROM = 12 +GAIN_RANGE_TO = 12 EXPOSURE_TIME_RANGE_FROM = 660000 EXPOSURE_TIME_RANGE_TO = 660000 AE_LOCK = True From ca5d27aba4e0b570ea0645ab1146cd35ce0332bb Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 18:14:37 +0200 Subject: [PATCH 08/12] Change for work with new camera manager --- v3_make_photos_manual.py | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/v3_make_photos_manual.py b/v3_make_photos_manual.py index 73eeeb0..23c33b7 100644 --- a/v3_make_photos_manual.py +++ b/v3_make_photos_manual.py @@ -7,8 +7,6 @@ import utility import select -OUTPUT_DIR = "" - def markup_5_points(image): img_y_c, img_x_c = int(image.shape[0] / 2), int(image.shape[1] / 2) # center @@ -31,6 +29,7 @@ def manual_photos_making(camera): label = input("Please type a label to be added to photos: ") sep = " " counter = 1 + global OUTPUT_DIR path_piece = OUTPUT_DIR + label + sep while True: @@ -53,6 +52,7 @@ def run_performance_test(camera): label = input("Please type a label to be added to photos: ") sep = " " counter = 1 + global OUTPUT_DIR path_piece = OUTPUT_DIR + label + sep paused = False @@ -80,6 +80,7 @@ def main(): print("Usage: python v3_make_photos_manual.py ") sys.exit(1) + global OUTPUT_DIR OUTPUT_DIR = sys.argv[1] if not os.path.exists(OUTPUT_DIR): create = input(f"The directory '{OUTPUT_DIR}' does not exist. Do you want to create it? (y/n): ").strip().lower() @@ -91,13 +92,13 @@ def main(): sys.exit(1) print("Loading...") - with adapters.CameraAdapterIMX219_170(config.CROP_W_FROM, config.CROP_W_TO, config.CROP_H_FROM, - config.CROP_H_TO, config.CV_ROTATE_CODE, - config.ISP_DIGITAL_GAIN_RANGE_FROM, config.ISP_DIGITAL_GAIN_RANGE_TO, - config.GAIN_RANGE_FROM, config.GAIN_RANGE_TO, - config.EXPOSURE_TIME_RANGE_FROM, config.EXPOSURE_TIME_RANGE_TO, - config.AE_LOCK, config.CAMERA_W, config.CAMERA_H, config.CAMERA_W, - config.CAMERA_H, config.CAMERA_FRAMERATE, config.CAMERA_FLIP_METHOD) \ + with adapters.CameraAdapterManager( config.CROP_W_FROM, config.CROP_W_TO, config.CROP_H_FROM, + config.CROP_H_TO, config.CV_ROTATE_CODE, + config.ISP_DIGITAL_GAIN_RANGE_FROM, config.ISP_DIGITAL_GAIN_RANGE_TO, + config.GAIN_RANGE_FROM, config.GAIN_RANGE_TO, + config.EXPOSURE_TIME_RANGE_FROM, config.EXPOSURE_TIME_RANGE_TO, + config.AE_LOCK, config.CAMERA_W, config.CAMERA_H, config.CAMERA_W, + config.CAMERA_H, config.CAMERA_FRAMERATE, config.CAMERA_FLIP_METHOD) \ as camera: time.sleep(2) From 092e07e617a26a6aff545a1fd12229721a4de1bf Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Thu, 9 Oct 2025 18:37:08 +0200 Subject: [PATCH 09/12] Call new camera manager --- extraction.py | 2 +- main.py | 4 ++-- uiWebRobot/state_machine/utilsFunction.py | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/extraction.py b/extraction.py index bf9d65f..4cb66df 100644 --- a/extraction.py +++ b/extraction.py @@ -16,7 +16,7 @@ class ExtractionManagerV3: def __init__(self, smoothie: adapters.SmoothieAdapter, - camera: adapters.CameraAdapterIMX219_170, + camera: adapters.CameraAdapterInterface, logger_full: utility.Logger, data_collector: datacollection.DataCollector, image_saver: utility.ImageSaver, diff --git a/main.py b/main.py index 1615987..3f60df5 100644 --- a/main.py +++ b/main.py @@ -144,7 +144,7 @@ def move_to_point_and_extract(coords_from_to: list, gps: adapters.GPSUbloxAdapter, vesc_engine: adapters.VescAdapterV4, smoothie: adapters.SmoothieAdapter, - camera: adapters.CameraAdapterIMX219_170, + camera: adapters.CameraAdapterInterface, periphery_det: detection.YoloOpenCVDetection, precise_det: detection.YoloOpenCVDetection, logger_full: utility.Logger, @@ -2162,7 +2162,7 @@ def main(): config.VESC_STOPPER_CHECK_FREQ, logger_full) as vesc_engine, \ adapters.SmoothieAdapter(smoothie_address) as smoothie, \ adapters.GPSUbloxAdapter(config.GPS_PORT, config.GPS_BAUDRATE, config.GPS_POSITIONS_TO_KEEP) as gps, \ - adapters.CameraAdapterIMX219_170(config.CROP_W_FROM, config.CROP_W_TO, config.CROP_H_FROM, + adapters.CameraAdapterManager(config.CROP_W_FROM, config.CROP_W_TO, config.CROP_H_FROM, config.CROP_H_TO, config.CV_ROTATE_CODE, config.ISP_DIGITAL_GAIN_RANGE_FROM, config.ISP_DIGITAL_GAIN_RANGE_TO, diff --git a/uiWebRobot/state_machine/utilsFunction.py b/uiWebRobot/state_machine/utilsFunction.py index 6767b5a..23dcd96 100644 --- a/uiWebRobot/state_machine/utilsFunction.py +++ b/uiWebRobot/state_machine/utilsFunction.py @@ -272,7 +272,7 @@ def startLiveCam(): """ Function for starting the live camera. """ - camSP = subprocess.Popen("python3 serveurCamLive.py", stdin=subprocess.PIPE, stdout=subprocess.DEVNULL, cwd=os.getcwd().split( + camSP = subprocess.Popen("python3 serverCamLive.py", stdin=subprocess.PIPE, stdout=subprocess.DEVNULL, cwd=os.getcwd().split( "/uiWebRobot")[0], shell=True, preexec_fn=os.setsid) return camSP From 3e0efcf774c386e411d82d46fa85aa96078de88c Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Tue, 13 Jan 2026 09:32:15 +0100 Subject: [PATCH 10/12] Save 13/01/26 after 5 hours field test done --- adapters.py | 106 ++++-- config/config_v20_defaults.py | 2 +- detection.py | 74 ++-- index_webrtc.html | 67 ++++ liveMain/webstreaming.py | 14 +- serverCamLive.py | 5 +- serverCamLiveWebRTC.py | 335 ++++++++++++++++++ uiWebRobot/application.py | 64 +++- uiWebRobot/state_machine/states/CheckState.py | 10 +- .../state_machine/states/WorkingState.py | 20 +- 10 files changed, 610 insertions(+), 87 deletions(-) create mode 100644 index_webrtc.html create mode 100644 serverCamLiveWebRTC.py diff --git a/adapters.py b/adapters.py index b63eb9e..d122167 100644 --- a/adapters.py +++ b/adapters.py @@ -15,12 +15,12 @@ from serial import SerialException import numpy as np from abc import ABC, abstractmethod +import os import gi gi.require_version('Aravis', '0.8') from gi.repository import Aravis - class SmoothieAdapter: RESPONSE_OK = "ok\r\n" RESPONSE_ALARM_LOCK = "error:Alarm lock\n" @@ -1019,6 +1019,8 @@ def __init__(self, except Exception as e: print(f"[{self.__class__.__name__}] ⚠️ Aravis unavailable: {e}") print(f"[{self.__class__.__name__}] → Falling back to IMX219 backend.") + print(f"[{self.__class__.__name__}] 🔄 Restarting nvargus-daemon (if available)...") + os.system("sudo systemctl restart nvargus-daemon") self._adapter = CameraAdapterIMX219_170( crop_w_from, crop_w_to, crop_h_from, crop_h_to, cv_rotate_code, ispdigitalgainrange_from, ispdigitalgainrange_to, @@ -1039,6 +1041,8 @@ def __init__(self, ) elif self._backend_mode == "imx219": + print(f"[{self.__class__.__name__}] 🔄 Restarting nvargus-daemon (if available)...") + os.system("sudo systemctl restart nvargus-daemon") self._adapter = CameraAdapterIMX219_170( crop_w_from, crop_w_to, crop_h_from, crop_h_to, cv_rotate_code, ispdigitalgainrange_from, ispdigitalgainrange_to, @@ -1245,7 +1249,6 @@ def __init__(self, self._running = False self._ready_index = 0 self._lock = threading.Lock() - self._new_frame = False self._framerate = framerate self._cv_codes = { @@ -1350,12 +1353,33 @@ def __init__(self, ] self.cam.start_acquisition() + + # ─────────── Timestamp offset calibration ─────────── + if config.CAMERA_PRINT_LATENCY: + print(f"[{self.__class__.__name__}] Waiting for first buffer to calibrate timestamp offset...") + buf = None + while buf is None: + buf = self.stream.try_pop_buffer() + + if buf.get_status() == Aravis.BufferStatus.SUCCESS: + # Get the camera’s hardware timestamp (in ns) and convert to seconds + cam_ts = buf.get_timestamp() / 1e9 + # Get the current system time in seconds + sys_ts = time.time() + # Compute the offset so that future timestamps are expressed in system time + self._timestamp_offset = sys_ts - cam_ts + print(f"[{self.__class__.__name__}] Timestamp offset calibrated: {self._timestamp_offset:.6f}s") + + # Push buffer back to the stream for reuse + self.stream.push_buffer(buf) + self._running = True self._thread = threading.Thread(target=self._capture_loop, daemon=True) self._thread.start() print(f"[{self.__class__.__name__}] Aravis acquisition launched in {self._framerate} FPS ({self._width}x{self._height})") self._pixel_format = self.cam.get_pixel_format_as_string() + # ─────────── Capture thread ─────────── def _capture_loop(self): @@ -1366,52 +1390,86 @@ def _capture_loop(self): continue if buf.get_status() == Aravis.BufferStatus.SUCCESS: data = buf.get_data() + + if config.CAMERA_PRINT_LATENCY: + # Hardware timestamp in seconds + ts_ns = buf.get_timestamp() # timestamp in nanoseconds + capture_time = ts_ns / 1e9 # conversion in seconds + np.copyto(self._buffers[idx], np.frombuffer(data, dtype=np.uint8).reshape(self._buffers[idx].shape)) + with self._lock: self._ready_index = idx - self._new_frame = True + if config.CAMERA_PRINT_LATENCY: + self._last_hw_timestamp = capture_time + idx = 1 - idx + self.stream.push_buffer(buf) # ─────────── Public interface ─────────── - def get_image(self, timeout_s: float = 2.0): - """Return the latest RGB frame, waiting up to `timeout_s` seconds if none is ready.""" - start_time = time.time() - - while True: - with self._lock: - if self._new_frame: - frame = self._buffers[self._ready_index] - self._new_frame = False - break - - # If no image has arrived yet, please wait a short while - if (time.time() - start_time) > timeout_s: - raise RuntimeError(f"[{self.__class__.__name__}] No image available after {timeout_s:.1f}s.") - time.sleep(0.05)# wait 50 ms before trying again - - frame_rgb = cv.cvtColor(frame, self._cv_codes.get(self._pixel_format, cv.COLOR_BAYER_GB2BGR)) + def get_image(self): + """Return the latest RGB frame and log latency statistics every 10 seconds.""" + + # Get the current frame safely + with self._lock: + frame = self._buffers[self._ready_index] + hw_ts = getattr(self, "_last_hw_timestamp", None) + # Convert Bayer → RGB + frame_rgb = cv.cvtColor(frame, self._cv_codes.get(self._pixel_format, cv.COLOR_BAYER_GB2BGR)) + + # Apply rotation if needed if self._software_rotate_code is not None: code = self._software_rotate_code if code == 1: - # rotate 90° counterclockwise frame_rgb = cv.transpose(frame_rgb) frame_rgb = cv.flip(frame_rgb, 0) elif code == 3: - # rotate 90° clockwise frame_rgb = cv.transpose(frame_rgb) frame_rgb = cv.flip(frame_rgb, 1) elif code == 5: - # upside down flip (vertical + horizontal) frame_rgb = cv.flip(frame_rgb, -1) elif code == 7: - # transverse (transpose + 180°) frame_rgb = cv.transpose(frame_rgb) frame_rgb = cv.flip(frame_rgb, -1) + # ─────────── Latency & FPS stats ─────────── + if config.CAMERA_PRINT_LATENCY: + hw_ts += getattr(self, "_timestamp_offset", 0.0) + now = time.time() + if hw_ts is not None: + latency_ms = (now - hw_ts) * 1000.0 + + # Initialize stats on first frame + if not hasattr(self, "_stats_start_time"): + self._stats_start_time = now + self._latencies = [] + self._frames = 0 + + self._latencies.append(latency_ms) + self._frames += 1 + + # Every 10 seconds → compute and print statistics + if (now - self._stats_start_time) >= 10.0: + avg_latency = sum(self._latencies) / len(self._latencies) + min_latency = min(self._latencies) + max_latency = max(self._latencies) + + print( + f"[{self.__class__.__name__}] " + f"Latency avg: {avg_latency:.2f} ms " + f"(min: {min_latency:.2f}, max: {max_latency:.2f})" + ) + + # Reset stats window + self._stats_start_time = now + self._latencies.clear() + self._frames = 0 + return frame_rgb + def release(self): """Stop the capture process cleanly.""" self._running = False diff --git a/config/config_v20_defaults.py b/config/config_v20_defaults.py index 085a081..8ed9dbe 100644 --- a/config/config_v20_defaults.py +++ b/config/config_v20_defaults.py @@ -641,7 +641,7 @@ CAMERA_FLIP_METHOD = 2 # 0=none, 1=counterclockwise, 2=rotate 180, 3=clockwise, 4=horizontal flip, 5=upside down flip, 6=transpose, 7=transverse SCENE_CENTER_X = CAMERA_W//2 SCENE_CENTER_Y = 1944//2//2 -ONE_MM_IN_PX = 3.2 +ONE_MM_IN_PX = 2.9 ISP_DIGITAL_GAIN_RANGE_FROM = 4 ISP_DIGITAL_GAIN_RANGE_TO = 4 GAIN_RANGE_FROM = 12 diff --git a/detection.py b/detection.py index ce18dfb..dc2cd26 100644 --- a/detection.py +++ b/detection.py @@ -164,7 +164,7 @@ def detect(self, image, disable_frame_show=False): if config.FRAME_SHOW and not disable_frame_show: - t1 = time.time() + #t1 = time.time() #img = draw_boxes(image, plant_boxes) img = image @@ -184,19 +184,19 @@ def detect(self, image, disable_frame_show=False): #print(time.time() - t1) - if not YoloDarknetDetector.WEBSTREAM: - template_dir = os.path.abspath('./liveMain') - app = Flask("webstreaming", template_folder=template_dir) - CORS(app) - app.add_url_rule('/', view_func=webstreaming.index) - app.add_url_rule('/video_feed', view_func=webstreaming.video_feed) + # if not YoloDarknetDetector.WEBSTREAM: + # template_dir = os.path.abspath('./liveMain') + # app = Flask("webstreaming", template_folder=template_dir) + # CORS(app) + # app.add_url_rule('/', view_func=webstreaming.index) + # app.add_url_rule('/video_feed', view_func=webstreaming.video_feed) - logging.getLogger('werkzeug').disabled = True - os.environ['WERKZEUG_RUN_MAIN'] = 'true' + # logging.getLogger('werkzeug').disabled = True + # os.environ['WERKZEUG_RUN_MAIN'] = 'true' - YoloDarknetDetector.webStream = Process(target=app.run, args=("0.0.0.0",8888,False)) - YoloDarknetDetector.webStream.start() - YoloDarknetDetector.WEBSTREAM = True + # YoloDarknetDetector.webStream = Process(target=app.run, args=("0.0.0.0",8888,False)) + # YoloDarknetDetector.webStream.start() + # YoloDarknetDetector.WEBSTREAM = True return plant_boxes @@ -286,7 +286,7 @@ def detect(self, image, disable_frame_show=False): if config.FRAME_SHOW and not disable_frame_show: - t1 = time.time() + #t1 = time.time() #img = draw_boxes(image, plant_boxes) img = image @@ -306,19 +306,19 @@ def detect(self, image, disable_frame_show=False): #print(time.time() - t1) - if not YoloTRTDetector.WEBSTREAM: - template_dir = os.path.abspath('./liveMain') - app = Flask("webstreaming", template_folder=template_dir) - CORS(app) - app.add_url_rule('/', view_func=webstreaming.index) - app.add_url_rule('/video_feed', view_func=webstreaming.video_feed) + # if not YoloTRTDetector.WEBSTREAM: + # template_dir = os.path.abspath('./liveMain') + # app = Flask("webstreaming", template_folder=template_dir) + # CORS(app) + # app.add_url_rule('/', view_func=webstreaming.index) + # app.add_url_rule('/video_feed', view_func=webstreaming.video_feed) - logging.getLogger('werkzeug').disabled = True - os.environ['WERKZEUG_RUN_MAIN'] = 'true' + # logging.getLogger('werkzeug').disabled = True + # os.environ['WERKZEUG_RUN_MAIN'] = 'true' - YoloTRTDetector.webStream = Process(target=app.run, args=("0.0.0.0",8888,False)) - YoloTRTDetector.webStream.start() - YoloTRTDetector.WEBSTREAM = True + # YoloTRTDetector.webStream = Process(target=app.run, args=("0.0.0.0",8888,False)) + # YoloTRTDetector.webStream.start() + # YoloTRTDetector.WEBSTREAM = True return plant_boxes @@ -353,8 +353,34 @@ def _allocate_buffers(self, engine): outputs.append(HostDeviceMem(host_mem, device_mem)) return inputs, outputs, bindings, stream + + def letterbox_fast(self, img, target_size=(416, 416)): + ih, iw = img.shape[:2] + h, w = target_size + + scale = min(w / iw, h / ih) + nw, nh = int(iw * scale), int(ih * scale) + + # Resize + img_resized = cv.resize(img, (nw, nh), interpolation=cv.INTER_LINEAR) + + # Padding avec copyMakeBorder (plus rapide) + top = (h - nh) // 2 + bottom = h - nh - top + left = (w - nw) // 2 + right = w - nw - left + + img_padded = cv.copyMakeBorder( + img_resized, + top, bottom, left, right, + cv.BORDER_CONSTANT, + value=[114, 114, 114] + ) + + return img_padded, scale, (left, top) def _preprocess(self, image): + #processed_image = self.letterbox_fast(image, (self.__width, self.__height))[0] processed_image = cv.resize(image, (self.__width, self.__height)) processed_image = cv.cvtColor(processed_image, cv.COLOR_BGR2RGB) processed_image = processed_image.transpose((2, 0, 1)).astype(np.float32) diff --git a/index_webrtc.html b/index_webrtc.html new file mode 100644 index 0000000..bb348f6 --- /dev/null +++ b/index_webrtc.html @@ -0,0 +1,67 @@ + + + + + + Aravis WebRTC Stream + + + + +

📡 Live Stream from Jetson / Aravis

+ +

Connecting...

+ + + + + \ No newline at end of file diff --git a/liveMain/webstreaming.py b/liveMain/webstreaming.py index 6770da8..b2af775 100644 --- a/liveMain/webstreaming.py +++ b/liveMain/webstreaming.py @@ -21,15 +21,17 @@ def rescale_frame(frame, percent=75): def generate(): sharedMemory = posix_ipc.SharedMemory(config.SHARED_MEMORY_NAME_DETECTED_FRAME) + sharedMem = mmap(fileno=sharedMemory.fd, length=0) sharedMemory.close_fd() - if config.APPLY_IMAGE_CROPPING: - img_w = config.CROP_W_TO - config.CROP_W_FROM - img_h = config.CROP_H_TO - config.CROP_H_FROM - else: - img_w = config.CAMERA_W - img_h = config.CAMERA_H + # if config.APPLY_IMAGE_CROPPING: + # img_w = config.CROP_W_TO - config.CROP_W_FROM + # img_h = config.CROP_H_TO - config.CROP_H_FROM + # else: + + img_w = config.CAMERA_W + img_h = config.CAMERA_H sharedArray = np.ndarray((img_h, img_w, 3), dtype=np.uint8, buffer=sharedMem) diff --git a/serverCamLive.py b/serverCamLive.py index 659d6a2..656cc3b 100644 --- a/serverCamLive.py +++ b/serverCamLive.py @@ -1,7 +1,6 @@ #!/usr/bin/env python3 import cv2 import threading -import os import signal import sys import numpy as np @@ -153,7 +152,7 @@ def encode_frame(self): except Exception as e: print(f"[{self.__class__.__name__}] ⚠️ Zone drawing failed: {e}") - frame = self.rescale_frame(frame, percent=50) + #frame = self.rescale_frame(frame, percent=50) ok, encoded = cv2.imencode(".jpg", frame) if not ok: continue @@ -173,8 +172,6 @@ def stream_frames(self): def start(self): """Initialize camera, detector, and capture thread. If no external app, also runs Flask server.""" - print(f"[{self.__class__.__name__}] 🔄 Restarting nvargus-daemon (if available)...") - os.system("sudo systemctl restart nvargus-daemon") self.init_camera() diff --git a/serverCamLiveWebRTC.py b/serverCamLiveWebRTC.py new file mode 100644 index 0000000..8e876d2 --- /dev/null +++ b/serverCamLiveWebRTC.py @@ -0,0 +1,335 @@ +#!/usr/bin/env python3 +import os, sys, cv2, time, threading, signal, json +from flask import Flask, request, jsonify, Response +from config import config +from adapters import CameraAdapterManager + +# ── GStreamer (fourni par JetPack) ───────────────────────────────────────────── +import gi +gi.require_version('Gst', '1.0') +gi.require_version('GstWebRTC', '1.0') +gi.require_version('GstSdp', '1.0') +from gi.repository import Gst, GstWebRTC, GstSdp, GObject, GLib + +Gst.init(None) +GObject.threads_init() + + +class ServerCamLiveWebRTC: + """ + WebRTC streaming server using: + - CameraAdapterManager for frame capture (Aravis / IMX219) + - GStreamer pipeline: appsrc -> (NVENC or x264enc) -> rtph264pay -> webrtcbin + - Flask for signaling (no extra libs needed on JetPack) + """ + + def __init__(self, app: Flask | None = None, port: int = 8080, + width: int = 960, height: int = 540, fps: int = 30): + self.external_app = app is not None + self.app = app or Flask(__name__) + self.port = port + self.width, self.height, self.fps = width, height, fps + + # Camera + self.cam = None + self.capture_thread = None + self._run_capture = False + self._last_frame = None + self._frame_lock = threading.Lock() + + # GStreamer / WebRTC + self.pipeline = None + self.appsrc = None + self.webrtcbin = None + self.loop = GLib.MainLoop() + self._gst_thread = None + + # Signaling sync + self._answer_ready = threading.Event() + self._gathering_done = threading.Event() + self._local_sdp_answer = None + + # Register routes + self._register_routes() + + # ─────────────────────────── Routes Flask ─────────────────────────── + def _register_routes(self): + @self.app.route("/") + def index(): + return Response(self._client_html(), mimetype="text/html") + + @self.app.route("/offer", methods=["POST"]) + def offer(): + """Receive SDP offer (from browser), set remote desc, create answer, return SDP answer.""" + data = request.get_json(force=True) + sdp = data["sdp"] + # Set remote description + ok, sdpmsg = GstSdp.SDPMessage.new() + GstSdp.sdp_message_parse_buffer(bytes(sdp.encode("utf-8")), sdpmsg) + remote_desc = GstWebRTC.WebRTCSessionDescription.new(GstWebRTC.WebRTCSDPType.OFFER, sdpmsg) + self.webrtcbin.emit("set-remote-description", remote_desc) + + # Create answer (async) + self.webrtcbin.emit("create-answer", None, self._on_create_answer, None) + + # Wait until local SDP answer is generated and ICE gathered + if not self._answer_ready.wait(timeout=5.0): + return jsonify({"error": "timeout creating answer"}), 500 + # Optionally wait ICE complete to bundle candidates in SDP (simpler client) + self._gathering_done.wait(timeout=5.0) + + return jsonify({"sdp": self._local_sdp_answer, "type": "answer"}) + + @self.app.route("/info") + def info(): + backend = self.cam.backend() if self.cam else None + whoami = self.cam.whoami() if self.cam else None + return jsonify({ + "backend": backend, + "class": whoami, + "webrtc": bool(self.webrtcbin is not None), + "width": self.width, + "height": self.height, + "fps": self.fps, + }) + + # ───────────────────── Client HTML minimal (WebRTC) ───────────────────── + def _client_html(self) -> str: + return f""" + +WebRTC Jetson + +
WebRTC stream (H.264) — {self.width}x{self.height}@{self.fps}fps
+ + + +""" + + # ───────────────────────── GStreamer / WebRTC ───────────────────────── + def _build_pipeline(self): + """Create pipeline: appsrc -> (encoder) -> rtph264pay -> webrtcbin""" + # Encoder: prefer NVENC if available, fallback to x264 + enc_factory = Gst.ElementFactory.find("nvv4l2h264enc") or Gst.ElementFactory.find("omxh264enc") + use_nvenc = enc_factory is not None + + self.pipeline = Gst.Pipeline.new("p") + + # appsrc + self.appsrc = Gst.ElementFactory.make("appsrc", "src") + self.appsrc.set_property("is-live", True) + self.appsrc.set_property("block", True) + self.appsrc.set_property("format", Gst.Format.TIME) + # caps: I420 @ width x height @ fps + caps = Gst.Caps.from_string( + f"video/x-raw,format=I420,width={self.width},height={self.height},framerate={self.fps}/1" + ) + self.appsrc.set_property("caps", caps) + + convert = Gst.ElementFactory.make("videoconvert", None) + + if use_nvenc: + encoder = Gst.ElementFactory.make("nvv4l2h264enc", "enc") + # low-latency settings + encoder.set_property("insert-sps-pps", True) + encoder.set_property("iframeinterval", self.fps) # keyframe every 1s + encoder.set_property("bitrate", 4000) # ~4Mbps + else: + encoder = Gst.ElementFactory.make("x264enc", "enc") + encoder.set_property("tune", "zerolatency") + encoder.set_property("speed-preset", "ultrafast") + encoder.set_property("bitrate", 2000) + encoder.set_property("key-int-max", self.fps) + + h264parse = Gst.ElementFactory.make("h264parse", None) + h264parse.set_property("config-interval", 1) + + pay = Gst.ElementFactory.make("rtph264pay", "pay") + pay.set_property("pt", 96) + pay.set_property("config-interval", 1) + + self.webrtcbin = Gst.ElementFactory.make("webrtcbin", "webrtc") + # STUN public (peut être omis en LAN) + self.webrtcbin.set_property("stun-server", "stun://stun.l.google.com:19302") + + # Signals for SDP/ICE + self.webrtcbin.connect("on-ice-candidate", self._on_ice_candidate) + self.webrtcbin.connect("ice-gathering-state-change", self._on_ice_gather_state) + + for el in [self.appsrc, convert, encoder, h264parse, pay, self.webrtcbin]: + self.pipeline.add(el) + + if not Gst.Element.link_many(self.appsrc, convert, encoder, h264parse, pay): + raise RuntimeError("Failed to link elements before webrtcbin") + # Link pay → webrtcbin (request pad) + pay_src_pad = pay.get_static_pad("src") + webrtc_sink_pad = self.webrtcbin.get_request_pad("sink_%u") + pay_src_pad.link(webrtc_sink_pad) + + def _on_create_answer(self, webrtc, promise, _): + """GStreamer async callback when answer is created.""" + reply = promise.get_reply() + answer = reply.get_value("answer") + promise = Gst.Promise.new() + self.webrtcbin.emit("set-local-description", answer, promise) + promise.interrupt() # we don't need to wait here + + # Serialize SDP + sdp_text = answer.sdp.as_text() + self._local_sdp_answer = sdp_text + self._answer_ready.set() + + def _on_ice_candidate(self, webrtc, mlineindex, candidate): + # Trickle ICE path (browser typically handles these incrementally). + # Here we do nothing explicit; candidates are included as gathering completes. + pass + + def _on_ice_gather_state(self, webrtc, state): + # GST_WEBRTC_ICE_GATHERING_STATE_COMPLETE == 2 (older) or 3 (newer); be permissive + try: + val = int(state.value_nick) # not reliable + except Exception: + val = None + # Just mark done when state nick says "complete" + if str(state).lower().endswith("complete"): + self._gathering_done.set() + + def _gst_mainloop(self): + try: + self.loop.run() + except Exception: + pass + + # ───────────────────────── Capture & push ───────────────────────── + def _capture_loop(self): + """Grab frames from CameraAdapterManager, push to appsrc as I420 buffers with timestamps.""" + nanos_per_frame = int(1e9 / self.fps) + pts = 0 + while self._run_capture: + try: + frame_bgr = self.cam.get_image() # numpy BGR + except Exception: + time.sleep(0.01) + continue + + # Resize to target, convert BGR->I420 + if frame_bgr.shape[1] != self.width or frame_bgr.shape[0] != self.height: + frame_bgr = cv2.resize(frame_bgr, (self.width, self.height), interpolation=cv2.INTER_AREA) + frame_yuv = cv2.cvtColor(frame_bgr, cv2.COLOR_BGR2YUV_I420) + + # Create Gst.Buffer + buf = Gst.Buffer.new_allocate(None, frame_yuv.nbytes, None) + buf.fill(0, frame_yuv.tobytes()) + buf.pts = pts + buf.dts = pts + buf.duration = nanos_per_frame + pts += nanos_per_frame + + # Push to appsrc + ret = self.appsrc.emit("push-buffer", buf) + if ret != Gst.FlowReturn.OK: + # If downstream not ready yet, wait a bit + time.sleep(0.005) + + # EOS when stopping + try: + self.appsrc.emit("end-of-stream") + except Exception: + pass + + # ───────────────────────── Lifecycle ───────────────────────── + def start(self): + # Camera via manager + self.cam = CameraAdapterManager( + crop_w_from=config.CROP_W_FROM, crop_w_to=config.CROP_W_TO, + crop_h_from=config.CROP_H_FROM, crop_h_to=config.CROP_H_TO, + cv_rotate_code=None, + ispdigitalgainrange_from=config.ISP_DIGITAL_GAIN_RANGE_FROM, + ispdigitalgainrange_to=config.ISP_DIGITAL_GAIN_RANGE_TO, + gainrange_from=config.GAIN_RANGE_FROM, gainrange_to=config.GAIN_RANGE_TO, + exposuretimerange_from=config.EXPOSURE_TIME_RANGE_FROM, + exposuretimerange_to=config.EXPOSURE_TIME_RANGE_TO, + aelock=config.AE_LOCK, + capture_width=self.width, capture_height=self.height, + display_width=self.width, display_height=self.height, + framerate=self.fps, + nvidia_flip_method=config.CAMERA_FLIP_METHOD, + backend="auto", + ) + print(f"[ServerCamLiveWebRTC] 🎥 Camera: {self.cam.backend()} ({self.cam.whoami()})") + + # Build pipeline and start GLib mainloop in thread + self._build_pipeline() + self.pipeline.set_state(Gst.State.PLAYING) + self._gst_thread = threading.Thread(target=self._gst_mainloop, daemon=True) + self._gst_thread.start() + + # Start capture → appsrc + self._run_capture = True + self.capture_thread = threading.Thread(target=self._capture_loop, daemon=True) + self.capture_thread.start() + + if not self.external_app: + print(f"[ServerCamLiveWebRTC] 🌐 Serving on http://0.0.0.0:{self.port}") + self.app.run("0.0.0.0", self.port, debug=False, use_reloader=False) + + def stop(self): + print("[ServerCamLiveWebRTC] 🛑 Stopping ...") + self._run_capture = False + try: + if self.capture_thread: + self.capture_thread.join(timeout=1.0) + except Exception: + pass + + if self.pipeline: + self.pipeline.set_state(Gst.State.NULL) + if self.cam: + self.cam.release() + try: + self.loop.quit() + except Exception: + pass + print("[ServerCamLiveWebRTC] ✅ Stopped.") + + +# ─────────────────────────── Entrypoint ─────────────────────────── +if __name__ == "__main__": + import argparse + parser = argparse.ArgumentParser() + parser.add_argument("--port", type=int, default=8080) + parser.add_argument("--width", type=int, default=960) + parser.add_argument("--height", type=int, default=540) + parser.add_argument("--fps", type=int, default=30) + args = parser.parse_args() + + server = ServerCamLiveWebRTC(port=args.port, width=args.width, height=args.height, fps=args.fps) + + def handle_exit(sig, frame): + print("\n[ServerCamLiveWebRTC] CTRL+C") + server.stop() + sys.exit(0) + + signal.signal(signal.SIGINT, handle_exit) + signal.signal(signal.SIGTERM, handle_exit) + + server.start() diff --git a/uiWebRobot/application.py b/uiWebRobot/application.py index 733b0e6..bd08a85 100644 --- a/uiWebRobot/application.py +++ b/uiWebRobot/application.py @@ -12,7 +12,7 @@ from flask_socketio import SocketIO, emit from engineio.payload import Payload from werkzeug.exceptions import HTTPException -from flask import Flask, render_template, make_response, send_from_directory, request, redirect +from flask import Flask, render_template, make_response, send_from_directory, request, redirect, Response import logging import json @@ -29,6 +29,11 @@ from uiWebRobot.state_machine.states import * import traceback +import cv2 as cv +import numpy as np +from mmap import mmap + + __author__ = 'Vincent LAMBERT' @@ -37,18 +42,22 @@ class UIWebRobot: def __init__(self): self.__app = Flask(__name__) self.__setting_flask() + self.__reload_config() self.__init_flask_route() # ROUTE FLASK self.__socketio = SocketIO( self.__app, async_mode=None, logger=False, engineio_logger=False) self.__init_socketio() # SOCKET IO - self.__reload_config() self.__robot_state_client = RobotStateClient() self.init_params() self.demo_pause_client = utility.DemoPauseClient( - config.DEMO_PAUSES_HOST, config.DEMO_PAUSES_PORT) - + self.__config.DEMO_PAUSES_HOST, self.__config.DEMO_PAUSES_PORT) def exit(self): + print(f"[{self.__class__.__name__}] -> Closing threads...") + self.__thread_notification_alive = False + self.__thread_notification.join() + print(f"[{self.__class__.__name__}] -> Threads closed ✅") + self.__generate_stream_alive = False print(f"[{self.__class__.__name__}] -> Send RobotSynthesis...") self.__robot_state_client.set_robot_state_and_wait_send(RobotSynthesis.OP) print(f"[{self.__class__.__name__}] -> Sent ✅") @@ -56,9 +65,6 @@ def exit(self): def on_connect(self): print("A client is connected.") - def on_connect(self): - print("A client is connected.") - def __init_socketio(self): self.__socketio.on_event( 'data', self.on_socket_broadcast, namespace='/broadcast') @@ -85,6 +91,8 @@ def __init_flask_route(self): self.__app.add_url_rule("/actuator_screening", view_func=self.actuator_screening) self.__app.add_url_rule("/run_life_line", view_func=self.run_life_line) self.__app.add_url_rule("/analyse_data_vesc", view_func=self.analyse_data_vesc) + if self.__config.FRAME_SHOW: + self.__app.add_url_rule("/video_feed", view_func=self.video_feed) def __setting_flask(self): self.__app.register_error_handler(Exception, self.handle_exception) @@ -106,9 +114,11 @@ def init_params(self): self.__filename_for_send_from_directory = not "path" in send_from_directory.__code__.co_varnames with open("ui_language.json", "r", encoding='utf-8') as read_file: self.__ui_languages = json.load(read_file) - thread_notification = Thread(target=self.catch_send_notification) - thread_notification.setDaemon(True) - thread_notification.start() + self.__thread_notification_alive = True + self.__generate_stream_alive = True + self.__thread_notification = Thread(target=self.catch_send_notification) + self.__thread_notification.setDaemon(True) + self.__thread_notification.start() self.__stateMachine = StateMachine(self.__socketio, self.__robot_state_client) def get_state_machine(self) -> StateMachine: @@ -158,17 +168,41 @@ def catch_send_notification(self): self.__config.QUEUE_NAME_UI_NOTIFICATION, posix_ipc.O_CREX) ui_language = self.__config.UI_LANGUAGE - while True: + while self.__thread_notification_alive: try: notification = notificationQueue.receive(timeout=1) message_name = json.loads(notification[0])["message_name"] message = self.__ui_languages[message_name][ui_language] self.__socketio.emit('notification', { "message_name": message_name, "message": message}, namespace='/broadcast', broadcast=True) - except KeyboardInterrupt: - raise KeyboardInterrupt except: continue + + def rescale_frame(self, frame, percent=75): + width = int(frame.shape[1] * percent / 100) + height = int(frame.shape[0] * percent / 100) + dim = (width, height) + return cv.resize(frame, dim, interpolation=cv.INTER_AREA) + + def generate_stream(self): + sharedMemory = posix_ipc.SharedMemory(self.__config.SHARED_MEMORY_NAME_DETECTED_FRAME) + sharedMem = mmap(fileno=sharedMemory.fd, length=0) + sharedMemory.close_fd() + + img_w = self.__config.CAMERA_W + img_h = self.__config.CAMERA_H + + sharedArray = np.ndarray((img_h, img_w, 3), dtype=np.uint8, buffer=sharedMem) + + while self.__generate_stream_alive: + #frame = self.rescale_frame(sharedArray, percent=30) + ok, encoded = cv.imencode(".jpg", sharedArray) + if not ok: + continue + yield (b'--frame\r\n' + b'Content-Type: image/jpeg\r\n\r\n' + + bytearray(encoded) + + b'\r\n') # SOCKET IO def on_socket_data(self, data): @@ -231,6 +265,9 @@ def on_disconnect(self): # ROUTE FLASK + def video_feed(self): + return Response(self.generate_stream(), mimetype="multipart/x-mixed-replace; boundary=frame") + def index(self): sn = self.__config.ROBOT_SN # sn = "SNXXX" @@ -454,6 +491,7 @@ def main(): print("[UIWebRobot] -> Closing app...") uiWebRobot.get_state_machine().on_event(Events.CLOSE_APP) uiWebRobot.exit() + exit(0) if __name__ == "__main__": main() diff --git a/uiWebRobot/state_machine/states/CheckState.py b/uiWebRobot/state_machine/states/CheckState.py index 24ed6c6..11b82ea 100644 --- a/uiWebRobot/state_machine/states/CheckState.py +++ b/uiWebRobot/state_machine/states/CheckState.py @@ -78,11 +78,11 @@ def on_event(self, event): self.logger.write_and_flush(msg + "\n") print(msg) os.killpg(os.getpgid(self.cam.pid), signal.SIGKILL) - if config.UI_VERBOSE_LOGGING: - msg = f"[{self.__class__.__name__}] -> Restarting camera nvargus-daemon service..." - self.logger.write_and_flush(msg + "\n") - print(msg) - os.system("sudo systemctl restart nvargus-daemon") + # if config.UI_VERBOSE_LOGGING: + # msg = f"[{self.__class__.__name__}] -> Restarting camera nvargus-daemon service..." + # self.logger.write_and_flush(msg + "\n") + # print(msg) + # os.system("sudo systemctl restart nvargus-daemon") if config.NTRIP: if config.UI_VERBOSE_LOGGING: msg = f"[{self.__class__.__name__}] -> Restarting ntripClient.service..." diff --git a/uiWebRobot/state_machine/states/WorkingState.py b/uiWebRobot/state_machine/states/WorkingState.py index f886d6b..af30053 100644 --- a/uiWebRobot/state_machine/states/WorkingState.py +++ b/uiWebRobot/state_machine/states/WorkingState.py @@ -144,12 +144,12 @@ def on_event(self, event): self.main.wait() - if config.UI_VERBOSE_LOGGING: - msg = f"[{self.__class__.__name__}] -> Restart camera" - self.logger.write_and_flush(msg + "\n") - print(msg) + # if config.UI_VERBOSE_LOGGING: + # msg = f"[{self.__class__.__name__}] -> Restart camera" + # self.logger.write_and_flush(msg + "\n") + # print(msg) - os.system("sudo systemctl restart nvargus-daemon") + # os.system("sudo systemctl restart nvargus-daemon") if config.UI_VERBOSE_LOGGING: msg = f"[{self.__class__.__name__}] -> Try to stop main thread if alive" @@ -210,12 +210,12 @@ def on_event(self, event): self.main.wait() - if config.UI_VERBOSE_LOGGING: - msg = f"[{self.__class__.__name__}] -> Restart camera" - self.logger.write_and_flush(msg + "\n") - print(msg) + # if config.UI_VERBOSE_LOGGING: + # msg = f"[{self.__class__.__name__}] -> Restart camera" + # self.logger.write_and_flush(msg + "\n") + # print(msg) - os.system("sudo systemctl restart nvargus-daemon") + # os.system("sudo systemctl restart nvargus-daemon") if config.UI_VERBOSE_LOGGING: msg = f"[{self.__class__.__name__}] -> Try to stop main thread if alive" From 449bd8c52c5d0a99655fae892a40068c3baaec27 Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Tue, 13 Jan 2026 09:37:24 +0100 Subject: [PATCH 11/12] update shared_class --- shared_class | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared_class b/shared_class index 49b1b3e..22847e1 160000 --- a/shared_class +++ b/shared_class @@ -1 +1 @@ -Subproject commit 49b1b3e5bc6283bacb526d80dbe7c5b9aabcdd61 +Subproject commit 22847e14b07dd778d352e49c2877ebe7e4685292 From a8973cd6fcaf5bae952d1e2c24bff112e5026aa4 Mon Sep 17 00:00:00 2001 From: Vincent LAMBERT Date: Tue, 13 Jan 2026 14:37:02 +0100 Subject: [PATCH 12/12] feat: Add web page to server cam live to calibrate the camera focus --- serverCamLive.py | 77 +++++++- serverCamLiveTemplate/index.html | 330 +++++++++++++++++++++++++++++++ serverCamLiveTemplate/target.png | Bin 0 -> 128986 bytes 3 files changed, 402 insertions(+), 5 deletions(-) create mode 100644 serverCamLiveTemplate/index.html create mode 100644 serverCamLiveTemplate/target.png diff --git a/serverCamLive.py b/serverCamLive.py index 656cc3b..b7d7a1f 100644 --- a/serverCamLive.py +++ b/serverCamLive.py @@ -4,7 +4,7 @@ import signal import sys import numpy as np -from flask import Flask, Response, jsonify +from flask import Flask, Response, jsonify, render_template, request from flask_cors import CORS from config import config import detection @@ -25,7 +25,7 @@ def __init__(self, app=None, port=8080, use_detector=True, display_zones=False): :param use_detector: Enable YOLO TRT detection on frames. """ self.external_app = app is not None - self.app = app or Flask(__name__) + self.app = app or Flask(__name__, template_folder="./serverCamLiveTemplate") CORS(self.app) self.port = port @@ -57,7 +57,9 @@ def _register_routes(self): """Attach /video and /info routes to the Flask app.""" self.app.add_url_rule("/video", view_func=self.stream_frames) self.app.add_url_rule("/info", view_func=self.camera_info) - + self.app.add_url_rule("/focus", view_func=self.liveFocusPage) + self.app.add_url_rule("/update_rectangles", view_func=self.update_rectangles, methods=["POST"]) + def _unregister_routes(self): """Remove previously added routes from the Flask app.""" removed = [] @@ -77,7 +79,68 @@ def camera_info(self): "class": self.cam.whoami() }) return jsonify({"status": "camera not initialized"}) + + def liveFocusPage(self): + """Serve the index.html page for focus""" + return render_template("index.html") + + def update_rectangles(self): + """calculates the focus percentage using the Sobel method""" + + data = request.get_json() + if data: + rectangles = data.get("rectangles") + img_size = data.get("image_size") + + # Crop frames + + with self.thread_lock: + frame = self.video_frame.copy() if self.video_frame is not None else None + + if frame is not None: + scale_x = frame.shape[1] / img_size["width"] + scale_y = frame.shape[0] / img_size["height"] + scores = dict() + for i, rect in enumerate(rectangles): + x_real = int(rect["x"] * scale_x) + y_real = int(rect["y"] * scale_y) + w_real = int(rect["w"] * scale_x) + h_real = int(rect["h"] * scale_y) + # Limites + x_real = max(0, x_real) + y_real = max(0, y_real) + w_real = min(w_real, frame.shape[1] - x_real) + h_real = min(h_real, frame.shape[0] - y_real) + + crop = frame[y_real:y_real+h_real, x_real:x_real+w_real] + + # Conversion to gray frames + if len(crop.shape) == 3: + crop_gray = cv2.cvtColor(crop, cv2.COLOR_BGR2GRAY) + else: + crop_gray = crop + + # Sobel horizontal and vertical + sobelx = cv2.Sobel(crop_gray, cv2.CV_64F, 1, 0, ksize=3) + sobely = cv2.Sobel(crop_gray, cv2.CV_64F, 0, 1, ksize=3) + + # Gradient magnitude + gradient_magnitude = np.sqrt(sobelx**2 + sobely**2) + + # focus score + score = np.mean(gradient_magnitude) + scores[rect["color"]] = f"{score:.0f}" + + + #filename = f"/tmp/crop_{i}.jpg" + #cv2.imwrite(filename, crop) + return jsonify({"status": "ok", "scores": scores}) + + return jsonify({"status": "error"}), 400 + + + # ─────────── CAMERA ─────────── def init_camera(self): """Initialize camera with CameraAdapterManager.""" @@ -139,8 +202,12 @@ def encode_frame(self): # Optional detector if self.detector: - boxes = self.detector.detect(frame, True) - frame = detection.draw_boxes(frame, boxes) + try: + boxes = self.detector.detect(frame, True) + frame = detection.draw_boxes(frame, boxes) + except: + frame = frame + pass # Optional zone display if self.display_zones: diff --git a/serverCamLiveTemplate/index.html b/serverCamLiveTemplate/index.html new file mode 100644 index 0000000..ddcea69 --- /dev/null +++ b/serverCamLiveTemplate/index.html @@ -0,0 +1,330 @@ + + + + + + Camera focus with target + + + + +
+ + +
+ + +
+ +
+ + +
+
+ + + + + \ No newline at end of file diff --git a/serverCamLiveTemplate/target.png b/serverCamLiveTemplate/target.png new file mode 100644 index 0000000000000000000000000000000000000000..d9e9ae6ed111793a738ae7311cdaad226cf1e1a6 GIT binary patch literal 128986 zcmeFYRa;z56E=zj5AN;|T!I952=1;yf-}hA!68_H;0}YkTW|@kgIjP21Hs+ro9F$G z_WlF=WFM^STGMN->gu|yyQ}W5iPlh4z(glQhl7K|RQxQf1qX)+`R_tSgthnuFf75r z!6Vqq$Y|JGS;4`Pq*_^6m?S3W7*8_v_5IA&*CN*P2+}R}nsn65cwN z0G<-b`Y?Fq2*(RCD)-$Nb@(bYGbk!@l=MTP zj1`28G*i>l$nQbive@L|25)r8$gy?r-%sM>SSo%bC24Kr<^KFfI;w)*!eSfn#bU*a z3hv@nb=~7HYBJ0yG*+LrRAIJZf`bbVhl6{9H3h>==E)5QcWeO%C!7HXN9>x@p(zRn zhmfM7q9b>AcXxk(KQ=bj(b3V{+uPaM`RmuO{{H^%?(U_frK6)GSy@?OVPP>bF-b{D z2?+^$dU`J}uZM>RX=&-^=H|!8M<^5;5D*X;7$_nlGCVx|`uci%dm9oGA}1%;*Vp&< z_7)l%dUA3iE-v2F)AREDqM)GQ@9%$kc_}3&<>%+;>+AdU^mKJ~m7Se^c6MfBVj?du zzp=3~FfcGUIJmpJdvS5Gy1H6ZQ&Uh-U}R+E=H@m!I%;NShK`ON6chvx53jDSetv%L zCcNb#(;<1nlhWa&vPL5fQn$ zx&Qq6^W(=4n3Xs?p`oGp_;?~B zqWACLfB*iShli)Cs!B^!%gV~i+}zy5!((A#0RaI)Lqh`v1qB2G?eFiasHnuo#=5$? z5)u;T zI64|Xk)eH2`tydbvbM+iw&rvJV_Zz7)2-BGBGvQ}+^+71wq3>i_pYdUZd3JWJ8SO$ zM2-B1lOG)|uj#)4h-114k{*Ja=)+AvTM%`qu0&#-&vDv)wnF!xVAhuI_zv_>*lnOJ z53Z3UPy{|6ds4ab5Wm6y|@k zPUA|m=tsV03ivgt$!i%k61`pau7$O^L~4N;p9V$@6l z$GaciJ(Z7a8k;7@2@_?61vd+FoOOqb`mYI5^8db6C9K$hoq@ArA$=eH8DPF}U{+Rn?Rpvr^Tt<)=468|WS_NAp)*VX4X4mbQ~ zYNVDMx1y1|pJDQ0H_b^Yw zcYFb3GH{+V=Pe=4;U<((Eob7=)2#NI5 zDYcvsDxfKw;_ypQ2d?w4f|bqnyZ|^DWGNbawR{AoQGdDE3uCFICf2D-9>zm#aTx5XF0fs;JQ{4;(Q}>Y1OO z;S>1~79X<2-}0FWpCHicD>P>8onDci`_c6uj(P2StKH4N7RCCJ2OLS8y>o6&FytaE z5pH^|8O_3K897uHny8wV#IQMt+VlCTHCgG3qU0$YiNJ2(o8F!f!wlSZ?m$?fpTCo5F#fl|Es&~J&Va!6`uvZ zbikI$Wqb&=dw1LHZ>s8`<-w&c(u^Uf;x?9TdSiv1UYdK}QL>G5IeuBU&Var_25Z^n1Z6 zZLipB6iY3G&Q)ncv=smlw~NSo8H~bfi`%}5AqfL|PTnZ~;>R6(s=*q#nRRY)fjN;EnZL0jnJ*5km-N^^M?V8VSmVH?`wIo^HHmgcBJ^SDORY$%ZQwTfox>K*tD z&j00EF13soU1y4ObU+yjw*J*m!$qxT_FXSLPp(M3;ir(@<)R+jpMDXDZR39C9+3VFf;+P_=w&dUC@BER3c-R##M?}IEE?*}ee&ws&>aI`2hP$Jo z1998Uv^Mz9&R6?u$&Nk%Gr>o9Bhc^o4}C(8yL z8}2s9QwZAKEI>9@X6TU@yu@@xgiZw28t~s0EK&bma?jo=Bu0)u#s=dc^wlukDD%cl1dk{j1um zd=>q+TFh($aD&d&7!!8`aG$?g11YGVv zPy1emDVEpYnK?dW=J!hUjD%zO^#GWTZhmr_|7$qd zEI@HNX;+|U7Vxqb*JX=EDv-JB8)o|;&ZcexokYGm86?aP_~--{%g<>F^<8P+C{T)OQ2 zldW<>zYNx!>lkJD`wc!sLY|UQBSE*_m9cEWjoa0q{T~HtNYhMR(Zu+n|`DXUU}WG z)QI_yU-|}=0Z%teC||p-_k@_msGxk~2}Ey#b);B0;E1R}eE;XL^XoYpKL2cXUcYZm zQuxoa&#fvQhlm zJQ*jl!y`tns+aj+q3h>f zq1%ak)_4)u$%#>vjlj$Df_KC0@ZoLhNS0lT-uoX&S_a77(fszp$KA}S=X>>UPu7f$ z(hjn<`~O+em2#^_5#S72BF=z_mOzeRs8^#tz7SB|uY(#hM~j7LSU_{9B*6_pZb%#_ zTaq8-bm&piW3j#0bG$f1>e?k{O=5QW$?54lN^{SOYuuLaO-uB4=6+f0=Mj`mpkYji zD`rQ=5s3M;rRWe4&G?${bAb zmJ_)KWL{S#3z11r3HA%~p9eCZcjnh2l-bW+pEA!#1V}Qw^PQ>O$MBb{N&NUI1<%h) zvh%it3N%E_e__2e{@o5cN?-U!YJCrA{k=!25SXtGalL=B3IP+rl| z$<2Q|{hm4ckYRBBcxflr8@d>BYncNJ3O5N<;ljB7QCZ+8(V zg6nr$l>2}6wBgCi>{vt|M#@os7e|EhM>dV+#Uyso)HQi?!|`z%|2r0?M8o~8ZIBTO zwMftjG|- z(lVQW`x9I+fcxh7mXKa6a=GL|T&S9z@QV;L%jc=aZ_zZY)`m;T)Bnf&puQFfLu^;u zhjl(kILSbWx%IE98(qt|?6yR9v2wY0?anz?S&-wE^GIjxC|MK|8pP8 ziqPrDm&E>=`nR!*HhXXbOWN9Fzv@e`Jf4xn*VHJ*0$gI$+rxqvqqj3H*)c zXG`P`u-8$3od`x#L4Tyb{5!9P2?vatEqDbTDF5$Ss~z~h9F|?2kQYjA75$eJOyGsv zTFeiw6o19%jPdJzrx`}a&I&D*ez9Y1BsLC2ZK1B0dIcT~)-itX{28LcuC@m)YbGjf zXxq9tr-v!h$y(Tq12s=(L`RC=H4i621)K*AbKU3H`(C59VVyvyHLbAL$18W?(goJP zXTB<+J@$4AVv@Z;uIWb-1j_RbN}{qj#L>YHq*9nq`7AJrzDbD2{j#QXzsSD)hFosH zrvDN9yHfXQoDsP%!};S((~!DGa?c2$Zd zk1kqPQVXLxibkq;9c=%Ti9$Z0a8D&*x1b!`$K1+GEQ&%ga!2w||NLW};!%=`PV*_p z__6$nv|J9nTQoA2?K4=PS`>eqc?k8j>9ZLzpWlm?mO}EV`Ed+OP+pZ`N!xnkS zC7y#IkQ7`ex-jwQuxU&Ll$ED9W|MWRX6^$_S=AWawfu3$a}gM%g+xIURThuIL{t}2+n`GW}(A@oS9$!SQ@f1x=I)T1(wy`amtG39i9V%;V*LP{1)W{$WcL<~MBu%7t>l4=@nzX$wQ^ zqK#&J{{4}&jGVkvv}r||ISf{VI9uvFFG~tua&ut=A5bp!*E@%?18s5J4ycVDPdZTv zIUKndzpg=H`7|RVLJo#s&r+}INs`cHTh{9oFEYM|R9S1&1X=gPuiUEHNWy^Zt!*gB zbcd^)xp>Id)$Cs?RN6RS8JK00lK!Gl`{u$gZw**@J7mO|y43-wAmO3i6QDg0C3kQY zaVJVNp~!EEC0-7dt#0TN%L{IuPnW`zR@S#nJ21A7J)WceJL5vPrSP z8Iv-+2%6@&v1#XbK&N>01m%7zlWp)motf*1AymYkO#-y#HvhWVx2@!tsKyGj!{=W) zS{NKu?myzl6|ChKiCBz|JlC7>gJl$5%@#d ziwbi8?tg&B$(Vl*=F(c0HG7pFzQM35$=00wsRO365K-s z_EZ}Aq=M5(59cjy1#9o_mB_CoCBCx~3JY%3ZFz!6ct;TfK1{P7t)T8LN_sy4skZN* zsW@YXyp^BW6MKKj@f4)t$qxg32U?T>TTn-VCbNfP!Nhw)#@c z*Ig!HRkX$(I*S5@Uwbb8bfD?4t{bXQnZO=0ju05GpJ}I21qkjS+1tEH5c7ZPAWvGYwrb;laantMgPDOISPWth!B3C)O1C2=k6J)J6Ol{ZM2bc`P)? z`F_fuEqNLxwfcn`w=*(rRNK=6h7ufJV%eBv-R8Tq#^kq%Jtf|`@k1ZHX?k#7ffAU7 zzsnRUw`+&FATbPUI@cEIuz6EubV!i*pX1 z4?KR*ntUhkDbpg&pQ$XnqHC3nS*1K0VJ-meFf~oLW6rR^G;OVrvtWPuO}05k5YbEs zI&|i=Y=x#ETb6}J zZc*K@_HPceAZYGT0<*K6&zGRO_ZseUt#Z#~iHo`wsh7tl;BM##sl#3|4)mZSDo9H9 zGAlUK+wn~KjqLlcv3&oKs41Bx{OsO$hY8)HaE(ZZ`{ z5vLY;lngTOWBYDvhgHMQ5aWxNB!Xl_6kk|KuZ1c&5R017b0_FJ5Be>1jKp&JY)k5+ z1pdM{4*$AfiWE?sjwpPhF%T6kl)LHxepER)3zraQtlNaF1=JBS3(~@bXksydRVVuF zmI6+z$;_!xrj6_JN@BJWQYU?7BCs?j;k(njV?orD3!o+eaR-)n_>P6SD8j!y@IV+S zp<{<(dxFN*%6V6p#TMCqPgH zA+p!PoEdpAVLQm5njzGcyO8K?fP?uBi&BsSAROGf#s>+K>3<7ug{L}lF$>im7s za4i?k^?-Yl?jm`txes6@yLmO{1%IjXc_DCRRg0HzBmSFJt=@KM2Yg^X|0B@w(t-in zIt|t;5{aZK`Td?LVL$ZDlrtg!e&Tb%EPmZpYo39uX7lsbate$u+DbakNcnab6uY9! zUh!R=ayVP6hE$RQr2V;k;`A5rELY;J6Q2{(07+yp=a=^WcAqm`nNe`F#{B zq1!dCK=#!M@_*Uf+jr1NlQ>Cn6c~w3%zyA#sZ9wwgVPQW+DpUyh%UwaiB}^4@<}f_ z@#zmwU`+a1SfEaX;yLqvhtG|w(j?~l18Q-9!VB53~x4%%hv zMZdw7t(iSyiC+V@QJ!0dt0F-PRjT;~KFIC0b}tPi@HwD;y1VnFRF)X7+Y{Syxb8ERA_lkW)d9B(6s$2Yd_i(_acKCO`L)Yd=tWpO^JL{uS~R?K$tr z#K#SNj|^S1Txg?Xi77&Y(6-+^a&N+`<#}L4Mfd9$=(kzW`3zpD8qV@x*E4rkr8Ez@ zHV_u1o}PIRy#&z|t(@O5c(L`FNuj626dS1LUQA|M4c@Rh$iM;k)#3r`_IQdvKr~)A z81zEDg7GeP3jg?;B!9+-3f6SNX!g1xUiJnyrwuRszD%ny2d2WR_y{G0>G$t!jgMpT zI>5-cIgg0S-SjOLM$iI(P%@gm2+g}(W7K~!#~}wzNuulmaFocp7+s&G4goyjt5{Xe z_`ks74H&Pc_lx|H=eCRJuke_?q{8~~CBH~Q)t1&CK@wm8R(I?T3H+K<;@CZOpPu%Z zL9cfSQ$ydg9(mpk)t5cCAC{mj{~%?1=Z+hbkV^I%TIEEec4ki} zB3yJhacky~f>T;Iq89GeXx%HvRhC_7x1={mQ&wncI*<(}S-CQ|b;*~N)vUij@ z>bT?ZxkeJHCmGrC2ABk$-|7-xM3P|k&SyBd?PspTsI!!~RnsHGG!Y#MvucY3Tl4$b zgeBx!t{w@wmTW&R3rjh#XVIjafYD3~5OTBU6RKJ}e{JwCv@DWscx6W)BfY}Al^u%Q zGgK2oXC{a-Y{_(tAuq=4Q}*C{W;FfPh$R8svsL2KJQAnZQb}gh*Y*C|a!K3PPVTz2 z2Yklc9s!CX7x|{5XOJ-wS?N2<)||@1ANg(4sXyk@$pcF2-fgU)dtI6J&vebQI-b`| z6Z1iy^ItY374F{htf5s{kt+kZzrS7d|f2V zt)MMRUehIY4xgOzxIS>#@$^gL-xyjL7J2zj#|u-u;006iUc@eW6e*ILLj+Nx%Gce- zM09W~KMpB;Owxx9KweQM?6eT#=8(RS(2;+ZNz{OM6XUO=MpmIMc^g=0_dCEKR|;9% zs+_kQIF$u~(#R2LV?G5k1rdXBS&}v#PZCC+OGp<$$w7xG*n zz45bj3}FX%T~O1w>M^0~Ra2Fp1i9!ljqHNB%Xd#JF>t$4&=(@9AbbfSm`u9a)~pB@ zk>pj^#Y)9TP*Jo?`FzRU&0J3Nj9s|!-bC~DLc-(sb!RY#tR#|fpM{OT#*@^LUYGe; z#Fl2__|^bk!Yq=3>vZ5?8H@r*r+7){Jqq^)>B*=4_5$=>)}2CiX-^` z<7$vp9VaTTwWa0lik|2Dd-30oRRh-e6Nnq9+^L87T{@T@##$0bRU6(R{2JJdkV%%$ z(-q<#PPlX)A$VQt`+;ZuWBCVc9?12h1j;03E^gErjMXTO`R5fd>4<2;8U1Ao#kagD z2A)k%89t(ZdLNGW4nofQ?#Fd)0^0;rak%}{t~C8U&!qVmHy!3*F+BZ2)S2!))1HUK zgy%#rSEV@=p3)TOBJjdeMKd0M9HY!r)xvs$M&B@nONoZ<4v91`L{=UhJo0B2A;fmacV-;WnVC|l&cu{FhyNjoh%_Mqib67s85D^6{xAdwTD%6GZF*Zb)Ep;*&9 zbi?MN6q`MmRKj6e%|R&j4*%0!fG7Wq`DIb~kCDouzuqE?8kVq>`jWIjaj6IpOW)Hh zaD#eb4NHKH+EZ82uU8bz;a;-_lu#$KA#NVAggdaLsE_-AeUmOGLVaV8O%E@OtLQmv z?4c~t26iw$J)N$Pg-sH!K^*@>K^exL;K7sek5NWKe;F9r;ESua;Z>#uQQ5-8U8?d} zcm6!0uoCS%SGao3AW{~2EReklMR=3T-{jk9H~_u$rklTK)OgSe29=&t{2OU|GRm<8 zt|LwZ>hLZJV}y*8o||FZ4Mqd1u)CL#p$vsmwLAGV2f^o7kJQ>q)vx}k@RbnG%V$An zAykT+)qw+9FKwq$$JE0RwNV6q$iIC>W^RsM6ww)Nha2sm<3NQ4N&NYHMU3p=mxDG7 z^)R;U!yeAub#`RRn%R5b)jBCbGuNEp>(50ZjL+c+V;gro@wXZ1K;*o8PU*^!P^hN-9FvWHzlcV`hKnl&#`Hg*BWVptA7{{9r$Sh z03+)lM$@pK1f|BXyQeHS?hR{KG(;3VZJY86oPScC0|Yh^%JEiP<~qjjwu0Sl$ntco zZMnzF&ulXq7JT=&bOy`aJvxYEOFC5ZgYYX3T+&pO!KNCaAj@j>8*v7-4xiNm<5iwE z&(peO7$YtIfdS8@SZl$vsZvH7N)sJ(rBq(`+x`?rn5`;ss@)jwJ|?N4E^%~>+{I_V_$#|G#NG5MKm+6Dke>3w0x zT@P$`3ec#mI@#?l9Jv)1C08;`ZM?2CiHir?fhx>^-Muj^^^ zSK5QQ844o;rQ59=Rhy#PaNh4o-7 znH2SQPPs`|%!*wgABMQlxYMDS4hc1@Vw`BKw(D`Va6M!zfzMq#Fod%Z=kPRMSntMk z#Bnr%u9oLqfwhiJV;SXA=Z2Q;px=nAe$H>v8F=^!&uA{rg)loA+);z8%42tX(m#!3 z9sRcWz1$XU!d5w9@goSq6H~f#&%gKv!JdUpip#sgz2+YBR_PBI^FRW516i&bjUnQ? zX~yd=*)=YD@&CRw6mpY}iufjrs+PZ4Z%Mh`pyg_2-d=<$zfe{t z0wT}eXgu*j$)Qp@Z&jz@hbXYN{u}a~gidf?j)X*NwllTcSV%{vy?BU|auOkp1zHZk zHVei}5&GNq?9rZI{alSe_T>&UPRPacuqZg%Gu}^V+DnPKYWYfBD`dLor|nNhCq&H#mTU{RYRnU%x~vH4h>iu~b--xF zbO!Dg9y$(0ka;X1k(_+(RG4fdLbbVrI=vgT5(}O5Od0N+GGn>|)@OhsSizJ&MhBYr zzTQ#_^iJwtqAQf+9F6|{ry3zWG-b{;gl5BjpY3kiG|wD5LJ~b$pj17M(qlroMEB|Y zi7?a^5x}ZN-po!!)B7m~QKIkLJ%C?!#l3jb${6p0B4>?^YvxYtbQ_q$MeX%Bw0OxV zu@b#p@#o<;5KJe1&6CcHI=R7GA%U1F8SjBS4f(Zp#yd@$9dec6-*?@$!5*q^n;Bce z1FC%hjrHuHkd}P*aahdA(olaPBh+skgo-61BvzyL=Ee!wqtmsOq>T(UNkFqE{X}_>E7H{^xf03sJ971ezb>Tr5O;C$0BUbOS06n}5tP!xJ|W z)Co`a+`5y-@;NZ7<0`8qw8C-DQR-pHaTFAP`WC((gdnY{F+6;)bSoKYhI&{mOqU); zuW3`*dzCzsEFKLoWrx?Vo!vl+2~Y7U+;`=N41^}Cu!Z`I)Au4WEm%!j@q)z+3PR(z z#{3dO$`Ep)_XU0>vuLD0FF4BKa>9Pf!KUcX6Ks$N;x`k8qfc8+^na#lyL0?NBId}Y z6_vkly`%~=!*sz-lh8Y*OAQcm6Lr;=Wt99&1ReAy!89OOWTJ6JpRFaqe{DZrO+0P`1J;FG~1( z&KQrzDT9$wl_gfl1=s4!W@NptVbGt%-rxwTRzfl(BtLBAIc{B7!Z_KQvcA@m(oWMS zlUd~5^d+4Uq>>}7X*kVBHFzi2DR1q24xY~U6Ml|yJzQhr*narZQ`jr|3rRS`GOT9q zwBE5(w`vYePl()Czq>%jXN_VChR~HTMXoUymcJy&1DelKu#kY3Ws|q* zDoXcb|6b!O^DR*}r2Ku(eDvsZB~FZZS{4)mh|L;MUbu#lX*cn&>f^cZWA5Z;V{Vry zm^k#$LYst^lj&@kDdC|;M_*DHXDj1VMb$*iR(FAs4#u<~nxBlH`iO@*8)|-JfFTUI z9|Sc)9RCbRI4T+UFO#&2p1%W0yAIj`ZOLOwI7qZ5Cz^y1yBvB`&qM8f)yB?kI=T&{ zS05&cyl%z>liv^m{gxdAVPsm^OC~AeN?yG-vgw8nBnN2uLqk*suFkON%D4HYW4$ka`pff@Ycob|ef^Xyr6t9LB;3@Y# zfOp*kuY?=><7Cn+q9@X_sUYkR3Tq@((5 z4{dn!8?ijlPztZ;J%oV2MXExZGM&@swBXG8dql0R%Orbz*tAU=9XWdik<(c4=!!{n zY*+8Eze4WmdV~;L_jP??Tk!?0E-+i>J*o->&loUH$d)fne!iyZ6!bSR{yA@4h}lju zyo0mJRCis(q*jg&2lc$D7&hh53Ls-#r}TsBJy)ZlW(?2? zMO{T^=Qha(3&KYWoH{99?t4Vhzg1lSlA?nZLe^bbS=?q~CG$R>c?@-ua3Qxw4|;je zX!v%KK&%tm$927tB`W`|L~m&V&-uhPV8J*sCRe$o$$baRJ(Czj7CgYdIJUD2CdeJ5 zqH8yvYK5dFW@6#oWkx%Dc_p?Xo~OB<%B6(>!0R8 zOj}h)w>NI41o>p-77de>Ps5KRb$te8ic8IMdF7$Ki zN7o+HbM7G_Dg-kp+gCX-}O;DVZSZBCsz`*)Xed6p|(B< zi6`pxg5{-@*N-aCcoUM(g)q~G>a;n&sM!#8e05K*4{$R`mPHcgB+HkoTj1& z{MJ1luXu6K*Rr`K>^&0fdFRRB;piY+13W%XIr`^O}7*j@ zPRv%$vJGsvn zte%>b0DZE&qU$XR_L{rnh7c|AV_y*~4*WF3P?CRQ;cqGX4t)@?Sh1mF5^qSX>Yp== ztJmN4>Q@Vz@}Lu47+3Ef&+_tD;Dh+fg(?cRsY-YvlYV>LprC4(xQOb?1LGKr5#UYrdtU+wH82g-!xq2M=JWZ}q5e?rLJsr$4l zMp15zm@8ClB`9FpvDlW=g0OV~e#5IRSnM-<7+wsu4WT$T8>}Q4S!`5vQixjT*1XG1>_;5WO;|~mMM~)@J`3;t7BxLz?uy@Gx^U$`}FBq430zP z{)73i_Qn|yenQCRZ+CF}#upc)(gldq>WT%U7Q8THTN7;e?c?Nlm{Rz;>Jf05__rrb z8J3>w%K{NgTI0Ap_Sl2ii5vhxJ-^H_;As1v%g1egSbH7tfk#iAxdg(%bnd8o zJD7uwJ58YW9xATu`~=YRNzKfb5#3d3jb~&Dq6yzbLAyJ~9IT5Jvl$jm7vg?TX z@Go?K>>TIFb|jCUU&hv$8Mkm{ji63M{4W~=Exl@E9p|w;HJ5d@rWdk@8c|ScOQoG={czc^1xAG76oI*Ks1aGNc9+B zHTfY6CrrU0&IbADZftx}t`JxS>(!cDpTvg~aml5IF*$*A(rb76tN?ucsqm!qaIsZiYW=evEuD;iDF>h?jw>NQcvH4T zut29yV1g=*m>JbV=zh=rbd`Jh0;T)uF`O|Yi!Oc+G|23#9Y3x`w%XQ$5F&pmCJq^O zj$d08JvV{A49Y$HW_P2$3R{Jp2D3sa+KksuR1T|3J&i`6<=hC4(_ZaIZx!Eks|TLO zj=P@Cob!D_IYqypmVBZ#y)Msfr`wBG^s7R8YKG_x`(XCBj_Oo5_JRlq3cfG@X&N+5BDI zUw3@3bZ}i=a!OnzSZX$HfHXkg=@`4?P#!Ladj0hH6^+p&o9M zienLiT9@JoB;g9^4r819H*pBLF5X_FM&T?TJKULMPX=HMpOV`ooP~+&&#LW88(X=I z@PgN0s|_DP0A}RWP?rM0&aED-TR5qR0AM7__$w7BF$*4L zjJb;5f-s`1ddiYVjPUM%~>vD!Mg@=X9?iU#TV)+9o&5D4Stb zSvU|m%Ttw+Zw$@tQ15fxA3ua+KQRmWg4$9Qh*J;m8$Y&sUckNoy0h?<)mtrl`411A zi3*pFmIzk>ms?24>*DO?>Q(gvTIiEO_vyf~8VrHpjp)gB!mA8_Quccwi{wP8zit+i zv;hH&4KI{THZLn^%f2F68J%xT6~^Q0+u{XviF$pZ4k z438u?hzd{z7-@y|1QL#a1=pGVmVEeBuS+Z0@ALl7-xK~XwDqQP+`*)#rt4lfANiFF ze|})tL#=`qyc27DrRuHrL+*_4nyLIm>@$m=6%`?ZNgAnlq9SZ#DoZhfv z{__{atgP*!We(#XHQinLwNlWDaL|rm-^pqL5O4K%>>L}UXpvmEMbn9ftpUb&1Alzz&`2>$BEQA}F&-WB2FL_w$ zr<1ED3nrb==@>RQcs3}IbDb?VPiX=@2LY1B1aXC`@sy)l_SBPt)xg`|rP@ANt9Un@ z-bNOu2=i{GvjD$1{Fo{YK@Sv{mtA9%q)y=AhwM|76@H%6MC@+X&c*$}8T)AKE=+W8 zlkW|iQgq?>EX_^LHLKiNwrlai+Fw@INvrv;_A=#82?H}4lVZ9N*rdg9g>m=2qB&}j&NZ67{4V_?NBj}BV@+G~ z$G8eI^ZZ;kov=SwE#Ym=Mt~9vuQ0WL5k+UO-K`gg#Ka)`Et_Mx5!F;ZcArziPFRBC zTt8lt3v{Ncquc-M{pZ2?RCuirm_aWGVf#C7B8>=U%O#J!DtwPhSQj?w;O%-Q;tutE zF&K!)FUiAB$Ngzrd<5; z!d*&NlFURdPY5Q_hkA<)^>u^e*VK`dg%+-yY@fULG|X8bcN}Aj``d?RnAvAv)zjc} zsl|~PUr-TTRXbGBJ5W>&kcH)~ev>(qf>$k$q;rBWRepFxtWN8+e6_VvRxAhAz zKHj{>$4~$b>=fPW2&bM8$X*H95QQ7!T}Xg0TySF)-9fm9pD;O%PHkdjpJraI)@V!o zx=0P-NatVwamId76zqW?No2cOqv;6rqcjQ&G80yP|0`afNco|+%`WcE8+n63{_e(} zk~!IO(Ks%nPCum`y$I{1ZzuU@Nel-umLsaEQy9A`EKp?&Xpk$Rawow2E6`-EiF3l0 zSbYPy+}C<~dfUlnq_Q8bbT0zU(G76R*bmbrX;PViG?v1N?6dquRSSJl731CZh#UzYsq-SHTK#LOHEBn&T-^ z<+{CZ{$Z8_mqV~Wrz;_%F6&r2WzbDYo9NC?_Y%}LGx=?$1#|MUuc#|4)9zI8g1eQQ zK-bCST#Y_CK=YUHKzY5(kFVj1ioMgv(!AhV+{wfc&Og{sJEACQxP9(YD9`gIC>ec) zGoym#M z9FvInn#pI1pnl!HVo*9on{BHQ{qnL@?Y4<(hsOqep`Do+cy>-d)W4A%yqFi)A`g9r zad_s|5{m4hg@3FGJOeZ;WI7-uR3=q(aF&ax#JC$y%Dj}1#N{bY{)K-A_djko{Kw1a z3MVjNE30~sB#CWJe&>IRV()^hrA72MVeHhV`5t{#N^uj7#zE!pveXK<1DyT=`Qu4N zZK<1a&GxIrs=_r9Rx)!Z5Gb>ZNh~(>x|%T5z5l5QR;sK;(4Si4*cI8ZV)45{SKsLy zoD1i1q1DCew&`q-YpKZNa_1;Vd*$_))ov{?&v1kXBRpN9cA85;5_{t>b+krBq6x5w zV+Xx(;TQ0;t^Ts8Z7G8<<#2Y0Z<05GBRa3Ed@O}V>pLKEsaU4{m>r0uTb|!_El`fg z^-$dbPN$=TNDT){MQC6jb9&R;K@B@wthb1Nf~=<62E5{~w-P$qPf>rmS}ZXbab3&h zu+1P~k-WFD@BBuD18j;t@c35i7S9<%05o7>YmvP;H*4Js6O`foNr1wKE*z*m>7%Wc z#*oX$(ag~)IkT0R%jM{8`5$e4I%grLj7}dtbCNlyD$nj;|4+OMy1~)$Yreva`BIE^ zGxysMXsmw$4(1aTVL_HlmdyX^};;F@^aY_nEg$h#A}+`i4l^Ai87%o z_lEjl;!%g7CQm}^-b87g1BWcb>1s+QK$83KXP zT=lw3NsF2p{|7HY(7yhX<0d1l0oPq^HBkS2ahna*IaU07xVGcnMGIP^|E)k5lX8St zR*pcHX;2h*!?MJakmlL-G`hzsHoK^p4|?GfPjx>3??s9!A;BZF*;)kX9vn$!ppT2C zn2zo-Dmy3;GNfVCT{zaJp22~U8PmOh3ir5>1>IwZNf#S2o?$CZ_fupo8GvpzFY;8o z=l&SPyoCtonBLWASzQsC`y3BaptCmK=8x`;r6LXbo)Xb{ECZcmU*`WM>1`=$CL5;F z^|_nB_%3W!*Ev_|RW16Jfz9cmp?Q-cuEvCmD>UC-zJX-@GHTmLFY5Mo*{C4j4Sm1eUuDi~uZDGjTx4mPv z$k?Sp|J#6Wk*l3A``}tnN{N5e1#9YpE;`ymk&#_`6XLJ!-07$-1NQ{Q6Jm3#tRwPE z-6b`LukkXV^HHI9`dB{C7}+T34_71)J}UdD6fgIr3jHP|1)Yv6NkMm+b0w0rr9V9< z=*g=9azS6y)Bxz~riul|aQ{5rzI<-*+bU{mjs7Nh{@$P~JBB$fvL%wr%09T>N7Bp$wj>5lsehvGcYTTp$_x3}|~m+~?R0jwD< z+u7KYqCwwtVj9z?-GZTC7umQ$qmdq>3`>SPw+JRodU>7vy#k;hpg z%cWa#izJ{sYehk~#I^ZPGS4y@=o5iu<}Tj(64M=jQi1Gb-tCZteild0cvG)aA#FUeK&$c4kp58ytJ_DCe{C4^aN!Ot7IT`&Bj1-yTazUqN z(|k`o!LD@<_CYhTa{R05u(q6z)e|WSIt)oE)LO?LY+*_AxEmn@I%5~re0$@E`nBO2 z0DY6^Wr%>Iv#*B>KV?)ul$iT7%7QM+tyP4TE*bjRPdR0&S9{^&nG|%G5#CJo$%}MH zX8&B)zBZi14GU$7y*(fr^gSl#NpP1aw3ZJ#*ARvJQL6yXM;1nE6<}D(Fd0^c_fWGX z?VuZ%$vfh2M6!p3ug-uDp50DS)^vV_W&L1epdSUDnE^ps(QSt(b&B7CvhJ^376>C< zX5zq5R8WE5wFdGv`X(Z~SL!+2GyCVV_Vu7N!~9EoqXvDC$=h&(u(oqS_bY&srn<3g zBH_{-7AmR}$XOF?Tkbd`de`}g%FX^Ea*gh;%ML0S-_`~IWahH}t@-|gtM z{r&TLpgRmo-xDOy=CemcgT6<^B4{C;D{>Z_q#o$SVzFy>o&9tW?jJjIDh2S4_M#`> zsuPPsZAOdqEZRqL+m({NW<)mMe5v9%n~gVlFJHZ%~m3UCI>109_vKhfVZdqkf1h_qfQ*F1}?Y}zM; z&PjtVuDwZ84rxIp+t+2FgT&iyh)mCwoeb$Fc)> zta7v<#A==9sLvfMeN2j8fYU_OT5HE z-->W%{y*4mY>p18w9^97b+{?>es?lS6;8|@D`TZ6togU{4m zkn$P`J*8X(D#Hy#ViHqC#{;+-OTYovL?xPaTj~*g-|a#cf+K4lsIlisgKqliViS{T zeu`U?wdm)rEDyawvu#Sr49THlyB^jc|BW(j#~*9fGD%gpu+^dRD<=6at0vk}^6a|v zFXq>utXv}o8%h?ig&6-usiidNf4cCSyjBbK2KL*%63(+*)Y!7RW;^xw(_g?!(20pw zeJu&^_6Hm&ZI!L@@`+{3KnX$s?I+6Y%GaFaf}aoi^z4x%U7z$^(D~nbrFX&jIUl62 zMG;xm#_Vh!`YWSKDPeo?k!!1@4S;zJezE*xGHpju@g?RdLFcdh0wP5-4@i^l=&Yrs z$%EbBWSINCzw&S4;fKLGRMepFr=TPBaOm8@72u*@43zP8Pn|%-#tmwkUDxa@c{>ed z3TUqFpOh#SzXMkoTyM%;OA$R-3P$O3@mT4bj7!axebE1zeUx!fO){GUIv*bX1F6+< zX2XKa10wv5V>2(4$@1Z3v-$^P^o@L;?6zN8y?eUtiU?irNA4>%`s;*i?0n6;qg~7m zoLWX+)%W8AE_^(W_@HwIaPOim&3{pFiw6Bq7i0Tl;XW<{ZgZYu)&m_GK7w6!=jl$_ z>!|`=IBOf5JxLZ8F%t%7+HfKdjCm+KW#C#2CRo{lp=nw&^wJ0Y&g^AJd)08d9MHLK z@;KPZL57czo3l@d-*zN(l1_^j(rrqR_3tv+*%f*yEjt-ZHV@eCA{}v?w6m?1Jg|szeb&uR8TgaGMT*&? zh!2ROg+X@?K_8g)mc>DRxdc3E(5Xp|uesXANFOSB%AZ*3g_u);yQ^-!@iw)L9tuYl zdvJVFG=A}d@mo%tJEiqUD@$Yf*AnsPB7eIdeh#3V0=Q6Vv+Wmrm*^k>f)70Rvx`Of zsXg5CN)lFFQ?fIle<6wQwxdjvD$x1EuFZJbIbO!IhvGv^nQb`!*E4X|bf>hh z9NN;y8)cyTKcAixfZ~96u!*{qpjYG1!(h1_&_U$bm}npz6NIj0pISs7n)s)R2K~j{x0)2jtjr>Ic{sZO^ta_kwONi$}B388-%`E zQCDl={O%wymLKa`*&gP0ePY0s_&Sma_SUHAcDQ#S3?u@$=k z)BUH6>29B${YF@l{guIlV6sztYoQ$r=n2Uhhf@X{##^%0ZH#E~AF6g1u8nXkiGShj zcWWU2Jh&F`0oz)nj#J+|pNNJj?wP(>6Ak*GAi)gVPv7=s;K7yt@Z4;J^J1CZRafD* zq}8&GdAXg&1@Axdq6Pjn%vYJz6;>2}8HTW#(M|?>dRjIt+-8+mGtX)Wca(JI7W;+l zgIsUdHQieX%4mIH*JQ1o)iO`FV`-EEq6RuL7i1IG`1RyY?~*QHTFCq^FF}O2W^_L2 z_2SQ?(FWSC+(3{Fbn|9+qGj&s02dAVpCHwahLLd&IAMC>L~j%ONN>L%23skv!l#Uw z(5`KDw1W$a*2$xp{fir?%g*;Z&grU;2e~Fr$Lg!4eSR2I*u^(K_4s2H^sb)Jo&pA^k!{Q#s@G~TDH6^)~>Se zRww>EYNz(oO(b`P7E2Z52-?HzM;i1$L8=|iB1ZxPDd@tF(sjNXTh*mXZCs?Hc4EuS zyiU``XN2(62IZ3=((;AhQ8RG3wtbmZ%vu#i^H7a@zK8udG9;g#SSDJ-ax^+y?U#r_GSC}~ zKd(utG(#*1P#Ngh+PJ8*H8)%QpCB6aKSlgbK*ui2``9*f)=wwFhPv`Pyz3T=g_gYi zbiY2Da9or041aalLMH=r+_Yz!(2L+aoVmaM>}#_wrp)%f6XEpnPR@JdBmUeqc3s}f zcVr%9oLAR$NBE4)F>Fe9N1>0TE!-E1iQI4EoF+87Q%>xA(zZ7E=|fz|E-u!drShLl z8nEbYjmMw!k&sQhSLETrQqT!5KFInSL8A9P2D=9RPZ9BnEHuKg^M$b=M9xT>dmYiU zhQFS75#fvj3$QG0u~^BqEILROc}aopYZjO-2YqbTX$Cx)FZ|=NCgr zCH)*$53jC9NBH|J=*MO~(0;MAk!#+Oex{fN=oAf>wwGgHsQT{ngsYkYbSR&b4Ka>= zrH13rS($Bny4A`_K!S^#VVFVpXhCHS`tC_=Imj9ebrTMF@OYOfPL^}IYJ7T~{d9h( z$1UmkxLD*k&I~}$EDDP1tSO&w@n;J3mxyD9S=)7$H6 zbWESg3^9aTl34WhU1Cfl@%JWZ(js}niGK37re@)AJKUhif_@f8naUf{-5QTS zci_LP43e9d0MoBvyR}C%y=%~SPhzl)XHH$v`5`~|$uHei-A^}i_tRaWi0&dXPdCg} z9WkHS0<2nfB+0J3WkYOc8~#}wnJqQ|4xG*>vI)>BMFUc%JHN|E=~to%>d(>XYgy25 zNE@&O&1Pv|d}iN_tR(3C3F(Q7=(Ah8q&ebD>uwQ5V2aG6N-6Cm&YOyppbNT&a5b28a)D*3nh5;-Z?4oRc&=i<^g6zcDhQ}ikv zL(m@FV$-1Sj>Jd$8yf?iAM)l7jH#6yhg@ery&CLZZlxyiJ-1?$)#`lJx)h)!1)Wop z)l?Rm2jFBthh8WNI+qV^NKXl%E1A`TciGwXP4})(GFC*XHND?WuTCGs4VB;1E~zG= z`tC~?Z3XhvGRT~S-H|!4f$g=IGVit)CtX$fk6&lr-)0kVI<*tQL!ELKItP9$NEAA?1RmxlZRi?6*(Mk9L9W&=8Y$gYCloo*KNR7P88 zK<{eHZ0S9dO7MX3Em(SXo|K5-q1>oJUz4yc%XHdi?9rwc*)?Zenf)!|L{ zxf_Z<7miaNbC%?p|B2@j|9{ar4k>En?Y?NxcT0kgLh&H`bxwJSH4HlYQdsA?*R8jo zF2r?CB`VNq%g1t!4)7u}%)~t1@7Ftnkt%*{86GHRKwqBCzBr1ag+H>=NyKmOL{|0j+Ty$B}{#FuN${yz%&RR$}dC_yaWzx>#}l zp1~m)?V;Ut4f<|Lur-B_h7sm}uIi3Pcj54(QI1Bhee62>>D+qnr2-w}#Zn(^5f?oi zp)BZ=9?NLN5_D|LfR5kGT(hH?1f810GJDz?(3{Gc_ZgikOHAlTnKrFJYgmUmyqNj6 zBU?RpCQzwHC)fM6Z=|4ix}&L_^Ty-P`H=6Ge?bj{&L?YK=kUqc)Rz1y-L8uUeYYg| zD9s;lnT1g67-(3ddwhcZ*gfif({K)5XFr`A=N*$2m6}M=nkWUG%iT$Z9^8u_m(_^2 z^Gq6a6P=XxCoiVv=;-MLE8c_w#d5+Ly(IvHFUbel-AB{`Q5eqJs7 zQkmRzU%wcstfYqH&%ySl%%LO)^mO>|oUeUb>m0O)+-5ZByDb>s3BOnfHJRUa0+bu8 z)FC>o_addS&X?^9{O;E2 z+dVM@x^MlEJ3Ynjx9h<(sCs?bH)$aLTsZ79`=kQO2R&vpn8vIx8B|yBx2!^Yq-?qd zeYa)w)=IO1uz{NRSiDJ|vrH;&0Hd0bnGbq?{d9q1#XH?1L@~F!)-I=mHvC@7?m=15 z(YsKI7m)}+e=2oJj{WZ$UHC%s{uZJ2tEpa}q7C30lv+(UXJ?Bmo^Dbr4iG`K>pUhQ zm(90ipksWYz*O!oTRIyRaZV2R`tj$?b3AVoK~|%nQ}o>;hgE_cd|*GYC;F%c{ZEj) zomVjmoUOPf>;1Lepg7QB!$Uhz9_aPzr~4Y+Yr6|8K*z=Zf(&%q{aOY(`oBa64nTi1 zm6sJ;##0&7y+29LEitO2(fPrTC$%uY^SHz!8~^VHNpXooEt~?#oV0~y2Uunwf@Gkh zE^a25BOw(!>VlEHzlkd87mq*>I=^)qOYPaWCBdX7`o&54-!t#MblPSU zljB^jN0ZOPXVO1Pe9T25>$997i(g8%@VWQY;Yr{A`13Xrf9^q>1HZ3ErX&@0;xWYg z2T3hn-BNPGti7VWzi38#ApNrjeYb>~&2M&IfRcrS@9E^zZ{{@uIw!rfQ=Py+@O$Gw z41b-eufgxrx!sU2Aek)>yWnMuDB7jAKBPH&{8^rxzCNr>y)!nuQeiE8;CM2j(Ro83 zl@B_9vCESX^Da&kU?xpuiBmsqhO z=U$0wi|_Kh;X)?NR8I=Ict>?ftB{BZ_352rp(oilxkh#tpsYs6<2=Y*yEFN0q9WUX zR1!vTZ%8GaB>n4x-Zwd@cyPHDwS#{x>!&o70JmiTBB$Evp^WQuwpnT@(L=8Sd9V=w zRQFg2Q6=aN#Gf+{PHK*#0^?50feIhaPj2r8WB<6KqCf10XwY|2ss#f^dJj;P z+;=rm3wn7ylo|rvE!e-6$dVa;Uf=gL60P+^!SA{Ly;qcX4-rWQ2l z`vmBO*Vfi1VV3?_E z1Qx;3T!W?T&0t$D>zYSMPsS>dD{SCY@=2IDu6Ep^=_xMUh!g$*gbqnRV|+2r@8}gT zF#&K(|4X;;jEqAHEX+(%3JbGS6XwFH(upn}CQTjXim_pdNu_WKX(0YwtkQk4Ffh(? zI}Y*V{|OqqE$f~vD#U~R6hZ3p*t;eg^j(nZ2jJTBarP}mDC?QVKjZQ34df*d!c}_t zv89OC0UbAg;JC_*aMDjCRKCiL-U1ouHasg^9GC*GodVsNlm@-!Iy-50+gnK-bPJiA z>VZz$Qo$tlEy?ypI9r?Tu?sSqj{GKZmht+^7qr$@ITKJF29AS&ek>ObB5zHraLZJAKOt< z$zVWedoKg}KhvSFFfR@|#$u`|q?GeR76(s=wid!Q(a>E?HwT04Hf-r**?D+8U=?^K2%OM|}GL9Z^9 zG<^pvte_08^q>N|aGF;?OQ`VX79aTb;Y3lgDHv7^!|3{4;bJR_DtOM}!!e?*@$&<7 zfS^mD0%?sdoMBGJ3Ey%eUgn3?DzLEKPsT})HS4yd4?6Fi|BT0Jn8Z3L4|E|tQ(FPv z0-A8BF|D^ManMU8mn|w}T6ug1I2Xzt8;WMSEip2_k5{>k-I;%-GYYBovzk|NWAW$w zpWfi}6`G$nLNoxSh;F#k6RV7lE!F7adh4IGs0MxC0NrYt`?*z3hb%pY|G(v!2E*Be z{JtF3R=u)!<2sVxWy2b|M^~T;*cwce(N8tYpIlmUvY<2e05%F~3&3gzHvu~DdvBnm zLkzW24uA~qj6XI;Rwk)q8uVe1%$n<5pRR;*dqSg^{NS!kBmXx89e@0Z7RtoY6SHfP z40I@Y02gL!E7aPfk@$0{RDSTQE7!x4niis~zh=TXkmR@vEAW;^APxFH0=l`9eQ5Ae zT&dAbkwobJw)#4~)?2Qc*GjMwbpO{EtWksR+3pL-uq2=pw5p?12D&{o;n(eV?81u3 zowRn`$EnOG6kVKxi(Qd?YHZd6{Y57^&u2YTOi*y+pu502(3tGUV}R zHqm9a6m)?0mB^w>&>M(9hh=_t0i!PG;y;6+!iN^uktL<9KAY>ntCVWc_X*Jd#V!_W zZc5Orep$DC)gbA>y!Pj$qz9m5DxzAOE>d5>6}e-O40H>OMA8#fei(3CnhL{3dPZImq1l0rm5lDFkq$?qgOjdhg(7BbQwyr2%B8fG1dx|0% z8IAso=gGXzs5Mc3Rm5fvN43Bffjq{uQyMD`djC}Fr)8<8qi-aWTk=2d zPdBi2o14{&Fd%BP@R>1wT2UDf;HZs+WTJM1^BRdi2Y8?%AjL>v+`p{$tsn<wa13<5{{4jfwx5iMsme{?vq%;xqn_G_0Jvnzec^-$naZ}DW)^e z5?dQ_57MCTbuYps6x(`MR!l`Ts$Ek_V%&mr}Sn8GDLbX{(0Q!Jb4!tz!zcWZ| zFFk^30`wLq33{71Cey$dd?Bf{dR`Pe5Ir;9>?lBY)?p;!JUFj``sX6cd?PRx5FWav zI@UG!C7MP3EPjq`N3(>7lirV0??O~ zm>P6`6rc4bH2$^NNPzx)3I+y`X1?DLC+q%N-e?+W&@q|AU!{_G_nLf)aFHlL&y7E? z{;CHqHl)$>2eGi3WX7g6_9^Z+24`sXyXI|K4Ym>w>DpQnLSa9wP1` zE!iYYOvA{}_ikT_u;fe*=R=+cDQ{SQm7_?JCLWoOO}B&V+Oat_^T6QvL{azr|D7q& zKSxov9P#Ih)FNaYbWz-y#T;{h4^T%pMc3yC7MG-8aMm{`yiqLFgyurveHgCHa~tJE znRi;#dTCQ}lj82|!NEXPFaEqFmPG7_rZ)nkfx74|4^>?GK7Lk$D7Lv>MyjC2u8RhJ z*W`-!W>VjD4-epw&^sQhUsl=gw9I*i_u)((^RNpN5ucvZN#GJATf|EY9b-Geah-HW zV+SScrU}pwuA1GE=6BDpRe!2p4fRcd-Vw{mF8+Kx;X5l=Zy<`%UajPlZERQ+^`%J}Gs~>+Z<{kD?O^uq@FAHDi?t#t* zVUuXk_a5j3UvFPyrL%cTj|>msX6cSKjjX)$d3p&Jh#jozygYq9|A(A>?|kOFut2l% zD*WZ25vfcv`^bl5BXJ9{u5fvB4;w0Mriqd}f8RlJ#|}=8yzIoE4_1;EOdNEI=uj40 zl?Mh>P;7I7zx8CWS#q%XKDCWW3tyMghC8r>&BPQTxZd-M03-OkN%7U{$Di}(^Ufre z8ua+Do*czz4t~x0hC%0#+%}e&8uYyeI-#aI{;|ascZ0lNFIlNQi$fi45X>jruB7N1+p?2c>Fv`z;UAsO--vVO^+kGmgiPTUgy2}=BLW!G{-|<7| z;teMLSg%-2>u92qJ`uEXUi`Tqq~M7%InhU!U8eTqw~sMDB(Phc+h4%|%Q7|Sdkb`g z?sUNUe56Q?fEp{IQ#+=|*L-5<$kugIVozOa;bJ&D$X-jG?_HceZ8*u~Q4$Z@GR==; zOZu2Y+ay$^iTSl9*2GhbMW>s|oa^|iY4c97Y`2Ok;%;`GF7E ziSh~#JKn?z&?yyGP4p`M0v21I4C?WB5egs4QcaWr7M+2xJmYJA{JGde0dLy>P>%Tb zrl??HH0kop=gkrDM>q%C7aC7N@4zd1_q(hHeHUbTN#q_ZT|U+nRWKU`-9N5t3Fivb z+hb8zXuH8rT|-r%EAzekXJ64ONh-n5dsxI;rc8HcFX0cCFuMu8D+BuMR23C`ZtA}O zZBE>;#Z6|GOGdAuBNApggR7I7Z1J)<=nN{A@qRAO*!v7+P}8n8(Bb7odj-~%`A;cY z;K9yXa-j70suO?C8VwWr<+AswsNtc~=<0m$K}WjXkb;ih04HNQf^#%VE~Ifw z<=^Q}38^Y?^wH$vqWe>_NV*wIV37u$Qha@KvCqCYUg;gv>A+&`;sVS>sZ2g}On9zc z^UB}ye%7TIOlEnBV~#s8^lGaH>|pc64Cpt}WMIpLRPKfnNhW*v0+bq^6Y`HF=*%SX z#W?i19S7a9*|j)XgB^|c;-Ckp|6pMw4LV+J`CKh(wFhWR*^d2ySPC4 z=&YGhv}o66iQf*}+7)|#|N7QuXiI2h1~()P__pOu{`L#40v0S?ZBZqBhwS@&ap_;p29j=ehZ=lu6`@2bYZ=6!QM zE+hwO*64pV=v>p`4}^C|n0bu8RZ2?sL@V;A3$9;Smh6-ce3I;O zydO1Mp%J^yiZveBeFW5`P(L;3W{-r}wV|YqL`wqxdFB7SG#Z z{hTI>3R2MP#GeDSttQ;Gt_M19-pMCmUag-rq|qytez)-VEQA^z9qgTrwdwv>gO0co zmsswc2L0!kOzqL>_caDP?^iXxacVKHq zryrn*P!pQ4KCvz3-_2e&D|7t?$q-Q9Y5OEpIv&pK*l-1KY+{;WZc+!e@Ci9fg8m?l zty3fVRH+mPovrVas<}KCSgbsYxDM+an{{3>eikD@rY@Tc4-0dL%0RCde-3LlntXO{ zC_%6Orq89G?KqY0XmtC{8&HAb$X^1P=qCFD^d}T!)1Y@tsMRtpp^0l9vEOv7nqMT> zgs*ihO!1@z!X**{t)%J*qO-3w5~q^*U-I(3Gu!Jg*4R+IBl{-*3O*NPZXyg7*hv;C zB%Tv3Pd-b9m9I~LZlTv9R`rCrZgM?gh^+*j+u@0K1rb^r2mQN)}#Lq;}4aKlgvVa${ZrMe*=Rr2Xm@Pc2jrbjC{jp&mOS zVG#wi-wPw~pHMPggWgTKTbdUf+U&KhHGQs1EfuE~V~V~JiOox1y^a7kZm_6`l#6MQ z80gA;?-f4DzbWZ(6FeKiH}VlCQ5%kTZhKy9!l8^H^X$Z8T*-!`;^s5I)EfYi+I8$w zA~7ZY#>p|=dnMo1O={PtJ5p`%3rc$Lw=N48ubQzxi6;8 zj2d+3G zw^{!jYff@8jvsY$?9F(GUh2EVgq_*xl>ogbvsIuY)FY|UN0Ed!elFDpTTyBQa|It) zV(Fs!u;raXtz^Ou%V<6qvVlYu*ZI;yM6S{6#GkXd-(qZ87FL7q=Xzbbts;z_*tDjO z=?*a9Xe*f+sP>7wI*<7iR^v42-IKMR40OM~2C$ENbOUrkO+sI+)CZlb+Z3+<#vFNr$jGZL{NBHzoH#2nozv75~(uR2#vGpGknbeCvXBBv8xrM|1 zb2;dg(6P4%&mPOnq58gHd&1KehE2liv}CR8A1V}ZBfB~p^gjc1%2mb!w+wlp13Pax zs^=yb2OZNP0FGS`^a`AAA=7HgTmt9kd*}1!hni)exBO(Y)LazUkkslfF$S{a!XV5` zKL5*NZ=iM!@Ge4$#mJn*6UOnSghn4v!YnU*ay^U1T+I0quP0Wx32K_+0E@4PGe6r# z1Yoea@g<}{=L4TtfuTvuDm=bU{5il!MaziFD$Bq$EMlG5A<@{1?^@}eH0(a|8QJEj=QSVmgw{n)2`&Q2bxee zn?!ZquFUr?lA!dBE7EGG#$>e@j|Z=Iy3f+jcy-EBU@K8#9zVStvkHK<72`hh1}MW+ z5jnw$zq7;JECQYUns^5rE=g@=E%coSW9L_V1alAD+^hgLncWo%`M3yN9y-xf& zJ5MZ$Muj2dVBU7A=SdxOmf-Y77W^R;R0_W#@F9~yDN%E$CN2PdhdXKmS&h3e-n-;P} zZPmEUO+LRlw=Ei=`0L+Rj6kPoe&XEZs(ZggVv8v_uFBJ1`0o) zeVjjj{8BFqItObBjiphJgRY7{ul?em{M9U4L{iXeU--z!_+8s21Fphib2`5B&!eU~ zfdxhXw7;Rd8JDg>Z=7>9A*2y<#0B?(<$NY*RTD=jKVVfXRD5_#xeYu=Jtgq%$&RI* z=#+C>?ZS$D@BVpk4G}5VQF75A&xcCpe!XZaA?0&+B71}fcO_!N(MieDzo*2~Ntx(! zbv!yfDxs0b#OuQwT^-3m?$Sh_dkggj+m2c8P;%Z&)mh<3js95D9&Tj>PJ`+nuZ}tJFXmt zNWwIy=(mLZ?RiP1Po7O`sOuAnIF2f*KrfP?5}*$v#Rxw0phP>k@J&M7QS%r#rX@up z4LAg)GBzW8GkB7ywTrrt4D`JCb3dupm&;Ke=-6-I?VpSI1jZPHIwBt4bz#J3xy4r_ znNd2`)S&-Gpp!$Zdr9@aVx`1fnEELbN(dZI@kp42q@R4mkgwd0y7><%@$%xkk^4Kj+h? z(wJ3<fktIGE-uGhw|aQJ8ul9}qG=o3gg{@BYVB{aH; zipy$GRDHi|5)WVeAYr=y9*b*7^mL`^PDsr5=GQ;jh-qYWRAK;Pr^WK;^DCQcSgb!W20iNG|BXD!2$X8OHm^G<7YmV7@(j zl5F=*mG3<~?cYrat3QCo=tys|IdFPH$?#JKbNv|)9{D(V_tPQnTr#aS?%j2XQlq0M zS*X!DNS!Tla7L#z>hor}N?xRhKH-$(O>Hw6oPf^~kA10R(DdL3T$T9odGY7Mh_UUR z38*E)2gehql~|PgF|Tu!fN?Wu$>=)QOm;u(s`q%yT8$pBLEl9omPxKG1>PeKfX=@- zH_gCXw89T(%*_-VXngGZe{U6GF1etWN^g#rUPPYny>^;sUzzaN6UTEUdZ7bOD(2k& zEWU|H3&lbwi)yxsmmh23(7vbW7ds9*d>A>lVAM;g(XH_i1Kr-1P?66kL7!@(`2ILr zn;2_3zn!BK+hrm$jGwXVQ9NCtXt{5c1`tyg}bjwU{2c0Eva#%Ta_;hJ#FYGif? zbVTne|6p2;AFn~*H8Bvng@2;9#uR$>dy1^2Q=dmD?$sp+U36igr~CYDm!u1FwJgEn z!pr_uq}hwe^Sy_li(&vM0<>lZpI1r-p4e^fsHS)%Drf962g))13dbdCAx=tYboex$ zK=RdgrAGgr&#a?C@yrD1|Cb!=-av65cDgkA1^7K5MM=<2bjuf>M5Ff&YR6|l&xt<= z$C-T)$}hb|P|LbfhX_UV{KT8}P4~|)jAe;#6x>B`V!RtpGaB@U#6rf|)d_8*pbKwj zuWZAJrAVHaECM}HRwAaM@O+1|Y*PTNNNV_^WVBG{dk^Y(fp;QK`m&28ZOyNwyyKt@ zJz^@I|7cy1^#6c26ID;q!1y%3G$a~y3dWPlR8q#LZZu@t&X72GIKHOHf81WMVp|vV zad1je85#cXucxNm{3hFMN&2YQi(RG+bXEL$kh^{UXb}xAg)$smkGEYYd7k6N{P5J$ zIe0YTW`HHVrb4ioLOqCfV=rBU-jHBC8A`6dwbnT3wGMMmGodK94wd@A@xK$)d<97M zw-cnnw99zsE69^Ss`I_KZBKi+B4qAJDs&+~Mb2*l(Mys$PB1Rs0j(A7Zmb-0|3sej zL=;#;qpygs3wZP5;7zD%#NdM7?BpYF+!B8l;iuRW;X>F1!nQ9Ca?_h+e1u#!8JXFI zGz0BW$Di}xtwm}}%(ot>wfKtKx?of?H~#%&SL1_8>B_Ol>^7|Y4ZD^NM0D2||$ zSFUK=Gb&E{-MI-qUidYnK{x0eW&F9rXJ2n&C0Eth{;o^xQmT%7YM>8avyETzy`J1W zETZlTw`9;Tx7Ths&1ldYlhKPr^3+`eou9I`XH28#fNlvt`5rH2NRM?Izjy#lIT;yJ z(3APzI|v{hU~2 zS0xr+ipUax(B$Vj^6BKWJeF#gwy~H-5v-zZ3m;@-1^`avZHp7_?cZ&VI{w^c<>!&5 zOu!n<0meQcoN-fWvE-mT;I@5AiY77|-aU_t^&uNm(4g;O(8)yj@UB-Xy99b0C)0&v zpRD!OT#fGU4UtWG8XbU@9IxX+N`qb9_;u3x-s9(a%*mDxrFg8JvU9<{IN6!ZdC8n> z@MvV)o5&gyOIqi!9lM zDqiN@H{)hhZLB!xb8_O(OH=MGijY`Umk{@Qw8MpXkZ~U96*jSn4~!V?QVO_PC$X}< zJl7#3S2XB#1q<8ox5F&d^6g=MJeXJ4@hSDGgO%77lc-2dj&Ys?O|>f?JQbW;53(g9 zt~bM?*rbX1zOQ8R^1WZ5>|}mty%y4QNjNC(vSlG_R0*Oa3KjeImkNuzca+p8(*bJ`p zYu}>8pqLYXE|xvrmzs(>--??D)Vf?9(wdllh_dZ)`;(}CF8H(*3ZerVBhRwS{F(j_ zA+n3CYtZWp#pqM_MBxu=_B>Xkb9B2wdIY-N{wx1xg?!L!n2cU2^2^$`0(8FvUx`r4 zItZo(NS*JUTd-#0W@4WC-{dVSu6>LdTQD*)J%z=K%RuL6anR?)!1UnfsN#!d-2@8I zY3zC)+!1P7O3@$jFdDXOcr3dvBG08NRKl-G)0*Oz^=Z&OsLUU2CAT>JpL62R!E??m zT6rm*4T49uLqnk3oqWum(whW{W4j3|F)=#0ufGt?uQFDw*K5%C4Cq!7w|;z;$hF2B zxbWd+6_-`I2YU76x0ha@XP|l?yIR12e&4|y7ji%cIHnImiOeKX8Y@MukgwJ;Fh=WeHda*hBMIlh!+&C`&5Q*(Ikxnywj~>zV zg`!dMa5*?L3eYQCPI)*%$vtTQ=bZR+4<`CW+~ZqusqeJ$ zkrIF^-Y{Xx^ZzeeAv#jsZ=VTi78!d^eO>s>I{dS^-XMf_aW7qiURU@?JPxkqL|K8l zd~#)XP50`@7b^O)cdMPJUa>ZWCmqFDF6hi%vltOG4SMhwdA@h>rj4yluxp^3=$^ze zoIseeG3<0cop)6tP0Fp%i{hZ;Gb7N!E=O~8gf^)_A6|}CS+NVTq!Xx=h?cv@id_#M z%@te1&!87h6<+)mvY=1fZqyu9;-Kf%Kkt}f`fsiRomi_ck`;!Kf$oBH_D13PXmNw3 zo1l}XPe1mA*DUxBJ7=?FePE(8SgX5WTrmk_%Y&i5zhHk8KppXiXAZVx6;f;&s3hi8HRD zq`Sty2E9?ili>|BDyqjPO|)=ahXd_)-4Q(vy6A>KorwK{yLBIil0#>gpagmS$Xi&X zB)dPX%J(kvvOJK=VoEWYFooHPtgznt<%whPC5bK#Z^VM_X`gaz;R}uo$;9+XCFou> zIKVNnodsfCS(EY|e`Sgy8T}gueaZ!W5r$EO|KRQo{c*0tK zHr|6NX*%(6x4!9?7T*jg4-getX}yOr4L+eCCP_e+xRLji=tpU{PDQ?V5md+6Bf-4B z)?u(!K-+6s6l)Nbehe4-e3)C-C$2Rm=!!wlqz^^Qj=%;-pyS2ybK;<1?Zo!VC&s-6 zzf4#Tt5IwN5ibb0Hv=LsiLJ!>uCH(LaUi+f0B{pUlI#w7@#kkYBTSRqaEZA!-T8$r z{9PsIrp4<#ftW2;Ls@}QeCmbCy9>nN>p?OVmh*f;gT5y~7fm{vEf9%UY9E_V)=gaC zzn}5?E`Z+ViXMKGn6%|T4dF%_qIBq1C$B4k?R+vkSjvxgOy4&|lJC7_v$9uu6vaX3 zW0--4_zTEkfC}?UN5(-XXpqog(Y9C5uz9#9y*q*rod4E}HS+&%P=S8E9j!mWe`40f zq*!`sDF246nB{)5s3#MfdrwJzC`5Po0if}Fy7qjO*taHO{&r>k^W%hxL=jej-u#J( z!wJ^mRG`;>c~ch=bAZNsTlGG)_a`1yT*qs7l63^w0Hi_x^Fa?f-!Qi~2@)10K70#8 zGwPnzW8a);Qfk$`IcH<|e|hgM`Tkpx#!cL7+xwzpCbYV6&NNI}zIRc+ z#aV|)v@nFJ$S>KiGm-a_d9RBhAiN%FUGK7}j53^rL(?5u^CI}5v^4~s|6kN4s&&+f zzMiahyLjESLt`5K`9H-jtPi!@aU9o)6u>jynF_ z&q?!5^@TGc@@?~{>B(ZE9Df=AV&1^%$+>-fvHWHut6wUI(RYb0JpQOB^Kp3>EK?17 zK5GJoDKDWE=VA9pi`Tl~wAIbyod%t2^{xLg2+qHGfI7O6tEmdOD$reU=kVw2%9!s& zn(v(xR+{@^G!>~vy?xeED#guS<}D;fZ0im$fmjZA=;(t((2*6*x4D|^ikT{9h)mBo z=qqF8luFGpm|uvVfm`h}#`DspOSJgL1U1ssrk3sC2*RG!gy>zirchaXp-zCs@I{!pc z&i&#+^ocWF+f{sSwMMtSvU|+Eb#7imeRMyuo^7i%x>sV~G)H^1iOwa-_wMjfW=&T# zulEz&6zR9A?LannLwt3Jp3GP&oL5(1VF)@!WMK98{uR!Mfqq5Vc4VOUk423A9!u=l z^zT?C9DIV~pa8KzPQRZIP_DJ8R{`(cM29EjVFrnHU z4U$=COT(g0FZOz_1SbUDvCpO9Ga__N@O#D_$6>$XX!UE90~IOgF^&FTR0yA0RLF=L z?@=qB(Xs>DVomA&Oyc3RToysH&>FYHpQ)W4|DLM&a}T`Rho`g2#z41FK_vTfWSTbf z;cvYFReg@S1^UJz>pkCzN4_v4qHjbt0=3G=)W@R}Y!iRm{Oy!oke_iLK4K$S?v1)P`MT7}e z*Wc0If$Gd-Xoa-H)gd{ zH1>AsH%wedwe;cH#vXT%M@- zK#z^Rg9Fc?YHB0ir@N+k%&mbwDpvLNxRUK{Lq)I)Ca@E4CLK=oF(a1E=yWx53ON)D7Vy z33>YGHou@;{JYBT#SSqW%m%MPZ=7?|{MaXm)~{rVc}M6Q+Zu}POXq9IxDipoB(8_+~Gu65)`f*qCkCL-foF?^aDXudt!xMdM~)K`-v+w z==DHHC)y8NR^41(z8j6zb4&!f(-7!PloN3_wblb2HBnS7TqfVM72ShR;qA^D@tlK! zmL$pe^qN%oS)KP<35{-&=8KXV-Tim`S`-Zc2E5v2yG7b(R@^FB5$nTPF0=StV=5zs@q|)O3_wtn)cn#Gkjp z{OKmj0sUX=87l#+r_mi4H9@5Kwi@Yau{+%}LikjRQh6*K(3GHi%Xfiv4SJn#@zT^r z7F24-EM4N+{w|cupb^l6L4mPvM3xj<%!eJLSLb@R%M{me+t?5zwUi|OS}Yd3W~cYl z#YH}tg)DA&NBimK(M~y*6_)?^yO_JIg^uL!6{Sr&9hsr|d|Tjp8e~9?<&--(_Rb;b z79L;Yykx^s;Vo$KJ65~1!(bwcOn164v}U+McG*!l+BR##2HDJ@oN(bS!G|QdeXfi@ z=da}2$2LjVN%$ye0M-c^oa$fYP3Ue&rtanMbQ zM%IvVnDa>O1{Ogh!u*P^4P)a?F~SR{EqtQ9{{6U_jnTTmRW#~e#G#fIJdtfe{a#&VeKp|@7x&Ze60ONgZ?Ljj^=*Skkdo$7?X2>(C~?m zmAeT#@7e2DToB8*CYdYxNha{p&lRKxrCz@{BdgKHK6%r&^zm-RVZWk8as`Z@n9CAz z*1iQ?eSZs6{$5dml?AbOxdB4c-M&29|G^c=fX-;v@lx|@#@`^^r)j~hV2KN)~;DPOsq17UT}|> zqRo7#V^RncMRwpZKsQ@vJK6p8_U%cJx&pq{hIj-SyN5RfCe^`Xc)JspXYwjL zW0g}scWa>A&T^yn`{L_f7Icbl53lci5zc8bnH}}<@;gz)7`7I~0bmzJ%^{qAHg>X9 zmfY*crrS?d|J<#3Gy7P{fiY@ogqr_RSHX(lfsVno?7j_vE{bpQ5q0PYuM*A(x&=Cy zYf+<-uNw6FVxsri+0i<7cQEIloT3LuFjn>&2E8QGm3lAq5kr2?cAJG(SGf z^U|Pm`?i00fA&!{kZy3pP7e0}!Zt9_EH@4SJQ!PxDj@6F3>@pSgR>(39PCG0FfC9S z=q92gmz5IrB^4p5=ZqFpd`xLQ`l>}AkZHc!&jZH}J4bgxpJ@^UbxSnpd0%Cdy&9A5 zgDzHC_{S8nZOo~!62e~ZiVj`cOh_K+f!X){w6Y3x2fW#7(1ZQ-mdrezo4j9{sk~@C z;{D8Rv#&Q$p$0mBdP@X}+xBG5HP}Q$S*X$BwaBDDChE8~&UWY_#8XqBgbdtcUy_UjCOsQaJBU=j_oRt zCrc6NFkd9Z@_&!eS$3$=e+xl3j*s%z)j&5a6m@1;8Uglk48n0{xIjiHMuP>{-J5Wt zxWr3#JOeaW?w4cK6@7-h_;Z*ty%2aGXFw;EZ1zgEg6DG3p&eXza0{&s>KNB?l@_~i zR`cM_+FHYIfDVs!x3a1RT@5R`37XNaF2+^iq6Wn+o4)Q~wpZ`t)w-1LoHlW}h1B;9 z_OEta!Bn7gRlkt;Rx{m!)AiH+`+Co%7XQ|zTrPXYOndXD5Omvh)>YkLIedTE;T(Nh zq4w-_P!wMtn(nA2oVUAflx_7hi1yrninZZw(_)oi+^rkqmCML$!et>ELtR+YY+AS} z{0uqq=WIQQp|O8wwq-1=Htql7bM$UBY;=;J<%#_9@A|HdQD+sTUw23Ce$o#rkTZ)%s6l6yA5$5N{hlbP zpAN7rk@Cni(Xhlo0Ha7)#2r~@)NWYf{q^o@h$(-`rD787KYs~^)}9@IpYnD0f8RR< zoy|tI3zL^)C8+L3Q4-c6tQ=cBJ2i;vtv16i(`+}gFgSeI4HtK<0hb$pzGS#x%fgg_ zepjcT$TL&#Jkf41%`?S{of7oaccbXu7i@pB6>$yx=Wh9CKi5plqY;g?1mTN?U}!zB0~9V1P4!bJf|Xe&Ghr5KqvaEp ziD|(7=RgHMkDhdS8o0!&Kc9%X;I7|U%*Ox6+Auc4BEPm`&;CxjoO5g%Q6F?a8-{N%jYSRmp8>jcR)r6~p557h#s$dl=)0DG(-(@2p#%B1^3(+x(jVA`zI`w; z@>k$nZikYjP=ha}hi+-ItYjzTMt0XWmYGJ(Y)x7YPcMq1sQ80@JUX_pcSu_~imEy! z3Z%MJ^hEH(GEN9DHC|%6<8PyZX$T6+yz|R%sd~{>#FkzSR6-VlpW8eTXGi3WgAKgW zv%@@gqA(&m6&uBxh82HG;?Mo`vux3+R0g`g3Oceaw+yl)hMmd_qIPsnk%w67X5qy^ ze;MF{7g`6I!J`4t+kMCC_pYBHe5xL1&vq}-j0RmPqlM-J-@nZ{?Nusfqq`0|$CaYx zD_vXdN}2w^UK`j$Hs)`&@fW(M-ILdN;Qf2qI+Sn*@m)G_)3&UG*xDrM_?zfiL|NA% zlr)DOc>si(Nvw|7|9B5c?TwTB-)62{Wbg$>!5$bc) z^s)G54fMAW4)^Fy+|x-EbYSivgrXe}|2Rqfc^ki6Whs(^-h}9+Bb-dy-TA7xo;x3&C=ZFFlqYaYA5BOFABZPshe4K$LRR54cG;>m1_KW z6aX7{i~ZDNmB@5&wW6Yn=>0a=F2%Ow;4(j}MI3Zl{5e49Z!JNE>8wUKrho1akunIY zQv|p4W)CbvOle~p9Swi+a50A26)zEA-U#T4IoWBiicR>Ua2KNJKJS7iy%@LKpo{&Y z+biMfXfQwAcE?!$>n7eQcO}I~HBbAhiCY5K?1m=me3W^;7xfp7tT>4A&V=y&d@ORM z1Bl0t5M@H5eP^zP3?sXr&fo6Sc;zB&ZCD0DRF$7X13rma2K3{|(Zjni>e)fT7XQUs zaTNl?YmX;~3>E}$ipnfky;b;w9afvvxTVV?fY4!~Hs`&5NTKF0ZWS@=FRY{LS$s5b z4@)x`%A zqjB@*-#l5kq=IyS7vAM`nzGgRTAAd`0N$dHyTB5iaP1hq&6@e18LAn;qvfN*VNjjmDsgdbYRa$ z!1i!L(1HCHCRP=h;Pgk_y z*c_4E(@4i~>CAMlQcd-Y=6ZiCLp z&-tF6OvdPnB&lLyc+neY>?-JnNJPr5TJ&7sGHZ}@#x1wsu8ts0gN{XR7W(kVK>?p+ z#|Dway<>Xf8G`t9GqIlz!sl$;=osh(z3&I4)tq2T--aF8B*(=@p&!ETwjt`IORDQs z6#pZm(Tk|FTs_&oh6amq7J8w*mh+yS7VQ*F2iFZjzn#WFH!pHxyA36qokEk#5oB?h zzk4eF9ANzpzs|G-^o>Mbk1^dy3`9 zKBU5lO>Vp2-%w^c4SGK5W8J)uvGqkhUFY46&lKxth?NLMg+q=B@=etBnDg)L4wxQz znQldpdb}?ZtC-$TFT?GqmTAQ=>@ddeK)UrM^ z`@L$p24Y#qgr%8ARPRU8aamt?s~jB0pY+2pjn%)Ma3Xtf@R_hh>1pjy^0(FamAzTT z@CgvQ9;*I1LOkYNk|=Y`X`GXeKX-*&#J0~eE9K3WzpFOBo#m{Xxco~kdky(vGzdvo z+r!4?^Bzi?7mjihb>!-cRr5NinxyaCU?uQtzLIjTv6zPq5~!u^@p?ZlUI*uY0u zAu$u}W^h3ue%9D`?-MR2tdUhYj)wa}mxzQkx}>0szur*dQ}R;i%N402C=a&GWaq@x zYDw*-94YdOZ;7rMBuL1)a3bhRT`W*PJH03%YPzDIja|$}O(z*!9J0=dCbTQDpYHD|-DO$fKw??eCr%7>cp|#raMx)M{>5Q; zR-I`u8Xs*DUQlfp^Te!19~ru;y;)P}=+SV^jlG6~eC+%MPqN*LuhBgQkF|;z|LXmX zpZH8FQs~a_sVX&SU4^CN&!OV-fvhVFDJr7Xv-wc!xH(&&$M(ReU`2DLJeA%w_~Q~d zC2to&=c>H)#mZYui^K~)XXGHbzZ)G+gDw@*aFrh^P)4@cYH^p{xnq}1cU0}kc=W_A zP6I04g?3>_fBXxM96iz<&M*);-?2*>jV>mA<(Y-pq0|y!(3Zr0x+vKS2glM_QFQVm zJ1Qy&pTr{h?h7@#^HZ^wP@-u|EnTs51FdSy=d+*>4O_8a=sR|?8>~$8|BkKJT`*CX zC!9Wmo4YTfNTHLH7}zm|KD%I92~E9Pg!ZT6&%wJZ9=RKFX_CiFV*B5zC_&%yEVbf} zXnCABuPBS85@M4^sVwrobvxK+{YQ*GzDu3D`&hrv*QWdKf=(8uwpJt(09bxy^949a zG=Uq}?gT|a7n?`!)Sx&d<|M=B$*Zg>D3Nzdi(W*_u=P zB)$7opx@~&*P!nv=+;?D@Km6CTn#eks9#qZLJd_bmox%8i9koj!jHvPYdz4J@9gHC z(`->$r>kZ^Ku5}=p7i<(eW-4t1u1-X=b^SLxNnj>2$ zF{o8$IkQ>-0--;`N-if=eTwLW@EJnThg98G8QWQ-ZfSM3n@^*^3p@A)ouM`1z#-w1 zx@9%3kH23TenBzLiHJXU?BskKO3wTbtNUVc(0S`yzqW_B$z)*_HPhjN$-X;U9nk%M zJ!nBxZMD0gi`?;W)!++i18v=~*XitA4f<|^-co5yqdS2a56;@2M$IF#+o1EOx?xPd zt6bZ3)mlhaE2>g>`oGoX*Y*7fhj2e(^l_j#-O`cPu4YQHmIwj+&xX*@mD zJBjyWcUf`Hi64KS+;-qHX1Fl@v)*v4P7+RqO3>}n2jeg$R(|f7V8}qrDN}97LN;N*e;*ByS$8LElZ#PvKp@0nqt>JdXtqt=FBtnr7Wp6(1@AI`7jM4ec9I zt%ltdE-LKHqotSR*Ag2pWaDK)s-{$Ta-e-dE%8&7O4-jN7u!2#@FR(r73vv*?l{Y8 zv=vROUkJMWO>M4AA1epH^PFIINhr#i?so8=zeR-`QGPg6faT7ra{k+lzil0n+hjYY4k8i(w_#tcm7!641)*` zgS10n)Lo?ZQJ?%VxLUbRD65c5pYZdJCbsr!*P^KS3%70Cf=-)Eo$z@dJ}IRU===w3 zTPokXGXsTtPzIj~g1?d<$bxF+B5a!L+*+YDc3GIw{4@vxP&_!qw`C2C!lnIidu@R4 zTFWoGCK&7xrgLi+5}OgMbMUiIglWM5<2j|b3MQ>uA$akYC_PoB1-$5k4z4#VjOb8d94phrOr&YHvinF??+(G_=)8dU{HbX53L@5 zhAaM9CBH)+=nupHP@|#K8g!Z9sgT-ZR)G!?=;DJpqke5}q2YWkieRb(x_=CP;wf$@ zS6s<-J$XOzmtmu8IpMOPldj1lO2VNo13GNI#UzDs52q zwaMwqJE@?lq zUACB24|LHr`2U<2UM-rqw)@o$&_zAJNt<1%6MP!<5|q9?70ETa*f?uK|MUduQAkJC zFlX0&U#&F|>8WBeJ{{O&i)$(!BMTqRBG6$#O*3NiQC72R>}yDM8=(aPGxtas&UyHxSH)2LAp4mWXb3A^BOTcdYoo z@o_D+lKVkzdm62QO0a5pOh7C~_oYF{UXW6WK`;Ngxe6Z@w)KY_gHDX;VIuilaL-Xi z!z4k7D?ZrqqKZ*=rDw97(i}5HaDm# z|AOJn=jk)S<3_&Cb_H}e>&PZ5+E|jks2=DRnsl|jlxmH>tDs|p{FYA6tO7mMEa9@P ze{czYy5n7hnnj|;hFoN$E{HAk%@<;)#ZhI5s@)I3xoND3jVCC(0w_ApYaldMX1j+i zpva1?Z54_};j7N*X5#qy6h{kk*5zIq0^`7Swuv zgU$@wBLasHbw9M1+}g@RW}fK8A+=rtqQ~?y12o!cma#Io9cVj`b_n?{aKa6 zW?mCl28{t5`^wmw0CzSTYoS5UHXxc+Vu}yd5a_`gU3>p;hl`lZhD@utw&4%?U|)b` zkW=)*?=U5BzZfFUE|Tokc;~^t{KlY?>3|;e9ZoG0-%}?WzG6=N+NE=GxFCnnge`tV zmA?!DL#n$!qzP{gpYP`ya5q%v=&sWo06`wNtE{p@)B63q79(eO|3h@TgjUy)TGE z=Y!+D)np2IPEh|%Tx;0{#Srv|!JZbXVfcrbAx9d$R{uQqzH=WoYp%i}Oc*sE9`NAtbL;n*&_!Z{MGF>-Rf63EowwW&cBlq@mq9Q7 z=&3$bqo50Q>*qAxa`w{t)pXMu-4roPC*M@c??ucL38Vl9ZbylEdZf`gi>Gw54CuV0 z&3!P6;tG^g^Xu_<;fCcmwIjr3KPrO{unT2w3u7O2j3$+9TfwCpaP>N)YAfabN*mYy zzhprVo~QJ4HNX|mueNdf;T-c||9uGy_wP4bG|<}o|I6%1qnBRVAkJ^9fl{k~9)I6C z)!l$N=w!kPA_TPh4O8FEEw^vlSfwamqc7YVSSAgX#ZGAS%B8PTfAuX`=i7DA5!nvU zYSVp}K}X9nAUFCUvkP?qTd%!W_>YTR4&BQl`{Wzz#dP0x97kpphVuk>Nvps6UrbdC zB%)N(SWaFkv%1H;8OZ^LGx<>Um1`i)L6KQFX|BJ><}ay3@1TQnh&Q`ck2d$T+OaE2 zfy=nFg!3sDt$PWJpT$7G8Xz#suOUG~$|nM-9oMRnCPoqC3Yxp-EpbME&z907n$HES+S=qCBghqt?gm>W*3pbZ+O^ z?Dk&COg>o<#VYr#O>-S!`QJR*hg^}=j{p7Zi4zct65NEctDvLX%T$BDi=gA<-9Hy} zhqWAcYIcPJM4s}F?<_W=v8N!-&)0Dlqf6rM0@pJ+dir$pCF(3pnKp< zCX{hRe=QHITvf<9=t$O@mU(J}6EamlaB))42B>F#)AdWxwO zMcv8KTvyDoFsxaF-fhtRkGjzjYh26`9U}d~x&wOnk!uTeV1IqhlVSm?fQv>o`B)=T z>@`rFEXE7jv($d)4Q>@0HM#IqmEP}(*?uyEN}GG#K~~H)w5h47WsS$e&1IKg(WoXl z;nRqvZhKgCaELz&@&8*V1(j#`)yMKnh~gnX_?4OXaBv~=lVp&7)km&@J^%tBFGoRg z!|kj(@9rc41BKT0L34SYb5j*O-d>wrx4I)xZg=l9B2AA9JIY*G%_UzL109PK0Y>~a zD5B=&X=})DHvm34f`2@b8zEx(ZTsOsM{1(0gj-I&Kg8z?Tfz>uyKwUsDPm;$3H0zS zb4Q58XBzbGg3de6^Kjw2*A6Hp3SIsgpa)@Y15aI5td&$~?3;_I(V=IRMKwhQ=)qka zx9wT%2hd3}l&<>76`tXV^K2+DM3Lqa&}_US$|&P-q<#oez5Bg$GXyK|qT`-ySOxz+ zI|A+KfOEcp!L-n1;h82zgJCF`LyxM~hOdF%znZ4`&LE%+T~qUqecxYb!_n^Yy zd2U;6@v%|R{TG|M=>i;V8}62wp6aODuOc_{oMB^rmfQgJ=c`X)UFH9sYuWPPV%77jupz9$24z^*f(kSQecjfOso=c1ql_k+ zhN{nfrKAN^6MpxOyG+r}#hhA^@I_*B>{GBg2^1Q9W zx1r*)=Nc;Hph3@oet3U>8f9Aa{e`D}u=}Qa4R#Sp4z8ce_o35|MveH<1P{d@MFc5* zc21iuyLPmiAXMjB6J$BZg%8@S0d_h4%r<<~9M|ZCG=JbiI5L4d_uXp4aI<>CdjDU_ z!g}rD=efqj92vYHA4Kl;*O_qP%xc){MSitlj0ZzBe7(lm7_Xi#>_%TEXqulb>-4RTWK7O{%{DlHOFR;%+ji_`DdK&c!_VH0E z7J}~G`OX%<+M=6>d_B-J$Fnup9x4(nQx>dQGr!Xk+S?y*Tv6bGD^A0r=sKu5-SqNvL{UoU ztE^&&F8;qp^K*)Ji2d`(Z0GasQ&FMyPUPO`0QNx*N=E2Scf1aQG%zsKq=_Q zvj$%W>DuN>5!+}?fVl114Z91q-$vD*=$lJjOMm@jQIM{$_AIYAG%|Kxj}RXXR;s8Xu`O^ayxQL-tRNcYEn`<^SrmRdU} znq6F@i4SEH7Vv?oqWqR=5%VjzGv zv$KNoTV}t7)A_>Drt#;jy7^gp_$$5t%h?yT`O6d@u*9Mwe4m^CU4t%#3Ztt=#r`g~ zZ%tI>T7@gf2|Jfu^(TRDyC9Oy@qYWt8&A|BJ)A@Hhd|<+_wJwXKqKUA9Tw!Pjn&J^j=#Hl)1B- zZ*Ox@b#z`e|DFJyYo_mm2686`FE^bLq5An=uqXFf#7uO4FdC2E_2a`p0BuGIrIzn|8TaA z4(IgZ_zPZ&9OM|ZA8OP}ia&i(*z^0-Kx5O*!3#tApFWtD87vk$?N*R1qMAWtQ;;q}3h%6j(##QkFlaISU;6fC-?$=bi z;0>>KOrp(g@27tvqz0YvKJeXd72%=Y*hjR5d;J$LKkZXm+-=Z|$-m^1)sJjHZu%PW_KR#^cnqVR5qCg@i z_~}8@+=}v|+}y0#eOEUjLKC3-F6zU-a)Cvli!rM_?Ut5!SD$cEq|w{hnn_hHh0yje z!iM#(&fSZT`ETsNVJL`G9}t-Lc56^3nMI)Uo1g9v3Z+WmxmGy5y0~|jKh-FjKl|np)+3bj}7s&L&YI! zj@W?G{_lP_e5+a*jD^afwCJ9eNTVavJU;~8_FzO)Fi%HCw7IrH$9@XTd4nEbGjN{t zSGLTz{C{`g!2r1Vm2i&E=^GF%z8&S?tGKb6=6Op{gn_;vw4Wok)=-ens&_2>^b#6{ zgiP;D?w`+Jhr&AIRgJ!)_A%0+pE<#*I>5_8pD=N~;|PC%oCVmpxTTLy@lP&_cA|85 zHTs+v4|Blr{C)eH>vOVaMSt_W!3|tdgPy{Py+Qplz;zC*%J%bLVq&%o!BVmv*X`W^ zJv?^i`IGsiTHJves(Z$Nch_&+NOxE^L3DM@_c|{@rkOQN&>0tr+zW|(azUzyD75OK zNLey=6YszU!yhCDIDu*24ueq;`ngeTuQ6`rKI5l+F;`bXeG-v??-MaEoFhC((d?j$F7ez*wMDz3H{&@-D7)ojAEhl_b(5$}c zZy`Psf71CqGL2fhuE8IYE?>~d_u~y$5he5ZyU)M>{p9z-l5bU~NAXW?`DaXi?w#wP zLGho%>07LSeGPg-@OXBE&@GLE&ga#wJ?{R}2{QgQQt3P&bWY5eNBam}hL!hB{L=V# zrY#FsuNij?ru59NDT*wpXER7@I_CTzF5>7u#V=V~H2wV!`Q(VM;&vM&jq|FUY_`OtulVn^`TO52mwMMQLN zTP>}0`S+;Z%{iUP{qwar4!Q_8{ZudGu3GyXCD~|3S?96%VLkgx7v*X;a2wqEbSeVcAJVLYeyXNsu1W>k z9*P%H7xC$#hn(9s-U_T-jJ|EFRjIjHtZx^s!sK?BIl_;BI`Y@R{u^BJbN`u*>jRht z=mcBU74nfm|85VSa|*(K9@!Jz>T_?duJWS`Mbd^~3vS!S*!+B2a{v4X;XoIGj?jja zJSb-kUZ-v1Dr6b5b`?^f2OnmaK^jw#7C-mIV@u}w>t;0By4?l6XmDd<{OPZY*ox}- z(J<)TzS^!q?IDtKc_#m{rkLiIfF}V zU_zo;?->hXsywqk$ZY5Fv`QC~ldjR1CGx9*=av5bVPw0D`1Ei)-DB(DZ3;j)tubz( zm0j5GYk7I9p`i+avtIn{p~iV!+&P;c$bByyM+S{Tz=nwj~%|-JHTtjpj`a2 zaS!yW(b2)nY*(^o;=D9VSSD7YVPlQ+ z?BQZ26o6L$!`UA#G^zjG@g!cm0=hNlj!)WHkkFqs9PM7y=IsTT^VK~Kt}a~n*y zmjYgFGoh}NC-xJ~zus=7pX3RjKEHnL(?U;h>zw2+suIz|?_F8)_oVESmsqZ;{oM8| zpFM{ei-ITSe_S|MR5q*av57xR4_dV&M11--r>4{$=cN|E8Y$Px+`z8RkNZ_~KktA* zH7}$7oTCr;kgV#(kW znha+DLaq2y^DbthrU|3$O4;@N?32}1ty4wlbv4Br-ZfK<5C8!Qs&%(ipTiI(2qXs(ilTqz>otr0a9CSW`VeYhR{P|F3 zJ>0JbS=cyuZV=p84|EQ>=S(@`36oaa660=zE?hPI)cUveeB-@XZM$6oolo{&r**wx zHRuVM0n>LC^dLQhAr?TJPhI;^!eZ>Mh%Rc2GLIc=dssL>cVIQUX@RtEo@=`?SN6o* z6kK<~tR(1SYH6ZNyjoR99}K&~7Wi7adT5{dVV*Xxbdqnlhy}ZwtC}9J>I&fN9TcU6 zwWc4BcQbQDwVBs^jsAUmq|wp$!4mojViOxRm4XeV&4FL}UDe_b-ca$zCNZ{uQ4OLg zmsU23XkGta2YnsQPq{&GlND`~Q4u))T1nWzEDo&4ZIzoh`kP;}T51-Wb@MX2YTDEV z9i}Y!(Bz~VCaNx5bQ^RL4@io=2EXo4RAMD#b^&zHh01Nns&hjPdP45A8!cLw0X;CV zEy^uU5vcOyueblU8%kY#MNzodb>4g9mVDFQ*C@gcCg{X3+G4ALG0?f*E3vtcw~QV0&8anG#ON;QIezOT{E0vA1wwibdIQD6-Zqce#{O>Yw>N@Aorv&YZJnch90v z-_PfFp2F_A%;lNq^}O$|cY!E5ZSAVtb3x)kdd&sHEr@YiC|GX_=eh>DVlD$V-+rDa znxc8v%XfW|H2zOw^4$8v736jdAdG1E8H;vIUx;lZLD{*~%I-;JBKktlZ>MvHYZMY+oUHIq)f1+%%k!(dk4h{UG;T$}A^i8qmcr+t!b09TDE&hIr)t57Fk5-8^=qi|DLNqV{t# zCK-<4t_y(2CRyJ$Zl;>8FjqX5K88-j0i!^7@FXB#&xaZlX#FhS&p#*ZaTw+E#2sq6 zox?7P@z+?@tLn1=mDKDj@_4sEy_pk+9~DX5KgQAJnF6Hfd()7=$7Vl?&7+MwMTbR3 z9GM|96F9Dmwz={BfV4aUNegJ)6q?j{#ODy@id6GAVe3=4GR{B>7>Sn)oA?gojfhTIO2pwAvn26S-BXq{fQ9iv9yHW9Qj z*lW-P)DLtb%fp_7ZNLQx1efTaMABWPYrPLfUGK)I+yI`RkoIm)j3#`hfo zqNgjs$%k42m;Wd7}MJh zWcNQru8CKOQn?eKj0viB0$t@N3#p{vjzTwY)Zg;kvA8*Gu|;bG@vTDOx*xBKI-wvP zhM8McbT;79$#3rgy^zguU(?T*3oihjqv|ke3dHG{*m*D+WOjJZ@NJwJaM0h$GCa}>~q{;9;pC(pJGUm(RBfZ_}V*f_za47 znIGs}b-u%L_yW)GjvWDiheye)5|4OU{H`@_I|rK^_zT%n82*K8&Uu9!urk1% zBx7~<&Zf-kT+FceO7O1(E7u%F|{@k+>ok2wbo;H-fSj zzbV4jqX#u@_u5%CI?cv`8`xY7AlJPzQ_}B;lO4!$P}Lvy>D)sRY9yHA^=$MF0lL`? zC@AaFM${K&qs3-HOX*km7RKt^xv_0HCk84(PkT6i#Z}#{3f9wQU?snc zq_v9DT(r1*U&L0#bROU?umHntZDeq|O^r%)jZjQyZ323NdJjeTJrUjRBgDJ;qX1*` zuonba;O4FoeO@FAVw*W47H1lPYek=q$ogF-M31v*`;YiXdT3UpPnm#RvGGUFNobfSsE z$S>Bsb_j}|?j!aFKya9|ame~$l1df72G7?fkq3`*7^?|%0EGE$KDSU~OejFcvZQ^q z?W)5lwXE-Bj;C$NBj-fGZ?#x#5W(HEP@)^a)(D^b9AzjQ0R+|RD|o)v_~ptd&=n$1 z@GfAxpSY%WTyr4W_bByE`m(DIcf{+qY?c{x=Te$c%%U9jPSG+#d<{yz&q8);KhPa^ z^1L34fW_KGtBO8hs_B$4;bg3Rho!W1NV5PC^+5h%LmFgyD`3-}oH7S^VNF3E@lOHW zJSnFoda6KI%h4RX`N6ea??)fg;Bw{|G`>E4d?%v#aPDK-X?&DnLK3S} zb!X18n{ZnirV1*0Lzl(C?WapjV4O1|{NfU9>W2q(5li2zku=a#1iGsJ!MZ}e81CK= z0qLZ6yAED&(sLE;^+@nipUvi90N!Fg_{wHgRbIVVH) z*cZI(YH~HqY=^pi3K)A@pV(6osRLCVe6MZ=I7TUXu_l_Mp;;+M5P@IGaagZoiE z1*b3?!Iz&vH6Dm3&ucZ)AEydCVY2;7fcwYCJW8^6nI z5tme+S;EFg^9bH02*^^#mw zH6=|?4MIIT%xUQEkkS6fLa~;p1 zZ5~ntb!{<<2_e)A4cnO=im!W8^%sj`< z5o2~|SruG$n}DBB^gn0xb+2&=a5a$cn4Q>as^e}_lh>Xb2)XmG8o&=#YnNOGo!ts| zbb_2YO_ie0FmWv;d9J8kkVzk%jEH6}anI`?1Uj^dv{}VsEe-Tkfv${?u!}jvr)PxX zp6@>cbahCK%TD3m@+JMfD?J(o0xi@@Q?P;;38tYthhn6!aD)(y*rWNM0 zYvWm6jnz;?g8Aynaj6_d*WHdIAyV)I=mmuwD)v*VDh0TT+QT*|-$K}az_yx!P%-|1 zCBGTZ(E_yJ4d`eCpiBEf)wfncF#td_07?DPHjiSSs0EDkGa8Aw*6@FlQJ0O(^1 zG0g;Hb`{I8LxZSTBiF82F8^J$YVS-3(E>7YDu&Ib4%YEnwF1tf?75q&=qslazv^Bu z(23q}+>mmt#)AN$XZ-y0K)?LV;WxG!v(pkiWuS))wyl!~;6{4&=5OggUalc!rhO#q<;y#|}HMX_~GLJckZM#~vRN*REcJ_&Mgi z+HCI^K_Zx5`3(p6_}XM)V<@)h7df5~lj!K3-@LR!r1>Usz+veOq~e^IULY%KYQz!1 z-XSYm2>c}Eg+}kSj?^A9eHcIowgKCLF7T9!r&HGENUx`>Wsv0uJL+{`ZW`#Z@x8l< z8Mu4+y1TTr^2dF^5a5FRA+@%S=N=WWNDz4LI&kUV$KH&ysgH|$3ZEGi=J9u@X578GNzm#M&@VJ=M&;Q)FkcG>E&pSn=^R0pF zxwcjDSz|4j&_dS(x~6f7t&uftpcEuw@S83FHeX0d_4$f-7f88FQoTTWlcY1tv z9<@xMvC=frl;bg~r^{4R1^RxE5Z`o*rnqJd>y}b`RJZImzJDl9aFYWa=w1}$V$gz$ z+P`O}m3n5pDb^WC_ES$i8owENKqn9;gCesgEm$JZaTT8W#!ZJsc6I*2ukPW3#I|J? zo6_7X_^O^Ll5T8vAzy`Z7WEj$2x%KU*QXK3bc{Rj+2$z6+ky1XiK^~7V3YI!FV}B{ z@U?lMD7=BlW`pxlq8BrYs{0>AbeY*TjYYEq#}VYoLnP-v=T@CXlYH*|#Py<(q9t(I zf7OaVOq&DUu#=*kk9U5;dKKLxz)TACgx@uN*_u8-h*ViO^WeU^?WPR$s=n=dEeWDx z8PqUV7_F(+zA-zcfu1VR-?XC%2+2ez*X8?UuiP!eVnp|pimuuF$bt4C=>IigL3R1~ z?MoEf2LSm*oeRUiaHxG@W&vh-By20uI&AsJC&P%~62Ej~%+6e{VYI=!vMwhbIKRlO zW2csY@~=UpZ7iP9G3jd>q=1uQ72z;U&=VL!ZVfIo`Uu=mCfBOjo8ZZB17E>}nX8~F z+<^8|=fJ;q2P(8lE2uJKTY?JoO`ak)pU9^oeol}i-U@>)QQBWsy;dk>#+@Sf(hbMq zdy!FcL=7sglLGDmE{^N{^H=$Nkbanl8Dl0pFqyL@!yZ-=FW$JE-c3j-u!_UNZ*Qy$I7lkBuK_xQ>SaHN;@P zm!JOd)2|@7Ok8RgZ>Lui{%sJ@6W;~eq|L8?c9A16oPzBa1v+0Ng&o((`FgBTq+fr~ zAeUv(d*FyL;?!6;$deny{^eep`azfh)2r}XYnr&WL~pWIFwYsy!NX z$?Bgmd+jOUfY=Z2@KgLqa=R$dA(_Q^gl~_VQJ{B*3v9-mLW~3huAdk6>ekoQLK9iC z5$}tch3v{T;_Bigm%J>xF~k_`zut`fC48Mx6_OvS{K0fsI4WsPm+C>>GMDqlneM(s z-(<1(*jwlr1g1D`%-S}52d1%t@`nj@zG*p@OLx!Ab5E{)eKW!A;W|x6vu7IUDFR&y zv%1R4gd&TKC64V}&8z%)9?+s{aqXK@2YTHDR+FTuAu?(I=`geE_2$NY2QgexzOGYj zRU|B2sGSWSu3{Al_A1{YD%$ZAOWsF=WY`6`Uqh((#!OFB%)N&ha$y$!DS%CihvTtW zHojX0K(F9GNCUV5ZAbVagHfQXkY~@}WAm|R%19tmg_e~L`&Hq4lYUJ&;>@ukcUA2$ z3-1kbc&2RA-858LpEMD=l2Mm8j)hsbm1wH^@0sZNog=sn*inCnALynXF5S@#A_qzw zZDw6S=O3K+e8&Ue*fXeUqy*fC0v&iaVGp^O_5RIW1z5ZkWf!V_9LTBr{WQ>{W2D<6 zqxOdd)NA5r3z~S-(tA4&H`%5>e4vYtsgPm~bOjkbE~g4~uJVf4!iT==mxOvscGFDA zzRHV2(Ewk)J5 z-UBSX^3*RsN>~yN&q4-S6nH@X3Isc(S1Y2Jy7}$5TwYl;+iG7d%m@B0A06jc1nlU( z6xrBXzS$azs!F24U*UppGXV?-)#J8!WFk2F1o0!gu$$;W(yT~(9U2D7y>Sz4McR)D zA39gniJZR?vH+fh9M@yuq`M)jq>%^ouiyrr2>hIB*I?xg6=piB#etu~b#84raRk!Bh4H{mtJ(ozb zrq)<70_tr{AH$U!t1~_ffvN7ru+;Y~zO#t(H|t;rqC(y~={*sdSSkA}#MOgbtr9NB zX7iwEt{pPX@cn?i0#=nDCWj@0V1;nP5mjuEterq-lD zhvHF@(`N2HmffUz2t2cT{b;Xyp{Z`PE1HT95Bl1|D}`PvdcBJZ$QtRPqn#8bY0(Q1 zwBMaIN>#1crWW8rRSx$8L`pR^)R z4Ft%eXyc6Io6Bl&+Gp{%SA!r2pnnS1cr$)OU&0NXgjL-KY-n?w1f{U2z}?Bhi^12a z>GKM4ZYvDu>W`9G`kK=G8K9ty-fVbcBY$N+PL%w3D_04r0dxq3Eqd|;@TkeEZ({3s zM9PHu$0`ajRZ+OuA12U&H`j@beS3PdePUOE%)t8qI*~iDU8Js&26}WHWA&GWCj&Zo zps^1ib0gX%Er;LglrNF`MoK_eeCrYa31vKX$w^#XweST)z}ul`-hLq&&@mt#7_-hV z(V+?8s$;(zp_fD>@1n+(dq!pf4<1$8)IuYR4UXs*bDs zJY=9xT#)_23qh_vsTdK3(tBOGFQ6Z1M~GU-`c4B~%oG1J(eQh(A8b%&P0MQc;?r0U zqWihx)f&$5+V_E^rLt%}f4p=Nav7MGpmt5R*!-^@{Ad`qc9PV1P{6-khLkdD**>y0 zzCXOP8S6q^E98l3OysoigMJM)*D(HK7FN0U!m#~(j?qY@br-&9_eC6z`gi#WjvD+k z1^krYIzXUX%#1*sAL`AEAkbZj%oUCK$@JU&GN@zZ@H1CS${4%_xQikCz$2wYr613kfC4guU<2X?}2{BQau9Y$0JdbEZE^5`hyp$1?sM!UZAqZ#$PKhBj-Siw-)- zuS5p3m?nNdKzH9HBgegY0P;pDB-GRgbS~naJPY1-Emposq9LO$v&%5QEarsgdTP5| z9mEWLEJ)tXGz1+IKW5fG?7^nw=ZWdEWv0&+u=TJS?E| zc_^e9dS|TS!f(^N?nX@{y5&D8%2kaVa2fT}K(9x2&oyG<)&~ZNao{Pn>}wUCJLT)Yz(Pm>^dU+%zTq_=SB1>-iqvQVJY? z-Xr{#mV7$`8@&y`lC4CRv!QMXsI|{p{Iih)Xam>6ak$KjEGLpGk!w{#^^O#Ms_POk zw+7IzcU;xkG%q$&WFNVu9we)eR+%iG9?G?^Y;)R>k2Tz~q?$mFJqHyUWvcz=??wh9$CM-m=CeT6HhPiY+@a>~=4WL6JucF?( z?6+na7iLaQClu*AhhBh;xq$l@gu05yp#83HxPTvZM(1;YNKF9M?02qX>kGh}{5_X2 zC-{lK<0r~FTxmfzB86H-4AH7d8YSlH}pGLBm_9q6D>i@k@8W`(zpxR%pfUz`xkA#+#X!KicP}$10lt zII6b3l`uM3%&UELHAo2=d7H>%7@NXl-pB`MyVTp=W5&XkLw@5wmC(mIj+-)8$lm5h zeTs$6Oum;k?Y6iY&Z$p~f) zoii&&8J)NeQUSDSAVWqN_9GghlwY!uGyH6`VL>J2@15uW_n{1xw6oGhE%gIk)uhkk zcHoDDb05&%H(>2i%WCu4*{;1scj7u*rPc>@7&7umUweMR9cETw6sUHf1E~dbS`2pW zL!TOpl6_Yz+i)D;_ezR-xU49xA$R3PDBU{&DR9p405}qsEJBmGZF+U_mcl(m?r64$B7(UY$Q9zVtys|j>&IgNgMk{Tkl0$o9ldf0Zy>{)OK zIX|oi06OL&xIs8>hOBz2a{aby1qF9acAAF@bcOuP`q#CV(m)q0o~Y0MM}Y3wSWoKM zwrw0b*<;+M5NTMW=9)kU8W~UowcJjhZ>iwwv&R>h1n3++g%F!M^mT@u7`#EfcH~mX zmM`(m!?_Ovq6-_>?|VPvHE%SZ10zHxT_AIYA8|S?vJM=zj=7lscmwijnsQq^!dTfC zgv{obwU&^5CN&Q6uf4|)vx-{;T}^(nOjw@#!7pwt2x!pAxfGdiOzShQ^Fmx;xqZN_2*S z3Bx?prsv>CbuFJD6^JVNnM?i=pcB%Gbq%F~ULVk95^D2L09`D+gd>W&E3g1L?#ll9 zeQ2Y1>q2yWK#!7B!$$|M-+G1`X7cNBWevPR*@4G4`z1PvbgrfcN8|AnG@us;lx0uKMQ@ zML)$s{imu1`@*G6;8J-8%PXXnayxBBnnq7dK$VK_ga>v_nklJJp{ z<9;o|h3mL6F(1$kpOcPl`KXJGOiRAj!$jA1XBSc+OLZLEK^40E*8+(vpaC#tzv#$B z*J88kd%V=%ComhncmO1sw}g$MGa@7ogw>|Ll7~FU9}Y1Dc-O9lAO= zQM;ONOc1T6Y|2Li)mjGTHi-Y{bO8*DDds0 zsXWU29Ackl*?JwiVH)V}RB7>UuBn;_+H_xh9mTVPT^WeSJ6-Q%j{6n7 z)bkcDu(81+trh4r!bS0Oe`szQh$q*9u;GP;C$O4?c@#8dv%yJ>xm)T?W>MkT+o=SV z5D6TGiaE0i1nn|t7|PD`>#5@3|Cx~G%r;(=)eQb}TZJsz@U*H&Uo8OV(huB#}|16P&+y0M^BJ~|FH4a)#FFXb0l2n?Aqpo4I~ z`rGDVbr9o%Dy@^%)45S@cs{!%&!t{99d5P6gkbyVlixlurW&7DJQrZibN_QduNXqK zG|=k-dM^1lfi5COu;6Udt{A;w|5w|pfo+(GVt1u(0@}of>v0t589nFto&JeHXTU#h z(DJVvY5rtOF1ls@<-zCpDn@Y!Wv8ZjW&rTVV~6lD7hHnK@L|}EB+|!Wg(YlGbFQeq zVc90@D-(UT8DUp+U7khRDoK?MW(`%vB-} zLR6))S0(I+5Nw{qB5r{lEAIt$cy4Mg3C>&R=@#P7(AQ|#MMoc3;r-g1T4>b;+uynh z(wH%yKcm4w2fu1j$KkJZ($V*?VREnly8qeyr+}WHI6LRx8ySh6AnBU90vi7ROD!3uS?`y3_ zIMAu2kpl)Tw&_F~x zX8qp-dd?MJp-vj;war!Ie+B6N#pGu{@kX1r^D_t%lS2m?$X-!pjntXz7$t=C7F@r< z3(7Fd%f#w!!)q553qx@`{KDD*HZ!dDH$J$Vg~~h1J$_;4a0qhiq?)KrN4cflb9#q> zFJg%8I4s;&(MaG9H`9Lz60+7X?S- zC<`$BK(DV74fi+)w-U#$Xt{Oz0F8u5P!GlmkrSc*F9F?_)6Tehfv#5Gr$oR1O`#SK zPyBUI6BJV;!Xj5*{<1@FxKsrd(}nk8LSJ%myQ5Y&XcpW<}>TkRK%fn9bN9ZLN zKrd)F8eIFLR8`>IWW_ty=i|M56X0`qLxuOSk9SAf*&DR;8$1)k_Y*IvQ;J{Bg}eAB~uyet81@9Ih!`iaCRy>zm=hc^fVmnFyB@V zT816D26}rK{abm}AtK3ghw+wIq4M?%G7$n@A-%J0Fw9Mt0UI}|@aY@Xs@nis(X>Q~ zu4im*iR|xq<7SQ7ukX3gi^tx7aZ-S2(fT$RT3vJguK>LX-K3_09;h!fZihi#-UzWE zJO~>Nh3bQhq(@DBjX6I&ll{hdMb?EoUdM!te5~eTZW^CkgzNSs8;5t3m=;uaQ zk*?lm;d8p)mV;Z;_-7}O46X-nlY1ALg(dk4sRX_FXEmf>zepiEHdQ#bj)20>cOJ^} z2Ili?4?x>0GH@N=SkR|nGqh^BT>oL=`NW_W(UC9%k`W&H=wvEjhG7G-ljTI)pz_%% zYxUutMyW&XejRQN`7Q=tWf=>aU^xdR%*#)`AS5wEX7jkMO9$k!D$G;eJypofY;0Za{`mzdV8 zizU90WJwovQhagUn8>^qFJWU;FMimNqLW?ip%0PC<_rS~H-tmhUJ+EuE6g@CiPG4l z;Xk0qn$d+k6{%>e5!+!JdE1~TNN7H##!o?IhQl}5&d?RLj1`#?^A`oOa{BGHEN0rk z?|PeHhcjJL^j%Lv@(u#sghsL)?FUATQ9W_*ZERT8rt-DFVcf4(rk#o%E`}(L!*2B~ zd~j~N54Q0`NkNj*_|E`6h|D1x5Z5Biq0WKG+Q<&;e>wa+>zwww*9UY>@75CQ2RqDY zy0%^0R_#XvHB{KavteYsz>wL3A(8YKSoF@WZfvj~& zCLxvRw_lz}p-pfi&{1DDN{2L-+(=e6EGISidf$jh?SXh#`%YNCs%pc_&4|qbH%8_v zz^{-DJAy;3Tg0T_Xru)*hR7t7*#pQL#%7ZalujXJ6|-&<^&(?)2+3c>arGNF`ukVG zO%-<1A!qe=nZxBPm)Nt`>fVjXovwfYHw7srw;>{S@sQh+Mj)xi4|I5nI_cf?vA>}G zI;)-fsm8oAG)3$~9V`F1-bD!_>2?EP`(Qv%QRxSD2cCzd20IOStAxmk2%Bu{|M5qaZQopRZjovJ9|AhozX3^x4S8=SRBo2dd9(Xh zt0kf)joZfk4&+eKWCqvF?r~4L>81X2zzHm)gdLc@S@0Bsna?F8>GTeYN9u6N%lhPU zpmPnf>!}EO!(QZ?a$p@O+=FGZxq`8)8fjKU3k&3zE7(kVrD3&I2RQ6AbvHj-F8R68 zpiPLnj-Tt`23>n(krgRqqrZnJV(?AWo4Fyd^mst#YH5&bsW;mjw8WLTpt?JD-@ygg z&j}oNa=hyPbi4LILE|{4(*U3|w(-idUp}G(Ev8rsKx~~l)b9uAF)b`LppWd|^layE zPv_-TL6{GFc0oh{U8y$94yJ)#571?q9gd2YJ z=<97mDK(^?*fh1Qst4N<;yvcx%SBs0+0(25Slne~UIP9@3A%l&HAi$=DPyJ|D`u9v zlTi=p2F9o9rJKhI*y}o}hOG18>bdB|Fd&J(DjU^EA{_%?Av114ecM#veVwP0_58KR zxbU`(!O8&Bd5<(+fs^*6OQR3U3jx?gBE5!uF1FxA>k~ft$wWB ztT3_ti8<{y7vicCc%n1{3{P*#x~jj)e=2@KR-P$j8wZh_PGKG)w%L&!XU6CHD~8bs z^4ix+>-ncfl998RUACNP*TdW#aegO2xw1}dIfbKNhnzEz@V$FN)jExc<;<1T(N8TA zDXzqIFalP|xSm|0_xfaZJ)3N(s&T>Ps$xNyECk=~~m9YTUX zm}~=S#Y{zJk#^*L<^-fwtdQu>Fl)A^w&YUv4MH{{)z&S(ywyPmO+4$O&ilA#0-Yps zhgLvvfC{G}b&C7k27HLrV38%jHz2MGeEjnGc-yBgpyP(TsLk-7ACVM@jr)6U{6{4^ zUOq>5HUBp-uS2u!p*`AUwnsg~VG&0(>_A39N|W4ByhLA+w$bYadK1>DPKl1RYW#CS zmlQ_Dv=Jy2gIq0L*C+kBes+(cIqiR__?LjrM5ZcNM@>PZz)JRh{b@$7lnm)npnL8s z_)PP0>->4~LY=38ygP@#;37xSxjDdrv2XFH5;yh6`6OS_xqi8aIuT~hS;pt&SN{3e zh~C&?MV-iWleSZ5GGibySUd8aJxhCm70x9Y+=QuLzrLH}d_w0uhTaO(NDb(D@2qXoTNBZ61qEvi zAOBgPcNx(5jn0)vJGMGwhjEV+sl_&gGpYMbp&r($)g+8b^sDLWwfcarHVb!E>lpq; z5cj<#L)$Q>$^6dmKbf_qj2hT?SOnv3Zf2s(TJ$BLUe5VHIZQiT(sIPkPS~7P^Z;>F zLTg#Zn-0GU>~oMI<4-NI&Ap5BF@_t&P~P^@(7VK;Hgo>QK+pGE;Ma<-T<(9uZ*(qE zM?|2CjoQ<+Wh~NIof!U{WYH|8m&LA;H<@!o?Z6G?9g;k0k!jhbOEgU#n8%d_t{PnF z#O)4X$ZE0_&P|ya#-`O5_P^kQ(DR!Def7wXUabn#By;I)R*?2;di$U;>YeOwt|@xm z1%dbHSo1bfK1ooMBMUA{zJ~@RS;Q!au!6LaO`6;~((`ot%*1Q1D~Ma40O4v;It8{q zpp(X|@k0VS0q+%P_cE-+j82U@x9y&ldAW=uJmO$aK&bNuRm}LuML(`?=sL>IywvmO zM>TQDz6-ChR{2uVI(&ZFa^e>nrWCyMvEXn5N1xs}51E%Ec6jsv0$H~2192ofOO()5 zt_7Tx^(oA}Nrp1x``{s(t!EkS)K+G9=^bYk`QEl$X=E=mCaPp!IXAx#0sz*Ou&`ah zDh6vr;u9!mWHPTUGXLS?w~vV8te7^UXv4nwZJL+zR&$dxMO4CJg*e^i?cbk2U>E>V zk?JM$s0HYCfj{mmd?UfKRbccdlBP*|D5Kf!p`Bko-To?=+7*xtVK_-1Sc8Bb_ZqX( z&bWGk{AW_CLgjQvWA_Ie`7~9gLNImoRI^W(MM^-DvF*~mlZ`!md(}n z#^)%t7+rB*4T3Y^<{4-v?B=td{ACzNK7W9sn<4;x`K>$~n$$Rkry3T~cAfF9a)cfjn~BNk+ys=(b5vvzDZ;nD#vof2V+M;^9BXD_6IUJuaq zg+@w1Ph~`R_9X6{#N%o@IseGxe|GNPqHi0=Cgc7$J}aVvoNqfSlsY%?cRgay96NhfNu#SpN(Kw z2UhimtZQT?IOH#_CfYj2F7+l;7<=?Mvz{2p7@5t!Q%puaXXB-(oQ(z5(;WM*a;+?4 zE*dN=(s!7ja4!RbefsXhvmh`J#2BpX+?U&g5EdII-+)$cKUrqcgmPOXsis(jXMm4^ zMauHFZf{DWovq@FNgMP`WsSIjN(@_KAPkc6AfH&(k!)KX*5U3?pMUpi$IRk-ACl)h ztL^>TfL{M#ooc_WG|&amJO4XC=ORYZIb?KM)vJ|ZUp0DhVcWUKuC#`{E(^LKKpY5G zFZjM~YN!6t>jpZ~o`#v#_odm*x}cB9UBPO6HXTud)s1_cppGHhLc4V7=7Puh0uRbs zkmU9#!rUx&r5V(GUtyMEEtBLv%*+Y)D`hK`A?!36&6dqJdkmxpwM^?q{zY@Ba=MWH ztXwN+;i@r2-E{#jZPpQJrlM@aHK`ohvtw2cxLX|u{j5g4 zt+)R%pqpu+*9&yglS%&y&^6CH2F%3puZEmNqwl^2k=16E4HFpd$?KXG<;Wv{HHCkbP@J=s0dlsQAl7ku|Rv73;YHixOb z^*G4QkyBwu3sVkt`{)N)CJXy8I=7m&n-Z}-Z8d>AAC(`IwmzNx(tHTr4)+M|6BE(#-6jRmR*-+_^yf|@Sv)xQCB6MuMg<4#xa;}%HdNoYC(^t zyApto(hQS2G}3S3>4@in=W>%;kG!vY|~_&&REIa*No2FA9xTWJ#%My%QvZS}~iMeV2oKpu^Wp7~B@ixf#+h z=?$yLltD9BxMjrDaUBnSpi@?y`P83Fs!=JCRWH5ip#VKds+VOnxi#~#ti1L>I1Bw+ z8FZnfrXZB(P>;Ypn8)yCGNO7<6xYx=MqQJ_M$~>+Nn3lT)BgUM;!ysZT zk!D%wQCQVWBVC^5KRy}MU$)uGE~BkAUClYYoh$w6>~Zvo_l=)_W|?Y^y(O@`ILx{e za<`OGdhRaVThlhwMs``_;zyg^{8r$>{bK%(#EXVnb>X_8PGs+AZ5yv9HA05|P0Rn9 z_#O0bq|a9{wyo=eS{v+b?Eg;WMqOVVTDh)UtI=ibzhfB2{@NFA8tDI3KqqRDXo>{- zy*}{AuXeWk?)Pq6svs}S4-mh{&R6H9%Js60tILPg)$Ck^OYYex$;q_-%6~&w69uYfN z?zg=2{s-Sn!l78JCYB87sHy}Yky*w>b4+fLWHPeJ<9lYeeWq__n1xL<;&x6plDotI zuMNYPod){<2+#vu#K~^8lNwS~T>(I-O5^^29DZ!-$;>-Q$7IBjKsE&Epb9u>Z<_SX z>Dk{5%Jo81s)D&)_~Wp_J1#Q^b{1+_5xZ#Jk`U|x$KP^H$FV=`P2PQnv02x0m$KIR z!&%!5Hnbh8AMm;TjKG-h3g$(2;1>&X4aC3#TR8h7n~IQzrXQ$}Gv6Gp;p z=tap)#|&F>O)LK|5B}IX*S>PnK>x1-x(vLDl7u}|kSdW|kh)+^!ZpvgfeDW^JNw6Jd&cXKh6q=`oABmgX@+V$s87Gekx2|5}N4;R`Z?fBniML}}i( z1Uf)5yUopNRTqqO^ImzUm^qjZ!;ND9HMd{)X_MoG>b$rl2Qjf4LB#Xkl&bXW1pM<5};F)Ri=SnAJF@@{I3AIa45x`OUV{>%%iV1 zTlxB)%5{Bn&X}Ts5EoM5HiGnTk@jYy7;ino^0u41$`9upZaMd@J2U8>@5~Q3 zg{_m?lFJU=xJHq;b)JRYP|w_24Mjs7xzgE}N5Q^R0l15}jE;^S{_B}`PwXaM=NjL0 zicSD9-vj*$Tr1}Ac^~Kv@v(UscZat7u1))~%tddsus>d_iEq|u{+9rq&r-WI(CY!Z zviI2k9MFRR8%2Q(J)Pt}I^gc~9_?CAZfSvT4t+|56bDftB1E+TU9^Uy4jXl4=ehZDpPC}SuxaJE*+Zwk+8(&7iXa9D`81}d!o*Q{!~p(Z33MY3 z^m>6#%AQjH*MQCi8#>cexA`9)076#H`)7ai~0k7s*d_>kSm8ojt;e~YQJOMfwL zIzOHHt5Y!>eEyhCpBqUU_hAs4ntPid$K{0VHYOytmRX(#VjDT@7Ir9*Mb#>akDK|P z6GwVA`p`k7%e$I2etzcG$t~t^RRydOsA>_Jg*K9_v4nU-8tDH^qs}r_mi<2`(M6v! z)g@xVM&Ua8$4RcHAgzfW)Sv$GZoAIeE&E;$vsxv(i*$Gis@(xO#Vz0aw3Cc(co}Q7 z9=SCcU`d%Z>hM6FG;6_F#mwrbSn;m6O1>#=8}3ZI_hg?>Joe^0;gwZY&2E>oO9S-A zea#AHw%RVim7V|cr80xM_1F&ZKpuRu-N*e176joI#qEYb!d&=%Q=abd)7tJw^YYHX zw}BPfG;J3E(dfKj|FWads0--vv+;j_@QX|XJr$t;w~U5tMD^P7(N8JL3qLlyxwhRq zt*&f@RTBX>n{BxC6Yw`RM8`vp7vyhqjA^a1cMby6Kv5-*_lzE6ktvxSyb+W;JZT!! z1~e|VzIvllQ`gf&ZXXex?EuSfU_2pJAXT5Xu(08R-J4?g+_x*B) zStZ|%fpXX1#`4353z6Kmc*>4nnspJ>X*xOsG*R=blAuI_z#yeJ?)uFul`p@!_i6+q z1fb=MCaetyN1ag!mYhNM|LRBsJq`4ffG%P6nhv!i(12WVZg-K$wGOCaIX zfjGO!#5HY;^1pz+>ypW=v%{W3T-|$s;iIy;R*D@>ziCmrg0%RKK|AQk9^tyo#KVjxNxV0sCK~{BH)__3+@?QgL z^&?$x@2~v&*p<-;bY_M<#U8N7$JGVhZ*PLS`z6!&avl6o&+FYw%G$N~>txP}($agU zT2Gv_XzrG)^M_ZlV>frdd*jtbP@u=Es`9$u{85u-QZ1to0eD%!XWrqfW^KDa)n@D! ztU)!n+%{~eUIl+VWrA*-8KRrT{f#ux{|Cqa3ef+Fk?4d}>lvha^CL}vschRVFVjKc z8V2SR4AvQJ?7DU0Usg5Ipl6KI_7&g0WlUSR?3)pzfQXf5 zP5tue-N0imlK=^-n$)~gv-zKQ{k4Ee-TE z&>tA+dgN;REZ@la|7>Jt!r!s`&Z=j$YSjw<%F1b#)v8UKoU9gECnvYcY@e0WjUQ-A ztIV8^ZE_aCQ9Jg{Y;hs4%>j_o957DHoL4K4yx+NVc4har?XriqZQHqX=e3oy_isI1 z*>mmC>@VLxJbP%{!`ZVtA6c6?4*vtAUBYO~N4x*hF?->ioHWqu0Xku3g!+d0|JiVP zTB7$&>lu#Yz+W7`5O6aiPz3KlYjKkmvO@kcm)Fx;9@{Z==r=tk?`U(P)De<0^23V0 zjFslJ=+k}Z&bytOYdX<^LPkPPHc$m1flro!b1`u!|AFzJI?q2b$gsQ?X`t5wbfwlF z=;@Jc7$QejsM|=(Y$GKV8=uvFZRIO>o6Y0;{pN4lw!ag(`q`T;PXQqY0R7aJS)+$k ze(?O!DPd-oL(*(kUW?A1pKm(gn&8e7J(6_HfJ+$lItUv){*%VhKR+}jCo2u~dVsD$ zt!12q`~Pbs_Ij^R13;w*inXap&5H+*&23w`xalJs_(bMIW6%x#yT3M;OZut>pDx}} zl#_X2^r=GZhFaRPct?+W=BlUOke1(Wmv;cD)(l!=aNWQ%&P?92^t;XxwZEGNx_H25;==#`Z}{&UIBKBH0E-yNERWPt4#j5hf_`Om%Wj_>KGOK< z>-jnoO~EXJQ?Aq5@3P8FaIUp~{^Nn!rOxnnXEIOa6c&|tEM0V<=+5tbi$<(}t0+>` zX6Dm;OZaj6`>l#87RulT1F7_;VHsikXKJUGrQaR;?abII2QTE^yV~l|!M!uLupt9?{?3*D zjgtqD1iG5@ohm<@A{ZyJpQw%DH7uXuw!xVzC#QBl^2W*;K~ZQPM22ip>7pyzf3*~T zs3Q&Z|6hULu>0`ex8O+!mMH7ql*v;o+xBnV6&YJp(ZrNs=M+T{LCgIbxBK<7g;k+k z6+iIg&1HnVc$CrNw*9|jS+5jLFItzm=w6$=_FrG-ww zf+XVl8;?CR%ETsR41IUdZr(H;({ft~SFn;PZH^9qe*4M+F9bty5poDQFw#KBkp_Ay zKsVDs_uY41%Qw3Zy>++oK+&@aY36|dM#a<^=o1USa$%k^eR$3x!^>l1?44UPIO?tq zsj!UV%6C61W9{a%*$0Od?|AF4Zhhun&H4S{l!a!Sr=K-g-;c@W?$ekRrpDgkU4g+K zguB}8`QNTog-xJ;u?#GL7bJFQG>G3g>>bBk)pEfnv)4B1^nF8tUgzikn>UR#&{F_9 zbN71A81~@2QHLzE_8n@4wm~uaa|_ zX`lz{jia;wWuTkXL3>+-#7rt05n2vwpV_9}+QS($CPBC20IuHG|t>e)ATLz9Ps#d{&UZTw)Z-(SK9ni zKJ&z9(>k#&UmbMb2{swc>@(AI1Nz4ckllis<$ZSc1MPt;3qfch@x@QGyB#u_>)@~J zW=(!6(8YA(VL*>VMUvGSw?1oA z1upfl1wEAcUSTogVvC)}p%(%PKJgoL12$VWQ-%$#VC8owO>xG}r`eMaWM6u3UALLE zSLCa*cLtkVMjm9RW~gh+4YRm1muLkyPMAPWTWFZ~KKY=x>Qc?Bil*yo*Xd8S8f7~s zX!5n(s`wumDlG#EC{WL^PG#mT?fJ@$yEBdl0@#p+8y)-}l>bqnD}=q026{a}S6Z6% ze;Mf1yu5dE+aAw<)pQ=mvK$0|IoD<-Ma7Uc^0)-Su?B8zQnP=!s?Pi6{RM}h9Wi4S zVNibr7n_x{f1V`C0Zr9*4KHCvl^NdARU?b5Z1!gFPNn9WF|5^kqt~7HI%ZGld8PBQ z%8WzcTieoc}f7e5&61LeLy3NK2edp z>Ri;n*p8@@HAQ(kRLfH|SL}#EnVr?@Slh$1JNfXopYPWt~QLz>bcv3svt%%uShuK{HC_eW0 zCWQ-hnIk?%2)X%*_xmow`xdN^rl6wsJu!d6PqLq3jB4L)>d>KU)^Ez?hm@bw&|RP#|8+o*L=2>7voY|@3Wampx!gYQ!_O-_b#0=_ zIzpJsXf0U+XfmLK`VPNHz%fH|JA64}Z=pDuONAar?>9fsnH}r*VLONBL<$UUg-zUz z@~x{?vTZ4|Sl{!c4`bt+Poy`dJB!z`< z2wj#$l-|f}b@Z{%f4QA8Qt(Ji(A-u-r=6s`q5A)xkp}wzCeXpEwOEPGY?I}*`Tf0x ze}2_}8^BuO;z&X{s47Si6-*iE8nV7|#s1p3%3~KHnB}U=mW{#_lwzZ#?4{|CYM|qz zZ~o(#kzIzdzuIo#5a|xh9J1wM&l&7f(#l$~Z&B6ms?3bY%DleK*f&d!ZKthok6$%^ z2t9Iu18tsC-8~%UJ66k`physT@hQ=jS=89f`RwE7iWU+bT`>>dC8>Ym?khVEhQ;>M zK%hIgQ<-qlTzOzvn`6<)y_}A}?O)r!)6=q)5A(riLjJd*n+AFs=#1UToIJI1_7m$n zC=gRpuoMJMTkkG8YN1!CqRA-(T_J&i8I>!>L#YZ%JrnI_R2yJ$jXkIGM~+7bdGo`o zW44yqP-@Q11M_qFOW)k#Ul>0rwCn<-R@|+mVW&#Xxn)whW9*ROR$N+P3rJP8q}gZS1Cj{;+|b71y!zUje!}DWFDh z9*XQVFug5&&xW?bnK|8htUcVd|7IxeR1>4!^=661`=B_k6(Ci1Gu?9g?-`L3t^pXx zbr+3T?1@`H4&q@5X234{`zq)a(B0|uV({HBI|+9%BA;vuhn+w5!6wak!7T3m4BPc9 zBkdzn`2lSsd!em4XTw?3no~{Y^1FL;x2|>Si}`Si78XdTFF)O<9JnYf=+25fbSoBb zMrbPnN!NmE z8G}xeXl1M@4fYPli*%?4N5HE~o_MU|p@^4CR|5T%;N8qf$+83 zcPikoNOLI-8-*P-ZN3>{z4TqodQZOMyw|&|h-7l0GbxJ={EZH6J~8qvd5W=vMC%zb z>Am&*yEn@mt}ld(Du)rFF+VYxLf3bQ`HL$fZBSj=Nq zHImUQS>^8>*#v1bGUTa(f-QgiYZ=y@fK#l`b+|bFl`?3k@aC`}`IhesKg%=9jEVUJ zEH?5ieTmpiX~EQ|*v)x%Y461*>qMTk*ri3W03MI$&1D%4N5HYaM#x}eS z*>0bCtb2Cn#u<-FTmuPd$gXuC8}CCM%~+E((CY!ZT*>}*pj#$Aoin8S;q5DD><0d0 zOzU#pPrB$a$Q4&;i>_(+o0RRx$FLvwd^m+~EgWA?Id%w7BF_0})#GWI?<`s_IQbMg zK*%FQH@a+Z%ywQouaSHrH@-?aC>G5pWZT#LSc6G*rs)hKcbp;WDt6FDm4vH)aWC`|nyOKPb>4*B+|zY{yHoTh1@*8_CY_8$Uzn2M$%)PdqISjXV_0X}30&cfHs zU#)W9>io)A19qvkjQG}y_d|}L#~OvBUR6;fexEA3JLn1& zjOof3Yez$LDr~{UFKX8%pmEK4U@Oc~&H0{-{fS12d6TG97^@`NrrG5SX7ziVwF-1J zJ7usUZI4l?HKyzt())m8PE<(qz052$_i&{p(0@GUyVypHCfJWDNUF(_b&-f=JDx1% z*A!ugj;&b+JTzR52*U1Da}y&ZFl^<*U;8o)6gcj~FwByKROeJilxV}K*>o}SvpG4x zf4g>Zqek1XMLUw@y4E{%iqype&~yxLJoLnzugu12pw|cVkK&)%!@{|3LSInC1U3+I z)6K)}vtIk|^Bavit(L(Trh$h?{l|a~K{iPAhShbvS@x@!iYUs++N2xDtj%G2=XXdw zcTcCu$otS`ekO;Dh};|WhoQY8>`c0Rf^K6X>b#@QW(P=j z`_(`uyQ@()X&_^Z$*(N(DS2cOb5;%0d;iK+gQC0%VDP?Dj@dtExZ?+kTMnyhAD=dm z07K-uqCU;6t4HtdQ;}pYAe5e({s*oS1h4)4%A2G3BXGq#(puc-sL8XJR6{VCP<2M{ zJ@(1xJu~_@gX9~Sd%Rl3qtH+vdZk=&kJ&p7^!kAQf$@)c-AzpDFsQ@ve)Y=9scnzE zzJ3?>J-{4ubUOiS5|@<9KLm95v%%h77e9NN6>_CQK-x^QNJZi-Gwev4zpr6j9sS!P zo~4lObD4>ru}GLhbJSpspcV1QBCd0r?A|;s!gf~hqYPHb--ccKh4PtYHqp+R@2Rh{ zwq&o-om{o2>v?RV(z}Y4Y*0Qnir9$)Rci;WTZ_Mey0v|uKs$3V$wzHhAyJ0!fm*0w z+$9vtA`Q-RE7sYRXPZf=uWL1cF7`K=V1AH-{%5zgUj#^n(w_STdP)OTd@SXM+yVy+ z4D7P3%vZM_x%v2v%>=I(I?KrqU!r$sb-4c1Ko@8jK>rb-TX}6xcb@%uhm02xY%rfvpr^7}f@1~`?KTV8T1=ax6mVkt1UmEGGyGdPv1fnRu@pU@ zL;}m+3v=tk0Ttci$7*#}>>_IaE#Q@N*n9i9)T)F~++dyjVKe6@nZT8KvWc&23;`odMG*-em^7lEirrzv}+xxzhN} z#}8_ObExvfw<5-m$ArX5^Ujw8QKhWzCw0MB?k;Plqhq#^d8Uc*hv-K3^%Se z0~1DWG@3#hJKs&L&LME}7wDKTv;1f|#Y=ZEdKP^s2ZqdlLBr^_R|^y8myeq$Y1s#r zua1Hp!t%|?Lj!+Zn||VF?TZ(>t!sPu##jAA?w*McQH3tHxX&tBZlqvZa`NXNzYKb? zI#ya5=q}Kmlz<)q-!CMcf?{U7c(K5Fm6O?`d(U4QH<>3#PZF%ZD&m2G9$#&xLLmrh zhDz^@&!64vR&+6=4xk&>jg!H~@vv2`fL)lf0lo_kkt`WNv*;3d-xgDV$$PQ)=2)x0ygGUJ2 z%fEcNx0*k&J&3;WQ+$yJgCx5Yt6=%1nJkFkT(EyJ ziKzCWV0F5p4)}R^n=;UB(DZklhlTV803EpT!d!QWpx+=fr$zSX`)3T;T&=ow!jPS# zL@R65x~l4g#-~5CDh>4dfKEboN_5Xar-Bt@Ca@WmwP`VA=&fFNulI%!kL0<3F$)~L zYf`=8mWK@V5D0>Trxzd2DL0&G$MA$DmVYJw>SFXc7s9JSA(8(KbK@&Apcqjmj zeYPy0C;_;&`FCK~qvplG!NYvL7+}*&QnbA`Wh?c4qfNS9eS#U;+UpL>AepSCevQ%L z(t2ihRJAN-&lyH`U*HSQxcyZ0;^Xyc}4GbU6!0_u(88 zW$}irEknDa4pk@8J$r;(_Ra4e{%lLwph+B){}G`3c41)PWD!UgV9w~V-F9?;<>$x8 zG>71U29@-h>TY0l0iCp&Qpb8r16^Q~Fq#U`4QkJ6Ke_vn*%|$xmPi415*OBBK!Lp% zsgHrmNVwSQ9S;-e5|NufG5eWw7CNrMA>?2)A& zwONS`9a@ZwJ@+9E1;6WNebMh^vKH?ue2@EJBMA2!MAp7$w)MV7xSBqi=qnU&`r^}nj!{XSlL;kvA^sT%Bk0vc`r^g4$IjI9v>Pnw8=|_K z)Uj%x)?Gx`xAS+O>GGA zh?p2HDzRDFm7L$-K76B5QFN-#*2Ga zJV_*&+E7_e(Z68)u&Y z4Tnt*>gBc}t2u^Al-CUB4f3cHVdu%aMI~l=z8V+@mvk_|?`KmPa#wEr7;Ncba___C zAm4Dcv#URW>j89b(Xb(Sy9MOdP=h4^25)`*h$j1hH7YK25C`>y=M&UaO)Y3L^Rw|0 zjN)OYjdR}`eX2mO?YoIUhg(HiZy8PzGqTz|*K^^`^)og@N+8(s)ez{UZPhf;>jS#h z3YNcNw`p;#?b^egR*uy8b{SL^(fUtxD*b&!(QYYQ|tp$s%{l~m84!!I)8HN`Ys=?-@c zv=Ui|cM+fc6#t+S=QBuD(FjV>M&51v>O^Q$Bbv(n-vGMnPep=z8>l+MHmLZlV%3yq zUT#}CBcm}PMq82wdVN5bbH+FBpo#{6C@h83Q_*Eb6G8z!q3F!{KLGUnj6HKRZDen@ zO<~(P$re^JpmUs$9{xcPi(?>%T_p+On0AZ%Uu;SZw3^ILVAp*E@Wf_ zBOktSeKa7;_(cx}^Go@5(?V7Qdrek+oV?4$;`hM;CT&GXPJ}hp*HinDM)vS)>Mh9| zDYMS%lAH(n#hm8+NE=#3K%X-2Jx*kFzIEM#z5%qOtg3dJFO2}`Uq*g@hWY#|Zh9)$ z{~gPwrc<_J|Ag2xuLJ6^ZSrT$?E(c`sw%mi&UWq=sRf+%r_nxapmTJiHxy!yEDU`u zv7R1@eZ{9BCI6MQM6VC%guG{Xi{YOHXze5Ud4ci;HxGPQ(`1sn=|;OY#a5kepE#h4 z#V?E!E(9W1hb(R$wNE`)v>b5L%jD(@e{fuN8NX;jVaJa10br8^@0H$rI7HJ+;IHSp zU?xgN5iGir8{D!Ub}(XFiv}v>27mi8qE%X~OxJoaCyQvAhLIs{<_7!(vW%}&F7-Qb z#1s$ImEC(`$NHf;)ZVT$EqFe4E9%SIX z+D+0xuNUZnwNxYjKw9F10bQhY5tomA^^4grO>{t)P5t3}KsS-n!d~&pqXYkl!wS$>uj)!O&4=8ii8_Nti0`?SCo>t$7CBW>!t0J6Kj!bb0GHK>rw2 zqKHIIbZ1i<==B0!ZD+350{$&R;B0wIST%=lbJdFm$rv%3kHK&*m?Etp+!96M7sWR}5}Gk}O6$ zD3E=}t)c#+@*xV?vZgOlVw0WZIVY3o{QMYn)JW)&vu*QATz>fn&ae3= zfKKVVN*d_(06kY7V0Q9(p8u}^o#f8=rESM@cjY=1`Ch4=l1TRh{mj>m@}YVPswaWe zIMKsEq+Q*^kUtJzu~}4gKhrsc;WiyJ^p~~5I@<{3cVq{#K6LdJ6XKF3H{oJ;azurT z3S{LA;9q-GAwz64Jdmix%vdXvHW8zTs=d#QMf`w;EOLNb3q8T8SkAFD&IBJr`+PN^ zs>|f}%JVyI39=GR@b=oP0lYo$9z)U zZG}KbZ+E4d0vXr2*%4@Rfpn1zQ@rYfQUl$vI8ZH8VyqC{|TU*Wh5=p>jOGb-ep5I@-Inq2$y-RDVhX% z>TQ>9De~5Xe}SY3bc4Eqrm}9Ij*)b=#)9>fUZSb;?weWMR5s&C6(AY2Ii zuvV(tiC@* zdGs-x&Y5=2p-mKtCNN=U-~8u9Wu93B=-w8_Z{qUst`I#fP$1;cV4$lI+zd*j@r}-z zMbs=bgr1QKMcqFNbY}}mhu7){Ix#uWgXCWt9u0y1^z@#sin+N-9p59o4~fpd=gg@b z0PT#35a2b!fE*Y3n)cOF2V%31N&P@)EN`WkoB~`gq|IwPpHaEvTMHgKVz$+2AK*k&(&Wd}`u z>PCD5-aTPqj$9Y$38j20oNtk$GfmJZsS#N_f6Nr*6Q+q}-{slExXlp-I_^liocsL5 zuxPMsBxd;YBRY^1%mu#n>ZkqrLF+?$Qi;xgs`h@{-SzJwd&^k8&y4fE@MYBW<(MN&QRDQq4w%`JOL06MbjLaq;npUakR z-;jv(1fV1ZIxZItOL)=BQVY(%IQyMd4Z!(70(9$>y7J-EKzD%_%*px>Def5EA}%Qk zc(aE!TifSCg`Jqb+MqQ;!L@7y6scXdV%+hNTI;}TP$g~T%xV6!F*jIE&61@feIE|V z1wBe}55Qv9jW@(5K?)`pVed0~Qx6bX--?XLYdPXWMa+mS;`cVrfZQ2HyIN#~`8iv0 zW1gS672m*i%H(?>SMAD=KNn8BfLq~YMk(mz#+>{RxcKK?b+3%gnS}F&n@+n5Gvb8N z@r4_c_3L&12H4t?8xKR}Meo0~FbwH}qKr0rmx7SX^qRc>r-07Zs%h1|KA`j2nes!d$H_w*wS{q@>k;^hSN`;VR*8dcerr6q z1}zX9{7(+I7IXgoei(Y0Y6ZF?b3yd(_7#b&uZ+ue$976916q`26>_Nu-w~C4d<$WA zi$UT&X<3d1^sdZxOEznx^zI?O1-ha9nx?aHNf$aOG zrNN?GX!7|p4Y24-PoKRmK@#GF039i>2$szaY})p@iA6BM%t&T`{S!bpJ1J?edwoFX zvb-G&J$xHI*~IV8nB6DSW{{nXe4&C)xMo30LxAo$=Z?M(ymSFH3N)zDhy%Cp=Xt~L za0rHt#QZMG3a@V0w16g&p!em_C%}Q`*c35!VGMCo>c%msHr;y|`Zrl?0BEhpIZTfrYii_c7Eo1%>pbyg0arAnDPLu((zxt3> zcQvScTwv(ImIlm!tbKXCo|;q!v?+%c#^|!!xZu<8-Mo$%wBvvd5D7vSXumxtJdngz zogv8Q+kZej2R;8GzgigBHV(Z}+IXO}rq4l2`5MT! zDXZppeTVN2ZxTh`%BA#c{7c}Bd!26+aOvZ?#D5j^=8^o3`LI;!LP%lnvPvx4E%}-Z zz`j`l?z1rD&veWUxaif$hM~oV>rwM^@=Mna8|D@ssjg?v1!U88j?r76K)^U^)Lw~c#~f2}6a8Q}CvCta67 zAmU;PajoEkJB8lo_#!QBBsfM@t#=Hy06Itb0wuf-E-n31p=rs<`>MZDJL6JmCnkFvkL;*nwzNyqfgb49yYx;E_{?P9H=SYZs(f}q68LChH@|J)C+V-pzGUi3EFT<1Cu0c z0XiH>(|0#H^31sivgqU%k{jYH*fa&b9th- zIA&u%6nZig3#{b*DH$>AX!6nR`M4)pVm9TYRa2ZY%F9)9Mo&6>o zv5m=OCkr%i%}EL=_zN7%T%yzYGHfyOQZ6YY%xt2`s&WLBjEx+nWGdf_OfapvJTAiLYX~`+X>gWa&K{c9awWVRUz=g<3j*+nH=BCFQZ8C+C3&| zE|!!aX*|(oe-=OmK6z_h^W5l$7o86Xmn*rSPE5=}@Br=yIt(zRo_T(?uDL8U4+wNG zkCrR+`OAK8+xHIaOl2%mQQxN1P@re=9WV{_dVtPFo??u+FQC`H6smWP8gYQjrKRM4W>^ zYTkUyiZ(wI&B@2_Lm|wL3|Z6SbsJfgft*Ia_U)mhpz?!@gV07D!E#3Zy1k%5BE2@C zgDD_11e`x@*wfRW&2(z=2Rtay*KwmN4fGU%p4U=osMkHJn|YL}-s{)z4qb4ugweVl zOhX3}57-=ird{>w{$+J!K}9bEg7yK0EZg%#7%1oCj)lBLAQY>zdt=8SbRcPv2dt6j zOAR-)1&vmnoZ~_CG4c7?Zoz?=8D>92uuIY#3t+D50%TC@EKmw|A|iJGujl+ z)s#;WNc6t^qP~KR_)q!f^ae0ymsj(xYTqIU3SwuVaqy)}$U7&9%_L>=NyLK66jWo@ zf_9>C{Q&adnrBncwJTx(u~>NWN_dJPB{A7W4HCKk++xZiTz$agx_ai@VkPIk8z8w! z4|wzOLi$05ISb5yvZ71F zx-NX{1a{zrGP8#Wbo?5$5X&68E2O%Tx9-d1W_ds^7~CezENa&vQA8gcJG5{gmehy@ zGaZWZgH6vcTeL31nljd14u9_gqD5;;Mt$S%p8M* zkJA*g7S1(55vqGDqHDt-<8}rAc%U_(roy3E-%7zhRhF-C8%pj|h)8E!wgF`Mna5GH z#Hhf&=PYX=)UyHqG1SOU$P@gj(FuYap7x9RomVHQINUsw)qoPb`3$f{1HE4TKsSma z%$TxgvkYQc(sd=}gqr%+je;Y(8O(X(Ep6>+9P6OO}o&rM=d5bTU?1*(MWZ#EsSA%+d8c% z6M0}^=GdVHw^l=k#D^!*)o528MIswkemR_*czhqU9>iI@D-HD2fIi>&zMVbVw%OU1dIt5(fVzwdSRXL`=M8Fd;zMg23-nZrPs6IRI=&YGhBLM4!X^10G+a& z#vm|Z^=lr`)!jp>X+ujIRQ36{Ufuu)L)wYZ7NA(h*VhE9Ay-Yw6m$>AkY91TQN`~( zk89O(FK&axOb z^l;%p45(=VvU-l&G7GYNI(7+S-5C@C1tob;F}FbsUq=Kub$RDNO{ayT>(EpqU*GoG zocbdmNU;IA4tysu=;*oYtAQre?_YZmz^g&kt02Vo?)l9dWuLxqzd(nFurCet)PUZY zHIq`oHm>`i=ysqVUthW7f|vGUnnrxo>Op`mKIdSrnBlbf^ZVEpsI^KK1^K?AvmiNt z~YUL67wpE4U402`$p;&fEZ4M7M6ALIGYN{)2+p^B9?iBU}&Dqg*L~O zm29r&D);VbkO4&dLr%*au7_H0!F8Y!$~6!LfNnrm`BsNxXg?_6<87Nc_n>G{$pU_= z!jgBP-x%4%^#+t~tA>$W6&!^HFTpIhp}td%ag*_qTXKhsws$NBb-p27?7mO&vBY_C zMsGvw`d$?h&rnuhVS%?XI&6F;au!HhoTu}?q3-*x_p|o>{2ncesUfU(*t5b;D(i*c zaIvJOfu0i3hZ%=caK@oQ4(t$8<6fV1E5p{?44eKvWS|?s^~r$t<=%UZ2yr`=)B|+z zGH`h+H6Pr!2)~@3TZ66n}DwFGd88kHVPcQtlV}hb9 z$$=guL21o%Kpt5q(&Oe2aOa$Ueu>vq?*Z95!$eG(M}b@fVl{;4f> zUq~A0F$mKq>r>rP*V6K@zxe*KL$DNWESfeP>_7OhfewPn`Qhs~x?q>(Sj4_Api43= z;q_lvm0-a}(&{OPnZ=I{Law!Vi85iS9cGASA;HYzkD$4Od!AdSC>rC(Jd0aIfP6zm z#pp9gw6wVxYdJp90}8ZbVqrrK5wZprY8yBP0==uQlCCI9hjD{pb2;#;PL@?!CL?eI zaw=h#_271f65Tc@c9F2fl^R@QV6G3fp}~507`89f)ufKYj6(KxQze)b z=&(O1a_;^sb(EMT0Noaw4>O9E4&FCRS5@_)13mf*I7>EkUHjzaB8F(MZ^7{Q=hl6; zG|*#XN{f0~UYsYN>X=;y*Hsu*Rawi`LDXO1JlYNi5P`%KHz5(0o8%oz@$js?i>}GK z@+O4qB4^O%Uj%I&vIK=I|6Ua6EQ3FS-C=%#_HDikNDC+gyE^e3)Q&I0iLp0{wBcWw zTeET@03LtPmY>F48ZbSWbR6Xo5>50pST@tj7yk^OO4y8Rh>PUm0I#37F z{m;sDkeL(A1jqR6?c2@Ox*H$f2hd^az#Feb7i#d)kK0YIvg!c1_wUfUeFkZu$Hr%+ zQ4r~}+qOZ4E?24=Qt~rC8qt1ZB3KiF>$N#cwqWW5I`o7xkvs*)m0OSYu6@BI0v!n- ziK1@avjzPH;+#fQItv>Ux2MrJdnbM${MRpT^f#GgPQ>i21dvu)Qxv&N3+8GAjBS@N z8BYrw;KJ46wsZz0(ve2ui#rKN5XROcm2m850N#f^pc_Y^*6j`eW;oGw`3BUun{9M8 zD3imGqi3))`>?e!=@xc#O6C+GnT!oScLz7Eg7N$00pL~Uktj!N{Nkdo61@(i}XH8(GX z)#@z4p6*i^gOmXyYT?w8WxEg2H(hVkFmhYbOf*83c$w~ol=ay3YVoAPcc zbCWq7b3PZM*oSFIA%m>m$f|1ijPi!4S)WNHK6%CP*)p)KH55BN;R^`#wj7(%VFr%1 zL0k<`eudZ{eHn-{$N+8=0msY-1d43+QWMTb-`dn3E= zs6q_JFw=uNx0KX0&{G7uw9kAcI$6@wGvDiW5s+h}?dK%#ZT2vM&e*7D{+{R2+_-%m zQv~|1_wNAxFyw{N+JJ5?=qk1jMb`Xkp7!}PWJB@71_1OwG#MKnVbSO75y5N$N4rU? z#RXI{Q6tNC;qRd${Qkv!u1o8`phs^35P3XpLM*L`2Xv#GtcTP!eABUw!H}fi2sRkX z2Ii}(q@4txhi#M(lVCg0I^jftQhkYAt-7wtimu$CQK0dS;LcqsHW%FJ*Qz_42?MiU z45zr~7q!WBP-&oR`lR=+HU#Jx?=uBiUix9vw%Q;qx>7ap=^*+AyFCVrJ@unLTCykAlm{XW`YkP-Ngm)QGN4 zSU4w6()ef*@h1m8Q*$Q}#m}pTW&vN{P42jvWg`EbUl2RpThhHUF-6@WTCAgixHDe? z?}bcmIzp-%?I3G~kjETsKH8Q9Ibe@*E!c=G=F3v=#Uc^Y$be%(3M?B7Jdf8Pf8Kl& zrPL?~jywbdR-5sXX=F0j-6bVRem0R7f{%kQRLeRvKP1}9l0q7tKU%U?(n9{+6@A%r z29%zg{^pCqxp;IlcouXB8Pul6|M(fW`k?Q6{VB4E&$(OnCQX;1O{b>(6QpE`jXi_X z$gbVrnj=^<*mEK8tu)Z<0lKbi*?V~E9Gi(!gQ!6GCxOmaRD@fH_daZztA=!v;6wpHlbjJZ&cytRw)PTim6e99J|+kL&iTL+iAG9hqI?c%`fSZ-<6IQi-S05^Z05 z=wpm;nrtu#O;W%$h*{#C<`h{828s3py0{}%)d~raTpO3(1U{p|_b|@BD+=@rn1z5@ zZf78BMxI3l#O^Iabb2VXJGUs?BkT*(hq-v8dv^oL9%Rc_k2%1iQk|Rh69=hUQ1uGO zV88Ca*Wvq!L;dSNOWZN>1C3b4>k{K&Q+awQl}M6`e}DR)grR&PUI6@IQ83 zWMNTgRx8jcE6VPIpBE0JD9}|cGy;mvoRV1kCez%q8TLFcp8LfW3(7{|n2xa>;HN1% z*;nP>K~+B)t4mrrPKm|Lw`AaMdj%vSJA(<`ZNTpkCLYjDhAzH2C}Eca)7xgOFkzMG zS1Y(E!j)y`QQMHnlkPrCjZ4in0J=;hs^K&4T zwS7~r7U;F%oSO!k5-j)>y!#CXI()}6%>%!_KJZ~v6(t2abfSWS15MNAr=1U?dQ8mfFXBu$;yyX2`m%(M-t7^@5D2j&;3kkA)E-bi2n zcJ1#7Fh;P#SdBWPJs?INJx7O&%=9u!=o(BMRDw$HgUoGdcuOc283@mau^Cf)=7fQJ z`ZGu$R5qGW2&a2MHyCnB_C=q;LWsnX@z^7#xEehIzd*xAZsA`-t3p*bjHM#Y&18FJ zF475B;HbZPw+bZf%*lJ#n<}_DXyjh~o5d2JpDDt3R~M@_3tpl_1IL1{Zu<64eK@Zv z(b3LxxH(gC>aj-pLna_h0(5*Dq8rt0V^bgv^b~A3X$69Tp-j$GKnBK9u<}kK< z2NGWyQNQm-a5Y2dZ^FW{)HIS^M~rm^Ow}`kYpfP%(IgSI(fEXgYCG)CqtR^yE@pld zC|sldsX#?>ERknKGK<6B6!S(#3AcV94Qga209z7so&aC`aqzA=75Fjqx;xFeg)CQs z!_Rz1hP~|<1|>9RJE3h{VdDDRg|I468Cm35?tE|A4cmyU!!6umqL>~xAZnIA!M6$A z0-_G7fm2w-HXNT|jy~H}e+HrNoL0LAuX3&6#b3+d%s>raKPynp)nT=tISzxDLaA2IxUmX?cYxX`rVHbXC3h z&r5X1M!od&1juvb)~%ijE1Cb{X&f85U+pLj)7r1Y11A@mO_an#A&U$l8}?Atwf(~? zybT4W(XWI~J5f$H!#WGQ5(4QLQ?zd?G@6KOYF;cP{1pvbHO-1d_%Gw}y4yn82u~G~$Dv<5h78Cf7tNTz zjHCHtQ&G3)0v(cW^jn2og@`&ZqR-Z`BWC$~+f!^d-gwmp?TM ztJ1JpZ=FDY^1MzG8bJ%72lZZMCXGPhm|s+_*iAfAEMR{dIS07k-D6odB%%d@&{p{o zN;?tQkBLn|d&^C+&CsFwS>p)gz_6|8S^N!%me~;E0iBsYad;6OC3?6A=KkHpQV}`| z;VGZ5z;lM_Z<-=HB79Qh-lJp9sTOt%=pFf&81?&4?C!cA1-cfLpo})~mdWCLEO;1< z&QoLE3relJyAlY&z6P1ao3mL zp@e0f;KadJ6ikAivIq1C>wyct6_?ShWIXIWWWzLZ7xP7@oVJkO0@wGAiu-_~ukgTX zIu~-`Gl~Sdb-~N{y;x}R;23Zb=y4&ad3}p07vSD>#ep;YQX`FP6ml>*;EA^rYu^k3 zicgExuEN*1KA7?A*{5;3WTnnbsQVe3zSx|RmguPiT@Ab#EfRQ0K!?v20v+MSxo_mk z_0*ErdR_3BM7G_01`b$Q7tpao05yt+<_4r%&NFC-8S}CWAXk`l)j;3pLbANQBPno;15O^C1`npCY%agF2rtcZ$45mA(*Q>^PMAh>kczMB3u;v zfgT{z>#J~%l7P=K3hoWG% z#|K5h82B2LPfH?^SWZINv^qk&=eVR2ep^E~Mkgy_Pqdji{)R>h^g4l#J(9_`nU|CI zQA-Kv5v*%=*u>v%cTpNlLR#P0a)K*dX`rVFbcig+a)%$1L^m^E`926?7SSq*)VuR0 z8-Wd5TLZx|HYiUDbZ`A}R9*gAhSo?VnCv_+UIk5@M%xYxoZtK2Uk$5iU3PHIx+JRF z-_*G}FJib$EwKTxk`_dk!Q563Kn%UmDEtL=e*GEY2<#QqH7)qM0ZA$qO;r!*meC5Y zsgvN>`xf^VB2vs*3!s+gIL#3okOkjzIx^>hoN?%G#ri?Md)pU=zo>JgOu0`lj3W9aZg_r6y;}>1E|6iEPRAxBS!qL% zaLt=M+RA?vQM$@O_5KE5rxsCEzI6U8@^(IA#(ZL8R$Dy~EJyQ*A6DjEL0!gmQa zk5QGI%obg4`02MmV>c|oS5$q%K{yhPp{?-PZr3yKpM{L}CWhl_}rEB?9H3-q|x%DVlzT+wtHwS@=GmesD&>2g|iPZ{Vi9(zEb z+t_Uoa!IcCS+h^Y?j~`4z#1}OJ?H-MJ7%)fr$a!or)jQhrmNM-YnT+J%Uh1+KZ*!h z*&AQy(%+XTUA?4~#hi7F%?F7l-kO0gRX~68CPJ0hzSs!XHjS{q(FsOoig4B<8K~Tp z(>N#g2F(MyV^yIItj^-Q7^gQ7m(|_1X~!*MMv3>n zMHh2rz>NVJdKExtV>jqP1ckISiU7bsKfm<8ZO5z` zlk($!tE-6x9=g=!h@D)b!}L;Sf3i6RpiA72(v?YnPhs(eL=6NwDi=T{wCd$%@`F~o zg~*5^=pC2_dINyI&omz}j$SeL@FcV#A=O)#C8@@uNp%crI~weA#>C%stM07)+ijqC z=W0o-lJ#cyAiQ0J4ykmuBJ0&eiUEC(V3l+~;Ovz7)*%-9hAj*;;3{az=nbejD@qfn zTBCf)c7~9brkr;((bjN5&EYB7UTmQe89dS(7s&Y_6TY<$5O+A>26$ELZrw(-G2cyA2 zN3uW@8sV1A+4@ax?ahl*0J^LOWpvr?{_` zBi};dDA#L7=E7a{7pybwr6|z3?3{tuH{V9a+;Z@YXxg?iVA|v&zFNbS9rX;02&djD zSx~d{z2O9lRiw@7Et*b@7|9&>Fls43AEqG-~v@wVx|uV1)kED1{Gzz!z3I84VFE{Lxs@=HXt9H(<3sg3`c zW?(AZ4-#gTjT1o65rh{)qO-<$eb?M%w`Jgo(zI?4YVxdy%U(5rxi+x*o#qvw?y6wX zqC&PeU-5u0>GJA>*a%BZmAJuH6EMc;11M}w`nYmNYbjEJZVBwv4ONp>t+r<-fG&p4 zb&2Qjeys-vI^O^{Lb);q6i5T(>_4&_{;d5p&{F|=uXt4}C5diX%ay!Rw1xn^ zrZufK{(Tzw^J>_D$rq<(UYZZwfqGJj4h>WWS3$>Nvm&l!lSQmq%XEyHN3Sh-?Q+C% zVxOU}qfsh4o18`U6pyhA8Xp4q_l<_cH_&COOPINwS;i_uujc9D&vc^|?Y&_tYubyniH>75T zCCfo{Fr1>`W(39C)usS)o*FnRSuxYMW0>G)%9&LKa#_@p86^3m1StsX2jeDL@uLGsxD#Onc z31VYpS(F{8VuO1(y7GBcb>|z(C0&bp++?l#YbTy%f*)*huHu_!Rh*ZQ^Bt2bM}lXY zTQo)OdZz+(w2S#GKW@EKYp?SZfo`~ruBOc@TJ4!f8dS@!FF2*v@9<3nJpp$tPGwFy zM3-9%Yvb}#;PJoj=!o}V6u=YFLkrJ^nUl%_VURY?)#i0gNnGqVwx|izdXw|7)m(V! zCog|Oa~G}nH2?fg$M%v>koWLL$nDa?kMn)8FeRYEdyiX*rJZ-&)Ka<)V%=QLFM{K9 z>pC9=tzIVL)Nfr2Q(XETvQB>gH1bm$pwAM>N@%6p!(z*?aRzcjzZ zUzr=$0++)DUqC}qL$4bNy^D&BQ;oUCQiC~)koBivM}y|2aiH`4JhdNgTuFhG2q=lD z-+a9&Y+|8YiV&|$OLW-9)AN^cLtVsXgRv)Ci*T~uOkt^|fu8Ubr_={@Tu$&2p!xM4 z{DT4=RD!b$Y-DXp1?Y~&Wt#c&c}zR433LV8uy7-~hh@7lHQ(|pp_IMaJSLss-yl(s zI%1FUG#YOAyJ0m=+x>%ZcmqLX-=IrL6@1mLV2!jv39l(XiQmmjcrBXb76_dcH!E`8 z*-~+xLro-{G&%_k-(^CcI-lZo$zu&ks4bO->FeS;Txou&=LY;gU$e^}r!G_Fp)+l44z z%a*#<*aYL1G|(Fk^v~<-n+>H64$GXrTr6(&!GI2-Cg3LR`f|BTC>={@twT0I`{1_k zYC!@O5=kUFHzESs;5%lN`rCIbYLq_j(W^vx>_b~D+lhU~VZQ{uW9dY`0I96PmMnRf z2xo-ajES9r6*hC{;Ix})GgSQE)m`~bV?gI(w2iQ<8<~Qu_&4-w5c!aMk>_OLFCgQ* zloWH(W--4q3H2UT7}a%n*5Ko@UQ20MAnp&c-LT0{YATSPyzc`2y+X`m;J#&*3A>fHOC zbj@Q!exOEsZgIxut*!a0E`$hEBtF(!+a*M*vU_8uCm|#m(D~nuvsk>7D0 z%sTJ8o90v){%(Wj_MqS~#bbR!(Y(fad66$Yy#T&*1qkc-EA|v2;q@*h?sd-)s{L#i z=uP}UH(KEJ>Dxdx=eVDUXCdS%yjI7y-@x}nGT9QnoH?S$0x8g?8Rb4FXvx^1d*=b{ zaPV%PSI_FspTjq(Ph*liI!AnK)yL$Rwa+g$nloG7jy+o+;a39C6;jP*KW5dB`D8CO z9}MWI*H~ONu_OErsd?wC%#pU0ov6&Ja#MWESARa= z#W=d_W*35%Ly;x&P2q^+y8d(___$&Egg9R4Z=sTy#X+>~_1|2;T~~ZSXRYzpHO;%< z-Z&A#Yg9No?MxXc+xY0}GP@KR?69JHtXoYi3LbiQT*!@UFGc23NG=jOxrmNa+HFF7 z#~bhSq4jqh;G?Q*Ts@2I(3&dOzI5UpVYhco;~OAXfSkJRzq*I`jCd-vxX;agLGfJm zcupex@lIwc_3de(Ck$<`pUWL5oZGaNMr?L*@}C2PF)HK-0XizzkgDD5B&7yT8R!f? zJm-dn608=WLuZF}Ai3MZUOsGU2;7&pt~bnVY2bReX|e9=hPY$qJ!wrv_!uTpesGhgf_as z*X>01wwuQRB$4=RhWiD&`0|fmW9ezcNg3$2$yzl7`#PxBT4|+_Z!VUg?~K-1YxeL0 z(Awj_xHP_b6V{)*8I}BgH&rnazXlTeCa$@nsKYG*LKYt9CZJ7lL?)=QM+iB^5ZP^} zo1un4=O2NextM$#@7JV#;F1+xoe5tBKS9S}zSuan8E$o%%?|W-!-u*m&*d6cw1n24 znCsuQbn-{oqoR)1+Z)E|E+h%iC4P#dbv96iIKEjvyBY$gwLarGpmU^?5LvyyrRmhA z!8Zix6n!CFpWnMSL(%laTDM+oS1K8_X`m+p{S6}#Y}S_FfIS5mg~dl=s^I+tUHjsx zJKP8hvl761sz5hBn*_mI$Vt^}1N!og)MmDWCP=i2u>0@FXwpk@i?f?6)BN@4TyzMh z7|D-#*T)K-;U3P(1o0h*h3|O0bnkgCfiXhDZ*%Wunnt2jQgDmg0_X|9g}+ee4iU*< z$5C|$q#qZNgMj`DhWjABH8MhW3;H!p&W!a@aY14N&qBSL zmr^}@8t64fUJ3A=LhZw>(=#W5x-L=|{EOp0aSj5J8>lzmbRdPSmIs@3a7kC%t_xBN z)|O>k4KG*TiC>`6)nc-ezhjHh)ia4YrZ~DO)Tlqt z5vyvYliQNq_?76WO&@j}EabV)KM&|lL@$_kflL;D-|hwuwtKZ9h5f*AfGF5tSDE0K zRV?EMgHej7%b7)ES#lQ!x>GBlu1h;?S{fg{;5xy?NA>ug4bf-PWk2}ulG@bXJleLE z)z$4rmnzWt_7~WBIt;v-PHo4%AE3k2xb$HYNN12WGSGaVq$T=&0sV8nDpj@p-X&EQ&%4uZ`Y)YelVaL6uL^}WG~kP z>J4K|8tC^2^p%WW{`U0(E|-7<4H*v=f4uxbfIi{v(Wc>6d^ZH>7jFh6U}RS%xdzaq z6&w8~M?>L>$7NP`Eu@HkU{M=2M4t7?;SCqf{`zxWk;XZ+$o7Cf#l34yQ+h(q5FWSc z1<+=pU0FoX!y3kB4OLwA0wj3x(bgqJ@PM9;>=J}@GfZT(E!RaiCP;7<;nLxvF6*c(FAu6YIcijHkxg5P2(cv4H#ymu`=u?8*uf|ue7 zU3~TDZfNaVkq0J+TMkRyb82d6me)O;eWIY*s%tkbw>V=CewW+B-eEsi^*Eq^=g#I( z<{B?gyOno$4L9K(%3#FJDN|$A)Qcu)O0*NpXVAz!HuesK&|7S1yQ;WmV8#W>O~)?& z01gWdGc{%b2`wQ1Y=uksm;5=nubn0zSd1G{gaBPj{_^dzNbLmwqPUm@PvMo>^^3Q#U-<6f8y~D0i z;wAc8t@)^HV)*qTJ=>& zHVo(novvu}Mx@~n)($V7r0bq!NK_1?*QBo; z>zIh6WXCGIOM-H|MCa<>(?t<8?z8^-bNI}_3#J_fQb~(gAbJcnymF9diD*GgHaN^} zhtky5GH!Xt?cko)1A0qUi1c~P6i(@uUU}BDVlqs_`dbOPIr~GSlsD8kB6+hQlWkW_ zpGdci%b_@+6D`!o-^Ilp5!O0Gap_q6Kv$6Zt6yG(C1<6GJ}3CA`0E$A8I;mmin%@c z2{tUe!`!O*hXr*03s&}|fqoxACu8hA4-9nwC%^AG+6|>S4Sld5f}>m0q`HB=>~}6< z3z1eT$+6z)%`FElzMNH+x0lyw2kfsu=i{i!!cm~#3B`b(Wk>r$jg*ClUYQ>C4HO8! z0a;rs(1{zWboCpPc@C~e@bV-4Hb$%Bo^@S0<6R`*7UpTLOM)v2{i=KtotqXH{6NR* z&bCSV)Z5JLsYD-B4CrVTsM^ox>IOP|?S_pgjwEy}bK6tec59VE8|HkWke6vv$2n5qhjucU!-lf2-K^y5 zrU86rh0pt)h^Qj#noQnzSlrri>(AW?mJ-m(vj{Gc58Q?&eA`+Ot$thO zb}?enF(t+4K+BoFIEy#1Ia-ahfDtcKTP2;qgk99BS?( zLA++fy2)VPJ0!K}dei|=l);cmSkq~7;W~D3Q4NZ&u}vP!=9+t%f1@_ z!1%{+FSUhp!ZB>q*N>ylQTuusE~jQvrh%Sh94(dZkAye2YBccYN&5CVI|WR2>auj};!U00`{DomcQO(Aje%4#JM=-fUJEG>zT?J~Fi+{L+~>z_J4pxf2)zbjKAv=DHRgOssVJzrAksydN;q-ySM$=SQW-SfD7p4M^jUA)Fvm`zP18&RJ=wU+ng;dz>5mnqY$3X$ z1-ecxMgc|Z#d$*iG%mwh->L!b8bF8D+;uV+rIAST)j?_JU_wS8EH={o0;6WcTR^yA z-1>7D=ZZQe7C-0sJh9s~Mr4f~X10TxJ2hHG)%^EO&xQV|d%j_U#g*TE4WJKm=k{~& z?#BzQfRJrPu61Lv$3qBoT_d|3+fAb9(*H$&GmOKIU!*g7p^Fm3xdMHpHvh$H*y*f- zu_^B+m+0WU&>e!BOXqf<`yFK_92JokR`$A1=Q%%TMrM?nQShRdU^6JlByMK3kp)9+hwU44-50XAH zXq|Fn?j(0tG)%XExK+}#1^J_6oKzB=aqJs+ac=OKUfJseO>|Y==|(2_4sq9Y=<|Jd zkw8CKwD#{nk>xd7(DyRSifSHwOw0w3I+S=tU6;Rc4XK75Y_rJ8E-DFW@$($rsCQ=< zF{GcUWyG|Il5cy%v(Qsx8uHEs{OyYT#13xRfVxt530+-4|654|{Q-dfiZMx+8(w4% z)kL~3ukS_+S=2F|I?yBVQG4z+*EX+HQt($_9OdPq*95xF%;JyLB+&v@pU$9rgAeFj z?KtbzpW|mG?HH;d?s5*d_tkhdjmgl+pB@!7c`kaaUw|S4%Ikh}NgVCdp0D2ndf`uA z)5dbQYbyH{LJJ76Dz^l{G_QETAo`Ig=ORbeY>kKw297(dlok1bXH3lJNLQjAS77Ju z#b^z{Lao8YM#Rm^j|aNoY#;QyVLP=Fbw+{CFTP~%aiyU^N2qi2?)Z(&FlA=F4!K%^ zeqKrg{l0;&sxO3R*HM66``{MkrlnOBIm)A%D78U5@xeJoeEm#a4U`lq^idzV!V8Zj zE5@MCn*}OSY8*q=zXp4P#R1)38%;oL0i=R56QJ0?9v|0nQ_mwLwvZ$>W{ z|6qH}Rxur;op%*ciN4U|pwANbZH7k!mpQ)nr0`tYjM|S9!Trcpmmj=2vMg2%mlL(a zug!`pNsTxYbCFiVQzLYRC`*cJ%#g6Bdh++Rq(Fx=e>IWTE75_(p6l>WJ}RfCLdQQ> zFo?8)hws(zd9MxVC)`FmX`tT^(D~#YI7p<113j=I`wmp4g^@Ff)$)*P0NtYxWz*h= zPDYxlCjol=!yNW46rP$jC60U2sy$pp2Gkl7J^unE)>ttg7JOwf#GOU`IogqHgh$L< z&QFk-Uviu+_7!-&holOLuDl*ir5&Y{d~7tYxKfJRZPf&z+iP717Wu^XCTN436hs=k zY_R;lK8j0VA(6Y$&5&POrpScFA*u7@C2YjF6wqTyKbSwDUb|ESH-_Vw)EK|XhjbDb zSBJY@Tv`|SgkJ#vHrTNy4F)>0Sj$9~wMRzWAJCaGRntOgpx-ypRkD?hOg+8^OyqoV zHJ^VaUahM2K_xC2{!#_A@3hUW<$?J?k1j%KdR*$NZ{dZ3yTN7`-mR{wkjR>{d{#Ji z1t^iY9zRZv@vcDuX@(PP#%M;^NuL_rJ9=8jD2-jzWU*&Bl=YFs73w2hmI-PvP6WES z&b2GmJyD0?OvR;-BBSx-$eq90yK_y;W7zjfocwbw3P`R9VCr0K<6?A9fZwa^<78LW z{LF+bId5|;xJXjx zTr!~32s390;>Z-vlm>dzagE)SQ~j{6bDJ^v@#(P1>gcFaJJ68?nf^7HKeIsX%fSoV zam%jLMAHxSDAT#{oKcg_2Fi#UPhV3ylu}j$=r$-Me^+-jO_rQEBK}wY z=fvOG3if`0&cCqX=PQ)bNGj{c)c`3g4=RwipURoiKueGKRUqV{{$WV9yG-JEZZ!PY;jp`;#$H)1KcQJ~ws0^q-o zt+(ofaf^xV3PrQu)Csl+biO-9+ZK_90%){^+55az_rBW=f|qya=;uY`sHo!RXhLlXy`)TTuEB>KCvBPL7eC+Gt@|M|0OIF3}4 zj9@8s4CdvYxZj{Vk=!ZCfu@h+| z5a3u}{##)(2I{0XI%9WJUC(Kt*EW8lH}mW2d8Ofhy0-7$T!B|&h!G>I zt3O^s!;3rup|Rh{{*439<(E{hnnY1>*N&<*BFTTMF_J>GXjcR3tFPOpJ)=yE28uI$4en+4veta36rfclQ}^( z<={{n=*eeYp7k2R?Yx#prK^y8a(9JYGr=`QpaUO}$x3&8A(8r;*mEOV*7?eAG6f3M zlEuw&@!FKVlUuWWE|g7?>z8U?lf(W5J;DPrM53N|Vogc;WnLT;D_d2ht7bSV2#2_R z$rOpaZ;CE1j?Gqj38A4fuMwH8CIX!rqF1x7Dc^cCV`dSzT2wpkn9zgHfbhjF&#d5o z&GBWn)1v%fOk(Px+sM}H8|=a`AJD}Sw1QQ(=w+X zfgUmEUei>;c-c^(i&1cP3RhdOny8NT!&t`#IR4T=Pd=0#i&WyzI!c&OE@0>NDPtyM z=6wU5(c&JxxwR?RBGG*k3EDMG_z=J8lDpIddc+JblvE$Ng!^?alH{hNYUWfkgIlMX zU!n(Z+rH!yM#G(vTgL_ZLf`e9o7|L6{(-9uIn2R@C%IX>>MoZ&(qwm(8bCMSbOca z&G6##EZmWJbjZIj3oT9CY$YcGow5F6US*QOTx;BLRuUKI+F*-eE)X2@^=K1IowPAy z8GR<3sYkU|ZbFfDju9u(89Pw}=sHo4M2v`!?%sVi75oCqX4Wdv3Er&ydAVI{Ub-LX zqKVv;8|r-m9Y4%%wQFxLs#A40SV0=-4-9lgzcW|%9+iijAl5uc>I*l{m9R+sgRUR! zQ3(QdE+)I$OD9_5!itBvyVyYNe!42I2qj^dP&?C3iHpv8U*^~RTa5+k@TIt2ReWAw zu8KDw#lhZ)I zPoNX!=pqPa#Q`1M(*f=7a}ic##Mgi~1n69eX6C^skYXw&pmQr>Y?WCD&>^I>@li#I zyFFb0@XGNOH4{F#sXE_ZlMSt=@+Zdf^C7d3KJGL4<>LnR_%obHme-h^FUL}^`i0SJ z(a(2_2JCy*1iCRhde}L(Tdn3?@*-xcG9=d6)w~^3ca-iiJDh)Dyy648N_zib*iKx} zHFofYgqh^`sV<+!ocPpM@0n5hgeC~FlLKAVLNiW64RMMMutZ}{@S}HuxX`t6LRcRtjpFrpOe#gdy6aXE1oj~_g z>cCWLIF93SjU~akX}q@^-OP#K=l{;z60Ru@9BXli$gzbCE`4x0c=y5=R$(`y2BO!c zwko9VdxZvQ)MA9x`Izs6z^c-s(zh_G2NnZi5}ccZkukyleboi}yo(W9 zlTOK5qs8(>Rg7u3HCP3W0^M{*7pNqvageWK_i3?v)!yrR@YQHJtI3+8eG?G|8EWgq@ z)lx9%-%Yv5mb>(+?b$i(R1-a6DMW#eW>ApiR;CPej&wftJHA)%3+SNA$*K(3Q@#AX z@|w^6N`t6T(m+o-pvq&1)kPzUc<_8{Z9eWYi%UIiD9}wTb*Xr3q?@s>CK>)~fDS?d z(&Vq&0FJLmAQO8*zNpypJD;F;8P^&9c4~BPf%@}b;LdcPho0O-z($X2aYNem8$-Jq zZ6l3J6l%U6mB?~Ft?2)6B>>6=Pt|cPRplrjm9 zp0KuKQf`P2ltf6T2GG@lx4_p`1L#nHE)&hK(iW7(JE-i-BuWlVs>!}m7Q1)W)2GtT zF{2K$dtNwFA#Zu-vyHAb!fPhYik>=P87|NbHp!b4LdJVQcbGHPC3PTLNKyK*m{XFg z3+w$`Cf^CV6;g&BW4vp!&4~qm8V|T95Z7ZWC`$%(#v)evt(w_p3C}1ruGnCyN_4!t z%Rhrw7$T{Uc%TQcxAf+je=)&^!OXc0(ht%=uN~;pRK}+_aD3<)v^HI*(ftGc%whuN z6S|b5MAxPR^RQEA-*n2_Vu08?o`~7Pzx?IgOUxrLiQ3GDs6SV9EzaXVF@eqq8mC6R z#d>h6Wq4du3k*-7gWvHxr}=(D@+((Q|*| zx~@1ZCi^mnY!>sN57B(>k9rtk{|&tURWwa)RlXuo{ zz`voZNwekPG9-;maEa^d9j=5h*rK*w2yQ(1V6XPRATz4yDbBmzbmFk9WzeIs8~IH~d8r$QM3Gwo=nZH%bbk z^ROq@M3HK-4JgmeQ-Ieu`sxTZ{Y+d4Au`>c^vjQT-HaxudEaMqUU28e4|Jk!O<;=h zKR;(~F3}`$KS_WttnE%*y>OD#O~uWpr`%9ho;`?9KJoRCyAPmqy&%+k#;P5z0rZ6W zbNuL8!P6GKWLCV4gh-TNQT@g6IRx2To_yuI$!+FwVwKQ|K#eJY{!`2s*G8>jqw^X4 zF?#Y2W|UUi*cHnZd@j z6H;MgBf?ItSAAMdJm`d;6C}Yet0Gp?<{3$V&X8!|*|8a!2UPX`fzFkJnf9Y;pg$a- z^I4R>uqxV>He9os(V6* zs-9USQ_mf;>`bTX`c-^`G+mLP=7RpOV+gTrgwquvyufTRF=WZ1yZj;Te=hYn4-yrV z@rNB;tmR;{c182|a=$db;x=C-WK!UjE!$lG{BToJ&L_zowQ{&VJ4YAO@gCKS4+(1V zkmvCBNLGi=S?tseOk& zv~RFUQ4cznQMb^PyWB>5^r$AaLHnd0GK%f)58cJz^y00=sdu~qy%ES|r76;<q-ZhgvA6;Hhb(T<%lW&gV)S0t6TCJQDzAqH-!#jm z`$`0#sN}>ll#)YkpVS%rKx2B*P=oDSM5vu7^M2GZ9?V9w} z+7fqr30IbhZS-EXmEp%{7vnrP7+fs}+^Y&Cc+J%w9iJF&H$;2ezY$z{Jn^5Gcx~_= zh;h$%Hc6PXJ=f`_LFfLA5d_CDjqD7N)qFpwA~%Kd1NR5VvNELCx&jjJ>0LTahW!od zF3VLx7u~>&R|{x2I4>I%kPk{PBC4%N2K26hE=G6Hy#>1mIuq5Fef_`C={gtm#LuX? zX>u#8EwdVB75~|b z#n$k))GSIJ=ZUJNVBlYGS7V~nmfDR@CfObx{Hk3nat73TbhxxOwJCm7U33#yJ-q_D z>|#3>v6_XVfaa~{reuX*y`nmzsDR$WzioCXNxWbA6GhK!L1$uG(%Vv-Dc2e*(Qwki zZS6rLNf@F#3ShS^W=4Xx#BJ+iDa=g2t9wRxss`mbWN zUQ3YRbOVSD-Px_Uy0}KhvuckXz|QKPFFB&tyRlzLc6-f-c{R{)u7S?~S}Py?*V-rp z;LFO3ld$5)+$!iLH*n#?q#;`ey>>+!bn#rBMJM@wku8lHoWE=KFlFcq=5Blzr@Qnx z=u!S>`pns_`jJ5zbTL+uQMqB`*b%GOI1d@iS^bpIKQnb0N4m_Apl^ zvK-z@t0AStm8T^$&A88ov-HY+*{HBX^^(H@Q3H1eT+`Ld>H!KP8r zMUC&69uS4Zxw32+-b2D{7>!7&^-XQrFsu!LQ55N@TOKDrhq!*Pd~7da52=$ zeiHOWs}Z8rc;Ws{C)QoV zckdaZI$yZjjV!dSQyn~#N&j;zbuZ`$xoTC4Ukm<&5}-G?vZ~3csGILK#Y*sQXsI3d zL9OS;Lu(bDJ!2_A=QqU);;9PgCC{B$YqZdR;x_*5aLejS`W z40jRq0kFw{zK21#r)Gmc=7G+=)s>3>eGlrv3pC-b2e!(HkWgyJUF_|)=;(Np^m#@#)RXS|j%_SIUxI6SkqFa?F| zKDxBOuO@&*=!**I;!gftE1;%A9CUttY$QR^i*e9p%(`1_8XNv%hZe7ZEa~3#X3Gxu z*%D=ksB=M^s|4MX_Y9?V=ho}d221rk za2o(!0ONV06Y2ZEDP1yTAa;jn6_%V*9g0HD+bmI0m^93WbyI25PQ6A95W#aVbhfP z5M3k&zHrYM(%K0}wKuHtQC-144w2qxF;{mEOyXfkV0DjAZGNwf% z{^|tNr)8FF1Nxo?-9|?=0=f*PB5LZFavP{ipv#s05kIvX*@kN`NA|HEB{fWG4xBjQuZm6Fw zkb$d4?MD1L1A0D)7=P3N=rY;?8#y+Ng3@Ss->8}wot>+I`Sn2OQ1afoTT}(=C>P=o zaVCuPeNciP`JdPJ&r#?z{$Pt6`fkUj3;&XaV9mA4e=;QI!ncpAt+-R`y7*PjshPBs zt7D+|B18##&q}2xbbKros(V{FLXSYl^C5_p$EG;wXeUo3Y;gTklg>S2eE)38&%7&- zeKLWjR^G!N9ns4+2X1DLT>~9fJ)8q#W%?wF`Iw);?F#4+xwd)p2RKa))Ehb`xUehH zUk&IDiCX9l7r?Cpy7>Hwp4AkdT^YKcJiR4M+ZD4VRfF#RUsKU04pHu`iHbV+6W6QR zcUO;dBmZ+kV?+1wM*kiTRpTuJyJ>`IdFs!Jy(cg4!6 zSIn+H4*Ia_bedS9-$}V^I|bol1$1j(;8n|m!8vizDgGw8#m2oOlI1Rbye*sZQVi#x zDmbb&6O5Z?wJRgMhM z7xGJ*x;_Oppyvxy+Xk)$z2ZK>{&p2P6&dr<3u1;7_iuwuja zu%Vh41_OvMPRfT~XNhryLo)m6lz!mlc?P$*Zw<4xxz1t@JZb8_wJnMsUkg5w*HP5o z!=z_WZfrSGY%N2(PPqZSE|#M6_&=51TSe`ntzYxfGY)dP1iGwOcZdDM z8)I05|5DHN@9;_zVRQsRTs$zJ3XVm9m3Zv=>!WR%;m~2Gwl$&bqtG?^Qayzz# zh3~Ig-ibD%8XF2Zn6yA`n`u4C+PX^(rnQ*t&-0j@?ARFSQ+Ac&bL{oSnyas9t6pdE zaw`RJ4yt){m3!$cd{&8d7xzzJhSJ+?Wr$ubfuD)jA8T>_^&L4cHa2yz2m8|etwGS^ z`mCpHhqX!g&{zCHgw3k^UH~00X8J^m4EW3iqmX4=4VolYzEeQ>*IkkzRu^>U&c6ty zR?Xw0Bhb6tQwNc(_@Bq?wVdL9RAPykX92k1+D-w*tNu$6+hh0L_D7IYTWDOuVr3AV zT0J+V&$uxc?G4T9#kc{8RD0)tuvlaFr?Oo^=+}NuNJ!(-29U7 zK5JL!>E#DK=4&_Gqr2{`QIuqRbb0pIHl|m^<3U8k-OQLva$arqGm4uR@-;l@D(G?u za%^`*brls)d2_3UkpX>gfQ~=WCsO3o9$SrQQ8dE1Ydt#YK2Ro8t+>JFfetgyl=ofK zfo^r&11*rvy&_3 z{mTo;dNOX3_H)coJP!K(vBu}g*ftnU$5m$?Y%NKQq~S`ZdJG~Rv_Dh>Vua?WUdzX| zz4qt_Yw^bRQl>|D+m}u#T8Z6@h)z)eQ&%L*K3<+-tmQTTYy@-}GHUKgP+df581!%^ z_uDHtzJCytJuFxdxlkC;_ax|1g}Ik2>|i+rE$-GG1l6~LPMi=miRRj#I?2tCDp7gy z0WS^0`e2fl=!K>(%_e9FkInj@hd&8QMP(1-dBQ~n`)6YN4Oudo8LL^Qt$=GOM%4$j zmexYIacGS>){uAN_4wA)4T9(ynLzUyj2@$g-$zg zkG!*_G0dfMR#H2E*;s+E>%cg^eNic3OpoboPZ<$aRlfT^qikf?VNIU1iGJT#u6@KC z@%lY_q_^%3R~)2qRC3#JAxz!9ye|gyx-ZPa(=wR1%06)9Fwre_)VG6l297&G ze;2Q-a7OKZiunHcN7vd|IduOfv>+%q8jE6}vu9&2p!j{!AjJw}d%P$q`6UGoz-=gH zWkAtH&STS~%0fM#-a+G5GnMj{F}8oyEQ(g-&%9K8yCe5KM-3Go-+!j-@w_!24d~#t zP98#QC##%yDlG46-gN_dqo8BFAoHREX!+n=i^|HM9RlXd#y?*yPtXwP@Ye})B~4|b zUDi&|^)(eo;eRfNgqO_`y-dIp+i-KnAS?d84ziV(JM{AK_{lIwd*uP&g;?VP|Eu+& zh%AlY3`XjGbk-azk?Uii!@O!oE1*4QP0aX&vELHqi_y>oI35I>mpC}t@M3g!m?|$m z-4gQHj4AOHE>+Ow2F3b(7=4#bnnG#ryAIDKPq*Ypue`C62rX3)bQ!8})rHR>r#cIX zG#FOe2K2oIIw=kbchchxvwP!YF(e7P`06KitV^%L zNgXlNcx6rgJetFoM^$zWa_S9|*_}wwb;&K%hCr9kA_i*9pDR@7{^6BYj6|kK-y5Kp zU)zt;ULvgU(ttXc^U%jlsYoLYoksjwJC7${sJizM*YN`QVzs^+VeB|))O9WDk%7wp zT*@NNoh~G&4WdT4 z(|tjP8uYCHd32-8qoiT+DRwYzRQ!7d(IQPMCv~ZSzRM~&l@1+Q&X0+U{Wl&B>)*8y zP~7ViFYq|%u+6DvBBv{B&o7$M$Ks&k&8660rthEJT-!sYMZ9(nBy+zrSeY?oM~~c| z^<7mqb9jP8SD<|%!lK~IR!b;kO_Ww zeOVOM$bi0gKu4$v_bw+0f%dPjB$e@N1E9x;g%0Z87g%yDO$$0_vo0a1s6VR!eePya z6V#w9{mLELYkQP9CHiPeY@NB{tDUP(kjR7u7T zISarJez5dw*>cc;zUM)gVlUX4%y!=wr@+7BMpp8rfF`Z#Zp| zgYz8FADj=+?y6&zDgDodc9uj(%aU_e_)EQp*(f+i*#l`*kh zU);OuRL?jY9pgONqyHKky3^^g3LmV9gNjbB*uS~a64g{(s5G(CK$&ihIq}OcmE8Z! zMr|dh19vl^18bQ+qFA&^jP&Ry`8@Qmm9HtFl#3wZuj`MY)lEq~=<+Ryw)3Oi0lh^| z6TrJ^$Hy`|&Kd2FWqS0z1$y+tI=R=*PU>F!T|=iT2iy<4hz%8J>RUq=Bo;(C~3pUt9bnLk6(PIth4T3J+B1b=&i~-j$=$4pHUfB}g$IS&@^tgYT zK#97is4jhv1|8@s|MReCvB#{EL;d*oMGqJ}f@s3^6;1e>2Z_b*MVG`lM`*m4Fete& z?t{OU)j$VWpab3OA1}jG6QIXi2aGOE#8GC!CW6Z&nrN2M%TITaE1Ijx;i{n1^H`}G z5-WbbSq1HotT=83)5Y7aKH|bDmJIkz>VO`;iwQ5u+#3N`o=6XRxLoS8ws-q18bWb2 zhA^P-Ezt2>yX<7v+r~k6ta0ng+s+O3=qr9kMO(9t5-k>uSUUsspr`%ME1<95BBM(t zY`;Ynx&>h?>Eqs?wIn)p_7IA5j;@Ykw^TlVvKYJ5Cm{~{={nH;vtwn5Pe_2?FYawk zmL!VChnG-%rySYO1nId8|F0b{u2A;sbxK}KLFWjpnIKVg^tw#)x|A5~>RxeguLrug zt0gzILYI5==yPc-@n0l6bYei?i=aCb-R*YjcXf`cf4|L{1;KLXs*WOK!zL!9kvN35{iW&>{ zQ>k8JG9_{ExMNN-TdC^BM!ka<1a9kN@ddo}nWG1IcB87IgiI>@&!a94(c@DVV$veU zZM!c@jaUT-q0ih@C0kgtw-yLm-vu?RI6>%^gp1}v?pGaUIE>YS?hdR4a}+%)b7P>x z_c3D{g05yU+j9tlcS1L_YC}qBtH*<6S=@dEj@jjhqI4yAUOB);t)Y{D#pAuFiyJR@ zgM8FQna`N(U`G#oZBbB;67b|!x2@`g)F|j-gMMQ(t?V5d(DxGPV%9ggbY!E4M{~%? zYi#G|5VJ6g|D6F{R_8Z2Icm_$zmx8;|8Uz?=PHAq@js8|vPdR1NFdxUxBA|uDL;4n zC}7D-=8uWT!Nd5RSeh|$y;BorBU@@7Zzbj>41N+l`t3C^M62{>9CY`uanL&^$cR_5 zXKm}ikslo@_m+c#q=S$jKqo~h8&w;lE6e%lQd1p>$9vDbO8Zr)G!QxgTXP$-^z-yM z=mLXu`pCNWXW}Gm+-*WS+fzOIkIB7Tx;ft4L$Ekr`I=U- z*t5EcL2&|fh>a2ux-ikB_l+OrI3MtMq?;0dklM9Ek>Q)B^Avb3a7W6co5=OXN5fzn znKca;YVqFFZ_=TKTU!&JHCgdCm-kzZNJF59mVMiX%1r5r-GT-{zX#jcfWEgu7e~GT zM|NT8E(edJZj^IkztmWd4)FU*V%I8+3UnJU>sNw+DbMBV{Lf{4dJkIDJvuMlbO}y5 zy*RH*7x~0+b!<5Vboo9`@M59n02YyWD=|2;o`&Y%v-9oRF zz^|QCloE|u!OHn+x8%aR7)b=~*vzXIMf(9LL3jNq-n(k5WFc#1C(9kWml(A3Mc+5n zqvJ5HCZShO>spU43+6=HMU!g-de>h@Zl+cJ($x6-q-f@!?4w?IdOSr63cf~SKn-BnJd+X(1l2)yRfg1*HL_l>11REdKYbcO$UIBZ89_Hm`G z324B7N^?%=X{mF1!KDe?FWNCb4m!AxB`V*BxQ~h7C-Dr)q5F}wRdJ!54sDxKGj&> zC_oqIeC7kcJ&2hL=YlSJf};%R`v`Q}v8uN%#$CE^#D2#3++N}0TBD!?{CNV2C1HtQ zxH1*6n#fmjlSK!*%Ku!-l563-#Y= zdV%QEHK0p-pqB%H9G?`I2f#QCC^$4R+fvn)$Wl&jHas~ik*qCujt;%*=6^Gw?4P6s-)fnfccPvfNP zK^Nz=MI&hKh_A@y_vqaX==%b6DU7DH4n?XUknv$Ma%{9+NJNd-)u(V;ut2mAKIAU;h0pV57XzFa z(Eo@!2D7n_BJ*YJ1&B|c+{&R*(3wm<;0{I=|8^bd4n|jP@pumCYX5Ul=bXD&Fx7~n z7e&d`K9r)HGCj%8$xO^;q#u$uY=XV7pQ?-IDBtw%ToO#+ar`J{s$_sVNQ z%5&-b&qaMJe68p)fXyF+(x#u}{lxvs+V@^6%a`4mataw03+RH;>G9+J(v#XAok73E zd5@?lbb0sBq!OZ{C;bfQUfarKcq}1mqY2+=xZ>`*QAiIGE?!v4 zypjdIR&d_N?b6OJsuFdBK8Z;^`uXep=rdB+Bb>;hYe3(Npo_|f`ol2AerpZ%DeuV1 zxjx}Twj1G(Hp!Q0DL3wFp#K_x%mc1Fm(KrO{PH9*;w)vZ>%ZM3PFsjw3fUbiGN8Xx zOy1YZli!chRGspr)k~?_huD}#iFK5w<&rcr~|rm5r)>~YpbuWE|ge$5C1y99_Wi5 zGj!i)pobtY+A3ao_B5m@#>mLoxu#T0q)-p^c0qY*#R-K(Q2=% z@jnmigR@+*_2dU|L2Y$jUdNK@KR!rW*@-@J=IXKwYt$4V^b(63%P{|Z>eS}wi1tn# z4@(lyk{G)48Oi$oksEX4Wqdfb;uU-98eTD9En~JUHAO*7#015U-MefMpubI}TW1Z9 z@IFtxU6z@r*e+vNbjXG+yGs@w-*I~T8gT0{DH_q=j*PjX=SPc;;uYNYlAOY+V~9w{ zn}sCvVh!kf6?8O+{XmMDEw<1}+&OX;tT6)Uxy#+Q5^z_2E}j2* zc*fg;?DxgU;Ok3JGB%2X?ZuI`eGL|$_pjVU`F0A^YT=iq(H|d+YA&wGA}xvMh2&@; z2|6z%p7S$ajZY_a1xkW^hMU}~(>)D#!;tsw$pa`ln53UC`0$rJ}iSuTqk2@zwt4(u@9kmuJFC`yRCaj8Z+i z0HT+dN(%)rwPJNyzMH36%vh$ygH}7Xyo~S!mOMV06g0UQ2g!G_fh9m+^D$0rCq3&% z<^$CpeZ}h3(4COqSuNp&{GPPq-8!PSSXh0B$iB#D0jNN4cc1D|B|eLe6T_ZSU)NnZ zlLl|F<=kouUKezUx`m$IrCEIs;Kz);g8_XngHD`#*+j*{8Toi{8)q?_>;^!0XG}#n zZyTok`)fBsIAB(tOXq)HKH=ilQg-jxhjtm?B?UTqTShF3UxUHx(w(JH8@iLxek{kY zm@ynHs(#GM=g35yb$6G(M=wEeN#eshgX9+4YfhqaQ{PQk^7t?yY0Hmr;o)@g$h(TRm&yeaZTb-d&2T+!D}R+4xr_Y2B562!N`RHG`KCjmJ;0? zyUKvRFF_AQ(U%(wQGmXXd(p~UVsie!&nqjZ)kuaK(902Kg1{Y2aDF8S&yRkcnTi~n zZ0$Av=MoMyYL}`aa=rz{x2M9Z;nlx!#uN9;VQS)r9JF>-d{p84@K~}yUrru>QnE!% z^yn@>GI8kC6mWk_Z63^ngy#zQE7oF^j16b^@e`#J4jkO05LWGIe8a;YT{S|QQBeD* zSITOz7l`xnT$5O--eEQxCl}24Gm7$k-47B$1Hys|`a4DRhh;$Tk}yV3vUgE!UW#QZ zl_N&BxoZ+}yX%1-u+5Lu4N)Ug2RrMl-s~FCmHy{a7_C#T?)bOgny6&ae-3aZip9MN z8@9zhR6}G{)pm?@2TB*Neasau*DP+r^!pNEr=dhU+k60**8`me4^vdkk4BUL-9k-c zdwX)tWli~{GAkBuvm3CWuPXz3*Hm!Oahsc~FUTU;o-n&j)I!D^2c0o~&JdXdDen!2 zpbxo=2R_f~(KY_(q3%-qZ?OL)-B?3L$84;mTB}|IPA17+bmxg=3MBXT zCuh5fD6qh`Cm*+W!s&*?_|&TU)^JU_HV0>4Q#7I$EjE0P(UnP2ZNHww^#rAi0YY87 zO1roT)7MrCR0U;08t_yHa5+|O3}#P2`77^+tM0vy8`--Fa&ho?T`@kS)!Bj0M@8L&+|W*TA5gXgQxF>+zU-01plIhS$vAnVqRs>Y-GZ;k(XSZj**mFmSNwkBQi?UXLGn{muVp?_cP@hkEz~oT;UMUTTd(p)ybwFt6Oqk{l!1?@*qwI zg?yzU!<)J?pm#-4(15$yz$RqNjJ8X9r_847fzG{v&%6kuIxmlejBQ^8xu9$O&!e@2 zm2;FsOJJ{M=bi}lV=|yx9CW^pR=fMKPsM1upLm{tk5965R1$P{bMm25`{-vU?g2fS z0{y+DiK~N_ra_0~avrj&MR)Na13Jt?Dzih3Ml-I3w6i0=fDtRJ@|2DKi3JSYdY}j3 zKJ}s95TmvD@6_(Tv`l*7b~a{VS62q~t|$T>Pxem~U9P?M!V*9-AZtG6;ZjlOwb<^c z`|>bxZd(D$(L(hX8vpYU%chyiePV#uRYS=KeJCYu*nN1g7Q{IM{Zj}MPXr$&dsN&% zx#`4CPF^In>V9nE!$L8!a45zOM<+lh&W;S|Ls2TY1j60?+7zl5?$R2d-MXbtq12vjRot54e0v`bWEqTek98MHZibH zc}La-JrEOD9Bp~$zC4SfNggB<2*%Hr=YKBMF~eg@%df4^DL@~!22!blO72Io1QHSG z=ZpJE4BdZ97AL+Y5l6xGPfmWG1l`>d|BNEMB3X{^EeX(3VHD%3-D~Kc4C*XXRrRSk zh*Zle2%8*5Sx@*x2P(Al>8g0|)v1Joir>wIx}cZj5{uhwRQe>^x)qwlQgO2%hq>R_ zc}2&7zVAUVn~62Q3b%}16bA{kie7jW3k_iF360$XJ?5K?O?3ivo&R}xRcCa2#(+x_ z;KI0UH|5|B*|mh=m1Ki}ox;V8B}Wy{l7!1H`8H|7$tg|j|E559ajZiYcQrD8teBhr zIT;$0kPCujfs|k#C9#G5@LtA4OV${@WpfA4j-PFePh3;dfC_HV*;FgsY%RdpUO7Fe zB*aJq52lD z9+~DtKIoeK=R^iCp#$2po)_{^_RoT10e3vGH0XR|Q=&3rTzoRddGyRftVAW8uqGK_ z-Ax79OM(u7;+}C9njAmWarHUiIO zTo0V z+xUxU(VH8%O4HLT0zYGUl^8bb{LkgE61^G#&jwd$*~mI=l(pn`E=U3#p8qst$19j< zQf8<3+1H_DZ?h7TB>Hx8?3*;00dNqheSwl!5}M1x<3;ao4+`-buX$= zPdC}4%X+)wm{bMBqi%OoPj#9YI@G>H$PSjYs~?C+j%6IciAmp}u}O$sw|}g=4y*q2 z$>|92fIpIYHnwy*~D{Q!Ce4)o$?mS-T7U_!=)gZ7KcFSFj65xS=}i04U7Un9r=JZyxP zYzC!C9D`dFS9H+2l#RRO{#2({`NAKpiHUP@Kj3q5<$0oO58ynJPWgI@w1Fq2o<#}6 zKmx%1`0+Dn%Gl()?7sIq*iLdNO6AR13ao06?vKQ%BmL}>Rr@n(x}H97<;WRfu2r>v zdbDu%>{~u$O=(pXfqgR<+g8$>PA8eU_v4v2R6|nz@k(nz-z_;2E=1`}%jmaF}m`OxhAyhzYREM?;^Z+ARSE)F4lT=HDtwpnt? zKej4=N|`PWr2(`;y^L#CJ}S35!Uq+P48DfLSkH0b3qBSqs`)NH|Q<+AA9C(ZwhT`ZSY< z;4L8Q#P$!!AIP_@_fC`oJ-nAcvAAPx_!DE7;BwaV$`$a-sh-XY-au6o-l*CqhW|pRp=3scH0T>r zJ^H)p9(_4VLQF1k)1doawoK{WH@RuhrM|IHV(t_jN2zo7nhdD5=Y-BCg_CFnbTRcI z$hk|o>aG~PbAQEI_4B7ipKWd(h3bE|VHwbOTi3V@)Gs#nzGa6#Z*@cGvmK0f%G9el zv5HuZ|G7-}h8_gT#7O!@#F&_S0*P zE56MO0`=%C-Kzs1Ee2LrPV|}b@B7312$>%JKmdKoDqatC846|9oycj#sX@Z>7nwL) z88^HJy3YR`i*|yHlfh_Ip!>TfWGa;ClI)?XtDKmu$U<{hBv-t-f3cM`XhHu-Km7>^ z!|n@`q$V-)-SRkOO)dx1i6IM%@gp zA=k)7BQF>99RG8H!s1mWb&t-Vdv-lZRH%o+&Ccih*mnH<67;_UB#dEvxFE66CLmmx z2K`nm$9qla&2#~*NcQO9{*ZuDJap3vNR2>zcV`*|(Yl=8RtXOfyQdONYu0RSHC?w6 z0-b+3ch&ppwUJaaA|L(+Ds$zG0vTv(0VVnfu@UG$`sZRN7U1L$%YeR{BE%`o(!AIj z=yR@?{$-76%=FOWgfR{1_59C?^~}H^?3olj`T%u>`du|m=z$9H^Gnb-yO8R!b|g+F zT83j2po{;GPc43>LH|5u!$P(s7qv?8L86k&kPlBVH#I~Ko=Ss&Ns(?*fX-b1Iu+=o zXrl?!nLacW_p1Bp$pWlEXcryw@i+AnCWb?I#(=fMtd&G-zaAF&o$x2|jtj(qzF$GF z%+1DepF_Ly#fD)AVBNV0HRO;W2IF(f>+G4;_G;zH@jsWMXlUTN+0}ZvUv>krGILqc zV{C{nSZf%-V|;1KeHx=ePak+{)&05jBX}v$d3v!r4Z2s}B(8p8cG8rTyYmZ4&&cLgx=2VRWza`)jq~}lh#Jrj5YR>GPgxNLjZuIOLD2VH8D6OY(1}w- ze_?Jt(DVGyg*v|CwftqtUT@|Lh||+kV`MyTTR1)0rkFy{vr!s!f(FR)%%+QmH>e79 zIeB`F=UB)E@JT_lq*@zN(QAX+>#CFQTolG#Yn#;dVMg01`;X>YOUr=1TZ&$+cmYoU zuyp7XIa^)vG_Ah>oEKF@GIsx{rMe1Ht;{+8=g~zjYf}vbL{0bEMwA&MI#e`5{S*xf zv}VFw5qoIX6K;Z&d?x$4q_4UUBh%MRgATVQW1bV#mU@1G%xZV>;_O4hRf%n=utA{3 z-y!faHtYcN??y=N`sv&ynmM=K)oER^mfuNJDR9RP@)4D3s#9;5^A@UwV6j;sKDo zv&GFgzd-PQCZb8KJLeAE8CD|ARO}J#D}Z~T_hy?lzWVZY)dH=a?FWiMfeLiaAXs20NtZj4-@%)E zB*1f02K3!htzuo|xhc>&_kOi4yD`uO=U=shTMzU+|8ps8Iw-e?JkdhTMhfRx%dvJr zduFK0SFO!}PA|%)8{3dFrzOphjQI}b1dTCedh{34mT!YH&;Mv@%7O8iY~uu_t3-2< z2z(`fI)i7u(&Sdi9p!zi^!+uVrd@6;R}S5y>&zNLQ2zVG#F7U2oN=CGDOUzvu87Rq zmW;b+q2jt#SM8~48j}Hiw^RYlanQibtoqHnt8?P|J-R)}VVQbuk58073Rz@K=->y4zotGWT{eqq?ncGAb3mU%Q8Xw^n=O@pdQD;?MjrH- z&l>s!44oa@S-cD|fXzK+oI(YT-p=n1R z=z0F<;kh09GGk1+RL{U4i?L!pik7uxv-Ac5ED?mnt+vE}Kjn~)fY~}BJ-7TvD$JD2 zk4j%N)1#k~971E#J@fqRlFY8w#7sj7aMKVcxosBy{Csr546s{A;NGBRw0d9^wKNa(Jpc2sVv&bE9q0h-smcZmqtTqXDPFt)ZbaBgfG+OwoK%Y-?&tc< z8q)e?Cf0yKkM!eaKp&b4Ea7yNGN7N8G8H9gf?TjpcbDr^b9wpmh$*dH2|COs2&F-f z3fKN$pr53>;eI;K3*r`jM4tO52;At6_R>{TE!?OvWfx>X|04>s zo70i87x!aPhJ|aWN0+e)cX7XNkDlj$9-jNMi$Mpv*GZ7l*m9UJcLmeDv>hF7Pt_K- zM4Po4Ql4wTA4{JOU(XY(?%>1N^z)`cXT5R4N=>|+&h+#1NjTXUh`#h+kZ5?q#7HZe zlB0tNxT}>tdPxSiQGqVKf34>^%jwenoc;9bb*Vk%yf*Ob_UIMR!Cig~E<`6-AeRvK z0_O(wKPF3({^Fu)jc|baxwA(X&9r<1A(B+V_f93FbrXmhWWwH>1>r4Ze0o~0M z&4%psdr5M^P6oS}38_Uk@sDZId@1pq4n0w3qE9>d$YcAV=FFTvDo>}l6acDrOQ{=@ zzpT5T9_n7v*6HFEC>kGskS)))v}LLt#iHBOGNAtvg&l!I(B<+?zBhP6Bj*o|>KxHP zTplyI%mH1S|2(Q__CmKDktS1lT;97Wf{7%vzb!~V0{~Q@!(-W@ezf30oyUEi z3wi_l>2g2(#8qx>5>O9x-omeV+;NVF+XywFAE2O%ZvDPi;GK^*=64?1V$<XRf6MRro5rKny`MQ&He2llXPy&lK&*PX6J}Oa;F!wJjB} zepWu{(rT|~D!)3uFFl>$a7GsNxqb$8fLRX8>@Hwuj1Khqi?IT9EL{TVN@&Xi-F55l zr#s@K6W6(3@*Z<~^mc%@|MYySB)3Trk?l3ucPu&)F)`O=4ox>H50(4TOa+>~NklUlX?bZEs z-Ai^H3p=9*28nyj0bQCjh>6^aV+b~&AAq3O;(MPB|3(e(ia1u!jj1gw73g*R&k07> zBP|LuPdAEX&hBcmQ*pt|^U!|2sv^S=xEQbW;Su9GWG3@7Qi~8pLWlb4mHG2>hVGT` ze4kk+eA7>bYG!a*`a1;m&%h$kJ#kk5ndEU*I98(z34_wg6gsp8aqC!I?&C4m}AkJ!ckR^*aYZ(n@}bRAbBD5!cA8AN0XpS&-}L39G&xr zaDC9<&kTQG_mUuRfCX95mt{;_#V`1YieNspuw4y$0PW8zNDtqq`0f2VFTzT6kXd>A z=~1nqPKV5`+)$4mo%}}{_2&lk0~T}#tqg|JIvb$ndV$f6qC02lIO*Anknevkx}J`2 zJsFrtQE@ym5bS0nCFta02nWb%&|gJ~P;t>5{c}ifx4Z6<$zl{YGCtcq4I=rVOJAVj znc@8{t{)_x2ZAl>?_kHtq&p78QIjanj3Nkiep7-j4&Svp>m?dBpbqNjbV0LY8I>>V z%-K&bgD%tH9JQ$N9(`I@NIlWi9_4Ehns#s>5Q6ZH729qG@F>Xv#$SD9BoeueMladW3K zy+^wIIc&fMyZ-+C?#h6^heXK7ZJnbk?^yYTumT;iipkuXbwSVfKbIDqw}@`V)l{5d z*k>Cx1ll>vRv=>+!z(c4&B&}G7eU!`eeP#5%i{^#Pi=f<)fXM2b@Mksr9g0}g} zxbg6=O;RR(qQmMIF1aTHmUI6@oL-Bdzh@h&N9uzf?8?q^Pf5jg7h0N}N{7+S}UhOJ=G_v*K?Y zficP04UlCQtH$oKPv-x#i86*97W~scLv=Kx0v+7;Z{&Wus!LC`%D=2?VVN`3?nLI0 z>xSY& zOnxnlzdIW;n*rjigK05qH{hUu$j~0jiF)gIR>np?yoNk($Seq0P*T0Gh)>{GbjVIv z@1Gu?i(-8DA{O{=i>JB=G3O}3U-oLvLa%To~_#NST zpo=-o-I;PaLNN`QmvR0h_z3B%n!LLfH)wP0#L9bQH$d@FnX*{*+;D?>O-25W(kYwe z1IMyTr+Q@W`kl>)C|`K&RC1@S`CA{jCQKD;=j)up-tbM0$$-A66u#`6;XJB%@3K)R zb7ulH1iE)~uKziqxcI#11v=0f+*M9_oCSR_sC)FYn=O(akrOg79h*X&JIDky!|0rh zn=SONjYulr%k=0x^p;D=p?)SN9N#(xC+|z1^YcuXE^dN7h_av)gtI1n0UdgmG>$p7raT(C}nB*W4|H->WxkZBU zy%0cV6*p6X_+qt_HoEG-ORxwc>b1kV?2IyZ4Mv zQGo8$?a_UgWk4siGjng8eVFL&qH~_+rvlB$^e1eWof^8!RW)p*<(_&^oCPxcT_tQ* z()L|O1e+MBW3*Q<>cVuZp7lhuF-`_SNp%Zyt)l1Nol{B~(D#_a&K6za9-T^eYlo@T zCO4EnTjoE%H%e8c?#;t%^sKH-XDXg#sRyw$^ZHQ5*HsOJ2fVj({CahEs2K$F6lsLs z%7E@4pUv%^0X=ZnXU}y{mW1H_SkT8xVUO`LHuzE#liv$}7Jo*xszDcHteZwfy=i9Q zGHfgR2OQjNI~G634C#+Rk=AXs+~#6>WovY<^gXzHA&h%Q2J}6qsJC6xHgm0$h@>he z%V^ZXS`SioH0?ytZTYeSy9D5$EiTa)7)$q1ixe-yu;1R z(SzYm2Au3-oFd07IyKwl@e8WuTfH|-I#r;<7RO4%8vc8@8uWlc+vVZ#9+7mW)$nI$ zxoiw_%ihcLb14J*9#iz9Nl!kIB=&P{$7xyzY(+z$ z`wte8t=>|rXvFlI^;o*%iQ0UHJ?+^7>4)uf5R%P0#yCDk)ugipW^C!du!6re+O{0E?tbJ4R_JYn4mhBLf z54!BOpSwKc-tR6(IngHfm<;H9RAH^^)qXFs%U+D~_5Nc%@RZx5lJa)${a|DLYJ1d> zJesUzDbV2!NqH7@2jd}Ili5@%^1h@B=MHSQC>E;WAt&3VpA%$2=bzS}ql>@ZOrJ_r z`AqUNantXhra0(f!QwAk72pOi*H-w66GZJWeR_aJBpbQiuNMDMK@ zo}0d*^m?oQ`y^Z0P{^EK{R7UF6?KP`wK*@6*L*j-=gv-4EHQ6^?CADx$F2){&^|qV zDslGA7@G&BPPsvu09};Q+X^F?0Q|F&)119W>>Lfc*m_WU0XHQ_Kk@fTe$F;znS1Q) z$R3=o7vbONAIuG^@#Z0zgbe5hDd-qIvTEy)N*7UleN8RcU_R)+7`Iy}w?}XKJ`w6T z1N!`C1?b^I5S_Y;ab-na)2!IToq&D>mK|ocG-pA_JUg^y%?%9Q83fsrp&PR#GJiaZ z=b4Wl%4*9tM824EpQ(7u;-%ofXuM9v?JQc1vLle{mB`DvLwBimud|uvY_nC*E55UB zW;BHg8;Du8mD9ajGY#l_RM87_zK4G06kS7RxsroMKo2I0?^}+O2l|JLKpB~)^6&3$ zq6QtKKc^zLl?R=!J6U1zfo1epR?3he2DzD``!RlY`w7Hcp>B^Zu8_GfMGs`)6-S*w z;{jcwha&S7mS&=jnS@o$5bL>_O3qzRjOaU2wqdGV$)RXrJhHP%h^hVW+#~GhpsZ>eK zWslx1P)1Dg_{L^s6}!^oHFx)DKI!{#i<2$Fo-DiSKC_uNu<8!*Tsm+rMz=B-GA+kX zh^Ad*i5!fpz-1FO5g~pBeM5U1tr|b54(&{}DVY}tZqV6OD|}tOh^Ajt&I@CGl{lQ6 zN+P-UWI*3LTJHZ_)Y|W72I`n$*@_ZO45NYP$imG_16N()q7m-zt1Fc$4LZiNl%O-_ zKU7qeihW!)rd;*>0>8zIDmfUki&a|?wi*Gwduq5V?sls9G&AS_wm_0;n&o+mUn|Gr zT<0KC_}$lm3SN&~NJqWLmE|6PgD`7Z_2zWdB0Rr??B@fJ3nt>7qkS+xmolL59XWm3 zljw&qhHoRF^Wdw3?A-D|$N15x@6doAz){u8lsJr1O0Hz;7-+y>#42O$O#o@oeFlqE zJ4pAi?9jcJMH^Xlhi(}TFqs1i1Dx?V{Y7!!;p!fJRkLQce5BR{Ie!vwpvoJ7!BcKNp3y9b_7j)-kF@E%z z7IYXKt4t}-N6g`_5_I;usCC(0A^VLi=p0(F!IqtY=qbgb`)E{uF;4z{FG_48hqpVF zDGKP}q~&ci1l|;`x@SyE`3uT-A|CUa%C|H9vDO~pg!pS^bR{ee|j`BBMzds zw!>$ryppjmYNP>u?+DXzZJ}9n{h_<`KmUi5-nUZ zW#T@E4bn~Fs#oS-30e|>uHkjroj4msHl_!`^D{mM@uosHo9miT-TdhUI}|x{dFK>6 zTyozx71DsdmxSqd8A>L%2dIz^r`sskyqy#Yn!74U22Mhw3o!7Ejdw8736wF>n92xVMQuM9G#<=}75CX1BOU`0!nNiDU; zZ{I1tonGV$|G5BMU-v%Ro-67X#%zK{gFdrPHL~sWCQ>hddWibm*4w8l0#oii8PNBZ zuyb0#8v+|Zs5f@FRuZ7 zsTh^g(^Zvzr<1)E73epnyx`^eZ)NQYcd^Bp`z%nanX6nsA^5V8?a{-$%Fk_%>=0D1 zf%V2j2VRG0kDPwBEHXOKy$159hYj~Sb_BAp0sRmFU1(BW&@2AuG0#>t=+E7tv}&uJ zXy^z>^K=-G^TBIV_UQe}BZ>4ei^9C^NzlPNKil^c{7+S-KN4kQldC|#KD8?^&u=Td zNOr5#v+E*3XB)tB) zmSQ=`!4Ib!lt^b~Zw`}w*$VHvC)%iPa7d}+RBO(&va5T{yuo$w~@&$=;HY{SJvPkdHK^L`cLy`$97ouO=UEo?={JbZEBD9ueG3;{m<*@!8UL`9q4joyBrZM z=xf`Q&4V1nKA0Kq%b_z`?JGfFn!Pb<`(2u?HP7#BWyY!D3GPi)+=|#kMMZSm zZY*2fIj0WE^k^#3L2*j@te@SnWBeS|v(fK(NeMb^vsL9G-pPw^xoXgTp9g$g4(Or@ zM1K)?;?@Jbq|Ki$fA_Zk`zX<#OfaAy^q`mbP{bbxKP_sIrbAEppR3Mf(E=r#Zc-*i ztPQDQY;uJ@b|=)jRhgMZg3GrnuS)SriEJs=>#WS~-(mUy%ifPaP;SjP(xWp~Sj4HW zB6Jhm8l`SXl{EUCtCA=N?vG)j@yr6A_}#m1iK!74_rBRt#Kf!Ye~b5NT_>|TsDjQU z%4?k_e>y3mPuJ|Sk?wu%JsHsVg2Gx6%E8Wq0DeRM=c+R`$yf!mcs}UCAZ^7Fxb@S5 zzG#$kl^HJyl%NMxl`ZzA>;F ze#|sqiztIh+9)y6xtgbgTT;Hy`1Sd8b^dgMzH4n;nGD{!Z|bB0eJ`j6x}1tV=4w){ zrTouTr;!=Zz6jcKK@WbXG+S{hA&f7D%78L`oWG%9E3dmior?JhW$E3JZFoF52{$-L z_diuFa&J*0^owd|f{Xzb=z$A&=|D&SuGu4G5QSiSIiRZ|@nZN|$ImRs+Rg*r*X*a; zquyI_HzuY>Kjc6cGwi0jARD0svi|4F)7bQQD93Kofj;wbRi3qq|MONY=qoz1TVSE- z=rrF|f&Q|ct+@ncqr8YY$z;;#V%$5~(xYg(0wL}$S201*ag1jJP;eduI?!#o#ijvW z49Ztrf^tAd#GVT-)B|0-@lRCw(}#T2cB!Zp)PR0SfSz>dD5BXcp1h$_rPBWAs#9R} zRrqCHrIIK9Cq+%Ft4k*-G?_6)zs04`_q&K>dUQ*SK^D7Nw^M1&yGdcejW=cI$J{Lq zQk97cbngzu7o9hhi-&y`mVcsvewA%z=F6g0>~B+b?sK$_`@ED|ysI9@`w;z#xcnX6 z?)uqGu9=33XZF*JbjWn~m3>tOQ!=3M6{RXlAMjJDh7|tis#Bm_)s|e<^ORUGK?YG> z9n&J-w8#Sm=q_*f-7!|S=W;~d{F5B`X4O~esnI>#^RIE?7FC(3KrhWxt#Xf5JK&tD zXlNWXLNr>LQH2Edy(w6k5}BZ;m*f~r2fD8aRUJPb(LpSIK^5rf{d9*|C&A8r5W-z4 z1NvT3yrPJUb{w19;!^paXHFr8nTv1Nxm8vw*s2bc*@=&)4x$G^^E4S(1sZn|q)72B z`k?ucP3tVUcwIThT#yCb^SmQfUsd+#rzni#$q2P!&_qR}AfEg#mc0iFEPDZIdUUdB zMUV~cRXMJG#Y*i~Ww~S*`l*$E73i*;+)sDNZ1>%LZJSw@0e!D14zDfxfaY(K6;b7X zo;ii6Y@IynJanK3{ChdAwz5~pGM+>aw*_=I@-I3lJ4YAj|I8E-V*<{uR6QrX$IH&q zy>bMMlvJSeld>!Mj)OeaT7-K|b}>%O!_oI#4LYCZP&Mcn4~o3=l%PX!LoVpzbq?9Z z>Vpn$dv!lup2+zi_&>|B_EVQ`K;P>MeU3+b0=`?$fGYY^mH&DAF!5)ox*|nYsU%}N zec)&-Bt^~_K6BMQI`5+#o{C|>Nh;9ARAZTP;piilaS0b+&Za{~n(ehu6cYjqja1(A z9A$V{j9UH7c3=ps|Eu0RY^%#ui<|N|kGlh8LVL}zVFNsBqdG1?0(DW!OQZdC3Aa6O z)#Z5}tb17o^t~?ma-CxHTcW39UD*yA;QKEK?ZqKVo;I~5GwQ4uh@PyVxh;g2p zI`p(u*QH1dn^jo_;VI>u)mj6J*bgOTIVeH*vadvR@$V=>59TVtbN-ff-wlCdv%>v!OdM+-Tt|@s{SXIT^v@rzDn}CK?C)6R zf1W%DV`nFayow~SY3u1wE$H}?%?YdSM8)h~+j~zQcW>x$m%d&JUQ%A?T7XP%%Aj3Y z&dS9&P<#~^URB+5;7?XUVqeR%uBt+U{?m0}VRVMC16^Ks+7xZj#t`%-{8$5^%l-7u zXg?j_!j~(iO8ZU*^u4a|<%*Ym_nN2zcvsp=|MSY1!@opj>dv7`x)OAN$ugp-4s_>K zmKcL4`rMnbvVp<&ENSAI0i6eDDHCq2m(5u?EO4clX zx)la@Q&*z0L{+-X3-l39qMq|uUGRS*qm*xQHI)y1_`FEeTSzaejX{8qQr_$O@>*ZA zSG+;__)5@0xj>IVVc-M2qz>so-_Yb>aorwB8O&N1{zDLKR5pT9*?zChWgNXAg3ji? zHn2$iT;B{qcqf~+kDXZ3GNA86eYa7JfwyN@$*YQG^la{w(a`ch=eHk$b(Kdh|9qh9 zWyFsU;>=!u)Y}XOCFtIFkbtfx@@9Gw7q2l(vV(li?0A}Ou)p=OkaI3OrNrk-BQyspzkv|2+v&w8$wrP z%~z_R+vrU(f@Z9mj89RKg8xx{<-zpl^x}D?-gzweEgVuPKqp^nLM7c%v{m;yznph1 z3FJcM!>Nbv+m+wFMiC576v$7?awX_ZrrFo#k9VjGTeMp{azGcuhb=OujQS;&%dNR@ z)%G?I^Z@$8z~>M)pdS{X%S6P)dVKz>Z8FZF{!3-M*hl3i7pn$7WXD`hIS4=*VnP6@iJw3bDaeT5A@hgr%(L(Wbe=)rQN z%ba54?R|GRTwm9y5+;aI6TO5;h~60tqYEK=Cn9=h^iB|+Xo)DJMGcW4x*)p9=z`J9 zAV$O>%5YD9@Atj;zR!K`fA{`(=Xqw%o_*F{`|P#WUT2rJ)*f@682bHvRRl$t`^&1) zdqLupF!F5T?#&;>SS42M@YB?Zwe`1>-y5G;Eqd%60sFZtZFx>{vBe4QQy$+)R_ml3 zoRQKlEUQQ}@bP@3uqA86gn~nQ*~>KNNlev{@E6onoe=BKG!(8=`!ihvg0A)57jf5X~f+-;Xmld+v7?|A;TES(f(&B3e+; zKHlkhE&AuHbmE-_X5VuTQ8=O&NTy;Kma zFpE^$g@D&#Wl@Po##yQ5R!J9i-dyJlPqn6FFW**((&J_w5Uq5c5AMFI_fC|Mb=xE1 zN9(z&${}?pi9Mq&kbS&Zd#!rgJSHTCFOqAgxcb8Vs^7&hWxDkD;}zCD*+?+_llyIwV0z^2$=;jzVfUX?v-ehCEZH zZC&At^HaBI9%mqA%H=ByB>q@knE9#wp<=eD|F@)q<^_mLlvpblF}9Z&&PVryuQlND z-mok(pQLT$=frnH6fVS90KLBXQek>zaA>+@{2l3p>(~7?bWXIU(4pzc>F|pH*s9X zN~|mkosP;y+9vivqZ2h;us|{0SIJwYjTaP{X23^T*$YY484S^C`1!M38B2>rxDTfFZ`qXiMK$> zpN3jis?CWd13)w}R0>lK`!{AV&iCRBXAz1Rj$G~r(P+IG)_lS4s4*4fH#UzE%= zU639Qm%N)cS)5aTo0J!6HwPrzZvgL@+vIqx94KhAvactB>& z%uToc`l8}DeL|RiDjpO;Uf24Gda-gX0I|9 z^^Yx!#KWyfcbX|CJ*Uc+(dVJ(S55z7xuLn`gP4)CQWCL~VAm3=$rjKV!l%=jU`V_u z^hWa)`cKE3ca?U&Wq|lh;ypcvIH)-7(;Rr%O{G*a*@*D* zUB6=$yGHay)|l6ej@Rd7L2Q?YB4@3-^y*+lR@X!^KF$-ApV0DFE|tGgWB-(Xd^?nt zo7`v(ajiGNvn7Q*MSIrI`)FH*vsOqZ;7z>&4N*S{565>4Kx0HqA`F$h+Lc5#PGt;M zo;FrbQLzmmsvMt#-=JhMvjgnM@wl< zNA%o$X7iBJ3EW0#Z^?mE(Y;$mE^pX&2c?(ynna++r|h%u!0^%esq?FwkeBYn;>}?m z$E5OshM%G@mDUrzzWhn{uH^M`$5sZRmsl6$#Wi@opNQ|QM>iFDvuR0xrVDCg7BHjp zitSMHO%WEC6X>{%{yj!~YO~dZOY`FaV$Ft@L}~TK7Z2@?KNwLj&kn%JEJ|zkI8z$M z?(@$tqQoCFrTa5P8CmCn&TFHBuK3i$r6w1Q6aphEU~GsKBy~t#rz8+Hkj|h!A>~Pi z2oaxcx8|Vk^7rquPnbCr>>|Vcsi;`ce@dNim~f$)gJy_O{gR^6d!(uOPtCJ__?(pg zRWHRl0mltQOvHJR6se4Y*6R*Ys_g7^?8ezu`Ag-J@e)S)N$o57eeaPxn5q} z@R~7Z=*>}dFegQZn#qvnIy00c?*W0y5kdorR^ zgF!@lJrz9p6=|6cX0R+NkdE%s5=E(oPe_*wQKY;xAcN$R2O<*J1wHWKd)8%x6rlMO zrs<8JsZ)c2z(9w_^yVSCH&W{-jErx}t%7-eA(MP$L@OaWXD-ylX zz5*hE=vchS{~&n=r=H(%t`fFiEhl7o+2A?f ztRtxL@9Fn^J&)bf05xkK#2?>{_^4)!^nUj)_X;#6hc<6MH1w}Ltm65s@_8rreiz;J zcDZ9(liDc`)>_oYCwb2G=gTp|2VG90NF~Fms`i=a*8O4o1WMq&O9JV!4jf39z1DL| z(oms`s$g-GSRgV`rf8mIZ+TXeTj&#BivGk>{EaNOW`Cs$_pxjqC)$XR@o%;;9Jgfi ztAxNA%#Z7G4bO{m6W$YszAmH3e`+u#7k6D0gvLm*wLy@Uo%KqyB{FN|Nt;RAk*r_j zO9sa7C>zpF{^B(=dtbSrZo7DN2G{PykmH+&qp6PLvn1&#*dW*y#cCXtp0RVZLUw^#ZRJ0 z#>MJJCW;Oi4Jnz$wOuL2^aC36?N|(TdB>>Y8)BXlR_4PL!CTo&abU^^*$qG^RnJ}t z9H!|WLtAGJKWU2FZ+2yDmM)DObNt!37_$2e4PgK#1Da_PL(47IiwZ;#vK3P`8zje= z@_OxuL)$Aw_1-3o9uw_y_Gw@;M_usE)xcfqJMTy2d+JjO3=W@LlTkPF-)O1o`$mqs z-4Iej-)_9Dgs<;12=crZ2LDKnr#%8T5gxo+mlkf4neV8jPb4?KTHt}8U-P$EwxV?( zg?FpuE|e4w1z5#hF??+Nel08XBvK$uSn)o|D09T2$j;{?g3t0jmZnKQbQP~kNy+U2 z!yZ51liTCBv`xA6TX+?+W+WG=h61m9eQdGu_FpdE?n;bga36ZhUr7Y0jS;vKp0C~t z`lR(eo)TOA&LlBf;2{VqQ>RIRz%Kb@Zk(cL2OrgfI%E{*S>0m5a1#gH;`!~SUp{G+N8+C_>)We+2sNr|gb zEI(27iWClYJ3RZoWmO-yV;5y5-z>KZ;TqKM&^D~!avlibj)XVR;AJk@!G6`gOCkxp zQ#|LzFjiJDBMDzysk4xm@1tH8zq@YDDzIfU^}Oi;b=3Ro>!9z1K-FhD_n z6+MH2;!5@5zeB!RHQjJmP)j&^t~|rh7)H^&WYQn)-fCX*wPl&;xJu@WiJdYXDE(qx z*Yy=AXt8X+v1m}&uW>BIn5AZ7f2#b^{2)P2HS9P}uW`uA%s@3eTR6nc0G?& zI7JLh24{WQ$!rPF@e#QB5}g<;CV`Oep-+TK@9W|y*HK*gE@GuezFFcy;%M4&N%{|8 zreAjFoIgr|ZrP1}qT8-O)T>wz!^qF$X~pv-On0R$$A*@2r6CRBHGH;}YMM5+40fqw z+Q{sP$2ISCq7jT`s(~TAiy9ht;0dfh2tHNnD;sz;HZT7j4RWAYhe9!?*Tvo_lAIWH zri8UM%GQM3B0-I7$=;a74sr@l{1~E9-aj(?9f#rL4y{3tA5QxG(cUnz zX>tbGKO0FIpjal=9uWN6n4jUj@-MHqN^U@8lM~TSq_2B5ID@70G>FDXg6I{5aJUM z=ac{*+><@gRiN2Eg0n1~0$zFkeXC{k8HeC69WFl^Pqz~p&J==d44*}^-f)?U%v#Z53v9mw+1gGP7TJ);M^ z{(UbJ({0zVR!_}}MQK6voXx5T9|3NiwfEX@{2kYTf83Y zRVQn8d>;ND1UdaY=Y_P6Z7Nahy(Y8*tP3^nHs2(F%K)iYuj6@Rz0#Ai+b+~WPdBzl zM6@TCo?l-$2qP?9StA1{^k|~pl zsURGPCqA??rXrH$yP0#8tVG(fV69Xn2Lxr#xq3K2Euya-nX*ehskVOrnM45g1h0y3 z2avtrCl5nE#}6Ub;$?pYYBgl<^`TpnvQ`(??U&1N8p;+${xrVuY)Cn3?5w_lKj(Rz zXGH-ChaH*at(qa}oI;j}c0>%olaW@tI*EY@`AQ8Y%YAg;b=;69o!j%|{O=bf%r0$z z$x5iP$(Quf#9#SrT&2UsG$}rx41#%`;Q%%N9W6{$wRF;*IhP2xDImNu2q3zRmdild zAJcZ zKOPs_on&mBe|2@>87u#xZKUN7LnLlwdf9)_Vt*e0I@KGk{Xyxl*Ifc?|NbyYS}VCW z7$4rFRrc29{oNzWYf-1s>t`OP&9=x$t0HHh;xvxe;1=TNu?kMb+Ld59&xOYElSVV? z)rTF)lB%;i51Y{W;p6?%ooT$==)A*vlgSaMZFGlk%Xn^8q8Eer1-hhl!f;pXxl3-s|ip~M1rdW+IAn0x1fF`&qaYQf9_b84SVrE zZ@ZxQp!-obm-?q2t(3`#m2MN1qY*`G&~)odWIY7=hK;M^N%o>r5K{V27e|#f7oF%E zr!2?j^Vmo#^pmhJY1^ez=s?yOGM))&2zh>VcY{5CNFT%JH zK{$$Jot>&;Vr>1FdZXT=4UBY$i3$CfV=Vhw8D>#XLlYh0_jRIM5Aj7;a`>JbuVG3LQgg0K*;>~<9x)<&sn1lbS#7#0ZVVobGnivFrM`bZ zq=BqFSCD5nj5&MJ`SXg(dZ&tnZ+rLdhjj$2`-W8k5euXeTG_+DvK288#B>)Vn^hIt+^M6cV+$CK+)Js- zz{f=x+_o3l)WI}(tw|E8kwE4f9@4=hmhE5vagji9coK?rH9r2Id9*I%;%;?KZHTAvV&U(VI?wScPTlU6{P7CGoQp?~H2mq-YvAA~7d~bv9E? zY5>|dzGQ1sTk>c=G~g-HpI=#!528-TCliB*}j0gHdz+x2e`O7^w`>ZyK)0G2^-@;p~+zKf#qMk;42 z0R7c|WBlZ$3u0e8;niwEeRQqW`nI_@zghMBq=~X%@KK}EsfX|c*6evLD|U5$8y^PVVZNJsVh8OuYhbupE zQutUZpS|vV4o}IU`19dIG&=P*IrrJ8x0cb|$&1STQ566OX1hsSe~tszf}NBSOVkf6 z;n8G@e!msi%5>)0?J=Rx$GF7NE0}w&&r`k;Hpm72>NxQ>L;k?c+p1J45e)OXS#*HoB+S`*djf z1kL>DLmIoAf^w7*DC@vJ1@udBoXh7P`WE@NK<3zVP@L20`08UE@rsxZ**Qnlae*UU zRP~rF4N*6Ms2I1yWjVB!B zu^_AB4eiBE(7&Z^6rLE2uEhkfzT|<-7}zIBIK#I6Wh{wM4mvx_BV7c5-aOY{E-7&n z*ocJsxP_&cP*qb?+4zSZu*Y}-OE3ykFp8jV*ho zNns%s#_uhp?SKTf=U+qSV1kd-d>eeAZ4MzO-G}C*--z-*Wf5p<&K8-Ecr%iE9!we9 zzXebFqStaOM&uy2h|i$wV)EN< zi~$6Ha#MXjt7A?Yec+z;P!(b6$?88JDpO7awH3+kMOznpt$7N3nh1}fh+RoN2DF?b z?X=U+6;5sMaG7D#4(=@U-O09W?Jt42l*ZdwDvKyvAIyd#pinQ8A*<1uVC*Y0IrzQR z9>y|#O?V3CoVDZS7@@KJ+Ul>Cr8Mi|yI6r11Jhh=9=#;<)bagS_&9_v5j#*2S28Xz9U+M`jnYcLtZNmIsWtLZUyET9W9CfId2-U3 z8FJNPKXh(}F%*#)xGVKb@4Qc{+4$gYScxB+^#el?l7!K#&A83z#Bqt~uHCZ}G(-BQ zQc2gv_)Q~ws?F0YPz<0ZGMvxo^ABe=&FS)K-k|UQFxS>4i@J?T-+}oX@5r?yL(jk5 z>XvboG(y>=Ve}*z5k&bQj0pd>qP#a|2L_V*F&1I9)KA;R`kPLY9!}CT<;4wseFp^x z)Pq))y_GK|*LoP4<@e0eVa71QiEVSGDQQjCpUw)~54Iv$12i3L)XV(4nhyum&V95?K$=%s{dNH2QoLuEgRk)9 zV)(uUG2Ay>U@}FM4ie(jit#NKN3lw$GbFm_+|%7bNSkztXJo43<6Z*CsqH3K? zr+qHvf2`#1>ffkFVNMRLKharlMqZhMU%jvbVo-gW;o$~D7)41|1}?y`VPGqoU7r!o z=c($qI%CQ+5&em(N19Ay%-Z5zw1q%_>g+cp5v?&X7eBgSa{WNx*? z`uy$=G!t4j9Me{%nxmA%3j+bx&*veZGx6VfyRtO^4&KbtH0L_V$q@t$Kdb$x*)@CdLS(yqcwm$;>0NLXr!&$1mt#)O{ynA>NZSOJKRy zJxuK+YB4nwsKhe6H8w2+isX z8^_ZiY?!+I=YfG8HOxwo;BGA2>RHOKPjZkcg=NpeP_${=L!jS@`A(nhUj@??l3lEf zuAEd_AkPYq%eh{T0Rw#5tGhqskTRQLO=A#uD+EhxqQ<$l7PDOSjGo}*)@JiJM$#*V zA$F6!?^FR>YzGd z$9X;xBf2TJi7~92K4T^7-pIY3VrWZW(F4NsyF71R-k=MYuKbD#d{sJ=i>~~!UnNDd zBzk@X!8(MV7_C4B%-W_)M5{n7@^2i3X%?5#%_%k6Z+r4;DQtFL-6dVuX6DeYI0hO= ztMWmqcUQ)Lg1PCKt?$Op*!~&fJ50T6S6jj{7>;Rj?QfG-6SRy<_qz@v5JGu<3}?-7 zI7mU#?C?OM$JWc|iup6^pM$$ud>R2!D6Pt(tLr@HG^zjP&0Iwc5TgNQ8ondE7h_6gu8=v?C(#@UN36X*q%)C+9_ir zrNPp`^hje`f$n+X@tf~q*EUfh0ps7zj|gs?d?$rM+2D;X+A9u;3JQaF{%v47r;h11z_+;pwcdEt1?rbOf2@dCsGM;cwIX^3HDTR=UEHoGLB~VAYhD7sfXk!@CUU1I+%EWW>cm=zThj*&o9Y?_p(oBL#=EHTjMl_|-;=fx6Jp;V9G zhNGhI8Qr<}4u?xPNd{Qc^pICu`NVFFYM?Hy?J38>e;VEJopnYT^;82RyWiA&W3I6(-K#zXH?5#55zuBBi+n zMTa!_2Ju4|F;SS4k65w@+R*p80tU6WE~&H5Twf=yPJI7jeUw9yZt)%%VcrKY&}HhY zT{=vqe0}Kmu<0VOZ*llKyN<~6Qat77ee|UiZmFYr)5RMW7dI_|Q_Jt*c6 z{Pia$WXVR9(;E3rU=LM9pSvmx3~Ca`-}sZ7VSa{UN7l9yB2h#v1XVh((FpQ-@fSbK z&VDmCQ$IV)L;qmg_G#YE;`x{_rFCiK4TydX?Z=3hkB4^6p$|E;#VAp+fP$g>G8<_{ zigzG^zO|{`2nz>PS;52p3x_0C+(oU#&9STDew!m3DK%j0S?exo@sf-PtT&WmksT*X z8Vm4!A*=W9nNXf4 zAc(v%Lb{qy-8Ds!Q^wj4xggjd((w#20@!I?!(Qv`>|zvAe(!MJnF!BDBp7-TOoVm& z%(BZ==DzlVwKevy+tuoWyju}}e*HX4iX+kgdTm{F!<M1&!qH5O;O{NF#o1c3y5F`=|E2b5Rw8F_<`zJs)NFzn@-T0!}9Q0pbnsl z0x?$I30av}w=mMQ{ORG-Uz4WaTFKqU30$jQm;r~zN3Hv}srj$sERYYPb8@_5mN$C) z4&1Gi)pZ+G2fK-}z$Qvu{sdsIT+~=^yWWRWOCUK&DqLbMhI)S;a<@vwXy0!m4-$HL zUzMTqV!z+?HWsVVOi_*L+IRGFV*u-Gj|mGS$^q{3sfa07FNZnBf`o8+v$2C4Jj(r5 zm0MbH;*H3$xt$mkQ3tJT0z8)Q_x3dO>nn9d`knlEeEH_E;KGG|Rgt=GZAaJ?iG}X<9VGPomU1p z7&TAN@AoxlGXcK26*|d27$VlVlW&D`zlxfL)i4NCziaDs2ACH>)QPonkTOL+(tYH@*xQZ*Qq=434!2{v=_7N>#=*DqS3~<(-^} z?AU4c+|0?mKf4V?_X3_Nfrki^Jry(JlbN6k&q(HT_*q9d_D7khRVEYD*?lVxV~9L} z?iQ0@?{|!^ckWT-iCxyX6}zM^<%vBNoSVa458G?_=*eq5XkMLw$%J@Gw zT|7ykJ}Xp5>vNcqkAr9$$~KINcVS=X*CW~G(x*h9r$;P70RQ%5)#+8tMu*BCaQD5W zrAuX!I7_*jJ>A7o(Xc0i-{Ly}v6^jD<@{EVVGb6{W``k1ymG;`72e+-JjfSu`Vzr{ zN?~4;dJ!v1L_GqtX?XBlL2{mdsMd^90G6X4Ae{B!86%r&qXM?dMlsy_7iI;f*b#h+ z5rwbRn+GK`|EOCYOy?Ao3jY<`t+*`zph;14028#QWLx4zZ?pP2l z`KZf?|Fnwm$KV8z$KvvLKgXfJ`K1K7RNz#r&p^HBgg{^81KNbc2kh}JGkkrJ*8)z13m4Y&Oh&^X`fhZj_Tk0V$$%GE&$@-nf3U@Y2WX zsz3Q5gXtjM1XsDA#Bk0MT-k>ltBH;Uf4KoTo8-yMjDgSq|5TdRR2E6U$?rKYS%bg6 zSs)#}@~jO#YGqYM$cNQ9k_yQD=+_KN@m4MoS{tesf~;v7e67x58E^P$wnh&;oGPe5 z5h>aIE-^*Lg94NHhv&g}%dpv>Jd;qBa8|&EpXH)|mTbJ#tpngIPmoLS8dpROo zxnzmq9zBk|1Y&m6YsSc9IUVMN8L0FrNG#;{JEpXbKO;P2kG!y!ImHLH?P+s$9&9qN zE=8!xF{!uEfb7v`|Enyzkc! z>FBK@<5Vdd?8bxO+f?K|B+@Ob>fHy#3GOn!i|X*b+X1+!`-H9dC^ViyGrijK{FUW` z|IKd&8#VLV=;}%1LVp&;kzX6fFWcjn74v(wm)4$63D<2~()gXs$24cu>`OOl~Ry|{mQw(5}Ye;<0O1K;d(z|0+w?&%}} zvIbyQ&=AV!=oaB%YohYL`H|cG)!5k!Eof(a>@sYso=OG0t58AjUa2b#PP@)pa2Bbx zrf0yTN+AD-a(ag0hz6xpxyz;(RF4b1(gk34kN**@%G?nvQn<^nc41;TVe5F&U4Ar? z7$Dbxc*MmvAZT1^{-G0P`dCppFBp2<<)R=dGG7Pu6X1ym{{;sK`CnXe_Xu0l$8FgE zAN(SEZ(>uRpYN=7W0R7=bW{yC$g3@n!uT-Jn)yyD&XQjBm#nIC5ILvb47p**k3qE1 z#GJc-erwm+f`jvUS7b*}&h!9~t9KCDu{^hY$?*R_|Mw}dABvNwgJ0u!?Fik&!^3N^ zGtscu(0GV<6Zk`nM~zR2hYzIwei`wJ{<#_fX{P^5TLEeA|AHX^(liAB6W%HA#y{}( zK>ptkaFE|W|Nr|+jE9#7!n*C?e~8aaPxTXWFPo{E|6wwrVSL}{&x*8(TX(32|{zanWErcL0F>e*tjw^l-Oxhx;gbxZ689_u?CpK*;CRA9B0h>d<^NIF-`hrZ-adbe|0Qv=pHTn+!0_+#s;)LZ zj!&Ed{tX1sn|g}7=0AXd`*yA-%0OG)|G@;n2n`hcdhx#lnf@nGm>sVx07Uoi>P(fM zDS1Ef@NxRvASZVRJmDIO2wMPz>Mw|stu4gX!!yv^$-xnhr=%o=n=;}DZqoku&F6ML ew%$&j|4_qL#MbGW^z^Uz;c2L7E7vMMjrt#~XXms4 literal 0 HcmV?d00001