From 55c28619da67cd3f770386123a5e920479a6a7f3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 8 Sep 2025 12:52:47 +0200 Subject: [PATCH 001/665] undistort asl folder --- tools/undistort_asl_folder.py | 168 ++++++++++++++++++++++++++++++++++ 1 file changed, 168 insertions(+) create mode 100644 tools/undistort_asl_folder.py diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py new file mode 100644 index 0000000..06bfea5 --- /dev/null +++ b/tools/undistort_asl_folder.py @@ -0,0 +1,168 @@ +import argparse +import copy +import json +import shutil +import subprocess +import tempfile +from pathlib import Path +from typing import Dict + +import pycolmap +from tqdm import tqdm + +from lamaria.utils.utils import ( + ARIA_CAMERAS, + add_cameras_to_reconstruction, +) + + +def undistort_reconstruction( + image_path: Path, + rec_path: Path, + output_path: Path, + ratio_blank_pixels: float = 0.2, + verbose: bool = False, +) -> Dict[int, pycolmap.Camera]: + with tempfile.TemporaryDirectory() as tmp_path: + tmp_path = Path(tmp_path) + + # Run COLMAP undistortion + print( + f"Undistorting the images to {tmp_path}, this may take a while..." + ) + cmd = f"colmap image_undistorter --image_path {image_path} \ + --input_path {rec_path} --output_path {tmp_path} \ + --blank_pixels {ratio_blank_pixels}" + stdout = None if verbose else subprocess.PIPE + out = subprocess.run( + cmd, shell=True, stderr=subprocess.STDOUT, stdout=stdout, check=True + ) + if out.returncode: + msg = f"Command '{cmd}' returned {out.returncode}." + if out.stdout: + msg += "\n" + out.stdout.decode("utf-8") + raise subprocess.SubprocessError(msg) + print("Done undistorting!") + + # Copy the cameras + rec = pycolmap.Reconstruction(tmp_path / "sparse") + cameras = {i: copy.copy(c) for i, c in rec.cameras.items()} + + if output_path.exists(): + if not output_path.is_dir() or output_path.iterdir(): + raise ValueError( + f"Output path {output_path} is not an empty directory." + ) + output_path.rmdir() + shutil.move(tmp_path / "images", output_path) + + return cameras + + +def write_cameras_json(cameras: Dict[int | str, pycolmap.Camera], path: Path): + camera_dicts = {} + for key, c in cameras.items(): + d = d = c.todict() + d["model"] = c.model.name + d["params"] = c.params.tolist() + camera_dicts[key] = d + path.write_text(json.dumps(camera_dicts)) + + +def undistort_asl( + calibration_file: Path, + asl_path: Path, + output_asl_path: Path, + **kwargs +): + if output_asl_path.exists(): + raise ValueError(f"{output_asl_path=} already exists.") + if not asl_path.exists(): + raise FileNotFoundError(f"{asl_path=}") + if not calibration_file.exists(): + raise FileNotFoundError(f"{calibration_file=}") + + recon = pycolmap.Reconstruction() + add_cameras_to_reconstruction( + reconstruction=recon, + calibration_file=calibration_file, + ) + # Create a dummy COLMAP reconstruction. + image_ext = ".png" + image_id = 1 + rig = recon.rig(rig_id=1) + colmap_images = {} + for i, (key, _) in enumerate(ARIA_CAMERAS): + cam = recon.cameras[i + 1] + image_names = sorted( + p.relative_to(asl_path) + for p in (asl_path / "aria" / key).glob(f"**/*{image_ext}") + ) + colmap_images[key] = [] + for n in image_names: + im = pycolmap.Image( + n, + pycolmap.Point2DList(), + cam.camera_id, + image_id, + ) + image_id += 1 + colmap_images[key].append(im) + + zipped_images = list( + zip(*[colmap_images[key] for key, _ in ARIA_CAMERAS]) + ) + + for j, (left_im, right_im) in enumerate(tqdm( + zipped_images, total=len(zipped_images), + desc="Adding images to reconstruction" + )): + frame = pycolmap.Frame() + frame.rig_id = rig.rig_id + frame.frame_id = j + 1 + frame.rig_from_world = pycolmap.Rigid3d() + left_im.frame_id = frame.frame_id + right_im.frame_id = frame.frame_id + frame.add_data_id(left_im.data_id) + frame.add_data_id(right_im.data_id) + recon.add_frame(frame) + recon.add_image(left_im) + recon.add_image(right_im) + + with tempfile.TemporaryDirectory() as temp_rec_path: + recon.write(temp_rec_path) + cameras_undist = undistort_reconstruction( + asl_path, temp_rec_path, output_asl_path, **kwargs + ) + + # Copy the undistorted cameras in json. + cameras_undist = { + key: cameras_undist[i+1] for i, (key, _) in enumerate(ARIA_CAMERAS) + } + write_cameras_json( + cameras_undist, output_asl_path / "aria" / "cameras.json" + ) + + # Copy the other files + for p in asl_path.glob("**/*"): + if p.is_dir() or p.suffix == image_ext: + continue + p_out = output_asl_path / p.relative_to(asl_path) + p_out.parent.mkdir(exist_ok=True, parents=True) + shutil.copyfile(p, p_out) + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--calibration_file", type=Path, required=True) + parser.add_argument("--asl_path", type=Path, required=True) + parser.add_argument("--output_asl_path", type=Path, required=True) + parser.add_argument("--ratio_blank_pixels", type=float, default=0.2) + args = parser.parse_args() + + undistort_asl( + args.calibration_file, + args.asl_path, + args.output_asl_path, + ratio_blank_pixels=args.ratio_blank_pixels, + ) From 103b4cdd9169d19b2608f8ec4f2c6be9915977bb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 8 Sep 2025 14:54:53 +0200 Subject: [PATCH 002/665] asl folder to rosbag --- tools/asl_folder_to_rosbag.py | 156 ++++++++++++++++++++++++++++++++++ 1 file changed, 156 insertions(+) create mode 100644 tools/asl_folder_to_rosbag.py diff --git a/tools/asl_folder_to_rosbag.py b/tools/asl_folder_to_rosbag.py new file mode 100644 index 0000000..163cc55 --- /dev/null +++ b/tools/asl_folder_to_rosbag.py @@ -0,0 +1,156 @@ +from __future__ import annotations + +import argparse +import csv +from dataclasses import dataclass +from pathlib import Path +from typing import List, Tuple + +import cv2 +import rosbag +import rospy +from cv_bridge import CvBridge +from sensor_msgs.msg import Imu +from tqdm import tqdm + +NS_TO_S = 1e-9 + +@dataclass(frozen=True) +class CamSample: + ts_ns: int + path: Path + topic: str + frame_id: str + +@dataclass(frozen=True) +class ImuSample: + ts_ns: int + gyro: Tuple[float, float, float] + accel: Tuple[float, float, float] + topic: str + frame_id: str + +def _is_int(s: str) -> bool: + try: + int(s) + return True + except Exception: + return False + + +def _read_cam_csv(csv_path: Path, images_dir: Path, topic: str, frame_id: str) -> List[CamSample]: + samples: List[CamSample] = [] + with csv_path.open("r", newline="") as f: + reader = csv.reader(f) + for row in reader: + if not row: + continue + if not _is_int(row[0]): + continue + ts_ns = int(row[0]) + img_rel = row[1] + samples.append(CamSample(ts_ns, images_dir / img_rel, topic, frame_id)) + + return samples + +def _read_imu_csv(csv_path: Path, topic: str, frame_id: str) -> List[ImuSample]: + samples: List[ImuSample] = [] + with csv_path.open("r", newline="") as f: + reader = csv.reader(f) + for row in reader: + if not row: + continue + if not _is_int(row[0]): + continue + ts_ns = int(row[0]) + wx, wy, wz = (float(x) for x in row[1:4]) + ax, ay, az = (float(x) for x in row[4:7]) + samples.append(ImuSample(ts_ns, (wx, wy, wz), (ax, ay, az), topic, frame_id)) + + return samples + + +def asl_to_rosbag( + input_asl_folder: Path, + output_rosbag: Path, + cam0_topic: str = "/cam0/image_raw", + cam1_topic: str = "/cam1/image_raw", + imu_topic: str = "/imu0", + cam0_frame: str = "cam0", + cam1_frame: str = "cam1", + imu_frame: str = "imu0", +) -> None: + + aria = input_asl_folder / "aria" + cam0_dir, cam1_dir, imu_dir = aria / "cam0", aria / "cam1", aria / "imu0" + + if not cam0_dir.exists(): + raise FileNotFoundError(f"Missing camera folder: {cam0_dir}") + if not imu_dir.exists(): + raise FileNotFoundError(f"Missing IMU folder: {imu_dir}") + + cam0 = _read_cam_csv(cam0_dir / "data.csv", cam0_dir / "data", cam0_topic, cam0_frame) + cam1 = [] + if cam1_dir.exists() and (cam1_dir / "data.csv").exists(): + cam1 = _read_cam_csv(cam1_dir / "data.csv", cam1_dir / "data", cam1_topic, cam1_frame) + imu = _read_imu_csv(imu_dir / "data.csv", imu_topic, imu_frame) + + if not cam0: + raise RuntimeError("cam0 data is empty.") + if not imu: + raise RuntimeError("IMU data is empty.") + + bag_timeline = [] + bag_timeline += [(s.ts_ns, "cam", s) for s in cam0] + bag_timeline += [(s.ts_ns, "cam", s) for s in cam1] + bag_timeline += [(s.ts_ns, "imu", s) for s in imu] + bag_timeline.sort(key=lambda x: x[0]) + + output_rosbag.parent.mkdir(parents=True, exist_ok=True) + bridge = CvBridge() + bag = rosbag.Bag(str(output_rosbag), "w") + + print(f"[asl_to_rosbag] Writing {len(bag_timeline):,} messages -> {output_rosbag}") + + for ts_ns, kind, sample in tqdm(bag_timeline, desc="Writing bag", unit="msg"): + stamp = rospy.Time.from_sec(ts_ns * NS_TO_S) + + if kind == "cam": + cv_image = cv2.imread(str(sample.path), cv2.IMREAD_GRAYSCALE) + if cv_image is None: + print(f"Warning: could not load image at path {sample.path}") + continue + img_msg = bridge.cv2_to_imgmsg(cv_image, encoding="mono8") + img_msg.header.stamp = stamp + img_msg.header.frame_id = sample.frame_id + bag.write(sample.topic, img_msg, t=stamp) + + else: + imu_msg = Imu() + imu_msg.header.stamp = stamp + imu_msg.header.frame_id = sample.frame_id + wx, wy, wz = sample.gyro + ax, ay, az = sample.accel + imu_msg.angular_velocity.x, imu_msg.angular_velocity.y, imu_msg.angular_velocity.z = wx, wy, wz + imu_msg.linear_acceleration.x, imu_msg.linear_acceleration.y, imu_msg.linear_acceleration.z = ax, ay, az + + imu_msg.orientation_covariance[0] = -1 + imu_msg.angular_velocity_covariance[0] = -1 + imu_msg.linear_acceleration_covariance[0] = -1 + + bag.write(sample.topic, imu_msg, t=stamp) + + bag.close() + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument( + "--input_asl_folder", type=Path, required=True, help="Input folder" + ) + parser.add_argument( + "--output_rosbag", type=Path, required=True, help="Output rosbag file" + ) + + args = parser.parse_args() + asl_to_rosbag(args.input_asl_folder, args.output_rosbag) From fc3bc120c2a698285f1839e5cf16a42424799623 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 8 Sep 2025 23:09:51 +0200 Subject: [PATCH 003/665] download lamaria --- tools/download_lamaria.py | 304 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 304 insertions(+) create mode 100644 tools/download_lamaria.py diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py new file mode 100644 index 0000000..29b391f --- /dev/null +++ b/tools/download_lamaria.py @@ -0,0 +1,304 @@ +from __future__ import annotations + +import argparse +import os +import re +import sys +from pathlib import Path +from typing import Dict, List, Tuple, Iterable +import requests +from bs4 import BeautifulSoup +from tqdm import tqdm + +BASE_URL_DEFAULT = "https://cvg-data.inf.ethz.ch/lamaria/" + +FOLDERS = [ + "raw_data", + "aria_calibrations", + "asl_folder", + "pinhole_calibrations", + "rosbag", + "ground_truth", +] +DEFAULT_SUBFOLDERS = ["training/", "test/"] +GT_SUBFOLDERS = ["pseudo_dense/", "sparse/"] + +PAYLOADS = { + "raw": ["raw_data", "aria_calibrations"], + "pinhole": ["asl_folder", "pinhole_calibrations", "rosbag"], + "both": [ + "raw_data", + "aria_calibrations", + "asl_folder", + "pinhole_calibrations", + "rosbag", + ], +} + +def fetch_index(full_url: str) -> List[str]: + """Return list of hrefs on an Apache index page (files and folders).""" + r = requests.get(full_url, timeout=30) + r.raise_for_status() + soup = BeautifulSoup(r.text, "html.parser") + hrefs = [] + for a in soup.find_all("a", href=True): + href = a["href"] + # skip parent directory, sort/query links, and anchors + if href == "../": + continue + if href.startswith("?") or "?" in href or href.startswith("#"): + continue + hrefs.append(href) + return hrefs + + +def build_catalog(base_url: str) -> Dict[str, List[Tuple[str, str]]]: + catalog = {} + for folder in FOLDERS: + entries = [] + subfolders = GT_SUBFOLDERS if folder == "ground_truth" else DEFAULT_SUBFOLDERS + for sub in subfolders: + url = base_url.rstrip("/") + "/" + folder + "/" + sub + try: + items = fetch_index(url) + except Exception as e: + print(f"[warn] Could not read {url}: {e}", file=sys.stderr) + items = [] + for it in items: + if it.endswith("/"): + continue + entries.append((sub, it)) + catalog[folder] = entries + return catalog + +def names_from_listing(files: Iterable[str]) -> List[str]: + names = set() + pattern = ( + r"\.(zip|tar|tar\.gz|tgz|7z|bag|vrs|json|txt|csv|tar\.xz)$" + ) + for f in files: + f = f.rstrip("/") + name = re.split(pattern, f, maxsplit=1, flags=re.IGNORECASE)[0] + names.add(name) + return sorted(names) + +def derive_splits(catalog: Dict[str, List[Tuple[str, str]]]) -> Tuple[List[str], List[str]]: + raw_entries = catalog.get("raw_data", []) + train_files = [fname for (sub, fname) in raw_entries if sub == "training/"] + test_files = [fname for (sub, fname) in raw_entries if sub == "test/"] + train = sorted(names_from_listing(train_files)) + test = sorted(names_from_listing(test_files)) + return train, test + + +def raw_split_map(catalog: Dict[str, List[Tuple[str, str]]]) -> Dict[str, str]: + mapping: Dict[str, str] = {} + for sub, fname in catalog.get("raw_data", []): + if sub not in ("training/", "test/"): + continue + if fname.startswith("?") or "?" in fname: + continue + base = names_from_listing([fname])[0] + if base in mapping and mapping[base] == "training/": + continue + mapping[base] = sub + return mapping + + + +def pick_files_for_sequence( + catalog: Dict[str, List[Tuple[str, str]]], + sequence: str, + folders: List[str], + split: str | None, +) -> List[Tuple[str, str, str]]: + matches: List[Tuple[str, str, str]] = [] + for folder in folders: + for sub, fname in catalog.get(folder, []): + if folder != "ground_truth" and split is not None and sub != split: + continue + if fname.startswith(sequence): + matches.append((folder, sub, fname)) + return matches + + +def ensure_dir(p: Path) -> None: + p.mkdir(parents=True, exist_ok=True) + + +def human_size(n: int) -> str: + for unit in ["B", "KB", "MB", "GB", "TB"]: + if n < 1024: + return f"{n:.1f}{unit}" + n /= 1024 + return f"{n:.1f}PB" + + +def download_file( + url: str, dest: Path, session: requests.Session, chunk_size: int = 1 << 20 +) -> None: + headers = {} + existing = dest.stat().st_size if dest.exists() else 0 + + head = session.head(url, allow_redirects=True, timeout=30) + head.raise_for_status() + total = ( + int(head.headers.get("Content-Length", "0")) + if head.headers.get("Content-Length") + else None + ) + + if total is not None and existing > 0 and existing < total: + headers["Range"] = f"bytes={existing}-" + elif total is not None and existing == total: + print(f"[skip] {dest} (already complete, {human_size(total)})") + return + + with session.get(url, headers=headers, stream=True, timeout=60) as r: + r.raise_for_status() + mode = "ab" if "Range" in headers else "wb" + total_to_show = None + if total is not None: + total_to_show = total - existing if "Range" in headers else total + + with open(dest, mode) as f, tqdm( + total=total_to_show, + unit="B", + unit_scale=True, + unit_divisor=1024, + initial=0, + desc=dest.name, + leave=False, + ) as pbar: + for chunk in r.iter_content(chunk_size=chunk_size): + if chunk: + f.write(chunk) + pbar.update(len(chunk)) + + if total is not None and dest.stat().st_size != total: + print( + f"[warn] Size mismatch for {dest} (expected {total}, got {dest.stat().st_size})" + ) + + +def main(): + parser = argparse.ArgumentParser(description="LaMAria dataset downloader") + parser.add_argument( + "--set", + choices=["train", "test", "specific"], + required=True, + help="What to download: training sequences, test sequences, or a specific list", + ) + parser.add_argument( + "--type", + choices=["raw", "pinhole", "both"], + required=True, + help="Which data to fetch", + ) + parser.add_argument( + "--sequences", + nargs="+", + help="Sequence names (required for --set specific). Example: R_01_easy sequence_3_17", + ) + parser.add_argument( + "--out-dir", default="out_dir", help="Root output folder (script will create out_dir/lamaria)" + ) + args = parser.parse_args() + + # Root: out_dir/lamaria + root = Path(args.out_dir) / "lamaria" + ensure_dir(root) + + print("[info] Building catalog from server…") + catalog = build_catalog(BASE_URL_DEFAULT) + + print("[info] Deriving training/test sequences from raw_data/…") + train_names, test_names = derive_splits(catalog) + split_lookup = raw_split_map(catalog) # seq -> 'training/' or 'test/' + + if args.set == "train": + target_sequences = train_names + global_split = "training/" + elif args.set == "test": + target_sequences = test_names + global_split = "test/" + else: + if not args.sequences: + print("[error] --set specific requires --sequences", file=sys.stderr) + sys.exit(2) + target_sequences = args.sequences + global_split = None # per-sequence + + # To fetch + folders = PAYLOADS[args.type].copy() + plan = [] + + created_split_dirs = set() + + for seq in target_sequences: + if global_split is not None: + seq_split = global_split + else: + seq_split = split_lookup.get(seq) + if seq_split is None: + raise ValueError(f"Could not determine split for sequence: {seq}") + + if seq_split in ("training/", "test/"): + split_folder = "training" if seq_split == "training/" else "test" + else: + split_folder = "unknown" + + seq_root = root / split_folder / seq + if split_folder not in created_split_dirs: + ensure_dir(root / split_folder) + created_split_dirs.add(split_folder) + ensure_dir(seq_root) + + selected = pick_files_for_sequence( + catalog, seq, folders, split=(seq_split if seq_split in ("training/", "test/") else None) + ) + + if seq_split == "training/": + selected += pick_files_for_sequence( + catalog, seq, ["ground_truth"], split=None + ) + + if not selected: + print(f"[warn] No files found for: {seq}") + continue + + for folder, sub, fname in selected: + url = BASE_URL_DEFAULT + folder + "/" + sub + fname + if folder == "ground_truth": + dest_dir = seq_root / folder / sub.rstrip("/") + else: + dest_dir = seq_root / folder + + ensure_dir(dest_dir) + dest = dest_dir / fname + plan.append((folder, sub, fname, url, dest)) + + if not plan: + print("[warn] Nothing to download with the given filters.") + return + + # Summarize + print("\n[download] Files to download:") + for _area, _sub, fname, url, dest in plan: + print(f" - {url} -> {dest}") + print() + + # Download + with requests.Session() as sess: + for _area, _sub, fname, url, dest in plan: + print(f"[get] {url}") + try: + download_file(url, dest, sess) + except Exception as e: + print(f"[error] Failed: {url} -> {dest}\n {e}", file=sys.stderr) + + print("\n[done] All downloads attempted. Files stored under:", root.resolve()) + + +if __name__ == "__main__": + main() \ No newline at end of file From 8ce7059ecf784f2644d7e2fe6c938f6cee58bebb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 8 Sep 2025 23:13:06 +0200 Subject: [PATCH 004/665] download --- tools/download_lamaria.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 29b391f..6039a5b 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -1,7 +1,6 @@ from __future__ import annotations import argparse -import os import re import sys from pathlib import Path @@ -185,7 +184,7 @@ def main(): parser = argparse.ArgumentParser(description="LaMAria dataset downloader") parser.add_argument( "--set", - choices=["train", "test", "specific"], + choices=["training", "test", "specific"], required=True, help="What to download: training sequences, test sequences, or a specific list", ) @@ -216,7 +215,7 @@ def main(): train_names, test_names = derive_splits(catalog) split_lookup = raw_split_map(catalog) # seq -> 'training/' or 'test/' - if args.set == "train": + if args.set == "training": target_sequences = train_names global_split = "training/" elif args.set == "test": From 2e54641e24cea13b3e7ad85f90fe9da024a62b97 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 8 Sep 2025 23:16:20 +0200 Subject: [PATCH 005/665] download --- tools/download_lamaria.py | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 6039a5b..135ba0c 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -210,8 +210,6 @@ def main(): print("[info] Building catalog from server…") catalog = build_catalog(BASE_URL_DEFAULT) - - print("[info] Deriving training/test sequences from raw_data/…") train_names, test_names = derive_splits(catalog) split_lookup = raw_split_map(catalog) # seq -> 'training/' or 'test/' @@ -281,13 +279,7 @@ def main(): print("[warn] Nothing to download with the given filters.") return - # Summarize - print("\n[download] Files to download:") - for _area, _sub, fname, url, dest in plan: - print(f" - {url} -> {dest}") - print() - - # Download + print("\n[download] Starting downloads.") with requests.Session() as sess: for _area, _sub, fname, url, dest in plan: print(f"[get] {url}") From 57d6c92d8e3b69e5d4f1127c8fd5092261e37927 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 8 Sep 2025 23:21:37 +0200 Subject: [PATCH 006/665] ignore --- .gitignore | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 .gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..f27b08a --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +**/__pycache__/ +.DS_Store \ No newline at end of file From fd42c381673de276adc9e9e3c23af551c0c6934a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 10:18:09 +0200 Subject: [PATCH 007/665] vrs asl --- tools/vrs_to_asl_folder.py | 273 +++++++++++++++++++++++++++++++++++++ 1 file changed, 273 insertions(+) create mode 100644 tools/vrs_to_asl_folder.py diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py new file mode 100644 index 0000000..2146ad9 --- /dev/null +++ b/tools/vrs_to_asl_folder.py @@ -0,0 +1,273 @@ +import argparse +import csv +import os +from pathlib import Path +from typing import List, Tuple + +from projectaria_tools.core import data_provider +from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from tqdm import tqdm + +from lamaria import logger +from lamaria.utils.utils import ( + LEFT_CAMERA_STREAM_ID, + RIGHT_CAMERA_STREAM_ID, + IMU_STREAM_ID, + extract_images_from_vrs, + get_matched_timestamps, +) + + +def remove_images_when_slam_drops( + image_folder: Path, + left_timestamps: List[int], + right_timestamps: List[int], + matched_timestamps: List[Tuple[int, int]], + left_subfolder_name="cam0/data", + right_subfolder_name="cam1/data", +): + left_image_folder = os.path.join(image_folder, left_subfolder_name) + right_image_folder = os.path.join(image_folder, right_subfolder_name) + + assert os.path.exists(left_image_folder) and os.path.exists( + right_image_folder + ) + + original_left_images = sorted(os.listdir(left_image_folder)) + original_right_images = sorted(os.listdir(right_image_folder)) + + assert len(original_left_images) == len(left_timestamps) + assert len(original_right_images) == len(right_timestamps) + + left_camera_mapping = { + ts: img for ts, img in zip(left_timestamps, original_left_images) + } + right_camera_mapping = { + ts: img for ts, img in zip(right_timestamps, original_right_images) + } + + matched_left_ts = [left_ts for left_ts, _ in matched_timestamps] + matched_right_ts = [right_ts for _, right_ts in matched_timestamps] + + if len(left_timestamps) != len(matched_timestamps): + for ts, img in left_camera_mapping.items(): + if ts not in matched_left_ts: + print(f"Removing {img}") + os.remove(os.path.join(left_image_folder, img)) + elif len(right_timestamps) != len(matched_timestamps): + for ts, img in right_camera_mapping.items(): + if ts not in matched_right_ts: + print(f"Removing {img}") + os.remove(os.path.join(right_image_folder, img)) + else: + raise ValueError("No images to remove") + + return matched_left_ts + + +def rename_images_in_folder( + aria_folder: Path, + image_timestamps, + left_subfolder_name="cam0/data", + right_subfolder_name="cam1/data", + image_extension=".jpg", +) -> List[int]: + + for subfolder in [left_subfolder_name, right_subfolder_name]: + subfolder_path = aria_folder / subfolder + + if not subfolder_path.exists() and not subfolder_path.is_dir(): + raise ValueError(f"{subfolder_path} does not exist or is not a directory") + + original_images = sorted([f for f in os.listdir(subfolder_path) if f.endswith(image_extension)]) + if len(original_images) == 0: + raise ValueError(f"No images found in {subfolder_path}") + + if len(original_images) != len(image_timestamps): + raise ValueError( + f"Number of images {len(original_images)} \ + does not match number of timestamps \ + {len(image_timestamps)} in {subfolder_path}" + ) + + for ts, img in zip(image_timestamps, original_images): + old_image_path = subfolder_path / img + new_image_path = subfolder_path / f"{ts}{image_extension}" + os.rename(old_image_path, new_image_path) + + return image_timestamps + + +def write_image_timestamps_to_txt(image_timestamps: List, txt_file: Path): + with open(txt_file, "w") as f: + for timestamp in image_timestamps: + f.write(f"{timestamp}\n") + + +def write_image_csv(image_timestamps, cam_folder): + images = os.listdir(os.path.join(cam_folder, "data")) + assert len(images) > 0 + + images = sorted(images, key=lambda img: int(img.split(".")[0])) + + assert len(images) == len(image_timestamps) + for ts, img in zip(image_timestamps, images): + assert int(img.split(".")[0]) == ts, f"{img} != {ts}" + + data_csv = os.path.join(cam_folder, "data.csv") + if os.path.exists(data_csv): + os.remove(data_csv) + + with open(data_csv, "w", newline="") as f: + writer = csv.writer(f) + for timestamp, image in zip(image_timestamps, images): + row = [timestamp, image] + writer.writerow(row) + + +def write_imu_data_to_csv(vrs_provider, csv_file): + imu_timestamps = vrs_provider.get_timestamps_ns( + IMU_STREAM_ID, TimeDomain.DEVICE_TIME + ) + + last_timestamp = None + if os.path.exists(csv_file): + with open(csv_file, "r") as f: + last_row = None + for last_row in csv.reader(f): + pass + if last_row is not None: + last_timestamp = int(last_row[0]) + + if last_timestamp is not None: + imu_timestamps = [ts for ts in imu_timestamps if ts > last_timestamp] + + if not imu_timestamps: + logger.info(f"No new IMU data to write to {csv_file}") + return + + with open(csv_file, "a", newline="") as f: + writer = csv.writer(f) + for timestamp in tqdm(imu_timestamps, desc="Appending IMU data to CSV"): + imu_data = vrs_provider.get_imu_data_by_time_ns( + IMU_STREAM_ID, + timestamp, + TimeDomain.DEVICE_TIME, + TimeQueryOptions.CLOSEST, + ) + if imu_data.accel_valid and imu_data.gyro_valid: + accel = imu_data.accel_msec2 + gyro = imu_data.gyro_radsec + + row = [ + timestamp, + gyro[0], + gyro[1], + gyro[2], + accel[0], + accel[1], + accel[2], + ] + writer.writerow(row) + + +def form_aria_asl_folder( + vrs_file: Path, + output_asl_folder: Path, + has_slam_drops=False +): + if output_asl_folder.exists(): + raise ValueError(f"{output_asl_folder=} already exists.") + + aria_folder = output_asl_folder / "aria" + aria_folder.mkdir(parents=True, exist_ok=True) + + dataset_name = vrs_file.stem + vrs_provider = data_provider.create_vrs_data_provider(vrs_file.as_posix()) + + # Get all image timestamps (in ns) + image_timestamps = vrs_provider.get_timestamps_ns( + LEFT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME + ) + assert ( + len(image_timestamps) > 0 + ), "No timestamps found" + + right_image_timestamps = None + matched_timestamps = None + if has_slam_drops: + right_image_timestamps = vrs_provider.get_timestamps_ns( + RIGHT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME + ) + assert ( + len(right_image_timestamps) > 0 + ), "No right camera image timestamps found" + assert len(right_image_timestamps) != len( + image_timestamps + ), "Left and right camera image timestamps are the same" + matched_timestamps = get_matched_timestamps( + left_timestamps=image_timestamps, + right_timestamps=right_image_timestamps, + ) + + assert len(matched_timestamps) > 0, "No matched timestamps found" + + extract_images_from_vrs( + vrs_file=vrs_file, + image_folder=aria_folder, + left_subfolder_name="cam0/data", + right_subfolder_name="cam1/data", + ) + + if has_slam_drops: + assert ( + right_image_timestamps is not None + and matched_timestamps is not None + ) + image_timestamps = remove_images_when_slam_drops( + aria_folder, + image_timestamps, + right_image_timestamps, + matched_timestamps, + ) + + image_timestamps = rename_images_in_folder( + aria_folder, + image_timestamps, + ) + + imu_folder = output_asl_folder / "aria" / "imu0" + imu_folder.mkdir(parents=True, exist_ok=True) + imu_csv = imu_folder / "data.csv" + + write_imu_data_to_csv( + vrs_provider, + imu_csv, + ) + + write_image_timestamps_to_txt( + image_timestamps, + aria_folder / f"{dataset_name}.txt", + ) + write_image_csv(image_timestamps, aria_folder / "cam0") + write_image_csv(image_timestamps, aria_folder / "cam1") + + +if __name__ == "__main__": + args = argparse.ArgumentParser() + + args.add_argument("--vrs_file", type=Path, required=True) + args.add_argument("--output_asl_folder", type=Path, required=True) + args.add_argument( + "--has_slam_drops", + action="store_true", + help="Whether the VRS file has dropped SLAM frames", + ) + + args = args.parse_args() + + form_aria_asl_folder( + args.vrs_file, + args.output_asl_folder, + has_slam_drops=args.has_slam_drops, + ) From 47706951eb7df4072a181fcb8c664ee8cf5fc80b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 11:57:46 +0200 Subject: [PATCH 008/665] config init --- lamaria/rig/config/defaults.yaml | 54 ++++++++++++++++++++++++++++++++ lamaria/rig/config/loaders.py | 38 ++++++++++++++++++++++ 2 files changed, 92 insertions(+) create mode 100644 lamaria/rig/config/defaults.yaml create mode 100644 lamaria/rig/config/loaders.py diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml new file mode 100644 index 0000000..59b6e64 --- /dev/null +++ b/lamaria/rig/config/defaults.yaml @@ -0,0 +1,54 @@ +paths: + base: /media/lamaria/ + recordings: ${paths.base}/recordings/ + mps: ${paths.base}/mps/ + +camera: + model: RAD_TAN_THIN_PRISM_FISHEYE + +streams: + left_cam_stream_id: 1201-1 + right_cam_stream_id: 1201-2 + imu_right_stream_id: 1202-1 + +flags: + use_constant_cam_calib: true + mps_fail: false + +vio: + parent_path: results/ + subfolder: rig/ + keyframes_subdir: keyframes/all/ + output_folder: outputs/ + + init_model: empty_recon + kf_model: keyframe_recon + optim_model: optim_recon + + sfm_pairs: pairs_from_retrieval_and_temporal.txt + feature_conf: aliked-n16 + matcher_conf: aliked+lightglue + retrieval_conf: netvlad + +optimization: + feature_std: 1.0 + use_callback: true + max_num_iterations: 10 + normalize_reconstruction: false + use_factory_cam_intrinsics: true + use_factory_cam_extrinsics: true + use_factory_imu: true + optimize_cam_intrinsics: false + optimize_cam_from_rig: false + optimize_scale: false + optimize_gravity: false + optimize_imu_from_rig: false + optimize_bias: false + imu_inflation_factor_gyro: 20.0 + imu_inflation_factor_acc: 1.0 + integration_noise_density: 0.05 + keep_imu_residuals: true + +run: + seq_id: long_1 + vrs_file: ${run.seq_id}.vrs diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py new file mode 100644 index 0000000..a1510ec --- /dev/null +++ b/lamaria/rig/config/loaders.py @@ -0,0 +1,38 @@ +from pathlib import Path +from typing import Optional, Sequence +from omegaconf import OmegaConf + +def _merge_if_exists(cfg, path: Path): + return OmegaConf.merge(cfg, OmegaConf.load(str(path))) if path.exists() else cfg + +def load_cfg( + base_file: str = "lamaria/rig/config/defaults.yaml", + local_file: Optional[str] = None, + cli_overrides: Optional[Sequence[str]] = None, +): + cfg = OmegaConf.load(base_file) + if local_file: + cfg = _merge_if_exists(cfg, Path(local_file)) + if cli_overrides: + cfg = OmegaConf.merge(cfg, OmegaConf.from_dotlist(list(cli_overrides))) + OmegaConf.resolve(cfg) + + vrs_stem = Path(cfg.run.vrs_file).stem + + base = Path(cfg.paths.base) + recordings = Path(cfg.paths.recordings) + mps = Path(cfg.paths.mps) + + parent_rel = cfg.vio.parent_path + + cfg.vrs_file_path = str(recordings / cfg.run.vrs_file) + cfg.mps_slam_path = str(mps / f"mps_{vrs_stem}_vrs" / "slam") + cfg.image_stream_path = str(base / parent_rel / vrs_stem / "image_stream") + + vio_base = base / parent_rel / vrs_stem / cfg.vio.subfolder + + cfg.vio.parent_path = vio_base + cfg.vio.keyframes_path = vio_base / cfg.vio.keyframes_subdir + cfg.vio.output_folder_path = vio_base / cfg.vio.output_folder + + return cfg From 7c93843b4c440539f3a4c15aba498a764bf50a2b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 13:27:34 +0200 Subject: [PATCH 009/665] extraction done --- lamaria/rig/keyframing/extraction.py | 30 ++++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) create mode 100644 lamaria/rig/keyframing/extraction.py diff --git a/lamaria/rig/keyframing/extraction.py b/lamaria/rig/keyframing/extraction.py new file mode 100644 index 0000000..114f576 --- /dev/null +++ b/lamaria/rig/keyframing/extraction.py @@ -0,0 +1,30 @@ +from __future__ import annotations + +from pathlib import Path + +from lamaria.rig.config.loaders import load_cfg +from ...utils.utils import extract_images_from_vrs + + +def run( + image_stream_folder: Path, + vrs_path: Path, +) -> None: + + image_stream_folder.mkdir(parents=True, exist_ok=True) + extract_images_from_vrs( + vrs_file=vrs_path, + image_folder=image_stream_folder, + ) + + +def main() -> None: + cfg = load_cfg() + run( + image_stream_folder=cfg.image_stream_path, + vrs_path=cfg.vrs_file_path, + ) + + +if __name__ == "__main__": + main() From d231bf1d9b9fa56349b6f2f2ee053e000cf54539 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 15:00:46 +0200 Subject: [PATCH 010/665] defs --- lamaria/rig/config/defaults.yaml | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 59b6e64..f9f910c 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -14,8 +14,9 @@ streams: flags: use_constant_cam_calib: true mps_fail: false + has_slam_drops: false -vio: +result: parent_path: results/ subfolder: rig/ keyframes_subdir: keyframes/all/ @@ -25,6 +26,12 @@ vio: kf_model: keyframe_recon optim_model: optim_recon +keyframing: + max_rotation: 20.0 + max_distance: 1.0 + max_elapsed: 1.0 + +triangulation: sfm_pairs: pairs_from_retrieval_and_temporal.txt feature_conf: aliked-n16 matcher_conf: aliked+lightglue From 72f77e2889091eaae359fca394422bc53d9e4a27 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 15:01:17 +0200 Subject: [PATCH 011/665] loaders --- lamaria/rig/config/loaders.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index a1510ec..d9e685c 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -23,16 +23,16 @@ def load_cfg( recordings = Path(cfg.paths.recordings) mps = Path(cfg.paths.mps) - parent_rel = cfg.vio.parent_path + parent_rel = cfg.result.parent_path cfg.vrs_file_path = str(recordings / cfg.run.vrs_file) - cfg.mps_slam_path = str(mps / f"mps_{vrs_stem}_vrs" / "slam") + cfg.mps_path = str(mps / f"mps_{vrs_stem}_vrs") cfg.image_stream_path = str(base / parent_rel / vrs_stem / "image_stream") - vio_base = base / parent_rel / vrs_stem / cfg.vio.subfolder + vio_base = base / parent_rel / vrs_stem / cfg.result.subfolder - cfg.vio.parent_path = vio_base - cfg.vio.keyframes_path = vio_base / cfg.vio.keyframes_subdir - cfg.vio.output_folder_path = vio_base / cfg.vio.output_folder + cfg.result.parent_path = vio_base + cfg.result.keyframes_path = vio_base / cfg.result.keyframes_subdir + cfg.result.output_folder_path = vio_base / cfg.result.output_folder return cfg From 5252b565ee35652370bf2bf2ca21dee307122c06 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 15:02:45 +0200 Subject: [PATCH 012/665] vrs to colmap --- lamaria/rig/builder/vrs_to_colmap.py | 69 ++++++++++++++++++++++++++++ 1 file changed, 69 insertions(+) create mode 100644 lamaria/rig/builder/vrs_to_colmap.py diff --git a/lamaria/rig/builder/vrs_to_colmap.py b/lamaria/rig/builder/vrs_to_colmap.py new file mode 100644 index 0000000..56bb5fa --- /dev/null +++ b/lamaria/rig/builder/vrs_to_colmap.py @@ -0,0 +1,69 @@ +from __future__ import annotations + +import json +import os +from typing import List, Optional, Tuple +from pathlib import Path +import numpy as np +import pycolmap + +import projectaria_tools.core.mps as mps +from projectaria_tools.core import data_provider +from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from projectaria_tools.core.stream_id import StreamId + +from ... import logger +from ..config.loaders import load_cfg +from ...utils.utils import find_closest_timestamp + +class VrsToColmap: + def __init__(self, cfg=None): + self.cfg = cfg or load_cfg() + self._init_io() + + def _init_io(self): + self.left_img_dir = self.cfg.image_stream_path / "left" + self.right_img_dir = self.cfg.image_stream_path / "right" + + self.empty_recons: pycolmap.Reconstruction = None + self.keyframed_recons: pycolmap.Reconstruction = None + + self.vrs_provider = data_provider.create_vrs_data_provider( + self.cfg.vrs_file_path + ) + data_paths = mps.MpsDataPathsProvider(self.cfg.mps_path).get_data_paths() + self.mps_data_provider = mps.MpsDataProvider(data_paths) + + self.left_cam_stream_id = StreamId(self.cfg.streams.left_cam_stream_id) + self.right_cam_stream_id = StreamId(self.cfg.streams.right_cam_stream_id) + self.imu_stream_id = StreamId(self.cfg.streams.imu_right_stream_id) + + def _list_images(self, folder: Path, ext: str =".jpg") -> List[str]: + if not folder.is_dir(): + return [] + return sorted(n for n in folder.iterdir() if n.suffix == ext) + + def _ts_from_vrs(self, sid: StreamId) -> List[int]: + """Timestamps in nanoseconds""" + return sorted(self.vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME)) + + def _match_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: + L = self._ts_from_vrs(self.left_cam_stream_id) + R = self._ts_from_vrs(self.right_cam_stream_id) + matched = [] + + if len(L) < len(R): + for l in L: + r = find_closest_timestamp(R, l, max_diff) + if r is not None: + matched.append((l, r)) + else: + for r in R: + l = find_closest_timestamp(L, r, max_diff) + if l is not None: + matched.append((l, r)) + return matched + + def _load_cameras(self) -> None: + pass + From b15cd86c8641288cea8c730d2d2879a4e433979a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 15:03:56 +0200 Subject: [PATCH 013/665] defs --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index f9f910c..c2c05af 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -14,7 +14,7 @@ streams: flags: use_constant_cam_calib: true mps_fail: false - has_slam_drops: false + has_slam_drops: false # check inside vrs.json file result: parent_path: results/ From 6d369a5e661d99ff6a75f645bc390b953aa08343 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 15:04:24 +0200 Subject: [PATCH 014/665] defs --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index c2c05af..9b8060f 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -12,7 +12,7 @@ streams: imu_right_stream_id: 1202-1 flags: - use_constant_cam_calib: true + use_constant_cam_calib: false mps_fail: false has_slam_drops: false # check inside vrs.json file From f05d3b8bf395e81fb30e4a7a4026c55cbdf64443 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 15:22:53 +0200 Subject: [PATCH 015/665] device calib --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 9b8060f..aab28ac 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -12,7 +12,7 @@ streams: imu_right_stream_id: 1202-1 flags: - use_constant_cam_calib: false + use_device_calib: false mps_fail: false has_slam_drops: false # check inside vrs.json file From bceeaf78dc6fce2e5a7f548fcda0fd28fccb6c49 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 9 Sep 2025 15:23:07 +0200 Subject: [PATCH 016/665] dev --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index aab28ac..7f11d09 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -12,7 +12,7 @@ streams: imu_right_stream_id: 1202-1 flags: - use_device_calib: false + use_device_calibration: false mps_fail: false has_slam_drops: false # check inside vrs.json file From 5ad8a649cb6fa30ba32d23650a5dcd25d41650e5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 09:51:41 +0200 Subject: [PATCH 017/665] loader upd --- lamaria/rig/config/loaders.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index d9e685c..414ade6 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -25,10 +25,10 @@ def load_cfg( parent_rel = cfg.result.parent_path - cfg.vrs_file_path = str(recordings / cfg.run.vrs_file) - cfg.mps_path = str(mps / f"mps_{vrs_stem}_vrs") - cfg.image_stream_path = str(base / parent_rel / vrs_stem / "image_stream") - + cfg.vrs_file_path = recordings / cfg.run.vrs_file + cfg.mps_path = mps / f"mps_{vrs_stem}_vrs" + cfg.image_stream_path = base / parent_rel / vrs_stem / "image_stream" + vio_base = base / parent_rel / vrs_stem / cfg.result.subfolder cfg.result.parent_path = vio_base From f1d17faceee955f88d4d31dfb92bca56ad011b0a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 14:49:40 +0200 Subject: [PATCH 018/665] vrs to colmap is complete --- lamaria/rig/builder/vrs_to_colmap.py | 324 +++++++++++++++++++++++++-- 1 file changed, 307 insertions(+), 17 deletions(-) diff --git a/lamaria/rig/builder/vrs_to_colmap.py b/lamaria/rig/builder/vrs_to_colmap.py index 56bb5fa..1786565 100644 --- a/lamaria/rig/builder/vrs_to_colmap.py +++ b/lamaria/rig/builder/vrs_to_colmap.py @@ -1,11 +1,11 @@ from __future__ import annotations -import json -import os -from typing import List, Optional, Tuple + +from typing import List, Tuple from pathlib import Path import numpy as np import pycolmap +from dataclasses import dataclass import projectaria_tools.core.mps as mps from projectaria_tools.core import data_provider @@ -14,42 +14,142 @@ from ... import logger from ..config.loaders import load_cfg -from ...utils.utils import find_closest_timestamp +from ...utils.utils import ( + find_closest_timestamp, + get_t_imu_camera, + camera_colmap_from_calib, + rigid3d_from_transform, + get_closed_loop_data_from_mps, + get_mps_poses_for_timestamps, +) + + + +@dataclass +class PerFrameData: + left_ts: int + right_ts: int + left_img: Path + right_img: Path + rig_from_world: pycolmap.Rigid3d + class VrsToColmap: def __init__(self, cfg=None): - self.cfg = cfg or load_cfg() + self.cfg = cfg if cfg is not None else load_cfg() self._init_io() + self._init_data() def _init_io(self): - self.left_img_dir = self.cfg.image_stream_path / "left" - self.right_img_dir = self.cfg.image_stream_path / "right" - - self.empty_recons: pycolmap.Reconstruction = None - self.keyframed_recons: pycolmap.Reconstruction = None - + self.empty_recons = pycolmap.Reconstruction() self.vrs_provider = data_provider.create_vrs_data_provider( - self.cfg.vrs_file_path + self.cfg.vrs_file_path.as_posix() ) - data_paths = mps.MpsDataPathsProvider(self.cfg.mps_path).get_data_paths() + data_paths = mps.MpsDataPathsProvider(self.cfg.mps_path.as_posix()).get_data_paths() self.mps_data_provider = mps.MpsDataProvider(data_paths) self.left_cam_stream_id = StreamId(self.cfg.streams.left_cam_stream_id) self.right_cam_stream_id = StreamId(self.cfg.streams.right_cam_stream_id) self.imu_stream_id = StreamId(self.cfg.streams.imu_right_stream_id) + + def _init_data(self): + images = self._get_images() + timestamps = self._get_timestamps() + closed_loop_data = get_closed_loop_data_from_mps(self.cfg.mps_path) + pose_timestamps = [ l for l, _ in timestamps ] + mps_poses = get_mps_poses_for_timestamps(closed_loop_data, pose_timestamps) + + self.per_frame_data = self._build_per_frame_data(images, timestamps, mps_poses) + + def _build_per_frame_data(self, images, timestamps, mps_poses) -> List[PerFrameData]: + per_frame_data = [] + imu_stream_label = self.vrs_provider.get_label_from_stream_id( + self.imu_stream_id + ) + + if self.cfg.flags.use_device_calibration: + device_calibration = self.vrs_provider.get_device_calibration() + imu_calib = device_calibration.get_imu_calib( + imu_stream_label + ) + + for (left_img, right_img), (left_ts, right_ts), t_world_device \ + in zip(images, timestamps, mps_poses): + + if t_world_device is None: + continue - def _list_images(self, folder: Path, ext: str =".jpg") -> List[str]: + if not self.cfg.flags.use_device_calibration: + ocalib = self.mps_data_provider.get_online_calibration( + left_ts, TimeQueryOptions.CLOSEST + ) + if ocalib is None: + continue + imu_calib = None + for calib in ocalib.imu_calibs: + if calib.get_label() == imu_stream_label: + imu_calib = calib + break + + t_device_imu = imu_calib.get_transform_device_imu() + t_world_imu = t_world_device @ t_device_imu + t_imu_world = t_world_imu.inverse() + rig_from_world = rigid3d_from_transform(t_imu_world) + + pfd = PerFrameData( + left_ts=left_ts, + right_ts=right_ts, + left_img=left_img, + right_img=right_img, + rig_from_world=rig_from_world + ) + per_frame_data.append(pfd) + + return per_frame_data + + def _images_from_vrs(self, folder: Path, wrt_to: Path, ext: str =".jpg") -> List[Path]: if not folder.is_dir(): return [] - return sorted(n for n in folder.iterdir() if n.suffix == ext) + images = sorted(n for n in folder.iterdir() if n.suffix == ext) + images = [n.relative_to(wrt_to) for n in images] + return images def _ts_from_vrs(self, sid: StreamId) -> List[int]: """Timestamps in nanoseconds""" return sorted(self.vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME)) + + def _get_images(self) -> List[Tuple[Path, Path]]: + left_img_dir = self.cfg.image_stream_path / "left" + right_img_dir = self.cfg.image_stream_path / "right" + + left_images = self._images_from_vrs(left_img_dir, self.cfg.image_stream_path) + right_images = self._images_from_vrs(right_img_dir, self.cfg.image_stream_path) + + return list(zip(left_images, right_images)) + + def _get_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: + if not self.cfg.flags.has_slam_drops: + L = self._ts_from_vrs(self.left_cam_stream_id) + R = self._ts_from_vrs(self.right_cam_stream_id) + assert len(L) == len(R), "Unequal number of left and right timestamps" + matched = list(zip(L, R)) + if not all(abs(l - r) < max_diff for l, r in matched): + logger.warning( + f"Left and right timestamps differ by more than {max_diff} ns" + ) + else: + matched = self._match_timestamps(max_diff) + + return matched def _match_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: L = self._ts_from_vrs(self.left_cam_stream_id) R = self._ts_from_vrs(self.right_cam_stream_id) + + # matching timestamps is only when we have slam drops + assert len(L) > 0 and len(R) > 0 and len(L) != len(R), \ + "Streams must have data and unequal lengths" + matched = [] if len(L) < len(R): @@ -64,6 +164,196 @@ def _match_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: matched.append((l, r)) return matched - def _load_cameras(self) -> None: - pass + def _get_camera_ids(self) -> List[int]: + if self.cfg.flags.use_device_calibration: + return [2, 3] # IMU is camera 1 + else: + frame_ids = self._get_frame_ids() + left_cam_ids = [2 * fid - 1 for fid in frame_ids] + right_cam_ids = [2 * fid for fid in frame_ids] + return zip(left_cam_ids, right_cam_ids) + + def _get_dummy_imu_params(self) -> List: + # Dummy values for IMU "camera" + width = 640 + height = 480 + random_params = [241.604, 241.604, 322.895, 240.444, \ + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, \ + 0.0, 0.0, 0.0, 0.0, 0.0] + + return width, height, random_params + + def _add_device_sensors(self) -> None: + device_calibration = self.vrs_provider.get_device_calibration() + imu_stream_label = self.vrs_provider.get_label_from_stream_id( + self.imu_stream_id + ) + imu_calib = device_calibration.get_imu_calib( + imu_stream_label + ) + + rig = pycolmap.Rig(rig_id=1) + + w, h, p = self._get_dummy_imu_params() + # DUMMY CAMERA FOR IMU, IMU ID is 1 + imu = pycolmap.Camera( + camera_id=1, + model=self.cfg.camera.model, + width=w, + height=h, + params=p, + ) + self.empty_recons.add_camera(imu) + rig.add_ref_sensor(imu.sensor_id) + + for cam_id, sid in [(2, self.left_cam_stream_id), (3, self.right_cam_stream_id)]: + stream_label = self.vrs_provider.get_label_from_stream_id( + sid + ) + camera_calib = device_calibration.get_camera_calib( + stream_label + ) + cam = camera_colmap_from_calib(camera_calib) + cam.camera_id = cam_id + + t_imu_camera = get_t_imu_camera( + imu_calib, + camera_calib, + ) + t_camera_imu = t_imu_camera.inverse() + sensor_from_rig = rigid3d_from_transform(t_camera_imu) + + self.empty_recons.add_camera(cam) + rig.add_sensor(cam.sensor_id, sensor_from_rig) + + self.empty_recons.add_rig(rig) + + def _add_online_sensors(self) -> None: + """Adds a new rig for each timestamp, with sensors calibrated online""" + sensor_id = 1 + for id, pfd in enumerate(self.per_frame_data): + t = pfd.left_ts + calibration = self.mps_data_provider.get_online_calibration( + t, TimeQueryOptions.CLOSEST + ) + if calibration is None: + continue + + rig = pycolmap.Rig(rig_id=id + 1) + w, h, p = self._get_dummy_imu_params() + # DUMMY CAMERA FOR IMU + imu = pycolmap.Camera( + camera_id=sensor_id, + model=self.cfg.camera.model, + width=w, + height=h, + params=p, + ) + self.empty_recons.add_camera(imu) + rig.add_ref_sensor(imu.sensor_id) + sensor_id += 1 + + imu_stream_label = self.vrs_provider.get_label_from_stream_id( + self.imu_stream_id + ) + imu_calib = None + for calib in calibration.imu_calibs: + if calib.get_label() == imu_stream_label: + imu_calib = calib + break + + for sid in [self.left_cam_stream_id, self.right_cam_stream_id]: + stream_label = self.vrs_provider.get_label_from_stream_id( + sid + ) + camera_calib = calibration.get_camera_calib( + stream_label + ) + cam = camera_colmap_from_calib(camera_calib) + cam.camera_id = sensor_id + sensor_id += 1 + + t_imu_camera = get_t_imu_camera( + imu_calib, + camera_calib, + ) + t_camera_imu = t_imu_camera.inverse() + sensor_from_rig = rigid3d_from_transform(t_camera_imu) + + self.empty_recons.add_camera(cam) + rig.add_sensor(cam.sensor_id, sensor_from_rig) + + self.empty_recons.add_rig(rig) + + def _add_device_frames(self) -> None: + image_id = 1 + + rig = self.empty_recons.rigs[1] + for id, pfd in enumerate(self.per_frame_data): + frame = pycolmap.Frame() + frame.rig_id = rig.rig_id + frame.frame_id = id + 1 + frame.rig_from_world = pfd.rig_from_world + + images_to_add = [] + for cam_id, img_path in [(2, pfd.left_img), (3, pfd.right_img)]: + im = pycolmap.Image( + str(img_path), + pycolmap.Point2DList(), + cam_id, + image_id, + ) + im.frame_id = frame.frame_id + frame.add_data_id(im.data_id) + images_to_add.append(im) + image_id += 1 + + self.empty_recons.add_frame(frame) + for im in images_to_add: + self.empty_recons.add_image(im) + + def _add_online_frames(self) -> None: + image_id = 1 + + for id, pfd in enumerate(self.per_frame_data): + frame = pycolmap.Frame() + frame.rig_id = id + 1 + frame.frame_id = id + 1 + frame.rig_from_world = pfd.rig_from_world + + images_to_add = [] + + for cam_id, img_path in [(3*id + 2, pfd.left_img), (3*id + 3, pfd.right_img)]: + im = pycolmap.Image( + str(img_path), + pycolmap.Point2DList(), + cam_id, + image_id, + ) + im.frame_id = frame.frame_id + frame.add_data_id(im.data_id) + images_to_add.append(im) + image_id += 1 + + self.empty_recons.add_frame(frame) + for im in images_to_add: + self.empty_recons.add_image(im) + + def create(self) -> pycolmap.Reconstruction: + if self.cfg.flags.use_device_calibration: + self._add_device_sensors() + self._add_device_frames() + else: + self._add_online_sensors() + self._add_online_frames() + + logger.info(self.empty_recons.summary()) + + return self.empty_recons + + def write(self, output_path: Path) -> None: + output_path.parent.mkdir(parents=True, exist_ok=True) + self.empty_recons.write(output_path) + + From ac83415bb3bda586c5663d97caa37c45cf62893e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 15:37:14 +0200 Subject: [PATCH 019/665] extraction --- lamaria/rig/keyframing/{extraction.py => image_extraction.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename lamaria/rig/keyframing/{extraction.py => image_extraction.py} (100%) diff --git a/lamaria/rig/keyframing/extraction.py b/lamaria/rig/keyframing/image_extraction.py similarity index 100% rename from lamaria/rig/keyframing/extraction.py rename to lamaria/rig/keyframing/image_extraction.py From 20f80857e8a4e942b78b4ae77afaf1f2b24241dd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 15:57:33 +0200 Subject: [PATCH 020/665] init --- lamaria/rig/keyframing/__init__.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 lamaria/rig/keyframing/__init__.py diff --git a/lamaria/rig/keyframing/__init__.py b/lamaria/rig/keyframing/__init__.py new file mode 100644 index 0000000..e69de29 From e21bd0b84ec49db49affff663b7b03ef8a8b61a6 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 15:57:38 +0200 Subject: [PATCH 021/665] init --- lamaria/__init__.py | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100644 lamaria/__init__.py diff --git a/lamaria/__init__.py b/lamaria/__init__.py new file mode 100644 index 0000000..c1dd40c --- /dev/null +++ b/lamaria/__init__.py @@ -0,0 +1,13 @@ +import logging + +formatter = logging.Formatter( + fmt="[%(asctime)s %(name)s %(levelname)s] %(message)s", + datefmt="%Y/%m/%d %H:%M:%S", +) +handler = logging.StreamHandler() +handler.setFormatter(formatter) + +logger = logging.getLogger(__name__) +logger.setLevel(logging.INFO) +logger.addHandler(handler) +logger.propagate = False \ No newline at end of file From d0ed078147c5ee3a91bde5c2d60b2955ca2610b7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 16:13:37 +0200 Subject: [PATCH 022/665] vrs to colmap upd --- lamaria/rig/builder/vrs_to_colmap.py | 17 +++-------------- 1 file changed, 3 insertions(+), 14 deletions(-) diff --git a/lamaria/rig/builder/vrs_to_colmap.py b/lamaria/rig/builder/vrs_to_colmap.py index 1786565..a31b7bc 100644 --- a/lamaria/rig/builder/vrs_to_colmap.py +++ b/lamaria/rig/builder/vrs_to_colmap.py @@ -23,8 +23,6 @@ get_mps_poses_for_timestamps, ) - - @dataclass class PerFrameData: left_ts: int @@ -163,15 +161,6 @@ def _match_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: if l is not None: matched.append((l, r)) return matched - - def _get_camera_ids(self) -> List[int]: - if self.cfg.flags.use_device_calibration: - return [2, 3] # IMU is camera 1 - else: - frame_ids = self._get_frame_ids() - left_cam_ids = [2 * fid - 1 for fid in frame_ids] - right_cam_ids = [2 * fid for fid in frame_ids] - return zip(left_cam_ids, right_cam_ids) def _get_dummy_imu_params(self) -> List: # Dummy values for IMU "camera" @@ -289,10 +278,10 @@ def _add_device_frames(self) -> None: image_id = 1 rig = self.empty_recons.rigs[1] - for id, pfd in enumerate(self.per_frame_data): + for pfd in self.per_frame_data: frame = pycolmap.Frame() frame.rig_id = rig.rig_id - frame.frame_id = id + 1 + frame.frame_id = pfd.left_ts # unique id frame.rig_from_world = pfd.rig_from_world images_to_add = [] @@ -318,7 +307,7 @@ def _add_online_frames(self) -> None: for id, pfd in enumerate(self.per_frame_data): frame = pycolmap.Frame() frame.rig_id = id + 1 - frame.frame_id = id + 1 + frame.frame_id = pfd.left_ts # unique id frame.rig_from_world = pfd.rig_from_world images_to_add = [] From e066ab32e0647391360f28cfd5f1e7b3446672e5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 21:45:35 +0200 Subject: [PATCH 023/665] keyframe selector --- lamaria/rig/keyframing/keyframe_selection.py | 220 +++++++++++++++++++ 1 file changed, 220 insertions(+) create mode 100644 lamaria/rig/keyframing/keyframe_selection.py diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py new file mode 100644 index 0000000..42ae655 --- /dev/null +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -0,0 +1,220 @@ +from __future__ import annotations + +import shutil +import numpy as np +from pathlib import Path +from copy import deepcopy +from dataclasses import dataclass +from typing import List, Optional + +import pycolmap + +from ... import logger +from ..config.loaders import load_cfg +from ...utils.utils import get_magnitude_from_transform + +@dataclass +class KFParams: + max_rotation_deg: float + max_distance_m: float + max_elapsed_ns: float + + +class KeyframeSelector: + def __init__(self, reconstruction: pycolmap.Reconstruction, timestamps: List[int], cfg=None): + self.init_recons = reconstruction + self.timestamps = timestamps + + cfg = load_cfg() if cfg is None else cfg + self.params = KFParams( + max_rotation_deg=float(cfg.keyframing.max_rotation), + max_distance_m=float(cfg.keyframing.max_distance), + max_elapsed_ns=float(cfg.keyframing.max_elapsed) * 1e9, # convert to ns + ) + + self.keyframes_dir = cfg.result.keyframes_path + self.image_stream_root = cfg.image_stream_path + + self.keyframed_recons = pycolmap.Reconstruction() + self.keyframe_frame_ids: Optional[List[int]] = None + + self.init_recon_type = "device" if len(self.init_recons.rigs) == 1 else "online" + + def _select_keyframes(self): + self.keyframe_frame_ids = [] + dr_dt = np.array([0.0, 0.0]) + dts = 0.0 + + init_frame_ids = sorted(self.init_recons.frames.keys()) + + for i, (prev, curr) in enumerate(zip(init_frame_ids[:-1], init_frame_ids[1:])): + if i == 0: + self.keyframe_frame_ids.append(prev) + continue + + current_rig_from_world = self.init_recons.frames[curr].rig_from_world + previous_rig_from_world = self.init_recons.frames[prev].rig_from_world + current_rig_from_previous_rig = current_rig_from_world * previous_rig_from_world.inverse() + + dr_dt += np.array(get_magnitude_from_transform(current_rig_from_previous_rig)) + dts += self.timestamps[i+1] - self.timestamps[i] + + if dr_dt[0] > self.params.max_rotation_deg or \ + dr_dt[1] > self.params.max_distance_m or \ + dts > self.params.max_elapsed_ns: + + self.keyframe_frame_ids.append(curr) + dr_dt = np.array([0.0, 0.0]) + dts = 0.0 + + def _build_device_keyframed_reconstruction(self): + old_rig = self.init_recons.rigs[1] + new_rig = pycolmap.Rig(rig_id=1) + + ref_sensor_id = old_rig.ref_sensor_id.id + new_ref_sensor = deepcopy(self.init_recons.cameras[ref_sensor_id]) + self.keyframed_recons.add_camera(new_ref_sensor) + new_rig.add_ref_sensor(new_ref_sensor.sensor_id) + + for sensor, sensor_from_rig in old_rig.sensors.items(): + new_sensor = deepcopy(self.init_recons.cameras[sensor.id]) + new_sensor_from_rig = deepcopy(sensor_from_rig) + self.keyframed_recons.add_camera(new_sensor) + new_rig.add_sensor(new_sensor.sensor_id, new_sensor_from_rig) + + self.keyframed_recons.add_rig(new_rig) + + image_id = 1 + for i, frame_id in enumerate(self.keyframe_frame_ids): + old_frame = self.init_recons.frames[frame_id] + + new_frame = pycolmap.Frame() + new_frame.rig_id = 1 + new_frame.frame_id = i + 1 + new_frame.rig_from_world = deepcopy(old_frame.rig_from_world) + + old_image_ids = sorted([d.id for d in old_frame.data_ids]) + + images_to_add = [] + for old_image_id in old_image_ids: + old_image = self.init_recons.images[old_image_id] + + new_image = pycolmap.Image( + old_image.name, + pycolmap.Point2DList(), + old_image.camera_id, + image_id, + ) + + new_image.frame_id = new_frame.frame_id + new_frame.add_data_id(new_image.data_id) + images_to_add.append(new_image) + image_id += 1 + + self.keyframed_recons.add_frame(new_frame) + for img in images_to_add: + self.keyframed_recons.add_image(img) + + def _clone_online_camera(self, old_camera_id: int, new_camera_id: int) -> pycolmap.Camera: + old_camera = self.init_recons.cameras[old_camera_id] + new_camera = deepcopy(old_camera) + new_camera.camera_id = new_camera_id + return new_camera + + def _build_online_keyframed_reconstruction(self): + camera_id = 1 + image_id = 1 + rig_id = 1 + + for i, frame_id in enumerate(self.keyframe_frame_ids): + old_frame = self.init_recons.frames[frame_id] + old_rig_id = old_frame.rig_id + old_rig = self.init_recons.rigs[old_rig_id] + + cam_id_map = {} + + # IMU cosplaying as a dummy camera + old_ref_sensor_id = old_rig.ref_sensor_id.id + new_ref_sensor = self._clone_online_camera(old_ref_sensor_id, camera_id) + self.keyframed_recons.add_camera(new_ref_sensor) + cam_id_map[old_ref_sensor_id] = camera_id + camera_id += 1 + + new_rig = pycolmap.Rig(rig_id=rig_id) + new_rig.add_ref_sensor(new_ref_sensor.sensor_id) + + for old_sensor, sensor_from_rig in old_rig.sensors.items(): + old_sensor_id = old_sensor.id + + if old_sensor_id not in cam_id_map: + new_sensor = self._clone_online_camera(old_sensor_id, camera_id) + self.keyframed_recons.add_camera(new_sensor) + cam_id_map[old_sensor_id] = camera_id + camera_id += 1 + + new_sensor_from_rig = deepcopy(sensor_from_rig) + new_rig.add_sensor(new_sensor.sensor_id, new_sensor_from_rig) + + self.keyframed_recons.add_rig(new_rig) + + new_frame = pycolmap.Frame() + new_frame.rig_id = new_rig.rig_id + new_frame.frame_id = i + 1 + new_frame.rig_from_world = deepcopy(old_frame.rig_from_world) + + old_image_ids = sorted([d.id for d in old_frame.data_ids]) + images_to_add = [] + for old_image_id in old_image_ids: + old_image = self.init_recons.images[old_image_id] + mapped_cam_id = cam_id_map[old_image.camera_id] + + new_image = pycolmap.Image( + old_image.name, + pycolmap.Point2DList(), + mapped_cam_id, + image_id, + ) + new_image.frame_id = new_frame.frame_id + new_frame.add_data_id(new_image.data_id) + images_to_add.append(new_image) + image_id += 1 + + self.keyframed_recons.add_frame(new_frame) + for img in images_to_add: + self.keyframed_recons.add_image(img) + + rig_id += 1 + + def run_keyframing(self) -> pycolmap.Reconstruction: + self._select_keyframes() + if self.init_recon_type == "device": + self._build_device_keyframed_reconstruction() + else: + self._build_online_keyframed_reconstruction() + return self.keyframed_recons + + def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: + if self.keyframe_frame_ids is None: + raise ValueError("Keyframes not selected yet. Run `run_keyframing` first.") + + if output_dir is None: + output_dir = self.keyframes_dir + + output_dir.mkdir(parents=True, exist_ok=True) + + for frame_id in self.keyframe_frame_ids: + frame = self.init_recons.frames[frame_id] + for data_id in frame.data_ids: + image = self.init_recons.images[data_id.id] + src_path = self.image_stream_root / image.name + dst_path = output_dir / image.name + dst_path.parent.mkdir(parents=True, exist_ok=True) + shutil.copy2(src_path, dst_path) + + def write_reconstruction(self, output_path: Path) -> None: + output_path.parent.mkdir(parents=True, exist_ok=True) + logger.info(self.keyframed_recons.summary()) + self.keyframed_recons.write(output_path) + + + \ No newline at end of file From 35bd6171c48f04d89f4d6c5e476de923b93c234e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 21:46:51 +0200 Subject: [PATCH 024/665] vrs to colmap --- lamaria/rig/builder/vrs_to_colmap.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/lamaria/rig/builder/vrs_to_colmap.py b/lamaria/rig/builder/vrs_to_colmap.py index a31b7bc..0b67c03 100644 --- a/lamaria/rig/builder/vrs_to_colmap.py +++ b/lamaria/rig/builder/vrs_to_colmap.py @@ -278,10 +278,10 @@ def _add_device_frames(self) -> None: image_id = 1 rig = self.empty_recons.rigs[1] - for pfd in self.per_frame_data: + for id, pfd in enumerate(self.per_frame_data): frame = pycolmap.Frame() frame.rig_id = rig.rig_id - frame.frame_id = pfd.left_ts # unique id + frame.frame_id = id + 1 # unique id frame.rig_from_world = pfd.rig_from_world images_to_add = [] @@ -307,7 +307,7 @@ def _add_online_frames(self) -> None: for id, pfd in enumerate(self.per_frame_data): frame = pycolmap.Frame() frame.rig_id = id + 1 - frame.frame_id = pfd.left_ts # unique id + frame.frame_id = id + 1 frame.rig_from_world = pfd.rig_from_world images_to_add = [] @@ -336,13 +336,13 @@ def create(self) -> pycolmap.Reconstruction: self._add_online_sensors() self._add_online_frames() - logger.info(self.empty_recons.summary()) - return self.empty_recons - def write(self, output_path: Path) -> None: + def write_reconstruction(self, output_path: Path) -> None: output_path.parent.mkdir(parents=True, exist_ok=True) + logger.info(self.empty_recons.summary()) self.empty_recons.write(output_path) - - - + + def write_frame_timestamps(self, output_path: Path) -> None: + left_ts = np.array(sorted([pfd.left_ts for pfd in self.per_frame_data])) + np.save(output_path, left_ts) From 274397138582475f212109324e417a1d96caec79 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 21:47:59 +0200 Subject: [PATCH 025/665] keyframes --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 7f11d09..7ff0169 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -19,7 +19,7 @@ flags: result: parent_path: results/ subfolder: rig/ - keyframes_subdir: keyframes/all/ + keyframes_subdir: keyframes/ output_folder: outputs/ init_model: empty_recon From ef00b55b996b9634fb5712d526ab0994477e6102 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 21:48:14 +0200 Subject: [PATCH 026/665] defs --- lamaria/rig/config/defaults.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 7ff0169..e347b53 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -1,5 +1,5 @@ paths: - base: /media/lamaria/ + base: /media/arialamar/ recordings: ${paths.base}/recordings/ mps: ${paths.base}/mps/ @@ -17,7 +17,7 @@ flags: has_slam_drops: false # check inside vrs.json file result: - parent_path: results/ + parent_path: test/ subfolder: rig/ keyframes_subdir: keyframes/ output_folder: outputs/ @@ -57,5 +57,5 @@ optimization: keep_imu_residuals: true run: - seq_id: long_1 + seq_id: 5cp vrs_file: ${run.seq_id}.vrs From 714b6b1513e0b8813acfd47a47f6d366e2c9ae8f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 10 Sep 2025 21:57:15 +0200 Subject: [PATCH 027/665] vrs to colmap --- lamaria/rig/builder/vrs_to_colmap.py | 4 +++- lamaria/rig/keyframing/keyframe_selection.py | 4 ++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/builder/vrs_to_colmap.py b/lamaria/rig/builder/vrs_to_colmap.py index 0b67c03..fcbd58e 100644 --- a/lamaria/rig/builder/vrs_to_colmap.py +++ b/lamaria/rig/builder/vrs_to_colmap.py @@ -336,11 +336,13 @@ def create(self) -> pycolmap.Reconstruction: self._add_online_sensors() self._add_online_frames() + logger.info(f"Created empty reconstruction with summary:") + logger.info(self.empty_recons.summary()) + return self.empty_recons def write_reconstruction(self, output_path: Path) -> None: output_path.parent.mkdir(parents=True, exist_ok=True) - logger.info(self.empty_recons.summary()) self.empty_recons.write(output_path) def write_frame_timestamps(self, output_path: Path) -> None: diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 42ae655..6d00b1e 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -191,6 +191,10 @@ def run_keyframing(self) -> pycolmap.Reconstruction: self._build_device_keyframed_reconstruction() else: self._build_online_keyframed_reconstruction() + + logger.info(f"Created keyframed reconstruction with summary:") + logger.info(self.keyframed_recons.summary()) + return self.keyframed_recons def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: From 2f7668e48d9f3408a37c573f1addf838aecf546e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 13:14:10 +0200 Subject: [PATCH 028/665] kf selection --- lamaria/rig/keyframing/keyframe_selection.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 6d00b1e..3ab5952 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -211,8 +211,11 @@ def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: for data_id in frame.data_ids: image = self.init_recons.images[data_id.id] src_path = self.image_stream_root / image.name - dst_path = output_dir / image.name + + name = Path(image.name).stem + Path(image.name).suffix + dst_path = output_dir / name dst_path.parent.mkdir(parents=True, exist_ok=True) + shutil.copy2(src_path, dst_path) def write_reconstruction(self, output_path: Path) -> None: From cd310d5ee4ea67f3502ae97d932496f3f33bb430 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 13:53:31 +0200 Subject: [PATCH 029/665] kf --- lamaria/rig/keyframing/keyframe_selection.py | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 3ab5952..4d22855 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -191,9 +191,6 @@ def run_keyframing(self) -> pycolmap.Reconstruction: self._build_device_keyframed_reconstruction() else: self._build_online_keyframed_reconstruction() - - logger.info(f"Created keyframed reconstruction with summary:") - logger.info(self.keyframed_recons.summary()) return self.keyframed_recons @@ -218,10 +215,10 @@ def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: shutil.copy2(src_path, dst_path) - def write_reconstruction(self, output_path: Path) -> None: + def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path) -> None: output_path.parent.mkdir(parents=True, exist_ok=True) - logger.info(self.keyframed_recons.summary()) - self.keyframed_recons.write(output_path) + logger.info(f"Keyframed {recon.summary()}") + recon.write(output_path) \ No newline at end of file From d8cc3a0c31faa5de09e2b6d5bda5448014d78139 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 14:20:34 +0200 Subject: [PATCH 030/665] kf --- lamaria/rig/keyframing/keyframe_selection.py | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 4d22855..a4d5d03 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -201,22 +201,24 @@ def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: if output_dir is None: output_dir = self.keyframes_dir + if output_dir.exists(): + shutil.rmtree(output_dir) + output_dir.mkdir(parents=True, exist_ok=True) for frame_id in self.keyframe_frame_ids: frame = self.init_recons.frames[frame_id] for data_id in frame.data_ids: image = self.init_recons.images[data_id.id] - src_path = self.image_stream_root / image.name - name = Path(image.name).stem + Path(image.name).suffix - dst_path = output_dir / name - dst_path.parent.mkdir(parents=True, exist_ok=True) + subdir = "left" if "1201-1" in image.name else "right" + src_path = self.image_stream_root / subdir / image.name + dst_path = output_dir / image.name shutil.copy2(src_path, dst_path) def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path) -> None: - output_path.parent.mkdir(parents=True, exist_ok=True) + output_path.mkdir(parents=True, exist_ok=True) logger.info(f"Keyframed {recon.summary()}") recon.write(output_path) From 3fc5d763c61a975d50fcd76e8ea935806922b377 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 14:21:11 +0200 Subject: [PATCH 031/665] kf --- lamaria/rig/keyframing/keyframe_selection.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index a4d5d03..641febd 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -201,7 +201,7 @@ def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: if output_dir is None: output_dir = self.keyframes_dir - if output_dir.exists(): + if output_dir.exists() and any(output_dir.iterdir()): shutil.rmtree(output_dir) output_dir.mkdir(parents=True, exist_ok=True) From 7f962eed788ee894a49115c87bf48280c3ecaf0e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 15:04:56 +0200 Subject: [PATCH 032/665] vrs --- lamaria/rig/builder/vrs_to_colmap.py | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/lamaria/rig/builder/vrs_to_colmap.py b/lamaria/rig/builder/vrs_to_colmap.py index fcbd58e..634efb5 100644 --- a/lamaria/rig/builder/vrs_to_colmap.py +++ b/lamaria/rig/builder/vrs_to_colmap.py @@ -120,8 +120,8 @@ def _get_images(self) -> List[Tuple[Path, Path]]: left_img_dir = self.cfg.image_stream_path / "left" right_img_dir = self.cfg.image_stream_path / "right" - left_images = self._images_from_vrs(left_img_dir, self.cfg.image_stream_path) - right_images = self._images_from_vrs(right_img_dir, self.cfg.image_stream_path) + left_images = self._images_from_vrs(left_img_dir, left_img_dir) + right_images = self._images_from_vrs(right_img_dir, right_img_dir) return list(zip(left_images, right_images)) @@ -336,15 +336,13 @@ def create(self) -> pycolmap.Reconstruction: self._add_online_sensors() self._add_online_frames() - logger.info(f"Created empty reconstruction with summary:") - logger.info(self.empty_recons.summary()) - return self.empty_recons - def write_reconstruction(self, output_path: Path) -> None: + def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path) -> None: output_path.parent.mkdir(parents=True, exist_ok=True) - self.empty_recons.write(output_path) - + logger.info(f"Init {recon.summary()}") + recon.write(output_path) + def write_frame_timestamps(self, output_path: Path) -> None: left_ts = np.array(sorted([pfd.left_ts for pfd in self.per_frame_data])) np.save(output_path, left_ts) From ddfb1b60948173b4a0138df5bdf965fdd9ef4e62 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 15:28:42 +0200 Subject: [PATCH 033/665] ttr --- lamaria/rig/optim/triangulation.py | 115 +++++++++++++++++++++++++++++ 1 file changed, 115 insertions(+) create mode 100644 lamaria/rig/optim/triangulation.py diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py new file mode 100644 index 0000000..99d9082 --- /dev/null +++ b/lamaria/rig/optim/triangulation.py @@ -0,0 +1,115 @@ +from __future__ import annotations + +from collections import defaultdict +from pathlib import Path + +import pycolmap + +from hloc import ( + extract_features, + match_features, + pairs_from_retrieval, + triangulation +) + +from ... import logger +from ..config.loaders import load_cfg + + +def pairs_from_frames(recon: pycolmap.Reconstruction): + rig_pairs = set() + by_index = defaultdict(list) + + for fid in sorted(recon.frames.keys()): + fr = recon.frames[fid] + img_ids = sorted([d.id for d in fr.data_ids]) + names = [recon.images[i].name for i in img_ids] + + for i in range(len(names)): + for j in range(i + 1, len(names)): + rig_pairs.add((names[i], names[j])) + rig_pairs.add((names[j], names[i])) + + for k, n in enumerate(names): + by_index[k].append(n) + + adj_pairs = set() + for idx, seq in by_index.items(): + for a, b in zip(seq[:-1], seq[1:]): + adj_pairs.add((a, b)) + + return rig_pairs, adj_pairs + +def postprocess_pairs_with_reconstruction(sfm_pairs_file: Path, + reconstruction: pycolmap.Reconstruction | Path): + + recon = (reconstruction if isinstance(reconstruction, pycolmap.Reconstruction) + else pycolmap.Reconstruction(str(reconstruction))) + + rig_pairs, adj_pairs = pairs_from_frames(recon) + + existing = set() + with open(sfm_pairs_file, "r") as f: + for line in f: + a, b = line.strip().split() + existing.add((a, b)) + + existing = {p for p in existing if p not in rig_pairs} + existing |= adj_pairs + + with open(sfm_pairs_file, "w") as f: + for a, b in sorted(existing): + f.write(f"{a} {b}\n") + + +def run( + cfg=None, + num_retrieval_matches: int = 5, +) -> Path: + + cfg = load_cfg() if cfg is None else cfg + + keyframes_dir = cfg.result.keyframes_path + hloc_outputs_dir = cfg.result.output_folder_path / "hloc" + hloc_outputs_dir.mkdir(parents=True, exist_ok=True) + + reference_model_path = cfg.result.output_folder_path / cfg.result.kf_model + if not reference_model_path.exists(): + raise FileNotFoundError(f"reference_model not found at {reference_model_path}") + + triangulated_model = cfg.result.output_folder_path / cfg.result.tri_model + pairs_path = hloc_outputs_dir / cfg.triangulation.pairs_file + + retrieval_conf = extract_features.confs[cfg.triangulation.retrieval_conf] + feature_conf = extract_features.confs[cfg.triangulation.feature_conf] + matcher_conf = match_features.confs[cfg.triangulation.matcher_conf] + + logger.info("HLOC confs: retrieval=%s, features=%s, matcher=%s", + cfg.triangulation.retrieval_conf, + cfg.triangulation.feature_conf, + cfg.triangulation.matcher_conf) + + retrieval_path = extract_features.main(retrieval_conf, image_dir=keyframes_dir, export_dir=hloc_outputs_dir) + features_path = extract_features.main(feature_conf, image_dir=keyframes_dir, export_dir=hloc_outputs_dir) + + pairs_from_retrieval.main(retrieval_path, pairs_path, num_retrieval_matches) + postprocess_pairs_with_reconstruction(pairs_path, reference_model_path) + + matches_path = match_features.main( + conf=matcher_conf, + pairs=pairs_path, + features=feature_conf["output"], + export_dir=hloc_outputs_dir, + ) + + triangulation.main( + sfm_dir=triangulated_model, + reference_model=reference_model_path, + image_dir=keyframes_dir, + pairs=pairs_path, + features=features_path, + matches=matches_path, + ) + + logger.info("Triangulated COLMAP model at %s", triangulated_model) + return triangulated_model \ No newline at end of file From 4bc0ae7694c6d3103639fb8ebf23fa110d0cac84 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 15:29:23 +0200 Subject: [PATCH 034/665] tri --- lamaria/rig/optim/triangulation.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 99d9082..ae67e64 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -40,9 +40,10 @@ def pairs_from_frames(recon: pycolmap.Reconstruction): return rig_pairs, adj_pairs -def postprocess_pairs_with_reconstruction(sfm_pairs_file: Path, - reconstruction: pycolmap.Reconstruction | Path): - +def postprocess_pairs_with_reconstruction( + sfm_pairs_file: Path, + reconstruction: pycolmap.Reconstruction | Path +): recon = (reconstruction if isinstance(reconstruction, pycolmap.Reconstruction) else pycolmap.Reconstruction(str(reconstruction))) From 6f8b4f37a609cba4708b9009b43889b2cc946a89 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 15:31:18 +0200 Subject: [PATCH 035/665] tr --- lamaria/rig/optim/triangulation.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index ae67e64..409ecd4 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -112,5 +112,4 @@ def run( matches=matches_path, ) - logger.info("Triangulated COLMAP model at %s", triangulated_model) return triangulated_model \ No newline at end of file From 2af3370b43bdca879dac455d7585e27b516fa47c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 16:02:22 +0200 Subject: [PATCH 036/665] utils --- lamaria/utils/utils.py | 373 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 373 insertions(+) create mode 100644 lamaria/utils/utils.py diff --git a/lamaria/utils/utils.py b/lamaria/utils/utils.py new file mode 100644 index 0000000..6355a98 --- /dev/null +++ b/lamaria/utils/utils.py @@ -0,0 +1,373 @@ +import os +import json +import numpy as np +import pycolmap +from pathlib import Path +from typing import List, Tuple +import shutil +from bisect import bisect_left +from typing import List +import subprocess +from scipy.spatial.transform import Rotation + +from projectaria_tools.core.stream_id import StreamId +from projectaria_tools.core import data_provider, mps +from projectaria_tools.core.mps.utils import get_nearest_pose +from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration + +from lamaria import logger + +ARIA_CAMERAS = [("cam0", "camera-slam-left"), ("cam1", "camera-slam-right")] +LEFT_CAMERA_STREAM_ID = StreamId("1201-1") +RIGHT_CAMERA_STREAM_ID = StreamId("1201-2") +IMU_STREAM_ID = StreamId("1202-1") +LEFT_CAMERA_STREAM_LABEL = "camera-slam-left" +RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" +IMU_STREAM_LABEL = "imu-right" + + +def find_closest_timestamp( + timestamps: list, + target_ts: int, + max_diff=1e6 # 1 ms in nanoseconds +) -> int | None: + + """Timestamps must be in nano seconds""" + index = bisect_left(timestamps, target_ts) + if index == 0: + return timestamps[0] + if index == len(timestamps): + return timestamps[-1] + before = timestamps[index - 1] + after = timestamps[index] + if abs(target_ts - before) < abs(target_ts - after): + closest = before + else: + closest = after + + if abs(target_ts - closest) > max_diff: + return None + + return closest + + +def get_matched_timestamps( + left_timestamps: list, + right_timestamps: list, + acceptable_diff=1e6 # 1 ms in nanoseconds +) -> list[tuple[int, int]]: + + matched_timestamps = [] + + assert all(isinstance(ts, int) for ts in left_timestamps) + assert all(isinstance(ts, int) for ts in right_timestamps) + + if len(left_timestamps) < len(right_timestamps): + for lts in left_timestamps: + closest_rts = find_closest_timestamp(right_timestamps, lts) + if abs(lts - closest_rts) < acceptable_diff: + matched_timestamps.append((lts, closest_rts)) + else: + for rts in right_timestamps: + closest_lts = find_closest_timestamp(left_timestamps, rts) + if abs(rts - closest_lts) < acceptable_diff: + matched_timestamps.append((closest_lts, rts)) + + return matched_timestamps + +def get_t_cam_a_cam_b_from_json( + calibration_file: Path, + camera_a_label: str, + camera_b_label: str, +) -> pycolmap.Rigid3d: + + calib = json.load(calibration_file.open("r")) + + t_body_cam_a = calib[camera_a_label]["T_b_s"] + t_body_cam_b = calib[camera_b_label]["T_b_s"] + + t_imu_cam_a = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam_a["qvec"]), + t_body_cam_a["tvec"], + ) + t_imu_cam_b = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam_b["qvec"]), + t_body_cam_b["tvec"], + ) + + t_camera_a_camera_b = t_imu_cam_a.inverse() * t_imu_cam_b + + return t_camera_a_camera_b + + +def add_cameras_to_reconstruction( + reconstruction: pycolmap.Reconstruction, + calibration_file: Path, +): + + for i, (key, _) in enumerate(ARIA_CAMERAS): + cam = camera_colmap_from_json( + calibration_file=calibration_file, + camera_label=key, + ) + cam.camera_id = i + 1 + reconstruction.add_camera(cam) + + rig = pycolmap.Rig(rig_id=1) + ref_sensor = pycolmap.sensor_t( + id=1, # left camera is the rig + type=pycolmap.SensorType.CAMERA, + ) + rig.add_ref_sensor(ref_sensor) + + sensor1 = pycolmap.sensor_t(id=2, type=pycolmap.SensorType.CAMERA) + sensor_from_rig = get_t_cam_a_cam_b_from_json( + calibration_file=calibration_file, + camera_a_label="cam1", # right + camera_b_label="cam0", # left + ) + rig.add_sensor(sensor1, sensor_from_rig) + + reconstruction.add_rig(rig) + + +def get_qvec_and_tvec_from_transform(transform): + """Returns qvec in format x,y,z,w and tvec in format x,y,z""" + # to_quat() returns in wxyz format + # https://github.com/facebookresearch/projectaria_tools/blob/867105e65cadbe777db355a407d90533c71d2d06/core/python/sophus/SO3PyBind.h#L161 + qvec = transform.rotation().to_quat()[0] + tvec = transform.translation()[0] + + qvec = np.roll( + qvec, -1 + ) # change from w,x,y,z to x,y,z,w for pycolmap format + + return np.array(qvec), np.array(tvec) + + +def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: + q, t = get_qvec_and_tvec_from_transform(transform) + return pycolmap.Rigid3d(pycolmap.Rotation3d(q), t) + + +def get_magnitude_from_transform(transform: pycolmap.Rigid3d) -> Tuple[float, float]: + translation = transform.translation + quat_xyzw = transform.rotation.quat + rotation = Rotation.from_quat(quat_xyzw) + dr = np.rad2deg(rotation.magnitude()) + dt = np.linalg.norm(translation) + + return dr, dt + + +def get_camera_params_for_colmap( + camera_calibration: CameraCalibration, + camera_model: str, +): + # params = [f_u {f_v} c_u c_v [k_0: k_{numK-1}] + # {p_0 p_1} {s_0 s_1 s_2 s_3}] + # projection_params is a 15 length vector, + # starting with focal length, pp, extra coeffs + camera_params = camera_calibration.get_projection_params() + f_x, f_y, c_x, c_y = ( + camera_params[0], + camera_params[0], + camera_params[1], + camera_params[2], + ) + + p2, p1 = camera_params[-5], camera_params[-6] + + k1, k2, k3, k4, k5, k6 = camera_params[3:9] + + # FULL_OPENCV model format: + # fx, fy, cx, cy, k1, k2, p1, p2, k3, k4, k5, k6 + + # OPENCV_FISHEYE model format: + # fx, fy, cx, cy, k1, k2, k3, k4 + + if camera_model == "OPENCV_FISHEYE": + params = [f_x, f_y, c_x, c_y, k1, k2, k3, k4] + elif camera_model == "FULL_OPENCV": + params = [f_x, f_y, c_x, c_y, k1, k2, p1, p2, k3, k4, k5, k6] + elif camera_model == "RAD_TAN_THIN_PRISM_FISHEYE": + aria_fisheye_params = camera_params + focal_length = aria_fisheye_params[0] + aria_fisheye_params = np.insert(aria_fisheye_params, 0, focal_length) + params = aria_fisheye_params + + return params + + +def camera_colmap_from_calib(calib: CameraCalibration) -> pycolmap.Camera: + if calib.get_model_name().name != "FISHEYE624": + raise ValueError(f"Unsupported Aria model {calib.get_model_name().name}") + model = "RAD_TAN_THIN_PRISM_FISHEYE" + params = get_camera_params_for_colmap(calib, model) + width, height = calib.get_image_size() + return pycolmap.Camera( + model=model, + width=width, + height=height, + params=params, + ) + + +def camera_colmap_from_json( + calibration_file: Path, # open sourced aria calibration files + camera_label: str +) -> pycolmap.Camera: + + calib = json.load(calibration_file.open("r")) + camera_data = calib[camera_label] + if camera_data["model"] != "RAD_TAN_THIN_PRISM_FISHEYE": + raise ValueError(f"Unsupported Aria model {camera_data['model']}") + + model = "RAD_TAN_THIN_PRISM_FISHEYE" + params = camera_data["params"] + width = camera_data["resolution"]["width"] + height = camera_data["resolution"]["height"] + return pycolmap.Camera( + model=model, + width=width, + height=height, + params=params, + ) + +def delete_files_in_folder(folder, exclude_pattern=None): + if os.path.isdir(folder): + for filename in os.listdir(folder): + file_path = os.path.join(folder, filename) + + if exclude_pattern is not None and exclude_pattern in filename: + continue + + try: + if os.path.isfile(file_path) or os.path.islink(file_path): + os.unlink(file_path) + elif os.path.isdir(file_path): + shutil.rmtree(file_path) + except Exception as e: + print("Failed to delete %s. Reason: %s" % (file_path, e)) + else: + os.makedirs(folder, exist_ok=True) + + +def extract_images_from_vrs( + vrs_file: Path, + image_folder: Path, + left_subfolder_name="left", + right_subfolder_name="right", + rgb_subfolder_name="rgb", + verbose: bool = False, + extract_rgb: bool = False, + extract_left: bool = True, + extract_right: bool = True, +): + for camera, stream_id in [ + (left_subfolder_name, "1201-1"), + (right_subfolder_name, "1201-2"), + (rgb_subfolder_name, "214-1"), + ]: + if camera == rgb_subfolder_name and not extract_rgb: + continue + + if camera == left_subfolder_name and not extract_left: + continue + + if camera == right_subfolder_name and not extract_right: + continue + + output_dir = image_folder / camera + output_dir.mkdir(parents=True, exist_ok=True) + delete_files_in_folder(output_dir) + logger.info( + "Extracting images for camera %s in VRS %s", camera, vrs_file + ) + cmd = f"vrs extract-images {vrs_file} --to {output_dir} + {stream_id}" + stdout = None if verbose else subprocess.PIPE + out = subprocess.run( + cmd, shell=True, stderr=subprocess.STDOUT, stdout=stdout + ) + if out.returncode: + msg = f"Command '{cmd}' returned {out.returncode}." + if out.stdout: + msg += "\n" + out.stdout.decode("utf-8") + raise subprocess.SubprocessError(msg) + logger.info("Done!") + + +def get_closed_loop_data_from_mps(mps_path: Path): + closed_loop_traj_file = mps_path / "slam" / "closed_loop_trajectory.csv" + data = mps.read_closed_loop_trajectory(closed_loop_traj_file.as_posix()) + return data + + +def get_mps_poses_for_timestamps( + trajectory_data: List[mps.ClosedLoopTrajectoryPose], + timestamps: List[int], +) -> List: + + poses = [] + if trajectory_data: + for ts in timestamps: + pose_information = get_nearest_pose(trajectory_data, ts) + if pose_information: + t_world_device = pose_information.transform_world_device + poses.append(t_world_device) + else: + poses.append(None) + + return poses + + +def get_t_rig_world_for_device_time_ns( + trajectory_data: List[mps.ClosedLoopTrajectoryPose], + device_time_ns: int, + imu_calibration: ImuCalibration, +): + if trajectory_data: + pose_information = get_nearest_pose(trajectory_data, device_time_ns) + if pose_information: + t_world_device = pose_information.transform_world_device + t_device_imu = imu_calibration.get_transform_device_imu() + assert ( + t_device_imu is not None + ), f"No t_device_imu found for device time {device_time_ns}, \ + check imu calibration" + + t_world_imu = t_world_device @ t_device_imu + t_imu_world = t_world_imu.inverse() + + return t_imu_world + else: + return None + else: + raise ValueError("No trajectory data found") + + +def get_t_imu_camera( + imu_calib: ImuCalibration, + camera_calib: CameraCalibration, + return_qt=False, + return_matrix=False, +): + t_device_cam = camera_calib.get_transform_device_camera() + t_device_imu = imu_calib.get_transform_device_imu() + t_imu_device = t_device_imu.inverse() + + t_imu_cam = t_imu_device @ t_device_cam + + assert not ( + return_qt and return_matrix + ), "Only one of return_qt or return_matrix can be True" + + if return_qt: + qvec, tvec = get_qvec_and_tvec_from_transform(t_imu_cam) + return qvec, tvec + + if return_matrix: + t_imu_cam_matrix = t_imu_cam.to_matrix() + return t_imu_cam_matrix + + return t_imu_cam \ No newline at end of file From 5f6d40cbef14c72251d60062b1399e3bad8f9b80 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 17:14:22 +0200 Subject: [PATCH 037/665] full timestamps --- lamaria/rig/builder/vrs_to_colmap.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/builder/vrs_to_colmap.py b/lamaria/rig/builder/vrs_to_colmap.py index 634efb5..f263a88 100644 --- a/lamaria/rig/builder/vrs_to_colmap.py +++ b/lamaria/rig/builder/vrs_to_colmap.py @@ -343,6 +343,7 @@ def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path logger.info(f"Init {recon.summary()}") recon.write(output_path) - def write_frame_timestamps(self, output_path: Path) -> None: + def write_full_timestamps(self, output_path: Path) -> None: + output_path.parent.mkdir(parents=True, exist_ok=True) left_ts = np.array(sorted([pfd.left_ts for pfd in self.per_frame_data])) np.save(output_path, left_ts) From 15298920c5e7980cc41f94d3d1e52e6e72507090 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 17:14:48 +0200 Subject: [PATCH 038/665] move --- lamaria/rig/{builder => keyframing}/vrs_to_colmap.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename lamaria/rig/{builder => keyframing}/vrs_to_colmap.py (100%) diff --git a/lamaria/rig/builder/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py similarity index 100% rename from lamaria/rig/builder/vrs_to_colmap.py rename to lamaria/rig/keyframing/vrs_to_colmap.py From 2ac6c9a6f44eafe84259a47a61503e378e5b2c2d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 17:15:54 +0200 Subject: [PATCH 039/665] keyframe timestamps --- lamaria/rig/keyframing/keyframe_selection.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 641febd..cab12c6 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -217,6 +217,11 @@ def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: shutil.copy2(src_path, dst_path) + def write_keyframe_timestamps(self, output_path: Path) -> None: + output_path.parent.mkdir(parents=True, exist_ok=True) + keyframed_timestamps = np.array([self.timestamps[i - 1] for i in self.keyframe_frame_ids]) + np.save(output_path, keyframed_timestamps) + def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path) -> None: output_path.mkdir(parents=True, exist_ok=True) logger.info(f"Keyframed {recon.summary()}") From ee6b9f33f07d94fc9e8b73d578e9ea707e27f031 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 17:32:26 +0200 Subject: [PATCH 040/665] calib imu --- lamaria/rig/optim/imu/calib.py | 30 ++++++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) create mode 100644 lamaria/rig/optim/imu/calib.py diff --git a/lamaria/rig/optim/imu/calib.py b/lamaria/rig/optim/imu/calib.py new file mode 100644 index 0000000..612d14d --- /dev/null +++ b/lamaria/rig/optim/imu/calib.py @@ -0,0 +1,30 @@ +import numpy as np +import pycolmap + +def get_imu_calibration_parameters( + gyro_infl: float = 1.0, + acc_infl: float = 1.0 +) -> pycolmap.ImuCalibration: + + imu_calib = pycolmap.ImuCalibration() + imu_calib.gravity_magnitude = 9.80600 + imu_calib.acc_noise_density = ( + 0.8e-4 * imu_calib.gravity_magnitude * acc_infl + ) + imu_calib.gyro_noise_density = ( + 1e-2 * (np.pi / 180.0) * gyro_infl + ) + imu_calib.acc_bias_random_walk_sigma = ( + 3.5e-5 + * imu_calib.gravity_magnitude + * np.sqrt(353) + * acc_infl + ) # accel_right BW = 353 + imu_calib.gyro_bias_random_walk_sigma = ( + 1.3e-3 * (np.pi / 180.0) * np.sqrt(116) * gyro_infl + ) # gyro_right BW = 116 + imu_calib.acc_saturation_max = 8.0 * imu_calib.gravity_magnitude + imu_calib.gyro_saturation_max = 1000.0 * (np.pi / 180.0) + imu_calib.imu_rate = 1000.0 + + return imu_calib From 26fd0feec0960bca3218350019b48bbb0fcbafdb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 17:40:22 +0200 Subject: [PATCH 041/665] model --- lamaria/rig/optim/imu/{calib.py => model.py} | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) rename lamaria/rig/optim/imu/{calib.py => model.py} (82%) diff --git a/lamaria/rig/optim/imu/calib.py b/lamaria/rig/optim/imu/model.py similarity index 82% rename from lamaria/rig/optim/imu/calib.py rename to lamaria/rig/optim/imu/model.py index 612d14d..41872da 100644 --- a/lamaria/rig/optim/imu/calib.py +++ b/lamaria/rig/optim/imu/model.py @@ -1,7 +1,15 @@ import numpy as np import pycolmap +from typing import List -def get_imu_calibration_parameters( +def load_imu_states( + reconstruction: pycolmap.Reconstruction, + timestamps: List[int] +) -> List[pycolmap.ImuState]: + pass + + +def load_imu_calibration( gyro_infl: float = 1.0, acc_infl: float = 1.0 ) -> pycolmap.ImuCalibration: From 84ae49f78b8b446ef3284fbfd9e285cec4a4ec49 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 11 Sep 2025 19:22:33 +0200 Subject: [PATCH 042/665] triangulation --- lamaria/rig/optim/triangulation.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 409ecd4..599c0ba 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -78,7 +78,7 @@ def run( if not reference_model_path.exists(): raise FileNotFoundError(f"reference_model not found at {reference_model_path}") - triangulated_model = cfg.result.output_folder_path / cfg.result.tri_model + triangulated_model_path = cfg.result.output_folder_path / cfg.result.tri_model pairs_path = hloc_outputs_dir / cfg.triangulation.pairs_file retrieval_conf = extract_features.confs[cfg.triangulation.retrieval_conf] @@ -103,8 +103,8 @@ def run( export_dir=hloc_outputs_dir, ) - triangulation.main( - sfm_dir=triangulated_model, + triangulated_model = triangulation.main( + sfm_dir=triangulated_model_path, reference_model=reference_model_path, image_dir=keyframes_dir, pairs=pairs_path, From e59b3854bf40b348373a67e06af655cba49ef4cd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 13 Sep 2025 09:36:10 +0200 Subject: [PATCH 043/665] defs --- lamaria/rig/config/defaults.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index e347b53..e380a34 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -24,6 +24,7 @@ result: init_model: empty_recon kf_model: keyframe_recon + tri_model: triangulated_recon optim_model: optim_recon keyframing: @@ -32,7 +33,7 @@ keyframing: max_elapsed: 1.0 triangulation: - sfm_pairs: pairs_from_retrieval_and_temporal.txt + pairs_file: pairs.txt feature_conf: aliked-n16 matcher_conf: aliked+lightglue retrieval_conf: netvlad From 38de0bb87f52c5c060122e7535a6790597a9ed2d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 13 Sep 2025 09:39:20 +0200 Subject: [PATCH 044/665] test_vrs_to_colmap --- scripts/rig/test_vrs_to_colmap.py | 38 +++++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) create mode 100644 scripts/rig/test_vrs_to_colmap.py diff --git a/scripts/rig/test_vrs_to_colmap.py b/scripts/rig/test_vrs_to_colmap.py new file mode 100644 index 0000000..36dc88d --- /dev/null +++ b/scripts/rig/test_vrs_to_colmap.py @@ -0,0 +1,38 @@ +# scripts/rig/test_vrs_to_colmap.py +import sys +import numpy as np +from pathlib import Path +from lamaria.rig.config.loaders import load_cfg +from lamaria.rig.keyframing.vrs_to_colmap import VrsToColmap +from lamaria.rig.keyframing.image_extraction import run as run_extraction +from lamaria.rig.keyframing.keyframe_selection import KeyframeSelector +from lamaria.rig.optim.triangulation import run as run_triangulation + +def main(): + cfg = load_cfg(cli_overrides=sys.argv[1:]) + seq_builder = VrsToColmap(cfg) + + run_extraction( + image_stream_folder=cfg.image_stream_path, + vrs_path=cfg.vrs_file_path, + ) + recon = seq_builder.create() + + out_dir = cfg.result.output_folder_path / cfg.result.init_model + out_dir.mkdir(parents=True, exist_ok=True) + seq_builder.write_reconstruction(recon, out_dir) + + seq_builder.write_full_timestamps(cfg.result.output_folder_path / "timestamps" /f"full.npy") + + timestamps = np.load(cfg.result.output_folder_path / "timestamps" /f"full.npy").tolist() + + kf_selector = KeyframeSelector(reconstruction=recon, timestamps=timestamps, cfg=cfg) + kf_recon = kf_selector.run_keyframing() + kf_selector.write_reconstruction(kf_recon, cfg.result.output_folder_path / cfg.result.kf_model) + kf_selector.copy_images_to_keyframes_dir() + # kf_selector.write_keyframe_timestamps(cfg.result.output_folder_path / "timestamps" / f"keyframe.npy") + # _ = run_triangulation(cfg=cfg) + + +if __name__ == "__main__": + main() From 817f924a08784c650ffe3aea701b1261e97d9bdf Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 15 Sep 2025 09:17:01 +0200 Subject: [PATCH 045/665] use dev calib --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index e380a34..2f6c0bf 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -12,7 +12,7 @@ streams: imu_right_stream_id: 1202-1 flags: - use_device_calibration: false + use_device_calibration: true mps_fail: false has_slam_drops: false # check inside vrs.json file From d2d9a77d6b6abf4cc06fe1d096184d4255e0bca2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 15 Sep 2025 09:23:44 +0200 Subject: [PATCH 046/665] keyframing --- lamaria/rig/keyframing/keyframe_selection.py | 28 ++++++++++++++------ 1 file changed, 20 insertions(+), 8 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index cab12c6..e435f73 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -70,14 +70,20 @@ def _select_keyframes(self): def _build_device_keyframed_reconstruction(self): old_rig = self.init_recons.rigs[1] new_rig = pycolmap.Rig(rig_id=1) + camera_id = 1 + cam_map = {} # new to old ref_sensor_id = old_rig.ref_sensor_id.id - new_ref_sensor = deepcopy(self.init_recons.cameras[ref_sensor_id]) + cam_map[ref_sensor_id] = camera_id + new_ref_sensor = self._clone_camera(ref_sensor_id, camera_id) + camera_id += 1 self.keyframed_recons.add_camera(new_ref_sensor) new_rig.add_ref_sensor(new_ref_sensor.sensor_id) for sensor, sensor_from_rig in old_rig.sensors.items(): - new_sensor = deepcopy(self.init_recons.cameras[sensor.id]) + new_sensor = self._clone_camera(sensor.id, camera_id) + cam_map[sensor.id] = camera_id + camera_id += 1 new_sensor_from_rig = deepcopy(sensor_from_rig) self.keyframed_recons.add_camera(new_sensor) new_rig.add_sensor(new_sensor.sensor_id, new_sensor_from_rig) @@ -98,11 +104,12 @@ def _build_device_keyframed_reconstruction(self): images_to_add = [] for old_image_id in old_image_ids: old_image = self.init_recons.images[old_image_id] + new_cam_id = cam_map[old_image.camera_id] new_image = pycolmap.Image( old_image.name, pycolmap.Point2DList(), - old_image.camera_id, + new_cam_id, image_id, ) @@ -115,10 +122,15 @@ def _build_device_keyframed_reconstruction(self): for img in images_to_add: self.keyframed_recons.add_image(img) - def _clone_online_camera(self, old_camera_id: int, new_camera_id: int) -> pycolmap.Camera: + def _clone_camera(self, old_camera_id: int, new_camera_id: int) -> pycolmap.Camera: old_camera = self.init_recons.cameras[old_camera_id] - new_camera = deepcopy(old_camera) - new_camera.camera_id = new_camera_id + new_camera = pycolmap.Camera( + model=old_camera.model, + width=old_camera.width, + height=old_camera.height, + params=old_camera.params, + camera_id=new_camera_id, + ) return new_camera def _build_online_keyframed_reconstruction(self): @@ -135,7 +147,7 @@ def _build_online_keyframed_reconstruction(self): # IMU cosplaying as a dummy camera old_ref_sensor_id = old_rig.ref_sensor_id.id - new_ref_sensor = self._clone_online_camera(old_ref_sensor_id, camera_id) + new_ref_sensor = self._clone_camera(old_ref_sensor_id, camera_id) self.keyframed_recons.add_camera(new_ref_sensor) cam_id_map[old_ref_sensor_id] = camera_id camera_id += 1 @@ -147,7 +159,7 @@ def _build_online_keyframed_reconstruction(self): old_sensor_id = old_sensor.id if old_sensor_id not in cam_id_map: - new_sensor = self._clone_online_camera(old_sensor_id, camera_id) + new_sensor = self._clone_camera(old_sensor_id, camera_id) self.keyframed_recons.add_camera(new_sensor) cam_id_map[old_sensor_id] = camera_id camera_id += 1 From 78edf55e1c9e75f6e0f2c0324ccf89ce93555c46 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 15 Sep 2025 09:24:12 +0200 Subject: [PATCH 047/665] test vrs to colmap --- scripts/rig/test_vrs_to_colmap.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/scripts/rig/test_vrs_to_colmap.py b/scripts/rig/test_vrs_to_colmap.py index 36dc88d..a6ee393 100644 --- a/scripts/rig/test_vrs_to_colmap.py +++ b/scripts/rig/test_vrs_to_colmap.py @@ -30,8 +30,8 @@ def main(): kf_recon = kf_selector.run_keyframing() kf_selector.write_reconstruction(kf_recon, cfg.result.output_folder_path / cfg.result.kf_model) kf_selector.copy_images_to_keyframes_dir() - # kf_selector.write_keyframe_timestamps(cfg.result.output_folder_path / "timestamps" / f"keyframe.npy") - # _ = run_triangulation(cfg=cfg) + kf_selector.write_keyframe_timestamps(cfg.result.output_folder_path / "timestamps" / f"keyframe.npy") + _ = run_triangulation(cfg=cfg) if __name__ == "__main__": From 3f9a7d5e1a46224f2e3abbedfacbd787da413655 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 15 Sep 2025 17:56:28 +0200 Subject: [PATCH 048/665] tri --- lamaria/rig/optim/triangulation.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 599c0ba..4bce52d 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -70,7 +70,10 @@ def run( cfg = load_cfg() if cfg is None else cfg - keyframes_dir = cfg.result.keyframes_path + keyframes_dir = cfg.result.output_folder_path / cfg.result.keyframes + if not keyframes_dir.exists(): + raise FileNotFoundError(f"keyframes_dir not found at {keyframes_dir}") + hloc_outputs_dir = cfg.result.output_folder_path / "hloc" hloc_outputs_dir.mkdir(parents=True, exist_ok=True) From 93593e321a7f624a1dae44e53f0621b08b5aa31c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 15 Sep 2025 17:56:46 +0200 Subject: [PATCH 049/665] fix --- lamaria/rig/config/defaults.yaml | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 2f6c0bf..e823d76 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -18,15 +18,17 @@ flags: result: parent_path: test/ - subfolder: rig/ - keyframes_subdir: keyframes/ - output_folder: outputs/ - + output_folder: rig/ + + keyframes: keyframes init_model: empty_recon kf_model: keyframe_recon tri_model: triangulated_recon optim_model: optim_recon + full_ts: timestamps/full.npy + kf_ts: timestamps/keyframe.npy + keyframing: max_rotation: 20.0 max_distance: 1.0 From d887d8389c8ab098192d2b04796767d6b0c6822a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 15 Sep 2025 17:57:00 +0200 Subject: [PATCH 050/665] f --- lamaria/rig/config/loaders.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index 414ade6..410d8f6 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -29,10 +29,9 @@ def load_cfg( cfg.mps_path = mps / f"mps_{vrs_stem}_vrs" cfg.image_stream_path = base / parent_rel / vrs_stem / "image_stream" - vio_base = base / parent_rel / vrs_stem / cfg.result.subfolder + vio_base = base / parent_rel / vrs_stem cfg.result.parent_path = vio_base - cfg.result.keyframes_path = vio_base / cfg.result.keyframes_subdir cfg.result.output_folder_path = vio_base / cfg.result.output_folder return cfg From d7980178a70eda2112bd2a0fd12b55f47f417533 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 09:54:43 +0200 Subject: [PATCH 051/665] image ext --- lamaria/rig/keyframing/image_extraction.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/image_extraction.py b/lamaria/rig/keyframing/image_extraction.py index 114f576..0f8f937 100644 --- a/lamaria/rig/keyframing/image_extraction.py +++ b/lamaria/rig/keyframing/image_extraction.py @@ -3,7 +3,7 @@ from pathlib import Path from lamaria.rig.config.loaders import load_cfg -from ...utils.utils import extract_images_from_vrs +from ...utils.general import extract_images_from_vrs def run( From 74d32431f080cd132fa7a32217bf2a381361550f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 09:55:05 +0200 Subject: [PATCH 052/665] undistort --- tools/undistort_asl_folder.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index 06bfea5..22bbdb7 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -10,7 +10,7 @@ import pycolmap from tqdm import tqdm -from lamaria.utils.utils import ( +from lamaria.utils.general import ( ARIA_CAMERAS, add_cameras_to_reconstruction, ) From da31d418b245126cbb83ee2f887e56f73a2e7d9f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 09:55:21 +0200 Subject: [PATCH 053/665] vrs to asl --- tools/vrs_to_asl_folder.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index 2146ad9..2a526b6 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -9,7 +9,7 @@ from tqdm import tqdm from lamaria import logger -from lamaria.utils.utils import ( +from lamaria.utils.general import ( LEFT_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, IMU_STREAM_ID, From 0abc29f94b68a3e879f305dfa18a69802235c428 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 09:56:24 +0200 Subject: [PATCH 054/665] kf --- lamaria/rig/keyframing/keyframe_selection.py | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index e435f73..2373ce8 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -11,7 +11,7 @@ from ... import logger from ..config.loaders import load_cfg -from ...utils.utils import get_magnitude_from_transform +from ...utils.general import get_magnitude_from_transform @dataclass class KFParams: @@ -32,7 +32,7 @@ def __init__(self, reconstruction: pycolmap.Reconstruction, timestamps: List[int max_elapsed_ns=float(cfg.keyframing.max_elapsed) * 1e9, # convert to ns ) - self.keyframes_dir = cfg.result.keyframes_path + self.keyframes_dir = cfg.result.output_folder_path / cfg.result.keyframes self.image_stream_root = cfg.image_stream_path self.keyframed_recons = pycolmap.Reconstruction() @@ -237,7 +237,4 @@ def write_keyframe_timestamps(self, output_path: Path) -> None: def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path) -> None: output_path.mkdir(parents=True, exist_ok=True) logger.info(f"Keyframed {recon.summary()}") - recon.write(output_path) - - - \ No newline at end of file + recon.write(output_path) \ No newline at end of file From 13a69edb5f0e11110b80ff10735d3cb69d7c8731 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 09:56:37 +0200 Subject: [PATCH 055/665] vrs --- lamaria/rig/keyframing/vrs_to_colmap.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py index f263a88..6bcc85b 100644 --- a/lamaria/rig/keyframing/vrs_to_colmap.py +++ b/lamaria/rig/keyframing/vrs_to_colmap.py @@ -14,7 +14,7 @@ from ... import logger from ..config.loaders import load_cfg -from ...utils.utils import ( +from ...utils.general import ( find_closest_timestamp, get_t_imu_camera, camera_colmap_from_calib, From 2fe9a72eae3ab9afd9c2180a5dcda03337c3914b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 09:56:50 +0200 Subject: [PATCH 056/665] lll --- lamaria/utils/{utils.py => general.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename lamaria/utils/{utils.py => general.py} (100%) diff --git a/lamaria/utils/utils.py b/lamaria/utils/general.py similarity index 100% rename from lamaria/utils/utils.py rename to lamaria/utils/general.py From ec42014815c882c8248a391473f054461e6ca81a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 10:36:50 +0200 Subject: [PATCH 057/665] imu --- lamaria/rig/optim/imu.py | 74 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 74 insertions(+) create mode 100644 lamaria/rig/optim/imu.py diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py new file mode 100644 index 0000000..6b9cf6a --- /dev/null +++ b/lamaria/rig/optim/imu.py @@ -0,0 +1,74 @@ +import numpy as np +import pycolmap +from typing import List + +from tqdm import tqdm + +def load_imu_states( + reconstruction: pycolmap.Reconstruction, + timestamps: List[int] # must be a sorted list in ns +) -> dict[int, pycolmap.ImuState]: + imu_states = {} + + frame_ids = sorted(reconstruction.frames.keys()) + assert len(timestamps) == len(frame_ids), "Unequal timestamps and frames for imu state calc" + assert len(frame_ids) >= 2, "Need at least two frames to compute velocity" + + ts_sec = np.asarray(timestamps, dtype=np.float64) / 1e9 + + + for k in tqdm( + range(len(frame_ids) - 1), + desc="Loading IMU states" + ): + i = frame_ids[k] + j = frame_ids[k + 1] + + t1, t2 = ts_sec[k], ts_sec[k + 1] + dt = t2 - t1 + if dt == 0: + raise ValueError(f"Zero dt between frames {i} and {j}") + + pi = reconstruction.frames[i].rig_from_world.inverse().translation + pj = reconstruction.frames[j].rig_from_world.inverse().translation + + vel = (pj - pi) / dt + s = pycolmap.ImuState() + s.set_velocity(vel) + imu_states[i] = s + + last_id = frame_ids[-1] + prev_id = frame_ids[-2] + last_state = pycolmap.ImuState() + last_state.set_velocity(imu_states[prev_id].velocity) + imu_states[last_id] = last_state + + return imu_states + +def load_imu_calibration( + gyro_infl: float = 1.0, + acc_infl: float = 1.0 +) -> pycolmap.ImuCalibration: + + imu_calib = pycolmap.ImuCalibration() + imu_calib.gravity_magnitude = 9.80600 + imu_calib.acc_noise_density = ( + 0.8e-4 * imu_calib.gravity_magnitude * acc_infl + ) + imu_calib.gyro_noise_density = ( + 1e-2 * (np.pi / 180.0) * gyro_infl + ) + imu_calib.acc_bias_random_walk_sigma = ( + 3.5e-5 + * imu_calib.gravity_magnitude + * np.sqrt(353) + * acc_infl + ) # accel_right BW = 353 + imu_calib.gyro_bias_random_walk_sigma = ( + 1.3e-3 * (np.pi / 180.0) * np.sqrt(116) * gyro_infl + ) # gyro_right BW = 116 + imu_calib.acc_saturation_max = 8.0 * imu_calib.gravity_magnitude + imu_calib.gyro_saturation_max = 1000.0 * (np.pi / 180.0) + imu_calib.imu_rate = 1000.0 + + return imu_calib From 1893a525586d0234bd004505759be0aa0f976f3f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 10:53:46 +0200 Subject: [PATCH 058/665] imu funcs --- lamaria/rig/optim/imu.py | 45 +++++++++++++++++++++++++++++++++++++++- 1 file changed, 44 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index 6b9cf6a..ed360ee 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -1,9 +1,53 @@ import numpy as np import pycolmap from typing import List +from pathlib import Path from tqdm import tqdm + +def load_preintegrated_imu_measurements( + rect_imu_data_npy: Path, + reconstruction: pycolmap.Reconstruction, + timestamps: List[int], # must be a sorted list in ns + gyro_infl: float = 1.0, + acc_infl: float = 1.0, + integration_noise_density: float = 1.0 +) -> dict[int, pycolmap.PreintegratedImuMeasurement]: + + preintegrated_measurements = {} + rect_imu_data = np.load(rect_imu_data_npy, allow_pickle=True) + imu_measurements = pycolmap.ImuMeasurements(rect_imu_data.tolist()) + + options = pycolmap.ImuPreintegrationOptions() + options.integration_noise_density = integration_noise_density + imu_calib = load_imu_calibration(gyro_infl, acc_infl) + + frame_ids = sorted(reconstruction.frames.keys()) + assert len(timestamps) == len(frame_ids), "Unequal timestamps and frames for preinteg calc" + assert len(frame_ids) >= 2, "Need at least two frames to compute preinteg measurements" + ts_sec = np.asarray(timestamps, dtype=np.float64) / 1e9 + + for k in tqdm( + range(len(frame_ids) - 1), # skip the last frame + desc="Loading preintegrated measurements" + ): + i = frame_ids[k] + t1, t2 = ts_sec[k], ts_sec[k + 1] + ms = imu_measurements.get_measurements_contain_edge(t1, t2) + if len(ms) == 0: + continue + integrated_m = pycolmap.PreintegratedImuMeasurement( + options, + imu_calib, + t1, + t2, + ) + integrated_m.add_measurements(ms) + preintegrated_measurements[i] = integrated_m + + return preintegrated_measurements + def load_imu_states( reconstruction: pycolmap.Reconstruction, timestamps: List[int] # must be a sorted list in ns @@ -16,7 +60,6 @@ def load_imu_states( ts_sec = np.asarray(timestamps, dtype=np.float64) / 1e9 - for k in tqdm( range(len(frame_ids) - 1), desc="Loading IMU states" From 5db7a1b9b2fa535359667cd6ffda789229b1dba3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 10:55:23 +0200 Subject: [PATCH 059/665] old --- lamaria/rig/optim/imu/model.py | 38 ---------------------------------- 1 file changed, 38 deletions(-) delete mode 100644 lamaria/rig/optim/imu/model.py diff --git a/lamaria/rig/optim/imu/model.py b/lamaria/rig/optim/imu/model.py deleted file mode 100644 index 41872da..0000000 --- a/lamaria/rig/optim/imu/model.py +++ /dev/null @@ -1,38 +0,0 @@ -import numpy as np -import pycolmap -from typing import List - -def load_imu_states( - reconstruction: pycolmap.Reconstruction, - timestamps: List[int] -) -> List[pycolmap.ImuState]: - pass - - -def load_imu_calibration( - gyro_infl: float = 1.0, - acc_infl: float = 1.0 -) -> pycolmap.ImuCalibration: - - imu_calib = pycolmap.ImuCalibration() - imu_calib.gravity_magnitude = 9.80600 - imu_calib.acc_noise_density = ( - 0.8e-4 * imu_calib.gravity_magnitude * acc_infl - ) - imu_calib.gyro_noise_density = ( - 1e-2 * (np.pi / 180.0) * gyro_infl - ) - imu_calib.acc_bias_random_walk_sigma = ( - 3.5e-5 - * imu_calib.gravity_magnitude - * np.sqrt(353) - * acc_infl - ) # accel_right BW = 353 - imu_calib.gyro_bias_random_walk_sigma = ( - 1.3e-3 * (np.pi / 180.0) * np.sqrt(116) * gyro_infl - ) # gyro_right BW = 116 - imu_calib.acc_saturation_max = 8.0 * imu_calib.gravity_magnitude - imu_calib.gyro_saturation_max = 1000.0 * (np.pi / 180.0) - imu_calib.imu_rate = 1000.0 - - return imu_calib From 2f4fb7d6d8effbfa6f36b15296dddd5bc3289f8d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 14:07:00 +0200 Subject: [PATCH 060/665] vrs to asl folder --- tools/vrs_to_asl_folder.py | 1 + 1 file changed, 1 insertion(+) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index 2a526b6..a0fa25c 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -208,6 +208,7 @@ def form_aria_asl_folder( matched_timestamps = get_matched_timestamps( left_timestamps=image_timestamps, right_timestamps=right_image_timestamps, + max_diff=1e6, # 1 ms in nanoseconds ) assert len(matched_timestamps) > 0, "No matched timestamps found" From 9305d8ad178aeb34b7d02d80abe4b2f32b31f320 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 14:29:49 +0200 Subject: [PATCH 061/665] imu utils --- lamaria/utils/imu.py | 88 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 88 insertions(+) create mode 100644 lamaria/utils/imu.py diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py new file mode 100644 index 0000000..969deeb --- /dev/null +++ b/lamaria/utils/imu.py @@ -0,0 +1,88 @@ +import pycolmap +import numpy as np +from pathlib import Path +from tqdm import tqdm +from projectaria_tools.core import mps, data_provider +from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from projectaria_tools.core.stream_id import StreamId + +from lamaria.utils.general import ( + IMU_STREAM_ID, + find_closest_timestamp, +) + +def get_online_params_for_imu_from_mps( + online_calibs_file: Path, + stream_label: str, + num_error: float = 1e6 +): + online_calibs = mps.read_online_calibration(online_calibs_file.as_posix()) + online_imu_calibs = {} + num_error = int(num_error) + for calib in tqdm(online_calibs, desc="Reading online IMU calibration data"): + for imuCalib in calib.imu_calibs: + if imuCalib.get_label() == stream_label: + # calib timestamp in microseconds + # convert to nanoseconds and then quantize to milliseconds + timestamp = int(calib.tracking_timestamp.total_seconds() * 1e9) + quantized_timestamp = timestamp // num_error + online_imu_calibs[quantized_timestamp] = imuCalib + + return online_imu_calibs + + +def get_online_imu_data_from_vrs( + vrs_file: Path, + mps_folder: Path, +): + vrs_provider = data_provider.create_vrs_data_provider(vrs_file.as_posix()) + imu_timestamps = sorted( + vrs_provider.get_timestamps_ns( + IMU_STREAM_ID, + TimeDomain.DEVICE_TIME + ) + ) + imu_stream_label = vrs_provider.get_label_from_stream_id(IMU_STREAM_ID) + + online_calibs_file = mps_folder / "slam" / "online_calibration.jsonl" + online_imu_calibs = get_online_params_for_imu_from_mps( + online_calibs_file, + imu_stream_label + ) + + acceptable_diff_ms = 5 # 5 milliseconds + + calib_timestamps = sorted(online_imu_calibs.keys()) + + ms = pycolmap.ImuMeasurements() + for timestamp in tqdm(imu_timestamps, desc="Loading rect IMU data"): + quantized_timestamp = timestamp // int(1e6) + closest_ts = find_closest_timestamp( + calib_timestamps, + quantized_timestamp, + acceptable_diff_ms + ) + + if closest_ts not in online_imu_calibs: + raise ValueError(f"No calibration found for timestamp {timestamp}") + + calibration = online_imu_calibs[closest_ts] + imu_data = vrs_provider.get_imu_data_by_time_ns( + IMU_STREAM_ID, + timestamp, + TimeDomain.DEVICE_TIME, + TimeQueryOptions.CLOSEST, + ) + if imu_data.accel_valid and imu_data.gyro_valid: + rectified_acc = calibration.raw_to_rectified_accel( + imu_data.accel_msec2 + ) + rectified_gyro = calibration.raw_to_rectified_gyro( + imu_data.gyro_radsec + ) + ts = float(timestamp) / 1e9 # convert to seconds + ms.insert( + pycolmap.ImuMeasurement(ts, rectified_acc, rectified_gyro) + ) + + return ms \ No newline at end of file From decff5935cbf7d110ea0ef24d15c5a63a4114570 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 14:30:54 +0200 Subject: [PATCH 062/665] general utils --- lamaria/utils/general.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 6355a98..6a6aef8 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -29,7 +29,7 @@ def find_closest_timestamp( timestamps: list, target_ts: int, - max_diff=1e6 # 1 ms in nanoseconds + max_diff: float, ) -> int | None: """Timestamps must be in nano seconds""" @@ -54,7 +54,7 @@ def find_closest_timestamp( def get_matched_timestamps( left_timestamps: list, right_timestamps: list, - acceptable_diff=1e6 # 1 ms in nanoseconds + max_diff: float, ) -> list[tuple[int, int]]: matched_timestamps = [] @@ -64,13 +64,13 @@ def get_matched_timestamps( if len(left_timestamps) < len(right_timestamps): for lts in left_timestamps: - closest_rts = find_closest_timestamp(right_timestamps, lts) - if abs(lts - closest_rts) < acceptable_diff: + closest_rts = find_closest_timestamp(right_timestamps, lts, max_diff) + if abs(lts - closest_rts) < max_diff: matched_timestamps.append((lts, closest_rts)) else: for rts in right_timestamps: - closest_lts = find_closest_timestamp(left_timestamps, rts) - if abs(rts - closest_lts) < acceptable_diff: + closest_lts = find_closest_timestamp(left_timestamps, rts, max_diff) + if abs(rts - closest_lts) < max_diff: matched_timestamps.append((closest_lts, rts)) return matched_timestamps From dcf44e449262662e014215dbd78eae25532757be Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 14:54:56 +0200 Subject: [PATCH 063/665] kf se --- lamaria/rig/keyframing/keyframe_selection.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 2373ce8..f3cd1ca 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -13,7 +13,7 @@ from ..config.loaders import load_cfg from ...utils.general import get_magnitude_from_transform -@dataclass +@dataclass(frozen=True) class KFParams: max_rotation_deg: float max_distance_m: float From 8a28510bd1249c4afd2404ba1818fba05e43c79d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 16:42:10 +0200 Subject: [PATCH 064/665] PARAMS --- lamaria/rig/optim/params.py | 75 +++++++++++++++++++++++++++++++++++++ 1 file changed, 75 insertions(+) create mode 100644 lamaria/rig/optim/params.py diff --git a/lamaria/rig/optim/params.py b/lamaria/rig/optim/params.py new file mode 100644 index 0000000..93ce42a --- /dev/null +++ b/lamaria/rig/optim/params.py @@ -0,0 +1,75 @@ + + +from dataclasses import dataclass + +@dataclass(frozen=True) +class CamParams: + feature_std: float = 1.0 # in pixels + optimize_cam_intrinsics: bool = False + optimize_cam_from_rig: bool = False + + @classmethod + def from_cfg(cls, cfg) -> "CamParams": + """ + Accepts the full OmegaConf cfg and returns camera parameters. + """ + opt = getattr(cfg, "optimization", cfg) + + return cls( + feature_std=float(opt.feature_std), + optimize_cam_intrinsics=bool(opt.optimize_cam_intrinsics), + optimize_cam_from_rig=bool(opt.optimize_cam_from_rig), + ) + + +@dataclass(frozen=True) +class IMUParams: + gyro_infl: float = 1.0 + acc_infl: float = 1.0 + integration_noise_density: float = 0.05 + + optimize_scale: bool = False + optimize_gravity: bool = False + optimize_imu_from_rig: bool = False + optimize_bias: bool = False + keep_imu_residuals: bool = True + + @classmethod + def from_cfg(cls, cfg) -> "IMUParams": + """ + Accepts the full OmegaConf cfg and returns IMU parameters. + """ + opt = getattr(cfg, "optimization", cfg) + + return cls( + gyro_infl=float(opt.imu_inflation_factor_gyro), + acc_infl=float(opt.imu_inflation_factor_acc), + integration_noise_density=float(opt.integration_noise_density), + optimize_scale=bool(opt.optimize_scale), + optimize_gravity=bool(opt.optimize_gravity), + optimize_imu_from_rig=bool(opt.optimize_imu_from_rig), + optimize_bias=bool(opt.optimize_bias), + keep_imu_residuals=bool(opt.keep_imu_residuals), + ) + + +@dataclass(frozen=True) +class OptParams: + use_callback: bool = True + max_num_iterations: int = 10 + normalize_reconstruction: bool = False + use_device_calibration: bool = True + + @classmethod + def from_cfg(cls, cfg) -> "OptParams": + """ + Accepts the full OmegaConf cfg and returns optimization parameters. + """ + opt = getattr(cfg, "optimization", cfg) + + return cls( + use_callback=bool(opt.use_callback), + max_num_iterations=int(opt.max_num_iterations), + normalize_reconstruction=bool(opt.normalize_reconstruction), + use_device_calibration=bool(opt.use_device_calibration), + ) \ No newline at end of file From 1394978572b9b6f86ddc89fa1f65d521069d1dce Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 16:46:49 +0200 Subject: [PATCH 065/665] session --- lamaria/rig/optim/session.py | 55 ++++++++++++++++++++++++++++++++++++ 1 file changed, 55 insertions(+) create mode 100644 lamaria/rig/optim/session.py diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py new file mode 100644 index 0000000..4c708d5 --- /dev/null +++ b/lamaria/rig/optim/session.py @@ -0,0 +1,55 @@ +from __future__ import annotations + + +from typing import List, Tuple +from pathlib import Path +import numpy as np +import pycolmap + + +from ... import logger +from ..config.loaders import load_cfg +from .imu import ( + load_imu_states, + load_preintegrated_imu_measurements, +) +from .params import ( + CamParams, + OptParams, + IMUParams +) + +class SingleSeqSession: + def __init__( + self, + reconstruction: pycolmap.Reconstruction, + timestamps: List[int], + rect_imu_data_npy: Path = None, + cfg=None + ): + cfg = cfg if cfg is not None else load_cfg() + self.reconstruction = reconstruction + self.timestamps = timestamps + self._init_params(cfg) + self._init_imu_data(rect_imu_data_npy) + + + def _init_imu_data(self, rect_imu_data_npy: Path): + self.preintegrated_imu_measurements = \ + load_preintegrated_imu_measurements( + rect_imu_data_npy, + self.reconstruction, + self.timestamps, + self.imu_params + ) + self.imu_states = load_imu_states( + self.reconstruction, + self.timestamps + ) + + def _init_params(self, cfg): + self.cam_params = CamParams.from_cfg(cfg) + self.imu_params = IMUParams.from_cfg(cfg) + self.opt_params = OptParams.from_cfg(cfg) + + From b46baa42dc3b1f21931ba5fdfb368c3b42b31a5f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 16:48:07 +0200 Subject: [PATCH 066/665] session --- lamaria/rig/optim/session.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py index 4c708d5..91f02f0 100644 --- a/lamaria/rig/optim/session.py +++ b/lamaria/rig/optim/session.py @@ -7,7 +7,6 @@ import pycolmap -from ... import logger from ..config.loaders import load_cfg from .imu import ( load_imu_states, From 14f76489fc0cc5eb6b5eb3fac091f8e56241b41a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 16:49:46 +0200 Subject: [PATCH 067/665] imu params in imu scriopt --- lamaria/rig/optim/imu.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index ed360ee..840e091 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -5,14 +5,14 @@ from tqdm import tqdm +from .params import IMUParams + def load_preintegrated_imu_measurements( rect_imu_data_npy: Path, reconstruction: pycolmap.Reconstruction, timestamps: List[int], # must be a sorted list in ns - gyro_infl: float = 1.0, - acc_infl: float = 1.0, - integration_noise_density: float = 1.0 + params: IMUParams = IMUParams(), ) -> dict[int, pycolmap.PreintegratedImuMeasurement]: preintegrated_measurements = {} @@ -20,8 +20,8 @@ def load_preintegrated_imu_measurements( imu_measurements = pycolmap.ImuMeasurements(rect_imu_data.tolist()) options = pycolmap.ImuPreintegrationOptions() - options.integration_noise_density = integration_noise_density - imu_calib = load_imu_calibration(gyro_infl, acc_infl) + options.integration_noise_density = params.integration_noise_density + imu_calib = load_imu_calibration(params.gyro_infl, params.acc_infl) frame_ids = sorted(reconstruction.frames.keys()) assert len(timestamps) == len(frame_ids), "Unequal timestamps and frames for preinteg calc" From dcc7617f694890cea9ece51178604e409073e026 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 16:50:07 +0200 Subject: [PATCH 068/665] update defs --- lamaria/rig/config/defaults.yaml | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index e823d76..97c2dcb 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -12,7 +12,6 @@ streams: imu_right_stream_id: 1202-1 flags: - use_device_calibration: true mps_fail: false has_slam_drops: false # check inside vrs.json file @@ -45,9 +44,7 @@ optimization: use_callback: true max_num_iterations: 10 normalize_reconstruction: false - use_factory_cam_intrinsics: true - use_factory_cam_extrinsics: true - use_factory_imu: true + use_device_calibration: false optimize_cam_intrinsics: false optimize_cam_from_rig: false optimize_scale: false From cb21307cfa51ee47654b21660855c47989556380 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 16:52:14 +0200 Subject: [PATCH 069/665] update --- lamaria/rig/keyframing/vrs_to_colmap.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py index 6bcc85b..64776a5 100644 --- a/lamaria/rig/keyframing/vrs_to_colmap.py +++ b/lamaria/rig/keyframing/vrs_to_colmap.py @@ -65,7 +65,7 @@ def _build_per_frame_data(self, images, timestamps, mps_poses) -> List[PerFrameD self.imu_stream_id ) - if self.cfg.flags.use_device_calibration: + if self.cfg.optimization.use_device_calibration: device_calibration = self.vrs_provider.get_device_calibration() imu_calib = device_calibration.get_imu_calib( imu_stream_label @@ -77,7 +77,7 @@ def _build_per_frame_data(self, images, timestamps, mps_poses) -> List[PerFrameD if t_world_device is None: continue - if not self.cfg.flags.use_device_calibration: + if not self.cfg.optimization.use_device_calibration: ocalib = self.mps_data_provider.get_online_calibration( left_ts, TimeQueryOptions.CLOSEST ) From c2e9f2ab3362b783c5295819097d40cf425c9c6e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 16:53:26 +0200 Subject: [PATCH 070/665] vrs --- lamaria/rig/keyframing/vrs_to_colmap.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py index 64776a5..fc05e58 100644 --- a/lamaria/rig/keyframing/vrs_to_colmap.py +++ b/lamaria/rig/keyframing/vrs_to_colmap.py @@ -329,7 +329,7 @@ def _add_online_frames(self) -> None: self.empty_recons.add_image(im) def create(self) -> pycolmap.Reconstruction: - if self.cfg.flags.use_device_calibration: + if self.cfg.optimization.use_device_calibration: self._add_device_sensors() self._add_device_frames() else: From ba15d287376cbac5c9e0017bd0b989b6c6b0625e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 22:17:38 +0200 Subject: [PATCH 071/665] bundle adjuster --- lamaria/rig/optim/bundle_adjuster.py | 182 +++++++++++++++++++++++++++ 1 file changed, 182 insertions(+) create mode 100644 lamaria/rig/optim/bundle_adjuster.py diff --git a/lamaria/rig/optim/bundle_adjuster.py b/lamaria/rig/optim/bundle_adjuster.py new file mode 100644 index 0000000..ec0c172 --- /dev/null +++ b/lamaria/rig/optim/bundle_adjuster.py @@ -0,0 +1,182 @@ +import numpy as np +import pyceres +import pycolmap +import pycolmap.cost_functions +from tqdm import tqdm + +from ... import logger +from .session import SingleSeqSession + + +class BundleAdjuster: + def __init__( + self, + options: pycolmap.BundleAdjustmentOptions, + config: pycolmap.BundleAdjustmentConfig, + ): + self.options = options + self.config = config + self.problem = pyceres.Problem() + self.summary = pyceres.SolverSummary() + self.camera_ids = set() + self.point3D_num_observations = dict() + logger.info("BundleAdjuster initialized") + + def solve(self, reconstruction: pycolmap.Reconstruction): + loss = self.options.create_loss_function() + self.set_up_problem(reconstruction, loss) + if self.problem.num_residuals() == 0: + return False + solver_options = self.set_up_solver_options( + self.problem, self.options.solver_options + ) + pyceres.solve(solver_options, self.problem, self.summary) + return True + + def set_up_problem( + self, + session: SingleSeqSession, + loss: pyceres.LossFunction, + ): + logger.info("Setting up problem") + assert session.reconstruction is not None + for image_id in tqdm(self.config.image_ids): + self.add_image_to_problem(session, image_id, loss) + self.parameterize_cameras(session.reconstruction) + self.parameterize_points(session.reconstruction) + logger.info("Problem set up") + return self.problem + + def set_up_solver_options( + self, problem: pyceres.Problem, solver_options: pyceres.SolverOptions + ): + bundle_adjuster = pycolmap.BundleAdjuster(self.options, self.config) + return bundle_adjuster.set_up_solver_options(problem, solver_options) + + def add_image_to_problem( + self, + session: SingleSeqSession, + image_id: int, + loss: pyceres.LossFunction, + ): + image = session.reconstruction.images[image_id] + frame = session.reconstruction.frames[image.frame_id] + rig = session.reconstruction.rigs[frame.rig_id] + camera = session.recon.cameras[image.camera_id] + rig_from_world = frame.rig_from_world + + cam_from_rig = None + for sensor, sensor_from_rig in rig.sensors.items(): + if image.camera_id == sensor.id: + cam_from_rig = sensor_from_rig + + optimize_cam_from_rig = session.cam_params.optimize_cam_from_rig + optimize_cam_intrinsics = session.cam_params.optimize_cam_intrinsics + feature_std = session.cam_params.feature_std + + num_observations = 0 + for point2D in image.points2D: + if not point2D.has_point3D(): + continue + num_observations += 1 + if point2D.point3D_id not in self.point3D_num_observations: + self.point3D_num_observations[point2D.point3D_id] = 0 + self.point3D_num_observations[point2D.point3D_id] += 1 + + point3D = session.recon.points3D[point2D.point3D_id] + assert point3D.track.length() > 1 + if not optimize_cam_from_rig: + cost = pycolmap.cost_functions.RigReprojErrorCost( + camera.model, + np.eye(2) * pow(feature_std, 2), + point2D.xy, + cam_from_rig, + ) + self.problem.add_residual_block( + cost, + loss, + [ + rig_from_world.rotation.quat, + rig_from_world.translation, + point3D.xyz, + camera.params, + ], + ) + if not optimize_cam_intrinsics: + # do not optimise camera parameters + self.problem.set_parameter_block_constant(camera.params) + else: + cost = pycolmap.cost_functions.RigReprojErrorCost( + camera.model, + np.eye(2) * pow(feature_std, 2), + point2D.xy + ) + self.problem.add_residual_block( + cost, + loss, + [ + cam_from_rig.rotation.quat, + cam_from_rig.translation, + rig_from_world.rotation.quat, + rig_from_world.translation, + point3D.xyz, + camera.params, + ], + ) + if not optimize_cam_intrinsics: + # do not optimise camera parameters + self.problem.set_parameter_block_constant(camera.params) + + if num_observations > 0: + self.camera_ids.add(image.camera_id) + # Set pose parameterization + self.problem.set_manifold( + rig_from_world.rotation.quat, + pyceres.EigenQuaternionManifold(), + ) + + if optimize_cam_from_rig: + self.problem.set_manifold( + cam_from_rig.rotation.quat, + pyceres.EigenQuaternionManifold(), + ) + + def parameterize_cameras(self, reconstruction: pycolmap.Reconstruction): + constant_camera = ( + (not self.options.refine_focal_length) + and (not self.options.refine_principal_point) + and (not self.options.refine_extra_params) + ) + for camera_id in self.camera_ids: + camera = reconstruction.cameras[camera_id] + if constant_camera or self.config.has_constant_cam_intrinsics( + camera_id + ): + self.problem.set_parameter_block_constant(camera.params) + continue + const_camera_params = [] + if not self.options.refine_focal_length: + const_camera_params.extend(camera.focal_length_idxs()) + if not self.options.refine_principal_point: + const_camera_params.extend(camera.principal_point_idxs()) + if not self.options.refine_extra_params: + const_camera_params.extend(camera.extra_point_idxs()) + if len(const_camera_params) > 0: + self.problem.set_manifold( + camera.params, + pyceres.SubsetManifold( + len(camera.params), const_camera_params + ), + ) + + def parameterize_points(self, reconstruction: pycolmap.Reconstruction): + for ( + point3D_id, + num_observations, + ) in self.point3D_num_observations.items(): + point3D = reconstruction.points3D[point3D_id] + if point3D.track.length() > num_observations: + self.problem.set_parameter_block_constant(point3D.xyz) + for point3D_id in self.config.constant_point3D_ids: + point3D = reconstruction.points3D[point3D_id] + self.problem.set_parameter_block_constant(point3D.xyz) From 063400936a7f5ab9da9d37362c4fcb8b241e6a04 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 22:18:24 +0200 Subject: [PATCH 072/665] session --- lamaria/rig/optim/session.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py index 91f02f0..6a3c479 100644 --- a/lamaria/rig/optim/session.py +++ b/lamaria/rig/optim/session.py @@ -27,12 +27,11 @@ def __init__( cfg=None ): cfg = cfg if cfg is not None else load_cfg() - self.reconstruction = reconstruction - self.timestamps = timestamps + self.reconstruction: pycolmap.Reconstruction = reconstruction + self.timestamps: List[int] = timestamps self._init_params(cfg) self._init_imu_data(rect_imu_data_npy) - def _init_imu_data(self, rect_imu_data_npy: Path): self.preintegrated_imu_measurements = \ load_preintegrated_imu_measurements( From 0800b2f2e245a445a90bb0d890e7eb87acfb4b2f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 22:18:40 +0200 Subject: [PATCH 073/665] s --- lamaria/rig/optim/session.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py index 6a3c479..c7ec3d6 100644 --- a/lamaria/rig/optim/session.py +++ b/lamaria/rig/optim/session.py @@ -23,7 +23,7 @@ def __init__( self, reconstruction: pycolmap.Reconstruction, timestamps: List[int], - rect_imu_data_npy: Path = None, + rect_imu_data_npy: Path, cfg=None ): cfg = cfg if cfg is not None else load_cfg() From 538b43ad8ac45945fbbc74b75e037063c2c2d484 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 22:19:23 +0200 Subject: [PATCH 074/665] ss --- lamaria/rig/optim/session.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py index c7ec3d6..1493fc2 100644 --- a/lamaria/rig/optim/session.py +++ b/lamaria/rig/optim/session.py @@ -1,9 +1,7 @@ from __future__ import annotations - -from typing import List, Tuple +from typing import List from pathlib import Path -import numpy as np import pycolmap From cacd01b73174967dba32e52f28e4358295b4310b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 22:20:21 +0200 Subject: [PATCH 075/665] lalala --- lamaria/rig/optim/bundle_adjuster.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/optim/bundle_adjuster.py b/lamaria/rig/optim/bundle_adjuster.py index ec0c172..19f96bd 100644 --- a/lamaria/rig/optim/bundle_adjuster.py +++ b/lamaria/rig/optim/bundle_adjuster.py @@ -38,13 +38,13 @@ def set_up_problem( session: SingleSeqSession, loss: pyceres.LossFunction, ): - logger.info("Setting up problem") + logger.info("Setting up optimization problem") assert session.reconstruction is not None for image_id in tqdm(self.config.image_ids): self.add_image_to_problem(session, image_id, loss) self.parameterize_cameras(session.reconstruction) self.parameterize_points(session.reconstruction) - logger.info("Problem set up") + logger.info("Optimization problem set up") return self.problem def set_up_solver_options( From 34a2d21dfb0d0959fbc4f4a038d9d615f9c351a5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 22:21:28 +0200 Subject: [PATCH 076/665] k --- lamaria/rig/keyframing/__init__.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 lamaria/rig/keyframing/__init__.py diff --git a/lamaria/rig/keyframing/__init__.py b/lamaria/rig/keyframing/__init__.py deleted file mode 100644 index e69de29..0000000 From beb8ad8cf96e0ea734e6da0c8c3ac48d8dcc3584 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 16 Sep 2025 22:22:11 +0200 Subject: [PATCH 077/665] a --- lamaria/rig/optim/params.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/lamaria/rig/optim/params.py b/lamaria/rig/optim/params.py index 93ce42a..4136ea6 100644 --- a/lamaria/rig/optim/params.py +++ b/lamaria/rig/optim/params.py @@ -1,5 +1,3 @@ - - from dataclasses import dataclass @dataclass(frozen=True) From ada1d230c0beda3c8e0dea1964eb6d989f8e86c4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 11:31:38 +0200 Subject: [PATCH 078/665] imu residual manager --- lamaria/rig/optim/imu.py | 70 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 70 insertions(+) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index 840e091..a7e7aa0 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -1,11 +1,14 @@ import numpy as np import pycolmap +import pyceres from typing import List from pathlib import Path from tqdm import tqdm +from ... import logger from .params import IMUParams +from .session import SingleSeqSession def load_preintegrated_imu_measurements( @@ -115,3 +118,70 @@ def load_imu_calibration( imu_calib.imu_rate = 1000.0 return imu_calib + + +class IMUResidualManager: + """Handles IMU residual setup and constraints""" + def __init__(self, session: SingleSeqSession): + self.session = session + + def add_residuals(self, problem): + """Add IMU residuals to the optimization problem""" + loss = pyceres.TrivialLoss() + + frame_ids = sorted(self.session.preintegrated_imu_measurements.keys()) + + for k in range(len(self.session.preintegrated_imu_measurements)): + i = frame_ids[k] + j = frame_ids[k + 1] + frame_i = self.session.reconstruction.frames[i] + frame_j = self.session.reconstruction.frames[j] + i_from_world = frame_i.rig_from_world + j_from_world = frame_j.rig_from_world + + integrated_m = self.session.preintegrated_imu_measurements[i] + + problem.add_residual_block( + pycolmap.PreintegratedImuMeasurementCost(integrated_m), + loss, + [ + self.session.imu_from_rig.rotation.quat, + self.session.imu_from_rig.translation, + self.session.log_scale, + self.session.gravity, + i_from_world.rotation.quat, + i_from_world.translation, + self.session.imu_states[i].data, + j_from_world.rotation.quat, + j_from_world.translation, + self.session.imu_states[j].data, + ], + ) + + self._setup_manifolds_and_constraints(problem) + logger.info("Added IMU residuals to the problem") + return problem + + def _setup_manifolds_and_constraints(self, problem): + """Setup manifolds and parameter constraints""" + problem.set_manifold(self.session.gravity, pyceres.SphereManifold(3)) + problem.set_manifold( + self.session.imu_from_rig.rotation.quat, + pyceres.EigenQuaternionManifold() + ) + + # Apply optimization constraints based on configuration + if not self.session.imu_params.optimize_scale: + problem.set_parameter_block_constant(self.session.log_scale) + if not self.session.imu_params.optimize_gravity: + problem.set_parameter_block_constant(self.session.gravity) + if not self.session.imu_params.optimize_imu_from_rig: + problem.set_parameter_block_constant(self.session.imu_from_rig.rotation.quat) + problem.set_parameter_block_constant(self.session.imu_from_rig.translation) + if not self.session.imu_params.optimize_bias: + constant_idxs = np.arange(3, 9) + for frame_id in self.session.imu_states.keys(): + problem.set_manifold( + self.session.imu_states[frame_id].data, + pyceres.SubsetManifold(9, constant_idxs), + ) \ No newline at end of file From 295ace1306aa0534fb828738a1ea4185876afe58 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 11:32:12 +0200 Subject: [PATCH 079/665] sess --- lamaria/rig/optim/session.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py index 1493fc2..d7aae3d 100644 --- a/lamaria/rig/optim/session.py +++ b/lamaria/rig/optim/session.py @@ -3,7 +3,7 @@ from typing import List from pathlib import Path import pycolmap - +import numpy as np from ..config.loaders import load_cfg from .imu import ( @@ -42,6 +42,9 @@ def _init_imu_data(self, rect_imu_data_npy: Path): self.reconstruction, self.timestamps ) + self.imu_from_rig = pycolmap.Rigid3d() + self.gravity = np.array([0.0, 0.0, -1.0]) + self.log_scale = np.array([0.0]) def _init_params(self, cfg): self.cam_params = CamParams.from_cfg(cfg) From 72071ee2cf4f7b6b068ec6eff01dcb9bd0be5a21 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 13:56:56 +0200 Subject: [PATCH 080/665] mv imu res --- lamaria/rig/optim/imu.py | 69 +--------------------------------------- 1 file changed, 1 insertion(+), 68 deletions(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index a7e7aa0..32f1e59 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -117,71 +117,4 @@ def load_imu_calibration( imu_calib.gyro_saturation_max = 1000.0 * (np.pi / 180.0) imu_calib.imu_rate = 1000.0 - return imu_calib - - -class IMUResidualManager: - """Handles IMU residual setup and constraints""" - def __init__(self, session: SingleSeqSession): - self.session = session - - def add_residuals(self, problem): - """Add IMU residuals to the optimization problem""" - loss = pyceres.TrivialLoss() - - frame_ids = sorted(self.session.preintegrated_imu_measurements.keys()) - - for k in range(len(self.session.preintegrated_imu_measurements)): - i = frame_ids[k] - j = frame_ids[k + 1] - frame_i = self.session.reconstruction.frames[i] - frame_j = self.session.reconstruction.frames[j] - i_from_world = frame_i.rig_from_world - j_from_world = frame_j.rig_from_world - - integrated_m = self.session.preintegrated_imu_measurements[i] - - problem.add_residual_block( - pycolmap.PreintegratedImuMeasurementCost(integrated_m), - loss, - [ - self.session.imu_from_rig.rotation.quat, - self.session.imu_from_rig.translation, - self.session.log_scale, - self.session.gravity, - i_from_world.rotation.quat, - i_from_world.translation, - self.session.imu_states[i].data, - j_from_world.rotation.quat, - j_from_world.translation, - self.session.imu_states[j].data, - ], - ) - - self._setup_manifolds_and_constraints(problem) - logger.info("Added IMU residuals to the problem") - return problem - - def _setup_manifolds_and_constraints(self, problem): - """Setup manifolds and parameter constraints""" - problem.set_manifold(self.session.gravity, pyceres.SphereManifold(3)) - problem.set_manifold( - self.session.imu_from_rig.rotation.quat, - pyceres.EigenQuaternionManifold() - ) - - # Apply optimization constraints based on configuration - if not self.session.imu_params.optimize_scale: - problem.set_parameter_block_constant(self.session.log_scale) - if not self.session.imu_params.optimize_gravity: - problem.set_parameter_block_constant(self.session.gravity) - if not self.session.imu_params.optimize_imu_from_rig: - problem.set_parameter_block_constant(self.session.imu_from_rig.rotation.quat) - problem.set_parameter_block_constant(self.session.imu_from_rig.translation) - if not self.session.imu_params.optimize_bias: - constant_idxs = np.arange(3, 9) - for frame_id in self.session.imu_states.keys(): - problem.set_manifold( - self.session.imu_states[frame_id].data, - pyceres.SubsetManifold(9, constant_idxs), - ) \ No newline at end of file + return imu_calib \ No newline at end of file From eb0d03b0bcaac229eaff2f436a32174cd4bb3623 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 13:57:14 +0200 Subject: [PATCH 081/665] aaa --- lamaria/rig/optim/iterative_global_ba.py | 182 ++++++++++++++++++ ...bundle_adjuster.py => residual_manager.py} | 114 ++++++++++- 2 files changed, 295 insertions(+), 1 deletion(-) create mode 100644 lamaria/rig/optim/iterative_global_ba.py rename lamaria/rig/optim/{bundle_adjuster.py => residual_manager.py} (59%) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py new file mode 100644 index 0000000..e8dca8b --- /dev/null +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -0,0 +1,182 @@ +import pycolmap +import pyceres +import numpy as np +from ... import logger +from .session import SingleSeqSession +from .residual_manager import RefinementCallback, ImageResidualManager, IMUResidualManager + + +class RigConstraintManager: + """Handles rig-specific constraints and problem setup""" + + def __init__(self, session: SingleSeqSession): + self.session = session + + def apply_constraints(self, problem): + """Apply rig-specific constraints to the problem""" + # Fix the first rig pose + frame_ids = sorted(self.session.reconstruction.frames.keys()) + first_frame = self.session.reconstruction.frames[frame_ids[0]] + problem.set_parameter_block_constant(first_frame.rotation.quat) + problem.set_parameter_block_constant(first_frame.translation) + + # Fix 1 DoF translation of the second rig + second_frame = self.session.reconstruction.frames[frame_ids[1]] + problem.set_manifold( + second_frame.translation, + pyceres.SubsetManifold(3, np.array([0])), + ) + return problem + + +class VIBundleAdjuster: + """Visual-Inertial Bundle Adjuster that combines visual and IMU residuals""" + + def __init__(self, session: SingleSeqSession): + self.session = session + + def _init_callback(self): + frame_ids = sorted(self.session.reconstruction.frames.keys()) + poses = list(self.session.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) + callback = RefinementCallback(poses) + + return callback + + def solve(self, ba_options, ba_config): + """Solve VI bundle adjustment problem""" + bundle_adjuster = ImageResidualManager(ba_options, ba_config) + imu_manager = IMUResidualManager(self.session) + + bundle_adjuster.set_up_problem( + self.session, + ba_options.create_loss_function(), + ) + + solver_options = bundle_adjuster.set_up_solver_options( + bundle_adjuster.problem, ba_options.solver_options + ) + problem = bundle_adjuster.problem + + # Add IMU residuals if enabled + if self.session.imu_params.keep_imu_residuals: + problem = imu_manager.add_residuals(problem) + + # Apply rig constraints + constraint_manager = RigConstraintManager(self.session) + problem = constraint_manager.apply_constraints(problem) + logger.info("Constrained the rig problem") + + # Setup solver + if self.session.opt_params.use_callback: + callback = self._init_callback() + solver_options.callbacks = [callback] + + solver_options.minimizer_progress_to_stdout = True + solver_options.update_state_every_iteration = True + solver_options.max_num_iterations = self.session.opt_params.max_num_iterations + + # Solve + summary = pyceres.SolverSummary() + pyceres.solve(solver_options, problem, summary) + print(summary.BriefReport()) + + return summary, problem + + + +class GlobalBundleAdjustment: + """Strategy for global bundle adjustment with VI integration""" + + def __init__(self, session: SingleSeqSession): + self.session = session + + def adjust(self, mapper, pipeline_options): + """Perform global bundle adjustment""" + reconstruction = mapper.reconstruction + assert reconstruction is not None + + reg_image_ids = reconstruction.reg_image_ids() + if len(reg_image_ids) < 2: + logger.warning("At least two images must be registered for global bundle-adjustment") + + ba_options = self._configure_ba_options(pipeline_options, len(reg_image_ids)) + + # Avoid degeneracies + mapper.observation_manager.filter_observations_with_negative_depth() + + # Configure bundle adjustment + ba_config = pycolmap.BundleAdjustmentConfig() + for image_id in reconstruction.reg_image_ids(): + ba_config.add_image(image_id) + + # Run bundle adjustment + vi_bundle_adjuster = VIBundleAdjuster(self.session) + _, _ = vi_bundle_adjuster.solve( + ba_options, + ba_config + ) + + def _configure_ba_options(self, pipeline_options, num_reg_images): + """Configure bundle adjustment options based on number of registered images""" + ba_options = pipeline_options.get_global_bundle_adjustment() + ba_options.print_summary = True + ba_options.refine_focal_length = True + ba_options.refine_extra_params = True + + # Use stricter convergence criteria for first registered images + if num_reg_images < 10: + ba_options.solver_options.function_tolerance /= 10 + ba_options.solver_options.gradient_tolerance /= 10 + ba_options.solver_options.parameter_tolerance /= 10 + ba_options.solver_options.max_num_iterations *= 2 + ba_options.solver_options.max_linear_solver_iterations = 200 + + return ba_options + + +class IterativeRefinement: + """Strategy for iterative global refinement""" + + def __init__(self, session: SingleSeqSession): + self.session = session + + def run(self, mapper, pipeline_options): + """Run iterative global refinement""" + reconstruction = mapper.reconstruction + + # Initial triangulation + tri_options = pipeline_options.get_triangulation() + mapper.complete_and_merge_tracks(tri_options) + num_retriangulated_observations = mapper.retriangulate(tri_options) + logger.info(1, f"=> Retriangulated observations: {num_retriangulated_observations}") + + # Configure mapper options + mapper_options = self._configure_mapper_options(pipeline_options) + global_ba_strategy = GlobalBundleAdjustment(self.session) + + # Iterative refinement + for i in range(pipeline_options.ba_global_max_refinements): + num_observations = reconstruction.compute_num_observations() + + global_ba_strategy.adjust( + mapper, + pipeline_options, + ) + + if self.session.opt_params.normalize_reconstruction: + reconstruction.normalize() + + # Check convergence + num_changed_observations = mapper.complete_and_merge_tracks(tri_options) + num_changed_observations += mapper.filter_points(mapper_options) + changed = (num_changed_observations / num_observations + if num_observations > 0 else 0) + + logger.info(1, f"=> Changed observations: {changed:.6f}") + if changed < pipeline_options.ba_global_max_refinement_change: + break + + def _configure_mapper_options(self, pipeline_options): + """Configure mapper options""" + mapper_options = pipeline_options.get_mapper() + return mapper_options \ No newline at end of file diff --git a/lamaria/rig/optim/bundle_adjuster.py b/lamaria/rig/optim/residual_manager.py similarity index 59% rename from lamaria/rig/optim/bundle_adjuster.py rename to lamaria/rig/optim/residual_manager.py index 19f96bd..1e4003d 100644 --- a/lamaria/rig/optim/bundle_adjuster.py +++ b/lamaria/rig/optim/residual_manager.py @@ -1,6 +1,8 @@ import numpy as np import pyceres import pycolmap +from copy import deepcopy +from typing import List, Tuple import pycolmap.cost_functions from tqdm import tqdm @@ -8,7 +10,75 @@ from .session import SingleSeqSession -class BundleAdjuster: +class IMUResidualManager: + """Handles IMU residual setup and constraints""" + def __init__(self, session: SingleSeqSession): + self.session = session + + def add_residuals(self, problem): + """Add IMU residuals to the optimization problem""" + loss = pyceres.TrivialLoss() + + frame_ids = sorted(self.session.preintegrated_imu_measurements.keys()) + + for k in range(len(self.session.preintegrated_imu_measurements)): + i = frame_ids[k] + j = frame_ids[k + 1] + frame_i = self.session.reconstruction.frames[i] + frame_j = self.session.reconstruction.frames[j] + i_from_world = frame_i.rig_from_world + j_from_world = frame_j.rig_from_world + + integrated_m = self.session.preintegrated_imu_measurements[i] + + problem.add_residual_block( + pycolmap.PreintegratedImuMeasurementCost(integrated_m), + loss, + [ + self.session.imu_from_rig.rotation.quat, + self.session.imu_from_rig.translation, + self.session.log_scale, + self.session.gravity, + i_from_world.rotation.quat, + i_from_world.translation, + self.session.imu_states[i].data, + j_from_world.rotation.quat, + j_from_world.translation, + self.session.imu_states[j].data, + ], + ) + + self._setup_manifolds_and_constraints(problem) + logger.info("Added IMU residuals to the problem") + return problem + + def _setup_manifolds_and_constraints(self, problem): + """Setup manifolds and parameter constraints""" + problem.set_manifold(self.session.gravity, pyceres.SphereManifold(3)) + problem.set_manifold( + self.session.imu_from_rig.rotation.quat, + pyceres.EigenQuaternionManifold() + ) + + # Apply optimization constraints based on configuration + if not self.session.imu_params.optimize_scale: + problem.set_parameter_block_constant(self.session.log_scale) + if not self.session.imu_params.optimize_gravity: + problem.set_parameter_block_constant(self.session.gravity) + if not self.session.imu_params.optimize_imu_from_rig: + problem.set_parameter_block_constant(self.session.imu_from_rig.rotation.quat) + problem.set_parameter_block_constant(self.session.imu_from_rig.translation) + if not self.session.imu_params.optimize_bias: + constant_idxs = np.arange(3, 9) + for frame_id in self.session.imu_states.keys(): + problem.set_manifold( + self.session.imu_states[frame_id].data, + pyceres.SubsetManifold(9, constant_idxs), + ) + + +class ImageResidualManager: + """Handles image residual setup and constraints""" def __init__( self, options: pycolmap.BundleAdjustmentOptions, @@ -180,3 +250,45 @@ def parameterize_points(self, reconstruction: pycolmap.Reconstruction): for point3D_id in self.config.constant_point3D_ids: point3D = reconstruction.points3D[point3D_id] self.problem.set_parameter_block_constant(point3D.xyz) + + +class RefinementCallback(pyceres.IterationCallback): + def __init__( + self, + poses: List[pycolmap.Rigid3d], + min_pose_change: Tuple[float, float] = (0.001, 0.000001), + min_iterations: int = 2, + ): + pyceres.IterationCallback.__init__(self) + self.poses = poses + self.poses_previous = deepcopy(self.poses) + self.min_pose_change = min_pose_change + self.min_iterations = min_iterations + self.pose_changes = [] + + def __call__(self, summary: pyceres.IterationSummary): + if not summary.step_is_successful: + return pyceres.CallbackReturnType.SOLVER_CONTINUE + diff = [] + for pose_prev, pose in zip(self.poses_previous, self.poses): + pose_rel = pose_prev * pose.inverse() + q_rel, t_rel = pose_rel.rotation.quat, pose_rel.translation + dr = np.rad2deg( + np.abs(2 * np.arctan2(np.linalg.norm(q_rel[:-1]), q_rel[-1])) + ) + dt = np.linalg.norm(t_rel) + diff.append((dr, dt)) + diff = np.array(diff) + self.poses_previous = deepcopy(self.poses) + med, q99, max_ = np.quantile(diff, [0.5, 0.99, 1.0], axis=0) + logger.info( + f"{summary.iteration:d} Pose update: " + f"med/q99/max dR={med[0]:.3f}/{q99[0]:.3f}/{max_[0]:.3f} deg, " + f"dt={med[1] * 1e2:.3f}/{q99[1] * 1e2:.3f}/{max_[1] * 1e2:.3f} cm" + ) + self.pose_changes.append((med, q99, max_)) + if summary.iteration >= self.min_iterations and np.all( + q99 <= self.min_pose_change + ): + return pyceres.CallbackReturnType.SOLVER_TERMINATE_SUCCESSFULLY + return pyceres.CallbackReturnType.SOLVER_CONTINUE \ No newline at end of file From 8d55fd8e1a7816bd5753b3b3fe4d26b4ea8fd65b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 14:12:30 +0200 Subject: [PATCH 082/665] vi optimization --- lamaria/rig/optim/vi_optimization.py | 66 ++++++++++++++++++++++++++++ 1 file changed, 66 insertions(+) create mode 100644 lamaria/rig/optim/vi_optimization.py diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py new file mode 100644 index 0000000..fd158f5 --- /dev/null +++ b/lamaria/rig/optim/vi_optimization.py @@ -0,0 +1,66 @@ +import pycolmap +from pathlib import Path + +from ... import logger +from .session import SingleSeqSession +from .iterative_global_ba import IterativeRefinement + + +class VIOptimizer: + """Main Visual-Inertial Optimizer""" + + def __init__(self, session: SingleSeqSession): + self.session = session + + def optimize(self, database_path: str, output_folder: Path): + """Run the complete VI optimization pipeline""" + + # Setup mapper + mapper = self._setup_incremental_mapper(database_path) + pipeline_options = self._get_incremental_pipeline_options() + + # Run iterative refinement + refinement_strategy = IterativeRefinement(self.session) + refinement_strategy.run( + mapper, + pipeline_options, + ) + + # Save results + optimized_reconstruction = mapper.reconstruction + output_folder.mkdir(parents=True, exist_ok=True) + optimized_reconstruction.write(output_folder.as_posix()) + + return optimized_reconstruction + + def _setup_incremental_mapper(self, database_path: str): + """Setup the incremental mapper""" + database = pycolmap.Database.open(database_path) + image_names = [self.session.reconstruction.images[image_id].name + for image_id in self.session.reconstruction.reg_image_ids()] + database_cache = pycolmap.DatabaseCache.create( + database, 15, False, set(image_names) + ) + mapper = pycolmap.IncrementalMapper(database_cache) + mapper.begin_reconstruction(self.session.reconstruction) + return mapper + + def _get_incremental_pipeline_options(self): + """Get incremental pipeline options""" + pipeline_options = pycolmap.IncrementalPipelineOptions() + pipeline_options.fix_existing_images = False + return pipeline_options + + +# Factory function for easy integration with existing pipeline +def create_vi_optimizer(session: SingleSeqSession) -> VIOptimizer: + """Factory function to create VI optimizer""" + return VIOptimizer(session) + + +# Convenience function for direct usage +def run_vi_optimization(session: SingleSeqSession, database_path: str, + output_folder: Path = None): + """Run VI optimization with given session and database""" + optimizer = create_vi_optimizer(session) + return optimizer.optimize(database_path, output_folder) \ No newline at end of file From c61edc7eac8d857661087497283ce460826ae14a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 14:18:18 +0200 Subject: [PATCH 083/665] ordering --- lamaria/rig/optim/residual_manager.py | 44 +-------------------------- 1 file changed, 1 insertion(+), 43 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 1e4003d..a511a32 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -249,46 +249,4 @@ def parameterize_points(self, reconstruction: pycolmap.Reconstruction): self.problem.set_parameter_block_constant(point3D.xyz) for point3D_id in self.config.constant_point3D_ids: point3D = reconstruction.points3D[point3D_id] - self.problem.set_parameter_block_constant(point3D.xyz) - - -class RefinementCallback(pyceres.IterationCallback): - def __init__( - self, - poses: List[pycolmap.Rigid3d], - min_pose_change: Tuple[float, float] = (0.001, 0.000001), - min_iterations: int = 2, - ): - pyceres.IterationCallback.__init__(self) - self.poses = poses - self.poses_previous = deepcopy(self.poses) - self.min_pose_change = min_pose_change - self.min_iterations = min_iterations - self.pose_changes = [] - - def __call__(self, summary: pyceres.IterationSummary): - if not summary.step_is_successful: - return pyceres.CallbackReturnType.SOLVER_CONTINUE - diff = [] - for pose_prev, pose in zip(self.poses_previous, self.poses): - pose_rel = pose_prev * pose.inverse() - q_rel, t_rel = pose_rel.rotation.quat, pose_rel.translation - dr = np.rad2deg( - np.abs(2 * np.arctan2(np.linalg.norm(q_rel[:-1]), q_rel[-1])) - ) - dt = np.linalg.norm(t_rel) - diff.append((dr, dt)) - diff = np.array(diff) - self.poses_previous = deepcopy(self.poses) - med, q99, max_ = np.quantile(diff, [0.5, 0.99, 1.0], axis=0) - logger.info( - f"{summary.iteration:d} Pose update: " - f"med/q99/max dR={med[0]:.3f}/{q99[0]:.3f}/{max_[0]:.3f} deg, " - f"dt={med[1] * 1e2:.3f}/{q99[1] * 1e2:.3f}/{max_[1] * 1e2:.3f} cm" - ) - self.pose_changes.append((med, q99, max_)) - if summary.iteration >= self.min_iterations and np.all( - q99 <= self.min_pose_change - ): - return pyceres.CallbackReturnType.SOLVER_TERMINATE_SUCCESSFULLY - return pyceres.CallbackReturnType.SOLVER_CONTINUE \ No newline at end of file + self.problem.set_parameter_block_constant(point3D.xyz) \ No newline at end of file From e5f38e0b14a40a2326f0705e6dff6472febd9602 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 14:18:33 +0200 Subject: [PATCH 084/665] callback --- lamaria/rig/optim/iterative_global_ba.py | 48 +++++++++++++++++++++++- 1 file changed, 46 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index e8dca8b..97677f7 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -1,9 +1,11 @@ import pycolmap import pyceres +from typing import List, Tuple +from copy import deepcopy import numpy as np from ... import logger from .session import SingleSeqSession -from .residual_manager import RefinementCallback, ImageResidualManager, IMUResidualManager +from .residual_manager import ImageResidualManager, IMUResidualManager class RigConstraintManager: @@ -179,4 +181,46 @@ def run(self, mapper, pipeline_options): def _configure_mapper_options(self, pipeline_options): """Configure mapper options""" mapper_options = pipeline_options.get_mapper() - return mapper_options \ No newline at end of file + return mapper_options + + +class RefinementCallback(pyceres.IterationCallback): + def __init__( + self, + poses: List[pycolmap.Rigid3d], + min_pose_change: Tuple[float, float] = (0.001, 0.000001), + min_iterations: int = 2, + ): + pyceres.IterationCallback.__init__(self) + self.poses = poses + self.poses_previous = deepcopy(self.poses) + self.min_pose_change = min_pose_change + self.min_iterations = min_iterations + self.pose_changes = [] + + def __call__(self, summary: pyceres.IterationSummary): + if not summary.step_is_successful: + return pyceres.CallbackReturnType.SOLVER_CONTINUE + diff = [] + for pose_prev, pose in zip(self.poses_previous, self.poses): + pose_rel = pose_prev * pose.inverse() + q_rel, t_rel = pose_rel.rotation.quat, pose_rel.translation + dr = np.rad2deg( + np.abs(2 * np.arctan2(np.linalg.norm(q_rel[:-1]), q_rel[-1])) + ) + dt = np.linalg.norm(t_rel) + diff.append((dr, dt)) + diff = np.array(diff) + self.poses_previous = deepcopy(self.poses) + med, q99, max_ = np.quantile(diff, [0.5, 0.99, 1.0], axis=0) + logger.info( + f"{summary.iteration:d} Pose update: " + f"med/q99/max dR={med[0]:.3f}/{q99[0]:.3f}/{max_[0]:.3f} deg, " + f"dt={med[1] * 1e2:.3f}/{q99[1] * 1e2:.3f}/{max_[1] * 1e2:.3f} cm" + ) + self.pose_changes.append((med, q99, max_)) + if summary.iteration >= self.min_iterations and np.all( + q99 <= self.min_pose_change + ): + return pyceres.CallbackReturnType.SOLVER_TERMINATE_SUCCESSFULLY + return pyceres.CallbackReturnType.SOLVER_CONTINUE \ No newline at end of file From fa2d20d62bec73b6355f10824b355c34dbe97a21 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 17:35:06 +0200 Subject: [PATCH 085/665] kf and res manager --- lamaria/rig/keyframing/keyframe_selection.py | 4 ++-- lamaria/rig/optim/residual_manager.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index f3cd1ca..0f2df2f 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -80,7 +80,7 @@ def _build_device_keyframed_reconstruction(self): self.keyframed_recons.add_camera(new_ref_sensor) new_rig.add_ref_sensor(new_ref_sensor.sensor_id) - for sensor, sensor_from_rig in old_rig.sensors.items(): + for sensor, sensor_from_rig in old_rig.non_ref_sensors.items(): new_sensor = self._clone_camera(sensor.id, camera_id) cam_map[sensor.id] = camera_id camera_id += 1 @@ -155,7 +155,7 @@ def _build_online_keyframed_reconstruction(self): new_rig = pycolmap.Rig(rig_id=rig_id) new_rig.add_ref_sensor(new_ref_sensor.sensor_id) - for old_sensor, sensor_from_rig in old_rig.sensors.items(): + for old_sensor, sensor_from_rig in old_rig.non_ref_sensors.items(): old_sensor_id = old_sensor.id if old_sensor_id not in cam_id_map: diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index a511a32..97d07c9 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -136,7 +136,7 @@ def add_image_to_problem( rig_from_world = frame.rig_from_world cam_from_rig = None - for sensor, sensor_from_rig in rig.sensors.items(): + for sensor, sensor_from_rig in rig.non_ref_sensors.items(): if image.camera_id == sensor.id: cam_from_rig = sensor_from_rig From 318aa3ac74408dd4a1227f1374f6d5ef3bbd7062 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 17 Sep 2025 17:35:47 +0200 Subject: [PATCH 086/665] na --- .../test_vrs_to_colmap.py => run_pipeline.py} | 16 +++++++--------- 1 file changed, 7 insertions(+), 9 deletions(-) rename scripts/{rig/test_vrs_to_colmap.py => run_pipeline.py} (80%) diff --git a/scripts/rig/test_vrs_to_colmap.py b/scripts/run_pipeline.py similarity index 80% rename from scripts/rig/test_vrs_to_colmap.py rename to scripts/run_pipeline.py index a6ee393..314e064 100644 --- a/scripts/rig/test_vrs_to_colmap.py +++ b/scripts/run_pipeline.py @@ -1,14 +1,13 @@ -# scripts/rig/test_vrs_to_colmap.py import sys import numpy as np -from pathlib import Path from lamaria.rig.config.loaders import load_cfg from lamaria.rig.keyframing.vrs_to_colmap import VrsToColmap from lamaria.rig.keyframing.image_extraction import run as run_extraction from lamaria.rig.keyframing.keyframe_selection import KeyframeSelector from lamaria.rig.optim.triangulation import run as run_triangulation -def main(): + +def run_pipeline(): cfg = load_cfg(cli_overrides=sys.argv[1:]) seq_builder = VrsToColmap(cfg) @@ -21,18 +20,17 @@ def main(): out_dir = cfg.result.output_folder_path / cfg.result.init_model out_dir.mkdir(parents=True, exist_ok=True) seq_builder.write_reconstruction(recon, out_dir) + seq_builder.write_full_timestamps(cfg.result.output_folder_path / cfg.result.full_ts) - seq_builder.write_full_timestamps(cfg.result.output_folder_path / "timestamps" /f"full.npy") - - timestamps = np.load(cfg.result.output_folder_path / "timestamps" /f"full.npy").tolist() + timestamps = np.load(cfg.result.output_folder_path / cfg.result.full_ts).tolist() kf_selector = KeyframeSelector(reconstruction=recon, timestamps=timestamps, cfg=cfg) kf_recon = kf_selector.run_keyframing() kf_selector.write_reconstruction(kf_recon, cfg.result.output_folder_path / cfg.result.kf_model) kf_selector.copy_images_to_keyframes_dir() - kf_selector.write_keyframe_timestamps(cfg.result.output_folder_path / "timestamps" / f"keyframe.npy") - _ = run_triangulation(cfg=cfg) + kf_selector.write_keyframe_timestamps(cfg.result.output_folder_path / cfg.result.kf_ts) + # _ = run_triangulation(cfg=cfg) if __name__ == "__main__": - main() + run_pipeline() From a7ba7d6992afa04aa0e0cb01651f8910bca55881 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 09:21:46 +0200 Subject: [PATCH 087/665] control point --- lamaria/utils/control_point.py | 211 +++++++++++++++++++++++++++++++++ 1 file changed, 211 insertions(+) create mode 100644 lamaria/utils/control_point.py diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py new file mode 100644 index 0000000..f8e3602 --- /dev/null +++ b/lamaria/utils/control_point.py @@ -0,0 +1,211 @@ +import json +import os + +import matplotlib.pyplot as plt +import numpy as np +import pycolmap +from tqdm import tqdm +from typing import Dict, List + +from .general import ( + get_image_names_to_ids, + CUSTOM_ORIGIN_COORDINATES, +) + + +def construct_control_points_from_json( + cp_json_file: str, +): + cp_data = json.load(open(cp_json_file, 'r')) + control_points = {} + for geo_id, data in cp_data["control_points"].items(): + tag_ids = data["tag_id"] + measurement = data["measurement"] + unc = data["uncertainty"] + + if measurement[2] == None: + assert unc[2] == None, "Uncertainty for z coordinate should be None if measurement is None" + measurement[2] = CUSTOM_ORIGIN_COORDINATES[2] + unc[2] = 1e9 # some large number + + translated_measurement = np.array(measurement) - np.array(CUSTOM_ORIGIN_COORDINATES) + # those without height will have 0 height and large uncertainty in z + + for tag_id in tag_ids: + control_points[tag_id] = { + "control_point": geo_id, + "topo": translated_measurement, + "covariance": np.diag(np.square(unc)) + } + + return control_points + + +def check_3d_error_bet_triang_and_topo(triangulated: List, topo: List): + """Calculate L2 error between triangulated and topo points + Args: + triangulated (list): list of triangulated points + topo (list): list of topocentric points + + Returns: + errors (list): list of L2 errors per point""" + errors = [] + for i in range(len(triangulated)): + errors.append(np.linalg.norm(triangulated[i] - topo[i])) + + return errors + + +def check_2d_error_bet_triang_and_topo(triangulated: List, topo: List): + """Calculate L2 error between triangulated and topo points + Args: + triangulated (list): list of 3d triangulated points + topo (list): list of 3d topocentric points + + Returns: + errors (list): list of 2d L2 errors per point""" + + errors = [] + for i in range(len(triangulated)): + errors.append(np.linalg.norm(triangulated[i][:2] - topo[i][:2])) + + return errors + + +def transform_points(points, r, t, scale): + transformed_points = [] + for point in points: + transformed_point = scale * r.apply(point) + t + transformed_points.append(transformed_point) + + return transformed_points + + +def transform_triangulated_control_points(control_points: Dict, r, t, scale): + for tag_id, cp in control_points.items(): + triangulated_point = cp["triangulated"] + triangulated_point = scale * r.apply(triangulated_point) + t + cp["triangulated"] = triangulated_point + + return control_points + + +def plot_ratio_of_inliers(control_points: Dict, save_folder: str): + tag_id_to_inlier_ratio = {} + for tag_id, cp in control_points.items(): + ratio = cp["inlier_ratio"] + tag_id_to_inlier_ratio[tag_id] = ratio + + sorted_tag_ids = sorted(tag_id_to_inlier_ratio.keys()) + sorted_ratios = [ + tag_id_to_inlier_ratio[tag_id] for tag_id in sorted_tag_ids + ] + + plt.bar(sorted_tag_ids, sorted_ratios, align="center") + plt.xticks(sorted_tag_ids, sorted_tag_ids, rotation=45) + plt.xlabel("Tag ID") + plt.ylabel("Inlier ratio") + plt.title("Inlier ratio for each tag after triangulation") + plt.savefig(os.path.join(save_folder, "inlier_ratio.png")) + plt.close() + + +def run_control_point_triangulation_from_json( + reconstruction_dir: str, + cp_json_file: str, + control_points: Dict, +): + rec = pycolmap.Reconstruction(reconstruction_dir) + + image_names_to_ids = get_image_names_to_ids(reconstruction_dir=reconstruction_dir) + + with open(cp_json_file, "r") as file: + data = json.load(file) + + image_data = data["images"] + control_point_data = data["control_points"] + + for tag_id, cp in tqdm( + control_points.items(), desc="Triangulating control points" + ): + geo_id = cp["control_point"] + images_observing_cp = control_point_data[geo_id]["image_names"] + + pixel_points = [] + cam_from_worlds = [] + cameras = [] + + image_ids_and_centers = [] + + for image_name in images_observing_cp: + if image_name not in image_names_to_ids: + continue + id = image_names_to_ids[image_name] + image = rec.images[id] + detection = image_data[image_name]["detection"] + pixel_points.append(detection) + cam_from_worlds.append(image.cam_from_world()) + cameras.append(rec.cameras[image.camera_id]) + image_ids_and_centers.append((id, detection)) + + # HANDLING THE CASE WHERE NO IMAGES OBSERVE THE CONTROL POINT + if pixel_points == []: + cp["triangulated"] = None + cp["inlier_ratio"] = 0 + cp["image_id_and_point2d"] = [] + continue + + pixel_points = np.array(pixel_points) + try: + output = pycolmap.estimate_triangulation( + pixel_points, + cam_from_worlds, + cameras, + options={ + "residual_type": "REPROJECTION_ERROR", + "ransac": {"max_error": 4.0}, + }, + ) + except Exception as e: + print( + f"Error in triangulating control point {geo_id}: {e}" + ) + output = None + + if output is None: + cp["triangulated"] = None + cp["inlier_ratio"] = 0 + cp["image_id_and_point2d"] = [] + continue + + control_points[tag_id]["triangulated"] = output["xyz"] + inliers = output["inliers"] + control_points[tag_id]["inlier_ratio"] = np.sum(inliers) / len(inliers) + image_ids_and_centers = [ + image_ids_and_centers[i] for i in range(len(inliers)) if inliers[i] + ] + control_points[tag_id]["image_id_and_point2d"] = image_ids_and_centers + + +def get_cps_for_initial_alignment(control_points: Dict): + triangulated_cp_alignment = [] + topo_cp_alignment = [] + for tag_id, cp in control_points.items(): + if cp["triangulated"] is None: + continue + + if cp["topo"][2] != 0: + print( + "Control point %s, %s has z != 0", tag_id, cp["control_point"] + ) + triangulated_cp_alignment.append(cp["triangulated"]) + topo_cp_alignment.append(cp["topo"]) + + if len(topo_cp_alignment) < 3: + print("Not enough control points with z != 0") + return None, None + + triangulated_cp_alignment = np.array(triangulated_cp_alignment) + topo_cp_alignment = np.array(topo_cp_alignment) + + return triangulated_cp_alignment, topo_cp_alignment From 555cb50a58d03c45582230c922d7c85a382adf6f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 09:22:11 +0200 Subject: [PATCH 088/665] image names --- lamaria/utils/general.py | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 6a6aef8..b17aa38 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -24,6 +24,7 @@ LEFT_CAMERA_STREAM_LABEL = "camera-slam-left" RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" IMU_STREAM_LABEL = "imu-right" +CUSTOM_ORIGIN_COORDINATES = (2683594.4120000005, 1247727.7470000014, 417.307) def find_closest_timestamp( @@ -370,4 +371,15 @@ def get_t_imu_camera( t_imu_cam_matrix = t_imu_cam.to_matrix() return t_imu_cam_matrix - return t_imu_cam \ No newline at end of file + return t_imu_cam + + +def get_image_names_to_ids(reconstruction_dir: str): + recon = pycolmap.Reconstruction(reconstruction_dir) + image_names_to_ids = {} + + for image_id in recon.images.keys(): + image_name = recon.images[image_id].name + image_names_to_ids[image_name] = image_id + + return image_names_to_ids \ No newline at end of file From 0a7f0339f1167b8be0b56b8442830343bce1d013 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 10:49:29 +0200 Subject: [PATCH 089/665] general --- lamaria/utils/general.py | 51 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 51 insertions(+) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index b17aa38..6a12626 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -9,6 +9,7 @@ from typing import List import subprocess from scipy.spatial.transform import Rotation +from decimal import Decimal, ROUND_HALF_UP from projectaria_tools.core.stream_id import StreamId from projectaria_tools.core import data_provider, mps @@ -235,6 +236,13 @@ def camera_colmap_from_json( params=params, ) +def round_ns(x: str | int | float) -> int: + # works for "5120...274.999939", "5.12e11", or ints + if isinstance(x, int): + return x + s = str(x) + return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) + def delete_files_in_folder(folder, exclude_pattern=None): if os.path.isdir(folder): for filename in os.listdir(folder): @@ -373,6 +381,49 @@ def get_t_imu_camera( return t_imu_cam +def get_t_imu_camera_from_json( + device_calibration_json: str, + camera_label: str, +) -> pycolmap.Rigid3d: + + with open(device_calibration_json, "r") as f: + device_calib = json.load(f) + + # body is right imu of Aria, therefore T_b_s is T_imu_camera + t_body_cam = device_calib[camera_label]["T_b_s"] + t_imu_camera = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam["qvec"]), + t_body_cam["tvec"], + ) + + return t_imu_camera + +def get_t_cam_a_cam_b_from_json( + device_calibration_json: str, + camera_a_label: str, + camera_b_label: str, +) -> pycolmap.Rigid3d: + + with open(device_calibration_json, "r") as f: + device_calib = json.load(f) + + # body is right imu of Aria, therefore T_b_s is T_imu_camera + t_body_cam_a = device_calib[camera_a_label]["T_b_s"] + t_body_cam_b = device_calib[camera_b_label]["T_b_s"] + + t_imu_cam_a = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam_a["qvec"]), + t_body_cam_a["tvec"], + ) + t_imu_cam_b = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam_b["qvec"]), + t_body_cam_b["tvec"], + ) + + t_camera_a_camera_b = t_imu_cam_a.inverse() * t_imu_cam_b + + return t_camera_a_camera_b + def get_image_names_to_ids(reconstruction_dir: str): recon = pycolmap.Reconstruction(reconstruction_dir) From 51ab7b91bd02c2b120bde934cb6efa3f3db48e41 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 10:59:47 +0200 Subject: [PATCH 090/665] create sparse empty recon --- .../eval/create_empty_recon_from_estimate.py | 150 ++++++++++++++++++ lamaria/eval/sparse_evaluation.py | 121 ++++++++++++++ 2 files changed, 271 insertions(+) create mode 100644 lamaria/eval/create_empty_recon_from_estimate.py create mode 100644 lamaria/eval/sparse_evaluation.py diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py new file mode 100644 index 0000000..873a9f6 --- /dev/null +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -0,0 +1,150 @@ +import json +import os +from pathlib import Path + +import numpy as np +import pycolmap +from tqdm import tqdm + +from ..utils.general import ( + LEFT_CAMERA_STREAM_LABEL, + RIGHT_CAMERA_STREAM_LABEL, + add_cameras_to_reconstruction, + find_closest_timestamp, + delete_files_in_folder, + get_t_imu_camera_from_json, + round_ns, +) + + +def add_images_to_reconstruction( + reconstruction: pycolmap.Reconstruction, + pred_estimate_file, + cp_json_file, + device_calibration_json, + slam_input_imu, +): + pose_data = [] + # ESTIMATE FORMAT: + # timestamp(ns) tx ty tz q_x q_y q_z q_w + with open(pred_estimate_file, "r") as f: + lines = f.readlines() + + if len(lines) == 0: + return reconstruction + + if "#" in lines[0]: + lines = lines[1:] + + for line in lines: + parts = line.split() + if len(parts) < 8: + continue + + timestamp = round_ns(parts[0]) + + tvec = np.array( + [float(parts[1]), + float(parts[2]), + float(parts[3])]) + q_xyzw = np.array([ + float(parts[4]), + float(parts[5]), + float(parts[6]), + float(parts[7]), + ]) + T_world_device = pycolmap.Rigid3d(pycolmap.Rotation3d(q_xyzw), + tvec) + + pose_data.append((timestamp, T_world_device)) + + with open(cp_json_file, "r") as f: + cp_data = json.load(f) + + image_id = 1 + rig = reconstruction.rig(rig_id=1) + + # if slam_input_imu is 1, then the poses are IMU poses + # otherwise, the poses are left camera poses (monocular-cam0) (rig poses) + if slam_input_imu == 1: + transform = get_t_imu_camera_from_json( + device_calibration_json=device_calibration_json, + camera_label="cam0", + ) + else: + transform = pycolmap.Rigid3d() + + ts_data_processed = {} + for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: + ts_data = cp_data["timestamps"][label] + ts_data_processed[label] = {int(k): v for k, v in ts_data.items()} + ts_data_processed[label]["sorted_keys"] = sorted(ts_data_processed[label].keys()) + + for i, (timestamp, pose) in tqdm(enumerate(pose_data), + total=len(pose_data), + desc="Adding images to reconstruction"): + + T_world_rig = pose * transform + frame = pycolmap.Frame() + frame.rig_id = rig.rig_id + frame.frame_id = i + 1 + frame.rig_from_world = T_world_rig.inverse() + + images_to_add = [] + + for label, camera_id in [(LEFT_CAMERA_STREAM_LABEL, 1), + (RIGHT_CAMERA_STREAM_LABEL, 2)]: + + source_timestamps = ts_data_processed[label]["sorted_keys"] + closest_timestamp = find_closest_timestamp( + source_timestamps, + timestamp + ) + if closest_timestamp is None: + raise ValueError + + image_name = ts_data_processed[label][closest_timestamp] + + im = pycolmap.Image( + image_name, + pycolmap.Point2DList(), + camera_id, + image_id, + ) + im.frame_id = frame.frame_id + frame.add_data_id(im.data_id) + + images_to_add.append(im) + image_id += 1 + + reconstruction.add_frame(frame) + for im in images_to_add: + reconstruction.add_image(im) + + +def create_baseline_reconstruction( + pred_estimate_file: Path, + eval_folder: Path, + cp_json_file: Path, + device_calibration_json: Path, + slam_input_imu: int, +): + recon_path = eval_folder / "reconstruction" + recon_path.mkdir(parents=True, exist_ok=True) + delete_files_in_folder(recon_path) + + recon = pycolmap.Reconstruction() + add_cameras_to_reconstruction( + recon, + device_calibration_json, + ) + + add_images_to_reconstruction( + reconstruction=recon, + pred_estimate_file=pred_estimate_file, + cp_json_file=cp_json_file, + device_calibration_json=device_calibration_json, + slam_input_imu=slam_input_imu, + ) + + recon.write(recon_path) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py new file mode 100644 index 0000000..1e3f1d3 --- /dev/null +++ b/lamaria/eval/sparse_evaluation.py @@ -0,0 +1,121 @@ +import copy +import os + +from pathlib import Path +import numpy as np +import pyceres +import pycolmap + +from ..utils.control_point import ( + construct_control_points_from_json, + get_cps_for_initial_alignment, + run_control_point_triangulation_from_json, +) +from ..utils.sparse_eval import ( + create_variables_for_sparse_evaluation, + get_problem_for_sparse_alignment, + update_sim3d_scale, +) + + +def run_baseline_evaluation( + cp_json_file: str, + sequence_eval_folder: Path, + cp_reproj_std=1.0, +): + + reconstruction_dir = sequence_eval_folder / "reconstruction" + aligned_transformed_folder = sequence_eval_folder / "aligned_transformed" + aligned_transformed_folder.mkdir(parents=True, exist_ok=True) + + control_points = construct_control_points_from_json(cp_json_file) + assert control_points is not None, "Control points could not be constructed from JSON" + + run_control_point_triangulation_from_json( + reconstruction_dir=reconstruction_dir, + cp_json_file=cp_json_file, + control_points=control_points, + ) + + triangulated_cp_alignment, topo_cp_alignment = ( + get_cps_for_initial_alignment(control_points) + ) + + if triangulated_cp_alignment is None or topo_cp_alignment is None: + return (False, "Not enough control points for INITIAL alignment") + + ret = pycolmap.estimate_sim3d_robust( + triangulated_cp_alignment, topo_cp_alignment, {"max_error": 5} + ) + + if ret is None: + return (False, "Failed to estimate robust sim3d") + + robust_sim3d = ret["tgt_from_src"] + + ######################################################################### + output_data = {} + output_data["robust_sim3d"] = copy.deepcopy(robust_sim3d) + + variables = create_variables_for_sparse_evaluation( + control_points, + robust_sim3d, + cp_reproj_std, + ) + + reconstruction = pycolmap.Reconstruction(reconstruction_dir) + problem, solver_options, summary = get_problem_for_sparse_alignment( + reconstruction, + variables + ) + pyceres.solve(solver_options, problem, summary) + print(summary.BriefReport()) + + update_sim3d_scale(variables) + + output_data["full_alignment"] = {} + output_data["full_alignment"]["sim3"] = copy.deepcopy(variables["sim3d"]) + output_data["full_alignment"]["error_3d"] = {} + output_data["full_alignment"]["points"] = {} + + for tag_id, cp in control_points.items(): + output_data["full_alignment"]["points"][tag_id] = {} + + if cp["triangulated"] is None: + output_data["full_alignment"]["points"][tag_id]["triangulated"] = ( + None + ) + output_data["full_alignment"]["error_3d"][tag_id] = [ + np.nan, + np.nan, + np.nan, + ] + continue + + original_triangulated_point = cp["triangulated"] + topo_cp = cp["topo"] + output_data["full_alignment"]["points"][tag_id]["triangulated"] = ( + original_triangulated_point + ) + output_data["full_alignment"]["points"][tag_id]["topo"] = topo_cp + output_data["full_alignment"]["points"][tag_id]["transformed"] = ( + variables["sim3d"] * original_triangulated_point + ) + error3d = variables["sim3d"] * original_triangulated_point - topo_cp + + output_data["full_alignment"]["error_3d"][tag_id] = error3d + + recon = pycolmap.Reconstruction(reconstruction_dir) + recon.transform(output_data["full_alignment"]["sim3"]) + recon.write(aligned_transformed_folder) + + output_data["control_points"] = {} + for tag_id, cp in control_points.items(): + output_data["control_points"][tag_id] = {} + output_data["control_points"][tag_id]["covariance"] = cp["covariance"] + output_data["control_points"][tag_id]["geo_id"] = cp["control_point"] + output_data["control_points"][tag_id]["topo"] = cp["topo"] + + np.save(os.path.join(sequence_eval_folder, "sparse_evaluation.npy"), output_data) + + return (True, "Sparse evaluation completed successfully") \ No newline at end of file From 8843475955fdbbc6b04abc7419ebeb4eb08102ec Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 11:00:42 +0200 Subject: [PATCH 091/665] sparse eval util.s --- lamaria/utils/sparse_eval.py | 113 +++++++++++++++++++++++++++++++++++ 1 file changed, 113 insertions(+) create mode 100644 lamaria/utils/sparse_eval.py diff --git a/lamaria/utils/sparse_eval.py b/lamaria/utils/sparse_eval.py new file mode 100644 index 0000000..a6583ee --- /dev/null +++ b/lamaria/utils/sparse_eval.py @@ -0,0 +1,113 @@ +import copy + +import numpy as np +import pycolmap +import pyceres +import pycolmap.cost_functions +from pathlib import Path +from typing import Dict, List + +from lamaria import logger + +def update_sim3d_scale(variables): + if "log_scale" not in variables: + raise ValueError("log_scale not found in variables") + + log_scale = copy.deepcopy(variables["log_scale"]) + variables["sim3d"].scale = np.exp(log_scale) + +def create_variables_for_sparse_evaluation( + control_points: Dict, + sim3d: pycolmap.Sim3d, + cp_reproj_std: float = 1.0 +) -> Dict: + + variables = {} + variables["control_points"] = copy.deepcopy(control_points) + variables["sim3d"] = copy.deepcopy(sim3d) + variables["cp_reproj_std"] = cp_reproj_std + scale = copy.deepcopy(variables["sim3d"].scale) + variables["log_scale"] = np.array(np.log(scale), dtype=np.float64) + + return variables + + +def get_problem_for_sparse_alignment( + reconstruction: pycolmap.Reconstruction, + variables: Dict, +): + problem = pyceres.Problem() + problem = add_alignment_residuals( + problem, + reconstruction, + variables, + ) + solver_options = pyceres.SolverOptions() + solver_options.minimizer_progress_to_stdout = True + summary = pyceres.SolverSummary() + + return problem, solver_options, summary + + +def add_alignment_residuals( + problem, + reconstruction: pycolmap.Reconstruction, + variables: Dict, +) -> pyceres.Problem: + + if ( + variables["control_points"] is not None + and variables["sim3d"] is not None + ): + loss = pyceres.TrivialLoss() + for tag_id, cp in variables["control_points"].items(): + if cp["triangulated"] is None: + logger.info(f"Control point {tag_id} not triangulated") + continue + for image_id_and_point2d in cp["image_id_and_point2d"]: + image_id, point2d = image_id_and_point2d + image = reconstruction.images[image_id] + pose = image.cam_from_world() + camera = reconstruction.cameras[image.camera_id] + + point2d = np.asarray(point2d, dtype=np.float64).reshape(2, 1) + point2d_cov = np.eye(2) * pow(variables["cp_reproj_std"], 2) + cost = pycolmap.cost_functions.ReprojErrorCost( + camera.model, + point2d_cov, + point2d, + pose, + ) + problem.add_residual_block( + cost, loss, [cp["triangulated"], camera.params] + ) + problem.set_parameter_block_constant(camera.params) + + for tag_id, cp in variables["control_points"].items(): + if cp["triangulated"] is None: + logger.info(f"Control point {tag_id} not triangulated") + continue + cost = pycolmap.cost_functions.Point3DAlignmentCost( + cp["covariance"], + cp["topo"], + ) + problem.add_residual_block( + cost, + loss, + [ + cp["triangulated"], + variables["sim3d"].rotation.quat, + variables["sim3d"].translation, + variables["log_scale"], + ], + ) + + logger.info(f"Added Point3dAlignmentCost and ReprojErrorCost \ + for {len(variables['control_points'])} control points") + + problem.set_manifold( + variables["sim3d"].rotation.quat, + pyceres.EigenQuaternionManifold(), + ) + + return problem From 56247d757feef5c734da3eef0d5a85be1305495a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 17:36:31 +0200 Subject: [PATCH 092/665] vi opt --- lamaria/rig/optim/vi_optimization.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index fd158f5..e0c1ea0 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -52,13 +52,11 @@ def _get_incremental_pipeline_options(self): return pipeline_options -# Factory function for easy integration with existing pipeline def create_vi_optimizer(session: SingleSeqSession) -> VIOptimizer: """Factory function to create VI optimizer""" return VIOptimizer(session) -# Convenience function for direct usage def run_vi_optimization(session: SingleSeqSession, database_path: str, output_folder: Path = None): """Run VI optimization with given session and database""" From c17e6856d784c5453411b63a372c09e6bdf89599 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 17:37:25 +0200 Subject: [PATCH 093/665] vi opt --- lamaria/rig/optim/vi_optimization.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index e0c1ea0..2828f9b 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -57,7 +57,7 @@ def create_vi_optimizer(session: SingleSeqSession) -> VIOptimizer: return VIOptimizer(session) -def run_vi_optimization(session: SingleSeqSession, database_path: str, +def run(session: SingleSeqSession, database_path: str, output_folder: Path = None): """Run VI optimization with given session and database""" optimizer = create_vi_optimizer(session) From 5a19502ef6df4b73df94c32933491071903e3507 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 18:01:53 +0200 Subject: [PATCH 094/665] imu --- lamaria/rig/keyframing/vrs_to_colmap.py | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py index fc05e58..ac2ef05 100644 --- a/lamaria/rig/keyframing/vrs_to_colmap.py +++ b/lamaria/rig/keyframing/vrs_to_colmap.py @@ -22,6 +22,9 @@ get_closed_loop_data_from_mps, get_mps_poses_for_timestamps, ) +from ...utils.imu import ( + get_online_imu_data_from_vrs +) @dataclass class PerFrameData: @@ -328,6 +331,16 @@ def _add_online_frames(self) -> None: for im in images_to_add: self.empty_recons.add_image(im) + def _save_imu_measurements(self) -> None: + file_path = self.cfg.result.output_folder_path / self.cfg.result.rect_imu_file + if not self.cfg.optimization.use_device_calibration: + ms = get_online_imu_data_from_vrs( + self.vrs_provider, + self.cfg.mps_path, + ) + np.save(file_path, ms.data) + # add device calib case if needed + def create(self) -> pycolmap.Reconstruction: if self.cfg.optimization.use_device_calibration: self._add_device_sensors() @@ -335,7 +348,9 @@ def create(self) -> pycolmap.Reconstruction: else: self._add_online_sensors() self._add_online_frames() - + + self._save_imu_measurements() + return self.empty_recons def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path) -> None: From c0f295c0056da57258d32925d8bb60f9cc974817 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 18:06:22 +0200 Subject: [PATCH 095/665] tri --- lamaria/rig/optim/triangulation.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 4bce52d..ad5cd64 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -106,7 +106,7 @@ def run( export_dir=hloc_outputs_dir, ) - triangulated_model = triangulation.main( + _ = triangulation.main( sfm_dir=triangulated_model_path, reference_model=reference_model_path, image_dir=keyframes_dir, @@ -115,4 +115,4 @@ def run( matches=matches_path, ) - return triangulated_model \ No newline at end of file + return triangulated_model_path \ No newline at end of file From b58090c22f7c68adfe36c3b8ceeb76d867d1417d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 18:06:39 +0200 Subject: [PATCH 096/665] pipeline --- scripts/run_pipeline.py | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/scripts/run_pipeline.py b/scripts/run_pipeline.py index 314e064..c634c00 100644 --- a/scripts/run_pipeline.py +++ b/scripts/run_pipeline.py @@ -5,6 +5,9 @@ from lamaria.rig.keyframing.image_extraction import run as run_extraction from lamaria.rig.keyframing.keyframe_selection import KeyframeSelector from lamaria.rig.optim.triangulation import run as run_triangulation +from lamaria.rig.optim.session import SingleSeqSession +from lamaria.rig.optim.vi_optimization import run as run_vi_optimization + def run_pipeline(): @@ -29,7 +32,25 @@ def run_pipeline(): kf_selector.write_reconstruction(kf_recon, cfg.result.output_folder_path / cfg.result.kf_model) kf_selector.copy_images_to_keyframes_dir() kf_selector.write_keyframe_timestamps(cfg.result.output_folder_path / cfg.result.kf_ts) - # _ = run_triangulation(cfg=cfg) + triangulated_model_path = run_triangulation(cfg=cfg) + + timestamps = kf_selector.read_keyframe_timestamps(cfg.result.output_folder_path / cfg.result.kf_ts) + rect_imu_file = cfg.result.output_folder_path / cfg.result.rect_imu_file + if not rect_imu_file.exists(): + raise FileNotFoundError(f"Rectified IMU file not found at {rect_imu_file}") + + session = SingleSeqSession( + reconstruction=kf_recon, + timestamps=timestamps, + rect_imu_file=rect_imu_file, + ) + optimized_recon = run_vi_optimization( + session=session, + database_path=triangulated_model_path / "database.db", + output_folder=cfg.result.output_folder_path / cfg.result.optim_model, + ) + + if __name__ == "__main__": From f04bc87958068a27d2f6eddfdc328323fb9d110c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 18:06:48 +0200 Subject: [PATCH 097/665] imu file --- lamaria/rig/config/defaults.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 97c2dcb..f048612 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -28,6 +28,8 @@ result: full_ts: timestamps/full.npy kf_ts: timestamps/keyframe.npy + rect_imu_file: rect_imu.npy + keyframing: max_rotation: 20.0 max_distance: 1.0 From 6d352fa8c14fb00d67d58527809d72ec53e2afd1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 18:11:19 +0200 Subject: [PATCH 098/665] viopt --- lamaria/rig/optim/vi_optimization.py | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 2828f9b..394e541 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -11,8 +11,8 @@ class VIOptimizer: def __init__(self, session: SingleSeqSession): self.session = session - - def optimize(self, database_path: str, output_folder: Path): + + def optimize(self, database_path: Path, output_folder: Path): """Run the complete VI optimization pipeline""" # Setup mapper @@ -30,10 +30,8 @@ def optimize(self, database_path: str, output_folder: Path): optimized_reconstruction = mapper.reconstruction output_folder.mkdir(parents=True, exist_ok=True) optimized_reconstruction.write(output_folder.as_posix()) - - return optimized_reconstruction - def _setup_incremental_mapper(self, database_path: str): + def _setup_incremental_mapper(self, database_path: Path): """Setup the incremental mapper""" database = pycolmap.Database.open(database_path) image_names = [self.session.reconstruction.images[image_id].name @@ -57,8 +55,11 @@ def create_vi_optimizer(session: SingleSeqSession) -> VIOptimizer: return VIOptimizer(session) -def run(session: SingleSeqSession, database_path: str, - output_folder: Path = None): +def run(session: SingleSeqSession, + database_path: Path, + output_folder: Path, +) -> None: + """Run VI optimization with given session and database""" optimizer = create_vi_optimizer(session) - return optimizer.optimize(database_path, output_folder) \ No newline at end of file + optimizer.optimize(database_path, output_folder) \ No newline at end of file From 9ace00930b32efe7a2d91803f3b8e077d7fef9d0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 18:13:44 +0200 Subject: [PATCH 099/665] kf timestamps --- lamaria/rig/keyframing/keyframe_selection.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 0f2df2f..3ccbc2c 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -229,6 +229,10 @@ def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: shutil.copy2(src_path, dst_path) + def read_keyframe_timestamps(self, input_path: Path) -> None: + ts = np.load(input_path).tolist() + return ts + def write_keyframe_timestamps(self, output_path: Path) -> None: output_path.parent.mkdir(parents=True, exist_ok=True) keyframed_timestamps = np.array([self.timestamps[i - 1] for i in self.keyframe_frame_ids]) From c91b5626332a0c9ac74ae0c1b53d6e7ba681cee5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 18:14:02 +0200 Subject: [PATCH 100/665] acce --- lamaria/utils/imu.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index 969deeb..ca3efd2 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -32,10 +32,9 @@ def get_online_params_for_imu_from_mps( def get_online_imu_data_from_vrs( - vrs_file: Path, + vrs_provider: data_provider.VrsDataProvider, mps_folder: Path, ): - vrs_provider = data_provider.create_vrs_data_provider(vrs_file.as_posix()) imu_timestamps = sorted( vrs_provider.get_timestamps_ns( IMU_STREAM_ID, @@ -50,7 +49,7 @@ def get_online_imu_data_from_vrs( imu_stream_label ) - acceptable_diff_ms = 5 # 5 milliseconds + acceptable_diff_ms = 1 # 1 milliseconds calib_timestamps = sorted(online_imu_calibs.keys()) From 7780979152289c2f4174e81351a88e472ece0a30 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 18 Sep 2025 18:16:20 +0200 Subject: [PATCH 101/665] frame pairs --- lamaria/rig/optim/triangulation.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index ad5cd64..db83850 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -17,7 +17,7 @@ def pairs_from_frames(recon: pycolmap.Reconstruction): - rig_pairs = set() + frame_pairs = set() by_index = defaultdict(list) for fid in sorted(recon.frames.keys()): @@ -27,8 +27,8 @@ def pairs_from_frames(recon: pycolmap.Reconstruction): for i in range(len(names)): for j in range(i + 1, len(names)): - rig_pairs.add((names[i], names[j])) - rig_pairs.add((names[j], names[i])) + frame_pairs.add((names[i], names[j])) + frame_pairs.add((names[j], names[i])) for k, n in enumerate(names): by_index[k].append(n) @@ -38,7 +38,7 @@ def pairs_from_frames(recon: pycolmap.Reconstruction): for a, b in zip(seq[:-1], seq[1:]): adj_pairs.add((a, b)) - return rig_pairs, adj_pairs + return frame_pairs, adj_pairs def postprocess_pairs_with_reconstruction( sfm_pairs_file: Path, @@ -47,7 +47,7 @@ def postprocess_pairs_with_reconstruction( recon = (reconstruction if isinstance(reconstruction, pycolmap.Reconstruction) else pycolmap.Reconstruction(str(reconstruction))) - rig_pairs, adj_pairs = pairs_from_frames(recon) + frame_pairs, adj_pairs = pairs_from_frames(recon) existing = set() with open(sfm_pairs_file, "r") as f: @@ -55,7 +55,7 @@ def postprocess_pairs_with_reconstruction( a, b = line.strip().split() existing.add((a, b)) - existing = {p for p in existing if p not in rig_pairs} + existing = {p for p in existing if p not in frame_pairs} existing |= adj_pairs with open(sfm_pairs_file, "w") as f: From bec4ee0c360c75aa897c33aa1f6da75b49452763 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 12:39:13 +0200 Subject: [PATCH 102/665] vrs to colmap --- lamaria/rig/keyframing/vrs_to_colmap.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py index ac2ef05..77d8bad 100644 --- a/lamaria/rig/keyframing/vrs_to_colmap.py +++ b/lamaria/rig/keyframing/vrs_to_colmap.py @@ -49,9 +49,9 @@ def _init_io(self): data_paths = mps.MpsDataPathsProvider(self.cfg.mps_path.as_posix()).get_data_paths() self.mps_data_provider = mps.MpsDataProvider(data_paths) - self.left_cam_stream_id = StreamId(self.cfg.streams.left_cam_stream_id) - self.right_cam_stream_id = StreamId(self.cfg.streams.right_cam_stream_id) - self.imu_stream_id = StreamId(self.cfg.streams.imu_right_stream_id) + self.left_cam_stream_id = StreamId(self.cfg.vrs_streams.left_cam_stream_id) + self.right_cam_stream_id = StreamId(self.cfg.vrs_streams.right_cam_stream_id) + self.imu_stream_id = StreamId(self.cfg.vrs_streams.imu_right_stream_id) def _init_data(self): images = self._get_images() From 3b8f7284fcc96312b005bc4a98bbdfd859e21c7e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 12:39:39 +0200 Subject: [PATCH 103/665] vrs streams --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index f048612..07a12f4 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -6,7 +6,7 @@ paths: camera: model: RAD_TAN_THIN_PRISM_FISHEYE -streams: +vrs_streams: left_cam_stream_id: 1201-1 right_cam_stream_id: 1201-2 imu_right_stream_id: 1202-1 From 2f9d12359aebc1f0abdafbcbdc6b0270c4cc919f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 13:32:30 +0200 Subject: [PATCH 104/665] defs --- lamaria/rig/config/defaults.yaml | 55 +++++++++++++++++--------------- 1 file changed, 29 insertions(+), 26 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 07a12f4..a66dccf 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -1,7 +1,32 @@ +run: + seq_id: 5cp + vrs_file: ${run.seq_id}.vrs + +flags: + use_mps: false + mps_fail: false + paths: base: /media/arialamar/ - recordings: ${paths.base}/recordings/ - mps: ${paths.base}/mps/ + recordings: ${paths.base}/recordings/ # always needed + estimates: ${paths.base}/estimates/ # estimates in seq_id.txt format + + mps: ${paths.base}/mps/ # not necessary if use_mps is false + + output: + base: ${paths.base}/test/ + images: image_stream/ + + keyframes: keyframes/ + init_model: empty_recon/ + kf_model: keyframe_recon/ + tri_model: triangulated_recon/ + optim_model: optim_recon/ + + full_ts: timestamps/full.npy + kf_ts: timestamps/keyframe.npy + + rect_imu_file: rect_imu.npy camera: model: RAD_TAN_THIN_PRISM_FISHEYE @@ -11,25 +36,6 @@ vrs_streams: right_cam_stream_id: 1201-2 imu_right_stream_id: 1202-1 -flags: - mps_fail: false - has_slam_drops: false # check inside vrs.json file - -result: - parent_path: test/ - output_folder: rig/ - - keyframes: keyframes - init_model: empty_recon - kf_model: keyframe_recon - tri_model: triangulated_recon - optim_model: optim_recon - - full_ts: timestamps/full.npy - kf_ts: timestamps/keyframe.npy - - rect_imu_file: rect_imu.npy - keyframing: max_rotation: 20.0 max_distance: 1.0 @@ -42,11 +48,12 @@ triangulation: retrieval_conf: netvlad optimization: + use_device_calibration: true # relevant only when use_mps is true (for online calib file) + feature_std: 1.0 use_callback: true max_num_iterations: 10 normalize_reconstruction: false - use_device_calibration: false optimize_cam_intrinsics: false optimize_cam_from_rig: false optimize_scale: false @@ -57,7 +64,3 @@ optimization: imu_inflation_factor_acc: 1.0 integration_noise_density: 0.05 keep_imu_residuals: true - -run: - seq_id: 5cp - vrs_file: ${run.seq_id}.vrs From 8d92f5446a5e4a53ddbafa75402f261ba7b80c7d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 13:33:49 +0200 Subject: [PATCH 105/665] defs --- lamaria/rig/config/defaults.yaml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index a66dccf..1a3b4f8 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -4,7 +4,7 @@ run: flags: use_mps: false - mps_fail: false + use_device_calibration: true # relevant only when use_mps is true (for online calib file) paths: base: /media/arialamar/ @@ -48,8 +48,6 @@ triangulation: retrieval_conf: netvlad optimization: - use_device_calibration: true # relevant only when use_mps is true (for online calib file) - feature_std: 1.0 use_callback: true max_num_iterations: 10 From 3d28e9ec41fcf548f3e308bc297783862b787c6d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 13:52:50 +0200 Subject: [PATCH 106/665] parmas --- lamaria/rig/config/params.py | 27 +++++++++++++ lamaria/rig/optim/params.py | 73 ------------------------------------ 2 files changed, 27 insertions(+), 73 deletions(-) create mode 100644 lamaria/rig/config/params.py delete mode 100644 lamaria/rig/optim/params.py diff --git a/lamaria/rig/config/params.py b/lamaria/rig/config/params.py new file mode 100644 index 0000000..becb228 --- /dev/null +++ b/lamaria/rig/config/params.py @@ -0,0 +1,27 @@ +from dataclasses import dataclass + +@dataclass(frozen=True, slots=True) +class OptCamParams: + feature_std: float = 1.0 # in pixels + optimize_cam_intrinsics: bool = False + optimize_cam_from_rig: bool = False + + +@dataclass(frozen=True, slots=True) +class OptIMUParams: + gyro_infl: float = 1.0 + acc_infl: float = 1.0 + integration_noise_density: float = 0.05 + + optimize_scale: bool = False + optimize_gravity: bool = False + optimize_imu_from_rig: bool = False + optimize_bias: bool = False + keep_imu_residuals: bool = True + + +@dataclass(frozen=True, slots=True) +class OptParams: + use_callback: bool = True + max_num_iterations: int = 10 + normalize_reconstruction: bool = False \ No newline at end of file diff --git a/lamaria/rig/optim/params.py b/lamaria/rig/optim/params.py deleted file mode 100644 index 4136ea6..0000000 --- a/lamaria/rig/optim/params.py +++ /dev/null @@ -1,73 +0,0 @@ -from dataclasses import dataclass - -@dataclass(frozen=True) -class CamParams: - feature_std: float = 1.0 # in pixels - optimize_cam_intrinsics: bool = False - optimize_cam_from_rig: bool = False - - @classmethod - def from_cfg(cls, cfg) -> "CamParams": - """ - Accepts the full OmegaConf cfg and returns camera parameters. - """ - opt = getattr(cfg, "optimization", cfg) - - return cls( - feature_std=float(opt.feature_std), - optimize_cam_intrinsics=bool(opt.optimize_cam_intrinsics), - optimize_cam_from_rig=bool(opt.optimize_cam_from_rig), - ) - - -@dataclass(frozen=True) -class IMUParams: - gyro_infl: float = 1.0 - acc_infl: float = 1.0 - integration_noise_density: float = 0.05 - - optimize_scale: bool = False - optimize_gravity: bool = False - optimize_imu_from_rig: bool = False - optimize_bias: bool = False - keep_imu_residuals: bool = True - - @classmethod - def from_cfg(cls, cfg) -> "IMUParams": - """ - Accepts the full OmegaConf cfg and returns IMU parameters. - """ - opt = getattr(cfg, "optimization", cfg) - - return cls( - gyro_infl=float(opt.imu_inflation_factor_gyro), - acc_infl=float(opt.imu_inflation_factor_acc), - integration_noise_density=float(opt.integration_noise_density), - optimize_scale=bool(opt.optimize_scale), - optimize_gravity=bool(opt.optimize_gravity), - optimize_imu_from_rig=bool(opt.optimize_imu_from_rig), - optimize_bias=bool(opt.optimize_bias), - keep_imu_residuals=bool(opt.keep_imu_residuals), - ) - - -@dataclass(frozen=True) -class OptParams: - use_callback: bool = True - max_num_iterations: int = 10 - normalize_reconstruction: bool = False - use_device_calibration: bool = True - - @classmethod - def from_cfg(cls, cfg) -> "OptParams": - """ - Accepts the full OmegaConf cfg and returns optimization parameters. - """ - opt = getattr(cfg, "optimization", cfg) - - return cls( - use_callback=bool(opt.use_callback), - max_num_iterations=int(opt.max_num_iterations), - normalize_reconstruction=bool(opt.normalize_reconstruction), - use_device_calibration=bool(opt.use_device_calibration), - ) \ No newline at end of file From ef6b5388da938d4eced4f959d9d7b391a6281bfa Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 13:53:25 +0200 Subject: [PATCH 107/665] opt --- lamaria/rig/config/{params.py => opt_params.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename lamaria/rig/config/{params.py => opt_params.py} (100%) diff --git a/lamaria/rig/config/params.py b/lamaria/rig/config/opt_params.py similarity index 100% rename from lamaria/rig/config/params.py rename to lamaria/rig/config/opt_params.py From 084237919ecb6c80de5d4aef1ebbbda14446b858 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 13:54:42 +0200 Subject: [PATCH 108/665] imu --- lamaria/rig/optim/imu.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index 32f1e59..f6c1204 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -1,21 +1,19 @@ import numpy as np import pycolmap -import pyceres from typing import List from pathlib import Path from tqdm import tqdm from ... import logger -from .params import IMUParams -from .session import SingleSeqSession +from ..config.opt_params import OptIMUParams def load_preintegrated_imu_measurements( rect_imu_data_npy: Path, reconstruction: pycolmap.Reconstruction, timestamps: List[int], # must be a sorted list in ns - params: IMUParams = IMUParams(), + params: OptIMUParams = OptIMUParams(), ) -> dict[int, pycolmap.PreintegratedImuMeasurement]: preintegrated_measurements = {} From 7ff7d667874defd2de3dd62495b891989d6eb7cf Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 13:58:13 +0200 Subject: [PATCH 109/665] opt params --- lamaria/rig/config/opt_params.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/config/opt_params.py b/lamaria/rig/config/opt_params.py index becb228..3bb9941 100644 --- a/lamaria/rig/config/opt_params.py +++ b/lamaria/rig/config/opt_params.py @@ -1,14 +1,14 @@ from dataclasses import dataclass @dataclass(frozen=True, slots=True) -class OptCamParams: +class OptCamOptions: feature_std: float = 1.0 # in pixels optimize_cam_intrinsics: bool = False optimize_cam_from_rig: bool = False @dataclass(frozen=True, slots=True) -class OptIMUParams: +class OptIMUOptions: gyro_infl: float = 1.0 acc_infl: float = 1.0 integration_noise_density: float = 0.05 @@ -21,7 +21,7 @@ class OptIMUParams: @dataclass(frozen=True, slots=True) -class OptParams: +class OptOptions: use_callback: bool = True max_num_iterations: int = 10 normalize_reconstruction: bool = False \ No newline at end of file From b46dcff57f59ebbc03aae926fcbb8c9bad7fd8db Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 13:58:22 +0200 Subject: [PATCH 110/665] defs --- lamaria/rig/config/defaults.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 1a3b4f8..9477cca 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -58,7 +58,7 @@ optimization: optimize_gravity: false optimize_imu_from_rig: false optimize_bias: false - imu_inflation_factor_gyro: 20.0 - imu_inflation_factor_acc: 1.0 + gyro_infl: 20.0 + acc_infl: 1.0 integration_noise_density: 0.05 keep_imu_residuals: true From 8938d2d557a664a7c5a0e280696badf772a1169b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 13:59:25 +0200 Subject: [PATCH 111/665] imu oipts --- lamaria/rig/optim/imu.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index f6c1204..858bcd3 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -6,14 +6,14 @@ from tqdm import tqdm from ... import logger -from ..config.opt_params import OptIMUParams +from ..config.opt_params import OptIMUOptions def load_preintegrated_imu_measurements( rect_imu_data_npy: Path, reconstruction: pycolmap.Reconstruction, timestamps: List[int], # must be a sorted list in ns - params: OptIMUParams = OptIMUParams(), + params: OptIMUOptions = OptIMUOptions(), ) -> dict[int, pycolmap.PreintegratedImuMeasurement]: preintegrated_measurements = {} From 9ceabf470e214a192d99af794199bdcf83660f44 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 14:00:28 +0200 Subject: [PATCH 112/665] optim opts --- lamaria/rig/config/{opt_params.py => optim_options.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename lamaria/rig/config/{opt_params.py => optim_options.py} (100%) diff --git a/lamaria/rig/config/opt_params.py b/lamaria/rig/config/optim_options.py similarity index 100% rename from lamaria/rig/config/opt_params.py rename to lamaria/rig/config/optim_options.py From b8230ea760a74c580d626cdbb07e862f7f2aad38 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 14:27:47 +0200 Subject: [PATCH 113/665] options --- lamaria/rig/config/optim_options.py | 27 ---------- lamaria/rig/config/options.py | 77 +++++++++++++++++++++++++++++ 2 files changed, 77 insertions(+), 27 deletions(-) delete mode 100644 lamaria/rig/config/optim_options.py create mode 100644 lamaria/rig/config/options.py diff --git a/lamaria/rig/config/optim_options.py b/lamaria/rig/config/optim_options.py deleted file mode 100644 index 3bb9941..0000000 --- a/lamaria/rig/config/optim_options.py +++ /dev/null @@ -1,27 +0,0 @@ -from dataclasses import dataclass - -@dataclass(frozen=True, slots=True) -class OptCamOptions: - feature_std: float = 1.0 # in pixels - optimize_cam_intrinsics: bool = False - optimize_cam_from_rig: bool = False - - -@dataclass(frozen=True, slots=True) -class OptIMUOptions: - gyro_infl: float = 1.0 - acc_infl: float = 1.0 - integration_noise_density: float = 0.05 - - optimize_scale: bool = False - optimize_gravity: bool = False - optimize_imu_from_rig: bool = False - optimize_bias: bool = False - keep_imu_residuals: bool = True - - -@dataclass(frozen=True, slots=True) -class OptOptions: - use_callback: bool = True - max_num_iterations: int = 10 - normalize_reconstruction: bool = False \ No newline at end of file diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py new file mode 100644 index 0000000..d0cb1fc --- /dev/null +++ b/lamaria/rig/config/options.py @@ -0,0 +1,77 @@ +from __future__ import annotations + +from dataclasses import dataclass, field, replace +from pathlib import Path +from typing import Optional + +from omegaconf import OmegaConf + +from projectaria_tools.core.stream_id import StreamId + +# General options +@dataclass(frozen=True, slots=True) +class MPSOptions: + use_mps: bool = False + use_device_calibration: bool = True # when use_mps is true (for online calib file) + +@dataclass(frozen=True, slots=True) +class SensorOptions: + left_cam_stream_id: StreamId = StreamId("1201-1") + right_cam_stream_id: StreamId = StreamId("1201-2") + right_imu_stream_id: StreamId = StreamId("1202-1") + camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" + +# Keyframing options +@dataclass(frozen=True, slots=True) +class KFOptions: + max_rotation: float = 20.0 # degrees + max_translation: float = 1.0 # meters + max_elapsed_time: float = 1e9 # 1 second in ns + +@dataclass(frozen=True, slots=True) +class KeyframeSelectorOptions: + options: KFOptions = field(default_factory=KFOptions) + init_model: Optional[Path] = None + keyframes_dir: Optional[Path] = None + kf_model: Optional[Path] = None + +# Triangulation options +@dataclass(frozen=True, slots=True) +class TriOptions: + pairs_path: Optional[Path] = None + feature_conf: str = "aliked-n16" + matcher_conf: str = "aliked+lightglue" + retrieval_conf: str = "netvlad" + num_retrieval_matches: int = 5 + +@dataclass(frozen=True, slots=True) +class TriangulatorOptions: + options: TriOptions = field(default_factory=TriOptions) + reference_model: Optional[Path] = None + triangulated_model: Optional[Path] = None + +# Optimization options +@dataclass(frozen=True, slots=True) +class OptCamOptions: + feature_std: float = 1.0 # in pixels + optimize_cam_intrinsics: bool = False + optimize_cam_from_rig: bool = False + +@dataclass(frozen=True, slots=True) +class OptIMUOptions: + gyro_infl: float = 1.0 + acc_infl: float = 1.0 + integration_noise_density: float = 0.05 + + optimize_scale: bool = False + optimize_gravity: bool = False + optimize_imu_from_rig: bool = False + optimize_bias: bool = False + keep_imu_residuals: bool = True + +@dataclass(frozen=True, slots=True) +class OptOptions: + use_callback: bool = True + max_num_iterations: int = 10 + normalize_reconstruction: bool = False + \ No newline at end of file From ddad0f88680010381074e647ac8cdb60b222f7c8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 14:55:14 +0200 Subject: [PATCH 114/665] options --- lamaria/rig/config/options.py | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index d0cb1fc..6aaf2c0 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -21,6 +21,26 @@ class SensorOptions: right_imu_stream_id: StreamId = StreamId("1202-1") camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" +# Image extraction options +@dataclass(frozen=True, slots=True) +class ExtractionOptions: + vrs_file: Optional[Path] = None + images_dir: Optional[Path] = None + +# To COLMAP options +@dataclass(frozen=True, slots=True) +class ToColmapOptions: + vrs_file: Optional[Path] = None + estimate_txt: Optional[Path] = None + init_model: Optional[Path] = None + images_dir: Optional[Path] = None + timestamps_npy: Optional[Path] = None + + mps_dir: Optional[Path] = None + mps_opts: MPSOptions = field(default_factory=MPSOptions) + + sensor_opts: SensorOptions = field(default_factory=SensorOptions) + # Keyframing options @dataclass(frozen=True, slots=True) class KFOptions: From 13d68d8d6b1b0d7d72f1780f0002ae28c290c0f7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 14:55:25 +0200 Subject: [PATCH 115/665] opts --- lamaria/rig/config/options.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 6aaf2c0..0f46498 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -51,8 +51,9 @@ class KFOptions: @dataclass(frozen=True, slots=True) class KeyframeSelectorOptions: options: KFOptions = field(default_factory=KFOptions) - init_model: Optional[Path] = None + init_model: Optional[Path] = None # init model from ToCOLMAP keyframes_dir: Optional[Path] = None + timestamps_npy: Optional[Path] = None kf_model: Optional[Path] = None # Triangulation options From 5c4027613e59489dbb2bb1ffe145ac246dc6f00b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 14:58:21 +0200 Subject: [PATCH 116/665] defs --- lamaria/rig/config/defaults.yaml | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 9477cca..a331dfa 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -11,16 +11,20 @@ paths: recordings: ${paths.base}/recordings/ # always needed estimates: ${paths.base}/estimates/ # estimates in seq_id.txt format - mps: ${paths.base}/mps/ # not necessary if use_mps is false + mps: ${paths.base}/mps/ # necessary if use_mps is true output: - base: ${paths.base}/test/ + base: ${paths.base}/res/ images: image_stream/ - - keyframes: keyframes/ + init_model: empty_recon/ + + keyframes: keyframes/ kf_model: keyframe_recon/ + + pairs_file: pairs.txt tri_model: triangulated_recon/ + optim_model: optim_recon/ full_ts: timestamps/full.npy @@ -31,18 +35,12 @@ paths: camera: model: RAD_TAN_THIN_PRISM_FISHEYE -vrs_streams: - left_cam_stream_id: 1201-1 - right_cam_stream_id: 1201-2 - imu_right_stream_id: 1202-1 - keyframing: max_rotation: 20.0 max_distance: 1.0 max_elapsed: 1.0 triangulation: - pairs_file: pairs.txt feature_conf: aliked-n16 matcher_conf: aliked+lightglue retrieval_conf: netvlad From 751d7cdc819b680b36dec661f56460dbde145220 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 15:29:51 +0200 Subject: [PATCH 117/665] options more --- lamaria/rig/config/options.py | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 0f46498..dacd3e8 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -3,6 +3,7 @@ from dataclasses import dataclass, field, replace from pathlib import Path from typing import Optional +import pycolmap from omegaconf import OmegaConf @@ -41,6 +42,8 @@ class ToColmapOptions: sensor_opts: SensorOptions = field(default_factory=SensorOptions) + rect_imu_data_npy: Optional[Path] = None + # Keyframing options @dataclass(frozen=True, slots=True) class KFOptions: @@ -65,6 +68,15 @@ class TriOptions: retrieval_conf: str = "netvlad" num_retrieval_matches: int = 5 + # colmap defaults + merge_max_reproj_error: float = 4.0 + complete_max_reproj_error: float = 4.0 + min_angle: float = 1.5 + + filter_max_reproj_error: float = 4.0 + filter_min_tri_angle: float = 1.5 + + @dataclass(frozen=True, slots=True) class TriangulatorOptions: options: TriOptions = field(default_factory=TriOptions) @@ -95,4 +107,19 @@ class OptOptions: use_callback: bool = True max_num_iterations: int = 10 normalize_reconstruction: bool = False + +@dataclass(frozen=True, slots=True) +class VIOptimizerOptions: + cam_opts: OptCamOptions = field(default_factory=OptCamOptions) + imu_opts: OptIMUOptions = field(default_factory=OptIMUOptions) + optim_opts: OptOptions = field(default_factory=OptOptions) + + colmap_pipeline_opts: pycolmap.IncrementalPipelineOptions = \ + pycolmap.IncrementalPipelineOptions() + + init_model: Optional[Path] = None + timestamps_npy: Optional[Path] = None + rect_imu_data_npy: Optional[Path] = None + + optimized_model: Optional[Path] = None \ No newline at end of file From aad6a1a2afc0318f96e1a0008e88371d579387ee Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 15:30:08 +0200 Subject: [PATCH 118/665] triangulation opts --- lamaria/rig/config/defaults.yaml | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index a331dfa..7c263bb 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -45,6 +45,15 @@ triangulation: matcher_conf: aliked+lightglue retrieval_conf: netvlad + # https://github.com/colmap/colmap/blob/dbdb3cd5a9a90a01b7e1096905ba2ffc34a68b82/src/colmap/sfm/incremental_triangulator.h + merge_max_reproj_error: 4.0 + complete_max_reproj_error: 4.0 + min_angle: 1.5 + + # https://github.com/colmap/colmap/blob/dbdb3cd5a9a90a01b7e1096905ba2ffc34a68b82/src/colmap/sfm/incremental_mapper.h + filter_max_reproj_error: 4.0 + filter_min_tri_angle: 1.5 + optimization: feature_std: 1.0 use_callback: true From 0e0833565eef7c5cc7b15dece93f4b12b2d09ae5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 15:36:22 +0200 Subject: [PATCH 119/665] more options --- lamaria/rig/config/options.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index dacd3e8..85b5152 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -5,8 +5,6 @@ from typing import Optional import pycolmap -from omegaconf import OmegaConf - from projectaria_tools.core.stream_id import StreamId # General options From 43ab886851b3501288531fc6a74dbc933d18550e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 15:47:14 +0200 Subject: [PATCH 120/665] upd ots --- lamaria/rig/config/options.py | 17 ++--------------- 1 file changed, 2 insertions(+), 15 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 85b5152..5c7f476 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -20,12 +20,6 @@ class SensorOptions: right_imu_stream_id: StreamId = StreamId("1202-1") camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" -# Image extraction options -@dataclass(frozen=True, slots=True) -class ExtractionOptions: - vrs_file: Optional[Path] = None - images_dir: Optional[Path] = None - # To COLMAP options @dataclass(frozen=True, slots=True) class ToColmapOptions: @@ -44,14 +38,11 @@ class ToColmapOptions: # Keyframing options @dataclass(frozen=True, slots=True) -class KFOptions: +class KeyframeSelectorOptions: max_rotation: float = 20.0 # degrees max_translation: float = 1.0 # meters max_elapsed_time: float = 1e9 # 1 second in ns -@dataclass(frozen=True, slots=True) -class KeyframeSelectorOptions: - options: KFOptions = field(default_factory=KFOptions) init_model: Optional[Path] = None # init model from ToCOLMAP keyframes_dir: Optional[Path] = None timestamps_npy: Optional[Path] = None @@ -59,7 +50,7 @@ class KeyframeSelectorOptions: # Triangulation options @dataclass(frozen=True, slots=True) -class TriOptions: +class TriangulatorOptions: pairs_path: Optional[Path] = None feature_conf: str = "aliked-n16" matcher_conf: str = "aliked+lightglue" @@ -73,11 +64,7 @@ class TriOptions: filter_max_reproj_error: float = 4.0 filter_min_tri_angle: float = 1.5 - -@dataclass(frozen=True, slots=True) -class TriangulatorOptions: - options: TriOptions = field(default_factory=TriOptions) reference_model: Optional[Path] = None triangulated_model: Optional[Path] = None From 0f44d3dc5d83e19c21a9ce961aafc7b6ded7b73e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 15:48:46 +0200 Subject: [PATCH 121/665] defs --- lamaria/rig/config/defaults.yaml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 7c263bb..133e463 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -55,12 +55,14 @@ triangulation: filter_min_tri_angle: 1.5 optimization: - feature_std: 1.0 use_callback: true max_num_iterations: 10 normalize_reconstruction: false + + feature_std: 1.0 optimize_cam_intrinsics: false optimize_cam_from_rig: false + optimize_scale: false optimize_gravity: false optimize_imu_from_rig: false @@ -68,4 +70,3 @@ optimization: gyro_infl: 20.0 acc_infl: 1.0 integration_noise_density: 0.05 - keep_imu_residuals: true From 55f42623903962e8a0e27a9b45f5dd7af8348c99 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 15:48:54 +0200 Subject: [PATCH 122/665] opts --- lamaria/rig/config/options.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 5c7f476..1a83fa9 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -85,7 +85,6 @@ class OptIMUOptions: optimize_gravity: bool = False optimize_imu_from_rig: bool = False optimize_bias: bool = False - keep_imu_residuals: bool = True @dataclass(frozen=True, slots=True) class OptOptions: From fee8b4b5a74ac14c4bdc8cde37cfd5daaeb29424 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 16:49:56 +0200 Subject: [PATCH 123/665] path opts --- lamaria/rig/config/options.py | 74 ++++++++++++++++++++++++----------- 1 file changed, 51 insertions(+), 23 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 1a83fa9..b520722 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -4,14 +4,47 @@ from pathlib import Path from typing import Optional import pycolmap +from omegaconf import OmegaConf from projectaria_tools.core.stream_id import StreamId + +@dataclass(slots=True) +class PathOptions: + vrs: Optional[Path] = None + estimate: Optional[Path] = None + init_model: Optional[Path] = None + images: Optional[Path] = None + full_ts: Optional[Path] = None + mps: Optional[Path] = None + + rect_imu: Optional[Path] = None + + keyframes: Optional[Path] = None + kf_model: Optional[Path] = None + kf_ts: Optional[Path] = None + + pairs_file: Optional[Path] = None + tri_model: Optional[Path] = None + + optim_model: Optional[Path] = None + + @classmethod + def load(cls, cfg: OmegaConf) -> PathOptions: + pass + # General options @dataclass(frozen=True, slots=True) class MPSOptions: use_mps: bool = False - use_device_calibration: bool = True # when use_mps is true (for online calib file) + use_online_calibration: bool = False # when use_mps is true (for online calib file) + + @classmethod + def load(cls, cfg: OmegaConf) -> MPSOptions: + return MPSOptions( + use_mps=cfg.get("use_mps", False), + use_online_calibration=cfg.get("use_online_calibration", False), + ) @dataclass(frozen=True, slots=True) class SensorOptions: @@ -20,37 +53,39 @@ class SensorOptions: right_imu_stream_id: StreamId = StreamId("1202-1") camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" + @classmethod + def load(cls, cfg: OmegaConf) -> SensorOptions: + pass + # To COLMAP options @dataclass(frozen=True, slots=True) class ToColmapOptions: - vrs_file: Optional[Path] = None - estimate_txt: Optional[Path] = None - init_model: Optional[Path] = None - images_dir: Optional[Path] = None - timestamps_npy: Optional[Path] = None - - mps_dir: Optional[Path] = None + paths: PathOptions = field(default_factory=PathOptions) mps_opts: MPSOptions = field(default_factory=MPSOptions) - sensor_opts: SensorOptions = field(default_factory=SensorOptions) - rect_imu_data_npy: Optional[Path] = None + @classmethod + def load(cls, cfg: OmegaConf) -> ToColmapOptions: + pass # Keyframing options @dataclass(frozen=True, slots=True) class KeyframeSelectorOptions: + paths: PathOptions = field(default_factory=PathOptions) + max_rotation: float = 20.0 # degrees max_translation: float = 1.0 # meters max_elapsed_time: float = 1e9 # 1 second in ns - init_model: Optional[Path] = None # init model from ToCOLMAP - keyframes_dir: Optional[Path] = None - timestamps_npy: Optional[Path] = None - kf_model: Optional[Path] = None + @classmethod + def load(cls, cfg: OmegaConf) -> KeyframeSelectorOptions: + pass # Triangulation options @dataclass(frozen=True, slots=True) class TriangulatorOptions: + paths: PathOptions = field(default_factory=PathOptions) + pairs_path: Optional[Path] = None feature_conf: str = "aliked-n16" matcher_conf: str = "aliked+lightglue" @@ -65,9 +100,6 @@ class TriangulatorOptions: filter_max_reproj_error: float = 4.0 filter_min_tri_angle: float = 1.5 - reference_model: Optional[Path] = None - triangulated_model: Optional[Path] = None - # Optimization options @dataclass(frozen=True, slots=True) class OptCamOptions: @@ -94,16 +126,12 @@ class OptOptions: @dataclass(frozen=True, slots=True) class VIOptimizerOptions: + paths: PathOptions = field(default_factory=PathOptions) + cam_opts: OptCamOptions = field(default_factory=OptCamOptions) imu_opts: OptIMUOptions = field(default_factory=OptIMUOptions) optim_opts: OptOptions = field(default_factory=OptOptions) colmap_pipeline_opts: pycolmap.IncrementalPipelineOptions = \ pycolmap.IncrementalPipelineOptions() - - init_model: Optional[Path] = None - timestamps_npy: Optional[Path] = None - rect_imu_data_npy: Optional[Path] = None - - optimized_model: Optional[Path] = None \ No newline at end of file From 2973fff977fc06f3c9b3f57cc1614f4f6017e9b5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 16:50:55 +0200 Subject: [PATCH 124/665] options remove opt name --- lamaria/rig/config/options.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index b520722..fdc6d1d 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -61,8 +61,8 @@ def load(cls, cfg: OmegaConf) -> SensorOptions: @dataclass(frozen=True, slots=True) class ToColmapOptions: paths: PathOptions = field(default_factory=PathOptions) - mps_opts: MPSOptions = field(default_factory=MPSOptions) - sensor_opts: SensorOptions = field(default_factory=SensorOptions) + mps: MPSOptions = field(default_factory=MPSOptions) + sensor: SensorOptions = field(default_factory=SensorOptions) @classmethod def load(cls, cfg: OmegaConf) -> ToColmapOptions: @@ -128,10 +128,10 @@ class OptOptions: class VIOptimizerOptions: paths: PathOptions = field(default_factory=PathOptions) - cam_opts: OptCamOptions = field(default_factory=OptCamOptions) - imu_opts: OptIMUOptions = field(default_factory=OptIMUOptions) - optim_opts: OptOptions = field(default_factory=OptOptions) + cam: OptCamOptions = field(default_factory=OptCamOptions) + imu: OptIMUOptions = field(default_factory=OptIMUOptions) + optim: OptOptions = field(default_factory=OptOptions) - colmap_pipeline_opts: pycolmap.IncrementalPipelineOptions = \ + colmap_pipeline: pycolmap.IncrementalPipelineOptions = \ pycolmap.IncrementalPipelineOptions() \ No newline at end of file From 827ca42fffe9c8b3c2d3a86bd55f33b461cbcf9b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 16:53:40 +0200 Subject: [PATCH 125/665] defs --- lamaria/rig/config/defaults.yaml | 30 ++++++++++++++---------------- 1 file changed, 14 insertions(+), 16 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 133e463..c9ede15 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -1,20 +1,14 @@ -run: - seq_id: 5cp - vrs_file: ${run.seq_id}.vrs +paths: + base: /media/arialamar/ + seq_name: 5cp -flags: - use_mps: false - use_device_calibration: true # relevant only when use_mps is true (for online calib file) + vrs: recordings/${paths.seq_name}.vrs + estimate: estimates/${paths.seq_name}.txt -paths: - base: /media/arialamar/ - recordings: ${paths.base}/recordings/ # always needed - estimates: ${paths.base}/estimates/ # estimates in seq_id.txt format - - mps: ${paths.base}/mps/ # necessary if use_mps is true + mps: mps/mps_${paths.seq_name}_vrs/ # necessary if use_mps is true output: - base: ${paths.base}/res/ + base: output/${paths.seq_name}/ images: image_stream/ init_model: empty_recon/ @@ -30,10 +24,10 @@ paths: full_ts: timestamps/full.npy kf_ts: timestamps/keyframe.npy - rect_imu_file: rect_imu.npy + rect_imu: rect_imu.npy -camera: - model: RAD_TAN_THIN_PRISM_FISHEYE +sensor: + camera_model: RAD_TAN_THIN_PRISM_FISHEYE keyframing: max_rotation: 20.0 @@ -70,3 +64,7 @@ optimization: gyro_infl: 20.0 acc_infl: 1.0 integration_noise_density: 0.05 + +mps: + use_mps: false + use_online_calibration: false # relevant only when use_mps is true (for online calib file) From 6785f8bc480edc1d063e5c219e7af86ceac999ec Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 19 Sep 2025 16:54:42 +0200 Subject: [PATCH 126/665] imu options --- lamaria/rig/optim/imu.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index 858bcd3..3038c6d 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -6,7 +6,7 @@ from tqdm import tqdm from ... import logger -from ..config.opt_params import OptIMUOptions +from ..config.options import OptIMUOptions def load_preintegrated_imu_measurements( From 3f31b9cdc0ef5af4781a3235bb1edc967ee3c2f8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 16:03:32 +0200 Subject: [PATCH 127/665] defs --- lamaria/rig/config/defaults.yaml | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index c9ede15..4f55673 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -16,9 +16,10 @@ paths: keyframes: keyframes/ kf_model: keyframe_recon/ + hloc: hloc/ pairs_file: pairs.txt - tri_model: triangulated_recon/ + tri_model: triangulated_recon/ optim_model: optim_recon/ full_ts: timestamps/full.npy @@ -32,13 +33,15 @@ sensor: keyframing: max_rotation: 20.0 max_distance: 1.0 - max_elapsed: 1.0 + max_elapsed: 1e9 # 1 second in ns triangulation: feature_conf: aliked-n16 matcher_conf: aliked+lightglue retrieval_conf: netvlad + num_retrieval_matches: 5 + # relaxed triangulation # https://github.com/colmap/colmap/blob/dbdb3cd5a9a90a01b7e1096905ba2ffc34a68b82/src/colmap/sfm/incremental_triangulator.h merge_max_reproj_error: 4.0 complete_max_reproj_error: 4.0 From a6fd478dccd751833234e9a2f503d1f8b4ce0b87 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 16:16:48 +0200 Subject: [PATCH 128/665] helpers --- lamaria/rig/config/helpers.py | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) create mode 100644 lamaria/rig/config/helpers.py diff --git a/lamaria/rig/config/helpers.py b/lamaria/rig/config/helpers.py new file mode 100644 index 0000000..1d20b39 --- /dev/null +++ b/lamaria/rig/config/helpers.py @@ -0,0 +1,26 @@ +# options.py +from __future__ import annotations +from pathlib import Path +from typing import Optional +from omegaconf import OmegaConf + +def _p( + x: Optional[str] | Optional[Path], + root: Optional[Path] = None +) -> Optional[Path]: + + if x is None: + return None + x = Path(x) + if root is not None and not x.is_absolute(): + return (root / x).resolve() + return x.resolve() + +def _structured_merge_to_obj(cls, section) -> object: + """ + Merge a YAML section onto a structured config made from the dataclass `cls`, + then return a dataclass instance (OmegaConf handles the casting). + """ + base = OmegaConf.structured(cls) + merged = OmegaConf.merge(base, section or {}) + return OmegaConf.to_object(merged) \ No newline at end of file From 430337cdd50b2a1905232496b27fcb1c0bc37a45 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 16:17:00 +0200 Subject: [PATCH 129/665] options --- lamaria/rig/config/options.py | 125 ++++++++++++++++++++++++++++++---- 1 file changed, 111 insertions(+), 14 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index fdc6d1d..603a4cc 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -7,6 +7,7 @@ from omegaconf import OmegaConf from projectaria_tools.core.stream_id import StreamId +from .helpers import _p, _structured_merge_to_obj @dataclass(slots=True) @@ -24,6 +25,7 @@ class PathOptions: kf_model: Optional[Path] = None kf_ts: Optional[Path] = None + hloc: Optional[Path] = None pairs_file: Optional[Path] = None tri_model: Optional[Path] = None @@ -31,7 +33,51 @@ class PathOptions: @classmethod def load(cls, cfg: OmegaConf) -> PathOptions: - pass + """ + Build PathOptions from `paths:` block, resolving relative paths + against `paths.base` and `paths.output.base`. + Layout from defaults.yaml. + """ + cfg_paths = cfg.paths + base_root = Path(cfg_paths.base).resolve() + out_root = _p(cfg_paths.output.base, base_root) + + vrs = _p(cfg_paths.vrs, base_root) + estimate = _p(cfg_paths.estimate, base_root) + mps = _p(cfg_paths.mps, base_root) + + images = _p(cfg_paths.output.images, out_root) + init_model = _p(cfg_paths.output.init_model, out_root) + + keyframes = _p(cfg_paths.output.keyframes, out_root) + kf_model = _p(cfg_paths.output.kf_model, out_root) + + hloc = _p(cfg_paths.output.hloc, out_root) + pairs_file = _p(cfg_paths.output.pairs_file, hloc) + + tri_model = _p(cfg_paths.output.tri_model, out_root) + optim_model= _p(cfg_paths.output.optim_model, out_root) + + full_ts = _p(cfg_paths.output.full_ts, out_root) + kf_ts = _p(cfg_paths.output.kf_ts, out_root) + rect_imu= _p(cfg_paths.output.rect_imu, out_root) + + return cls( + vrs=vrs, + estimate=estimate, + init_model=init_model, + images=images, + full_ts=full_ts, + mps=mps, + rect_imu=rect_imu, + keyframes=keyframes, + kf_model=kf_model, + kf_ts=kf_ts, + hloc=hloc, + pairs_file=pairs_file, + tri_model=tri_model, + optim_model=optim_model, + ) # General options @dataclass(frozen=True, slots=True) @@ -41,10 +87,7 @@ class MPSOptions: @classmethod def load(cls, cfg: OmegaConf) -> MPSOptions: - return MPSOptions( - use_mps=cfg.get("use_mps", False), - use_online_calibration=cfg.get("use_online_calibration", False), - ) + return _structured_merge_to_obj(cls, cfg.mps) @dataclass(frozen=True, slots=True) class SensorOptions: @@ -54,8 +97,15 @@ class SensorOptions: camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" @classmethod - def load(cls, cfg: OmegaConf) -> SensorOptions: - pass + def load(cls, cfg) -> SensorOptions: + obj: SensorOptions = _structured_merge_to_obj(cls, cfg.sensor) + if not isinstance(obj.left_cam_stream_id, StreamId): + object.__setattr__(obj, "left_cam_stream_id", StreamId(str(obj.left_cam_stream_id))) + if not isinstance(obj.right_cam_stream_id, StreamId): + object.__setattr__(obj, "right_cam_stream_id", StreamId(str(obj.right_cam_stream_id))) + if not isinstance(obj.right_imu_stream_id, StreamId): + object.__setattr__(obj, "right_imu_stream_id", StreamId(str(obj.right_imu_stream_id))) + return obj # To COLMAP options @dataclass(frozen=True, slots=True) @@ -65,8 +115,12 @@ class ToColmapOptions: sensor: SensorOptions = field(default_factory=SensorOptions) @classmethod - def load(cls, cfg: OmegaConf) -> ToColmapOptions: - pass + def load(cls, cfg) -> ToColmapOptions: + return cls( + paths=PathOptions.load(cfg), + mps=MPSOptions.load(cfg), + sensor=SensorOptions.load(cfg), + ) # Keyframing options @dataclass(frozen=True, slots=True) @@ -74,19 +128,25 @@ class KeyframeSelectorOptions: paths: PathOptions = field(default_factory=PathOptions) max_rotation: float = 20.0 # degrees - max_translation: float = 1.0 # meters - max_elapsed_time: float = 1e9 # 1 second in ns + max_distance: float = 1.0 # meters + max_elapsed: int = int(1e9) # 1 second in ns @classmethod - def load(cls, cfg: OmegaConf) -> KeyframeSelectorOptions: - pass + def load(cls, cfg) -> "KeyframeSelectorOptions": + section = { + "max_rotation": float(cfg.keyframing.max_rotation), + "max_distance": float(cfg.keyframing.max_distance), + "max_elapsed": int(float(cfg.keyframing.max_elapsed)), + } + obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, section) + return replace(obj, paths=PathOptions.load(cfg)) + # Triangulation options @dataclass(frozen=True, slots=True) class TriangulatorOptions: paths: PathOptions = field(default_factory=PathOptions) - pairs_path: Optional[Path] = None feature_conf: str = "aliked-n16" matcher_conf: str = "aliked+lightglue" retrieval_conf: str = "netvlad" @@ -100,6 +160,11 @@ class TriangulatorOptions: filter_max_reproj_error: float = 4.0 filter_min_tri_angle: float = 1.5 + @classmethod + def load(cls, cfg: OmegaConf) -> "TriangulatorOptions": + obj: TriangulatorOptions = _structured_merge_to_obj(cls, cfg.triangulation) + return replace(obj, paths=PathOptions.load(cfg)) + # Optimization options @dataclass(frozen=True, slots=True) class OptCamOptions: @@ -134,4 +199,36 @@ class VIOptimizerOptions: colmap_pipeline: pycolmap.IncrementalPipelineOptions = \ pycolmap.IncrementalPipelineOptions() + + @classmethod + def load(cls, cfg: OmegaConf) -> "VIOptimizerOptions": + base: VIOptimizerOptions = OmegaConf.to_object(OmegaConf.structured(cls)) + opt = cfg.optimization + cam = _structured_merge_to_obj(OptCamOptions, { + "feature_std": opt.feature_std, + "optimize_cam_intrinsics": opt.optimize_cam_intrinsics, + "optimize_cam_from_rig": opt.optimize_cam_from_rig, + }) + imu = _structured_merge_to_obj(OptIMUOptions, { + "gyro_infl": opt.gyro_infl, + "acc_infl": opt.acc_infl, + "integration_noise_density": opt.integration_noise_density, + "optimize_scale": opt.optimize_scale, + "optimize_gravity": opt.optimize_gravity, + "optimize_imu_from_rig": opt.optimize_imu_from_rig, + "optimize_bias": opt.optimize_bias, + }) + optim = _structured_merge_to_obj(OptOptions, { + "use_callback": opt.use_callback, + "max_num_iterations": opt.max_num_iterations, + "normalize_reconstruction": opt.normalize_reconstruction, + }) + # leave colmap_pipeline as default + return replace( + base, + paths=PathOptions.load(cfg), + cam=cam, + imu=imu, + optim=optim, + ) \ No newline at end of file From 939679d471aa0d0ff820b5ce617b8eabd524ba8a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 16:17:08 +0200 Subject: [PATCH 130/665] lodarers --- lamaria/rig/config/loaders.py | 88 +++++++++++++++++++++-------------- 1 file changed, 54 insertions(+), 34 deletions(-) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index 410d8f6..3288ad3 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -1,37 +1,57 @@ from pathlib import Path -from typing import Optional, Sequence +from typing import Optional, Sequence, Tuple from omegaconf import OmegaConf -def _merge_if_exists(cfg, path: Path): - return OmegaConf.merge(cfg, OmegaConf.load(str(path))) if path.exists() else cfg - -def load_cfg( - base_file: str = "lamaria/rig/config/defaults.yaml", - local_file: Optional[str] = None, - cli_overrides: Optional[Sequence[str]] = None, -): - cfg = OmegaConf.load(base_file) - if local_file: - cfg = _merge_if_exists(cfg, Path(local_file)) - if cli_overrides: - cfg = OmegaConf.merge(cfg, OmegaConf.from_dotlist(list(cli_overrides))) - OmegaConf.resolve(cfg) - - vrs_stem = Path(cfg.run.vrs_file).stem - - base = Path(cfg.paths.base) - recordings = Path(cfg.paths.recordings) - mps = Path(cfg.paths.mps) - - parent_rel = cfg.result.parent_path - - cfg.vrs_file_path = recordings / cfg.run.vrs_file - cfg.mps_path = mps / f"mps_{vrs_stem}_vrs" - cfg.image_stream_path = base / parent_rel / vrs_stem / "image_stream" - - vio_base = base / parent_rel / vrs_stem - - cfg.result.parent_path = vio_base - cfg.result.output_folder_path = vio_base / cfg.result.output_folder - - return cfg +from .options import ( + MPSOptions, + PathOptions, + SensorOptions, + ToColmapOptions, + VIOptimizerOptions, + TriangulatorOptions, + KeyframeSelectorOptions, +) + +class Config: + def __init__( + self, + base_file: str = "lamaria/rig/config/defaults.yaml", + cli_overrides: Optional[Sequence[str]] = None + ): + self.config = OmegaConf.load(base_file) + if cli_overrides: + self.config = OmegaConf.merge( + self.config, + OmegaConf.from_dotlist(list(cli_overrides)) + ) + + OmegaConf.resolve(self.config) + + def get_paths(self) -> PathOptions: + """ Get resolved paths from config. """ + return PathOptions.load(self.config) + + def get_mps_options(self) -> MPSOptions: + """ Get MPS options from config. """ + return MPSOptions.load(self.config) + + def get_sensor_options(self) -> SensorOptions: + """ Get sensor options from config. """ + return SensorOptions.load(self.config) + + def get_to_colmap_options(self) -> ToColmapOptions: + """ Get options for to_colmap pipeline from config. """ + return ToColmapOptions.load(self.config) + + def get_keyframing_options(self) -> KeyframeSelectorOptions: + """ Get keyframing options from config. """ + return KeyframeSelectorOptions.load(self.config) + + def get_triangulator_options(self) -> TriangulatorOptions: + """ Get triangulation options from config. """ + return TriangulatorOptions.load(self.config) + + def get_vi_optimizer_options(self) -> VIOptimizerOptions: + """ Get visual-inertial optimization options from config. """ + return VIOptimizerOptions.load(self.config) + \ No newline at end of file From ee351d49f599fe2883bd1d51e9d39a84621283ff Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 17:12:39 +0200 Subject: [PATCH 131/665] loaders --- lamaria/rig/config/loaders.py | 28 ++++++++++++++++++++-------- 1 file changed, 20 insertions(+), 8 deletions(-) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index 3288ad3..d8adea4 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -13,19 +13,31 @@ ) class Config: - def __init__( - self, + def __init__(self, cfg: OmegaConf): + self.config = cfg + + @classmethod + def load_default( + cls, + ) -> 'Config': + return cls.load() + + @classmethod + def load( + cls, base_file: str = "lamaria/rig/config/defaults.yaml", cli_overrides: Optional[Sequence[str]] = None - ): - self.config = OmegaConf.load(base_file) + ) -> 'Config': + + config = OmegaConf.load(base_file) if cli_overrides: - self.config = OmegaConf.merge( - self.config, + config = OmegaConf.merge( + config, OmegaConf.from_dotlist(list(cli_overrides)) ) - - OmegaConf.resolve(self.config) + + OmegaConf.resolve(config) + return cls(config) def get_paths(self) -> PathOptions: """ Get resolved paths from config. """ From 80b275da2d9709fdc0526d0bfe58d209c8e13d76 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 21:33:33 +0200 Subject: [PATCH 132/665] options --- lamaria/rig/config/options.py | 39 ++++++++++++++++++++++++++++------- 1 file changed, 32 insertions(+), 7 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 603a4cc..3d4bad0 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -32,12 +32,15 @@ class PathOptions: optim_model: Optional[Path] = None @classmethod - def load(cls, cfg: OmegaConf) -> PathOptions: + def load(cls, cfg: Optional[OmegaConf] = None) -> PathOptions: """ Build PathOptions from `paths:` block, resolving relative paths against `paths.base` and `paths.output.base`. Layout from defaults.yaml. """ + if cfg is None or not hasattr(cfg, 'paths'): + return cls() + cfg_paths = cfg.paths base_root = Path(cfg_paths.base).resolve() out_root = _p(cfg_paths.output.base, base_root) @@ -86,7 +89,10 @@ class MPSOptions: use_online_calibration: bool = False # when use_mps is true (for online calib file) @classmethod - def load(cls, cfg: OmegaConf) -> MPSOptions: + def load(cls, cfg: Optional[OmegaConf] = None) -> MPSOptions: + if cfg is None or not hasattr(cfg, 'mps'): + return cls() + return _structured_merge_to_obj(cls, cfg.mps) @dataclass(frozen=True, slots=True) @@ -97,7 +103,10 @@ class SensorOptions: camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" @classmethod - def load(cls, cfg) -> SensorOptions: + def load(cls, cfg: Optional[OmegaConf] = None) -> SensorOptions: + if cfg is None or not hasattr(cfg, 'sensor'): + return cls() + obj: SensorOptions = _structured_merge_to_obj(cls, cfg.sensor) if not isinstance(obj.left_cam_stream_id, StreamId): object.__setattr__(obj, "left_cam_stream_id", StreamId(str(obj.left_cam_stream_id))) @@ -115,7 +124,14 @@ class ToColmapOptions: sensor: SensorOptions = field(default_factory=SensorOptions) @classmethod - def load(cls, cfg) -> ToColmapOptions: + def load(cls, cfg: Optional[OmegaConf] = None) -> ToColmapOptions: + if cfg is None: + return cls( + paths=PathOptions(), + mps=MPSOptions(), + sensor=SensorOptions(), + ) + return cls( paths=PathOptions.load(cfg), mps=MPSOptions.load(cfg), @@ -132,7 +148,10 @@ class KeyframeSelectorOptions: max_elapsed: int = int(1e9) # 1 second in ns @classmethod - def load(cls, cfg) -> "KeyframeSelectorOptions": + def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": + if cfg is None or not hasattr(cfg, 'keyframing'): + return cls(paths=PathOptions()) + section = { "max_rotation": float(cfg.keyframing.max_rotation), "max_distance": float(cfg.keyframing.max_distance), @@ -161,7 +180,10 @@ class TriangulatorOptions: filter_min_tri_angle: float = 1.5 @classmethod - def load(cls, cfg: OmegaConf) -> "TriangulatorOptions": + def load(cls, cfg: Optional[OmegaConf] = None) -> "TriangulatorOptions": + if cfg is None or not hasattr(cfg, 'triangulation'): + return cls(paths=PathOptions()) + obj: TriangulatorOptions = _structured_merge_to_obj(cls, cfg.triangulation) return replace(obj, paths=PathOptions.load(cfg)) @@ -201,7 +223,10 @@ class VIOptimizerOptions: pycolmap.IncrementalPipelineOptions() @classmethod - def load(cls, cfg: OmegaConf) -> "VIOptimizerOptions": + def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": + if cfg is None or not hasattr(cfg, 'optimization'): + return cls(paths=PathOptions()) + base: VIOptimizerOptions = OmegaConf.to_object(OmegaConf.structured(cls)) opt = cfg.optimization cam = _structured_merge_to_obj(OptCamOptions, { From 6a03915551fd0f2f10614022956948a56004d57c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 21:39:29 +0200 Subject: [PATCH 133/665] triangulator opts --- lamaria/rig/optim/triangulation.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index db83850..679fe6c 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -13,7 +13,7 @@ ) from ... import logger -from ..config.loaders import load_cfg +from ..config.options import TriangulatorOptions def pairs_from_frames(recon: pycolmap.Reconstruction): From 5b2989423abaafe540ece046b3a6fd68796b8d06 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 21:42:15 +0200 Subject: [PATCH 134/665] triangulation.main --- lamaria/rig/optim/triangulation.py | 29 +++++++++++++---------------- 1 file changed, 13 insertions(+), 16 deletions(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 679fe6c..8d7f81a 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -64,39 +64,36 @@ def postprocess_pairs_with_reconstruction( def run( - cfg=None, - num_retrieval_matches: int = 5, + options: TriangulatorOptions, ) -> Path: - - cfg = load_cfg() if cfg is None else cfg - keyframes_dir = cfg.result.output_folder_path / cfg.result.keyframes + keyframes_dir = options.paths.keyframes if not keyframes_dir.exists(): raise FileNotFoundError(f"keyframes_dir not found at {keyframes_dir}") - hloc_outputs_dir = cfg.result.output_folder_path / "hloc" + hloc_outputs_dir = options.paths.hloc hloc_outputs_dir.mkdir(parents=True, exist_ok=True) - reference_model_path = cfg.result.output_folder_path / cfg.result.kf_model + reference_model_path = options.paths.kf_model if not reference_model_path.exists(): raise FileNotFoundError(f"reference_model not found at {reference_model_path}") - triangulated_model_path = cfg.result.output_folder_path / cfg.result.tri_model - pairs_path = hloc_outputs_dir / cfg.triangulation.pairs_file + triangulated_model_path = options.paths.tri_model + pairs_path = options.paths.pairs_file - retrieval_conf = extract_features.confs[cfg.triangulation.retrieval_conf] - feature_conf = extract_features.confs[cfg.triangulation.feature_conf] - matcher_conf = match_features.confs[cfg.triangulation.matcher_conf] + retrieval_conf = extract_features.confs[options.retrieval_conf] + feature_conf = extract_features.confs[options.feature_conf] + matcher_conf = match_features.confs[options.matcher_conf] logger.info("HLOC confs: retrieval=%s, features=%s, matcher=%s", - cfg.triangulation.retrieval_conf, - cfg.triangulation.feature_conf, - cfg.triangulation.matcher_conf) + options.retrieval_conf, + options.feature_conf, + options.matcher_conf) retrieval_path = extract_features.main(retrieval_conf, image_dir=keyframes_dir, export_dir=hloc_outputs_dir) features_path = extract_features.main(feature_conf, image_dir=keyframes_dir, export_dir=hloc_outputs_dir) - pairs_from_retrieval.main(retrieval_path, pairs_path, num_retrieval_matches) + pairs_from_retrieval.main(retrieval_path, pairs_path, options.num_retrieval_matches) postprocess_pairs_with_reconstruction(pairs_path, reference_model_path) matches_path = match_features.main( From bba43cfe2cef1e28d9e07d1c34b84587d7561025 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 23:14:00 +0200 Subject: [PATCH 135/665] vrs to colmap --- lamaria/rig/keyframing/vrs_to_colmap.py | 74 +++++++++++++++---------- 1 file changed, 46 insertions(+), 28 deletions(-) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py index 77d8bad..6d686b5 100644 --- a/lamaria/rig/keyframing/vrs_to_colmap.py +++ b/lamaria/rig/keyframing/vrs_to_colmap.py @@ -13,7 +13,7 @@ from projectaria_tools.core.stream_id import StreamId from ... import logger -from ..config.loaders import load_cfg +from ..config.options import ToColmapOptions from ...utils.general import ( find_closest_timestamp, get_t_imu_camera, @@ -21,6 +21,8 @@ rigid3d_from_transform, get_closed_loop_data_from_mps, get_mps_poses_for_timestamps, + extract_images_from_vrs, + round_ns, ) from ...utils.imu import ( get_online_imu_data_from_vrs @@ -35,25 +37,36 @@ class PerFrameData: rig_from_world: pycolmap.Rigid3d -class VrsToColmap: - def __init__(self, cfg=None): - self.cfg = cfg if cfg is not None else load_cfg() +class ToColmap: + def __init__( + self, + options: ToColmapOptions + ): + self.options = options self._init_io() self._init_data() def _init_io(self): + """Initializes output and data providers""" self.empty_recons = pycolmap.Reconstruction() self.vrs_provider = data_provider.create_vrs_data_provider( - self.cfg.vrs_file_path.as_posix() + self.options.paths.vrs.as_posix() ) - data_paths = mps.MpsDataPathsProvider(self.cfg.mps_path.as_posix()).get_data_paths() - self.mps_data_provider = mps.MpsDataProvider(data_paths) - - self.left_cam_stream_id = StreamId(self.cfg.vrs_streams.left_cam_stream_id) - self.right_cam_stream_id = StreamId(self.cfg.vrs_streams.right_cam_stream_id) - self.imu_stream_id = StreamId(self.cfg.vrs_streams.imu_right_stream_id) + if self.options.mps.use_mps: + data_paths = mps.MpsDataPathsProvider(self.cfg.mps_path.as_posix()).get_data_paths() + self.mps_data_provider = mps.MpsDataProvider(data_paths) + else: + assert self.options.paths.estimate is not None, \ + "Estimate path must be provided if MPS is not used" def _init_data(self): + """Extracts images, timestamps and builds per-frame data""" + + extract_images_from_vrs( + vrs_file=self.options.paths.vrs, + image_folder=self.options.paths.images, + ) + images = self._get_images() timestamps = self._get_timestamps() closed_loop_data = get_closed_loop_data_from_mps(self.cfg.mps_path) @@ -65,10 +78,10 @@ def _init_data(self): def _build_per_frame_data(self, images, timestamps, mps_poses) -> List[PerFrameData]: per_frame_data = [] imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.imu_stream_id + self.options.sensor.right_imu_stream_id ) - if self.cfg.optimization.use_device_calibration: + if not self.options.mps.use_online_calibration: device_calibration = self.vrs_provider.get_device_calibration() imu_calib = device_calibration.get_imu_calib( imu_stream_label @@ -80,7 +93,7 @@ def _build_per_frame_data(self, images, timestamps, mps_poses) -> List[PerFrameD if t_world_device is None: continue - if not self.cfg.optimization.use_device_calibration: + if self.options.mps.use_online_calibration: ocalib = self.mps_data_provider.get_online_calibration( left_ts, TimeQueryOptions.CLOSEST ) @@ -120,18 +133,18 @@ def _ts_from_vrs(self, sid: StreamId) -> List[int]: return sorted(self.vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME)) def _get_images(self) -> List[Tuple[Path, Path]]: - left_img_dir = self.cfg.image_stream_path / "left" - right_img_dir = self.cfg.image_stream_path / "right" + left_img_dir = self.options.paths.images / "left" + right_img_dir = self.options.paths.images / "right" left_images = self._images_from_vrs(left_img_dir, left_img_dir) right_images = self._images_from_vrs(right_img_dir, right_img_dir) return list(zip(left_images, right_images)) - def _get_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: - if not self.cfg.flags.has_slam_drops: - L = self._ts_from_vrs(self.left_cam_stream_id) - R = self._ts_from_vrs(self.right_cam_stream_id) + def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: + if not self.options.mps.has_slam_drops: + L = self._ts_from_vrs(self.options.sensor.left_cam_stream_id) + R = self._ts_from_vrs(self.options.sensor.right_cam_stream_id) assert len(L) == len(R), "Unequal number of left and right timestamps" matched = list(zip(L, R)) if not all(abs(l - r) < max_diff for l, r in matched): @@ -144,8 +157,8 @@ def _get_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: return matched def _match_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: - L = self._ts_from_vrs(self.left_cam_stream_id) - R = self._ts_from_vrs(self.right_cam_stream_id) + L = self._ts_from_vrs(self.options.sensor.left_cam_stream_id) + R = self._ts_from_vrs(self.options.sensor.right_cam_stream_id) # matching timestamps is only when we have slam drops assert len(L) > 0 and len(R) > 0 and len(L) != len(R), \ @@ -178,7 +191,7 @@ def _get_dummy_imu_params(self) -> List: def _add_device_sensors(self) -> None: device_calibration = self.vrs_provider.get_device_calibration() imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.imu_stream_id + self.options.sensor.right_imu_stream_id ) imu_calib = device_calibration.get_imu_calib( imu_stream_label @@ -190,7 +203,7 @@ def _add_device_sensors(self) -> None: # DUMMY CAMERA FOR IMU, IMU ID is 1 imu = pycolmap.Camera( camera_id=1, - model=self.cfg.camera.model, + model=self.options.sensor.camera_model, width=w, height=h, params=p, @@ -198,7 +211,10 @@ def _add_device_sensors(self) -> None: self.empty_recons.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) - for cam_id, sid in [(2, self.left_cam_stream_id), (3, self.right_cam_stream_id)]: + for cam_id, sid in \ + [(2, self.options.sensor.left_cam_stream_id), + (3, self.options.sensor.right_cam_stream_id) + ]: stream_label = self.vrs_provider.get_label_from_stream_id( sid ) @@ -236,7 +252,7 @@ def _add_online_sensors(self) -> None: # DUMMY CAMERA FOR IMU imu = pycolmap.Camera( camera_id=sensor_id, - model=self.cfg.camera.model, + model=self.options.sensor.camera_model, width=w, height=h, params=p, @@ -246,7 +262,7 @@ def _add_online_sensors(self) -> None: sensor_id += 1 imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.imu_stream_id + self.options.sensor.right_imu_stream_id ) imu_calib = None for calib in calibration.imu_calibs: @@ -254,7 +270,9 @@ def _add_online_sensors(self) -> None: imu_calib = calib break - for sid in [self.left_cam_stream_id, self.right_cam_stream_id]: + for sid in \ + [self.options.sensor.left_cam_stream_id, self.options.sensor.right_cam_stream_id + ]: stream_label = self.vrs_provider.get_label_from_stream_id( sid ) From b44706051afee57bd52dbbed6cf6da7d893f2686 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 23:14:11 +0200 Subject: [PATCH 136/665] ext --- lamaria/rig/keyframing/image_extraction.py | 30 ---------------------- 1 file changed, 30 deletions(-) delete mode 100644 lamaria/rig/keyframing/image_extraction.py diff --git a/lamaria/rig/keyframing/image_extraction.py b/lamaria/rig/keyframing/image_extraction.py deleted file mode 100644 index 0f8f937..0000000 --- a/lamaria/rig/keyframing/image_extraction.py +++ /dev/null @@ -1,30 +0,0 @@ -from __future__ import annotations - -from pathlib import Path - -from lamaria.rig.config.loaders import load_cfg -from ...utils.general import extract_images_from_vrs - - -def run( - image_stream_folder: Path, - vrs_path: Path, -) -> None: - - image_stream_folder.mkdir(parents=True, exist_ok=True) - extract_images_from_vrs( - vrs_file=vrs_path, - image_folder=image_stream_folder, - ) - - -def main() -> None: - cfg = load_cfg() - run( - image_stream_folder=cfg.image_stream_path, - vrs_path=cfg.vrs_file_path, - ) - - -if __name__ == "__main__": - main() From e0a1e57d9d3ceebed9683a67ef7463dd527461b0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 23:14:24 +0200 Subject: [PATCH 137/665] init data --- lamaria/rig/keyframing/vrs_to_colmap.py | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py index 6d686b5..788b505 100644 --- a/lamaria/rig/keyframing/vrs_to_colmap.py +++ b/lamaria/rig/keyframing/vrs_to_colmap.py @@ -68,14 +68,19 @@ def _init_data(self): ) images = self._get_images() - timestamps = self._get_timestamps() - closed_loop_data = get_closed_loop_data_from_mps(self.cfg.mps_path) - pose_timestamps = [ l for l, _ in timestamps ] - mps_poses = get_mps_poses_for_timestamps(closed_loop_data, pose_timestamps) - self.per_frame_data = self._build_per_frame_data(images, timestamps, mps_poses) - - def _build_per_frame_data(self, images, timestamps, mps_poses) -> List[PerFrameData]: + if self.options.mps.use_mps: + timestamps = self._get_mps_timestamps() + closed_loop_data = get_closed_loop_data_from_mps(self.options.paths.mps) + pose_timestamps = [ l for l, _ in timestamps ] + mps_poses = get_mps_poses_for_timestamps(closed_loop_data, pose_timestamps) + self.per_frame_data = self._build_per_frame_data_from_mps(images, timestamps, mps_poses) + else: + timestamps = self._get_estimate_timestamps() + if len(images) != len(timestamps): + images, timestamps = self._match_estimate_ts_to_images(images, timestamps) + + def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[PerFrameData]: per_frame_data = [] imu_stream_label = self.vrs_provider.get_label_from_stream_id( self.options.sensor.right_imu_stream_id From 82618bce671c17e28dec78511013e6805c44451a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 23:14:40 +0200 Subject: [PATCH 138/665] colmap --- lamaria/rig/keyframing/vrs_to_colmap.py | 56 +++++++++++++++++++++++++ 1 file changed, 56 insertions(+) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/vrs_to_colmap.py index 788b505..f0f1f34 100644 --- a/lamaria/rig/keyframing/vrs_to_colmap.py +++ b/lamaria/rig/keyframing/vrs_to_colmap.py @@ -6,6 +6,7 @@ import numpy as np import pycolmap from dataclasses import dataclass +from bisect import bisect_left import projectaria_tools.core.mps as mps from projectaria_tools.core import data_provider @@ -161,6 +162,61 @@ def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: return matched + def _get_estimate_timestamps(self): + assert self.options.paths.estimate is not None, \ + "Estimate path must be provided if MPS is not used" + + with open(self.options.paths.estimate, 'r') as f: + lines = f.readlines() + + timestamps = [] + for line in lines: + if line.startswith('#') or not line.strip(): + continue + + ts = round_ns(line.split()[0]) + timestamps.append(ts) + + return sorted(timestamps) + + def _match_estimate_ts_to_images( + self, + images: List[Tuple[Path, Path]], + est_timestamps: List[int], + max_diff: int = 1000000, # 1 ms + ) -> Tuple[List[Tuple[Path, Path]], List[int]]: + + left_ts = self._ts_from_vrs(self.options.sensor.left_cam_stream_id) + assert len(images) == len(left_ts), \ + "Number of images and left timestamps must be equal" + + order = sorted(range(len(left_ts)), key=lambda i: left_ts[i]) + left_ts = [left_ts[i] for i in order] + images = [images[i] for i in order] + + matched_images: List[Tuple[Path, Path]] = [] + matched_timestamps: List[int] = [] + + # estimate timestamps will be in nanoseconds like vrs timestamps + for est in est_timestamps: + idx = bisect_left(left_ts, est) + + cand_idxs = [] + if idx > 0: cand_idxs.append(idx - 1) + if idx < len(left_ts): cand_idxs.append(idx) + + if not cand_idxs: + continue + + best = min(cand_idxs, key=lambda j: abs(left_ts[j] - est)) + if (max_diff is not None) and (abs(left_ts[best] - est) > max_diff): + continue + + matched_images.append(images[best]) + matched_timestamps.append(left_ts[best]) + + return matched_images, matched_timestamps + def _match_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: L = self._ts_from_vrs(self.options.sensor.left_cam_stream_id) R = self._ts_from_vrs(self.options.sensor.right_cam_stream_id) From b1ab35153a19dab6c8a9edd73b7f17ef2c6f0cb1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 23:15:07 +0200 Subject: [PATCH 139/665] iii --- lamaria/rig/keyframing/{vrs_to_colmap.py => to_colmap.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename lamaria/rig/keyframing/{vrs_to_colmap.py => to_colmap.py} (100%) diff --git a/lamaria/rig/keyframing/vrs_to_colmap.py b/lamaria/rig/keyframing/to_colmap.py similarity index 100% rename from lamaria/rig/keyframing/vrs_to_colmap.py rename to lamaria/rig/keyframing/to_colmap.py From ac4953b1e3191f264e63fb1416054677af09979a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 23:45:39 +0200 Subject: [PATCH 140/665] defs --- lamaria/rig/config/defaults.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 4f55673..06788da 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -71,3 +71,4 @@ optimization: mps: use_mps: false use_online_calibration: false # relevant only when use_mps is true (for online calib file) + has_slam_drops: false # check vrs json metadata file for each sequence From 343c1ae01a1eec35b41d94db5c0ff60b622e5ac0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 23:46:24 +0200 Subject: [PATCH 141/665] est --- lamaria/rig/keyframing/to_colmap.py | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index f0f1f34..4f94655 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -22,6 +22,7 @@ rigid3d_from_transform, get_closed_loop_data_from_mps, get_mps_poses_for_timestamps, + get_rig_from_worlds_from_estimate, extract_images_from_vrs, round_ns, ) @@ -80,6 +81,11 @@ def _init_data(self): timestamps = self._get_estimate_timestamps() if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images(images, timestamps) + + rig_from_worlds = get_rig_from_worlds_from_estimate( + self.options.paths.estimate, + ) + self.per_frame_data = self._build_per_frame_data_from_estimate(images, timestamps, rig_from_worlds) def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[PerFrameData]: per_frame_data = [] @@ -127,6 +133,23 @@ def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[ return per_frame_data + def _build_per_frame_data_from_estimate(self, images, timestamps, rig_from_worlds) -> List[PerFrameData]: + per_frame_data = [] + assert len(images) == len(timestamps) == len(rig_from_worlds), \ + "Number of images, timestamps and poses must be equal" + for (left_img, right_img), ts, rig_from_world \ + in zip(images, timestamps, rig_from_worlds): + pfd = PerFrameData( + left_ts=ts, + right_ts=ts, # right timestamp is not available in estimate + left_img=left_img, + right_img=right_img, + rig_from_world=rig_from_world + ) + per_frame_data.append(pfd) + + return per_frame_data + def _images_from_vrs(self, folder: Path, wrt_to: Path, ext: str =".jpg") -> List[Path]: if not folder.is_dir(): return [] From cfc20ebe8a6f06d7c86b5eadbe3da15575c9bbcf Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 21 Sep 2025 23:49:27 +0200 Subject: [PATCH 142/665] rig from worlds --- lamaria/utils/general.py | 25 ++++++++++++++++++++++++- 1 file changed, 24 insertions(+), 1 deletion(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 6a12626..2560381 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -306,11 +306,34 @@ def extract_images_from_vrs( logger.info("Done!") -def get_closed_loop_data_from_mps(mps_path: Path): +def get_closed_loop_data_from_mps(mps_path: Path) -> List[mps.ClosedLoopTrajectoryPose]: closed_loop_traj_file = mps_path / "slam" / "closed_loop_trajectory.csv" data = mps.read_closed_loop_trajectory(closed_loop_traj_file.as_posix()) return data +def get_rig_from_worlds_from_estimate( + estimate_path: Path +) -> List[pycolmap.Rigid3d]: + """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" + + rig_from_worlds = [] + with open(estimate_path, "r") as f: + lines = f.readlines() + for line in lines: + if line.startswith("#"): + continue + + parts = line.strip().split() + if len(parts) != 8: + continue + + tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) + qvec = np.array([float(parts[4]), float(parts[5]), float(parts[6]), float(parts[7])]) + pose = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) + rig_from_world = pose.inverse() + rig_from_worlds.append(rig_from_world) + + return rig_from_worlds def get_mps_poses_for_timestamps( trajectory_data: List[mps.ClosedLoopTrajectoryPose], From 00d17eabfafc880561db2f5a6db2c479502bfb7d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 00:27:55 +0200 Subject: [PATCH 143/665] upd with config --- lamaria/rig/keyframing/to_colmap.py | 58 ++++++++++++++++++----------- 1 file changed, 37 insertions(+), 21 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 4f94655..9be5a06 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -27,7 +27,7 @@ round_ns, ) from ...utils.imu import ( - get_online_imu_data_from_vrs + get_imu_data_from_vrs, ) @dataclass @@ -51,6 +51,9 @@ def __init__( def _init_io(self): """Initializes output and data providers""" self.empty_recons = pycolmap.Reconstruction() + output_base = self.options.paths.init_model.parent + output_base.mkdir(parents=True, exist_ok=True) + self.vrs_provider = data_provider.create_vrs_data_provider( self.options.paths.vrs.as_posix() ) @@ -433,34 +436,47 @@ def _add_online_frames(self) -> None: for im in images_to_add: self.empty_recons.add_image(im) - def _save_imu_measurements(self) -> None: - file_path = self.cfg.result.output_folder_path / self.cfg.result.rect_imu_file - if not self.cfg.optimization.use_device_calibration: - ms = get_online_imu_data_from_vrs( + def save_imu_measurements(self) -> Path: + """Saves rectified IMU measurements to a numpy file""" + if self.options.mps.use_online_calibration \ + and self.options.mps.use_mps: + ms = get_imu_data_from_vrs( + self.vrs_provider, + self.options.paths.mps, + ) + else: + ms = get_imu_data_from_vrs( self.vrs_provider, - self.cfg.mps_path, ) - np.save(file_path, ms.data) - # add device calib case if needed + + np.save(self.options.paths.rect_imu, ms.data) + + return self.options.paths.rect_imu def create(self) -> pycolmap.Reconstruction: - if self.cfg.optimization.use_device_calibration: - self._add_device_sensors() - self._add_device_frames() - else: + """Creates an empty COLMAP reconstruction with cameras and frames""" + if self.options.mps.use_online_calibration: self._add_online_sensors() self._add_online_frames() - - self._save_imu_measurements() + else: + self._add_device_sensors() + self._add_device_frames() return self.empty_recons - def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path) -> None: - output_path.parent.mkdir(parents=True, exist_ok=True) - logger.info(f"Init {recon.summary()}") - recon.write(output_path) + def write_reconstruction(self) -> Path: + recon_path = self.options.paths.init_model + recon_path.mkdir(parents=True, exist_ok=True) + + logger.info(f"Init {self.empty_recons.summary()}") + self.empty_recons.write(recon_path.as_posix()) - def write_full_timestamps(self, output_path: Path) -> None: - output_path.parent.mkdir(parents=True, exist_ok=True) + return recon_path + + def write_full_timestamps(self) -> Path: + ts_path = self.options.paths.full_ts + ts_path.parent.mkdir(parents=True, exist_ok=True) left_ts = np.array(sorted([pfd.left_ts for pfd in self.per_frame_data])) - np.save(output_path, left_ts) + np.save(ts_path, left_ts) + + return ts_path From 05991d47c63d115760c6a1ccf86af85040b5ffe3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 00:28:21 +0200 Subject: [PATCH 144/665] imu --- lamaria/utils/imu.py | 47 +++++++++++++++++++++++--------------------- 1 file changed, 25 insertions(+), 22 deletions(-) diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index ca3efd2..c8670fa 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -1,10 +1,9 @@ import pycolmap -import numpy as np +from typing import Optional from pathlib import Path from tqdm import tqdm from projectaria_tools.core import mps, data_provider from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions -from projectaria_tools.core.stream_id import StreamId from lamaria.utils.general import ( IMU_STREAM_ID, @@ -31,9 +30,9 @@ def get_online_params_for_imu_from_mps( return online_imu_calibs -def get_online_imu_data_from_vrs( +def get_imu_data_from_vrs( vrs_provider: data_provider.VrsDataProvider, - mps_folder: Path, + mps_folder: Optional[Path] = None, ): imu_timestamps = sorted( vrs_provider.get_timestamps_ns( @@ -43,29 +42,33 @@ def get_online_imu_data_from_vrs( ) imu_stream_label = vrs_provider.get_label_from_stream_id(IMU_STREAM_ID) - online_calibs_file = mps_folder / "slam" / "online_calibration.jsonl" - online_imu_calibs = get_online_params_for_imu_from_mps( - online_calibs_file, - imu_stream_label - ) - - acceptable_diff_ms = 1 # 1 milliseconds - - calib_timestamps = sorted(online_imu_calibs.keys()) + if mps_folder is not None: + online_calibs_file = mps_folder / "slam" / "online_calibration.jsonl" + online_imu_calibs = get_online_params_for_imu_from_mps( + online_calibs_file, + imu_stream_label + ) + acceptable_diff_ms = 1 # 1 milliseconds + calib_timestamps = sorted(online_imu_calibs.keys()) + else: + device_calib = vrs_provider.get_device_calibration() + calibration = device_calib.get_imu_calib(imu_stream_label) ms = pycolmap.ImuMeasurements() for timestamp in tqdm(imu_timestamps, desc="Loading rect IMU data"): - quantized_timestamp = timestamp // int(1e6) - closest_ts = find_closest_timestamp( - calib_timestamps, - quantized_timestamp, - acceptable_diff_ms - ) + if mps_folder is not None: + quantized_timestamp = timestamp // int(1e6) + closest_ts = find_closest_timestamp( + calib_timestamps, + quantized_timestamp, + acceptable_diff_ms + ) - if closest_ts not in online_imu_calibs: - raise ValueError(f"No calibration found for timestamp {timestamp}") + if closest_ts not in online_imu_calibs: + raise ValueError(f"No calibration found for timestamp {timestamp}") - calibration = online_imu_calibs[closest_ts] + calibration = online_imu_calibs[closest_ts] + imu_data = vrs_provider.get_imu_data_by_time_ns( IMU_STREAM_ID, timestamp, From fdc1108c84235d064cddcf52ad4c78cd7a4fb70c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 00:56:27 +0200 Subject: [PATCH 145/665] gen --- lamaria/utils/general.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 2560381..ff35e00 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -105,7 +105,7 @@ def get_t_cam_a_cam_b_from_json( def add_cameras_to_reconstruction( reconstruction: pycolmap.Reconstruction, calibration_file: Path, -): +) -> None: for i, (key, _) in enumerate(ARIA_CAMERAS): cam = camera_colmap_from_json( @@ -133,7 +133,7 @@ def add_cameras_to_reconstruction( reconstruction.add_rig(rig) -def get_qvec_and_tvec_from_transform(transform): +def get_qvec_and_tvec_from_transform(transform) -> Tuple[np.ndarray, np.ndarray]: """Returns qvec in format x,y,z,w and tvec in format x,y,z""" # to_quat() returns in wxyz format # https://github.com/facebookresearch/projectaria_tools/blob/867105e65cadbe777db355a407d90533c71d2d06/core/python/sophus/SO3PyBind.h#L161 @@ -165,7 +165,7 @@ def get_magnitude_from_transform(transform: pycolmap.Rigid3d) -> Tuple[float, fl def get_camera_params_for_colmap( camera_calibration: CameraCalibration, camera_model: str, -): +) -> List[float]: # params = [f_u {f_v} c_u c_v [k_0: k_{numK-1}] # {p_0 p_1} {s_0 s_1 s_2 s_3}] # projection_params is a 15 length vector, From 579bf3b158d10305883041e77413de08352e1427 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 00:58:11 +0200 Subject: [PATCH 146/665] est format --- lamaria/utils/general.py | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index ff35e00..641c1c2 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -261,6 +261,28 @@ def delete_files_in_folder(folder, exclude_pattern=None): else: os.makedirs(folder, exist_ok=True) +def check_estimate_format(estimate_path: Path) -> bool: + """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" + with open(estimate_path, "r") as f: + lines = f.readlines() + lines = [line for line in lines if not line.startswith("#")] + if not lines: + raise ValueError(f"Estimate file {estimate_path} is empty \ + or has no valid lines.") + + for line in lines: + parts = line.strip().split() + if len(parts) != 8: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values.") + + try: + [float(part) for part in parts] + except ValueError: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number.") + + return True def extract_images_from_vrs( vrs_file: Path, From eeb5127b32ac45e686e375ffd84d85be51f58de3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 00:58:28 +0200 Subject: [PATCH 147/665] flag --- lamaria/rig/keyframing/to_colmap.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 9be5a06..31bc8dd 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -25,6 +25,7 @@ get_rig_from_worlds_from_estimate, extract_images_from_vrs, round_ns, + check_estimate_format, ) from ...utils.imu import ( get_imu_data_from_vrs, @@ -85,6 +86,10 @@ def _init_data(self): if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images(images, timestamps) + flag = check_estimate_format(self.options.paths.estimate) + if not flag: + raise ValueError("Estimate file format is incorrect.") + rig_from_worlds = get_rig_from_worlds_from_estimate( self.options.paths.estimate, ) From 889ea69923d69f6c7c90dcb656d49f00c270e9c5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 01:00:59 +0200 Subject: [PATCH 148/665] def load --- lamaria/rig/config/loaders.py | 1 + 1 file changed, 1 insertion(+) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index d8adea4..fb4a3a8 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -20,6 +20,7 @@ def __init__(self, cfg: OmegaConf): def load_default( cls, ) -> 'Config': + """ Load default config from default file inside lamaria/rig/config/ """ return cls.load() @classmethod From c6db845f3dce06a4e83fa2d6dd4de7266059a6d3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 01:19:05 +0200 Subject: [PATCH 149/665] kf selectn --- lamaria/rig/keyframing/keyframe_selection.py | 63 ++++++++------------ 1 file changed, 25 insertions(+), 38 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 3ccbc2c..de811fa 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -10,36 +10,19 @@ import pycolmap from ... import logger -from ..config.loaders import load_cfg +from ..config.options import KeyframeSelectorOptions from ...utils.general import get_magnitude_from_transform -@dataclass(frozen=True) -class KFParams: - max_rotation_deg: float - max_distance_m: float - max_elapsed_ns: float - class KeyframeSelector: - def __init__(self, reconstruction: pycolmap.Reconstruction, timestamps: List[int], cfg=None): - self.init_recons = reconstruction - self.timestamps = timestamps - - cfg = load_cfg() if cfg is None else cfg - self.params = KFParams( - max_rotation_deg=float(cfg.keyframing.max_rotation), - max_distance_m=float(cfg.keyframing.max_distance), - max_elapsed_ns=float(cfg.keyframing.max_elapsed) * 1e9, # convert to ns - ) - - self.keyframes_dir = cfg.result.output_folder_path / cfg.result.keyframes - self.image_stream_root = cfg.image_stream_path + def __init__(self, options: KeyframeSelectorOptions): + self.options = options + self.init_recons = pycolmap.Reconstruction(self.options.paths.init_model) + self.timestamps = np.load(self.options.paths.full_ts).tolist() self.keyframed_recons = pycolmap.Reconstruction() self.keyframe_frame_ids: Optional[List[int]] = None - self.init_recon_type = "device" if len(self.init_recons.rigs) == 1 else "online" - def _select_keyframes(self): self.keyframe_frame_ids = [] dr_dt = np.array([0.0, 0.0]) @@ -59,9 +42,9 @@ def _select_keyframes(self): dr_dt += np.array(get_magnitude_from_transform(current_rig_from_previous_rig)) dts += self.timestamps[i+1] - self.timestamps[i] - if dr_dt[0] > self.params.max_rotation_deg or \ - dr_dt[1] > self.params.max_distance_m or \ - dts > self.params.max_elapsed_ns: + if dr_dt[0] > self.options.max_rotation or \ + dr_dt[1] > self.options.max_distance or \ + dts > self.options.max_elapsed: self.keyframe_frame_ids.append(curr) dr_dt = np.array([0.0, 0.0]) @@ -198,20 +181,22 @@ def _build_online_keyframed_reconstruction(self): rig_id += 1 def run_keyframing(self) -> pycolmap.Reconstruction: + """ Main function to run keyframing.""" self._select_keyframes() - if self.init_recon_type == "device": + if len(self.init_recons.rigs.keys()) == 1: # device rig has been added self._build_device_keyframed_reconstruction() else: self._build_online_keyframed_reconstruction() return self.keyframed_recons - def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: + def copy_images_to_keyframes_dir(self) -> Path: + """ Copy images corresponding to keyframes to a separate directory. """ if self.keyframe_frame_ids is None: raise ValueError("Keyframes not selected yet. Run `run_keyframing` first.") - if output_dir is None: - output_dir = self.keyframes_dir + output_dir = self.options.paths.keyframes + image_stream_root = self.options.paths.images if output_dir.exists() and any(output_dir.iterdir()): shutil.rmtree(output_dir) @@ -224,21 +209,23 @@ def copy_images_to_keyframes_dir(self, output_dir: Path = None) -> None: image = self.init_recons.images[data_id.id] subdir = "left" if "1201-1" in image.name else "right" - src_path = self.image_stream_root / subdir / image.name + src_path = image_stream_root / subdir / image.name dst_path = output_dir / image.name shutil.copy2(src_path, dst_path) + + return output_dir - def read_keyframe_timestamps(self, input_path: Path) -> None: - ts = np.load(input_path).tolist() - return ts - - def write_keyframe_timestamps(self, output_path: Path) -> None: + def write_keyframe_timestamps(self) -> Path: + output_path = self.options.paths.kf_ts output_path.parent.mkdir(parents=True, exist_ok=True) keyframed_timestamps = np.array([self.timestamps[i - 1] for i in self.keyframe_frame_ids]) np.save(output_path, keyframed_timestamps) + return output_path - def write_reconstruction(self, recon: pycolmap.Reconstruction, output_path: Path) -> None: + def write_reconstruction(self) -> Path: + output_path = self.options.paths.kf_model output_path.mkdir(parents=True, exist_ok=True) - logger.info(f"Keyframed {recon.summary()}") - recon.write(output_path) \ No newline at end of file + logger.info(f"Keyframed {self.keyframed_recons.summary()}") + self.keyframed_recons.write(output_path) + return output_path \ No newline at end of file From e2a9a8d41ad9332b0ac7a12272a3dfafd6ea3d5b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 10:18:36 +0200 Subject: [PATCH 150/665] base --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 06788da..d45d2af 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -8,7 +8,7 @@ paths: mps: mps/mps_${paths.seq_name}_vrs/ # necessary if use_mps is true output: - base: output/${paths.seq_name}/ + base: output/ images: image_stream/ init_model: empty_recon/ From b49709c10ac4734734f831ea734398cf89cf1f1c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 10:23:39 +0200 Subject: [PATCH 151/665] output base --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index d45d2af..06788da 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -8,7 +8,7 @@ paths: mps: mps/mps_${paths.seq_name}_vrs/ # necessary if use_mps is true output: - base: output/ + base: output/${paths.seq_name}/ images: image_stream/ init_model: empty_recon/ From 168abf18efc9effe14ecd362b1e5abeaefe5db95 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 10:24:35 +0200 Subject: [PATCH 152/665] run pip --- scripts/run_pipeline.py | 57 ----------------------------------------- 1 file changed, 57 deletions(-) delete mode 100644 scripts/run_pipeline.py diff --git a/scripts/run_pipeline.py b/scripts/run_pipeline.py deleted file mode 100644 index c634c00..0000000 --- a/scripts/run_pipeline.py +++ /dev/null @@ -1,57 +0,0 @@ -import sys -import numpy as np -from lamaria.rig.config.loaders import load_cfg -from lamaria.rig.keyframing.vrs_to_colmap import VrsToColmap -from lamaria.rig.keyframing.image_extraction import run as run_extraction -from lamaria.rig.keyframing.keyframe_selection import KeyframeSelector -from lamaria.rig.optim.triangulation import run as run_triangulation -from lamaria.rig.optim.session import SingleSeqSession -from lamaria.rig.optim.vi_optimization import run as run_vi_optimization - - - -def run_pipeline(): - cfg = load_cfg(cli_overrides=sys.argv[1:]) - seq_builder = VrsToColmap(cfg) - - run_extraction( - image_stream_folder=cfg.image_stream_path, - vrs_path=cfg.vrs_file_path, - ) - recon = seq_builder.create() - - out_dir = cfg.result.output_folder_path / cfg.result.init_model - out_dir.mkdir(parents=True, exist_ok=True) - seq_builder.write_reconstruction(recon, out_dir) - seq_builder.write_full_timestamps(cfg.result.output_folder_path / cfg.result.full_ts) - - timestamps = np.load(cfg.result.output_folder_path / cfg.result.full_ts).tolist() - - kf_selector = KeyframeSelector(reconstruction=recon, timestamps=timestamps, cfg=cfg) - kf_recon = kf_selector.run_keyframing() - kf_selector.write_reconstruction(kf_recon, cfg.result.output_folder_path / cfg.result.kf_model) - kf_selector.copy_images_to_keyframes_dir() - kf_selector.write_keyframe_timestamps(cfg.result.output_folder_path / cfg.result.kf_ts) - triangulated_model_path = run_triangulation(cfg=cfg) - - timestamps = kf_selector.read_keyframe_timestamps(cfg.result.output_folder_path / cfg.result.kf_ts) - rect_imu_file = cfg.result.output_folder_path / cfg.result.rect_imu_file - if not rect_imu_file.exists(): - raise FileNotFoundError(f"Rectified IMU file not found at {rect_imu_file}") - - session = SingleSeqSession( - reconstruction=kf_recon, - timestamps=timestamps, - rect_imu_file=rect_imu_file, - ) - optimized_recon = run_vi_optimization( - session=session, - database_path=triangulated_model_path / "database.db", - output_folder=cfg.result.output_folder_path / cfg.result.optim_model, - ) - - - - -if __name__ == "__main__": - run_pipeline() From 91569c924b8d9148b4ba761db2123d2f287c04f4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 11:36:40 +0200 Subject: [PATCH 153/665] options --- lamaria/rig/config/options.py | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 3d4bad0..cf188e3 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -2,7 +2,7 @@ from dataclasses import dataclass, field, replace from pathlib import Path -from typing import Optional +from typing import Optional, Any import pycolmap from omegaconf import OmegaConf @@ -87,6 +87,7 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> PathOptions: class MPSOptions: use_mps: bool = False use_online_calibration: bool = False # when use_mps is true (for online calib file) + has_slam_drops: bool = False # check vrs json metadata file for each sequence @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> MPSOptions: @@ -97,23 +98,17 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> MPSOptions: @dataclass(frozen=True, slots=True) class SensorOptions: - left_cam_stream_id: StreamId = StreamId("1201-1") - right_cam_stream_id: StreamId = StreamId("1201-2") - right_imu_stream_id: StreamId = StreamId("1202-1") + left_cam_stream_id: str = "1201-1" + right_cam_stream_id: str = "1201-2" + right_imu_stream_id: str = "1202-1" camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> SensorOptions: + def load(cls, cfg: Optional[OmegaConf] = None) -> "SensorOptions": if cfg is None or not hasattr(cfg, 'sensor'): return cls() obj: SensorOptions = _structured_merge_to_obj(cls, cfg.sensor) - if not isinstance(obj.left_cam_stream_id, StreamId): - object.__setattr__(obj, "left_cam_stream_id", StreamId(str(obj.left_cam_stream_id))) - if not isinstance(obj.right_cam_stream_id, StreamId): - object.__setattr__(obj, "right_cam_stream_id", StreamId(str(obj.right_cam_stream_id))) - if not isinstance(obj.right_imu_stream_id, StreamId): - object.__setattr__(obj, "right_imu_stream_id", StreamId(str(obj.right_imu_stream_id))) return obj # To COLMAP options From b91fe29d749c0a69473e76c80312314eee57a45f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 11:39:26 +0200 Subject: [PATCH 154/665] keyframe selection --- lamaria/rig/keyframing/keyframe_selection.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index de811fa..2b258b4 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -15,9 +15,13 @@ class KeyframeSelector: - def __init__(self, options: KeyframeSelectorOptions): + def __init__( + self, + options: KeyframeSelectorOptions, + reconstruction: pycolmap.Reconstruction + ): self.options = options - self.init_recons = pycolmap.Reconstruction(self.options.paths.init_model) + self.init_recons = reconstruction self.timestamps = np.load(self.options.paths.full_ts).tolist() self.keyframed_recons = pycolmap.Reconstruction() From a0743895ca8204c3e4edec0619d16fd552d55f09 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 13:52:02 +0200 Subject: [PATCH 155/665] to colmap --- lamaria/rig/keyframing/to_colmap.py | 32 ++++++++++++++++++----------- 1 file changed, 20 insertions(+), 12 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 31bc8dd..0c6bf5f 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -64,6 +64,10 @@ def _init_io(self): else: assert self.options.paths.estimate is not None, \ "Estimate path must be provided if MPS is not used" + + self.left_cam_stream_id = StreamId(self.options.sensor.left_cam_stream_id) + self.right_cam_stream_id = StreamId(self.options.sensor.right_cam_stream_id) + self.right_imu_stream_id = StreamId(self.options.sensor.right_imu_stream_id) def _init_data(self): """Extracts images, timestamps and builds per-frame data""" @@ -98,7 +102,7 @@ def _init_data(self): def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[PerFrameData]: per_frame_data = [] imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.options.sensor.right_imu_stream_id + self.right_imu_stream_id ) if not self.options.mps.use_online_calibration: @@ -180,8 +184,8 @@ def _get_images(self) -> List[Tuple[Path, Path]]: def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: if not self.options.mps.has_slam_drops: - L = self._ts_from_vrs(self.options.sensor.left_cam_stream_id) - R = self._ts_from_vrs(self.options.sensor.right_cam_stream_id) + L = self._ts_from_vrs(self.left_cam_stream_id) + R = self._ts_from_vrs(self.right_cam_stream_id) assert len(L) == len(R), "Unequal number of left and right timestamps" matched = list(zip(L, R)) if not all(abs(l - r) < max_diff for l, r in matched): @@ -216,8 +220,8 @@ def _match_estimate_ts_to_images( est_timestamps: List[int], max_diff: int = 1000000, # 1 ms ) -> Tuple[List[Tuple[Path, Path]], List[int]]: - - left_ts = self._ts_from_vrs(self.options.sensor.left_cam_stream_id) + + left_ts = self._ts_from_vrs(self.left_cam_stream_id) assert len(images) == len(left_ts), \ "Number of images and left timestamps must be equal" @@ -249,8 +253,8 @@ def _match_estimate_ts_to_images( return matched_images, matched_timestamps def _match_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: - L = self._ts_from_vrs(self.options.sensor.left_cam_stream_id) - R = self._ts_from_vrs(self.options.sensor.right_cam_stream_id) + L = self._ts_from_vrs(self.left_cam_stream_id) + R = self._ts_from_vrs(self.right_cam_stream_id) # matching timestamps is only when we have slam drops assert len(L) > 0 and len(R) > 0 and len(L) != len(R), \ @@ -283,7 +287,7 @@ def _get_dummy_imu_params(self) -> List: def _add_device_sensors(self) -> None: device_calibration = self.vrs_provider.get_device_calibration() imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.options.sensor.right_imu_stream_id + self.right_imu_stream_id ) imu_calib = device_calibration.get_imu_calib( imu_stream_label @@ -304,8 +308,8 @@ def _add_device_sensors(self) -> None: rig.add_ref_sensor(imu.sensor_id) for cam_id, sid in \ - [(2, self.options.sensor.left_cam_stream_id), - (3, self.options.sensor.right_cam_stream_id) + [(2, self.left_cam_stream_id), + (3, self.right_cam_stream_id) ]: stream_label = self.vrs_provider.get_label_from_stream_id( sid @@ -354,7 +358,7 @@ def _add_online_sensors(self) -> None: sensor_id += 1 imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.options.sensor.right_imu_stream_id + self.right_imu_stream_id ) imu_calib = None for calib in calibration.imu_calibs: @@ -363,7 +367,7 @@ def _add_online_sensors(self) -> None: break for sid in \ - [self.options.sensor.left_cam_stream_id, self.options.sensor.right_cam_stream_id + [self.left_cam_stream_id, self.right_cam_stream_id ]: stream_label = self.vrs_provider.get_label_from_stream_id( sid @@ -469,7 +473,11 @@ def create(self) -> pycolmap.Reconstruction: return self.empty_recons + def get_full_timestamps(self) -> List[int]: + return sorted([pfd.left_ts for pfd in self.per_frame_data]) + def write_reconstruction(self) -> Path: + """Writes the empty reconstruction. Returns the path to the reconstruction folder.""" recon_path = self.options.paths.init_model recon_path.mkdir(parents=True, exist_ok=True) From 9c7587b955afc8b1a440a87a78c23dbe4c35037f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 14:17:46 +0200 Subject: [PATCH 156/665] loaders --- lamaria/rig/config/loaders.py | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index fb4a3a8..d30cba5 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -1,10 +1,8 @@ -from pathlib import Path -from typing import Optional, Sequence, Tuple +from typing import Optional, Sequence from omegaconf import OmegaConf from .options import ( MPSOptions, - PathOptions, SensorOptions, ToColmapOptions, VIOptimizerOptions, @@ -39,10 +37,6 @@ def load( OmegaConf.resolve(config) return cls(config) - - def get_paths(self) -> PathOptions: - """ Get resolved paths from config. """ - return PathOptions.load(self.config) def get_mps_options(self) -> MPSOptions: """ Get MPS options from config. """ From a8c2cea992abb277ef3adeeb806a6dd8a08a9a98 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 14:28:08 +0200 Subject: [PATCH 157/665] loaders --- lamaria/rig/config/loaders.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index d30cba5..d6b2bca 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -3,6 +3,7 @@ from .options import ( MPSOptions, + PathOptions, SensorOptions, ToColmapOptions, VIOptimizerOptions, @@ -38,6 +39,10 @@ def load( OmegaConf.resolve(config) return cls(config) + def get_path_options(self) -> PathOptions: + """ Get path options from config. """ + return PathOptions.load(self.config) + def get_mps_options(self) -> MPSOptions: """ Get MPS options from config. """ return MPSOptions.load(self.config) From a954a7de5f532042c896beb5b6a84041c8ff3280 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 14:31:23 +0200 Subject: [PATCH 158/665] l --- lamaria/rig/config/loaders.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index d6b2bca..b72d826 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -5,7 +5,7 @@ MPSOptions, PathOptions, SensorOptions, - ToColmapOptions, + EstimateToColmapOptions, VIOptimizerOptions, TriangulatorOptions, KeyframeSelectorOptions, @@ -51,9 +51,9 @@ def get_sensor_options(self) -> SensorOptions: """ Get sensor options from config. """ return SensorOptions.load(self.config) - def get_to_colmap_options(self) -> ToColmapOptions: + def get_estimate_to_colmap_options(self) -> EstimateToColmapOptions: """ Get options for to_colmap pipeline from config. """ - return ToColmapOptions.load(self.config) + return EstimateToColmapOptions.load(self.config) def get_keyframing_options(self) -> KeyframeSelectorOptions: """ Get keyframing options from config. """ From 414cb8d9359c1778910aa91ab70b9151b5c44d37 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 14:31:32 +0200 Subject: [PATCH 159/665] est --- lamaria/rig/config/options.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index cf188e3..7c59427 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -113,13 +113,13 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "SensorOptions": # To COLMAP options @dataclass(frozen=True, slots=True) -class ToColmapOptions: +class EstimateToColmapOptions: paths: PathOptions = field(default_factory=PathOptions) mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> ToColmapOptions: + def load(cls, cfg: Optional[OmegaConf] = None) -> EstimateToColmapOptions: if cfg is None: return cls( paths=PathOptions(), From b05d5e19cf52c8ef55c94697bffe7eb2929023ec Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 14:32:08 +0200 Subject: [PATCH 160/665] to colmap --- lamaria/rig/keyframing/to_colmap.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 0c6bf5f..da40ba1 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -14,7 +14,7 @@ from projectaria_tools.core.stream_id import StreamId from ... import logger -from ..config.options import ToColmapOptions +from ..config.options import EstimateToColmapOptions from ...utils.general import ( find_closest_timestamp, get_t_imu_camera, @@ -43,7 +43,7 @@ class PerFrameData: class ToColmap: def __init__( self, - options: ToColmapOptions + options: EstimateToColmapOptions ): self.options = options self._init_io() From e9e6db38085abd15e340d0933928974d800b99e0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 14:35:16 +0200 Subject: [PATCH 161/665] removed init model not needed --- lamaria/rig/config/defaults.yaml | 2 -- 1 file changed, 2 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 06788da..f901b5b 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -11,8 +11,6 @@ paths: base: output/${paths.seq_name}/ images: image_stream/ - init_model: empty_recon/ - keyframes: keyframes/ kf_model: keyframe_recon/ From 577c8a883208281181cfb3b08588476e896f75b4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 14:42:43 +0200 Subject: [PATCH 162/665] options --- lamaria/rig/config/options.py | 98 +++-------------------------------- 1 file changed, 7 insertions(+), 91 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 7c59427..af39ea3 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -1,87 +1,13 @@ from __future__ import annotations from dataclasses import dataclass, field, replace -from pathlib import Path -from typing import Optional, Any +from typing import Optional import pycolmap from omegaconf import OmegaConf -from projectaria_tools.core.stream_id import StreamId -from .helpers import _p, _structured_merge_to_obj +from .helpers import _structured_merge_to_obj -@dataclass(slots=True) -class PathOptions: - vrs: Optional[Path] = None - estimate: Optional[Path] = None - init_model: Optional[Path] = None - images: Optional[Path] = None - full_ts: Optional[Path] = None - mps: Optional[Path] = None - - rect_imu: Optional[Path] = None - - keyframes: Optional[Path] = None - kf_model: Optional[Path] = None - kf_ts: Optional[Path] = None - - hloc: Optional[Path] = None - pairs_file: Optional[Path] = None - tri_model: Optional[Path] = None - - optim_model: Optional[Path] = None - - @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> PathOptions: - """ - Build PathOptions from `paths:` block, resolving relative paths - against `paths.base` and `paths.output.base`. - Layout from defaults.yaml. - """ - if cfg is None or not hasattr(cfg, 'paths'): - return cls() - - cfg_paths = cfg.paths - base_root = Path(cfg_paths.base).resolve() - out_root = _p(cfg_paths.output.base, base_root) - - vrs = _p(cfg_paths.vrs, base_root) - estimate = _p(cfg_paths.estimate, base_root) - mps = _p(cfg_paths.mps, base_root) - - images = _p(cfg_paths.output.images, out_root) - init_model = _p(cfg_paths.output.init_model, out_root) - - keyframes = _p(cfg_paths.output.keyframes, out_root) - kf_model = _p(cfg_paths.output.kf_model, out_root) - - hloc = _p(cfg_paths.output.hloc, out_root) - pairs_file = _p(cfg_paths.output.pairs_file, hloc) - - tri_model = _p(cfg_paths.output.tri_model, out_root) - optim_model= _p(cfg_paths.output.optim_model, out_root) - - full_ts = _p(cfg_paths.output.full_ts, out_root) - kf_ts = _p(cfg_paths.output.kf_ts, out_root) - rect_imu= _p(cfg_paths.output.rect_imu, out_root) - - return cls( - vrs=vrs, - estimate=estimate, - init_model=init_model, - images=images, - full_ts=full_ts, - mps=mps, - rect_imu=rect_imu, - keyframes=keyframes, - kf_model=kf_model, - kf_ts=kf_ts, - hloc=hloc, - pairs_file=pairs_file, - tri_model=tri_model, - optim_model=optim_model, - ) - # General options @dataclass(frozen=True, slots=True) class MPSOptions: @@ -114,7 +40,6 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "SensorOptions": # To COLMAP options @dataclass(frozen=True, slots=True) class EstimateToColmapOptions: - paths: PathOptions = field(default_factory=PathOptions) mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) @@ -122,13 +47,11 @@ class EstimateToColmapOptions: def load(cls, cfg: Optional[OmegaConf] = None) -> EstimateToColmapOptions: if cfg is None: return cls( - paths=PathOptions(), mps=MPSOptions(), sensor=SensorOptions(), ) return cls( - paths=PathOptions.load(cfg), mps=MPSOptions.load(cfg), sensor=SensorOptions.load(cfg), ) @@ -136,8 +59,6 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> EstimateToColmapOptions: # Keyframing options @dataclass(frozen=True, slots=True) class KeyframeSelectorOptions: - paths: PathOptions = field(default_factory=PathOptions) - max_rotation: float = 20.0 # degrees max_distance: float = 1.0 # meters max_elapsed: int = int(1e9) # 1 second in ns @@ -145,7 +66,7 @@ class KeyframeSelectorOptions: @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": if cfg is None or not hasattr(cfg, 'keyframing'): - return cls(paths=PathOptions()) + return cls() section = { "max_rotation": float(cfg.keyframing.max_rotation), @@ -153,14 +74,12 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": "max_elapsed": int(float(cfg.keyframing.max_elapsed)), } obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, section) - return replace(obj, paths=PathOptions.load(cfg)) + return obj # Triangulation options @dataclass(frozen=True, slots=True) class TriangulatorOptions: - paths: PathOptions = field(default_factory=PathOptions) - feature_conf: str = "aliked-n16" matcher_conf: str = "aliked+lightglue" retrieval_conf: str = "netvlad" @@ -177,10 +96,10 @@ class TriangulatorOptions: @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "TriangulatorOptions": if cfg is None or not hasattr(cfg, 'triangulation'): - return cls(paths=PathOptions()) + return cls() obj: TriangulatorOptions = _structured_merge_to_obj(cls, cfg.triangulation) - return replace(obj, paths=PathOptions.load(cfg)) + return obj # Optimization options @dataclass(frozen=True, slots=True) @@ -208,8 +127,6 @@ class OptOptions: @dataclass(frozen=True, slots=True) class VIOptimizerOptions: - paths: PathOptions = field(default_factory=PathOptions) - cam: OptCamOptions = field(default_factory=OptCamOptions) imu: OptIMUOptions = field(default_factory=OptIMUOptions) optim: OptOptions = field(default_factory=OptOptions) @@ -220,7 +137,7 @@ class VIOptimizerOptions: @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": if cfg is None or not hasattr(cfg, 'optimization'): - return cls(paths=PathOptions()) + return cls() base: VIOptimizerOptions = OmegaConf.to_object(OmegaConf.structured(cls)) opt = cfg.optimization @@ -246,7 +163,6 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": # leave colmap_pipeline as default return replace( base, - paths=PathOptions.load(cfg), cam=cam, imu=imu, optim=optim, From 7d04ccb5e0fa924b8720d156441e5e0210ce2814 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 15:16:18 +0200 Subject: [PATCH 163/665] lamaria reconstruction --- .../rig/keyframing/lamaria_reconstruction.py | 31 +++++++++++++++++++ 1 file changed, 31 insertions(+) create mode 100644 lamaria/rig/keyframing/lamaria_reconstruction.py diff --git a/lamaria/rig/keyframing/lamaria_reconstruction.py b/lamaria/rig/keyframing/lamaria_reconstruction.py new file mode 100644 index 0000000..d4efba6 --- /dev/null +++ b/lamaria/rig/keyframing/lamaria_reconstruction.py @@ -0,0 +1,31 @@ +import pycolmap +from typing import List +from pathlib import Path + +class LamariaReconstruction: + reconstruction: pycolmap.Reconstruction + timestamps: List[int] + + def read_reconstruction_with_timestamps( + self, + input_folder: Path, + ) -> "LamariaReconstruction": + assert input_folder.exists(), f"Input folder {input_folder} does not exist" + self.reconstruction = pycolmap.Reconstruction(input_folder) + ts_path = input_folder / "timestamps.txt" + assert ts_path.exists(), f"Timestamps file {ts_path} does not exist in {input_folder}" + with open(ts_path, 'r') as f: + self.timestamps = [int(line.strip()) for line in f if line.strip().isdigit()] + + return self + + def write_reconstruction_with_timestamps( + self, + output_folder: Path, + ) -> None: + output_folder.mkdir(parents=True, exist_ok=True) + self.reconstruction.write(output_folder.as_posix()) + ts_path = output_folder / "timestamps.txt" + with open(ts_path, 'w') as f: + for ts in self.timestamps: + f.write(f"{ts}\n") \ No newline at end of file From 73acb177e4823c886006433d8d7248c543977ea7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 15:22:54 +0200 Subject: [PATCH 164/665] lamaria reconstructioin --- lamaria/rig/keyframing/lamaria_reconstruction.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/keyframing/lamaria_reconstruction.py b/lamaria/rig/keyframing/lamaria_reconstruction.py index d4efba6..994df54 100644 --- a/lamaria/rig/keyframing/lamaria_reconstruction.py +++ b/lamaria/rig/keyframing/lamaria_reconstruction.py @@ -6,18 +6,19 @@ class LamariaReconstruction: reconstruction: pycolmap.Reconstruction timestamps: List[int] + @classmethod def read_reconstruction_with_timestamps( - self, + cls, input_folder: Path, ) -> "LamariaReconstruction": assert input_folder.exists(), f"Input folder {input_folder} does not exist" - self.reconstruction = pycolmap.Reconstruction(input_folder) + instance = cls() + instance.reconstruction = pycolmap.Reconstruction(input_folder) ts_path = input_folder / "timestamps.txt" assert ts_path.exists(), f"Timestamps file {ts_path} does not exist in {input_folder}" with open(ts_path, 'r') as f: - self.timestamps = [int(line.strip()) for line in f if line.strip().isdigit()] - - return self + instance.timestamps = [int(line.strip()) for line in f if line.strip().isdigit()] + return instance def write_reconstruction_with_timestamps( self, From 977cb4003c16530d13b245bacfe8e6bdba489a43 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 15:37:04 +0200 Subject: [PATCH 165/665] lamaria recons --- .../lamaria_reconstruction.py | 25 ++++++++++++++++--- 1 file changed, 22 insertions(+), 3 deletions(-) rename lamaria/rig/{keyframing => }/lamaria_reconstruction.py (53%) diff --git a/lamaria/rig/keyframing/lamaria_reconstruction.py b/lamaria/rig/lamaria_reconstruction.py similarity index 53% rename from lamaria/rig/keyframing/lamaria_reconstruction.py rename to lamaria/rig/lamaria_reconstruction.py index 994df54..8ad65a1 100644 --- a/lamaria/rig/keyframing/lamaria_reconstruction.py +++ b/lamaria/rig/lamaria_reconstruction.py @@ -1,26 +1,41 @@ +import numpy as np import pycolmap from typing import List from pathlib import Path +from .. import logger + class LamariaReconstruction: reconstruction: pycolmap.Reconstruction timestamps: List[int] + imu_measurements: pycolmap.ImuMeasurements @classmethod - def read_reconstruction_with_timestamps( + def read_reconstruction( cls, input_folder: Path, ) -> "LamariaReconstruction": assert input_folder.exists(), f"Input folder {input_folder} does not exist" instance = cls() instance.reconstruction = pycolmap.Reconstruction(input_folder) + ts_path = input_folder / "timestamps.txt" assert ts_path.exists(), f"Timestamps file {ts_path} does not exist in {input_folder}" with open(ts_path, 'r') as f: instance.timestamps = [int(line.strip()) for line in f if line.strip().isdigit()] + + rectified_imu_data_npy = input_folder / "rectified_imu_data.npy" + assert rectified_imu_data_npy.exists(), \ + f"Rectified IMU data file {rectified_imu_data_npy} \ + does not exist in {input_folder}" + rectified_imu_data = np.load(rectified_imu_data_npy, allow_pickle=True) + instance.imu_measurements = pycolmap.ImuMeasurements(rectified_imu_data.tolist()) + + logger.info(f"Reconstruction read from {input_folder}") + return instance - def write_reconstruction_with_timestamps( + def write_reconstruction( self, output_folder: Path, ) -> None: @@ -29,4 +44,8 @@ def write_reconstruction_with_timestamps( ts_path = output_folder / "timestamps.txt" with open(ts_path, 'w') as f: for ts in self.timestamps: - f.write(f"{ts}\n") \ No newline at end of file + f.write(f"{ts}\n") + + rectified_imu_data_npy = output_folder / "rectified_imu_data.npy" + np.save(rectified_imu_data_npy, self.imu_measurements.data) + logger.info(f"Reconstruction written to {output_folder}") \ No newline at end of file From c8a07bbacbe60162a7bdecb5a5f2b5644ad290d8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 15:41:17 +0200 Subject: [PATCH 166/665] imu get data --- lamaria/utils/imu.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index c8670fa..299dc94 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -33,7 +33,9 @@ def get_online_params_for_imu_from_mps( def get_imu_data_from_vrs( vrs_provider: data_provider.VrsDataProvider, mps_folder: Optional[Path] = None, -): +) -> pycolmap.ImuMeasurements: + """ Get rectified IMU data from VRS file. If mps_folder is provided, use online + calibration data from MPS folder. Otherwise, use device calibration from VRS file. """ imu_timestamps = sorted( vrs_provider.get_timestamps_ns( IMU_STREAM_ID, From b44619b7fb2b9c691c838ae7cb6c4af08757d83d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 15:41:29 +0200 Subject: [PATCH 167/665] renane --- lamaria/rig/keyframing/to_colmap.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index da40ba1..18c8296 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -40,7 +40,7 @@ class PerFrameData: rig_from_world: pycolmap.Rigid3d -class ToColmap: +class EstimateToColmap: def __init__( self, options: EstimateToColmapOptions From eead33979ab08b74ec77fb40ca4969140960c16c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 16:01:58 +0200 Subject: [PATCH 168/665] defs --- lamaria/rig/config/defaults.yaml | 40 ++++++++++++++------------------ 1 file changed, 17 insertions(+), 23 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index f901b5b..15fb024 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -1,39 +1,32 @@ -paths: - base: /media/arialamar/ - seq_name: 5cp +# Default configuration for lamaria rig pipeline - vrs: recordings/${paths.seq_name}.vrs - estimate: estimates/${paths.seq_name}.txt +base: /media/arialamar/ +seq_name: 5cp - mps: mps/mps_${paths.seq_name}_vrs/ # necessary if use_mps is true +estimate_to_colmap: + vrs: recordings/${seq_name}.vrs + estimate: est/${seq_name}.txt + mps: mps/mps_${seq_name}_vrs/ # necessary if use_mps is true - output: - base: output/${paths.seq_name}/ - images: image_stream/ - - keyframes: keyframes/ - kf_model: keyframe_recon/ - - hloc: hloc/ - pairs_file: pairs.txt - - tri_model: triangulated_recon/ - optim_model: optim_recon/ - - full_ts: timestamps/full.npy - kf_ts: timestamps/keyframe.npy - - rect_imu: rect_imu.npy + base: output/${seq_name}/ + images: image_stream sensor: camera_model: RAD_TAN_THIN_PRISM_FISHEYE keyframing: + keyframes: keyframes + kf_model: keyframe_recon + max_rotation: 20.0 max_distance: 1.0 max_elapsed: 1e9 # 1 second in ns triangulation: + hloc: hloc + pairs_file: pairs.txt + tri_model: triangulated_recon + feature_conf: aliked-n16 matcher_conf: aliked+lightglue retrieval_conf: netvlad @@ -50,6 +43,7 @@ triangulation: filter_min_tri_angle: 1.5 optimization: + optim_model: optim_recon use_callback: true max_num_iterations: 10 normalize_reconstruction: false From 816855359a50d8dc3bf849afe530854e1dc1b85e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 17:52:45 +0200 Subject: [PATCH 169/665] options --- lamaria/rig/config/options.py | 48 +++++++++++++++-------------------- 1 file changed, 21 insertions(+), 27 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index af39ea3..842d750 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -40,6 +40,7 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "SensorOptions": # To COLMAP options @dataclass(frozen=True, slots=True) class EstimateToColmapOptions: + images: str = "image_stream" mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) @@ -52,6 +53,7 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> EstimateToColmapOptions: ) return cls( + images=cfg.estimate_to_colmap.images, mps=MPSOptions.load(cfg), sensor=SensorOptions.load(cfg), ) @@ -59,6 +61,9 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> EstimateToColmapOptions: # Keyframing options @dataclass(frozen=True, slots=True) class KeyframeSelectorOptions: + keyframes: str = "keyframes" + kf_model: str = "keyframe_recon" + max_rotation: float = 20.0 # degrees max_distance: float = 1.0 # meters max_elapsed: int = int(1e9) # 1 second in ns @@ -67,19 +72,22 @@ class KeyframeSelectorOptions: def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": if cfg is None or not hasattr(cfg, 'keyframing'): return cls() - - section = { - "max_rotation": float(cfg.keyframing.max_rotation), - "max_distance": float(cfg.keyframing.max_distance), - "max_elapsed": int(float(cfg.keyframing.max_elapsed)), - } - obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, section) + + obj: KeyframeSelectorOptions = _structured_merge_to_obj( + cls, + cfg.keyframing + ) + obj.replace(max_elapsed=int(obj.max_elapsed)) return obj # Triangulation options @dataclass(frozen=True, slots=True) class TriangulatorOptions: + hloc: str = "hloc" + pairs_file: str = "pairs.txt" + tri_model: str = "triangulated_recon" + feature_conf: str = "aliked-n16" matcher_conf: str = "aliked+lightglue" retrieval_conf: str = "netvlad" @@ -121,6 +129,7 @@ class OptIMUOptions: @dataclass(frozen=True, slots=True) class OptOptions: + optim_model: str = "optim_recon" use_callback: bool = True max_num_iterations: int = 10 normalize_reconstruction: bool = False @@ -140,26 +149,11 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": return cls() base: VIOptimizerOptions = OmegaConf.to_object(OmegaConf.structured(cls)) - opt = cfg.optimization - cam = _structured_merge_to_obj(OptCamOptions, { - "feature_std": opt.feature_std, - "optimize_cam_intrinsics": opt.optimize_cam_intrinsics, - "optimize_cam_from_rig": opt.optimize_cam_from_rig, - }) - imu = _structured_merge_to_obj(OptIMUOptions, { - "gyro_infl": opt.gyro_infl, - "acc_infl": opt.acc_infl, - "integration_noise_density": opt.integration_noise_density, - "optimize_scale": opt.optimize_scale, - "optimize_gravity": opt.optimize_gravity, - "optimize_imu_from_rig": opt.optimize_imu_from_rig, - "optimize_bias": opt.optimize_bias, - }) - optim = _structured_merge_to_obj(OptOptions, { - "use_callback": opt.use_callback, - "max_num_iterations": opt.max_num_iterations, - "normalize_reconstruction": opt.normalize_reconstruction, - }) + + cam = _structured_merge_to_obj(OptCamOptions, cfg.optimization.cam) + imu = _structured_merge_to_obj(OptIMUOptions, cfg.optimization.imu) + optim = _structured_merge_to_obj(OptOptions, cfg.optimization.opt) + # leave colmap_pipeline as default return replace( base, From 2869a1333430b0622545b298de73e0cf84d2738a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 18:00:09 +0200 Subject: [PATCH 170/665] cls --- lamaria/rig/config/options.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 842d750..3debf35 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -148,8 +148,7 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": if cfg is None or not hasattr(cfg, 'optimization'): return cls() - base: VIOptimizerOptions = OmegaConf.to_object(OmegaConf.structured(cls)) - + base = cls() cam = _structured_merge_to_obj(OptCamOptions, cfg.optimization.cam) imu = _structured_merge_to_obj(OptIMUOptions, cfg.optimization.imu) optim = _structured_merge_to_obj(OptOptions, cfg.optimization.opt) From e82856c7ef3fbd7cd0a77ef83154ca40fdab38d7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 18:00:24 +0200 Subject: [PATCH 171/665] loaders --- lamaria/rig/config/loaders.py | 5 ----- 1 file changed, 5 deletions(-) diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py index b72d826..1cbcf62 100644 --- a/lamaria/rig/config/loaders.py +++ b/lamaria/rig/config/loaders.py @@ -3,7 +3,6 @@ from .options import ( MPSOptions, - PathOptions, SensorOptions, EstimateToColmapOptions, VIOptimizerOptions, @@ -38,10 +37,6 @@ def load( OmegaConf.resolve(config) return cls(config) - - def get_path_options(self) -> PathOptions: - """ Get path options from config. """ - return PathOptions.load(self.config) def get_mps_options(self) -> MPSOptions: """ Get MPS options from config. """ From de839683909241610175aab23af3e20efc575cc8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 22 Sep 2025 18:01:04 +0200 Subject: [PATCH 172/665] defs --- lamaria/rig/config/defaults.yaml | 31 +++++++++++++++++-------------- 1 file changed, 17 insertions(+), 14 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 15fb024..85dbac5 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -43,22 +43,25 @@ triangulation: filter_min_tri_angle: 1.5 optimization: - optim_model: optim_recon - use_callback: true - max_num_iterations: 10 - normalize_reconstruction: false + opt: + optim_model: optim_recon + use_callback: true + max_num_iterations: 10 + normalize_reconstruction: false - feature_std: 1.0 - optimize_cam_intrinsics: false - optimize_cam_from_rig: false + cam: + feature_std: 1.0 + optimize_cam_intrinsics: false + optimize_cam_from_rig: false - optimize_scale: false - optimize_gravity: false - optimize_imu_from_rig: false - optimize_bias: false - gyro_infl: 20.0 - acc_infl: 1.0 - integration_noise_density: 0.05 + imu: + optimize_scale: false + optimize_gravity: false + optimize_imu_from_rig: false + optimize_bias: false + gyro_infl: 20.0 + acc_infl: 1.0 + integration_noise_density: 0.05 mps: use_mps: false From 202043c0ab88fe7c9ab574446ef903ecd76d76f3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 00:33:12 +0200 Subject: [PATCH 173/665] options --- lamaria/rig/config/options.py | 74 +++++++++++++++++++++-------------- 1 file changed, 45 insertions(+), 29 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 3debf35..283bdd8 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -2,8 +2,9 @@ from dataclasses import dataclass, field, replace from typing import Optional +from pathlib import Path import pycolmap -from omegaconf import OmegaConf +from omegaconf import OmegaConf, open_dict from .helpers import _structured_merge_to_obj @@ -17,10 +18,10 @@ class MPSOptions: @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> MPSOptions: - if cfg is None or not hasattr(cfg, 'mps'): + if cfg is None: return cls() - return _structured_merge_to_obj(cls, cfg.mps) + return _structured_merge_to_obj(cls, cfg) @dataclass(frozen=True, slots=True) class SensorOptions: @@ -31,53 +32,67 @@ class SensorOptions: @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "SensorOptions": - if cfg is None or not hasattr(cfg, 'sensor'): + if cfg is None: return cls() - obj: SensorOptions = _structured_merge_to_obj(cls, cfg.sensor) + obj: SensorOptions = _structured_merge_to_obj(cls, cfg) return obj -# To COLMAP options +# Estimate to COLMAP options @dataclass(frozen=True, slots=True) class EstimateToColmapOptions: + vrs: str = "recordings/xyz.vrs" + estimate: str = "estimates/xyz.txt" images: str = "image_stream" + mps_folder: str = "mps/mps_xyz_vrs" # necessary if use_mps is true + mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) + output_path: Path = Path("/output") + @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> EstimateToColmapOptions: - if cfg is None: - return cls( - mps=MPSOptions(), - sensor=SensorOptions(), - ) + def load( + cls, + cfg_estimate_to_colmap: Optional[OmegaConf] = None, + cfg_mps: Optional[OmegaConf] = None, + cfg_sensor: Optional[OmegaConf] = None, + ) -> EstimateToColmapOptions: - return cls( - images=cfg.estimate_to_colmap.images, - mps=MPSOptions.load(cfg), - sensor=SensorOptions.load(cfg), + if cfg_estimate_to_colmap is None: + return cls() + + base = _structured_merge_to_obj(cls, cfg_estimate_to_colmap) + return replace( + base, + mps=MPSOptions.load(cfg_mps), + sensor=SensorOptions.load(cfg_sensor) ) + # Keyframing options @dataclass(frozen=True, slots=True) class KeyframeSelectorOptions: keyframes: str = "keyframes" kf_model: str = "keyframe_recon" - + max_rotation: float = 20.0 # degrees max_distance: float = 1.0 # meters max_elapsed: int = int(1e9) # 1 second in ns + output_path: Path = Path("/output") + @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": - if cfg is None or not hasattr(cfg, 'keyframing'): + if cfg is None: return cls() - obj: KeyframeSelectorOptions = _structured_merge_to_obj( - cls, - cfg.keyframing - ) - obj.replace(max_elapsed=int(obj.max_elapsed)) + cfg = OmegaConf.create(cfg) + with open_dict(cfg): + if "max_elapsed" in cfg and isinstance(cfg.max_elapsed, float): + cfg.max_elapsed = int(cfg.max_elapsed) + + obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, cfg) return obj @@ -101,13 +116,14 @@ class TriangulatorOptions: filter_max_reproj_error: float = 4.0 filter_min_tri_angle: float = 1.5 + output_path: Path = Path("/output") + @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "TriangulatorOptions": - if cfg is None or not hasattr(cfg, 'triangulation'): + if cfg is None: return cls() - obj: TriangulatorOptions = _structured_merge_to_obj(cls, cfg.triangulation) - return obj + return _structured_merge_to_obj(cls, cfg) # Optimization options @dataclass(frozen=True, slots=True) @@ -129,7 +145,7 @@ class OptIMUOptions: @dataclass(frozen=True, slots=True) class OptOptions: - optim_model: str = "optim_recon" + optim_model: Path = Path("optim_recon") use_callback: bool = True max_num_iterations: int = 10 normalize_reconstruction: bool = False @@ -145,13 +161,13 @@ class VIOptimizerOptions: @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": - if cfg is None or not hasattr(cfg, 'optimization'): + if cfg is None: return cls() base = cls() cam = _structured_merge_to_obj(OptCamOptions, cfg.optimization.cam) imu = _structured_merge_to_obj(OptIMUOptions, cfg.optimization.imu) - optim = _structured_merge_to_obj(OptOptions, cfg.optimization.opt) + optim = _structured_merge_to_obj(OptOptions, cfg.optimization.general) # leave colmap_pipeline as default return replace( From dbe53600d289115a7fb5b5b34b9542f171b227f7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 00:33:45 +0200 Subject: [PATCH 174/665] pipeline --- lamaria/rig/config/pipeline.py | 115 +++++++++++++++++++++++++++++++++ 1 file changed, 115 insertions(+) create mode 100644 lamaria/rig/config/pipeline.py diff --git a/lamaria/rig/config/pipeline.py b/lamaria/rig/config/pipeline.py new file mode 100644 index 0000000..e52a317 --- /dev/null +++ b/lamaria/rig/config/pipeline.py @@ -0,0 +1,115 @@ +from pathlib import Path +from typing import Optional, Sequence, Any +from omegaconf import OmegaConf, DictConfig +from dataclasses import replace + +from .options import ( + MPSOptions, + SensorOptions, + EstimateToColmapOptions, + VIOptimizerOptions, + TriangulatorOptions, + KeyframeSelectorOptions, +) + +class PipelineOptions: + default_cfg: Path = Path("lamaria/rig/config/defaults.yaml") + workspace: Path = Path("/media/lamaria/") + seq_name: str = "5cp" + + def __init__(self) -> None: + self._cfg: DictConfig = self._load_cfg(self.default_cfg, None) + + @classmethod + def _from_cfg(cls, cfg: DictConfig) -> "PipelineOptions": + obj = cls.__new__(cls) + obj._cfg = cfg + return obj + + @staticmethod + def _load_cfg( + cfg_file: Path | str, + cli_overrides: Optional[Sequence[str]], + ) -> DictConfig: + cfg = OmegaConf.load(str(cfg_file)) + if cli_overrides: + cfg = OmegaConf.merge(cfg, OmegaConf.from_dotlist(list(cli_overrides))) + OmegaConf.resolve(cfg) + return cfg + + @classmethod + def load( + cls, + base_file: Path | str | None = None, + cli_overrides: Optional[Sequence[str]] = None, + ) -> "PipelineOptions": + cfg_path = base_file if base_file is not None else cls.default_cfg + return cls._from_cfg(cls._load_cfg(cfg_path, cli_overrides)) + + @property + def config(self) -> DictConfig: + return self._cfg + + @staticmethod + def _select(cfg: DictConfig, key: str, default: Any = None) -> Any: + val = OmegaConf.select(cfg, key) + return default if val is None else val + + @property + def workspace_path(self) -> Path: + return Path(self._select(self._cfg, "workspace", Path(type(self).workspace))) + + @property + def seq_name(self) -> str: + return str(self._select(self._cfg, "seq_name", type(self).seq_name)) + + @property + def output_path(self) -> Path: + return self.workspace / "output" / self.seq_name + + def get_estimate_to_colmap_options(self) -> EstimateToColmapOptions: + """Get EstimateToColmapOptions from config.""" + options = EstimateToColmapOptions.load( + self._cfg.estimate_to_colmap, + self._cfg.mps, + self._cfg.sensor, + ) + return replace( + options, + vrs=self.workspace_path / options.vrs, + estimate=self.workspace_path / options.estimate, + images=self.output_path / options.images, + mps_folder=(self.workspace_path / options.mps_folder) if options.mps_folder else None, + output_path=self.output_path, + ) + + def get_keyframing_options(self) -> KeyframeSelectorOptions: + """Get KeyframeSelectorOptions from config.""" + options = KeyframeSelectorOptions.load(self._cfg.keyframing) + return replace( + options, + keyframes=self.output_path / options.keyframes, + kf_model=self.output_path / options.kf_model, + output_path=self.output_path, + ) + + def get_triangulator_options(self) -> TriangulatorOptions: + """Get TriangulatorOptions from config.""" + options = TriangulatorOptions.load(self._cfg.triangulation) + return replace( + options, + hloc=self.output_path / options.hloc, + pairs_file=self.output_path / options.hloc / options.pairs_file, + tri_model=self.output_path / options.tri_model, + output_path=self.output_path, + ) + + def get_vi_optimizer_options(self) -> VIOptimizerOptions: + """Get VIOptimizerOptions from config.""" + options = VIOptimizerOptions.load(self._cfg.optimization) + return replace( + options, + optim_model=self.output_path / options.optim_model, + output_path=self.output_path, + ) + \ No newline at end of file From 621b807d3d72f41537f8f871c581644c62d4faa5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 00:34:23 +0200 Subject: [PATCH 175/665] pipeline --- lamaria/rig/config/pipeline.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/lamaria/rig/config/pipeline.py b/lamaria/rig/config/pipeline.py index e52a317..298e3c5 100644 --- a/lamaria/rig/config/pipeline.py +++ b/lamaria/rig/config/pipeline.py @@ -4,8 +4,6 @@ from dataclasses import replace from .options import ( - MPSOptions, - SensorOptions, EstimateToColmapOptions, VIOptimizerOptions, TriangulatorOptions, From 970076a32dbc9bb923973de17487670fb6c927b3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 00:34:30 +0200 Subject: [PATCH 176/665] rm loaders --- lamaria/rig/config/loaders.py | 64 ----------------------------------- 1 file changed, 64 deletions(-) delete mode 100644 lamaria/rig/config/loaders.py diff --git a/lamaria/rig/config/loaders.py b/lamaria/rig/config/loaders.py deleted file mode 100644 index 1cbcf62..0000000 --- a/lamaria/rig/config/loaders.py +++ /dev/null @@ -1,64 +0,0 @@ -from typing import Optional, Sequence -from omegaconf import OmegaConf - -from .options import ( - MPSOptions, - SensorOptions, - EstimateToColmapOptions, - VIOptimizerOptions, - TriangulatorOptions, - KeyframeSelectorOptions, -) - -class Config: - def __init__(self, cfg: OmegaConf): - self.config = cfg - - @classmethod - def load_default( - cls, - ) -> 'Config': - """ Load default config from default file inside lamaria/rig/config/ """ - return cls.load() - - @classmethod - def load( - cls, - base_file: str = "lamaria/rig/config/defaults.yaml", - cli_overrides: Optional[Sequence[str]] = None - ) -> 'Config': - - config = OmegaConf.load(base_file) - if cli_overrides: - config = OmegaConf.merge( - config, - OmegaConf.from_dotlist(list(cli_overrides)) - ) - - OmegaConf.resolve(config) - return cls(config) - - def get_mps_options(self) -> MPSOptions: - """ Get MPS options from config. """ - return MPSOptions.load(self.config) - - def get_sensor_options(self) -> SensorOptions: - """ Get sensor options from config. """ - return SensorOptions.load(self.config) - - def get_estimate_to_colmap_options(self) -> EstimateToColmapOptions: - """ Get options for to_colmap pipeline from config. """ - return EstimateToColmapOptions.load(self.config) - - def get_keyframing_options(self) -> KeyframeSelectorOptions: - """ Get keyframing options from config. """ - return KeyframeSelectorOptions.load(self.config) - - def get_triangulator_options(self) -> TriangulatorOptions: - """ Get triangulation options from config. """ - return TriangulatorOptions.load(self.config) - - def get_vi_optimizer_options(self) -> VIOptimizerOptions: - """ Get visual-inertial optimization options from config. """ - return VIOptimizerOptions.load(self.config) - \ No newline at end of file From de80ff208043a5c2aea18e076a59eb9d190880c7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 00:35:43 +0200 Subject: [PATCH 177/665] general --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 85dbac5..0e73e04 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -43,7 +43,7 @@ triangulation: filter_min_tri_angle: 1.5 optimization: - opt: + general: optim_model: optim_recon use_callback: true max_num_iterations: 10 From d068ed3d4ad7d8bf576801392a7a014fdcc9dab3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 00:35:57 +0200 Subject: [PATCH 178/665] workspace and mps --- lamaria/rig/config/defaults.yaml | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index 0e73e04..ba9c535 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -1,14 +1,12 @@ # Default configuration for lamaria rig pipeline -base: /media/arialamar/ +workspace: /media/arialamar/ seq_name: 5cp estimate_to_colmap: vrs: recordings/${seq_name}.vrs estimate: est/${seq_name}.txt - mps: mps/mps_${seq_name}_vrs/ # necessary if use_mps is true - - base: output/${seq_name}/ + mps_folder: mps/mps_${seq_name}_vrs/ # necessary if use_mps is true images: image_stream sensor: From 8b7f12168213d6754f209cc379bfe67e9ee25123 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 10:05:36 +0200 Subject: [PATCH 179/665] helpers --- lamaria/rig/config/helpers.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/lamaria/rig/config/helpers.py b/lamaria/rig/config/helpers.py index 1d20b39..eff5d54 100644 --- a/lamaria/rig/config/helpers.py +++ b/lamaria/rig/config/helpers.py @@ -1,4 +1,4 @@ -# options.py +# options.py helper functions from __future__ import annotations from pathlib import Path from typing import Optional @@ -8,7 +8,7 @@ def _p( x: Optional[str] | Optional[Path], root: Optional[Path] = None ) -> Optional[Path]: - + if x is None: return None x = Path(x) @@ -18,8 +18,9 @@ def _p( def _structured_merge_to_obj(cls, section) -> object: """ - Merge a YAML section onto a structured config made from the dataclass `cls`, - then return a dataclass instance (OmegaConf handles the casting). + Merge a YAML section onto a structured + config made from the dataclass `cls`, + then return a dataclass instance. """ base = OmegaConf.structured(cls) merged = OmegaConf.merge(base, section or {}) From 72932448af65f70560c3711bb3bc6f4b244edb18 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 10:09:40 +0200 Subject: [PATCH 180/665] lamaria recons --- lamaria/rig/lamaria_reconstruction.py | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/lamaria_reconstruction.py b/lamaria/rig/lamaria_reconstruction.py index 8ad65a1..af965b7 100644 --- a/lamaria/rig/lamaria_reconstruction.py +++ b/lamaria/rig/lamaria_reconstruction.py @@ -1,13 +1,13 @@ import numpy as np import pycolmap -from typing import List +from typing import Dict from pathlib import Path from .. import logger class LamariaReconstruction: reconstruction: pycolmap.Reconstruction - timestamps: List[int] + timestamps: Dict[int, int] imu_measurements: pycolmap.ImuMeasurements @classmethod @@ -22,7 +22,13 @@ def read_reconstruction( ts_path = input_folder / "timestamps.txt" assert ts_path.exists(), f"Timestamps file {ts_path} does not exist in {input_folder}" with open(ts_path, 'r') as f: - instance.timestamps = [int(line.strip()) for line in f if line.strip().isdigit()] + lines = f.readlines() + instance.timestamps = {} + for line in lines: + if line.startswith("#"): + continue + frame_id, ts = line.strip().split() + instance.timestamps[int(frame_id)] = int(ts) rectified_imu_data_npy = input_folder / "rectified_imu_data.npy" assert rectified_imu_data_npy.exists(), \ @@ -41,10 +47,13 @@ def write_reconstruction( ) -> None: output_folder.mkdir(parents=True, exist_ok=True) self.reconstruction.write(output_folder.as_posix()) + ts_path = output_folder / "timestamps.txt" + frame_ids = sorted(self.timestamps.keys()) with open(ts_path, 'w') as f: - for ts in self.timestamps: - f.write(f"{ts}\n") + f.write("# FrameID Timestamp(ns)\n") + for frame_id in frame_ids: + f.write(f"{frame_id} {self.timestamps[frame_id]}\n") rectified_imu_data_npy = output_folder / "rectified_imu_data.npy" np.save(rectified_imu_data_npy, self.imu_measurements.data) From a18ebbfbdfb79f45d36453777fe0e4f040091076 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 10:38:24 +0200 Subject: [PATCH 181/665] to colmap upds --- lamaria/rig/keyframing/to_colmap.py | 193 +++++++++++----------------- 1 file changed, 75 insertions(+), 118 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 18c8296..e671c41 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -14,9 +14,10 @@ from projectaria_tools.core.stream_id import StreamId from ... import logger +from ..lamaria_reconstruction import LamariaReconstruction from ..config.options import EstimateToColmapOptions from ...utils.general import ( - find_closest_timestamp, + get_matched_timestamps, get_t_imu_camera, camera_colmap_from_calib, rigid3d_from_transform, @@ -51,62 +52,59 @@ def __init__( def _init_io(self): """Initializes output and data providers""" - self.empty_recons = pycolmap.Reconstruction() - output_base = self.options.paths.init_model.parent - output_base.mkdir(parents=True, exist_ok=True) - - self.vrs_provider = data_provider.create_vrs_data_provider( - self.options.paths.vrs.as_posix() + self.data = LamariaReconstruction() + self._vrs_provider = data_provider.create_vrs_data_provider( + self.options.vrs.as_posix() ) - if self.options.mps.use_mps: - data_paths = mps.MpsDataPathsProvider(self.cfg.mps_path.as_posix()).get_data_paths() - self.mps_data_provider = mps.MpsDataProvider(data_paths) - else: - assert self.options.paths.estimate is not None, \ - "Estimate path must be provided if MPS is not used" + + # Initialize stream IDs + self._left_cam_sid = StreamId(self.options.sensor.left_cam_stream_id) + self._right_cam_sid = StreamId(self.options.sensor.right_cam_stream_id) + self._right_imu_sid = StreamId(self.options.sensor.right_imu_stream_id) - self.left_cam_stream_id = StreamId(self.options.sensor.left_cam_stream_id) - self.right_cam_stream_id = StreamId(self.options.sensor.right_cam_stream_id) - self.right_imu_stream_id = StreamId(self.options.sensor.right_imu_stream_id) + # Initialize MPS data provider if needed + if self.options.mps.use_mps: + data_paths = mps.MpsDataPathsProvider(self.options.mps_folder.as_posix()).get_data_paths() + self._mps_data_provider = mps.MpsDataProvider(data_paths) def _init_data(self): """Extracts images, timestamps and builds per-frame data""" extract_images_from_vrs( - vrs_file=self.options.paths.vrs, - image_folder=self.options.paths.images, + vrs_file=self.options.vrs, + image_folder=self.options.images, ) images = self._get_images() if self.options.mps.use_mps: timestamps = self._get_mps_timestamps() - closed_loop_data = get_closed_loop_data_from_mps(self.options.paths.mps) + closed_loop_data = get_closed_loop_data_from_mps(self.options.mps) pose_timestamps = [ l for l, _ in timestamps ] mps_poses = get_mps_poses_for_timestamps(closed_loop_data, pose_timestamps) - self.per_frame_data = self._build_per_frame_data_from_mps(images, timestamps, mps_poses) + self._per_frame_data = self._build_per_frame_data_from_mps(images, timestamps, mps_poses) else: + flag = check_estimate_format(self.options.estimate) + if not flag: + raise ValueError("Estimate file format is incorrect.") + timestamps = self._get_estimate_timestamps() if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images(images, timestamps) - flag = check_estimate_format(self.options.paths.estimate) - if not flag: - raise ValueError("Estimate file format is incorrect.") - rig_from_worlds = get_rig_from_worlds_from_estimate( - self.options.paths.estimate, + self.options.estimate, ) - self.per_frame_data = self._build_per_frame_data_from_estimate(images, timestamps, rig_from_worlds) + self._per_frame_data = self._build_per_frame_data_from_estimate(images, timestamps, rig_from_worlds) def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[PerFrameData]: per_frame_data = [] - imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.right_imu_stream_id + imu_stream_label = self._vrs_provider.get_label_from_stream_id( + self._right_imu_sid ) if not self.options.mps.use_online_calibration: - device_calibration = self.vrs_provider.get_device_calibration() + device_calibration = self._vrs_provider.get_device_calibration() imu_calib = device_calibration.get_imu_calib( imu_stream_label ) @@ -118,7 +116,7 @@ def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[ continue if self.options.mps.use_online_calibration: - ocalib = self.mps_data_provider.get_online_calibration( + ocalib = self._mps_data_provider.get_online_calibration( left_ts, TimeQueryOptions.CLOSEST ) if ocalib is None: @@ -171,11 +169,11 @@ def _images_from_vrs(self, folder: Path, wrt_to: Path, ext: str =".jpg") -> List def _ts_from_vrs(self, sid: StreamId) -> List[int]: """Timestamps in nanoseconds""" - return sorted(self.vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME)) + return sorted(self._vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME)) def _get_images(self) -> List[Tuple[Path, Path]]: - left_img_dir = self.options.paths.images / "left" - right_img_dir = self.options.paths.images / "right" + left_img_dir = self.options.images / "left" + right_img_dir = self.options.images / "right" left_images = self._images_from_vrs(left_img_dir, left_img_dir) right_images = self._images_from_vrs(right_img_dir, right_img_dir) @@ -184,8 +182,8 @@ def _get_images(self) -> List[Tuple[Path, Path]]: def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: if not self.options.mps.has_slam_drops: - L = self._ts_from_vrs(self.left_cam_stream_id) - R = self._ts_from_vrs(self.right_cam_stream_id) + L = self._ts_from_vrs(self._left_cam_sid) + R = self._ts_from_vrs(self._right_cam_sid) assert len(L) == len(R), "Unequal number of left and right timestamps" matched = list(zip(L, R)) if not all(abs(l - r) < max_diff for l, r in matched): @@ -193,15 +191,15 @@ def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: f"Left and right timestamps differ by more than {max_diff} ns" ) else: - matched = self._match_timestamps(max_diff) + matched = get_matched_timestamps(L, R, max_diff) return matched def _get_estimate_timestamps(self): - assert self.options.paths.estimate is not None, \ + assert self.options.estimate is not None, \ "Estimate path must be provided if MPS is not used" - - with open(self.options.paths.estimate, 'r') as f: + + with open(self.options.estimate, 'r') as f: lines = f.readlines() timestamps = [] @@ -221,7 +219,7 @@ def _match_estimate_ts_to_images( max_diff: int = 1000000, # 1 ms ) -> Tuple[List[Tuple[Path, Path]], List[int]]: - left_ts = self._ts_from_vrs(self.left_cam_stream_id) + left_ts = self._ts_from_vrs(self._left_cam_sid) assert len(images) == len(left_ts), \ "Number of images and left timestamps must be equal" @@ -251,28 +249,6 @@ def _match_estimate_ts_to_images( matched_timestamps.append(left_ts[best]) return matched_images, matched_timestamps - - def _match_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: - L = self._ts_from_vrs(self.left_cam_stream_id) - R = self._ts_from_vrs(self.right_cam_stream_id) - - # matching timestamps is only when we have slam drops - assert len(L) > 0 and len(R) > 0 and len(L) != len(R), \ - "Streams must have data and unequal lengths" - - matched = [] - - if len(L) < len(R): - for l in L: - r = find_closest_timestamp(R, l, max_diff) - if r is not None: - matched.append((l, r)) - else: - for r in R: - l = find_closest_timestamp(L, r, max_diff) - if l is not None: - matched.append((l, r)) - return matched def _get_dummy_imu_params(self) -> List: # Dummy values for IMU "camera" @@ -285,9 +261,9 @@ def _get_dummy_imu_params(self) -> List: return width, height, random_params def _add_device_sensors(self) -> None: - device_calibration = self.vrs_provider.get_device_calibration() - imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.right_imu_stream_id + device_calibration = self._vrs_provider.get_device_calibration() + imu_stream_label = self._vrs_provider.get_label_from_stream_id( + self._right_imu_sid ) imu_calib = device_calibration.get_imu_calib( imu_stream_label @@ -304,14 +280,14 @@ def _add_device_sensors(self) -> None: height=h, params=p, ) - self.empty_recons.add_camera(imu) + self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) for cam_id, sid in \ - [(2, self.left_cam_stream_id), - (3, self.right_cam_stream_id) + [(2, self._left_cam_sid), + (3, self._right_cam_sid) ]: - stream_label = self.vrs_provider.get_label_from_stream_id( + stream_label = self._vrs_provider.get_label_from_stream_id( sid ) camera_calib = device_calibration.get_camera_calib( @@ -327,17 +303,17 @@ def _add_device_sensors(self) -> None: t_camera_imu = t_imu_camera.inverse() sensor_from_rig = rigid3d_from_transform(t_camera_imu) - self.empty_recons.add_camera(cam) + self.data.reconstruction.add_camera(cam) rig.add_sensor(cam.sensor_id, sensor_from_rig) - self.empty_recons.add_rig(rig) + self.data.reconstruction.add_rig(rig) def _add_online_sensors(self) -> None: """Adds a new rig for each timestamp, with sensors calibrated online""" sensor_id = 1 - for id, pfd in enumerate(self.per_frame_data): + for id, pfd in enumerate(self._per_frame_data): t = pfd.left_ts - calibration = self.mps_data_provider.get_online_calibration( + calibration = self._mps_data_provider.get_online_calibration( t, TimeQueryOptions.CLOSEST ) if calibration is None: @@ -353,12 +329,12 @@ def _add_online_sensors(self) -> None: height=h, params=p, ) - self.empty_recons.add_camera(imu) + self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) sensor_id += 1 - imu_stream_label = self.vrs_provider.get_label_from_stream_id( - self.right_imu_stream_id + imu_stream_label = self._vrs_provider.get_label_from_stream_id( + self._right_imu_sid ) imu_calib = None for calib in calibration.imu_calibs: @@ -367,9 +343,9 @@ def _add_online_sensors(self) -> None: break for sid in \ - [self.left_cam_stream_id, self.right_cam_stream_id + [self._left_cam_sid, self._right_cam_sid ]: - stream_label = self.vrs_provider.get_label_from_stream_id( + stream_label = self._vrs_provider.get_label_from_stream_id( sid ) camera_calib = calibration.get_camera_calib( @@ -386,16 +362,16 @@ def _add_online_sensors(self) -> None: t_camera_imu = t_imu_camera.inverse() sensor_from_rig = rigid3d_from_transform(t_camera_imu) - self.empty_recons.add_camera(cam) + self.data.reconstruction.add_camera(cam) rig.add_sensor(cam.sensor_id, sensor_from_rig) - self.empty_recons.add_rig(rig) + self.data.reconstruction.add_rig(rig) def _add_device_frames(self) -> None: image_id = 1 - rig = self.empty_recons.rigs[1] - for id, pfd in enumerate(self.per_frame_data): + rig = self.data.reconstruction.rigs[1] + for id, pfd in enumerate(self._per_frame_data): frame = pycolmap.Frame() frame.rig_id = rig.rig_id frame.frame_id = id + 1 # unique id @@ -414,14 +390,14 @@ def _add_device_frames(self) -> None: images_to_add.append(im) image_id += 1 - self.empty_recons.add_frame(frame) + self.data.reconstruction.add_frame(frame) for im in images_to_add: - self.empty_recons.add_image(im) + self.data.reconstruction.add_image(im) def _add_online_frames(self) -> None: image_id = 1 - for id, pfd in enumerate(self.per_frame_data): + for id, pfd in enumerate(self._per_frame_data): frame = pycolmap.Frame() frame.rig_id = id + 1 frame.frame_id = id + 1 @@ -441,55 +417,36 @@ def _add_online_frames(self) -> None: images_to_add.append(im) image_id += 1 - self.empty_recons.add_frame(frame) + self.data.reconstruction.add_frame(frame) for im in images_to_add: - self.empty_recons.add_image(im) + self.data.reconstruction.add_image(im) - def save_imu_measurements(self) -> Path: - """Saves rectified IMU measurements to a numpy file""" + def _get_rectified_imu_data(self) -> Path: + """Generates rectified IMU data from VRS file""" if self.options.mps.use_online_calibration \ and self.options.mps.use_mps: ms = get_imu_data_from_vrs( - self.vrs_provider, + self._vrs_provider, self.options.paths.mps, ) else: ms = get_imu_data_from_vrs( - self.vrs_provider, + self._vrs_provider, ) - - np.save(self.options.paths.rect_imu, ms.data) - return self.options.paths.rect_imu + return ms - def create(self) -> pycolmap.Reconstruction: + def create(self) -> LamariaReconstruction: """Creates an empty COLMAP reconstruction with cameras and frames""" - if self.options.mps.use_online_calibration: + if self.options.mps.use_online_calibration \ + and self.options.mps.use_mps: self._add_online_sensors() self._add_online_frames() else: self._add_device_sensors() self._add_device_frames() + + ms = self._get_rectified_imu_data() + self.data.imu_measurements = ms - return self.empty_recons - - def get_full_timestamps(self) -> List[int]: - return sorted([pfd.left_ts for pfd in self.per_frame_data]) - - def write_reconstruction(self) -> Path: - """Writes the empty reconstruction. Returns the path to the reconstruction folder.""" - recon_path = self.options.paths.init_model - recon_path.mkdir(parents=True, exist_ok=True) - - logger.info(f"Init {self.empty_recons.summary()}") - self.empty_recons.write(recon_path.as_posix()) - - return recon_path - - def write_full_timestamps(self) -> Path: - ts_path = self.options.paths.full_ts - ts_path.parent.mkdir(parents=True, exist_ok=True) - left_ts = np.array(sorted([pfd.left_ts for pfd in self.per_frame_data])) - np.save(ts_path, left_ts) - - return ts_path + return self.data From 2b1ece653069cc7b527ab22a0e01d7c9d0b3aba8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 10:44:02 +0200 Subject: [PATCH 182/665] general --- lamaria/utils/general.py | 59 ++++++++++++++++++++++++++++++++-------- 1 file changed, 47 insertions(+), 12 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 641c1c2..1b11391 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -54,25 +54,27 @@ def find_closest_timestamp( def get_matched_timestamps( - left_timestamps: list, - right_timestamps: list, + left_timestamps: List[int], + right_timestamps: List[int], max_diff: float, -) -> list[tuple[int, int]]: - +) -> List[Tuple[int, int]]: + matched_timestamps = [] - assert all(isinstance(ts, int) for ts in left_timestamps) - assert all(isinstance(ts, int) for ts in right_timestamps) + assert all(isinstance(ts, int) for ts in left_timestamps), \ + "Left timestamps must be integers" + assert all(isinstance(ts, int) for ts in right_timestamps), \ + "Right timestamps must be integers" if len(left_timestamps) < len(right_timestamps): for lts in left_timestamps: closest_rts = find_closest_timestamp(right_timestamps, lts, max_diff) - if abs(lts - closest_rts) < max_diff: + if closest_rts is not None: matched_timestamps.append((lts, closest_rts)) else: for rts in right_timestamps: closest_lts = find_closest_timestamp(left_timestamps, rts, max_diff) - if abs(rts - closest_lts) < max_diff: + if closest_lts is not None: matched_timestamps.append((closest_lts, rts)) return matched_timestamps @@ -284,6 +286,33 @@ def check_estimate_format(estimate_path: Path) -> bool: return True +def get_estimate_timestamps(estimate_path: Path) -> List[int]: + """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" + timestamps = [] + with open(estimate_path, "r") as f: + lines = f.readlines() + lines = [line for line in lines if not line.startswith("#")] + if not lines: + raise ValueError(f"Estimate file {estimate_path} is empty \ + or has no valid lines.") + + for line in lines: + parts = line.strip().split() + if len(parts) != 8: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values.") + + try: + ts = round_ns(parts[0]) + except ValueError: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number.") + + timestamps.append(ts) + + return timestamps + + def extract_images_from_vrs( vrs_file: Path, image_folder: Path, @@ -347,10 +376,16 @@ def get_rig_from_worlds_from_estimate( parts = line.strip().split() if len(parts) != 8: - continue - - tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) - qvec = np.array([float(parts[4]), float(parts[5]), float(parts[6]), float(parts[7])]) + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values.") + + try: + tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) + qvec = np.array([float(parts[4]), float(parts[5]), float(parts[6]), float(parts[7])]) + except ValueError: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number.") + pose = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) rig_from_world = pose.inverse() rig_from_worlds.append(rig_from_world) From 9082561ea744f2362d325516a70ff8d5d31deaea Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 10:46:01 +0200 Subject: [PATCH 183/665] estimtate utils --- lamaria/utils/estimate.py | 95 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 95 insertions(+) create mode 100644 lamaria/utils/estimate.py diff --git a/lamaria/utils/estimate.py b/lamaria/utils/estimate.py new file mode 100644 index 0000000..7ae994a --- /dev/null +++ b/lamaria/utils/estimate.py @@ -0,0 +1,95 @@ +from pathlib import Path +from typing import List +import numpy as np +import pycolmap +from decimal import Decimal, ROUND_HALF_UP + + +def round_ns(x: str | int | float) -> int: + # works for "5120...274.999939", "5.12e11", or ints + if isinstance(x, int): + return x + s = str(x) + return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) + + +def get_rig_from_worlds_from_estimate( + estimate_path: Path +) -> List[pycolmap.Rigid3d]: + """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" + + rig_from_worlds = [] + with open(estimate_path, "r") as f: + lines = f.readlines() + for line in lines: + if line.startswith("#"): + continue + + parts = line.strip().split() + if len(parts) != 8: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values.") + + try: + tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) + qvec = np.array([float(parts[4]), float(parts[5]), float(parts[6]), float(parts[7])]) + except ValueError: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number.") + + pose = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) + rig_from_world = pose.inverse() + rig_from_worlds.append(rig_from_world) + + return rig_from_worlds + + +def check_estimate_format(estimate_path: Path) -> bool: + """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" + with open(estimate_path, "r") as f: + lines = f.readlines() + lines = [line for line in lines if not line.startswith("#")] + if not lines: + raise ValueError(f"Estimate file {estimate_path} is empty \ + or has no valid lines.") + + for line in lines: + parts = line.strip().split() + if len(parts) != 8: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values.") + + try: + [float(part) for part in parts] + except ValueError: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number.") + + return True + + +def get_estimate_timestamps(estimate_path: Path) -> List[int]: + """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" + timestamps = [] + with open(estimate_path, "r") as f: + lines = f.readlines() + lines = [line for line in lines if not line.startswith("#")] + if not lines: + raise ValueError(f"Estimate file {estimate_path} is empty \ + or has no valid lines.") + + for line in lines: + parts = line.strip().split() + if len(parts) != 8: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values.") + + try: + ts = round_ns(parts[0]) + except ValueError: + raise ValueError(f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number.") + + timestamps.append(ts) + + return timestamps \ No newline at end of file From ece89f15ad889974f1411e35feb7e36d52c227a1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 10:47:36 +0200 Subject: [PATCH 184/665] general --- lamaria/utils/general.py | 85 ---------------------------------------- 1 file changed, 85 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 1b11391..7b33416 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -9,7 +9,6 @@ from typing import List import subprocess from scipy.spatial.transform import Rotation -from decimal import Decimal, ROUND_HALF_UP from projectaria_tools.core.stream_id import StreamId from projectaria_tools.core import data_provider, mps @@ -238,12 +237,6 @@ def camera_colmap_from_json( params=params, ) -def round_ns(x: str | int | float) -> int: - # works for "5120...274.999939", "5.12e11", or ints - if isinstance(x, int): - return x - s = str(x) - return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) def delete_files_in_folder(folder, exclude_pattern=None): if os.path.isdir(folder): @@ -263,55 +256,6 @@ def delete_files_in_folder(folder, exclude_pattern=None): else: os.makedirs(folder, exist_ok=True) -def check_estimate_format(estimate_path: Path) -> bool: - """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - with open(estimate_path, "r") as f: - lines = f.readlines() - lines = [line for line in lines if not line.startswith("#")] - if not lines: - raise ValueError(f"Estimate file {estimate_path} is empty \ - or has no valid lines.") - - for line in lines: - parts = line.strip().split() - if len(parts) != 8: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values.") - - try: - [float(part) for part in parts] - except ValueError: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number.") - - return True - -def get_estimate_timestamps(estimate_path: Path) -> List[int]: - """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - timestamps = [] - with open(estimate_path, "r") as f: - lines = f.readlines() - lines = [line for line in lines if not line.startswith("#")] - if not lines: - raise ValueError(f"Estimate file {estimate_path} is empty \ - or has no valid lines.") - - for line in lines: - parts = line.strip().split() - if len(parts) != 8: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values.") - - try: - ts = round_ns(parts[0]) - except ValueError: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number.") - - timestamps.append(ts) - - return timestamps - def extract_images_from_vrs( vrs_file: Path, @@ -362,35 +306,6 @@ def get_closed_loop_data_from_mps(mps_path: Path) -> List[mps.ClosedLoopTrajecto data = mps.read_closed_loop_trajectory(closed_loop_traj_file.as_posix()) return data -def get_rig_from_worlds_from_estimate( - estimate_path: Path -) -> List[pycolmap.Rigid3d]: - """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - - rig_from_worlds = [] - with open(estimate_path, "r") as f: - lines = f.readlines() - for line in lines: - if line.startswith("#"): - continue - - parts = line.strip().split() - if len(parts) != 8: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values.") - - try: - tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) - qvec = np.array([float(parts[4]), float(parts[5]), float(parts[6]), float(parts[7])]) - except ValueError: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number.") - - pose = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) - rig_from_world = pose.inverse() - rig_from_worlds.append(rig_from_world) - - return rig_from_worlds def get_mps_poses_for_timestamps( trajectory_data: List[mps.ClosedLoopTrajectoryPose], From e14ac1ecb6ad6d624753aa005cbf0bd2a0e0e305 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 10:49:58 +0200 Subject: [PATCH 185/665] to colmap upd --- lamaria/rig/keyframing/to_colmap.py | 27 ++++++--------------------- 1 file changed, 6 insertions(+), 21 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index e671c41..43d569a 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -23,10 +23,12 @@ rigid3d_from_transform, get_closed_loop_data_from_mps, get_mps_poses_for_timestamps, - get_rig_from_worlds_from_estimate, extract_images_from_vrs, - round_ns, +) +from ...utils.estimate import ( check_estimate_format, + get_estimate_timestamps, + get_rig_from_worlds_from_estimate, ) from ...utils.imu import ( get_imu_data_from_vrs, @@ -87,8 +89,8 @@ def _init_data(self): flag = check_estimate_format(self.options.estimate) if not flag: raise ValueError("Estimate file format is incorrect.") - - timestamps = self._get_estimate_timestamps() + + timestamps = get_estimate_timestamps(self.options.estimate) if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images(images, timestamps) @@ -195,23 +197,6 @@ def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: return matched - def _get_estimate_timestamps(self): - assert self.options.estimate is not None, \ - "Estimate path must be provided if MPS is not used" - - with open(self.options.estimate, 'r') as f: - lines = f.readlines() - - timestamps = [] - for line in lines: - if line.startswith('#') or not line.strip(): - continue - - ts = round_ns(line.split()[0]) - timestamps.append(ts) - - return sorted(timestamps) - def _match_estimate_ts_to_images( self, images: List[Tuple[Path, Path]], From bf246108cc1a2e19a9797b32f1d89a0ed95de213 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 11:04:40 +0200 Subject: [PATCH 186/665] better mods --- lamaria/utils/general.py | 294 +-------------------------------------- 1 file changed, 1 insertion(+), 293 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 7b33416..047693e 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -1,6 +1,4 @@ import os -import json -import numpy as np import pycolmap from pathlib import Path from typing import List, Tuple @@ -8,22 +6,10 @@ from bisect import bisect_left from typing import List import subprocess -from scipy.spatial.transform import Rotation - -from projectaria_tools.core.stream_id import StreamId -from projectaria_tools.core import data_provider, mps -from projectaria_tools.core.mps.utils import get_nearest_pose -from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration from lamaria import logger -ARIA_CAMERAS = [("cam0", "camera-slam-left"), ("cam1", "camera-slam-right")] -LEFT_CAMERA_STREAM_ID = StreamId("1201-1") -RIGHT_CAMERA_STREAM_ID = StreamId("1201-2") -IMU_STREAM_ID = StreamId("1202-1") -LEFT_CAMERA_STREAM_LABEL = "camera-slam-left" -RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" -IMU_STREAM_LABEL = "imu-right" + CUSTOM_ORIGIN_COORDINATES = (2683594.4120000005, 1247727.7470000014, 417.307) @@ -78,165 +64,6 @@ def get_matched_timestamps( return matched_timestamps -def get_t_cam_a_cam_b_from_json( - calibration_file: Path, - camera_a_label: str, - camera_b_label: str, -) -> pycolmap.Rigid3d: - - calib = json.load(calibration_file.open("r")) - - t_body_cam_a = calib[camera_a_label]["T_b_s"] - t_body_cam_b = calib[camera_b_label]["T_b_s"] - - t_imu_cam_a = pycolmap.Rigid3d( - pycolmap.Rotation3d(t_body_cam_a["qvec"]), - t_body_cam_a["tvec"], - ) - t_imu_cam_b = pycolmap.Rigid3d( - pycolmap.Rotation3d(t_body_cam_b["qvec"]), - t_body_cam_b["tvec"], - ) - - t_camera_a_camera_b = t_imu_cam_a.inverse() * t_imu_cam_b - - return t_camera_a_camera_b - - -def add_cameras_to_reconstruction( - reconstruction: pycolmap.Reconstruction, - calibration_file: Path, -) -> None: - - for i, (key, _) in enumerate(ARIA_CAMERAS): - cam = camera_colmap_from_json( - calibration_file=calibration_file, - camera_label=key, - ) - cam.camera_id = i + 1 - reconstruction.add_camera(cam) - - rig = pycolmap.Rig(rig_id=1) - ref_sensor = pycolmap.sensor_t( - id=1, # left camera is the rig - type=pycolmap.SensorType.CAMERA, - ) - rig.add_ref_sensor(ref_sensor) - - sensor1 = pycolmap.sensor_t(id=2, type=pycolmap.SensorType.CAMERA) - sensor_from_rig = get_t_cam_a_cam_b_from_json( - calibration_file=calibration_file, - camera_a_label="cam1", # right - camera_b_label="cam0", # left - ) - rig.add_sensor(sensor1, sensor_from_rig) - - reconstruction.add_rig(rig) - - -def get_qvec_and_tvec_from_transform(transform) -> Tuple[np.ndarray, np.ndarray]: - """Returns qvec in format x,y,z,w and tvec in format x,y,z""" - # to_quat() returns in wxyz format - # https://github.com/facebookresearch/projectaria_tools/blob/867105e65cadbe777db355a407d90533c71d2d06/core/python/sophus/SO3PyBind.h#L161 - qvec = transform.rotation().to_quat()[0] - tvec = transform.translation()[0] - - qvec = np.roll( - qvec, -1 - ) # change from w,x,y,z to x,y,z,w for pycolmap format - - return np.array(qvec), np.array(tvec) - - -def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: - q, t = get_qvec_and_tvec_from_transform(transform) - return pycolmap.Rigid3d(pycolmap.Rotation3d(q), t) - - -def get_magnitude_from_transform(transform: pycolmap.Rigid3d) -> Tuple[float, float]: - translation = transform.translation - quat_xyzw = transform.rotation.quat - rotation = Rotation.from_quat(quat_xyzw) - dr = np.rad2deg(rotation.magnitude()) - dt = np.linalg.norm(translation) - - return dr, dt - - -def get_camera_params_for_colmap( - camera_calibration: CameraCalibration, - camera_model: str, -) -> List[float]: - # params = [f_u {f_v} c_u c_v [k_0: k_{numK-1}] - # {p_0 p_1} {s_0 s_1 s_2 s_3}] - # projection_params is a 15 length vector, - # starting with focal length, pp, extra coeffs - camera_params = camera_calibration.get_projection_params() - f_x, f_y, c_x, c_y = ( - camera_params[0], - camera_params[0], - camera_params[1], - camera_params[2], - ) - - p2, p1 = camera_params[-5], camera_params[-6] - - k1, k2, k3, k4, k5, k6 = camera_params[3:9] - - # FULL_OPENCV model format: - # fx, fy, cx, cy, k1, k2, p1, p2, k3, k4, k5, k6 - - # OPENCV_FISHEYE model format: - # fx, fy, cx, cy, k1, k2, k3, k4 - - if camera_model == "OPENCV_FISHEYE": - params = [f_x, f_y, c_x, c_y, k1, k2, k3, k4] - elif camera_model == "FULL_OPENCV": - params = [f_x, f_y, c_x, c_y, k1, k2, p1, p2, k3, k4, k5, k6] - elif camera_model == "RAD_TAN_THIN_PRISM_FISHEYE": - aria_fisheye_params = camera_params - focal_length = aria_fisheye_params[0] - aria_fisheye_params = np.insert(aria_fisheye_params, 0, focal_length) - params = aria_fisheye_params - - return params - - -def camera_colmap_from_calib(calib: CameraCalibration) -> pycolmap.Camera: - if calib.get_model_name().name != "FISHEYE624": - raise ValueError(f"Unsupported Aria model {calib.get_model_name().name}") - model = "RAD_TAN_THIN_PRISM_FISHEYE" - params = get_camera_params_for_colmap(calib, model) - width, height = calib.get_image_size() - return pycolmap.Camera( - model=model, - width=width, - height=height, - params=params, - ) - - -def camera_colmap_from_json( - calibration_file: Path, # open sourced aria calibration files - camera_label: str -) -> pycolmap.Camera: - - calib = json.load(calibration_file.open("r")) - camera_data = calib[camera_label] - if camera_data["model"] != "RAD_TAN_THIN_PRISM_FISHEYE": - raise ValueError(f"Unsupported Aria model {camera_data['model']}") - - model = "RAD_TAN_THIN_PRISM_FISHEYE" - params = camera_data["params"] - width = camera_data["resolution"]["width"] - height = camera_data["resolution"]["height"] - return pycolmap.Camera( - model=model, - width=width, - height=height, - params=params, - ) - def delete_files_in_folder(folder, exclude_pattern=None): if os.path.isdir(folder): @@ -301,125 +128,6 @@ def extract_images_from_vrs( logger.info("Done!") -def get_closed_loop_data_from_mps(mps_path: Path) -> List[mps.ClosedLoopTrajectoryPose]: - closed_loop_traj_file = mps_path / "slam" / "closed_loop_trajectory.csv" - data = mps.read_closed_loop_trajectory(closed_loop_traj_file.as_posix()) - return data - - -def get_mps_poses_for_timestamps( - trajectory_data: List[mps.ClosedLoopTrajectoryPose], - timestamps: List[int], -) -> List: - - poses = [] - if trajectory_data: - for ts in timestamps: - pose_information = get_nearest_pose(trajectory_data, ts) - if pose_information: - t_world_device = pose_information.transform_world_device - poses.append(t_world_device) - else: - poses.append(None) - - return poses - - -def get_t_rig_world_for_device_time_ns( - trajectory_data: List[mps.ClosedLoopTrajectoryPose], - device_time_ns: int, - imu_calibration: ImuCalibration, -): - if trajectory_data: - pose_information = get_nearest_pose(trajectory_data, device_time_ns) - if pose_information: - t_world_device = pose_information.transform_world_device - t_device_imu = imu_calibration.get_transform_device_imu() - assert ( - t_device_imu is not None - ), f"No t_device_imu found for device time {device_time_ns}, \ - check imu calibration" - - t_world_imu = t_world_device @ t_device_imu - t_imu_world = t_world_imu.inverse() - - return t_imu_world - else: - return None - else: - raise ValueError("No trajectory data found") - - -def get_t_imu_camera( - imu_calib: ImuCalibration, - camera_calib: CameraCalibration, - return_qt=False, - return_matrix=False, -): - t_device_cam = camera_calib.get_transform_device_camera() - t_device_imu = imu_calib.get_transform_device_imu() - t_imu_device = t_device_imu.inverse() - - t_imu_cam = t_imu_device @ t_device_cam - - assert not ( - return_qt and return_matrix - ), "Only one of return_qt or return_matrix can be True" - - if return_qt: - qvec, tvec = get_qvec_and_tvec_from_transform(t_imu_cam) - return qvec, tvec - - if return_matrix: - t_imu_cam_matrix = t_imu_cam.to_matrix() - return t_imu_cam_matrix - - return t_imu_cam - -def get_t_imu_camera_from_json( - device_calibration_json: str, - camera_label: str, -) -> pycolmap.Rigid3d: - - with open(device_calibration_json, "r") as f: - device_calib = json.load(f) - - # body is right imu of Aria, therefore T_b_s is T_imu_camera - t_body_cam = device_calib[camera_label]["T_b_s"] - t_imu_camera = pycolmap.Rigid3d( - pycolmap.Rotation3d(t_body_cam["qvec"]), - t_body_cam["tvec"], - ) - - return t_imu_camera - -def get_t_cam_a_cam_b_from_json( - device_calibration_json: str, - camera_a_label: str, - camera_b_label: str, -) -> pycolmap.Rigid3d: - - with open(device_calibration_json, "r") as f: - device_calib = json.load(f) - - # body is right imu of Aria, therefore T_b_s is T_imu_camera - t_body_cam_a = device_calib[camera_a_label]["T_b_s"] - t_body_cam_b = device_calib[camera_b_label]["T_b_s"] - - t_imu_cam_a = pycolmap.Rigid3d( - pycolmap.Rotation3d(t_body_cam_a["qvec"]), - t_body_cam_a["tvec"], - ) - t_imu_cam_b = pycolmap.Rigid3d( - pycolmap.Rotation3d(t_body_cam_b["qvec"]), - t_body_cam_b["tvec"], - ) - - t_camera_a_camera_b = t_imu_cam_a.inverse() * t_imu_cam_b - - return t_camera_a_camera_b - - def get_image_names_to_ids(reconstruction_dir: str): recon = pycolmap.Reconstruction(reconstruction_dir) image_names_to_ids = {} From 3652ee78877526abede1dc9f62f88e0604d3ebc4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 11:05:16 +0200 Subject: [PATCH 187/665] imu --- lamaria/utils/imu.py | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index 299dc94..b29bd7e 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -4,12 +4,17 @@ from tqdm import tqdm from projectaria_tools.core import mps, data_provider from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from projectaria_tools.core.stream_id import StreamId from lamaria.utils.general import ( - IMU_STREAM_ID, find_closest_timestamp, ) +RIGHT_IMU_STREAM_ID = StreamId("1202-1") +RIGHT_IMU_STREAM_LABEL = "imu-right" + + + def get_online_params_for_imu_from_mps( online_calibs_file: Path, stream_label: str, @@ -38,11 +43,11 @@ def get_imu_data_from_vrs( calibration data from MPS folder. Otherwise, use device calibration from VRS file. """ imu_timestamps = sorted( vrs_provider.get_timestamps_ns( - IMU_STREAM_ID, + RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME ) ) - imu_stream_label = vrs_provider.get_label_from_stream_id(IMU_STREAM_ID) + imu_stream_label = vrs_provider.get_label_from_stream_id(RIGHT_IMU_STREAM_ID) if mps_folder is not None: online_calibs_file = mps_folder / "slam" / "online_calibration.jsonl" @@ -72,7 +77,7 @@ def get_imu_data_from_vrs( calibration = online_imu_calibs[closest_ts] imu_data = vrs_provider.get_imu_data_by_time_ns( - IMU_STREAM_ID, + RIGHT_IMU_STREAM_ID, timestamp, TimeDomain.DEVICE_TIME, TimeQueryOptions.CLOSEST, From 5313cc32ee5e6036ac92a73c065787833263484e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 11:06:47 +0200 Subject: [PATCH 188/665] camera --- lamaria/utils/camera.py | 133 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 133 insertions(+) create mode 100644 lamaria/utils/camera.py diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py new file mode 100644 index 0000000..0bcd9ca --- /dev/null +++ b/lamaria/utils/camera.py @@ -0,0 +1,133 @@ + +import json +import numpy as np +import pycolmap +from pathlib import Path +from typing import List + +from projectaria_tools.core.stream_id import StreamId +from projectaria_tools.core.calibration import CameraCalibration + +from .transformation import get_t_cam_a_cam_b_from_json + + +ARIA_CAMERAS = [("cam0", "camera-slam-left"), ("cam1", "camera-slam-right")] +LEFT_CAMERA_STREAM_ID = StreamId("1201-1") +RIGHT_CAMERA_STREAM_ID = StreamId("1201-2") +LEFT_CAMERA_STREAM_LABEL = "camera-slam-left" +RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" + + + +def add_cameras_to_reconstruction( + reconstruction: pycolmap.Reconstruction, + calibration_file: Path, +) -> None: + """ Add Aria cameras to COLMAP reconstruction from calibration json file found on website: + https://lamaria.ethz.ch/slam_datasets""" + + for i, (key, _) in enumerate(ARIA_CAMERAS): + cam = camera_colmap_from_json( + calibration_file=calibration_file, + camera_label=key, + ) + cam.camera_id = i + 1 + reconstruction.add_camera(cam) + + rig = pycolmap.Rig(rig_id=1) + ref_sensor = pycolmap.sensor_t( + id=1, # left camera is the rig + type=pycolmap.SensorType.CAMERA, + ) + rig.add_ref_sensor(ref_sensor) + + sensor1 = pycolmap.sensor_t(id=2, type=pycolmap.SensorType.CAMERA) + sensor_from_rig = get_t_cam_a_cam_b_from_json( + calibration_file=calibration_file, + camera_a_label="cam1", # right + camera_b_label="cam0", # left + ) + rig.add_sensor(sensor1, sensor_from_rig) + + reconstruction.add_rig(rig) + + +def get_camera_params_for_colmap( + camera_calibration: CameraCalibration, + camera_model: str, +) -> List[float]: + """ Convert Aria CameraCalibration to COLMAP camera parameters. + Supported models: OPENCV_FISHEYE, FULL_OPENCV, RAD_TAN_THIN_PRISM_FISHEYE +""" + # params = [f_u {f_v} c_u c_v [k_0: k_{numK-1}] + # {p_0 p_1} {s_0 s_1 s_2 s_3}] + # projection_params is a 15 length vector, + # starting with focal length, pp, extra coeffs + camera_params = camera_calibration.get_projection_params() + f_x, f_y, c_x, c_y = ( + camera_params[0], + camera_params[0], + camera_params[1], + camera_params[2], + ) + + p2, p1 = camera_params[-5], camera_params[-6] + + k1, k2, k3, k4, k5, k6 = camera_params[3:9] + + # FULL_OPENCV model format: + # fx, fy, cx, cy, k1, k2, p1, p2, k3, k4, k5, k6 + + # OPENCV_FISHEYE model format: + # fx, fy, cx, cy, k1, k2, k3, k4 + + if camera_model == "OPENCV_FISHEYE": + params = [f_x, f_y, c_x, c_y, k1, k2, k3, k4] + elif camera_model == "FULL_OPENCV": + params = [f_x, f_y, c_x, c_y, k1, k2, p1, p2, k3, k4, k5, k6] + elif camera_model == "RAD_TAN_THIN_PRISM_FISHEYE": + aria_fisheye_params = camera_params + focal_length = aria_fisheye_params[0] + aria_fisheye_params = np.insert(aria_fisheye_params, 0, focal_length) + params = aria_fisheye_params + + return params + + +def camera_colmap_from_calib(calib: CameraCalibration) -> pycolmap.Camera: + """Loads pycolmap camera from Aria CameraCalibration object""" + if calib.get_model_name().name != "FISHEYE624": + raise ValueError(f"Unsupported Aria model {calib.get_model_name().name}") + model = "RAD_TAN_THIN_PRISM_FISHEYE" + params = get_camera_params_for_colmap(calib, model) + width, height = calib.get_image_size() + return pycolmap.Camera( + model=model, + width=width, + height=height, + params=params, + ) + + +def camera_colmap_from_json( + calibration_file: Path, # open sourced aria calibration files + camera_label: str +) -> pycolmap.Camera: + """Loads pycolmap camera from Aria calibration json file found on website: + https://lamaria.ethz.ch/slam_datasets""" + + calib = json.load(calibration_file.open("r")) + camera_data = calib[camera_label] + if camera_data["model"] != "RAD_TAN_THIN_PRISM_FISHEYE": + raise ValueError(f"Unsupported Aria model {camera_data['model']}") + + model = "RAD_TAN_THIN_PRISM_FISHEYE" + params = camera_data["params"] + width = camera_data["resolution"]["width"] + height = camera_data["resolution"]["height"] + return pycolmap.Camera( + model=model, + width=width, + height=height, + params=params, + ) \ No newline at end of file From a81a4bcef3f9bae0b51342d0a9a16899913ebf0e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 11:10:35 +0200 Subject: [PATCH 189/665] transformation functions --- lamaria/utils/transformation.py | 173 ++++++++++++++++++++++++++++++++ 1 file changed, 173 insertions(+) create mode 100644 lamaria/utils/transformation.py diff --git a/lamaria/utils/transformation.py b/lamaria/utils/transformation.py new file mode 100644 index 0000000..c1d5f69 --- /dev/null +++ b/lamaria/utils/transformation.py @@ -0,0 +1,173 @@ +from pathlib import Path +import json +import pycolmap +from typing import Tuple, List +from scipy.spatial.transform import Rotation +import numpy as np + +from projectaria_tools.core import mps +from projectaria_tools.core.mps.utils import get_nearest_pose +from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration + + + +def get_closed_loop_data_from_mps(mps_path: Path) -> List[mps.ClosedLoopTrajectoryPose]: + """ Get closed loop trajectory data from MPS folder.""" + closed_loop_traj_file = mps_path / "slam" / "closed_loop_trajectory.csv" + data = mps.read_closed_loop_trajectory(closed_loop_traj_file.as_posix()) + return data + + +def get_mps_poses_for_timestamps( + trajectory_data: List[mps.ClosedLoopTrajectoryPose], + timestamps: List[int], +) -> List: + """ Get T_world_device for a list of device timestamps in nanoseconds using MPS trajectory data. + Returns None for timestamps where no trajectory data is found.""" + poses = [] + if trajectory_data: + for ts in timestamps: + pose_information = get_nearest_pose(trajectory_data, ts) + if pose_information: + t_world_device = pose_information.transform_world_device + poses.append(t_world_device) + else: + poses.append(None) + + return poses + + +def get_t_rig_world_for_device_time_ns( + trajectory_data: List[mps.ClosedLoopTrajectoryPose], + device_time_ns: int, + imu_calibration: ImuCalibration, +): + """ Get T_rig_world (rig is right IMU sensor) for a given device time in nanoseconds using MPS trajectory data and IMU calibration. + Returns None if no trajectory data is found for the given timestamp.""" + if trajectory_data: + pose_information = get_nearest_pose(trajectory_data, device_time_ns) + if pose_information: + t_world_device = pose_information.transform_world_device + t_device_imu = imu_calibration.get_transform_device_imu() + assert ( + t_device_imu is not None + ), f"No t_device_imu found for device time {device_time_ns}, \ + check imu calibration" + + t_world_imu = t_world_device @ t_device_imu + t_imu_world = t_world_imu.inverse() + + return t_imu_world + else: + return None + else: + raise ValueError("No trajectory data found") + + +def get_t_imu_camera( + imu_calib: ImuCalibration, + camera_calib: CameraCalibration, + return_qt=False, + return_matrix=False, +): + """ Get T_imu_camera from Aria calibrations. Either return as qvec,tvec or 4x4 matrix. + If neither return_qt or return_matrix is True, returns as projectaria_tools Rigid3d object.""" + + t_device_cam = camera_calib.get_transform_device_camera() + t_device_imu = imu_calib.get_transform_device_imu() + t_imu_device = t_device_imu.inverse() + + t_imu_cam = t_imu_device @ t_device_cam + + assert not ( + return_qt and return_matrix + ), "Only one of return_qt or return_matrix can be True" + + if return_qt: + qvec, tvec = get_qvec_and_tvec_from_transform(t_imu_cam) + return qvec, tvec + + if return_matrix: + t_imu_cam_matrix = t_imu_cam.to_matrix() + return t_imu_cam_matrix + + return t_imu_cam + + +def get_qvec_and_tvec_from_transform(transform) -> Tuple[np.ndarray, np.ndarray]: + """Converts projectaria_tools Rigid3d to qvec and tvec. + Returns qvec in format x,y,z,w and tvec in format x,y,z""" + # to_quat() returns in wxyz format + # https://github.com/facebookresearch/projectaria_tools/blob/867105e65cadbe777db355a407d90533c71d2d06/core/python/sophus/SO3PyBind.h#L161 + qvec = transform.rotation().to_quat()[0] + tvec = transform.translation()[0] + + qvec = np.roll( + qvec, -1 + ) # change from w,x,y,z to x,y,z,w for pycolmap format + + return np.array(qvec), np.array(tvec) + + +def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: + """ Converts projectaria_tools Rigid3d to pycolmap Rigid3d""" + q, t = get_qvec_and_tvec_from_transform(transform) + return pycolmap.Rigid3d(pycolmap.Rotation3d(q), t) + + +def get_magnitude_from_transform(transform: pycolmap.Rigid3d) -> Tuple[float, float]: + """ Returns rotation (in degrees) and translation (in meters) magnitudes from a Rigid3d transform""" + translation = transform.translation + quat_xyzw = transform.rotation.quat + rotation = Rotation.from_quat(quat_xyzw) + dr = np.rad2deg(rotation.magnitude()) + dt = np.linalg.norm(translation) + + return dr, dt + + +def get_t_cam_a_cam_b_from_json( + calibration_file: Path, + camera_a_label: str, + camera_b_label: str, +) -> pycolmap.Rigid3d: + """ Get T_cam_a_cam_b from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) + for given camera labels.""" + + calib = json.load(calibration_file.open("r")) + + # body is right imu of Aria, therefore T_b_s is T_imu_camera + t_body_cam_a = calib[camera_a_label]["T_b_s"] + t_body_cam_b = calib[camera_b_label]["T_b_s"] + + t_imu_cam_a = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam_a["qvec"]), + t_body_cam_a["tvec"], + ) + t_imu_cam_b = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam_b["qvec"]), + t_body_cam_b["tvec"], + ) + + t_camera_a_camera_b = t_imu_cam_a.inverse() * t_imu_cam_b + + return t_camera_a_camera_b + + +def get_t_imu_camera_from_json( + calibration_file: Path, + camera_label: str, +) -> pycolmap.Rigid3d: + """ Get T_imu_camera from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) + for a given camera label.""" + + calib = json.load(calibration_file.open("r")) + + # body is right imu of Aria, therefore T_b_s is T_imu_camera + t_body_cam = calib[camera_label]["T_b_s"] + t_imu_camera = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam["qvec"]), + t_body_cam["tvec"], + ) + + return t_imu_camera \ No newline at end of file From b248172d8ed13cb107ec9919e4b6ea399e645417 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 11:12:18 +0200 Subject: [PATCH 190/665] custom paths fn --- lamaria/rig/config/options.py | 78 +++++++++++++++++++++++++++++------ 1 file changed, 66 insertions(+), 12 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 283bdd8..3e287e7 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -41,11 +41,11 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "SensorOptions": # Estimate to COLMAP options @dataclass(frozen=True, slots=True) class EstimateToColmapOptions: - vrs: str = "recordings/xyz.vrs" - estimate: str = "estimates/xyz.txt" - images: str = "image_stream" - mps_folder: str = "mps/mps_xyz_vrs" # necessary if use_mps is true - + vrs: Path = Path("recordings/xyz.vrs") + estimate: Path = Path("estimates/xyz.txt") + images: Path = Path("image_stream") + mps_folder: Path = Path("mps/mps_xyz_vrs") # necessary if use_mps is true + mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) @@ -68,13 +68,30 @@ def load( mps=MPSOptions.load(cfg_mps), sensor=SensorOptions.load(cfg_sensor) ) - + + def set_custom_paths( + self, + output_path: Path, + vrs: Path, + estimate: Path, + images: Path, + mps_folder: Optional[Path] = None, + ) -> EstimateToColmapOptions: + return replace( + self, + output_path=output_path, + vrs=vrs, + estimate=estimate, + images=images, + mps_folder=mps_folder if mps_folder is not None else self.mps_folder + ) + # Keyframing options @dataclass(frozen=True, slots=True) class KeyframeSelectorOptions: - keyframes: str = "keyframes" - kf_model: str = "keyframe_recon" + keyframes: Path = Path("keyframes") + kf_model: Path = Path("keyframe_recon") max_rotation: float = 20.0 # degrees max_distance: float = 1.0 # meters @@ -94,14 +111,27 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, cfg) return obj + + def set_custom_paths( + self, + output_path: Path, + keyframes: Path, + kf_model: Path + ) -> KeyframeSelectorOptions: + return replace( + self, + output_path=output_path, + keyframes=keyframes, + kf_model=kf_model + ) # Triangulation options @dataclass(frozen=True, slots=True) class TriangulatorOptions: - hloc: str = "hloc" - pairs_file: str = "pairs.txt" - tri_model: str = "triangulated_recon" + hloc: Path = Path("hloc") + pairs_file: Path = Path("pairs.txt") + tri_model: Path = Path("triangulated_recon") feature_conf: str = "aliked-n16" matcher_conf: str = "aliked+lightglue" @@ -124,6 +154,22 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "TriangulatorOptions": return cls() return _structured_merge_to_obj(cls, cfg) + + def set_custom_paths( + self, + output_path: Path, + hloc: Path, + pairs_file: Path, + tri_model: Path + ) -> TriangulatorOptions: + return replace( + self, + output_path=output_path, + hloc=hloc, + pairs_file=pairs_file, + tri_model=tri_model + ) + # Optimization options @dataclass(frozen=True, slots=True) @@ -176,4 +222,12 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": imu=imu, optim=optim, ) - \ No newline at end of file + + def set_custom_paths( + self, + optim_model: Path, + ) -> VIOptimizerOptions: + return replace( + self, + optim=replace(self.optim, optim_model=optim_model) + ) From 7562b5e6100a618556b8b915c71518e810226a91 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 11:21:22 +0200 Subject: [PATCH 191/665] updating function locations --- lamaria/rig/keyframing/to_colmap.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 43d569a..87dcde7 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -18,12 +18,16 @@ from ..config.options import EstimateToColmapOptions from ...utils.general import ( get_matched_timestamps, + extract_images_from_vrs, +) +from ...utils.transformation import ( get_t_imu_camera, - camera_colmap_from_calib, rigid3d_from_transform, get_closed_loop_data_from_mps, get_mps_poses_for_timestamps, - extract_images_from_vrs, +) +from ...utils.camera import ( + camera_colmap_from_calib, ) from ...utils.estimate import ( check_estimate_format, From 14952cce605f3a30e8c8e8c62556632dc0a245db Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 13:23:44 +0200 Subject: [PATCH 192/665] to colmap --- lamaria/rig/keyframing/to_colmap.py | 63 ++++++++++++++++++++++------- 1 file changed, 48 insertions(+), 15 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 87dcde7..13eee77 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -1,7 +1,7 @@ from __future__ import annotations -from typing import List, Tuple +from typing import List, Tuple, Dict from pathlib import Path import numpy as np import pycolmap @@ -74,7 +74,9 @@ def _init_io(self): self._mps_data_provider = mps.MpsDataProvider(data_paths) def _init_data(self): - """Extracts images, timestamps and builds per-frame data""" + """Extracts images, timestamps and builds per-frame data object. + Per-frame data is used to create the initial Lamaria reconstruction. + """ extract_images_from_vrs( vrs_file=self.options.vrs, @@ -88,7 +90,11 @@ def _init_data(self): closed_loop_data = get_closed_loop_data_from_mps(self.options.mps) pose_timestamps = [ l for l, _ in timestamps ] mps_poses = get_mps_poses_for_timestamps(closed_loop_data, pose_timestamps) - self._per_frame_data = self._build_per_frame_data_from_mps(images, timestamps, mps_poses) + self._per_frame_data = self._build_per_frame_data_from_mps( + images, + timestamps, + mps_poses + ) else: flag = check_estimate_format(self.options.estimate) if not flag: @@ -101,10 +107,19 @@ def _init_data(self): rig_from_worlds = get_rig_from_worlds_from_estimate( self.options.estimate, ) - self._per_frame_data = self._build_per_frame_data_from_estimate(images, timestamps, rig_from_worlds) - - def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[PerFrameData]: - per_frame_data = [] + self._per_frame_data = self._build_per_frame_data_from_estimate( + images, + timestamps, + rig_from_worlds + ) + + def _build_per_frame_data_from_mps( + self, + images, + timestamps, + mps_poses + ) -> Dict[int, PerFrameData]: + per_frame_data: Dict[int, PerFrameData] = {} imu_stream_label = self._vrs_provider.get_label_from_stream_id( self._right_imu_sid ) @@ -115,6 +130,8 @@ def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[ imu_stream_label ) + frame_id = 1 + for (left_img, right_img), (left_ts, right_ts), t_world_device \ in zip(images, timestamps, mps_poses): @@ -145,24 +162,34 @@ def _build_per_frame_data_from_mps(self, images, timestamps, mps_poses) -> List[ right_img=right_img, rig_from_world=rig_from_world ) - per_frame_data.append(pfd) + per_frame_data[frame_id] = pfd + frame_id += 1 return per_frame_data - def _build_per_frame_data_from_estimate(self, images, timestamps, rig_from_worlds) -> List[PerFrameData]: - per_frame_data = [] + def _build_per_frame_data_from_estimate( + self, + images, + timestamps, + rig_from_worlds + ) -> Dict[int, PerFrameData]: + per_frame_data: Dict[int, PerFrameData] = {} assert len(images) == len(timestamps) == len(rig_from_worlds), \ "Number of images, timestamps and poses must be equal" + + frame_id = 1 + for (left_img, right_img), ts, rig_from_world \ in zip(images, timestamps, rig_from_worlds): pfd = PerFrameData( left_ts=ts, - right_ts=ts, # right timestamp is not available in estimate + right_ts=ts, left_img=left_img, right_img=right_img, rig_from_world=rig_from_world ) - per_frame_data.append(pfd) + per_frame_data[frame_id] = pfd + frame_id += 1 return per_frame_data @@ -250,6 +277,8 @@ def _get_dummy_imu_params(self) -> List: return width, height, random_params def _add_device_sensors(self) -> None: + """Adds a new rig with device calibrated sensors. + The rig is consistent across all frames""" device_calibration = self._vrs_provider.get_device_calibration() imu_stream_label = self._vrs_provider.get_label_from_stream_id( self._right_imu_sid @@ -298,7 +327,9 @@ def _add_device_sensors(self) -> None: self.data.reconstruction.add_rig(rig) def _add_online_sensors(self) -> None: - """Adds a new rig for each timestamp, with sensors calibrated online""" + """Adds a new rig for each frame timestamp. + Each rig has its own online calibrated sensors. + """ sensor_id = 1 for id, pfd in enumerate(self._per_frame_data): t = pfd.left_ts @@ -357,10 +388,11 @@ def _add_online_sensors(self) -> None: self.data.reconstruction.add_rig(rig) def _add_device_frames(self) -> None: + """Adds frame data for each rig, all rigs share same device calibrated sensors""" image_id = 1 rig = self.data.reconstruction.rigs[1] - for id, pfd in enumerate(self._per_frame_data): + for id, pfd in self._per_frame_data.items(): frame = pycolmap.Frame() frame.rig_id = rig.rig_id frame.frame_id = id + 1 # unique id @@ -384,9 +416,10 @@ def _add_device_frames(self) -> None: self.data.reconstruction.add_image(im) def _add_online_frames(self) -> None: + """Adds frame data for each rig, each rig has its own online calibrated sensors""" image_id = 1 - for id, pfd in enumerate(self._per_frame_data): + for id, pfd in self._per_frame_data.items(): frame = pycolmap.Frame() frame.rig_id = id + 1 frame.frame_id = id + 1 From 5ea1231866c719ce913bdb7d050ecb8d88ed63b2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 13:26:16 +0200 Subject: [PATCH 193/665] to colmap --- lamaria/rig/keyframing/to_colmap.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 13eee77..58d0fed 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -119,6 +119,7 @@ def _build_per_frame_data_from_mps( timestamps, mps_poses ) -> Dict[int, PerFrameData]: + per_frame_data: Dict[int, PerFrameData] = {} imu_stream_label = self._vrs_provider.get_label_from_stream_id( self._right_imu_sid @@ -173,6 +174,7 @@ def _build_per_frame_data_from_estimate( timestamps, rig_from_worlds ) -> Dict[int, PerFrameData]: + per_frame_data: Dict[int, PerFrameData] = {} assert len(images) == len(timestamps) == len(rig_from_worlds), \ "Number of images, timestamps and poses must be equal" From bb39768c7444083aedaf80bf6e6d3513cf54c85e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 13:36:23 +0200 Subject: [PATCH 194/665] to colmap --- lamaria/rig/keyframing/to_colmap.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 58d0fed..5cdf5a4 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -445,7 +445,7 @@ def _add_online_frames(self) -> None: for im in images_to_add: self.data.reconstruction.add_image(im) - def _get_rectified_imu_data(self) -> Path: + def _get_rectified_imu_data(self) -> pycolmap.ImuMeasurements: """Generates rectified IMU data from VRS file""" if self.options.mps.use_online_calibration \ and self.options.mps.use_mps: @@ -461,7 +461,7 @@ def _get_rectified_imu_data(self) -> Path: return ms def create(self) -> LamariaReconstruction: - """Creates an empty COLMAP reconstruction with cameras and frames""" + """Creates Lamaria reconstruction with timestamps, IMU data, sensors and frames""" if self.options.mps.use_online_calibration \ and self.options.mps.use_mps: self._add_online_sensors() @@ -470,7 +470,14 @@ def create(self) -> LamariaReconstruction: self._add_device_sensors() self._add_device_frames() + # Populating IMU data ms = self._get_rectified_imu_data() self.data.imu_measurements = ms + # Populating timestamps map + self.data.timestamps = { + frame_id: pfd.left_ts + for frame_id, pfd in self._per_frame_data.items() + } + return self.data From 0ab3bfafb8c6e421fe73141bf7455832204ef9b1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 13:37:36 +0200 Subject: [PATCH 195/665] kf selection --- lamaria/rig/keyframing/keyframe_selection.py | 63 +++++++++----------- 1 file changed, 29 insertions(+), 34 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 2b258b4..9cc57ac 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -4,27 +4,28 @@ import numpy as np from pathlib import Path from copy import deepcopy -from dataclasses import dataclass from typing import List, Optional import pycolmap from ... import logger +from ..lamaria_reconstruction import LamariaReconstruction from ..config.options import KeyframeSelectorOptions -from ...utils.general import get_magnitude_from_transform +from ...utils.transformation import get_magnitude_from_transform class KeyframeSelector: def __init__( self, options: KeyframeSelectorOptions, - reconstruction: pycolmap.Reconstruction + data: LamariaReconstruction, ): self.options = options - self.init_recons = reconstruction - self.timestamps = np.load(self.options.paths.full_ts).tolist() + self.init_data: LamariaReconstruction = data + self.init_recons = data.reconstruction # pycolmap.Reconstruction + self.timestamps = data.timestamps # frame id to timestamp mapping - self.keyframed_recons = pycolmap.Reconstruction() + self.keyframed_data: LamariaReconstruction = LamariaReconstruction() self.keyframe_frame_ids: Optional[List[int]] = None def _select_keyframes(self): @@ -44,7 +45,7 @@ def _select_keyframes(self): current_rig_from_previous_rig = current_rig_from_world * previous_rig_from_world.inverse() dr_dt += np.array(get_magnitude_from_transform(current_rig_from_previous_rig)) - dts += self.timestamps[i+1] - self.timestamps[i] + dts += self.timestamps[curr] - self.timestamps[prev] if dr_dt[0] > self.options.max_rotation or \ dr_dt[1] > self.options.max_distance or \ @@ -64,7 +65,7 @@ def _build_device_keyframed_reconstruction(self): cam_map[ref_sensor_id] = camera_id new_ref_sensor = self._clone_camera(ref_sensor_id, camera_id) camera_id += 1 - self.keyframed_recons.add_camera(new_ref_sensor) + self.keyframed_data.reconstruction.add_camera(new_ref_sensor) new_rig.add_ref_sensor(new_ref_sensor.sensor_id) for sensor, sensor_from_rig in old_rig.non_ref_sensors.items(): @@ -72,10 +73,10 @@ def _build_device_keyframed_reconstruction(self): cam_map[sensor.id] = camera_id camera_id += 1 new_sensor_from_rig = deepcopy(sensor_from_rig) - self.keyframed_recons.add_camera(new_sensor) + self.keyframed_data.reconstruction.add_camera(new_sensor) new_rig.add_sensor(new_sensor.sensor_id, new_sensor_from_rig) - self.keyframed_recons.add_rig(new_rig) + self.keyframed_data.reconstruction.add_rig(new_rig) image_id = 1 for i, frame_id in enumerate(self.keyframe_frame_ids): @@ -105,9 +106,9 @@ def _build_device_keyframed_reconstruction(self): images_to_add.append(new_image) image_id += 1 - self.keyframed_recons.add_frame(new_frame) + self.keyframed_data.reconstruction.add_frame(new_frame) for img in images_to_add: - self.keyframed_recons.add_image(img) + self.keyframed_data.reconstruction.add_image(img) def _clone_camera(self, old_camera_id: int, new_camera_id: int) -> pycolmap.Camera: old_camera = self.init_recons.cameras[old_camera_id] @@ -135,7 +136,7 @@ def _build_online_keyframed_reconstruction(self): # IMU cosplaying as a dummy camera old_ref_sensor_id = old_rig.ref_sensor_id.id new_ref_sensor = self._clone_camera(old_ref_sensor_id, camera_id) - self.keyframed_recons.add_camera(new_ref_sensor) + self.keyframed_data.reconstruction.add_camera(new_ref_sensor) cam_id_map[old_ref_sensor_id] = camera_id camera_id += 1 @@ -147,14 +148,14 @@ def _build_online_keyframed_reconstruction(self): if old_sensor_id not in cam_id_map: new_sensor = self._clone_camera(old_sensor_id, camera_id) - self.keyframed_recons.add_camera(new_sensor) + self.keyframed_data.reconstruction.add_camera(new_sensor) cam_id_map[old_sensor_id] = camera_id camera_id += 1 new_sensor_from_rig = deepcopy(sensor_from_rig) new_rig.add_sensor(new_sensor.sensor_id, new_sensor_from_rig) - self.keyframed_recons.add_rig(new_rig) + self.keyframed_data.reconstruction.add_rig(new_rig) new_frame = pycolmap.Frame() new_frame.rig_id = new_rig.rig_id @@ -178,21 +179,29 @@ def _build_online_keyframed_reconstruction(self): images_to_add.append(new_image) image_id += 1 - self.keyframed_recons.add_frame(new_frame) + self.keyframed_data.reconstruction.add_frame(new_frame) for img in images_to_add: - self.keyframed_recons.add_image(img) + self.keyframed_data.reconstruction.add_image(img) rig_id += 1 - def run_keyframing(self) -> pycolmap.Reconstruction: + def run_keyframing(self) -> LamariaReconstruction: """ Main function to run keyframing.""" self._select_keyframes() if len(self.init_recons.rigs.keys()) == 1: # device rig has been added self._build_device_keyframed_reconstruction() else: self._build_online_keyframed_reconstruction() + + # set timestamps keys as the new frame ids + self.keyframed_data.timestamps = { + frame_id: self.timestamps[frame_id] + for frame_id in self.keyframe_frame_ids + } + + self.keyframed_data.imu_measurements = deepcopy(self.init_data.imu_measurements) - return self.keyframed_recons + return self.keyframed_data def copy_images_to_keyframes_dir(self) -> Path: """ Copy images corresponding to keyframes to a separate directory. """ @@ -218,18 +227,4 @@ def copy_images_to_keyframes_dir(self) -> Path: shutil.copy2(src_path, dst_path) - return output_dir - - def write_keyframe_timestamps(self) -> Path: - output_path = self.options.paths.kf_ts - output_path.parent.mkdir(parents=True, exist_ok=True) - keyframed_timestamps = np.array([self.timestamps[i - 1] for i in self.keyframe_frame_ids]) - np.save(output_path, keyframed_timestamps) - return output_path - - def write_reconstruction(self) -> Path: - output_path = self.options.paths.kf_model - output_path.mkdir(parents=True, exist_ok=True) - logger.info(f"Keyframed {self.keyframed_recons.summary()}") - self.keyframed_recons.write(output_path) - return output_path \ No newline at end of file + return output_dir \ No newline at end of file From 26974d862817823ee5ee3aa4f69cde8fb94fa03c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 13:48:24 +0200 Subject: [PATCH 196/665] d --- lamaria/rig/config/defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/defaults.yaml b/lamaria/rig/config/defaults.yaml index ba9c535..7dc6711 100644 --- a/lamaria/rig/config/defaults.yaml +++ b/lamaria/rig/config/defaults.yaml @@ -64,4 +64,4 @@ optimization: mps: use_mps: false use_online_calibration: false # relevant only when use_mps is true (for online calib file) - has_slam_drops: false # check vrs json metadata file for each sequence + has_slam_drops: false From 8b87f872f24da54e66116c5dd7cb2e482fd2978d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 13:51:37 +0200 Subject: [PATCH 197/665] defs --- lamaria/rig/config/defaults.yaml => defaults.yaml | 0 lamaria/rig/config/pipeline.py | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) rename lamaria/rig/config/defaults.yaml => defaults.yaml (100%) diff --git a/lamaria/rig/config/defaults.yaml b/defaults.yaml similarity index 100% rename from lamaria/rig/config/defaults.yaml rename to defaults.yaml diff --git a/lamaria/rig/config/pipeline.py b/lamaria/rig/config/pipeline.py index 298e3c5..1b9f3a0 100644 --- a/lamaria/rig/config/pipeline.py +++ b/lamaria/rig/config/pipeline.py @@ -11,7 +11,7 @@ ) class PipelineOptions: - default_cfg: Path = Path("lamaria/rig/config/defaults.yaml") + default_cfg: Path = Path("defaults.yaml") workspace: Path = Path("/media/lamaria/") seq_name: str = "5cp" From c0b2ccb04abc818f80b9054b33115069f1c85b2b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 13:52:25 +0200 Subject: [PATCH 198/665] defs --- defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/defaults.yaml b/defaults.yaml index 7dc6711..3b31c97 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -1,4 +1,4 @@ -# Default configuration for lamaria rig pipeline +# Default configuration for run_pipeline.py workspace: /media/arialamar/ seq_name: 5cp From 62f8d023d8810b18e9a10517c4d4e5813e52e66c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 14:35:46 +0200 Subject: [PATCH 199/665] colmap model --- defaults.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/defaults.yaml b/defaults.yaml index 3b31c97..1eb42c1 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -8,6 +8,7 @@ estimate_to_colmap: estimate: est/${seq_name}.txt mps_folder: mps/mps_${seq_name}_vrs/ # necessary if use_mps is true images: image_stream + colmap_model: initial_recon sensor: camera_model: RAD_TAN_THIN_PRISM_FISHEYE From afedcac500d5fc335ff4f10844ac5fee171306c9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 14:49:00 +0200 Subject: [PATCH 200/665] copy images --- lamaria/rig/keyframing/keyframe_selection.py | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 9cc57ac..ca59004 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -186,7 +186,7 @@ def _build_online_keyframed_reconstruction(self): rig_id += 1 def run_keyframing(self) -> LamariaReconstruction: - """ Main function to run keyframing.""" + """ Main function to run keyframing on input lamaria reconstruction.""" self._select_keyframes() if len(self.init_recons.rigs.keys()) == 1: # device rig has been added self._build_device_keyframed_reconstruction() @@ -202,14 +202,20 @@ def run_keyframing(self) -> LamariaReconstruction: self.keyframed_data.imu_measurements = deepcopy(self.init_data.imu_measurements) return self.keyframed_data - - def copy_images_to_keyframes_dir(self) -> Path: - """ Copy images corresponding to keyframes to a separate directory. """ + + def copy_images_to_keyframes_dir( + self, + images: Path, + output: Optional[Path] = None, + ) -> Path: + """ Copy images corresponding to keyframes to a separate directory. + Images are expected to be in `images/left` and `images/right` subdirectories. + Check: `extract_images_from_vrs` in `lamaria/utils/general.py` for more details. + """ if self.keyframe_frame_ids is None: raise ValueError("Keyframes not selected yet. Run `run_keyframing` first.") - output_dir = self.options.paths.keyframes - image_stream_root = self.options.paths.images + output_dir = output if output is not None else self.options.keyframes if output_dir.exists() and any(output_dir.iterdir()): shutil.rmtree(output_dir) @@ -222,7 +228,7 @@ def copy_images_to_keyframes_dir(self) -> Path: image = self.init_recons.images[data_id.id] subdir = "left" if "1201-1" in image.name else "right" - src_path = image_stream_root / subdir / image.name + src_path = images / subdir / image.name dst_path = output_dir / image.name shutil.copy2(src_path, dst_path) From 3917001a116572db006cf68571972da41618b500 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 14:49:25 +0200 Subject: [PATCH 201/665] kf --- lamaria/rig/keyframing/keyframe_selection.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index ca59004..d6fbba5 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -8,7 +8,6 @@ import pycolmap -from ... import logger from ..lamaria_reconstruction import LamariaReconstruction from ..config.options import KeyframeSelectorOptions from ...utils.transformation import get_magnitude_from_transform From bf0516a7ed6cd396024a13a33073f87b28e16635 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 14:52:14 +0200 Subject: [PATCH 202/665] opts --- lamaria/rig/config/options.py | 37 +++++++++++++++++++++-------------- 1 file changed, 22 insertions(+), 15 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 3e287e7..6996120 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -44,12 +44,13 @@ class EstimateToColmapOptions: vrs: Path = Path("recordings/xyz.vrs") estimate: Path = Path("estimates/xyz.txt") images: Path = Path("image_stream") - mps_folder: Path = Path("mps/mps_xyz_vrs") # necessary if use_mps is true + colmap_model: Path = Path("initial_recon") mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) - output_path: Path = Path("/output") + mps_folder: Optional[Path] = None # necessary if use_mps is true + output_path: Optional[Path] = None @classmethod def load( @@ -71,18 +72,20 @@ def load( def set_custom_paths( self, - output_path: Path, vrs: Path, estimate: Path, images: Path, + colmap_model: Path, + output_path: Optional[Path] = None, mps_folder: Optional[Path] = None, ) -> EstimateToColmapOptions: return replace( self, - output_path=output_path, vrs=vrs, estimate=estimate, images=images, + colmap_model=colmap_model, + output_path=output_path if output_path is not None else self.output_path, mps_folder=mps_folder if mps_folder is not None else self.mps_folder ) @@ -97,7 +100,7 @@ class KeyframeSelectorOptions: max_distance: float = 1.0 # meters max_elapsed: int = int(1e9) # 1 second in ns - output_path: Path = Path("/output") + output_path: Optional[Path] = None @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": @@ -114,15 +117,15 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": def set_custom_paths( self, - output_path: Path, keyframes: Path, - kf_model: Path + kf_model: Path, + output_path: Optional[Path] = None, ) -> KeyframeSelectorOptions: return replace( self, - output_path=output_path, keyframes=keyframes, - kf_model=kf_model + kf_model=kf_model, + output_path=output_path if output_path is not None else self.output_path, ) @@ -146,7 +149,7 @@ class TriangulatorOptions: filter_max_reproj_error: float = 4.0 filter_min_tri_angle: float = 1.5 - output_path: Path = Path("/output") + output_path: Optional[Path] = None @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "TriangulatorOptions": @@ -157,17 +160,17 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "TriangulatorOptions": def set_custom_paths( self, - output_path: Path, hloc: Path, pairs_file: Path, - tri_model: Path + tri_model: Path, + output_path: Optional[Path] = None, ) -> TriangulatorOptions: return replace( self, - output_path=output_path, hloc=hloc, pairs_file=pairs_file, - tri_model=tri_model + tri_model=tri_model, + output_path=output_path if output_path is not None else self.output_path ) @@ -204,6 +207,8 @@ class VIOptimizerOptions: colmap_pipeline: pycolmap.IncrementalPipelineOptions = \ pycolmap.IncrementalPipelineOptions() + + output_path: Optional[Path] = None @classmethod def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": @@ -226,8 +231,10 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": def set_custom_paths( self, optim_model: Path, + output_path: Optional[Path] = None ) -> VIOptimizerOptions: return replace( self, - optim=replace(self.optim, optim_model=optim_model) + optim=replace(self.optim, optim_model=optim_model), + output_path=output_path if output_path is not None else self.output_path ) From 92d2a91fe71ce2971ae6d51404d1e9a6d43e3c77 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 14:53:37 +0200 Subject: [PATCH 203/665] pipeline --- lamaria/rig/config/pipeline.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/config/pipeline.py b/lamaria/rig/config/pipeline.py index 1b9f3a0..dff1dcb 100644 --- a/lamaria/rig/config/pipeline.py +++ b/lamaria/rig/config/pipeline.py @@ -77,8 +77,9 @@ def get_estimate_to_colmap_options(self) -> EstimateToColmapOptions: vrs=self.workspace_path / options.vrs, estimate=self.workspace_path / options.estimate, images=self.output_path / options.images, - mps_folder=(self.workspace_path / options.mps_folder) if options.mps_folder else None, + colmap_model=self.output_path / options.colmap_model, output_path=self.output_path, + mps_folder=(self.workspace_path / options.mps_folder) if options.mps_folder else None, ) def get_keyframing_options(self) -> KeyframeSelectorOptions: @@ -107,7 +108,7 @@ def get_vi_optimizer_options(self) -> VIOptimizerOptions: options = VIOptimizerOptions.load(self._cfg.optimization) return replace( options, - optim_model=self.output_path / options.optim_model, + optim_model=self.output_path / options.optim.optim_model, output_path=self.output_path, ) \ No newline at end of file From c18659471fd4b1e834d820321edb1872159fc8db Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 15:09:21 +0200 Subject: [PATCH 204/665] tri --- lamaria/rig/optim/triangulation.py | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 8d7f81a..03c24a3 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -63,23 +63,23 @@ def postprocess_pairs_with_reconstruction( f.write(f"{a} {b}\n") -def run( +def run_triangulation( options: TriangulatorOptions, + reference_model: Path, # reconstruction path + keyframes: Path, ) -> Path: - keyframes_dir = options.paths.keyframes - if not keyframes_dir.exists(): - raise FileNotFoundError(f"keyframes_dir not found at {keyframes_dir}") + if not keyframes.exists(): + raise FileNotFoundError(f"keyframes_dir not found at {keyframes}") - hloc_outputs_dir = options.paths.hloc + hloc_outputs_dir = options.hloc hloc_outputs_dir.mkdir(parents=True, exist_ok=True) - reference_model_path = options.paths.kf_model - if not reference_model_path.exists(): - raise FileNotFoundError(f"reference_model not found at {reference_model_path}") + if not reference_model.exists(): + raise FileNotFoundError(f"reference_model not found at {reference_model}") - triangulated_model_path = options.paths.tri_model - pairs_path = options.paths.pairs_file + triangulated_model_path = options.tri_model + pairs_path = options.pairs_file retrieval_conf = extract_features.confs[options.retrieval_conf] feature_conf = extract_features.confs[options.feature_conf] @@ -90,11 +90,11 @@ def run( options.feature_conf, options.matcher_conf) - retrieval_path = extract_features.main(retrieval_conf, image_dir=keyframes_dir, export_dir=hloc_outputs_dir) - features_path = extract_features.main(feature_conf, image_dir=keyframes_dir, export_dir=hloc_outputs_dir) + retrieval_path = extract_features.main(retrieval_conf, image_dir=keyframes, export_dir=hloc_outputs_dir) + features_path = extract_features.main(feature_conf, image_dir=keyframes, export_dir=hloc_outputs_dir) pairs_from_retrieval.main(retrieval_path, pairs_path, options.num_retrieval_matches) - postprocess_pairs_with_reconstruction(pairs_path, reference_model_path) + postprocess_pairs_with_reconstruction(pairs_path, reference_model) matches_path = match_features.main( conf=matcher_conf, @@ -105,8 +105,8 @@ def run( _ = triangulation.main( sfm_dir=triangulated_model_path, - reference_model=reference_model_path, - image_dir=keyframes_dir, + reference_model=reference_model, + image_dir=keyframes, pairs=pairs_path, features=features_path, matches=matches_path, From f2811f099406f3097db047377db8b0867decb53c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 15:09:35 +0200 Subject: [PATCH 205/665] run --- lamaria/rig/optim/triangulation.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 03c24a3..2f84704 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -63,7 +63,7 @@ def postprocess_pairs_with_reconstruction( f.write(f"{a} {b}\n") -def run_triangulation( +def run( options: TriangulatorOptions, reference_model: Path, # reconstruction path keyframes: Path, From e7c71b4aa6d295eb5ced5a1c1cbc19c8c7cc1534 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 15:33:15 +0200 Subject: [PATCH 206/665] bug fic --- lamaria/rig/config/pipeline.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/config/pipeline.py b/lamaria/rig/config/pipeline.py index dff1dcb..2102422 100644 --- a/lamaria/rig/config/pipeline.py +++ b/lamaria/rig/config/pipeline.py @@ -63,7 +63,7 @@ def seq_name(self) -> str: @property def output_path(self) -> Path: - return self.workspace / "output" / self.seq_name + return self.workspace_path / "output" / self.seq_name def get_estimate_to_colmap_options(self) -> EstimateToColmapOptions: """Get EstimateToColmapOptions from config.""" From 4467bc78767a7a75e670e71a789bb706d62fd288 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 15:33:33 +0200 Subject: [PATCH 207/665] run piprline --- run_pipeline.py | 157 ++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 157 insertions(+) create mode 100644 run_pipeline.py diff --git a/run_pipeline.py b/run_pipeline.py new file mode 100644 index 0000000..b2ff62a --- /dev/null +++ b/run_pipeline.py @@ -0,0 +1,157 @@ +import pycolmap +from copy import deepcopy +from typing import Optional +from pathlib import Path + +from lamaria.rig.lamaria_reconstruction import LamariaReconstruction +from lamaria.rig.keyframing.to_colmap import EstimateToColmap +from lamaria.rig.keyframing.keyframe_selection import KeyframeSelector +from lamaria.rig.optim.triangulation import run as triangulation_run +from lamaria.rig.optim.session import SingleSeqSession +from lamaria.rig.optim.vi_optimization import run +from lamaria.rig.config.pipeline import PipelineOptions +from lamaria.rig.config.options import ( + EstimateToColmapOptions, + KeyframeSelectorOptions, + TriangulatorOptions +) + + +def run_estimate_to_colmap( + options: EstimateToColmapOptions, + vrs: Path, + estimate: Path, + images: Path, + colmap_model: Path, + mps_folder: Optional[Path] = None, +) -> LamariaReconstruction: + + options = options.set_custom_paths( + vrs, + estimate, + images, + colmap_model, + mps_folder, + ) + + est_to_colmap = EstimateToColmap(options) + lamaria_recon = est_to_colmap.create() + + if not colmap_model.exists(): + colmap_model.mkdir(parents=True, exist_ok=True) + + lamaria_recon.write(colmap_model) + + return lamaria_recon + + +def run_keyframe_selection( + options: KeyframeSelectorOptions, + input: Path | LamariaReconstruction, + images: Path, + keyframes: Path, + kf_model: Path, +) -> LamariaReconstruction: + + if isinstance(input, Path): + input_recon = LamariaReconstruction.read(input) + else: + input_recon = input + + options = options.set_custom_paths( + keyframes, + kf_model, + ) + + kf_selector = KeyframeSelector(options, input_recon) + kf_lamaria_recon = kf_selector.run_keyframing() + + if not kf_model.exists(): + kf_model.mkdir(parents=True, exist_ok=True) + + kf_lamaria_recon.write(kf_model) + + if not keyframes.exists(): + keyframes.mkdir(parents=True, exist_ok=True) + + kf_selector.copy_images_to_keyframes_dir(images, keyframes) + + return kf_lamaria_recon + + +def run_triangulation( + options: TriangulatorOptions, + input: Path, # path to LamariaReconstruction + keyframes: Path, + hloc: Path, + pairs_file: Path, + tri_model: Path, +) -> LamariaReconstruction: + if not isinstance(input, Path): + raise ValueError("Input must be a Path to the reconstruction") + + assert input.exists(), f"input reconstruction path {input} does not exist" + + options = options.set_custom_paths( + hloc, + pairs_file, + tri_model, + ) + + triangulated_model_path = triangulation_run( + options, + reference_model=input, + keyframes=keyframes, + ) + + input_lamaria_recon = LamariaReconstruction.read(input) + tri_recon = pycolmap.Reconstruction(triangulated_model_path) + + tri_lamaria_recon = LamariaReconstruction() + tri_lamaria_recon.reconstruction = tri_recon + tri_lamaria_recon.timestamps = \ + deepcopy(input_lamaria_recon.timestamps) + tri_lamaria_recon.imu_measurements = \ + deepcopy(input_lamaria_recon.imu_measurements) + + tri_lamaria_recon.write(triangulated_model_path) + + return tri_lamaria_recon + + +def run_pipeline(): + pipeline_options = PipelineOptions() + + # Step 1: Estimate to COLMAP + est_options = pipeline_options.get_estimate_to_colmap_options() + _ = run_estimate_to_colmap( + est_options, + est_options.vrs, + est_options.estimate, + est_options.images, + est_options.colmap_model, + ) + + # Step 2: Keyframe Selection + kf_options = pipeline_options.get_keyframing_options() + _ = run_keyframe_selection( + kf_options, + est_options.colmap_model, + est_options.images, + kf_options.keyframes, + kf_options.kf_model, + ) + + # Step 3: Triangulation + tri_options = pipeline_options.get_triangulator_options() + _ = run_triangulation( + tri_options, + kf_options.kf_model, + kf_options.keyframes, + tri_options.hloc, + tri_options.pairs_file, + tri_options.tri_model, + ) + +if __name__ == "__main__": + run_pipeline() From df4829cb269edff6feb0e78a3ae1ab38455a6c47 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 15:54:19 +0200 Subject: [PATCH 208/665] fix --- lamaria/rig/keyframing/to_colmap.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 5cdf5a4..a2b48ee 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -333,7 +333,7 @@ def _add_online_sensors(self) -> None: Each rig has its own online calibrated sensors. """ sensor_id = 1 - for id, pfd in enumerate(self._per_frame_data): + for fid, pfd in self._per_frame_data.items(): t = pfd.left_ts calibration = self._mps_data_provider.get_online_calibration( t, TimeQueryOptions.CLOSEST @@ -341,7 +341,7 @@ def _add_online_sensors(self) -> None: if calibration is None: continue - rig = pycolmap.Rig(rig_id=id + 1) + rig = pycolmap.Rig(rig_id=fid) w, h, p = self._get_dummy_imu_params() # DUMMY CAMERA FOR IMU imu = pycolmap.Camera( @@ -394,10 +394,10 @@ def _add_device_frames(self) -> None: image_id = 1 rig = self.data.reconstruction.rigs[1] - for id, pfd in self._per_frame_data.items(): + for fid, pfd in self._per_frame_data.items(): frame = pycolmap.Frame() frame.rig_id = rig.rig_id - frame.frame_id = id + 1 # unique id + frame.frame_id = fid frame.rig_from_world = pfd.rig_from_world images_to_add = [] @@ -421,10 +421,10 @@ def _add_online_frames(self) -> None: """Adds frame data for each rig, each rig has its own online calibrated sensors""" image_id = 1 - for id, pfd in self._per_frame_data.items(): + for fid, pfd in self._per_frame_data.items(): frame = pycolmap.Frame() - frame.rig_id = id + 1 - frame.frame_id = id + 1 + frame.rig_id = fid + frame.frame_id = fid frame.rig_from_world = pfd.rig_from_world images_to_add = [] From 050e66e45e7b8c5ea0498f4a848bdbba96b1b8d9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 16:05:13 +0200 Subject: [PATCH 209/665] la --- lamaria/rig/lamaria_reconstruction.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/lamaria_reconstruction.py b/lamaria/rig/lamaria_reconstruction.py index af965b7..261ffba 100644 --- a/lamaria/rig/lamaria_reconstruction.py +++ b/lamaria/rig/lamaria_reconstruction.py @@ -6,12 +6,13 @@ from .. import logger class LamariaReconstruction: - reconstruction: pycolmap.Reconstruction - timestamps: Dict[int, int] - imu_measurements: pycolmap.ImuMeasurements + def __init__(self) -> None: + self.reconstruction = pycolmap.Reconstruction() + self.timestamps = {} + self.imu_measurements = pycolmap.ImuMeasurements([]) @classmethod - def read_reconstruction( + def read( cls, input_folder: Path, ) -> "LamariaReconstruction": @@ -41,7 +42,7 @@ def read_reconstruction( return instance - def write_reconstruction( + def write( self, output_folder: Path, ) -> None: From f64620afc9f93464930ef734732ab1015f639f7a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 16:13:27 +0200 Subject: [PATCH 210/665] run pipelimne --- run_pipeline.py | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index b2ff62a..34343d9 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -34,12 +34,14 @@ def run_estimate_to_colmap( mps_folder, ) - est_to_colmap = EstimateToColmap(options) - lamaria_recon = est_to_colmap.create() - - if not colmap_model.exists(): + if colmap_model.exists(): + lamaria_recon = LamariaReconstruction.read(colmap_model) + return lamaria_recon + else: colmap_model.mkdir(parents=True, exist_ok=True) + est_to_colmap = EstimateToColmap(options) + lamaria_recon = est_to_colmap.create() lamaria_recon.write(colmap_model) return lamaria_recon @@ -63,11 +65,14 @@ def run_keyframe_selection( kf_model, ) + if kf_model.exists(): + kf_lamaria_recon = LamariaReconstruction.read(kf_model) + return kf_lamaria_recon + else: + kf_model.mkdir(parents=True, exist_ok=True) + kf_selector = KeyframeSelector(options, input_recon) kf_lamaria_recon = kf_selector.run_keyframing() - - if not kf_model.exists(): - kf_model.mkdir(parents=True, exist_ok=True) kf_lamaria_recon.write(kf_model) @@ -109,11 +114,8 @@ def run_triangulation( tri_lamaria_recon = LamariaReconstruction() tri_lamaria_recon.reconstruction = tri_recon - tri_lamaria_recon.timestamps = \ - deepcopy(input_lamaria_recon.timestamps) - tri_lamaria_recon.imu_measurements = \ - deepcopy(input_lamaria_recon.imu_measurements) - + tri_lamaria_recon.timestamps = input_lamaria_recon.timestamps + tri_lamaria_recon.imu_measurements = input_lamaria_recon.imu_measurements tri_lamaria_recon.write(triangulated_model_path) return tri_lamaria_recon From 703877e620c20d1958b37324a6ee0256f40b7ec1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 16:21:01 +0200 Subject: [PATCH 211/665] lamaria recon --- lamaria/rig/lamaria_reconstruction.py | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/lamaria/rig/lamaria_reconstruction.py b/lamaria/rig/lamaria_reconstruction.py index 261ffba..2b641d1 100644 --- a/lamaria/rig/lamaria_reconstruction.py +++ b/lamaria/rig/lamaria_reconstruction.py @@ -37,8 +37,6 @@ def read( does not exist in {input_folder}" rectified_imu_data = np.load(rectified_imu_data_npy, allow_pickle=True) instance.imu_measurements = pycolmap.ImuMeasurements(rectified_imu_data.tolist()) - - logger.info(f"Reconstruction read from {input_folder}") return instance @@ -57,5 +55,4 @@ def write( f.write(f"{frame_id} {self.timestamps[frame_id]}\n") rectified_imu_data_npy = output_folder / "rectified_imu_data.npy" - np.save(rectified_imu_data_npy, self.imu_measurements.data) - logger.info(f"Reconstruction written to {output_folder}") \ No newline at end of file + np.save(rectified_imu_data_npy, self.imu_measurements.data) \ No newline at end of file From f4e5ff541fca7f82d0f85ae2dc0400d3cbf5f7a1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 16:21:32 +0200 Subject: [PATCH 212/665] lamaria --- lamaria/rig/lamaria_reconstruction.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/lamaria/rig/lamaria_reconstruction.py b/lamaria/rig/lamaria_reconstruction.py index 2b641d1..a853bb6 100644 --- a/lamaria/rig/lamaria_reconstruction.py +++ b/lamaria/rig/lamaria_reconstruction.py @@ -3,12 +3,10 @@ from typing import Dict from pathlib import Path -from .. import logger - class LamariaReconstruction: def __init__(self) -> None: self.reconstruction = pycolmap.Reconstruction() - self.timestamps = {} + self.timestamps: Dict[int, int] = {} self.imu_measurements = pycolmap.ImuMeasurements([]) @classmethod From f246dc9abc33142f9697fd4e34ae5105bb5e7651 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 16:46:14 +0200 Subject: [PATCH 213/665] a --- run_pipeline.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/run_pipeline.py b/run_pipeline.py index 34343d9..655a8f8 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -102,6 +102,10 @@ def run_triangulation( pairs_file, tri_model, ) + + if tri_model.exists(): + tri_lamaria_recon = LamariaReconstruction.read(tri_model) + return tri_lamaria_recon triangulated_model_path = triangulation_run( options, From 4c6e76d5a21c945413b96e4f339d86616ace03a5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 16:46:25 +0200 Subject: [PATCH 214/665] a --- lamaria/rig/keyframing/keyframe_selection.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index d6fbba5..b00b410 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -198,7 +198,7 @@ def run_keyframing(self) -> LamariaReconstruction: for frame_id in self.keyframe_frame_ids } - self.keyframed_data.imu_measurements = deepcopy(self.init_data.imu_measurements) + self.keyframed_data.imu_measurements = self.init_data.imu_measurements return self.keyframed_data From d4e288cd5333491a1795211f5a822d7f312d20e3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 16:46:32 +0200 Subject: [PATCH 215/665] a --- lamaria/rig/optim/triangulation.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 2f84704..7539efd 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -45,7 +45,7 @@ def postprocess_pairs_with_reconstruction( reconstruction: pycolmap.Reconstruction | Path ): recon = (reconstruction if isinstance(reconstruction, pycolmap.Reconstruction) - else pycolmap.Reconstruction(str(reconstruction))) + else pycolmap.Reconstruction(reconstruction.as_posix())) frame_pairs, adj_pairs = pairs_from_frames(recon) From 9f01082b5614f36b4eb67390795c7e6e7404f838 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 17:34:26 +0200 Subject: [PATCH 216/665] lamaria in imu --- lamaria/rig/optim/imu.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index 3038c6d..8c6ae58 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -1,12 +1,12 @@ import numpy as np import pycolmap -from typing import List -from pathlib import Path +from typing import Dict from tqdm import tqdm from ... import logger from ..config.options import OptIMUOptions +from ..lamaria_reconstruction import LamariaReconstruction def load_preintegrated_imu_measurements( From 3705520bbe5acdd9bd3c0a6e01f029d493046d23 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 17:35:26 +0200 Subject: [PATCH 217/665] imu stuff --- lamaria/rig/optim/imu.py | 41 ++++++++++++++++++++-------------------- 1 file changed, 20 insertions(+), 21 deletions(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index 8c6ae58..08c033f 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -10,22 +10,21 @@ def load_preintegrated_imu_measurements( - rect_imu_data_npy: Path, - reconstruction: pycolmap.Reconstruction, - timestamps: List[int], # must be a sorted list in ns - params: OptIMUOptions = OptIMUOptions(), -) -> dict[int, pycolmap.PreintegratedImuMeasurement]: + options: OptIMUOptions, + data: LamariaReconstruction, +) -> Dict[int, pycolmap.PreintegratedImuMeasurement]: preintegrated_measurements = {} - rect_imu_data = np.load(rect_imu_data_npy, allow_pickle=True) - imu_measurements = pycolmap.ImuMeasurements(rect_imu_data.tolist()) + + imu_measurements = data.imu_measurements - options = pycolmap.ImuPreintegrationOptions() - options.integration_noise_density = params.integration_noise_density - imu_calib = load_imu_calibration(params.gyro_infl, params.acc_infl) + colmap_imu_opts = pycolmap.ImuPreintegrationOptions() + colmap_imu_opts.integration_noise_density = options.integration_noise_density + imu_calib = load_imu_calibration(options.gyro_infl, options.acc_infl) + + frame_ids = sorted(data.reconstruction.frames.keys()) + timestamps = [data.timestamps[fid] for fid in frame_ids] - frame_ids = sorted(reconstruction.frames.keys()) - assert len(timestamps) == len(frame_ids), "Unequal timestamps and frames for preinteg calc" assert len(frame_ids) >= 2, "Need at least two frames to compute preinteg measurements" ts_sec = np.asarray(timestamps, dtype=np.float64) / 1e9 @@ -39,7 +38,7 @@ def load_preintegrated_imu_measurements( if len(ms) == 0: continue integrated_m = pycolmap.PreintegratedImuMeasurement( - options, + colmap_imu_opts, imu_calib, t1, t2, @@ -50,14 +49,14 @@ def load_preintegrated_imu_measurements( return preintegrated_measurements def load_imu_states( - reconstruction: pycolmap.Reconstruction, - timestamps: List[int] # must be a sorted list in ns -) -> dict[int, pycolmap.ImuState]: + data: LamariaReconstruction, +) -> Dict[int, pycolmap.ImuState]: imu_states = {} - frame_ids = sorted(reconstruction.frames.keys()) - assert len(timestamps) == len(frame_ids), "Unequal timestamps and frames for imu state calc" - assert len(frame_ids) >= 2, "Need at least two frames to compute velocity" + frame_ids = sorted(data.reconstruction.frames.keys()) + timestamps = [data.timestamps[fid] for fid in frame_ids] + + assert len(frame_ids) >= 2, "Need at least two frames to compute imu states" ts_sec = np.asarray(timestamps, dtype=np.float64) / 1e9 @@ -73,8 +72,8 @@ def load_imu_states( if dt == 0: raise ValueError(f"Zero dt between frames {i} and {j}") - pi = reconstruction.frames[i].rig_from_world.inverse().translation - pj = reconstruction.frames[j].rig_from_world.inverse().translation + pi = data.reconstruction.frames[i].rig_from_world.inverse().translation + pj = data.reconstruction.frames[j].rig_from_world.inverse().translation vel = (pj - pi) / dt s = pycolmap.ImuState() From 46f1d13dea341128675a9c73bf7d1c602ac70bce Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 17:38:09 +0200 Subject: [PATCH 218/665] lamaria --- lamaria/rig/lamaria_reconstruction.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/lamaria/rig/lamaria_reconstruction.py b/lamaria/rig/lamaria_reconstruction.py index a853bb6..0744b25 100644 --- a/lamaria/rig/lamaria_reconstruction.py +++ b/lamaria/rig/lamaria_reconstruction.py @@ -47,6 +47,12 @@ def write( ts_path = output_folder / "timestamps.txt" frame_ids = sorted(self.timestamps.keys()) + + # sanity check of frame ids in reconstruction and timestamps + recon_frame_ids = np.array(sorted(self.reconstruction.frames.keys())) + assert np.array_equal(np.array(frame_ids), recon_frame_ids), \ + "Frame IDs in reconstruction and timestamps do not match" + with open(ts_path, 'w') as f: f.write("# FrameID Timestamp(ns)\n") for frame_id in frame_ids: From 40182dac8d175b3c3683f90b6b46dad9bd6bb98a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 22:59:19 +0200 Subject: [PATCH 219/665] iter --- lamaria/rig/optim/iterative_global_ba.py | 18 +++++++++--------- lamaria/rig/optim/session.py | 24 ++++++++---------------- 2 files changed, 17 insertions(+), 25 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 97677f7..fc00761 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -17,13 +17,13 @@ def __init__(self, session: SingleSeqSession): def apply_constraints(self, problem): """Apply rig-specific constraints to the problem""" # Fix the first rig pose - frame_ids = sorted(self.session.reconstruction.frames.keys()) - first_frame = self.session.reconstruction.frames[frame_ids[0]] + frame_ids = sorted(self.session.data.reconstruction.frames.keys()) + first_frame = self.session.data.reconstruction.frames[frame_ids[0]] problem.set_parameter_block_constant(first_frame.rotation.quat) problem.set_parameter_block_constant(first_frame.translation) # Fix 1 DoF translation of the second rig - second_frame = self.session.reconstruction.frames[frame_ids[1]] + second_frame = self.session.data.reconstruction.frames[frame_ids[1]] problem.set_manifold( second_frame.translation, pyceres.SubsetManifold(3, np.array([0])), @@ -38,8 +38,8 @@ def __init__(self, session: SingleSeqSession): self.session = session def _init_callback(self): - frame_ids = sorted(self.session.reconstruction.frames.keys()) - poses = list(self.session.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) + frame_ids = sorted(self.session.data.reconstruction.frames.keys()) + poses = list(self.session.data.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) callback = RefinementCallback(poses) return callback @@ -60,7 +60,7 @@ def solve(self, ba_options, ba_config): problem = bundle_adjuster.problem # Add IMU residuals if enabled - if self.session.imu_params.keep_imu_residuals: + if self.session.imu_options.keep_imu_residuals: problem = imu_manager.add_residuals(problem) # Apply rig constraints @@ -69,13 +69,13 @@ def solve(self, ba_options, ba_config): logger.info("Constrained the rig problem") # Setup solver - if self.session.opt_params.use_callback: + if self.session.opt_options.use_callback: callback = self._init_callback() solver_options.callbacks = [callback] solver_options.minimizer_progress_to_stdout = True solver_options.update_state_every_iteration = True - solver_options.max_num_iterations = self.session.opt_params.max_num_iterations + solver_options.max_num_iterations = self.session.opt_options.max_num_iterations # Solve summary = pyceres.SolverSummary() @@ -165,7 +165,7 @@ def run(self, mapper, pipeline_options): pipeline_options, ) - if self.session.opt_params.normalize_reconstruction: + if self.session.opt_options.normalize_reconstruction: reconstruction.normalize() # Check convergence diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py index d7aae3d..c70f91a 100644 --- a/lamaria/rig/optim/session.py +++ b/lamaria/rig/optim/session.py @@ -5,32 +5,24 @@ import pycolmap import numpy as np -from ..config.loaders import load_cfg from .imu import ( load_imu_states, load_preintegrated_imu_measurements, ) -from .params import ( - CamParams, - OptParams, - IMUParams -) +from ..config.options import VIOptimizerOptions +from ..lamaria_reconstruction import LamariaReconstruction class SingleSeqSession: def __init__( self, - reconstruction: pycolmap.Reconstruction, - timestamps: List[int], - rect_imu_data_npy: Path, - cfg=None + options: VIOptimizerOptions, + data: LamariaReconstruction, ): - cfg = cfg if cfg is not None else load_cfg() - self.reconstruction: pycolmap.Reconstruction = reconstruction - self.timestamps: List[int] = timestamps - self._init_params(cfg) - self._init_imu_data(rect_imu_data_npy) + self.data = data + self._init_options(options) + self._init_imu_data() - def _init_imu_data(self, rect_imu_data_npy: Path): + def _init_imu_data(self): self.preintegrated_imu_measurements = \ load_preintegrated_imu_measurements( rect_imu_data_npy, From c44904b20614c33fc1317ffec7f02d155046b896 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 23:00:01 +0200 Subject: [PATCH 220/665] res --- lamaria/rig/optim/residual_manager.py | 32 +++++++++++++-------------- 1 file changed, 15 insertions(+), 17 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 97d07c9..fc84e3b 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -1,8 +1,6 @@ import numpy as np import pyceres import pycolmap -from copy import deepcopy -from typing import List, Tuple import pycolmap.cost_functions from tqdm import tqdm @@ -24,8 +22,8 @@ def add_residuals(self, problem): for k in range(len(self.session.preintegrated_imu_measurements)): i = frame_ids[k] j = frame_ids[k + 1] - frame_i = self.session.reconstruction.frames[i] - frame_j = self.session.reconstruction.frames[j] + frame_i = self.session.data.reconstruction.frames[i] + frame_j = self.session.data.reconstruction.frames[j] i_from_world = frame_i.rig_from_world j_from_world = frame_j.rig_from_world @@ -61,14 +59,14 @@ def _setup_manifolds_and_constraints(self, problem): ) # Apply optimization constraints based on configuration - if not self.session.imu_params.optimize_scale: + if not self.session.imu_options.optimize_scale: problem.set_parameter_block_constant(self.session.log_scale) - if not self.session.imu_params.optimize_gravity: + if not self.session.imu_options.optimize_gravity: problem.set_parameter_block_constant(self.session.gravity) - if not self.session.imu_params.optimize_imu_from_rig: + if not self.session.imu_options.optimize_imu_from_rig: problem.set_parameter_block_constant(self.session.imu_from_rig.rotation.quat) problem.set_parameter_block_constant(self.session.imu_from_rig.translation) - if not self.session.imu_params.optimize_bias: + if not self.session.imu_options.optimize_bias: constant_idxs = np.arange(3, 9) for frame_id in self.session.imu_states.keys(): problem.set_manifold( @@ -109,11 +107,11 @@ def set_up_problem( loss: pyceres.LossFunction, ): logger.info("Setting up optimization problem") - assert session.reconstruction is not None + assert session.data.reconstruction is not None for image_id in tqdm(self.config.image_ids): self.add_image_to_problem(session, image_id, loss) - self.parameterize_cameras(session.reconstruction) - self.parameterize_points(session.reconstruction) + self.parameterize_cameras(session.data.reconstruction) + self.parameterize_points(session.data.reconstruction) logger.info("Optimization problem set up") return self.problem @@ -129,9 +127,9 @@ def add_image_to_problem( image_id: int, loss: pyceres.LossFunction, ): - image = session.reconstruction.images[image_id] - frame = session.reconstruction.frames[image.frame_id] - rig = session.reconstruction.rigs[frame.rig_id] + image = session.data.reconstruction.images[image_id] + frame = session.data.reconstruction.frames[image.frame_id] + rig = session.data.reconstruction.rigs[frame.rig_id] camera = session.recon.cameras[image.camera_id] rig_from_world = frame.rig_from_world @@ -140,9 +138,9 @@ def add_image_to_problem( if image.camera_id == sensor.id: cam_from_rig = sensor_from_rig - optimize_cam_from_rig = session.cam_params.optimize_cam_from_rig - optimize_cam_intrinsics = session.cam_params.optimize_cam_intrinsics - feature_std = session.cam_params.feature_std + optimize_cam_from_rig = session.cam_options.optimize_cam_from_rig + optimize_cam_intrinsics = session.cam_options.optimize_cam_intrinsics + feature_std = session.cam_options.feature_std num_observations = 0 for point2D in image.points2D: From 4c2271852ac321a5082c2d7af8ae38e8c90b9381 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 23:00:19 +0200 Subject: [PATCH 221/665] sess --- lamaria/rig/optim/session.py | 22 +++++++--------------- 1 file changed, 7 insertions(+), 15 deletions(-) diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py index c70f91a..0f9621a 100644 --- a/lamaria/rig/optim/session.py +++ b/lamaria/rig/optim/session.py @@ -1,7 +1,4 @@ from __future__ import annotations - -from typing import List -from pathlib import Path import pycolmap import numpy as np @@ -25,22 +22,17 @@ def __init__( def _init_imu_data(self): self.preintegrated_imu_measurements = \ load_preintegrated_imu_measurements( - rect_imu_data_npy, - self.reconstruction, - self.timestamps, - self.imu_params + self.imu_options, + self.data ) - self.imu_states = load_imu_states( - self.reconstruction, - self.timestamps - ) + self.imu_states = load_imu_states(self.data) self.imu_from_rig = pycolmap.Rigid3d() self.gravity = np.array([0.0, 0.0, -1.0]) self.log_scale = np.array([0.0]) - def _init_params(self, cfg): - self.cam_params = CamParams.from_cfg(cfg) - self.imu_params = IMUParams.from_cfg(cfg) - self.opt_params = OptParams.from_cfg(cfg) + def _init_options(self, options: VIOptimizerOptions): + self.cam_options = options.cam + self.imu_options = options.imu + self.opt_options = options.optim From 33fdf9f3e1e37cf2e6463ba8386a6a707629c09f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 23:00:34 +0200 Subject: [PATCH 222/665] vi opt --- lamaria/rig/optim/vi_optimization.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 394e541..1ef0fff 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -34,13 +34,13 @@ def optimize(self, database_path: Path, output_folder: Path): def _setup_incremental_mapper(self, database_path: Path): """Setup the incremental mapper""" database = pycolmap.Database.open(database_path) - image_names = [self.session.reconstruction.images[image_id].name - for image_id in self.session.reconstruction.reg_image_ids()] + image_names = [self.session.data.reconstruction.images[image_id].name + for image_id in self.session.data.reconstruction.reg_image_ids()] database_cache = pycolmap.DatabaseCache.create( database, 15, False, set(image_names) ) mapper = pycolmap.IncrementalMapper(database_cache) - mapper.begin_reconstruction(self.session.reconstruction) + mapper.begin_reconstruction(self.session.data.reconstruction) return mapper def _get_incremental_pipeline_options(self): From 2592f064595ff1412514af7548bbe9742b261c21 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 23 Sep 2025 23:33:20 +0200 Subject: [PATCH 223/665] vi opto --- lamaria/rig/optim/vi_optimization.py | 22 ++++++++++------------ 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 1ef0fff..095a3c6 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -1,7 +1,7 @@ import pycolmap from pathlib import Path -from ... import logger +from ..lamaria_reconstruction import LamariaReconstruction from .session import SingleSeqSession from .iterative_global_ba import IterativeRefinement @@ -12,7 +12,7 @@ class VIOptimizer: def __init__(self, session: SingleSeqSession): self.session = session - def optimize(self, database_path: Path, output_folder: Path): + def optimize(self, database_path: Path): """Run the complete VI optimization pipeline""" # Setup mapper @@ -26,10 +26,7 @@ def optimize(self, database_path: Path, output_folder: Path): pipeline_options, ) - # Save results - optimized_reconstruction = mapper.reconstruction - output_folder.mkdir(parents=True, exist_ok=True) - optimized_reconstruction.write(output_folder.as_posix()) + return mapper.reconstruction def _setup_incremental_mapper(self, database_path: Path): """Setup the incremental mapper""" @@ -54,12 +51,13 @@ def create_vi_optimizer(session: SingleSeqSession) -> VIOptimizer: """Factory function to create VI optimizer""" return VIOptimizer(session) - -def run(session: SingleSeqSession, - database_path: Path, - output_folder: Path, -) -> None: +def run( + session: SingleSeqSession, + database_path: Path, +) -> pycolmap.Reconstruction: """Run VI optimization with given session and database""" optimizer = create_vi_optimizer(session) - optimizer.optimize(database_path, output_folder) \ No newline at end of file + optimized_recon = optimizer.optimize(database_path) + + return optimized_recon \ No newline at end of file From 0c38607237b6430266eff5a9ff7cbaa5fc3ec6f8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 00:07:00 +0200 Subject: [PATCH 224/665] kf selector --- lamaria/rig/keyframing/keyframe_selection.py | 34 ++++++++++---------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index b00b410..81ce345 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -4,7 +4,7 @@ import numpy as np from pathlib import Path from copy import deepcopy -from typing import List, Optional +from typing import Optional, Dict import pycolmap @@ -25,18 +25,20 @@ def __init__( self.timestamps = data.timestamps # frame id to timestamp mapping self.keyframed_data: LamariaReconstruction = LamariaReconstruction() - self.keyframe_frame_ids: Optional[List[int]] = None + self.keyframe_frame_ids: Optional[Dict[int, int]] = None def _select_keyframes(self): - self.keyframe_frame_ids = [] + self.keyframe_frame_ids: Dict[int, int] = {} dr_dt = np.array([0.0, 0.0]) dts = 0.0 init_frame_ids = sorted(self.init_recons.frames.keys()) + new_frame_id = 1 for i, (prev, curr) in enumerate(zip(init_frame_ids[:-1], init_frame_ids[1:])): if i == 0: - self.keyframe_frame_ids.append(prev) + self.keyframe_frame_ids[new_frame_id] = prev + new_frame_id += 1 continue current_rig_from_world = self.init_recons.frames[curr].rig_from_world @@ -50,7 +52,8 @@ def _select_keyframes(self): dr_dt[1] > self.options.max_distance or \ dts > self.options.max_elapsed: - self.keyframe_frame_ids.append(curr) + self.keyframe_frame_ids[new_frame_id] = curr + new_frame_id += 1 dr_dt = np.array([0.0, 0.0]) dts = 0.0 @@ -78,12 +81,12 @@ def _build_device_keyframed_reconstruction(self): self.keyframed_data.reconstruction.add_rig(new_rig) image_id = 1 - for i, frame_id in enumerate(self.keyframe_frame_ids): + for new_fid, frame_id in self.keyframe_frame_ids.items(): old_frame = self.init_recons.frames[frame_id] new_frame = pycolmap.Frame() new_frame.rig_id = 1 - new_frame.frame_id = i + 1 + new_frame.frame_id = new_fid new_frame.rig_from_world = deepcopy(old_frame.rig_from_world) old_image_ids = sorted([d.id for d in old_frame.data_ids]) @@ -123,9 +126,8 @@ def _clone_camera(self, old_camera_id: int, new_camera_id: int) -> pycolmap.Came def _build_online_keyframed_reconstruction(self): camera_id = 1 image_id = 1 - rig_id = 1 - for i, frame_id in enumerate(self.keyframe_frame_ids): + for new_fid, frame_id in self.keyframe_frame_ids.items(): old_frame = self.init_recons.frames[frame_id] old_rig_id = old_frame.rig_id old_rig = self.init_recons.rigs[old_rig_id] @@ -139,7 +141,7 @@ def _build_online_keyframed_reconstruction(self): cam_id_map[old_ref_sensor_id] = camera_id camera_id += 1 - new_rig = pycolmap.Rig(rig_id=rig_id) + new_rig = pycolmap.Rig(rig_id=new_fid) new_rig.add_ref_sensor(new_ref_sensor.sensor_id) for old_sensor, sensor_from_rig in old_rig.non_ref_sensors.items(): @@ -158,7 +160,7 @@ def _build_online_keyframed_reconstruction(self): new_frame = pycolmap.Frame() new_frame.rig_id = new_rig.rig_id - new_frame.frame_id = i + 1 + new_frame.frame_id = new_fid new_frame.rig_from_world = deepcopy(old_frame.rig_from_world) old_image_ids = sorted([d.id for d in old_frame.data_ids]) @@ -181,8 +183,6 @@ def _build_online_keyframed_reconstruction(self): self.keyframed_data.reconstruction.add_frame(new_frame) for img in images_to_add: self.keyframed_data.reconstruction.add_image(img) - - rig_id += 1 def run_keyframing(self) -> LamariaReconstruction: """ Main function to run keyframing on input lamaria reconstruction.""" @@ -192,10 +192,10 @@ def run_keyframing(self) -> LamariaReconstruction: else: self._build_online_keyframed_reconstruction() - # set timestamps keys as the new frame ids + # set timestamps keys with new frame ids self.keyframed_data.timestamps = { - frame_id: self.timestamps[frame_id] - for frame_id in self.keyframe_frame_ids + new_fid: self.timestamps[old_fid] + for new_fid, old_fid in self.keyframe_frame_ids.items() } self.keyframed_data.imu_measurements = self.init_data.imu_measurements @@ -221,7 +221,7 @@ def copy_images_to_keyframes_dir( output_dir.mkdir(parents=True, exist_ok=True) - for frame_id in self.keyframe_frame_ids: + for _, frame_id in self.keyframe_frame_ids.items(): frame = self.init_recons.frames[frame_id] for data_id in frame.data_ids: image = self.init_recons.images[data_id.id] From aacc8217f36f9ea26aa704d222f49fea0f117061 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 00:07:10 +0200 Subject: [PATCH 225/665] fix --- lamaria/rig/config/options.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index 6996120..fe0c59f 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -216,9 +216,9 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": return cls() base = cls() - cam = _structured_merge_to_obj(OptCamOptions, cfg.optimization.cam) - imu = _structured_merge_to_obj(OptIMUOptions, cfg.optimization.imu) - optim = _structured_merge_to_obj(OptOptions, cfg.optimization.general) + cam = _structured_merge_to_obj(OptCamOptions, cfg.cam) + imu = _structured_merge_to_obj(OptIMUOptions, cfg.imu) + optim = _structured_merge_to_obj(OptOptions, cfg.general) # leave colmap_pipeline as default return replace( From af03d6c1fdc042a5c25d291d71654273ab986f2a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 00:07:22 +0200 Subject: [PATCH 226/665] pipeline --- lamaria/rig/config/pipeline.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/config/pipeline.py b/lamaria/rig/config/pipeline.py index 2102422..5b83d1d 100644 --- a/lamaria/rig/config/pipeline.py +++ b/lamaria/rig/config/pipeline.py @@ -108,7 +108,10 @@ def get_vi_optimizer_options(self) -> VIOptimizerOptions: options = VIOptimizerOptions.load(self._cfg.optimization) return replace( options, - optim_model=self.output_path / options.optim.optim_model, + optim=replace( + options.optim, + optim_model=self.output_path / options.optim.optim_model, + ), output_path=self.output_path, ) \ No newline at end of file From 87beba03b91a676dfae15dbdb65d9721b75b608e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 01:01:34 +0200 Subject: [PATCH 227/665] fix --- lamaria/rig/optim/vi_optimization.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 095a3c6..6558c0f 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -43,7 +43,7 @@ def _setup_incremental_mapper(self, database_path: Path): def _get_incremental_pipeline_options(self): """Get incremental pipeline options""" pipeline_options = pycolmap.IncrementalPipelineOptions() - pipeline_options.fix_existing_images = False + pipeline_options.fix_existing_frames = False return pipeline_options From 5bba3a7b6303cb1a3a72d6a949138668e30801ed Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 10:01:34 +0200 Subject: [PATCH 228/665] load states --- lamaria/rig/optim/imu.py | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index 08c033f..d6b8283 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -76,15 +76,12 @@ def load_imu_states( pj = data.reconstruction.frames[j].rig_from_world.inverse().translation vel = (pj - pi) / dt - s = pycolmap.ImuState() - s.set_velocity(vel) - imu_states[i] = s + imu_states[i] = pycolmap.ImuState() + imu_states[i].set_velocity(vel) - last_id = frame_ids[-1] - prev_id = frame_ids[-2] - last_state = pycolmap.ImuState() - last_state.set_velocity(imu_states[prev_id].velocity) - imu_states[last_id] = last_state + imu_states[frame_ids[-1]] = pycolmap.ImuState() + vel = imu_states[frame_ids[-2]].velocity + imu_states[frame_ids[-1]].set_velocity(vel) return imu_states From 33421c1c4b200d82084d8f78209c760c5b66824d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 10:11:10 +0200 Subject: [PATCH 229/665] res --- lamaria/rig/optim/residual_manager.py | 22 ++++++++-------------- 1 file changed, 8 insertions(+), 14 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index fc84e3b..74b47f8 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -17,7 +17,7 @@ def add_residuals(self, problem): """Add IMU residuals to the optimization problem""" loss = pyceres.TrivialLoss() - frame_ids = sorted(self.session.preintegrated_imu_measurements.keys()) + frame_ids = sorted(self.session.data.reconstruction.frames.keys()) for k in range(len(self.session.preintegrated_imu_measurements)): i = frame_ids[k] @@ -75,7 +75,7 @@ def _setup_manifolds_and_constraints(self, problem): ) -class ImageResidualManager: +class BundleAdjuster: """Handles image residual setup and constraints""" def __init__( self, @@ -95,8 +95,8 @@ def solve(self, reconstruction: pycolmap.Reconstruction): self.set_up_problem(reconstruction, loss) if self.problem.num_residuals() == 0: return False - solver_options = self.set_up_solver_options( - self.problem, self.options.solver_options + solver_options = self.options.create_solver_options( + self.config, self.problem ) pyceres.solve(solver_options, self.problem, self.summary) return True @@ -108,19 +108,13 @@ def set_up_problem( ): logger.info("Setting up optimization problem") assert session.data.reconstruction is not None - for image_id in tqdm(self.config.image_ids): + for image_id in tqdm(self.config.images): self.add_image_to_problem(session, image_id, loss) self.parameterize_cameras(session.data.reconstruction) self.parameterize_points(session.data.reconstruction) logger.info("Optimization problem set up") return self.problem - def set_up_solver_options( - self, problem: pyceres.Problem, solver_options: pyceres.SolverOptions - ): - bundle_adjuster = pycolmap.BundleAdjuster(self.options, self.config) - return bundle_adjuster.set_up_solver_options(problem, solver_options) - def add_image_to_problem( self, session: SingleSeqSession, @@ -130,7 +124,7 @@ def add_image_to_problem( image = session.data.reconstruction.images[image_id] frame = session.data.reconstruction.frames[image.frame_id] rig = session.data.reconstruction.rigs[frame.rig_id] - camera = session.recon.cameras[image.camera_id] + camera = session.data.reconstruction.cameras[image.camera_id] rig_from_world = frame.rig_from_world cam_from_rig = None @@ -151,7 +145,7 @@ def add_image_to_problem( self.point3D_num_observations[point2D.point3D_id] = 0 self.point3D_num_observations[point2D.point3D_id] += 1 - point3D = session.recon.points3D[point2D.point3D_id] + point3D = session.data.reconstruction.points3D[point2D.point3D_id] assert point3D.track.length() > 1 if not optimize_cam_from_rig: cost = pycolmap.cost_functions.RigReprojErrorCost( @@ -245,6 +239,6 @@ def parameterize_points(self, reconstruction: pycolmap.Reconstruction): point3D = reconstruction.points3D[point3D_id] if point3D.track.length() > num_observations: self.problem.set_parameter_block_constant(point3D.xyz) - for point3D_id in self.config.constant_point3D_ids: + for point3D_id in self.config.constant_points: point3D = reconstruction.points3D[point3D_id] self.problem.set_parameter_block_constant(point3D.xyz) \ No newline at end of file From 864e4dc8456423ee06ae403b7dd273fdb5333f3c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 10:19:25 +0200 Subject: [PATCH 230/665] iterative --- lamaria/rig/optim/iterative_global_ba.py | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index fc00761..e315354 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -1,11 +1,12 @@ import pycolmap +from pycolmap import logging import pyceres from typing import List, Tuple from copy import deepcopy import numpy as np from ... import logger from .session import SingleSeqSession -from .residual_manager import ImageResidualManager, IMUResidualManager +from .residual_manager import BundleAdjuster, IMUResidualManager class RigConstraintManager: @@ -46,22 +47,20 @@ def _init_callback(self): def solve(self, ba_options, ba_config): """Solve VI bundle adjustment problem""" - bundle_adjuster = ImageResidualManager(ba_options, ba_config) + bundle_adjuster = BundleAdjuster(ba_options, ba_config) imu_manager = IMUResidualManager(self.session) bundle_adjuster.set_up_problem( self.session, ba_options.create_loss_function(), ) + problem = bundle_adjuster.problem - solver_options = bundle_adjuster.set_up_solver_options( - bundle_adjuster.problem, ba_options.solver_options + solver_options = ba_options.create_solver_options( + ba_config, problem ) - problem = bundle_adjuster.problem - # Add IMU residuals if enabled - if self.session.imu_options.keep_imu_residuals: - problem = imu_manager.add_residuals(problem) + problem = imu_manager.add_residuals(problem) # Apply rig constraints constraint_manager = RigConstraintManager(self.session) @@ -150,7 +149,9 @@ def run(self, mapper, pipeline_options): tri_options = pipeline_options.get_triangulation() mapper.complete_and_merge_tracks(tri_options) num_retriangulated_observations = mapper.retriangulate(tri_options) - logger.info(1, f"=> Retriangulated observations: {num_retriangulated_observations}") + logging.verbose( + 1, f"=> Retriangulated observations: {num_retriangulated_observations}" + ) # Configure mapper options mapper_options = self._configure_mapper_options(pipeline_options) @@ -174,7 +175,7 @@ def run(self, mapper, pipeline_options): changed = (num_changed_observations / num_observations if num_observations > 0 else 0) - logger.info(1, f"=> Changed observations: {changed:.6f}") + logging.verbose(1, f"=> Changed observations: {changed:.6f}") if changed < pipeline_options.ba_global_max_refinement_change: break From ddad432cb75a672b1656ccb1d0416feb7b94a3c5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 10:21:59 +0200 Subject: [PATCH 231/665] defs --- defaults.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/defaults.yaml b/defaults.yaml index 1eb42c1..a71637d 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -33,13 +33,13 @@ triangulation: # relaxed triangulation # https://github.com/colmap/colmap/blob/dbdb3cd5a9a90a01b7e1096905ba2ffc34a68b82/src/colmap/sfm/incremental_triangulator.h - merge_max_reproj_error: 4.0 - complete_max_reproj_error: 4.0 - min_angle: 1.5 + merge_max_reproj_error: 15.0 + complete_max_reproj_error: 15.0 + min_angle: 1.0 # https://github.com/colmap/colmap/blob/dbdb3cd5a9a90a01b7e1096905ba2ffc34a68b82/src/colmap/sfm/incremental_mapper.h - filter_max_reproj_error: 4.0 - filter_min_tri_angle: 1.5 + filter_max_reproj_error: 15.0 + filter_min_tri_angle: 1.0 optimization: general: From 88dba4ed23e8738d0f9af01681a157e4e4bb58ab Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 10:22:51 +0200 Subject: [PATCH 232/665] run iot --- run_pipeline.py | 69 ++++++++++++++++++++++++++++++++++++++++--------- 1 file changed, 57 insertions(+), 12 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index 655a8f8..098c594 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -1,19 +1,20 @@ import pycolmap -from copy import deepcopy +import shutil from typing import Optional from pathlib import Path from lamaria.rig.lamaria_reconstruction import LamariaReconstruction from lamaria.rig.keyframing.to_colmap import EstimateToColmap from lamaria.rig.keyframing.keyframe_selection import KeyframeSelector -from lamaria.rig.optim.triangulation import run as triangulation_run +from lamaria.rig.optim.triangulation import run as triangulate from lamaria.rig.optim.session import SingleSeqSession -from lamaria.rig.optim.vi_optimization import run +from lamaria.rig.optim.vi_optimization import run as run_vi_optimization from lamaria.rig.config.pipeline import PipelineOptions from lamaria.rig.config.options import ( EstimateToColmapOptions, KeyframeSelectorOptions, - TriangulatorOptions + TriangulatorOptions, + VIOptimizerOptions, ) @@ -37,8 +38,8 @@ def run_estimate_to_colmap( if colmap_model.exists(): lamaria_recon = LamariaReconstruction.read(colmap_model) return lamaria_recon - else: - colmap_model.mkdir(parents=True, exist_ok=True) + + colmap_model.mkdir(parents=True, exist_ok=True) est_to_colmap = EstimateToColmap(options) lamaria_recon = est_to_colmap.create() @@ -68,8 +69,8 @@ def run_keyframe_selection( if kf_model.exists(): kf_lamaria_recon = LamariaReconstruction.read(kf_model) return kf_lamaria_recon - else: - kf_model.mkdir(parents=True, exist_ok=True) + + kf_model.mkdir(parents=True, exist_ok=True) kf_selector = KeyframeSelector(options, input_recon) kf_lamaria_recon = kf_selector.run_keyframing() @@ -107,7 +108,7 @@ def run_triangulation( tri_lamaria_recon = LamariaReconstruction.read(tri_model) return tri_lamaria_recon - triangulated_model_path = triangulation_run( + triangulated_model_path = triangulate( options, reference_model=input, keyframes=keyframes, @@ -125,10 +126,46 @@ def run_triangulation( return tri_lamaria_recon +def run_optimization( + options: VIOptimizerOptions, + input: Path, # path to LamariaReconstruction + optim_model: Path, +) -> LamariaReconstruction: + if not isinstance(input, Path): + raise ValueError("Input must be a Path to the reconstruction") + + db_path = input / "database.db" + assert db_path.exists(), f"Database path {db_path} does not exist in input reconstruction" + if optim_model.exists(): + optim_lamaria_recon = LamariaReconstruction.read(optim_model) + return optim_lamaria_recon + + optim_model.mkdir(parents=True, exist_ok=True) + db_dst = optim_model / "database.db" + shutil.copy(db_path, db_dst) + + init_lamaria_recon = LamariaReconstruction.read(input) + session = SingleSeqSession( + options, + init_lamaria_recon, + ) + + optimized_recon = run_vi_optimization( + session, + db_dst, + ) + + optim_lamaria_recon = LamariaReconstruction() + optim_lamaria_recon.reconstruction = optimized_recon + optim_lamaria_recon.timestamps = init_lamaria_recon.timestamps + optim_lamaria_recon.imu_measurements = init_lamaria_recon.imu_measurements + optim_lamaria_recon.write(optim_model) + + def run_pipeline(): pipeline_options = PipelineOptions() - # Step 1: Estimate to COLMAP + # Estimate to COLMAP est_options = pipeline_options.get_estimate_to_colmap_options() _ = run_estimate_to_colmap( est_options, @@ -138,7 +175,7 @@ def run_pipeline(): est_options.colmap_model, ) - # Step 2: Keyframe Selection + # Keyframe Selection kf_options = pipeline_options.get_keyframing_options() _ = run_keyframe_selection( kf_options, @@ -148,7 +185,7 @@ def run_pipeline(): kf_options.kf_model, ) - # Step 3: Triangulation + # Triangulation tri_options = pipeline_options.get_triangulator_options() _ = run_triangulation( tri_options, @@ -159,5 +196,13 @@ def run_pipeline(): tri_options.tri_model, ) + # Visual-Inertial Optimization + vi_options = pipeline_options.get_vi_optimizer_options() + _ = run_optimization( + vi_options, + tri_options.tri_model, + vi_options.optim.optim_model, + ) + if __name__ == "__main__": run_pipeline() From b0e892e9b6a0e3231606cb182c55cb5c41d5f0fd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 10:49:14 +0200 Subject: [PATCH 233/665] iterative --- lamaria/rig/optim/iterative_global_ba.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index e315354..a955cec 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -59,6 +59,7 @@ def solve(self, ba_options, ba_config): solver_options = ba_options.create_solver_options( ba_config, problem ) + pyceres_solver_options = pyceres.SolverOptions(solver_options) problem = imu_manager.add_residuals(problem) @@ -70,15 +71,15 @@ def solve(self, ba_options, ba_config): # Setup solver if self.session.opt_options.use_callback: callback = self._init_callback() - solver_options.callbacks = [callback] + pyceres_solver_options.callbacks = [callback] - solver_options.minimizer_progress_to_stdout = True - solver_options.update_state_every_iteration = True - solver_options.max_num_iterations = self.session.opt_options.max_num_iterations + pyceres_solver_options.minimizer_progress_to_stdout = True + pyceres_solver_options.update_state_every_iteration = True + pyceres_solver_options.max_num_iterations = self.session.opt_options.max_num_iterations # Solve summary = pyceres.SolverSummary() - pyceres.solve(solver_options, problem, summary) + pyceres.solve(pyceres_solver_options, problem, summary) print(summary.BriefReport()) return summary, problem From e6b56d2ef0c9b9ef682abdffb257d7cdd963f53a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 11:04:43 +0200 Subject: [PATCH 234/665] config ba --- lamaria/rig/optim/iterative_global_ba.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index a955cec..0be8447 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -108,8 +108,12 @@ def adjust(self, mapper, pipeline_options): # Configure bundle adjustment ba_config = pycolmap.BundleAdjustmentConfig() - for image_id in reconstruction.reg_image_ids(): - ba_config.add_image(image_id) + for frame_id in reconstruction.reg_frame_ids(): + frame = reconstruction.frame(frame_id) + for data_id in frame.data_ids: + if data_id.sensor_id.type != pycolmap.SensorType.CAMERA: + continue + ba_config.add_image(data_id.id) # Run bundle adjustment vi_bundle_adjuster = VIBundleAdjuster(self.session) From 46c285955534042f2263567488108924e1a5e84a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 11:09:36 +0200 Subject: [PATCH 235/665] iter --- lamaria/rig/optim/iterative_global_ba.py | 1 + 1 file changed, 1 insertion(+) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 0be8447..8ac0834 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -4,6 +4,7 @@ from typing import List, Tuple from copy import deepcopy import numpy as np + from ... import logger from .session import SingleSeqSession from .residual_manager import BundleAdjuster, IMUResidualManager From bf3573d18bb73456c25c678ed20f1dd493916812 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 11:15:55 +0200 Subject: [PATCH 236/665] fix gauge --- lamaria/rig/optim/iterative_global_ba.py | 30 ++---------------------- 1 file changed, 2 insertions(+), 28 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 8ac0834..76d68f1 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -10,29 +10,6 @@ from .residual_manager import BundleAdjuster, IMUResidualManager -class RigConstraintManager: - """Handles rig-specific constraints and problem setup""" - - def __init__(self, session: SingleSeqSession): - self.session = session - - def apply_constraints(self, problem): - """Apply rig-specific constraints to the problem""" - # Fix the first rig pose - frame_ids = sorted(self.session.data.reconstruction.frames.keys()) - first_frame = self.session.data.reconstruction.frames[frame_ids[0]] - problem.set_parameter_block_constant(first_frame.rotation.quat) - problem.set_parameter_block_constant(first_frame.translation) - - # Fix 1 DoF translation of the second rig - second_frame = self.session.data.reconstruction.frames[frame_ids[1]] - problem.set_manifold( - second_frame.translation, - pyceres.SubsetManifold(3, np.array([0])), - ) - return problem - - class VIBundleAdjuster: """Visual-Inertial Bundle Adjuster that combines visual and IMU residuals""" @@ -64,11 +41,6 @@ def solve(self, ba_options, ba_config): problem = imu_manager.add_residuals(problem) - # Apply rig constraints - constraint_manager = RigConstraintManager(self.session) - problem = constraint_manager.apply_constraints(problem) - logger.info("Constrained the rig problem") - # Setup solver if self.session.opt_options.use_callback: callback = self._init_callback() @@ -116,6 +88,8 @@ def adjust(self, mapper, pipeline_options): continue ba_config.add_image(data_id.id) + ba_config.fix_gauge(pycolmap.BundleAdjustmentGauge.TWO_CAMS_FROM_WORLD) + # Run bundle adjustment vi_bundle_adjuster = VIBundleAdjuster(self.session) _, _ = vi_bundle_adjuster.solve( From 7d7f295346deadbc38ef38d1534e43fb5e7ed021 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 11:25:33 +0200 Subject: [PATCH 237/665] iterative ba --- lamaria/rig/optim/iterative_global_ba.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 76d68f1..352c43b 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -25,13 +25,11 @@ def _init_callback(self): def solve(self, ba_options, ba_config): """Solve VI bundle adjustment problem""" - bundle_adjuster = BundleAdjuster(ba_options, ba_config) + bundle_adjuster = pycolmap.create_default_bundle_adjuster( + ba_options, ba_config, self.session.data.reconstruction + ) imu_manager = IMUResidualManager(self.session) - bundle_adjuster.set_up_problem( - self.session, - ba_options.create_loss_function(), - ) problem = bundle_adjuster.problem solver_options = ba_options.create_solver_options( From 9114fbfbada85f504bff054a888bef4c33784c0d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 14:05:03 +0200 Subject: [PATCH 238/665] updated options --- lamaria/rig/config/options.py | 131 +++++++++------------------------- 1 file changed, 35 insertions(+), 96 deletions(-) diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py index fe0c59f..0347eef 100644 --- a/lamaria/rig/config/options.py +++ b/lamaria/rig/config/options.py @@ -10,20 +10,24 @@ # General options -@dataclass(frozen=True, slots=True) +@dataclass(slots=True) class MPSOptions: use_mps: bool = False use_online_calibration: bool = False # when use_mps is true (for online calib file) has_slam_drops: bool = False # check vrs json metadata file for each sequence @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> MPSOptions: + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> MPSOptions: if cfg is None: return cls() return _structured_merge_to_obj(cls, cfg) -@dataclass(frozen=True, slots=True) + +@dataclass(slots=True) class SensorOptions: left_cam_stream_id: str = "1201-1" right_cam_stream_id: str = "1201-2" @@ -31,21 +35,20 @@ class SensorOptions: camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> "SensorOptions": + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> "SensorOptions": if cfg is None: return cls() obj: SensorOptions = _structured_merge_to_obj(cls, cfg) return obj + # Estimate to COLMAP options -@dataclass(frozen=True, slots=True) +@dataclass(slots=True) class EstimateToColmapOptions: - vrs: Path = Path("recordings/xyz.vrs") - estimate: Path = Path("estimates/xyz.txt") - images: Path = Path("image_stream") - colmap_model: Path = Path("initial_recon") - mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) @@ -55,55 +58,33 @@ class EstimateToColmapOptions: @classmethod def load( cls, - cfg_estimate_to_colmap: Optional[OmegaConf] = None, cfg_mps: Optional[OmegaConf] = None, cfg_sensor: Optional[OmegaConf] = None, ) -> EstimateToColmapOptions: - if cfg_estimate_to_colmap is None: + if cfg_mps or cfg_sensor is None: return cls() - base = _structured_merge_to_obj(cls, cfg_estimate_to_colmap) + base = cls() return replace( base, mps=MPSOptions.load(cfg_mps), sensor=SensorOptions.load(cfg_sensor) ) - def set_custom_paths( - self, - vrs: Path, - estimate: Path, - images: Path, - colmap_model: Path, - output_path: Optional[Path] = None, - mps_folder: Optional[Path] = None, - ) -> EstimateToColmapOptions: - return replace( - self, - vrs=vrs, - estimate=estimate, - images=images, - colmap_model=colmap_model, - output_path=output_path if output_path is not None else self.output_path, - mps_folder=mps_folder if mps_folder is not None else self.mps_folder - ) - # Keyframing options -@dataclass(frozen=True, slots=True) +@dataclass(slots=True) class KeyframeSelectorOptions: - keyframes: Path = Path("keyframes") - kf_model: Path = Path("keyframe_recon") - max_rotation: float = 20.0 # degrees max_distance: float = 1.0 # meters max_elapsed: int = int(1e9) # 1 second in ns - output_path: Optional[Path] = None - @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> "KeyframeSelectorOptions": if cfg is None: return cls() @@ -114,28 +95,11 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "KeyframeSelectorOptions": obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, cfg) return obj - - def set_custom_paths( - self, - keyframes: Path, - kf_model: Path, - output_path: Optional[Path] = None, - ) -> KeyframeSelectorOptions: - return replace( - self, - keyframes=keyframes, - kf_model=kf_model, - output_path=output_path if output_path is not None else self.output_path, - ) # Triangulation options -@dataclass(frozen=True, slots=True) +@dataclass(slots=True) class TriangulatorOptions: - hloc: Path = Path("hloc") - pairs_file: Path = Path("pairs.txt") - tri_model: Path = Path("triangulated_recon") - feature_conf: str = "aliked-n16" matcher_conf: str = "aliked+lightglue" retrieval_conf: str = "netvlad" @@ -149,39 +113,25 @@ class TriangulatorOptions: filter_max_reproj_error: float = 4.0 filter_min_tri_angle: float = 1.5 - output_path: Optional[Path] = None - @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> "TriangulatorOptions": + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> "TriangulatorOptions": if cfg is None: return cls() return _structured_merge_to_obj(cls, cfg) - - def set_custom_paths( - self, - hloc: Path, - pairs_file: Path, - tri_model: Path, - output_path: Optional[Path] = None, - ) -> TriangulatorOptions: - return replace( - self, - hloc=hloc, - pairs_file=pairs_file, - tri_model=tri_model, - output_path=output_path if output_path is not None else self.output_path - ) - + # Optimization options -@dataclass(frozen=True, slots=True) +@dataclass(slots=True) class OptCamOptions: feature_std: float = 1.0 # in pixels optimize_cam_intrinsics: bool = False optimize_cam_from_rig: bool = False -@dataclass(frozen=True, slots=True) +@dataclass(slots=True) class OptIMUOptions: gyro_infl: float = 1.0 acc_infl: float = 1.0 @@ -192,14 +142,13 @@ class OptIMUOptions: optimize_imu_from_rig: bool = False optimize_bias: bool = False -@dataclass(frozen=True, slots=True) +@dataclass(slots=True) class OptOptions: - optim_model: Path = Path("optim_recon") use_callback: bool = True max_num_iterations: int = 10 normalize_reconstruction: bool = False -@dataclass(frozen=True, slots=True) +@dataclass(slots=True) class VIOptimizerOptions: cam: OptCamOptions = field(default_factory=OptCamOptions) imu: OptIMUOptions = field(default_factory=OptIMUOptions) @@ -207,11 +156,12 @@ class VIOptimizerOptions: colmap_pipeline: pycolmap.IncrementalPipelineOptions = \ pycolmap.IncrementalPipelineOptions() - - output_path: Optional[Path] = None @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> "VIOptimizerOptions": if cfg is None: return cls() @@ -226,15 +176,4 @@ def load(cls, cfg: Optional[OmegaConf] = None) -> "VIOptimizerOptions": cam=cam, imu=imu, optim=optim, - ) - - def set_custom_paths( - self, - optim_model: Path, - output_path: Optional[Path] = None - ) -> VIOptimizerOptions: - return replace( - self, - optim=replace(self.optim, optim_model=optim_model), - output_path=output_path if output_path is not None else self.output_path - ) + ) \ No newline at end of file From 7921048ca6f426b407ab5c93ab1dfe7998438e17 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 14:25:44 +0200 Subject: [PATCH 239/665] mv --- lamaria/rig/config/helpers.py | 27 ----- lamaria/rig/config/options.py | 179 --------------------------------- lamaria/rig/config/pipeline.py | 117 --------------------- 3 files changed, 323 deletions(-) delete mode 100644 lamaria/rig/config/helpers.py delete mode 100644 lamaria/rig/config/options.py delete mode 100644 lamaria/rig/config/pipeline.py diff --git a/lamaria/rig/config/helpers.py b/lamaria/rig/config/helpers.py deleted file mode 100644 index eff5d54..0000000 --- a/lamaria/rig/config/helpers.py +++ /dev/null @@ -1,27 +0,0 @@ -# options.py helper functions -from __future__ import annotations -from pathlib import Path -from typing import Optional -from omegaconf import OmegaConf - -def _p( - x: Optional[str] | Optional[Path], - root: Optional[Path] = None -) -> Optional[Path]: - - if x is None: - return None - x = Path(x) - if root is not None and not x.is_absolute(): - return (root / x).resolve() - return x.resolve() - -def _structured_merge_to_obj(cls, section) -> object: - """ - Merge a YAML section onto a structured - config made from the dataclass `cls`, - then return a dataclass instance. - """ - base = OmegaConf.structured(cls) - merged = OmegaConf.merge(base, section or {}) - return OmegaConf.to_object(merged) \ No newline at end of file diff --git a/lamaria/rig/config/options.py b/lamaria/rig/config/options.py deleted file mode 100644 index 0347eef..0000000 --- a/lamaria/rig/config/options.py +++ /dev/null @@ -1,179 +0,0 @@ -from __future__ import annotations - -from dataclasses import dataclass, field, replace -from typing import Optional -from pathlib import Path -import pycolmap -from omegaconf import OmegaConf, open_dict - -from .helpers import _structured_merge_to_obj - - -# General options -@dataclass(slots=True) -class MPSOptions: - use_mps: bool = False - use_online_calibration: bool = False # when use_mps is true (for online calib file) - has_slam_drops: bool = False # check vrs json metadata file for each sequence - - @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> MPSOptions: - if cfg is None: - return cls() - - return _structured_merge_to_obj(cls, cfg) - - -@dataclass(slots=True) -class SensorOptions: - left_cam_stream_id: str = "1201-1" - right_cam_stream_id: str = "1201-2" - right_imu_stream_id: str = "1202-1" - camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" - - @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> "SensorOptions": - if cfg is None: - return cls() - - obj: SensorOptions = _structured_merge_to_obj(cls, cfg) - return obj - - -# Estimate to COLMAP options -@dataclass(slots=True) -class EstimateToColmapOptions: - mps: MPSOptions = field(default_factory=MPSOptions) - sensor: SensorOptions = field(default_factory=SensorOptions) - - mps_folder: Optional[Path] = None # necessary if use_mps is true - output_path: Optional[Path] = None - - @classmethod - def load( - cls, - cfg_mps: Optional[OmegaConf] = None, - cfg_sensor: Optional[OmegaConf] = None, - ) -> EstimateToColmapOptions: - - if cfg_mps or cfg_sensor is None: - return cls() - - base = cls() - return replace( - base, - mps=MPSOptions.load(cfg_mps), - sensor=SensorOptions.load(cfg_sensor) - ) - - -# Keyframing options -@dataclass(slots=True) -class KeyframeSelectorOptions: - max_rotation: float = 20.0 # degrees - max_distance: float = 1.0 # meters - max_elapsed: int = int(1e9) # 1 second in ns - - @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> "KeyframeSelectorOptions": - if cfg is None: - return cls() - - cfg = OmegaConf.create(cfg) - with open_dict(cfg): - if "max_elapsed" in cfg and isinstance(cfg.max_elapsed, float): - cfg.max_elapsed = int(cfg.max_elapsed) - - obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, cfg) - return obj - - -# Triangulation options -@dataclass(slots=True) -class TriangulatorOptions: - feature_conf: str = "aliked-n16" - matcher_conf: str = "aliked+lightglue" - retrieval_conf: str = "netvlad" - num_retrieval_matches: int = 5 - - # colmap defaults - merge_max_reproj_error: float = 4.0 - complete_max_reproj_error: float = 4.0 - min_angle: float = 1.5 - - filter_max_reproj_error: float = 4.0 - filter_min_tri_angle: float = 1.5 - - @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> "TriangulatorOptions": - if cfg is None: - return cls() - - return _structured_merge_to_obj(cls, cfg) - - -# Optimization options -@dataclass(slots=True) -class OptCamOptions: - feature_std: float = 1.0 # in pixels - optimize_cam_intrinsics: bool = False - optimize_cam_from_rig: bool = False - -@dataclass(slots=True) -class OptIMUOptions: - gyro_infl: float = 1.0 - acc_infl: float = 1.0 - integration_noise_density: float = 0.05 - - optimize_scale: bool = False - optimize_gravity: bool = False - optimize_imu_from_rig: bool = False - optimize_bias: bool = False - -@dataclass(slots=True) -class OptOptions: - use_callback: bool = True - max_num_iterations: int = 10 - normalize_reconstruction: bool = False - -@dataclass(slots=True) -class VIOptimizerOptions: - cam: OptCamOptions = field(default_factory=OptCamOptions) - imu: OptIMUOptions = field(default_factory=OptIMUOptions) - optim: OptOptions = field(default_factory=OptOptions) - - colmap_pipeline: pycolmap.IncrementalPipelineOptions = \ - pycolmap.IncrementalPipelineOptions() - - @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> "VIOptimizerOptions": - if cfg is None: - return cls() - - base = cls() - cam = _structured_merge_to_obj(OptCamOptions, cfg.cam) - imu = _structured_merge_to_obj(OptIMUOptions, cfg.imu) - optim = _structured_merge_to_obj(OptOptions, cfg.general) - - # leave colmap_pipeline as default - return replace( - base, - cam=cam, - imu=imu, - optim=optim, - ) \ No newline at end of file diff --git a/lamaria/rig/config/pipeline.py b/lamaria/rig/config/pipeline.py deleted file mode 100644 index 5b83d1d..0000000 --- a/lamaria/rig/config/pipeline.py +++ /dev/null @@ -1,117 +0,0 @@ -from pathlib import Path -from typing import Optional, Sequence, Any -from omegaconf import OmegaConf, DictConfig -from dataclasses import replace - -from .options import ( - EstimateToColmapOptions, - VIOptimizerOptions, - TriangulatorOptions, - KeyframeSelectorOptions, -) - -class PipelineOptions: - default_cfg: Path = Path("defaults.yaml") - workspace: Path = Path("/media/lamaria/") - seq_name: str = "5cp" - - def __init__(self) -> None: - self._cfg: DictConfig = self._load_cfg(self.default_cfg, None) - - @classmethod - def _from_cfg(cls, cfg: DictConfig) -> "PipelineOptions": - obj = cls.__new__(cls) - obj._cfg = cfg - return obj - - @staticmethod - def _load_cfg( - cfg_file: Path | str, - cli_overrides: Optional[Sequence[str]], - ) -> DictConfig: - cfg = OmegaConf.load(str(cfg_file)) - if cli_overrides: - cfg = OmegaConf.merge(cfg, OmegaConf.from_dotlist(list(cli_overrides))) - OmegaConf.resolve(cfg) - return cfg - - @classmethod - def load( - cls, - base_file: Path | str | None = None, - cli_overrides: Optional[Sequence[str]] = None, - ) -> "PipelineOptions": - cfg_path = base_file if base_file is not None else cls.default_cfg - return cls._from_cfg(cls._load_cfg(cfg_path, cli_overrides)) - - @property - def config(self) -> DictConfig: - return self._cfg - - @staticmethod - def _select(cfg: DictConfig, key: str, default: Any = None) -> Any: - val = OmegaConf.select(cfg, key) - return default if val is None else val - - @property - def workspace_path(self) -> Path: - return Path(self._select(self._cfg, "workspace", Path(type(self).workspace))) - - @property - def seq_name(self) -> str: - return str(self._select(self._cfg, "seq_name", type(self).seq_name)) - - @property - def output_path(self) -> Path: - return self.workspace_path / "output" / self.seq_name - - def get_estimate_to_colmap_options(self) -> EstimateToColmapOptions: - """Get EstimateToColmapOptions from config.""" - options = EstimateToColmapOptions.load( - self._cfg.estimate_to_colmap, - self._cfg.mps, - self._cfg.sensor, - ) - return replace( - options, - vrs=self.workspace_path / options.vrs, - estimate=self.workspace_path / options.estimate, - images=self.output_path / options.images, - colmap_model=self.output_path / options.colmap_model, - output_path=self.output_path, - mps_folder=(self.workspace_path / options.mps_folder) if options.mps_folder else None, - ) - - def get_keyframing_options(self) -> KeyframeSelectorOptions: - """Get KeyframeSelectorOptions from config.""" - options = KeyframeSelectorOptions.load(self._cfg.keyframing) - return replace( - options, - keyframes=self.output_path / options.keyframes, - kf_model=self.output_path / options.kf_model, - output_path=self.output_path, - ) - - def get_triangulator_options(self) -> TriangulatorOptions: - """Get TriangulatorOptions from config.""" - options = TriangulatorOptions.load(self._cfg.triangulation) - return replace( - options, - hloc=self.output_path / options.hloc, - pairs_file=self.output_path / options.hloc / options.pairs_file, - tri_model=self.output_path / options.tri_model, - output_path=self.output_path, - ) - - def get_vi_optimizer_options(self) -> VIOptimizerOptions: - """Get VIOptimizerOptions from config.""" - options = VIOptimizerOptions.load(self._cfg.optimization) - return replace( - options, - optim=replace( - options.optim, - optim_model=self.output_path / options.optim.optim_model, - ), - output_path=self.output_path, - ) - \ No newline at end of file From 892bd3f865f7ee27a73e07e4401b5dbfed6ef6da Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 14:25:56 +0200 Subject: [PATCH 240/665] help --- lamaria/config/helpers.py | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) create mode 100644 lamaria/config/helpers.py diff --git a/lamaria/config/helpers.py b/lamaria/config/helpers.py new file mode 100644 index 0000000..eff5d54 --- /dev/null +++ b/lamaria/config/helpers.py @@ -0,0 +1,27 @@ +# options.py helper functions +from __future__ import annotations +from pathlib import Path +from typing import Optional +from omegaconf import OmegaConf + +def _p( + x: Optional[str] | Optional[Path], + root: Optional[Path] = None +) -> Optional[Path]: + + if x is None: + return None + x = Path(x) + if root is not None and not x.is_absolute(): + return (root / x).resolve() + return x.resolve() + +def _structured_merge_to_obj(cls, section) -> object: + """ + Merge a YAML section onto a structured + config made from the dataclass `cls`, + then return a dataclass instance. + """ + base = OmegaConf.structured(cls) + merged = OmegaConf.merge(base, section or {}) + return OmegaConf.to_object(merged) \ No newline at end of file From 4eb16570d4db17c705d109654d7b1db06acbbcad Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 14:26:02 +0200 Subject: [PATCH 241/665] opts --- lamaria/config/options.py | 179 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 179 insertions(+) create mode 100644 lamaria/config/options.py diff --git a/lamaria/config/options.py b/lamaria/config/options.py new file mode 100644 index 0000000..0347eef --- /dev/null +++ b/lamaria/config/options.py @@ -0,0 +1,179 @@ +from __future__ import annotations + +from dataclasses import dataclass, field, replace +from typing import Optional +from pathlib import Path +import pycolmap +from omegaconf import OmegaConf, open_dict + +from .helpers import _structured_merge_to_obj + + +# General options +@dataclass(slots=True) +class MPSOptions: + use_mps: bool = False + use_online_calibration: bool = False # when use_mps is true (for online calib file) + has_slam_drops: bool = False # check vrs json metadata file for each sequence + + @classmethod + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> MPSOptions: + if cfg is None: + return cls() + + return _structured_merge_to_obj(cls, cfg) + + +@dataclass(slots=True) +class SensorOptions: + left_cam_stream_id: str = "1201-1" + right_cam_stream_id: str = "1201-2" + right_imu_stream_id: str = "1202-1" + camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" + + @classmethod + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> "SensorOptions": + if cfg is None: + return cls() + + obj: SensorOptions = _structured_merge_to_obj(cls, cfg) + return obj + + +# Estimate to COLMAP options +@dataclass(slots=True) +class EstimateToColmapOptions: + mps: MPSOptions = field(default_factory=MPSOptions) + sensor: SensorOptions = field(default_factory=SensorOptions) + + mps_folder: Optional[Path] = None # necessary if use_mps is true + output_path: Optional[Path] = None + + @classmethod + def load( + cls, + cfg_mps: Optional[OmegaConf] = None, + cfg_sensor: Optional[OmegaConf] = None, + ) -> EstimateToColmapOptions: + + if cfg_mps or cfg_sensor is None: + return cls() + + base = cls() + return replace( + base, + mps=MPSOptions.load(cfg_mps), + sensor=SensorOptions.load(cfg_sensor) + ) + + +# Keyframing options +@dataclass(slots=True) +class KeyframeSelectorOptions: + max_rotation: float = 20.0 # degrees + max_distance: float = 1.0 # meters + max_elapsed: int = int(1e9) # 1 second in ns + + @classmethod + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> "KeyframeSelectorOptions": + if cfg is None: + return cls() + + cfg = OmegaConf.create(cfg) + with open_dict(cfg): + if "max_elapsed" in cfg and isinstance(cfg.max_elapsed, float): + cfg.max_elapsed = int(cfg.max_elapsed) + + obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, cfg) + return obj + + +# Triangulation options +@dataclass(slots=True) +class TriangulatorOptions: + feature_conf: str = "aliked-n16" + matcher_conf: str = "aliked+lightglue" + retrieval_conf: str = "netvlad" + num_retrieval_matches: int = 5 + + # colmap defaults + merge_max_reproj_error: float = 4.0 + complete_max_reproj_error: float = 4.0 + min_angle: float = 1.5 + + filter_max_reproj_error: float = 4.0 + filter_min_tri_angle: float = 1.5 + + @classmethod + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> "TriangulatorOptions": + if cfg is None: + return cls() + + return _structured_merge_to_obj(cls, cfg) + + +# Optimization options +@dataclass(slots=True) +class OptCamOptions: + feature_std: float = 1.0 # in pixels + optimize_cam_intrinsics: bool = False + optimize_cam_from_rig: bool = False + +@dataclass(slots=True) +class OptIMUOptions: + gyro_infl: float = 1.0 + acc_infl: float = 1.0 + integration_noise_density: float = 0.05 + + optimize_scale: bool = False + optimize_gravity: bool = False + optimize_imu_from_rig: bool = False + optimize_bias: bool = False + +@dataclass(slots=True) +class OptOptions: + use_callback: bool = True + max_num_iterations: int = 10 + normalize_reconstruction: bool = False + +@dataclass(slots=True) +class VIOptimizerOptions: + cam: OptCamOptions = field(default_factory=OptCamOptions) + imu: OptIMUOptions = field(default_factory=OptIMUOptions) + optim: OptOptions = field(default_factory=OptOptions) + + colmap_pipeline: pycolmap.IncrementalPipelineOptions = \ + pycolmap.IncrementalPipelineOptions() + + @classmethod + def load( + cls, + cfg: Optional[OmegaConf] = None + ) -> "VIOptimizerOptions": + if cfg is None: + return cls() + + base = cls() + cam = _structured_merge_to_obj(OptCamOptions, cfg.cam) + imu = _structured_merge_to_obj(OptIMUOptions, cfg.imu) + optim = _structured_merge_to_obj(OptOptions, cfg.general) + + # leave colmap_pipeline as default + return replace( + base, + cam=cam, + imu=imu, + optim=optim, + ) \ No newline at end of file From 279e861bef5ce1f4922b01a2b03ab37f450fc316 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 14:26:09 +0200 Subject: [PATCH 242/665] pip --- lamaria/config/pipeline.py | 83 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 83 insertions(+) create mode 100644 lamaria/config/pipeline.py diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py new file mode 100644 index 0000000..3cf80f4 --- /dev/null +++ b/lamaria/config/pipeline.py @@ -0,0 +1,83 @@ +from pathlib import Path +from typing import Optional, Sequence, Any +from omegaconf import OmegaConf, DictConfig +from dataclasses import replace, field + +from .options import ( + EstimateToColmapOptions, + VIOptimizerOptions, + TriangulatorOptions, + KeyframeSelectorOptions, +) + +class PipelineOptions: + output_path: Path = Path("/media/lamaria/output/") + + # this should be initialized at load(config) + estimate_to_colmap_options: EstimateToColmapOptions = field( + default_factory=EstimateToColmapOptions + ) + keyframing_options: KeyframeSelectorOptions = field( + default_factory=KeyframeSelectorOptions + ) + triangulator_options: TriangulatorOptions = field( + default_factory=TriangulatorOptions + ) + vi_optimizer_options: VIOptimizerOptions = field( + default_factory=VIOptimizerOptions + ) + + @classmethod + def load( + cls, + yaml: Path | str, + cli_overrides: Optional[Sequence[str]] = None, + ) -> "PipelineOptions": + cfg = OmegaConf.load(str(yaml)) + if cli_overrides: + cfg = OmegaConf.merge(cfg, OmegaConf.from_dotlist(list(cli_overrides))) + OmegaConf.resolve(cfg) + return cls._from_cfg(cfg) + + @classmethod + def _from_cfg(cls, cfg: DictConfig) -> "PipelineOptions": + obj = cls.__new__(cls) + obj.output_path = Path(cls._select(cfg, "output_path", obj.output_path)) + obj.estimate_to_colmap_options = EstimateToColmapOptions.load( + cfg.mps, + cfg.sensor, + ) + obj.keyframing_options = KeyframeSelectorOptions.load(cfg.keyframing) + obj.triangulator_options = TriangulatorOptions.load(cfg.triangulation) + obj.vi_optimizer_options = VIOptimizerOptions.load(cfg.optimization) + return obj + + @staticmethod + def _select(cfg: DictConfig, key: str, default: Any = None) -> Any: + val = OmegaConf.select(cfg, key) + return default if val is None else val + + @property + def output_path(self) -> Path: + return self.output_path + + @property + def estimate_to_colmap_options(self) -> EstimateToColmapOptions: + return self.estimate_to_colmap_options + + @property + def colmap_model(self) -> Path: + return self.output_path / "initial_recon" + + @property + def keyframing_options(self) -> KeyframeSelectorOptions: + return self.keyframing_options + + @property + def triangulator_options(self) -> TriangulatorOptions: + return self.triangulator_options + + @property + def vi_optimizer_options(self) -> VIOptimizerOptions: + return self.vi_optimizer_options + \ No newline at end of file From 96c93d31b79abb638d0fe9e47983cf65d7a4fb59 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 15:48:07 +0200 Subject: [PATCH 243/665] pipeleine --- lamaria/config/pipeline.py | 108 ++++++++++++++++++++++--------------- 1 file changed, 66 insertions(+), 42 deletions(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 3cf80f4..af46249 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -1,7 +1,6 @@ from pathlib import Path -from typing import Optional, Sequence, Any +from typing import Optional, Sequence from omegaconf import OmegaConf, DictConfig -from dataclasses import replace, field from .options import ( EstimateToColmapOptions, @@ -11,73 +10,98 @@ ) class PipelineOptions: - output_path: Path = Path("/media/lamaria/output/") + def __init__(self) -> None: + self._output_path: Path = Path("/output/") + self._estimate_to_colmap_options: EstimateToColmapOptions = EstimateToColmapOptions() + self._keyframing_options: KeyframeSelectorOptions = KeyframeSelectorOptions() + self._triangulator_options: TriangulatorOptions = TriangulatorOptions() + self._vi_optimizer_options: VIOptimizerOptions = VIOptimizerOptions() - # this should be initialized at load(config) - estimate_to_colmap_options: EstimateToColmapOptions = field( - default_factory=EstimateToColmapOptions - ) - keyframing_options: KeyframeSelectorOptions = field( - default_factory=KeyframeSelectorOptions - ) - triangulator_options: TriangulatorOptions = field( - default_factory=TriangulatorOptions - ) - vi_optimizer_options: VIOptimizerOptions = field( - default_factory=VIOptimizerOptions - ) - - @classmethod def load( - cls, + self, yaml: Path | str, cli_overrides: Optional[Sequence[str]] = None, - ) -> "PipelineOptions": + ) -> None: + """Load configuration from a YAML file and apply any overrides.""" cfg = OmegaConf.load(str(yaml)) if cli_overrides: cfg = OmegaConf.merge(cfg, OmegaConf.from_dotlist(list(cli_overrides))) OmegaConf.resolve(cfg) - return cls._from_cfg(cfg) - - @classmethod - def _from_cfg(cls, cfg: DictConfig) -> "PipelineOptions": - obj = cls.__new__(cls) - obj.output_path = Path(cls._select(cfg, "output_path", obj.output_path)) - obj.estimate_to_colmap_options = EstimateToColmapOptions.load( + + self._update_from_cfg(cfg) + + def _update_from_cfg(self, cfg: DictConfig) -> None: + """Update object attributes from a config.""" + self._estimate_to_colmap_options = EstimateToColmapOptions.load( cfg.mps, cfg.sensor, ) - obj.keyframing_options = KeyframeSelectorOptions.load(cfg.keyframing) - obj.triangulator_options = TriangulatorOptions.load(cfg.triangulation) - obj.vi_optimizer_options = VIOptimizerOptions.load(cfg.optimization) - return obj + self._keyframing_options = KeyframeSelectorOptions.load(cfg.keyframing) + self._triangulator_options = TriangulatorOptions.load(cfg.triangulation) + self._vi_optimizer_options = VIOptimizerOptions.load(cfg.optimization) + + out = cfg.get("output_path", None) + self._output_path = Path(out) if out is not None else Path("/output/") - @staticmethod - def _select(cfg: DictConfig, key: str, default: Any = None) -> Any: - val = OmegaConf.select(cfg, key) - return default if val is None else val - @property def output_path(self) -> Path: - return self.output_path + """Get the parent output path.""" + return self._output_path + @output_path.setter + def output_path(self, path: Path) -> None: + """Set the parent output path.""" + self._output_path = path + + # Properties for estimate to COLMAP @property def estimate_to_colmap_options(self) -> EstimateToColmapOptions: - return self.estimate_to_colmap_options + return self._estimate_to_colmap_options + + @property + def images(self) -> Path: + return self._output_path / "images" @property def colmap_model(self) -> Path: - return self.output_path / "initial_recon" + return self._output_path / "initial_recon" + # Properties for keyframing @property def keyframing_options(self) -> KeyframeSelectorOptions: - return self.keyframing_options + return self._keyframing_options + + @property + def keyframes(self) -> Path: + return self._output_path / "keyframes" + @property + def kf_model(self) -> Path: + return self._output_path / "keyframed_recon" + + # Properties for triangulation @property def triangulator_options(self) -> TriangulatorOptions: - return self.triangulator_options + return self._triangulator_options + + @property + def hloc(self) -> Path: + return self._output_path / "hloc" + + @property + def pairs_file(self) -> Path: + return self._output_path / "pairs.txt" + + @property + def tri_model(self) -> Path: + return self._output_path / "triangulated_recon" + # Properties for visual-inertial optimization @property def vi_optimizer_options(self) -> VIOptimizerOptions: - return self.vi_optimizer_options + return self._vi_optimizer_options + + @property + def optim_model(self) -> Path: + return self._output_path / "optim_recon" \ No newline at end of file From 1af9a6c071449b154ab84faf70ec89971f163c1f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 15:52:54 +0200 Subject: [PATCH 244/665] bug fix --- lamaria/config/options.py | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 0347eef..5d7ec92 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -52,9 +52,6 @@ class EstimateToColmapOptions: mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) - mps_folder: Optional[Path] = None # necessary if use_mps is true - output_path: Optional[Path] = None - @classmethod def load( cls, @@ -62,7 +59,7 @@ def load( cfg_sensor: Optional[OmegaConf] = None, ) -> EstimateToColmapOptions: - if cfg_mps or cfg_sensor is None: + if cfg_mps is None or cfg_sensor is None: return cls() base = cls() From eb7f759095f4dd7898fddf3c19103869fc163a19 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 15:53:52 +0200 Subject: [PATCH 245/665] fatcs --- defaults.yaml | 18 +----------------- 1 file changed, 1 insertion(+), 17 deletions(-) diff --git a/defaults.yaml b/defaults.yaml index a71637d..2e298de 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -1,31 +1,16 @@ # Default configuration for run_pipeline.py -workspace: /media/arialamar/ -seq_name: 5cp - -estimate_to_colmap: - vrs: recordings/${seq_name}.vrs - estimate: est/${seq_name}.txt - mps_folder: mps/mps_${seq_name}_vrs/ # necessary if use_mps is true - images: image_stream - colmap_model: initial_recon +output_path: /output sensor: camera_model: RAD_TAN_THIN_PRISM_FISHEYE keyframing: - keyframes: keyframes - kf_model: keyframe_recon - max_rotation: 20.0 max_distance: 1.0 max_elapsed: 1e9 # 1 second in ns triangulation: - hloc: hloc - pairs_file: pairs.txt - tri_model: triangulated_recon - feature_conf: aliked-n16 matcher_conf: aliked+lightglue retrieval_conf: netvlad @@ -43,7 +28,6 @@ triangulation: optimization: general: - optim_model: optim_recon use_callback: true max_num_iterations: 10 normalize_reconstruction: false From de215e7685430679e06ab27d2a23e1f779b92b47 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 15:55:24 +0200 Subject: [PATCH 246/665] to col --- lamaria/rig/keyframing/to_colmap.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index a2b48ee..2cd8a32 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -15,7 +15,7 @@ from ... import logger from ..lamaria_reconstruction import LamariaReconstruction -from ..config.options import EstimateToColmapOptions +from ...config.options import EstimateToColmapOptions from ...utils.general import ( get_matched_timestamps, extract_images_from_vrs, From 336519f72ffe8a10a2e86668445693f08ae1996b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 15:56:01 +0200 Subject: [PATCH 247/665] kf --- lamaria/rig/keyframing/keyframe_selection.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 81ce345..0f1b2ed 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -9,7 +9,7 @@ import pycolmap from ..lamaria_reconstruction import LamariaReconstruction -from ..config.options import KeyframeSelectorOptions +from ...config.options import KeyframeSelectorOptions from ...utils.transformation import get_magnitude_from_transform From 53bfd3cae7382a0acba0f030dd15fc7459c27ed9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 16:25:59 +0200 Subject: [PATCH 248/665] fixes --- lamaria/rig/keyframing/to_colmap.py | 33 +++++++++++++++++++++++------ 1 file changed, 27 insertions(+), 6 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 2cd8a32..dcca314 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -1,7 +1,7 @@ from __future__ import annotations -from typing import List, Tuple, Dict +from typing import List, Tuple, Dict, Optional from pathlib import Path import numpy as np import pycolmap @@ -216,9 +216,9 @@ def _get_images(self) -> List[Tuple[Path, Path]]: return list(zip(left_images, right_images)) def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: + L = self._ts_from_vrs(self._left_cam_sid) + R = self._ts_from_vrs(self._right_cam_sid) if not self.options.mps.has_slam_drops: - L = self._ts_from_vrs(self._left_cam_sid) - R = self._ts_from_vrs(self._right_cam_sid) assert len(L) == len(R), "Unequal number of left and right timestamps" matched = list(zip(L, R)) if not all(abs(l - r) < max_diff for l, r in matched): @@ -280,7 +280,11 @@ def _get_dummy_imu_params(self) -> List: def _add_device_sensors(self) -> None: """Adds a new rig with device calibrated sensors. - The rig is consistent across all frames""" + The rig is consistent across all frames + + Camera ID layout: + rig_id=1 -> (imu=1, left=2, right=3) + """ device_calibration = self._vrs_provider.get_device_calibration() imu_stream_label = self._vrs_provider.get_label_from_stream_id( self._right_imu_sid @@ -331,6 +335,12 @@ def _add_device_sensors(self) -> None: def _add_online_sensors(self) -> None: """Adds a new rig for each frame timestamp. Each rig has its own online calibrated sensors. + + Camera ID layout: + rig_id=1 -> (imu=1, left=2, right=3); + rig_id=2 -> (imu=4, left=5, right=6); + rig_id=3 -> (imu=7, left=8, right=9); + ... """ sensor_id = 1 for fid, pfd in self._per_frame_data.items(): @@ -418,7 +428,14 @@ def _add_device_frames(self) -> None: self.data.reconstruction.add_image(im) def _add_online_frames(self) -> None: - """Adds frame data for each rig, each rig has its own online calibrated sensors""" + """Adds frame data for each rig, each rig has its own online calibrated sensors + + Frame ID layout: + fid=1 -> (imu=1, left=2, right=3), (image IDs: 1, 2); + fid=2 -> (imu=4, left=5, right=6), (image IDs: 3, 4); + fid=3 -> (imu=7, left=8, right=9), (image IDs: 5, 6); + ... + """ image_id = 1 for fid, pfd in self._per_frame_data.items(): @@ -428,8 +445,12 @@ def _add_online_frames(self) -> None: frame.rig_from_world = pfd.rig_from_world images_to_add = [] + # Camera ID layout from _add_online_sensors(): + # fid=1 -> (imu=1, left=2, right=3); fid=2 -> (imu=4, left=5, right=6); ... + left_cam_id = 3 * fid - 1 + right_cam_id = 3 * fid - for cam_id, img_path in [(3*id + 2, pfd.left_img), (3*id + 3, pfd.right_img)]: + for cam_id, img_path in [(left_cam_id, pfd.left_img), (right_cam_id, pfd.right_img)]: im = pycolmap.Image( str(img_path), pycolmap.Point2DList(), From eab2c16a6fa03a0cbf47a934c298973749b4db31 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 16:48:39 +0200 Subject: [PATCH 249/665] may changes to to colmap --- lamaria/rig/keyframing/to_colmap.py | 125 +++++++++++++++++----------- 1 file changed, 78 insertions(+), 47 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index dcca314..b018a54 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -48,19 +48,73 @@ class PerFrameData: class EstimateToColmap: - def __init__( - self, - options: EstimateToColmapOptions - ): + """Converts estimate or MPS data to COLMAP format.""" + + def __init__(self, options: EstimateToColmapOptions): self.options = options - self._init_io() - self._init_data() + self.data: LamariaReconstruction | None = None + self._vrs_provider = None + self._mps_data_provider = None + self._left_cam_sid: StreamId | None = None + self._right_cam_sid: StreamId | None = None + self._right_imu_sid: StreamId | None = None + self._per_frame_data: Dict[int, PerFrameData] = {} + + + @classmethod + def run( + cls, + options: EstimateToColmapOptions, + vrs: Path, + images: Path, + estimate: Optional[Path] = None, + mps_folder: Optional[Path] = None, + ) -> LamariaReconstruction: + """Static method to run the full pipeline.""" + return cls(options).process(vrs, images, estimate, mps_folder) + + + # -------- public API -------- + def process( + self, + vrs: Path, + images: Path, + estimate: Optional[Path] = None, + mps_folder: Optional[Path] = None, + ) -> LamariaReconstruction: + """Main one-shot runner.""" + self._init_data(vrs, images, estimate, mps_folder) + + if self.options.mps.use_online_calibration and self.options.mps.use_mps: + self._add_online_sensors() + self._add_online_frames() + else: + self._add_device_sensors() + self._add_device_frames() + + # IMU + timestamps + ms = self._get_rectified_imu_data() + self.data.imu_measurements = ms + self.data.timestamps = {fid: pfd.left_ts for fid, pfd in self._per_frame_data.items()} + return self.data + + # -------- internal methods -------- + def _init_data( + self, + vrs: Path, + image_folder: Path, + estimate: Optional[Path] = None, + mps_folder: Optional[Path] = None + ) -> None: + """Initializes data providers and extracts images, timestamps and builds per-frame data object. + Per-frame data is used to create the initial Lamaria reconstruction. + """ - def _init_io(self): - """Initializes output and data providers""" self.data = LamariaReconstruction() + + # Initialize VRS data provider self._vrs_provider = data_provider.create_vrs_data_provider( - self.options.vrs.as_posix() + vrs.as_posix() ) # Initialize stream IDs @@ -70,24 +124,22 @@ def _init_io(self): # Initialize MPS data provider if needed if self.options.mps.use_mps: - data_paths = mps.MpsDataPathsProvider(self.options.mps_folder.as_posix()).get_data_paths() + assert mps_folder is not None, "MPS folder path must be provided if using MPS" + data_paths = mps.MpsDataPathsProvider(mps_folder.as_posix()).get_data_paths() self._mps_data_provider = mps.MpsDataProvider(data_paths) - - def _init_data(self): - """Extracts images, timestamps and builds per-frame data object. - Per-frame data is used to create the initial Lamaria reconstruction. - """ + # Extract images from VRS file extract_images_from_vrs( - vrs_file=self.options.vrs, - image_folder=self.options.images, + vrs_file=vrs, + image_folder=image_folder, ) - images = self._get_images() + images = self._get_images(image_folder) + # Get timestamps and build per-frame data if self.options.mps.use_mps: timestamps = self._get_mps_timestamps() - closed_loop_data = get_closed_loop_data_from_mps(self.options.mps) + closed_loop_data = get_closed_loop_data_from_mps(mps_folder) pose_timestamps = [ l for l, _ in timestamps ] mps_poses = get_mps_poses_for_timestamps(closed_loop_data, pose_timestamps) self._per_frame_data = self._build_per_frame_data_from_mps( @@ -96,16 +148,17 @@ def _init_data(self): mps_poses ) else: - flag = check_estimate_format(self.options.estimate) + assert estimate is not None, "Estimate path must be provided if not using MPS" + flag = check_estimate_format(estimate) if not flag: raise ValueError("Estimate file format is incorrect.") - timestamps = get_estimate_timestamps(self.options.estimate) + timestamps = get_estimate_timestamps(estimate) if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images(images, timestamps) rig_from_worlds = get_rig_from_worlds_from_estimate( - self.options.estimate, + estimate, ) self._per_frame_data = self._build_per_frame_data_from_estimate( images, @@ -206,9 +259,9 @@ def _ts_from_vrs(self, sid: StreamId) -> List[int]: """Timestamps in nanoseconds""" return sorted(self._vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME)) - def _get_images(self) -> List[Tuple[Path, Path]]: - left_img_dir = self.options.images / "left" - right_img_dir = self.options.images / "right" + def _get_images(self, images: Path) -> List[Tuple[Path, Path]]: + left_img_dir = images / "left" + right_img_dir = images / "right" left_images = self._images_from_vrs(left_img_dir, left_img_dir) right_images = self._images_from_vrs(right_img_dir, right_img_dir) @@ -480,25 +533,3 @@ def _get_rectified_imu_data(self) -> pycolmap.ImuMeasurements: ) return ms - - def create(self) -> LamariaReconstruction: - """Creates Lamaria reconstruction with timestamps, IMU data, sensors and frames""" - if self.options.mps.use_online_calibration \ - and self.options.mps.use_mps: - self._add_online_sensors() - self._add_online_frames() - else: - self._add_device_sensors() - self._add_device_frames() - - # Populating IMU data - ms = self._get_rectified_imu_data() - self.data.imu_measurements = ms - - # Populating timestamps map - self.data.timestamps = { - frame_id: pfd.left_ts - for frame_id, pfd in self._per_frame_data.items() - } - - return self.data From 9ffc3b16a32a1acd8cb8e799334d15cc1df73505 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 16:56:08 +0200 Subject: [PATCH 250/665] to colmap --- lamaria/rig/keyframing/to_colmap.py | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index b018a54..0486458 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -70,7 +70,7 @@ def run( estimate: Optional[Path] = None, mps_folder: Optional[Path] = None, ) -> LamariaReconstruction: - """Static method to run the full pipeline.""" + """Class method to run the full pipeline.""" return cls(options).process(vrs, images, estimate, mps_folder) @@ -93,7 +93,7 @@ def process( self._add_device_frames() # IMU + timestamps - ms = self._get_rectified_imu_data() + ms = self._get_rectified_imu_data(mps_folder) self.data.imu_measurements = ms self.data.timestamps = {fid: pfd.left_ts for fid, pfd in self._per_frame_data.items()} return self.data @@ -321,7 +321,7 @@ def _match_estimate_ts_to_images( return matched_images, matched_timestamps - def _get_dummy_imu_params(self) -> List: + def _get_dummy_imu_params(self) -> Tuple[int, int, List[float]]: # Dummy values for IMU "camera" width = 640 height = 480 @@ -519,13 +519,17 @@ def _add_online_frames(self) -> None: for im in images_to_add: self.data.reconstruction.add_image(im) - def _get_rectified_imu_data(self) -> pycolmap.ImuMeasurements: + def _get_rectified_imu_data( + self, + mps_folder: Optional[Path] = None, + ) -> pycolmap.ImuMeasurements: """Generates rectified IMU data from VRS file""" if self.options.mps.use_online_calibration \ and self.options.mps.use_mps: + assert mps_folder is not None, "MPS folder path must be provided if using MPS" ms = get_imu_data_from_vrs( self._vrs_provider, - self.options.paths.mps, + mps_folder, ) else: ms = get_imu_data_from_vrs( From d57a2584b3d0520855a1d007e04835a44d028649 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 16:59:02 +0200 Subject: [PATCH 251/665] aaaaaa --- lamaria/rig/keyframing/to_colmap.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 0486458..b11db72 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -52,7 +52,7 @@ class EstimateToColmap: def __init__(self, options: EstimateToColmapOptions): self.options = options - self.data: LamariaReconstruction | None = None + self.data: LamariaReconstruction = LamariaReconstruction() self._vrs_provider = None self._mps_data_provider = None self._left_cam_sid: StreamId | None = None @@ -109,8 +109,6 @@ def _init_data( """Initializes data providers and extracts images, timestamps and builds per-frame data object. Per-frame data is used to create the initial Lamaria reconstruction. """ - - self.data = LamariaReconstruction() # Initialize VRS data provider self._vrs_provider = data_provider.create_vrs_data_provider( @@ -322,7 +320,7 @@ def _match_estimate_ts_to_images( return matched_images, matched_timestamps def _get_dummy_imu_params(self) -> Tuple[int, int, List[float]]: - # Dummy values for IMU "camera" + """Generates dummy IMU camera parameters for COLMAP.""" width = 640 height = 480 random_params = [241.604, 241.604, 322.895, 240.444, \ From aa4703604a4ccfb1b4b884c0e83cb104909f10f9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 16:59:49 +0200 Subject: [PATCH 252/665] convert --- lamaria/rig/keyframing/to_colmap.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index b11db72..d5f0cba 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -62,7 +62,7 @@ def __init__(self, options: EstimateToColmapOptions): @classmethod - def run( + def convert( cls, options: EstimateToColmapOptions, vrs: Path, From d8b6ebfa2a767f66d341b94cc39f7bfe7d0d0dc7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 17:43:18 +0200 Subject: [PATCH 253/665] bunch of changes --- run_pipeline.py | 137 ++++++++++++++++++++++++++++++------------------ 1 file changed, 86 insertions(+), 51 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index 098c594..888c98e 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -9,8 +9,8 @@ from lamaria.rig.optim.triangulation import run as triangulate from lamaria.rig.optim.session import SingleSeqSession from lamaria.rig.optim.vi_optimization import run as run_vi_optimization -from lamaria.rig.config.pipeline import PipelineOptions -from lamaria.rig.config.options import ( +from lamaria.config.pipeline import PipelineOptions +from lamaria.config.options import ( EstimateToColmapOptions, KeyframeSelectorOptions, TriangulatorOptions, @@ -21,19 +21,35 @@ def run_estimate_to_colmap( options: EstimateToColmapOptions, vrs: Path, - estimate: Path, images: Path, + estimate: Path, colmap_model: Path, - mps_folder: Optional[Path] = None, ) -> LamariaReconstruction: - options = options.set_custom_paths( + if colmap_model.exists(): + lamaria_recon = LamariaReconstruction.read(colmap_model) + return lamaria_recon + + colmap_model.mkdir(parents=True, exist_ok=True) + + lamaria_recon = EstimateToColmap.convert( + options, vrs, - estimate, images, - colmap_model, - mps_folder, + estimate, ) + lamaria_recon.write(colmap_model) + + return lamaria_recon + + +def run_mps_to_colmap( + options: EstimateToColmapOptions, + vrs: Path, + images: Path, + mps_folder: Path, + colmap_model: Path, +) -> LamariaReconstruction: if colmap_model.exists(): lamaria_recon = LamariaReconstruction.read(colmap_model) @@ -41,8 +57,12 @@ def run_estimate_to_colmap( colmap_model.mkdir(parents=True, exist_ok=True) - est_to_colmap = EstimateToColmap(options) - lamaria_recon = est_to_colmap.create() + lamaria_recon = EstimateToColmap.convert( + options, + vrs, + images, + mps_folder, + ) lamaria_recon.write(colmap_model) return lamaria_recon @@ -61,27 +81,21 @@ def run_keyframe_selection( else: input_recon = input - options = options.set_custom_paths( - keyframes, - kf_model, - ) - if kf_model.exists(): kf_lamaria_recon = LamariaReconstruction.read(kf_model) return kf_lamaria_recon kf_model.mkdir(parents=True, exist_ok=True) - kf_selector = KeyframeSelector(options, input_recon) - kf_lamaria_recon = kf_selector.run_keyframing() + kf_lamaria_recon = KeyframeSelector.run( + options, + input_recon, + images, + keyframes, + ) kf_lamaria_recon.write(kf_model) - if not keyframes.exists(): - keyframes.mkdir(parents=True, exist_ok=True) - - kf_selector.copy_images_to_keyframes_dir(images, keyframes) - return kf_lamaria_recon @@ -97,12 +111,6 @@ def run_triangulation( raise ValueError("Input must be a Path to the reconstruction") assert input.exists(), f"input reconstruction path {input} does not exist" - - options = options.set_custom_paths( - hloc, - pairs_file, - tri_model, - ) if tri_model.exists(): tri_lamaria_recon = LamariaReconstruction.read(tri_model) @@ -110,8 +118,11 @@ def run_triangulation( triangulated_model_path = triangulate( options, - reference_model=input, - keyframes=keyframes, + input, + keyframes, + hloc, + pairs_file, + tri_model, ) input_lamaria_recon = LamariaReconstruction.read(input) @@ -162,38 +173,62 @@ def run_optimization( optim_lamaria_recon.write(optim_model) -def run_pipeline(): - pipeline_options = PipelineOptions() +def run_pipeline( + options: PipelineOptions, + vrs: Path, + output_path: Path, + estimate: Optional[Path] = None, + mps_folder: Optional[Path] = None, +): + # Using setter to set output path for entire pipeline + options.output_path = output_path + if not output_path.exists(): + output_path.mkdir(parents=True, exist_ok=True) # Estimate to COLMAP - est_options = pipeline_options.get_estimate_to_colmap_options() - _ = run_estimate_to_colmap( - est_options, - est_options.vrs, - est_options.estimate, - est_options.images, - est_options.colmap_model, - ) + est_options = options.estimate_to_colmap_options + if not est_options.mps.use_mps: + assert estimate is not None \ + and estimate.exists(), "Estimate path must be provided if not using MPS" + + _ = run_estimate_to_colmap( + est_options, + vrs, + options.images, + estimate, + options.colmap_model, + ) + else: + assert mps_folder is not None \ + and mps_folder.exists(), "MPS folder path must be provided if using MPS" + + _ = run_mps_to_colmap( + est_options, + vrs, + options.images, + mps_folder, + options.colmap_model, + ) # Keyframe Selection - kf_options = pipeline_options.get_keyframing_options() + kf_options = options.keyframing_options _ = run_keyframe_selection( kf_options, - est_options.colmap_model, - est_options.images, - kf_options.keyframes, - kf_options.kf_model, + options.colmap_model, + options.images, + options.keyframes, + options.kf_model, ) # Triangulation - tri_options = pipeline_options.get_triangulator_options() + tri_options = options.triangulator_options _ = run_triangulation( tri_options, - kf_options.kf_model, - kf_options.keyframes, - tri_options.hloc, - tri_options.pairs_file, - tri_options.tri_model, + options.kf_model, + options.keyframes, + options.hloc, + options.pairs_file, + options.tri_model, ) # Visual-Inertial Optimization From b8482a656965bca48eff7a9331742c2b0a2eeedf Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 17:44:24 +0200 Subject: [PATCH 254/665] kf selections --- lamaria/rig/keyframing/keyframe_selection.py | 36 ++++++++++++++------ 1 file changed, 26 insertions(+), 10 deletions(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 0f1b2ed..e1d010c 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -14,6 +14,8 @@ class KeyframeSelector: + """Class to perform keyframe selection on a LamariaReconstruction object.""" + def __init__( self, options: KeyframeSelectorOptions, @@ -27,6 +29,21 @@ def __init__( self.keyframed_data: LamariaReconstruction = LamariaReconstruction() self.keyframe_frame_ids: Optional[Dict[int, int]] = None + @staticmethod + def run( + options: KeyframeSelectorOptions, + data: LamariaReconstruction, + original_image_dir: Path, + keyframes_dir: Path, + ) -> LamariaReconstruction: + """ Static method to run keyframing and copy images to keyframes directory.""" + + selector = KeyframeSelector(options, data) + kf_recon = selector.run_keyframing() + selector.copy_images_to_keyframes_dir(original_image_dir, keyframes_dir) + + return kf_recon + def _select_keyframes(self): self.keyframe_frame_ids: Dict[int, int] = {} dr_dt = np.array([0.0, 0.0]) @@ -184,8 +201,9 @@ def _build_online_keyframed_reconstruction(self): for img in images_to_add: self.keyframed_data.reconstruction.add_image(img) + # -------- public API -------- def run_keyframing(self) -> LamariaReconstruction: - """ Main function to run keyframing on input lamaria reconstruction.""" + """ Function to run keyframing on lamaria reconstruction.""" self._select_keyframes() if len(self.init_recons.rigs.keys()) == 1: # device rig has been added self._build_device_keyframed_reconstruction() @@ -205,7 +223,7 @@ def run_keyframing(self) -> LamariaReconstruction: def copy_images_to_keyframes_dir( self, images: Path, - output: Optional[Path] = None, + output: Path, ) -> Path: """ Copy images corresponding to keyframes to a separate directory. Images are expected to be in `images/left` and `images/right` subdirectories. @@ -214,12 +232,10 @@ def copy_images_to_keyframes_dir( if self.keyframe_frame_ids is None: raise ValueError("Keyframes not selected yet. Run `run_keyframing` first.") - output_dir = output if output is not None else self.options.keyframes + if output.exists() and any(output.iterdir()): + shutil.rmtree(output) - if output_dir.exists() and any(output_dir.iterdir()): - shutil.rmtree(output_dir) - - output_dir.mkdir(parents=True, exist_ok=True) + output.mkdir(parents=True, exist_ok=True) for _, frame_id in self.keyframe_frame_ids.items(): frame = self.init_recons.frames[frame_id] @@ -228,8 +244,8 @@ def copy_images_to_keyframes_dir( subdir = "left" if "1201-1" in image.name else "right" src_path = images / subdir / image.name - dst_path = output_dir / image.name + dst_path = output / image.name shutil.copy2(src_path, dst_path) - - return output_dir \ No newline at end of file + + return output \ No newline at end of file From e3b685bf879611f49890af2fdfae8b374dfa63d1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 17:45:22 +0200 Subject: [PATCH 255/665] fix pairs path --- lamaria/config/pipeline.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index af46249..2fe1598 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -90,7 +90,7 @@ def hloc(self) -> Path: @property def pairs_file(self) -> Path: - return self._output_path / "pairs.txt" + return self._output_path / "hloc" / "pairs.txt" @property def tri_model(self) -> Path: From c414acb215c4abf09c53f296b951fe40150af1b3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 17:45:48 +0200 Subject: [PATCH 256/665] omu --- lamaria/rig/optim/imu.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index d6b8283..12abb87 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -5,7 +5,7 @@ from tqdm import tqdm from ... import logger -from ..config.options import OptIMUOptions +from ...config.options import OptIMUOptions from ..lamaria_reconstruction import LamariaReconstruction From 570c59a9535fc3d05c4090c0c20a49689871264d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 17:46:25 +0200 Subject: [PATCH 257/665] triangulation --- lamaria/rig/optim/triangulation.py | 17 ++++++++--------- 1 file changed, 8 insertions(+), 9 deletions(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 7539efd..eba4820 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -13,7 +13,7 @@ ) from ... import logger -from ..config.options import TriangulatorOptions +from ...config.options import TriangulatorOptions def pairs_from_frames(recon: pycolmap.Reconstruction): @@ -67,20 +67,19 @@ def run( options: TriangulatorOptions, reference_model: Path, # reconstruction path keyframes: Path, + hloc_dir: Path, + pairs_path: Path, + triangulated_model_path: Path, ) -> Path: if not keyframes.exists(): raise FileNotFoundError(f"keyframes_dir not found at {keyframes}") - hloc_outputs_dir = options.hloc - hloc_outputs_dir.mkdir(parents=True, exist_ok=True) + hloc_dir.mkdir(parents=True, exist_ok=True) if not reference_model.exists(): raise FileNotFoundError(f"reference_model not found at {reference_model}") - triangulated_model_path = options.tri_model - pairs_path = options.pairs_file - retrieval_conf = extract_features.confs[options.retrieval_conf] feature_conf = extract_features.confs[options.feature_conf] matcher_conf = match_features.confs[options.matcher_conf] @@ -90,8 +89,8 @@ def run( options.feature_conf, options.matcher_conf) - retrieval_path = extract_features.main(retrieval_conf, image_dir=keyframes, export_dir=hloc_outputs_dir) - features_path = extract_features.main(feature_conf, image_dir=keyframes, export_dir=hloc_outputs_dir) + retrieval_path = extract_features.main(retrieval_conf, image_dir=keyframes, export_dir=hloc_dir) + features_path = extract_features.main(feature_conf, image_dir=keyframes, export_dir=hloc_dir) pairs_from_retrieval.main(retrieval_path, pairs_path, options.num_retrieval_matches) postprocess_pairs_with_reconstruction(pairs_path, reference_model) @@ -100,7 +99,7 @@ def run( conf=matcher_conf, pairs=pairs_path, features=feature_conf["output"], - export_dir=hloc_outputs_dir, + export_dir=hloc_dir, ) _ = triangulation.main( From e8cd72643dd1747af0f40e5bd77a2a0d5d687065 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 17:47:02 +0200 Subject: [PATCH 258/665] cd --- lamaria/rig/keyframing/to_colmap.py | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index d5f0cba..ce4aae0 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -59,20 +59,24 @@ def __init__(self, options: EstimateToColmapOptions): self._right_cam_sid: StreamId | None = None self._right_imu_sid: StreamId | None = None self._per_frame_data: Dict[int, PerFrameData] = {} - - - @classmethod + + + @staticmethod def convert( - cls, options: EstimateToColmapOptions, vrs: Path, images: Path, estimate: Optional[Path] = None, mps_folder: Optional[Path] = None, ) -> LamariaReconstruction: - """Class method to run the full pipeline.""" - return cls(options).process(vrs, images, estimate, mps_folder) - + """Static method to run the full pipeline.""" + converter = EstimateToColmap(options) + return converter.process( + vrs, + images, + estimate, + mps_folder + ) # -------- public API -------- def process( @@ -82,7 +86,7 @@ def process( estimate: Optional[Path] = None, mps_folder: Optional[Path] = None, ) -> LamariaReconstruction: - """Main one-shot runner.""" + """Main runner.""" self._init_data(vrs, images, estimate, mps_folder) if self.options.mps.use_online_calibration and self.options.mps.use_mps: From 94d33cca602a3b3507f36cdc5fad1cd377a10f31 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 17:52:46 +0200 Subject: [PATCH 259/665] settt --- run_pipeline.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/run_pipeline.py b/run_pipeline.py index 888c98e..3cdabef 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -180,7 +180,7 @@ def run_pipeline( estimate: Optional[Path] = None, mps_folder: Optional[Path] = None, ): - # Using setter to set output path for entire pipeline + # Setting output path for entire pipeline options.output_path = output_path if not output_path.exists(): output_path.mkdir(parents=True, exist_ok=True) From f2aa6083e4526e63c6f8b8fc2f8f4d9c8b38fdd8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 18:54:20 +0200 Subject: [PATCH 260/665] relpath --- lamaria/config/pipeline.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 2fe1598..22900b6 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -11,7 +11,7 @@ class PipelineOptions: def __init__(self) -> None: - self._output_path: Path = Path("/output/") + self._output_path: Path = Path("output/") self._estimate_to_colmap_options: EstimateToColmapOptions = EstimateToColmapOptions() self._keyframing_options: KeyframeSelectorOptions = KeyframeSelectorOptions() self._triangulator_options: TriangulatorOptions = TriangulatorOptions() From 87489fd37a164ec7d42b0ae18c409165087f2bd9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 19:07:20 +0200 Subject: [PATCH 261/665] callback --- lamaria/rig/optim/callback.py | 49 +++++++++++++++++++++++++++++++++++ 1 file changed, 49 insertions(+) create mode 100644 lamaria/rig/optim/callback.py diff --git a/lamaria/rig/optim/callback.py b/lamaria/rig/optim/callback.py new file mode 100644 index 0000000..4e14677 --- /dev/null +++ b/lamaria/rig/optim/callback.py @@ -0,0 +1,49 @@ + +from copy import deepcopy +from typing import List, Tuple +import numpy as np +import pycolmap +import pyceres + +from ... import logger + +class RefinementCallback(pyceres.IterationCallback): + def __init__( + self, + poses: List[pycolmap.Rigid3d], + min_pose_change: Tuple[float, float] = (0.001, 0.000001), + min_iterations: int = 2, + ): + pyceres.IterationCallback.__init__(self) + self.poses = poses + self.poses_previous = deepcopy(self.poses) + self.min_pose_change = min_pose_change + self.min_iterations = min_iterations + self.pose_changes = [] + + def __call__(self, summary: pyceres.IterationSummary): + if not summary.step_is_successful: + return pyceres.CallbackReturnType.SOLVER_CONTINUE + diff = [] + for pose_prev, pose in zip(self.poses_previous, self.poses): + pose_rel = pose_prev * pose.inverse() + q_rel, t_rel = pose_rel.rotation.quat, pose_rel.translation + dr = np.rad2deg( + np.abs(2 * np.arctan2(np.linalg.norm(q_rel[:-1]), q_rel[-1])) + ) + dt = np.linalg.norm(t_rel) + diff.append((dr, dt)) + diff = np.array(diff) + self.poses_previous = deepcopy(self.poses) + med, q99, max_ = np.quantile(diff, [0.5, 0.99, 1.0], axis=0) + logger.info( + f"{summary.iteration:d} Pose update: " + f"med/q99/max dR={med[0]:.3f}/{q99[0]:.3f}/{max_[0]:.3f} deg, " + f"dt={med[1] * 1e2:.3f}/{q99[1] * 1e2:.3f}/{max_[1] * 1e2:.3f} cm" + ) + self.pose_changes.append((med, q99, max_)) + if summary.iteration >= self.min_iterations and np.all( + q99 <= self.min_pose_change + ): + return pyceres.CallbackReturnType.SOLVER_TERMINATE_SUCCESSFULLY + return pyceres.CallbackReturnType.SOLVER_CONTINUE \ No newline at end of file From 0c0eec36e788494e2619d5d9a81fc9f49978138e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 19:08:00 +0200 Subject: [PATCH 262/665] import callback --- lamaria/rig/optim/iterative_global_ba.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 352c43b..9156993 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -1,13 +1,12 @@ import pycolmap from pycolmap import logging import pyceres -from typing import List, Tuple -from copy import deepcopy import numpy as np from ... import logger from .session import SingleSeqSession -from .residual_manager import BundleAdjuster, IMUResidualManager +from .residual_manager import IMUResidualManager +from .callback import RefinementCallback class VIBundleAdjuster: From 3d3594727b7f95aa81eb3e9fa424836a07ae40ec Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Wed, 24 Sep 2025 19:24:06 +0200 Subject: [PATCH 263/665] mv refinement --- lamaria/rig/optim/iterative_global_ba.py | 44 +----------------------- 1 file changed, 1 insertion(+), 43 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 9156993..01ed26f 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -159,46 +159,4 @@ def run(self, mapper, pipeline_options): def _configure_mapper_options(self, pipeline_options): """Configure mapper options""" mapper_options = pipeline_options.get_mapper() - return mapper_options - - -class RefinementCallback(pyceres.IterationCallback): - def __init__( - self, - poses: List[pycolmap.Rigid3d], - min_pose_change: Tuple[float, float] = (0.001, 0.000001), - min_iterations: int = 2, - ): - pyceres.IterationCallback.__init__(self) - self.poses = poses - self.poses_previous = deepcopy(self.poses) - self.min_pose_change = min_pose_change - self.min_iterations = min_iterations - self.pose_changes = [] - - def __call__(self, summary: pyceres.IterationSummary): - if not summary.step_is_successful: - return pyceres.CallbackReturnType.SOLVER_CONTINUE - diff = [] - for pose_prev, pose in zip(self.poses_previous, self.poses): - pose_rel = pose_prev * pose.inverse() - q_rel, t_rel = pose_rel.rotation.quat, pose_rel.translation - dr = np.rad2deg( - np.abs(2 * np.arctan2(np.linalg.norm(q_rel[:-1]), q_rel[-1])) - ) - dt = np.linalg.norm(t_rel) - diff.append((dr, dt)) - diff = np.array(diff) - self.poses_previous = deepcopy(self.poses) - med, q99, max_ = np.quantile(diff, [0.5, 0.99, 1.0], axis=0) - logger.info( - f"{summary.iteration:d} Pose update: " - f"med/q99/max dR={med[0]:.3f}/{q99[0]:.3f}/{max_[0]:.3f} deg, " - f"dt={med[1] * 1e2:.3f}/{q99[1] * 1e2:.3f}/{max_[1] * 1e2:.3f} cm" - ) - self.pose_changes.append((med, q99, max_)) - if summary.iteration >= self.min_iterations and np.all( - q99 <= self.min_pose_change - ): - return pyceres.CallbackReturnType.SOLVER_TERMINATE_SUCCESSFULLY - return pyceres.CallbackReturnType.SOLVER_CONTINUE \ No newline at end of file + return mapper_options \ No newline at end of file From 40e2fee54deb4b959460af328e04007773b1be3d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 10:26:21 +0200 Subject: [PATCH 264/665] colmap format for bundle adjuster --- lamaria/rig/optim/residual_manager.py | 59 ++++++++++++++------------- 1 file changed, 30 insertions(+), 29 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 74b47f8..f44a641 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -75,7 +75,7 @@ def _setup_manifolds_and_constraints(self, problem): ) -class BundleAdjuster: +class DefaultBundleAdjuster: """Handles image residual setup and constraints""" def __init__( self, @@ -125,29 +125,34 @@ def add_image_to_problem( frame = session.data.reconstruction.frames[image.frame_id] rig = session.data.reconstruction.rigs[frame.rig_id] camera = session.data.reconstruction.cameras[image.camera_id] - rig_from_world = frame.rig_from_world cam_from_rig = None for sensor, sensor_from_rig in rig.non_ref_sensors.items(): if image.camera_id == sensor.id: cam_from_rig = sensor_from_rig + break + + assert cam_from_rig is not None, "Camera must be part of the rig" optimize_cam_from_rig = session.cam_options.optimize_cam_from_rig - optimize_cam_intrinsics = session.cam_options.optimize_cam_intrinsics feature_std = session.cam_options.feature_std num_observations = 0 for point2D in image.points2D: if not point2D.has_point3D(): continue + num_observations += 1 if point2D.point3D_id not in self.point3D_num_observations: self.point3D_num_observations[point2D.point3D_id] = 0 - self.point3D_num_observations[point2D.point3D_id] += 1 + self.point3D_num_observations[point2D.point3D_id] += 1 point3D = session.data.reconstruction.points3D[point2D.point3D_id] assert point3D.track.length() > 1 - if not optimize_cam_from_rig: + + # we always set refine_rig_from_world to True + # so that rig poses are optimized + if not optimize_cam_from_rig: # constant sensor_from_rig cost = pycolmap.cost_functions.RigReprojErrorCost( camera.model, np.eye(2) * pow(feature_std, 2), @@ -158,15 +163,12 @@ def add_image_to_problem( cost, loss, [ - rig_from_world.rotation.quat, - rig_from_world.translation, + frame.rig_from_world.rotation.quat, + frame.rig_from_world.translation, point3D.xyz, camera.params, ], ) - if not optimize_cam_intrinsics: - # do not optimise camera parameters - self.problem.set_parameter_block_constant(camera.params) else: cost = pycolmap.cost_functions.RigReprojErrorCost( camera.model, @@ -179,21 +181,18 @@ def add_image_to_problem( [ cam_from_rig.rotation.quat, cam_from_rig.translation, - rig_from_world.rotation.quat, - rig_from_world.translation, + frame.rig_from_world.rotation.quat, + frame.rig_from_world.translation, point3D.xyz, camera.params, ], ) - if not optimize_cam_intrinsics: - # do not optimise camera parameters - self.problem.set_parameter_block_constant(camera.params) if num_observations > 0: - self.camera_ids.add(image.camera_id) + self.camera_ids.add(image.camera_id) # to parameterize later # Set pose parameterization self.problem.set_manifold( - rig_from_world.rotation.quat, + frame.rig_from_world.rotation.quat, pyceres.EigenQuaternionManifold(), ) @@ -203,25 +202,27 @@ def add_image_to_problem( pyceres.EigenQuaternionManifold(), ) - def parameterize_cameras(self, reconstruction: pycolmap.Reconstruction): - constant_camera = ( - (not self.options.refine_focal_length) - and (not self.options.refine_principal_point) - and (not self.options.refine_extra_params) + def parameterize_cameras(self, session: SingleSeqSession): + constant_camera = all( + not session.cam_options.optimize_focal_length, + not session.cam_options.optimize_principal_point, + not session.cam_options.optimize_extra_params, ) + for camera_id in self.camera_ids: - camera = reconstruction.cameras[camera_id] + camera = session.data.reconstruction.cameras[camera_id] if constant_camera or self.config.has_constant_cam_intrinsics( camera_id ): self.problem.set_parameter_block_constant(camera.params) continue + const_camera_params = [] - if not self.options.refine_focal_length: + if not session.cam_options.optimize_focal_length: const_camera_params.extend(camera.focal_length_idxs()) - if not self.options.refine_principal_point: + if not session.cam_options.optimize_principal_point: const_camera_params.extend(camera.principal_point_idxs()) - if not self.options.refine_extra_params: + if not session.cam_options.optimize_extra_params: const_camera_params.extend(camera.extra_point_idxs()) if len(const_camera_params) > 0: self.problem.set_manifold( @@ -231,14 +232,14 @@ def parameterize_cameras(self, reconstruction: pycolmap.Reconstruction): ), ) - def parameterize_points(self, reconstruction: pycolmap.Reconstruction): + def parameterize_points(self, session: SingleSeqSession): for ( point3D_id, num_observations, ) in self.point3D_num_observations.items(): - point3D = reconstruction.points3D[point3D_id] + point3D = session.data.reconstruction.points3D[point3D_id] if point3D.track.length() > num_observations: self.problem.set_parameter_block_constant(point3D.xyz) for point3D_id in self.config.constant_points: - point3D = reconstruction.points3D[point3D_id] + point3D = session.data.reconstruction.points3D[point3D_id] self.problem.set_parameter_block_constant(point3D.xyz) \ No newline at end of file From 010b71e7109d95995e2ccb01584f0c1c733b8438 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 10:33:02 +0200 Subject: [PATCH 265/665] colmap defs --- defaults.yaml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/defaults.yaml b/defaults.yaml index 2e298de..90dc2fc 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -34,7 +34,9 @@ optimization: cam: feature_std: 1.0 - optimize_cam_intrinsics: false + optimize_focal_length: false + optimize_principal_point: false + optimize_extra_params: false optimize_cam_from_rig: false imu: From 685afd341fd252c61b8a6a960bf2eaad4324083e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 10:33:29 +0200 Subject: [PATCH 266/665] colmap options from defs --- lamaria/config/options.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 5d7ec92..5dbde76 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -125,7 +125,9 @@ def load( @dataclass(slots=True) class OptCamOptions: feature_std: float = 1.0 # in pixels - optimize_cam_intrinsics: bool = False + optimize_focal_length: bool = False + optimize_principal_point: bool = False + optimize_extra_params: bool = False optimize_cam_from_rig: bool = False @dataclass(slots=True) From d3fe6c6074fc92db2dee9f628dc764eb1dfc1984 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 10:34:19 +0200 Subject: [PATCH 267/665] apply constraints --- lamaria/rig/optim/iterative_global_ba.py | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 01ed26f..90e65bb 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -9,6 +9,23 @@ from .callback import RefinementCallback +def apply_constraints(problem, session: SingleSeqSession): + """Apply rig-specific constraints to the problem""" + # Fix the first rig pose + frame_ids = sorted(session.data.reconstruction.frames.keys()) + first_frame = session.data.reconstruction.frames[frame_ids[0]] + problem.set_parameter_block_constant(first_frame.rig_from_world.rotation.quat) + problem.set_parameter_block_constant(first_frame.rig_from_world.translation) + + # Fix 1 DoF translation of the second rig + second_frame = session.data.reconstruction.frames[frame_ids[1]] + problem.set_manifold( + second_frame.rig_from_world.translation, + pyceres.SubsetManifold(3, np.array([0])), + ) + return problem + + class VIBundleAdjuster: """Visual-Inertial Bundle Adjuster that combines visual and IMU residuals""" From 78b1ce52142a50e480593d11c2b0fdfc56fdf8e4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 13:12:03 +0200 Subject: [PATCH 268/665] res manager --- lamaria/rig/optim/residual_manager.py | 45 +++++++++++++++++---------- 1 file changed, 28 insertions(+), 17 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index f44a641..506b649 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -106,12 +106,12 @@ def set_up_problem( session: SingleSeqSession, loss: pyceres.LossFunction, ): - logger.info("Setting up optimization problem") assert session.data.reconstruction is not None - for image_id in tqdm(self.config.images): + for image_id in tqdm(self.config.images, desc="Adding images to problem"): self.add_image_to_problem(session, image_id, loss) - self.parameterize_cameras(session.data.reconstruction) - self.parameterize_points(session.data.reconstruction) + + self.parameterize_cameras(session) + self.parameterize_points(session) logger.info("Optimization problem set up") return self.problem @@ -125,6 +125,7 @@ def add_image_to_problem( frame = session.data.reconstruction.frames[image.frame_id] rig = session.data.reconstruction.rigs[frame.rig_id] camera = session.data.reconstruction.cameras[image.camera_id] + rig_from_world = frame.rig_from_world cam_from_rig = None for sensor, sensor_from_rig in rig.non_ref_sensors.items(): @@ -163,8 +164,8 @@ def add_image_to_problem( cost, loss, [ - frame.rig_from_world.rotation.quat, - frame.rig_from_world.translation, + rig_from_world.rotation.quat, + rig_from_world.translation, point3D.xyz, camera.params, ], @@ -181,8 +182,8 @@ def add_image_to_problem( [ cam_from_rig.rotation.quat, cam_from_rig.translation, - frame.rig_from_world.rotation.quat, - frame.rig_from_world.translation, + rig_from_world.rotation.quat, + rig_from_world.translation, point3D.xyz, camera.params, ], @@ -190,11 +191,21 @@ def add_image_to_problem( if num_observations > 0: self.camera_ids.add(image.camera_id) # to parameterize later - # Set pose parameterization - self.problem.set_manifold( - frame.rig_from_world.rotation.quat, - pyceres.EigenQuaternionManifold(), - ) + + # Set pose parameterization and apply gauge constraints + if frame.frame_id == 1: # first frame of the sequence + self.problem.set_parameter_block_constant(rig_from_world.rotation.quat) + self.problem.set_parameter_block_constant(rig_from_world.translation) + elif frame.frame_id == 2: # second frame of the sequence + self.problem.set_manifold( + rig_from_world.translation, + pyceres.SubsetManifold(3, np.array([0])), + ) + else: + self.problem.set_manifold( + rig_from_world.rotation.quat, + pyceres.EigenQuaternionManifold(), + ) if optimize_cam_from_rig: self.problem.set_manifold( @@ -203,10 +214,10 @@ def add_image_to_problem( ) def parameterize_cameras(self, session: SingleSeqSession): - constant_camera = all( - not session.cam_options.optimize_focal_length, - not session.cam_options.optimize_principal_point, - not session.cam_options.optimize_extra_params, + constant_camera = not ( + session.cam_options.optimize_focal_length + or session.cam_options.optimize_principal_point + or session.cam_options.optimize_extra_params ) for camera_id in self.camera_ids: From b5eaee31e0f09bc6afedb8669378efa0562a6875 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 13:23:54 +0200 Subject: [PATCH 269/665] rm tree --- run_pipeline.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index 3cdabef..4a0df7c 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -147,9 +147,9 @@ def run_optimization( db_path = input / "database.db" assert db_path.exists(), f"Database path {db_path} does not exist in input reconstruction" + if optim_model.exists(): - optim_lamaria_recon = LamariaReconstruction.read(optim_model) - return optim_lamaria_recon + shutil.rmtree(optim_model) optim_model.mkdir(parents=True, exist_ok=True) db_dst = optim_model / "database.db" From 062a9dac1d991a255ff92cbca6b3ea67466ed38c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 13:24:08 +0200 Subject: [PATCH 270/665] vi opt --- run_pipeline.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index 4a0df7c..2faf1e6 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -232,11 +232,11 @@ def run_pipeline( ) # Visual-Inertial Optimization - vi_options = pipeline_options.get_vi_optimizer_options() + vi_options = options.vi_optimizer_options _ = run_optimization( vi_options, - tri_options.tri_model, - vi_options.optim.optim_model, + options.tri_model, + options.optim_model, ) if __name__ == "__main__": From c85f25e74ddc8ec68ccd4dfe052c99d8ba822feb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 13:29:01 +0200 Subject: [PATCH 271/665] argparser --- run_pipeline.py | 50 ++++++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 49 insertions(+), 1 deletion(-) diff --git a/run_pipeline.py b/run_pipeline.py index 2faf1e6..2feaed9 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -1,5 +1,6 @@ import pycolmap import shutil +import argparse from typing import Optional from pathlib import Path @@ -240,4 +241,51 @@ def run_pipeline( ) if __name__ == "__main__": - run_pipeline() + parser = argparse.ArgumentParser(description="Run full pipeline.") + parser.add_argument( + "--config", + type=str, + default="./defaults.yaml", + help="Path to the configuration YAML file.", + ) + parser.add_argument( + "--vrs", + type=str, + required=True, + help="Path to the input VRS file.", + ) + parser.add_argument( + "--output", + type=str, + required=True, + help="Path to the output directory.", + ) + parser.add_argument( + "--estimate", + type=str, + default=None, + help="Path to the input estimate file (if not using MPS).", + ) + parser.add_argument( + "--mps_folder", + type=str, + default=None, + help="Path to the input MPS folder (if using MPS).", + ) + args = parser.parse_args() + + # ensure either estimate or mps_folder is provided + if args.estimate is None and args.mps_folder is None: + parser.error("Either --estimate or --mps_folder must be provided.") + if args.estimate is not None and args.mps_folder is not None: + parser.error("Only one of --estimate or --mps_folder should be provided.") + + options = PipelineOptions() + options.load(args.config) + run_pipeline( + options, + Path(args.vrs), + Path(args.output), + estimate=Path(args.estimate) if args.estimate else None, + mps_folder=Path(args.mps_folder) if args.mps_folder else None, + ) From 910250e320b46c30b71be7c41535fa6e1eeb5f52 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 13:44:39 +0200 Subject: [PATCH 272/665] relaxing tri thresholds --- lamaria/rig/optim/triangulation.py | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index eba4820..487c3b6 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -16,6 +16,21 @@ from ...config.options import TriangulatorOptions +def set_colmap_triangulation_options( + options: TriangulatorOptions, +) -> pycolmap.IncrementalPipelineOptions: + + colmap_options = pycolmap.IncrementalPipelineOptions() + colmap_options.triangulation.merge_max_reproj_error = options.merge_max_reproj_error + colmap_options.triangulation.complete_max_reproj_error = options.complete_max_reproj_error + colmap_options.triangulation.min_angle = options.min_angle + + colmap_options.mapper.filter_max_reproj_error = options.filter_max_reproj_error + colmap_options.mapper.filter_min_tri_angle = options.filter_min_tri_angle + + return colmap_options + + def pairs_from_frames(recon: pycolmap.Reconstruction): frame_pairs = set() by_index = defaultdict(list) @@ -102,6 +117,9 @@ def run( export_dir=hloc_dir, ) + colmap_opts = set_colmap_triangulation_options(options) + logger.info("COLMAP options: %s", colmap_opts) + _ = triangulation.main( sfm_dir=triangulated_model_path, reference_model=reference_model, @@ -109,6 +127,7 @@ def run( pairs=pairs_path, features=features_path, matches=matches_path, + mapper_options=colmap_opts, ) return triangulated_model_path \ No newline at end of file From bdc66ac892969dded08f1cc09bc448282b61872d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 14:22:21 +0200 Subject: [PATCH 273/665] print ingo --- lamaria/rig/optim/triangulation.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/rig/optim/triangulation.py index 487c3b6..fac9efa 100644 --- a/lamaria/rig/optim/triangulation.py +++ b/lamaria/rig/optim/triangulation.py @@ -118,7 +118,6 @@ def run( ) colmap_opts = set_colmap_triangulation_options(options) - logger.info("COLMAP options: %s", colmap_opts) _ = triangulation.main( sfm_dir=triangulated_model_path, From 41de54fad4269178fb586dc6e54d838671c47d12 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 14:48:20 +0200 Subject: [PATCH 274/665] gen --- lamaria/utils/general.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 047693e..a1b9c53 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -1,7 +1,7 @@ import os import pycolmap from pathlib import Path -from typing import List, Tuple +from typing import List, Tuple, Dict import shutil from bisect import bisect_left from typing import List @@ -128,8 +128,11 @@ def extract_images_from_vrs( logger.info("Done!") -def get_image_names_to_ids(reconstruction_dir: str): - recon = pycolmap.Reconstruction(reconstruction_dir) +def get_image_names_to_ids( + reconstruction_path: Path +) -> Dict[str, int]: + + recon = pycolmap.Reconstruction(reconstruction_path) image_names_to_ids = {} for image_id in recon.images.keys(): From b9f51f4f8fbe6fc8c01be4935545f05185e13cea Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 14:49:42 +0200 Subject: [PATCH 275/665] cp --- lamaria/utils/control_point.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index f8e3602..3473428 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -1,5 +1,6 @@ import json import os +from pathlib import Path import matplotlib.pyplot as plt import numpy as np @@ -111,13 +112,13 @@ def plot_ratio_of_inliers(control_points: Dict, save_folder: str): def run_control_point_triangulation_from_json( - reconstruction_dir: str, - cp_json_file: str, - control_points: Dict, -): - rec = pycolmap.Reconstruction(reconstruction_dir) + reconstruction_path: Path, + cp_json_file: Path, + control_points: Dict, # edits control_points in place +) -> None: + rec = pycolmap.Reconstruction(reconstruction_path) - image_names_to_ids = get_image_names_to_ids(reconstruction_dir=reconstruction_dir) + image_names_to_ids = get_image_names_to_ids(reconstruction_path=reconstruction_path) with open(cp_json_file, "r") as file: data = json.load(file) From 462286037f721fa0ebeab5f50bd6f8eadad189d9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 14:50:55 +0200 Subject: [PATCH 276/665] ss --- lamaria/eval/sparse_evaluation.py | 17 ++++++++--------- 1 file changed, 8 insertions(+), 9 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 1e3f1d3..397e8cd 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -19,22 +19,21 @@ def run_baseline_evaluation( + reconstruction_path: Path, cp_json_file: str, - sequence_eval_folder: Path, + output_path: Path, cp_reproj_std=1.0, ): - - reconstruction_dir = sequence_eval_folder / "reconstruction" - aligned_transformed_folder = sequence_eval_folder / "aligned_transformed" + aligned_transformed_folder = output_path / "aligned_transformed" aligned_transformed_folder.mkdir(parents=True, exist_ok=True) control_points = construct_control_points_from_json(cp_json_file) assert control_points is not None, "Control points could not be constructed from JSON" run_control_point_triangulation_from_json( - reconstruction_dir=reconstruction_dir, - cp_json_file=cp_json_file, - control_points=control_points, + reconstruction_path, + cp_json_file, + control_points, ) triangulated_cp_alignment, topo_cp_alignment = ( @@ -63,7 +62,7 @@ def run_baseline_evaluation( cp_reproj_std, ) - reconstruction = pycolmap.Reconstruction(reconstruction_dir) + reconstruction = pycolmap.Reconstruction(reconstruction_path) problem, solver_options, summary = get_problem_for_sparse_alignment( reconstruction, variables @@ -105,7 +104,7 @@ def run_baseline_evaluation( output_data["full_alignment"]["error_3d"][tag_id] = error3d - recon = pycolmap.Reconstruction(reconstruction_dir) + recon = pycolmap.Reconstruction(reconstruction) recon.transform(output_data["full_alignment"]["sim3"]) recon.write(aligned_transformed_folder) From cd4a443180519ff41af9fcb0d8c4a3d4712f6ded Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 14:51:51 +0200 Subject: [PATCH 277/665] ss --- lamaria/eval/sparse_evaluation.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 397e8cd..4efc6bd 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -24,6 +24,9 @@ def run_baseline_evaluation( output_path: Path, cp_reproj_std=1.0, ): + + output_path.mkdir(parents=True, exist_ok=True) + aligned_transformed_folder = output_path / "aligned_transformed" aligned_transformed_folder.mkdir(parents=True, exist_ok=True) @@ -115,6 +118,6 @@ def run_baseline_evaluation( output_data["control_points"][tag_id]["geo_id"] = cp["control_point"] output_data["control_points"][tag_id]["topo"] = cp["topo"] - np.save(os.path.join(sequence_eval_folder, "sparse_evaluation.npy"), output_data) + np.save(os.path.join(output_path, "sparse_evaluation.npy"), output_data) return (True, "Sparse evaluation completed successfully") \ No newline at end of file From 3d740dc4e0a212063b12b3e025f2f1266c98c688 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 14:56:30 +0200 Subject: [PATCH 278/665] defs --- defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/defaults.yaml b/defaults.yaml index 90dc2fc..38f8b4e 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -28,7 +28,7 @@ triangulation: optimization: general: - use_callback: true + use_callback: false max_num_iterations: 10 normalize_reconstruction: false From 8205a70b2ceabfce4c750240c7fba3495509d231 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 15:05:52 +0200 Subject: [PATCH 279/665] sparse eval script --- lamaria/eval/sparse_evaluation.py | 47 +++++++++++++++++++++++++++++-- 1 file changed, 45 insertions(+), 2 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 4efc6bd..634cc7c 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -1,11 +1,14 @@ import copy import os +import argparse from pathlib import Path import numpy as np import pyceres import pycolmap +from .. import logger + from ..utils.control_point import ( construct_control_points_from_json, get_cps_for_initial_alignment, @@ -20,7 +23,7 @@ def run_baseline_evaluation( reconstruction_path: Path, - cp_json_file: str, + cp_json_file: Path, output_path: Path, cp_reproj_std=1.0, ): @@ -120,4 +123,44 @@ def run_baseline_evaluation( np.save(os.path.join(output_path, "sparse_evaluation.npy"), output_data) - return (True, "Sparse evaluation completed successfully") \ No newline at end of file + return (True, "Sparse evaluation completed successfully") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description="Run baseline sparse evaluation" + ) + parser.add_argument( + "--reconstruction_path", + type=str, + required=True, + help="Path to the reconstruction folder", + ) + parser.add_argument( + "--cp_json_file", + type=str, + required=True, + help="Path to the sparse GT JSON file", + ) + parser.add_argument( + "--output_path", + type=str, + required=True, + help="Path to the output folder", + ) + parser.add_argument( + "--cp_reproj_std", + type=float, + default=1.0, + help="Control point reprojection standard deviation", + ) + args = parser.parse_args() + + state, msg = run_baseline_evaluation( + Path(args.reconstruction_path), + Path(args.cp_json_file), + Path(args.output_path), + args.cp_reproj_std, + ) + + logger.info(f"Evaluation completed? {state}. Message: {msg}") From 4c734caee6c95dfa5e2657b52c9a8bdf12def47d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 17:47:09 +0200 Subject: [PATCH 280/665] vi opt --- lamaria/rig/optim/vi_optimization.py | 79 ++++++++++++++++++---------- lamaria/utils/control_point.py | 9 +++- run_pipeline.py | 13 +++-- 3 files changed, 67 insertions(+), 34 deletions(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 6558c0f..554b462 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -1,35 +1,58 @@ import pycolmap from pathlib import Path -from ..lamaria_reconstruction import LamariaReconstruction from .session import SingleSeqSession from .iterative_global_ba import IterativeRefinement +from ...config.options import VIOptimizerOptions, TriangulatorOptions class VIOptimizer: """Main Visual-Inertial Optimizer""" - def __init__(self, session: SingleSeqSession): + def __init__( + self, + vi_options: VIOptimizerOptions, + triangulator_options: TriangulatorOptions, + session: SingleSeqSession + ): + self.vi_options = vi_options + self.triangulator_options = triangulator_options self.session = session - def optimize(self, database_path: Path): - """Run the complete VI optimization pipeline""" - - # Setup mapper + @staticmethod + def optimize( + vi_options: VIOptimizerOptions, + triangulator_options: TriangulatorOptions, + session: SingleSeqSession, + database_path: Path + ) -> pycolmap.Reconstruction: + """Runs the complete VI optimization pipeline""" + + optimizer = VIOptimizer( + vi_options, + triangulator_options, + session + ) + + optimized_recon = optimizer.process(database_path) + + return optimized_recon + + def process(self, database_path: Path) -> pycolmap.Reconstruction: + """Optimize the reconstruction using VI optimization""" mapper = self._setup_incremental_mapper(database_path) pipeline_options = self._get_incremental_pipeline_options() - - # Run iterative refinement + refinement_strategy = IterativeRefinement(self.session) refinement_strategy.run( - mapper, pipeline_options, + mapper ) - + return mapper.reconstruction def _setup_incremental_mapper(self, database_path: Path): - """Setup the incremental mapper""" + """Setup the COLMAP incremental mapper""" database = pycolmap.Database.open(database_path) image_names = [self.session.data.reconstruction.images[image_id].name for image_id in self.session.data.reconstruction.reg_image_ids()] @@ -41,23 +64,25 @@ def _setup_incremental_mapper(self, database_path: Path): return mapper def _get_incremental_pipeline_options(self): - """Get incremental pipeline options""" + """Get incremental pipeline options for COLMAP bundle adjustment""" pipeline_options = pycolmap.IncrementalPipelineOptions() pipeline_options.fix_existing_frames = False - return pipeline_options - - -def create_vi_optimizer(session: SingleSeqSession) -> VIOptimizer: - """Factory function to create VI optimizer""" - return VIOptimizer(session) + + if not self.vi_options.cam.optimize_cam_from_rig: + pipeline_options.ba_refine_sensor_from_rig = False + if not self.vi_options.cam.optimize_focal_length: + pipeline_options.ba_refine_focal_length = False + if not self.vi_options.cam.optimize_principal_point: + pipeline_options.ba_refine_principal_point = False + if not self.vi_options.cam.optimize_extra_params: + pipeline_options.ba_refine_extra_params = False -def run( - session: SingleSeqSession, - database_path: Path, -) -> pycolmap.Reconstruction: - - """Run VI optimization with given session and database""" - optimizer = create_vi_optimizer(session) - optimized_recon = optimizer.optimize(database_path) + # Setting up relaxed triangulation + pipeline_options.triangulation.merge_max_reproj_error = self.triangulator_options.merge_max_reproj_error + pipeline_options.triangulation.complete_max_reproj_error = self.triangulator_options.complete_max_reproj_error + pipeline_options.triangulation.min_angle = self.triangulator_options.min_angle - return optimized_recon \ No newline at end of file + pipeline_options.mapper.filter_max_reproj_error = self.triangulator_options.filter_max_reproj_error + pipeline_options.mapper.filter_min_tri_angle = self.triangulator_options.filter_min_tri_angle + + return pipeline_options \ No newline at end of file diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 3473428..78be0ac 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -15,8 +15,13 @@ def construct_control_points_from_json( - cp_json_file: str, -): + cp_json_file: Path, +) -> Dict: + """Construct control points dict from JSON file + Args: + cp_json_file (Path): Path to the sparse GT JSON file + """ + cp_data = json.load(open(cp_json_file, 'r')) control_points = {} for geo_id, data in cp_data["control_points"].items(): diff --git a/run_pipeline.py b/run_pipeline.py index 2feaed9..6fd15ce 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -9,7 +9,7 @@ from lamaria.rig.keyframing.keyframe_selection import KeyframeSelector from lamaria.rig.optim.triangulation import run as triangulate from lamaria.rig.optim.session import SingleSeqSession -from lamaria.rig.optim.vi_optimization import run as run_vi_optimization +from lamaria.rig.optim.vi_optimization import VIOptimizer from lamaria.config.pipeline import PipelineOptions from lamaria.config.options import ( EstimateToColmapOptions, @@ -139,7 +139,8 @@ def run_triangulation( def run_optimization( - options: VIOptimizerOptions, + vi_options: VIOptimizerOptions, + triangulator_options: TriangulatorOptions, input: Path, # path to LamariaReconstruction optim_model: Path, ) -> LamariaReconstruction: @@ -158,13 +159,15 @@ def run_optimization( init_lamaria_recon = LamariaReconstruction.read(input) session = SingleSeqSession( - options, + vi_options.imu, init_lamaria_recon, ) - optimized_recon = run_vi_optimization( + optimized_recon = VIOptimizer.optimize( + vi_options, + triangulator_options, session, - db_dst, + db_dst ) optim_lamaria_recon = LamariaReconstruction() From 990139376f52e7dc41ed7feb7a3ff741baa6204c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 17:47:50 +0200 Subject: [PATCH 281/665] sess --- lamaria/rig/optim/session.py | 20 ++++++-------------- 1 file changed, 6 insertions(+), 14 deletions(-) diff --git a/lamaria/rig/optim/session.py b/lamaria/rig/optim/session.py index 0f9621a..a066e81 100644 --- a/lamaria/rig/optim/session.py +++ b/lamaria/rig/optim/session.py @@ -6,33 +6,25 @@ load_imu_states, load_preintegrated_imu_measurements, ) -from ..config.options import VIOptimizerOptions +from ...config.options import OptIMUOptions from ..lamaria_reconstruction import LamariaReconstruction class SingleSeqSession: def __init__( self, - options: VIOptimizerOptions, + imu_options: OptIMUOptions, data: LamariaReconstruction, ): self.data = data - self._init_options(options) - self._init_imu_data() + self._init_imu_data(imu_options) - def _init_imu_data(self): + def _init_imu_data(self, imu_options): self.preintegrated_imu_measurements = \ load_preintegrated_imu_measurements( - self.imu_options, + imu_options, self.data ) self.imu_states = load_imu_states(self.data) self.imu_from_rig = pycolmap.Rigid3d() self.gravity = np.array([0.0, 0.0, -1.0]) - self.log_scale = np.array([0.0]) - - def _init_options(self, options: VIOptimizerOptions): - self.cam_options = options.cam - self.imu_options = options.imu - self.opt_options = options.optim - - + self.log_scale = np.array([0.0]) \ No newline at end of file From 8c204f918d8b83d1377df4622d4d8b3519c1464f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 17:50:56 +0200 Subject: [PATCH 282/665] vio --- lamaria/rig/optim/vi_optimization.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 554b462..402a156 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -77,7 +77,7 @@ def _get_incremental_pipeline_options(self): if not self.vi_options.cam.optimize_extra_params: pipeline_options.ba_refine_extra_params = False - # Setting up relaxed triangulation + # Setting up triangulation and mapper options pipeline_options.triangulation.merge_max_reproj_error = self.triangulator_options.merge_max_reproj_error pipeline_options.triangulation.complete_max_reproj_error = self.triangulator_options.complete_max_reproj_error pipeline_options.triangulation.min_angle = self.triangulator_options.min_angle From aaf4b53b1a59e07bb6b6f135c22e6df9647e633b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 17:51:25 +0200 Subject: [PATCH 283/665] fixes --- lamaria/utils/sparse_eval.py | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/lamaria/utils/sparse_eval.py b/lamaria/utils/sparse_eval.py index a6583ee..605db12 100644 --- a/lamaria/utils/sparse_eval.py +++ b/lamaria/utils/sparse_eval.py @@ -4,12 +4,11 @@ import pycolmap import pyceres import pycolmap.cost_functions -from pathlib import Path -from typing import Dict, List +from typing import Dict from lamaria import logger -def update_sim3d_scale(variables): +def update_sim3d_scale(variables: Dict): if "log_scale" not in variables: raise ValueError("log_scale not found in variables") @@ -101,9 +100,8 @@ def add_alignment_residuals( variables["log_scale"], ], ) - - logger.info(f"Added Point3dAlignmentCost and ReprojErrorCost \ - for {len(variables['control_points'])} control points") + + logger.info(f"Added Point3dAlignmentCost and ReprojErrorCost costs") problem.set_manifold( variables["sim3d"].rotation.quat, From f28181f5158b09463a0becdf346c66d9635299b9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 17:51:38 +0200 Subject: [PATCH 284/665] metrics --- lamaria/utils/metrics.py | 98 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 98 insertions(+) create mode 100644 lamaria/utils/metrics.py diff --git a/lamaria/utils/metrics.py b/lamaria/utils/metrics.py new file mode 100644 index 0000000..fb28275 --- /dev/null +++ b/lamaria/utils/metrics.py @@ -0,0 +1,98 @@ +from pathlib import Path +import numpy as np +import pycolmap +from scipy.interpolate import interp1d +from typing import List + + +def get_sim3_from_sparse_evaluation( + sparse_evaluation_npy: Path +) -> pycolmap.Sim3d: + data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() + sim3 = data_sparse["full_alignment"]["sim3"] + return sim3 + + +def get_all_tag_ids( + sparse_evaluation_npy: Path +) -> List[str]: + + data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() + tag_ids = sorted(list(data_sparse["control_points"].keys())) + return tag_ids + + +def calculate_2d_alignment_errors( + sparse_evaluation_npy: Path +) -> List[float]: + + data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() + tag_ids = get_all_tag_ids(sparse_evaluation_npy) + err_2d = [ + np.linalg.norm(data_sparse["full_alignment"]["error_3d"][i][:2]) + for i in tag_ids + ] + + return err_2d + + +def piecewise_linear_scoring(): + """ + Error Score + 0 - 0.05 m 20 + 0.05 - 0.20 m 18 + 0.20 - 0.50 m 15 + 0.50 - 1.00 m 12 + 1.00 - 2.00 m 8 + 2.00 - 5.00 m 4 + 5.00 - 10.00 m 0 + > 10.00 m 0 + """ + x_vals = [0.00, 0.05, 0.20, 0.50, 1.00, 2.00, 5.00, 10.00] + y_vals = [20, 20, 18, 15, 12, 8, 4, 0] + + scoring = interp1d( + x_vals, + y_vals, + kind="linear", + fill_value=(y_vals[0], 0), # left=20, right=0 + bounds_error=False, + ) + return scoring + + +def calculate_score_piecewise(errors): + if len(errors) == 0 or errors is None: + return 0.0 + + if any(e < 0 for e in errors): + raise ValueError("Norm error cannot be negative.") + + errors = np.nan_to_num(errors, nan=1000) # 1km error for NaNs + + scoring = piecewise_linear_scoring() + scores = scoring(errors) + score_sum = np.sum(scores) + max_score = 20 * len(errors) + + S_j = (score_sum / max_score) * 100 + return S_j + + +def calculate_score_from_alignment_data( + sparse_evaluation_npy: Path +) -> float: + + tag_ids = get_all_tag_ids(sparse_evaluation_npy) + err_2d = calculate_2d_alignment_errors(sparse_evaluation_npy) + + if len(err_2d) == 0: + raise ValueError("No valid control points found.") + + assert len(err_2d) == len( + tag_ids + ), "Mismatch in number of 2D CPs and errors." + + S_2d = calculate_score_piecewise(err_2d) + + return S_2d \ No newline at end of file From cae50574776ca9b78ba9e862a88f1efce92ea37f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 18:11:46 +0200 Subject: [PATCH 285/665] vi opt --- lamaria/rig/optim/vi_optimization.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 402a156..8a5104d 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -7,7 +7,7 @@ class VIOptimizer: - """Main Visual-Inertial Optimizer""" + """Main Visual-Inertial Optimizer Class""" def __init__( self, @@ -43,8 +43,9 @@ def process(self, database_path: Path) -> pycolmap.Reconstruction: mapper = self._setup_incremental_mapper(database_path) pipeline_options = self._get_incremental_pipeline_options() - refinement_strategy = IterativeRefinement(self.session) - refinement_strategy.run( + refinement = IterativeRefinement(self.session) + refinement.run( + self.vi_options, pipeline_options, mapper ) From b74577d9dbae7a63039c00eae7d1615e197ad8b9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 18:15:11 +0200 Subject: [PATCH 286/665] iterative global ba --- lamaria/rig/optim/iterative_global_ba.py | 87 ++++++++++++++---------- 1 file changed, 51 insertions(+), 36 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 90e65bb..2569488 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -7,20 +7,21 @@ from .session import SingleSeqSession from .residual_manager import IMUResidualManager from .callback import RefinementCallback +from ...config.options import VIOptimizerOptions def apply_constraints(problem, session: SingleSeqSession): """Apply rig-specific constraints to the problem""" # Fix the first rig pose frame_ids = sorted(session.data.reconstruction.frames.keys()) - first_frame = session.data.reconstruction.frames[frame_ids[0]] - problem.set_parameter_block_constant(first_frame.rig_from_world.rotation.quat) - problem.set_parameter_block_constant(first_frame.rig_from_world.translation) + first_frame_rfw = session.data.reconstruction.frames[frame_ids[0]].rig_from_world + problem.set_parameter_block_constant(first_frame_rfw.rotation.quat) + problem.set_parameter_block_constant(first_frame_rfw.translation) # Fix 1 DoF translation of the second rig - second_frame = session.data.reconstruction.frames[frame_ids[1]] + second_frame_rfw = session.data.reconstruction.frames[frame_ids[1]].rig_from_world problem.set_manifold( - second_frame.rig_from_world.translation, + second_frame_rfw.translation, pyceres.SubsetManifold(3, np.array([0])), ) return problem @@ -39,30 +40,38 @@ def _init_callback(self): return callback - def solve(self, ba_options, ba_config): + def solve( + self, + vi_options: VIOptimizerOptions, + ba_options: pycolmap.BundleAdjustmentOptions, + ba_config: pycolmap.BundleAdjustmentConfig, + ): """Solve VI bundle adjustment problem""" bundle_adjuster = pycolmap.create_default_bundle_adjuster( - ba_options, ba_config, self.session.data.reconstruction + ba_options, + ba_config, + self.session.data.reconstruction ) imu_manager = IMUResidualManager(self.session) problem = bundle_adjuster.problem solver_options = ba_options.create_solver_options( - ba_config, problem + ba_config, + problem ) pyceres_solver_options = pyceres.SolverOptions(solver_options) - problem = imu_manager.add_residuals(problem) + # problem = imu_manager.add_residuals(problem) # Setup solver - if self.session.opt_options.use_callback: + if vi_options.optim.use_callback: callback = self._init_callback() pyceres_solver_options.callbacks = [callback] - pyceres_solver_options.minimizer_progress_to_stdout = True - pyceres_solver_options.update_state_every_iteration = True - pyceres_solver_options.max_num_iterations = self.session.opt_options.max_num_iterations + pyceres_solver_options.minimizer_progress_to_stdout = vi_options.optim.minimizer_progress_to_stdout + pyceres_solver_options.update_state_every_iteration = vi_options.optim.update_state_every_iteration + pyceres_solver_options.max_num_iterations = vi_options.optim.max_num_iterations # Solve summary = pyceres.SolverSummary() @@ -74,12 +83,17 @@ def solve(self, ba_options, ba_config): class GlobalBundleAdjustment: - """Strategy for global bundle adjustment with VI integration""" + """Global bundle adjustment with visual-inertial constraints""" def __init__(self, session: SingleSeqSession): self.session = session - def adjust(self, mapper, pipeline_options): + def adjust( + self, + vi_options: VIOptimizerOptions, + pipeline_options: pycolmap.IncrementalPipelineOptions, + mapper: pycolmap.IncrementalMapper, + ): """Perform global bundle adjustment""" reconstruction = mapper.reconstruction assert reconstruction is not None @@ -88,12 +102,15 @@ def adjust(self, mapper, pipeline_options): if len(reg_image_ids) < 2: logger.warning("At least two images must be registered for global bundle-adjustment") - ba_options = self._configure_ba_options(pipeline_options, len(reg_image_ids)) + ba_options = self._configure_ba_options( + pipeline_options, + len(reg_image_ids) + ) - # Avoid degeneracies + # Avoid negative depths mapper.observation_manager.filter_observations_with_negative_depth() - # Configure bundle adjustment + # Setting up bundle adjustment configuration ba_config = pycolmap.BundleAdjustmentConfig() for frame_id in reconstruction.reg_frame_ids(): frame = reconstruction.frame(frame_id) @@ -102,11 +119,10 @@ def adjust(self, mapper, pipeline_options): continue ba_config.add_image(data_id.id) - ba_config.fix_gauge(pycolmap.BundleAdjustmentGauge.TWO_CAMS_FROM_WORLD) - # Run bundle adjustment vi_bundle_adjuster = VIBundleAdjuster(self.session) _, _ = vi_bundle_adjuster.solve( + vi_options, ba_options, ba_config ) @@ -115,8 +131,7 @@ def _configure_ba_options(self, pipeline_options, num_reg_images): """Configure bundle adjustment options based on number of registered images""" ba_options = pipeline_options.get_global_bundle_adjustment() ba_options.print_summary = True - ba_options.refine_focal_length = True - ba_options.refine_extra_params = True + ba_options.refine_rig_from_world = True # Refine rig poses # Use stricter convergence criteria for first registered images if num_reg_images < 10: @@ -135,11 +150,16 @@ class IterativeRefinement: def __init__(self, session: SingleSeqSession): self.session = session - def run(self, mapper, pipeline_options): - """Run iterative global refinement""" + def run( + self, + vi_options: VIOptimizerOptions, + pipeline_options: pycolmap.IncrementalPipelineOptions, + mapper: pycolmap.IncrementalMapper, + ): + """Run iterative global refinement of the reconstruction""" reconstruction = mapper.reconstruction - - # Initial triangulation + + # Configure triangulation options tri_options = pipeline_options.get_triangulation() mapper.complete_and_merge_tracks(tri_options) num_retriangulated_observations = mapper.retriangulate(tri_options) @@ -148,7 +168,7 @@ def run(self, mapper, pipeline_options): ) # Configure mapper options - mapper_options = self._configure_mapper_options(pipeline_options) + mapper_options = pipeline_options.get_mapper() global_ba_strategy = GlobalBundleAdjustment(self.session) # Iterative refinement @@ -156,14 +176,14 @@ def run(self, mapper, pipeline_options): num_observations = reconstruction.compute_num_observations() global_ba_strategy.adjust( - mapper, + vi_options, pipeline_options, + mapper, ) - if self.session.opt_options.normalize_reconstruction: + if vi_options.optim.normalize_reconstruction: reconstruction.normalize() - # Check convergence num_changed_observations = mapper.complete_and_merge_tracks(tri_options) num_changed_observations += mapper.filter_points(mapper_options) changed = (num_changed_observations / num_observations @@ -171,9 +191,4 @@ def run(self, mapper, pipeline_options): logging.verbose(1, f"=> Changed observations: {changed:.6f}") if changed < pipeline_options.ba_global_max_refinement_change: - break - - def _configure_mapper_options(self, pipeline_options): - """Configure mapper options""" - mapper_options = pipeline_options.get_mapper() - return mapper_options \ No newline at end of file + break \ No newline at end of file From 2d9b0d92fc31b58eff4e56ad2794ec384191ca93 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 18:15:21 +0200 Subject: [PATCH 287/665] ceres defs to defs --- defaults.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/defaults.yaml b/defaults.yaml index 38f8b4e..28668fb 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -31,6 +31,8 @@ optimization: use_callback: false max_num_iterations: 10 normalize_reconstruction: false + minimizer_progress_to_stdout: true + update_state_every_iteration: true cam: feature_std: 1.0 From 34033a48337081b9b35a0e99d15f705f0a74aabd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 18:20:10 +0200 Subject: [PATCH 288/665] static method --- lamaria/rig/optim/iterative_global_ba.py | 31 ++++++++++++++++++------ 1 file changed, 24 insertions(+), 7 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 2569488..1037a62 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -28,17 +28,27 @@ def apply_constraints(problem, session: SingleSeqSession): class VIBundleAdjuster: - """Visual-Inertial Bundle Adjuster that combines visual and IMU residuals""" + """Visual-Inertial Bundle Adjuster Class that combines visual and IMU residuals""" def __init__(self, session: SingleSeqSession): self.session = session - def _init_callback(self): - frame_ids = sorted(self.session.data.reconstruction.frames.keys()) - poses = list(self.session.data.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) - callback = RefinementCallback(poses) - - return callback + @staticmethod + def run_vi_bundle_adjustment( + vi_options: VIOptimizerOptions, + ba_options: pycolmap.BundleAdjustmentOptions, + ba_config: pycolmap.BundleAdjustmentConfig, + session: SingleSeqSession + ): + """Run visual-inertial bundle adjustment""" + vi_bundle_adjuster = VIBundleAdjuster(session) + summary, problem = vi_bundle_adjuster.solve( + vi_options, + ba_options, + ba_config + ) + + return summary, problem def solve( self, @@ -79,7 +89,14 @@ def solve( print(summary.BriefReport()) return summary, problem + + def _init_callback(self): + """Initialize the refinement callback to check pose changes""" + frame_ids = sorted(self.session.data.reconstruction.frames.keys()) + poses = list(self.session.data.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) + callback = RefinementCallback(poses) + return callback class GlobalBundleAdjustment: From 479c7ab0ac7ce25e0f1511f926f8b93737f754cd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:21:18 +0200 Subject: [PATCH 289/665] vi opt --- lamaria/rig/optim/vi_optimization.py | 40 +++++++++++++++------------- 1 file changed, 21 insertions(+), 19 deletions(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 8a5104d..30f9700 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -13,44 +13,46 @@ def __init__( self, vi_options: VIOptimizerOptions, triangulator_options: TriangulatorOptions, - session: SingleSeqSession + session: SingleSeqSession, ): self.vi_options = vi_options self.triangulator_options = triangulator_options self.session = session - @staticmethod + @classmethod def optimize( + cls, vi_options: VIOptimizerOptions, triangulator_options: TriangulatorOptions, session: SingleSeqSession, - database_path: Path + database_path: Path, ) -> pycolmap.Reconstruction: - """Runs the complete VI optimization pipeline""" - - optimizer = VIOptimizer( - vi_options, - triangulator_options, - session - ) - - optimized_recon = optimizer.process(database_path) - - return optimized_recon + """Entry point for running full VI optimization""" + return cls(vi_options, triangulator_options, session).process(database_path) - def process(self, database_path: Path) -> pycolmap.Reconstruction: + def process( + self, + database_path: Path + ) -> pycolmap.Reconstruction: """Optimize the reconstruction using VI optimization""" + + if not database_path.exists(): + raise FileNotFoundError(f"Database not found: {database_path}") + + if not self.session.data.reconstruction.reg_image_ids(): + raise ValueError("Reconstruction has no registered images.") + mapper = self._setup_incremental_mapper(database_path) pipeline_options = self._get_incremental_pipeline_options() - refinement = IterativeRefinement(self.session) - refinement.run( + reconstruction = IterativeRefinement.run( self.vi_options, pipeline_options, - mapper + mapper, + self.session ) - return mapper.reconstruction + return reconstruction def _setup_incremental_mapper(self, database_path: Path): """Setup the COLMAP incremental mapper""" From 1efed6e7c99f8307b13a8f38ed877ac888652dbd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:23:14 +0200 Subject: [PATCH 290/665] class methods --- lamaria/rig/optim/iterative_global_ba.py | 80 +++++++++++++++++------- 1 file changed, 58 insertions(+), 22 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 1037a62..0b31662 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -11,7 +11,7 @@ def apply_constraints(problem, session: SingleSeqSession): - """Apply rig-specific constraints to the problem""" + """Apply rig constraints to the problem for fixing gauge freedom.""" # Fix the first rig pose frame_ids = sorted(session.data.reconstruction.frames.keys()) first_frame_rfw = session.data.reconstruction.frames[frame_ids[0]].rig_from_world @@ -28,26 +28,28 @@ def apply_constraints(problem, session: SingleSeqSession): class VIBundleAdjuster: - """Visual-Inertial Bundle Adjuster Class that combines visual and IMU residuals""" + """Visual-Inertial Bundle Adjuster class that + adds visual and IMU residuals to the + optimization problem.""" def __init__(self, session: SingleSeqSession): self.session = session - @staticmethod - def run_vi_bundle_adjustment( + @classmethod + def run( + cls, vi_options: VIOptimizerOptions, ba_options: pycolmap.BundleAdjustmentOptions, ba_config: pycolmap.BundleAdjustmentConfig, session: SingleSeqSession ): - """Run visual-inertial bundle adjustment""" - vi_bundle_adjuster = VIBundleAdjuster(session) - summary, problem = vi_bundle_adjuster.solve( + """Entry point for running VI bundle adjustment.""" + summary, problem = cls(session).solve( vi_options, ba_options, ba_config ) - + return summary, problem def solve( @@ -56,7 +58,7 @@ def solve( ba_options: pycolmap.BundleAdjustmentOptions, ba_config: pycolmap.BundleAdjustmentConfig, ): - """Solve VI bundle adjustment problem""" + """Solves the VI bundle adjustment problem.""" bundle_adjuster = pycolmap.create_default_bundle_adjuster( ba_options, ba_config, @@ -73,6 +75,7 @@ def solve( pyceres_solver_options = pyceres.SolverOptions(solver_options) # problem = imu_manager.add_residuals(problem) + # problem = apply_constraints(problem, self.session) # Setup solver if vi_options.optim.use_callback: @@ -91,7 +94,7 @@ def solve( return summary, problem def _init_callback(self): - """Initialize the refinement callback to check pose changes""" + """Initialize the refinement callback to check pose changes.""" frame_ids = sorted(self.session.data.reconstruction.frames.keys()) poses = list(self.session.data.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) callback = RefinementCallback(poses) @@ -100,18 +103,32 @@ def _init_callback(self): class GlobalBundleAdjustment: - """Global bundle adjustment with visual-inertial constraints""" + """Global bundle adjustment with visual-inertial constraints.""" def __init__(self, session: SingleSeqSession): self.session = session + @classmethod + def run( + cls, + vi_options: VIOptimizerOptions, + pipeline_options: pycolmap.IncrementalPipelineOptions, + mapper: pycolmap.IncrementalMapper, + session: SingleSeqSession, + ): + """Entry point for running global bundle adjustment.""" + return cls(session).adjust( + vi_options, + pipeline_options, + mapper, + ) + def adjust( self, vi_options: VIOptimizerOptions, pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, ): - """Perform global bundle adjustment""" reconstruction = mapper.reconstruction assert reconstruction is not None @@ -137,12 +154,14 @@ def adjust( ba_config.add_image(data_id.id) # Run bundle adjustment - vi_bundle_adjuster = VIBundleAdjuster(self.session) - _, _ = vi_bundle_adjuster.solve( + _, _ = VIBundleAdjuster.run( vi_options, ba_options, - ba_config + ba_config, + self.session ) + + return reconstruction def _configure_ba_options(self, pipeline_options, num_reg_images): """Configure bundle adjustment options based on number of registered images""" @@ -162,18 +181,33 @@ def _configure_ba_options(self, pipeline_options, num_reg_images): class IterativeRefinement: - """Strategy for iterative global refinement""" + """Iterative global refinement + through repeated global bundle adjustments.""" def __init__(self, session: SingleSeqSession): self.session = session - + + @classmethod def run( + cls, + vi_options: VIOptimizerOptions, + pipeline_options: pycolmap.IncrementalPipelineOptions, + mapper: pycolmap.IncrementalMapper, + session: SingleSeqSession, + ): + """Entry point for running iterative refinement""" + return cls(session).refine( + vi_options, + pipeline_options, + mapper, + ) + + def refine( self, vi_options: VIOptimizerOptions, pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, ): - """Run iterative global refinement of the reconstruction""" reconstruction = mapper.reconstruction # Configure triangulation options @@ -186,18 +220,18 @@ def run( # Configure mapper options mapper_options = pipeline_options.get_mapper() - global_ba_strategy = GlobalBundleAdjustment(self.session) # Iterative refinement for i in range(pipeline_options.ba_global_max_refinements): num_observations = reconstruction.compute_num_observations() - global_ba_strategy.adjust( + reconstruction = GlobalBundleAdjustment.run( vi_options, pipeline_options, mapper, + self.session ) - + if vi_options.optim.normalize_reconstruction: reconstruction.normalize() @@ -208,4 +242,6 @@ def run( logging.verbose(1, f"=> Changed observations: {changed:.6f}") if changed < pipeline_options.ba_global_max_refinement_change: - break \ No newline at end of file + break + + return reconstruction \ No newline at end of file From 4dacd0b6ec2d06b0dda64a40b210b889cd263340 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:23:54 +0200 Subject: [PATCH 291/665] f --- lamaria/rig/keyframing/keyframe_selection.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index e1d010c..2449b23 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -201,7 +201,6 @@ def _build_online_keyframed_reconstruction(self): for img in images_to_add: self.keyframed_data.reconstruction.add_image(img) - # -------- public API -------- def run_keyframing(self) -> LamariaReconstruction: """ Function to run keyframing on lamaria reconstruction.""" self._select_keyframes() From 7836f18adb97d55841c028e11c682193d0f6b6ab Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:24:44 +0200 Subject: [PATCH 292/665] fix --- lamaria/rig/keyframing/keyframe_selection.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 2449b23..020cd7c 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -36,7 +36,7 @@ def run( original_image_dir: Path, keyframes_dir: Path, ) -> LamariaReconstruction: - """ Static method to run keyframing and copy images to keyframes directory.""" + """ Entry point to run keyframing and copy keyframes into keyframe directory.""" selector = KeyframeSelector(options, data) kf_recon = selector.run_keyframing() From 8c0e5174b74bea6f66f3eb862f4a8ee1b30954ae Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:26:14 +0200 Subject: [PATCH 293/665] f --- lamaria/rig/keyframing/to_colmap.py | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index ce4aae0..f7aaf4f 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -61,24 +61,23 @@ def __init__(self, options: EstimateToColmapOptions): self._per_frame_data: Dict[int, PerFrameData] = {} - @staticmethod + @classmethod def convert( + cls, options: EstimateToColmapOptions, vrs: Path, images: Path, estimate: Optional[Path] = None, mps_folder: Optional[Path] = None, ) -> LamariaReconstruction: - """Static method to run the full pipeline.""" - converter = EstimateToColmap(options) - return converter.process( + """Entry point to run estimate/MPS to colmap conversion.""" + return cls(options).process( vrs, images, estimate, mps_folder ) - # -------- public API -------- def process( self, vrs: Path, @@ -86,7 +85,7 @@ def process( estimate: Optional[Path] = None, mps_folder: Optional[Path] = None, ) -> LamariaReconstruction: - """Main runner.""" + self._init_data(vrs, images, estimate, mps_folder) if self.options.mps.use_online_calibration and self.options.mps.use_mps: From 43e79064dd53324e1fd026321469a0a5cbdaa00f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:31:09 +0200 Subject: [PATCH 294/665] cleanup and comments --- .../eval/create_empty_recon_from_estimate.py | 33 ++++++++++++++----- 1 file changed, 25 insertions(+), 8 deletions(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index 873a9f6..9f09436 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -6,27 +6,44 @@ import pycolmap from tqdm import tqdm -from ..utils.general import ( +from ..utils.camera import ( LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL, add_cameras_to_reconstruction, +) +from ..utils.general import ( find_closest_timestamp, delete_files_in_folder, - get_t_imu_camera_from_json, +) +from ..utils.estimate import ( round_ns, ) +from ..utils.transformation import ( + get_t_imu_camera_from_json, +) def add_images_to_reconstruction( reconstruction: pycolmap.Reconstruction, - pred_estimate_file, - cp_json_file, - device_calibration_json, - slam_input_imu, + pred_estimate_file: Path, + cp_json_file: Path, + device_calibration_json: Path, + slam_input_imu: int = 1, ): + """Add images to an existing empty reconstruction from a pose estimate file. + The pose estimate file is assumed to be in the format: + timestamp(ns) tx ty tz q_x q_y q_z q_w + + Args: + reconstruction (pycolmap.Reconstruction): The reconstruction to add images to. + pred_estimate_file (Path): Path to the pose estimate file. + cp_json_file (Path): Path to the sparse GT json file. + device_calibration_json (Path): Path to the Aria device calibration json file. + slam_input_imu (int, optional): If 1, the poses in the estimate file are IMU poses. + If 0, the poses are left camera poses (monocular-cam0). + Defaults to 1. + """ pose_data = [] - # ESTIMATE FORMAT: - # timestamp(ns) tx ty tz q_x q_y q_z q_w with open(pred_estimate_file, "r") as f: lines = f.readlines() From a700b8eefbf19d2b714b2f8073a49c8e8b3bb999 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:35:49 +0200 Subject: [PATCH 295/665] camera --- lamaria/utils/camera.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py index 0bcd9ca..fc85a59 100644 --- a/lamaria/utils/camera.py +++ b/lamaria/utils/camera.py @@ -24,7 +24,12 @@ def add_cameras_to_reconstruction( calibration_file: Path, ) -> None: """ Add Aria cameras to COLMAP reconstruction from calibration json file found on website: - https://lamaria.ethz.ch/slam_datasets""" + https://lamaria.ethz.ch/slam_datasets + + Args: + reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction to which cameras will be added + calibration_file (Path): Path to the Aria calibration json file + """ for i, (key, _) in enumerate(ARIA_CAMERAS): cam = camera_colmap_from_json( From 76e101416277bdd4f9203c52f23f39cbdabb39d4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:36:21 +0200 Subject: [PATCH 296/665] adding details --- .../eval/create_empty_recon_from_estimate.py | 55 ++++++++++--------- 1 file changed, 28 insertions(+), 27 deletions(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index 9f09436..d6361ca 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -25,26 +25,14 @@ def add_images_to_reconstruction( reconstruction: pycolmap.Reconstruction, - pred_estimate_file: Path, + estimate_file: Path, cp_json_file: Path, device_calibration_json: Path, slam_input_imu: int = 1, ): - """Add images to an existing empty reconstruction from a pose estimate file. - The pose estimate file is assumed to be in the format: - timestamp(ns) tx ty tz q_x q_y q_z q_w - - Args: - reconstruction (pycolmap.Reconstruction): The reconstruction to add images to. - pred_estimate_file (Path): Path to the pose estimate file. - cp_json_file (Path): Path to the sparse GT json file. - device_calibration_json (Path): Path to the Aria device calibration json file. - slam_input_imu (int, optional): If 1, the poses in the estimate file are IMU poses. - If 0, the poses are left camera poses (monocular-cam0). - Defaults to 1. - """ + """Add images to an existing empty reconstruction from a pose estimate file.""" pose_data = [] - with open(pred_estimate_file, "r") as f: + with open(estimate_file, "r") as f: lines = f.readlines() if len(lines) == 0: @@ -140,28 +128,41 @@ def add_images_to_reconstruction( def create_baseline_reconstruction( - pred_estimate_file: Path, - eval_folder: Path, + estimate_file: Path, cp_json_file: Path, device_calibration_json: Path, - slam_input_imu: int, + output_path: Path, + slam_input_imu: int = 1, ): - recon_path = eval_folder / "reconstruction" + """Create a baseline reconstruction from a pose estimate file. + The pose estimate file is assumed to be in the format: + + timestamp(ns) tx ty tz q_x q_y q_z q_w + + Args: + estimate_file (Path): Path to the pose estimate file. + cp_json_file (Path): Path to the sparse GT json file. + device_calibration_json (Path): Path to the Aria device calibration json file. + output_path (Path): Path to the output folder where the reconstruction will be saved. + slam_input_imu (int, optional): If 1, the poses in the estimate file are IMU poses. + If 0, the poses are left camera poses (monocular-cam0). + """ + recon_path = output_path / "reconstruction" recon_path.mkdir(parents=True, exist_ok=True) delete_files_in_folder(recon_path) - recon = pycolmap.Reconstruction() + reconstruction = pycolmap.Reconstruction() add_cameras_to_reconstruction( - recon, + reconstruction, device_calibration_json, ) add_images_to_reconstruction( - reconstruction=recon, - pred_estimate_file=pred_estimate_file, - cp_json_file=cp_json_file, - device_calibration_json=device_calibration_json, - slam_input_imu=slam_input_imu, + reconstruction, + estimate_file, + cp_json_file, + device_calibration_json, + slam_input_imu, ) - recon.write(recon_path) + reconstruction.write(recon_path) From c2fcc430704b6f875be07a8ba03e30778947aebf Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:36:38 +0200 Subject: [PATCH 297/665] fixes --- lamaria/config/options.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 5dbde76..2014ffe 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -146,6 +146,8 @@ class OptOptions: use_callback: bool = True max_num_iterations: int = 10 normalize_reconstruction: bool = False + minimizer_progress_to_stdout: bool = True + update_state_every_iteration: bool = True @dataclass(slots=True) class VIOptimizerOptions: @@ -153,9 +155,6 @@ class VIOptimizerOptions: imu: OptIMUOptions = field(default_factory=OptIMUOptions) optim: OptOptions = field(default_factory=OptOptions) - colmap_pipeline: pycolmap.IncrementalPipelineOptions = \ - pycolmap.IncrementalPipelineOptions() - @classmethod def load( cls, @@ -169,7 +168,6 @@ def load( imu = _structured_merge_to_obj(OptIMUOptions, cfg.imu) optim = _structured_merge_to_obj(OptOptions, cfg.general) - # leave colmap_pipeline as default return replace( base, cam=cam, From cbf8537e434e322b243c737d9e8e6d653cffd525 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:36:59 +0200 Subject: [PATCH 298/665] unused import --- lamaria/eval/create_empty_recon_from_estimate.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index d6361ca..97aa1f8 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -1,5 +1,4 @@ import json -import os from pathlib import Path import numpy as np From aae69c4a71ea6e65824e6d34cbc2c7b2a2e8b1fc Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:38:12 +0200 Subject: [PATCH 299/665] get cam params comments --- lamaria/utils/camera.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py index fc85a59..2c31729 100644 --- a/lamaria/utils/camera.py +++ b/lamaria/utils/camera.py @@ -61,9 +61,15 @@ def get_camera_params_for_colmap( camera_calibration: CameraCalibration, camera_model: str, ) -> List[float]: - """ Convert Aria CameraCalibration to COLMAP camera parameters. + """ + Convert Aria CameraCalibration to COLMAP camera parameters. Supported models: OPENCV_FISHEYE, FULL_OPENCV, RAD_TAN_THIN_PRISM_FISHEYE -""" + Args: + camera_calibration (CameraCalibration): The projectaria_tools CameraCalibration object + camera_model (str): The COLMAP camera model to use + Returns: + List[float]: The camera parameters in COLMAP format + """ # params = [f_u {f_v} c_u c_v [k_0: k_{numK-1}] # {p_0 p_1} {s_0 s_1 s_2 s_3}] # projection_params is a 15 length vector, From ae583cc790e9f1339f7a600b447e542c56e0608d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 21:42:32 +0200 Subject: [PATCH 300/665] tocolmap libraries --- lamaria/rig/keyframing/to_colmap.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index f7aaf4f..76c4fa3 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -1,9 +1,5 @@ -from __future__ import annotations - - from typing import List, Tuple, Dict, Optional from pathlib import Path -import numpy as np import pycolmap from dataclasses import dataclass from bisect import bisect_left From 2fce69f59aac1f8f5e983e94d5a8caddfaebd964 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 22:33:11 +0200 Subject: [PATCH 301/665] fix --- run_pipeline.py | 1 + 1 file changed, 1 insertion(+) diff --git a/run_pipeline.py b/run_pipeline.py index 6fd15ce..86f110d 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -239,6 +239,7 @@ def run_pipeline( vi_options = options.vi_optimizer_options _ = run_optimization( vi_options, + tri_options, options.tri_model, options.optim_model, ) From 61872aa3d37af6be657e0705028d964e8e731a7e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 22:38:15 +0200 Subject: [PATCH 302/665] trial defs for imu --- defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/defaults.yaml b/defaults.yaml index 28668fb..c9a7515 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -46,7 +46,7 @@ optimization: optimize_gravity: false optimize_imu_from_rig: false optimize_bias: false - gyro_infl: 20.0 + gyro_infl: 1.0 acc_infl: 1.0 integration_noise_density: 0.05 From 80dc20aaf8bb709d114a9ac52f4e5707067fb088 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 22:39:27 +0200 Subject: [PATCH 303/665] imu --- lamaria/rig/optim/imu.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/lamaria/rig/optim/imu.py b/lamaria/rig/optim/imu.py index 12abb87..963ff28 100644 --- a/lamaria/rig/optim/imu.py +++ b/lamaria/rig/optim/imu.py @@ -89,6 +89,8 @@ def load_imu_calibration( gyro_infl: float = 1.0, acc_infl: float = 1.0 ) -> pycolmap.ImuCalibration: + """Load Aria IMU calibration parameters. + Here: https://facebookresearch.github.io/projectaria_tools/docs/tech_insights""" imu_calib = pycolmap.ImuCalibration() imu_calib.gravity_magnitude = 9.80600 From f41d5721d8646f6d09c79480d6f2f7ba2903f9f0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 22:42:42 +0200 Subject: [PATCH 304/665] res --- lamaria/rig/optim/residual_manager.py | 183 +------------------------- 1 file changed, 1 insertion(+), 182 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 506b649..5f2a293 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -72,185 +72,4 @@ def _setup_manifolds_and_constraints(self, problem): problem.set_manifold( self.session.imu_states[frame_id].data, pyceres.SubsetManifold(9, constant_idxs), - ) - - -class DefaultBundleAdjuster: - """Handles image residual setup and constraints""" - def __init__( - self, - options: pycolmap.BundleAdjustmentOptions, - config: pycolmap.BundleAdjustmentConfig, - ): - self.options = options - self.config = config - self.problem = pyceres.Problem() - self.summary = pyceres.SolverSummary() - self.camera_ids = set() - self.point3D_num_observations = dict() - logger.info("BundleAdjuster initialized") - - def solve(self, reconstruction: pycolmap.Reconstruction): - loss = self.options.create_loss_function() - self.set_up_problem(reconstruction, loss) - if self.problem.num_residuals() == 0: - return False - solver_options = self.options.create_solver_options( - self.config, self.problem - ) - pyceres.solve(solver_options, self.problem, self.summary) - return True - - def set_up_problem( - self, - session: SingleSeqSession, - loss: pyceres.LossFunction, - ): - assert session.data.reconstruction is not None - for image_id in tqdm(self.config.images, desc="Adding images to problem"): - self.add_image_to_problem(session, image_id, loss) - - self.parameterize_cameras(session) - self.parameterize_points(session) - logger.info("Optimization problem set up") - return self.problem - - def add_image_to_problem( - self, - session: SingleSeqSession, - image_id: int, - loss: pyceres.LossFunction, - ): - image = session.data.reconstruction.images[image_id] - frame = session.data.reconstruction.frames[image.frame_id] - rig = session.data.reconstruction.rigs[frame.rig_id] - camera = session.data.reconstruction.cameras[image.camera_id] - rig_from_world = frame.rig_from_world - - cam_from_rig = None - for sensor, sensor_from_rig in rig.non_ref_sensors.items(): - if image.camera_id == sensor.id: - cam_from_rig = sensor_from_rig - break - - assert cam_from_rig is not None, "Camera must be part of the rig" - - optimize_cam_from_rig = session.cam_options.optimize_cam_from_rig - feature_std = session.cam_options.feature_std - - num_observations = 0 - for point2D in image.points2D: - if not point2D.has_point3D(): - continue - - num_observations += 1 - if point2D.point3D_id not in self.point3D_num_observations: - self.point3D_num_observations[point2D.point3D_id] = 0 - - self.point3D_num_observations[point2D.point3D_id] += 1 - point3D = session.data.reconstruction.points3D[point2D.point3D_id] - assert point3D.track.length() > 1 - - # we always set refine_rig_from_world to True - # so that rig poses are optimized - if not optimize_cam_from_rig: # constant sensor_from_rig - cost = pycolmap.cost_functions.RigReprojErrorCost( - camera.model, - np.eye(2) * pow(feature_std, 2), - point2D.xy, - cam_from_rig, - ) - self.problem.add_residual_block( - cost, - loss, - [ - rig_from_world.rotation.quat, - rig_from_world.translation, - point3D.xyz, - camera.params, - ], - ) - else: - cost = pycolmap.cost_functions.RigReprojErrorCost( - camera.model, - np.eye(2) * pow(feature_std, 2), - point2D.xy - ) - self.problem.add_residual_block( - cost, - loss, - [ - cam_from_rig.rotation.quat, - cam_from_rig.translation, - rig_from_world.rotation.quat, - rig_from_world.translation, - point3D.xyz, - camera.params, - ], - ) - - if num_observations > 0: - self.camera_ids.add(image.camera_id) # to parameterize later - - # Set pose parameterization and apply gauge constraints - if frame.frame_id == 1: # first frame of the sequence - self.problem.set_parameter_block_constant(rig_from_world.rotation.quat) - self.problem.set_parameter_block_constant(rig_from_world.translation) - elif frame.frame_id == 2: # second frame of the sequence - self.problem.set_manifold( - rig_from_world.translation, - pyceres.SubsetManifold(3, np.array([0])), - ) - else: - self.problem.set_manifold( - rig_from_world.rotation.quat, - pyceres.EigenQuaternionManifold(), - ) - - if optimize_cam_from_rig: - self.problem.set_manifold( - cam_from_rig.rotation.quat, - pyceres.EigenQuaternionManifold(), - ) - - def parameterize_cameras(self, session: SingleSeqSession): - constant_camera = not ( - session.cam_options.optimize_focal_length - or session.cam_options.optimize_principal_point - or session.cam_options.optimize_extra_params - ) - - for camera_id in self.camera_ids: - camera = session.data.reconstruction.cameras[camera_id] - if constant_camera or self.config.has_constant_cam_intrinsics( - camera_id - ): - self.problem.set_parameter_block_constant(camera.params) - continue - - const_camera_params = [] - if not session.cam_options.optimize_focal_length: - const_camera_params.extend(camera.focal_length_idxs()) - if not session.cam_options.optimize_principal_point: - const_camera_params.extend(camera.principal_point_idxs()) - if not session.cam_options.optimize_extra_params: - const_camera_params.extend(camera.extra_point_idxs()) - if len(const_camera_params) > 0: - self.problem.set_manifold( - camera.params, - pyceres.SubsetManifold( - len(camera.params), const_camera_params - ), - ) - - def parameterize_points(self, session: SingleSeqSession): - for ( - point3D_id, - num_observations, - ) in self.point3D_num_observations.items(): - point3D = session.data.reconstruction.points3D[point3D_id] - if point3D.track.length() > num_observations: - self.problem.set_parameter_block_constant(point3D.xyz) - for point3D_id in self.config.constant_points: - point3D = session.data.reconstruction.points3D[point3D_id] - self.problem.set_parameter_block_constant(point3D.xyz) \ No newline at end of file + ) \ No newline at end of file From ea90968e94c89b8ad141c857ab38a893a326625b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 22:44:36 +0200 Subject: [PATCH 305/665] res manager --- lamaria/rig/optim/residual_manager.py | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 5f2a293..1185012 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -1,8 +1,6 @@ import numpy as np import pyceres import pycolmap -import pycolmap.cost_functions -from tqdm import tqdm from ... import logger from .session import SingleSeqSession @@ -12,6 +10,15 @@ class IMUResidualManager: """Handles IMU residual setup and constraints""" def __init__(self, session: SingleSeqSession): self.session = session + + @classmethod + def add( + cls, + problem, + session: SingleSeqSession + ): + """Entry point for adding IMU residuals to the problem.""" + return cls(session).add_residuals(problem) def add_residuals(self, problem): """Add IMU residuals to the optimization problem""" From 6bbc29cf9baeac43d6afb3c2f9a090c296139b7b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 22:46:18 +0200 Subject: [PATCH 306/665] res --- lamaria/rig/optim/residual_manager.py | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 1185012..0d8c60e 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -4,11 +4,17 @@ from ... import logger from .session import SingleSeqSession +from ...config.options import OptIMUOptions class IMUResidualManager: """Handles IMU residual setup and constraints""" - def __init__(self, session: SingleSeqSession): + def __init__( + self, + imu_options: OptIMUOptions, + session: SingleSeqSession + ): + self.imu_options = imu_options self.session = session @classmethod @@ -66,14 +72,14 @@ def _setup_manifolds_and_constraints(self, problem): ) # Apply optimization constraints based on configuration - if not self.session.imu_options.optimize_scale: + if not self.imu_options.optimize_scale: problem.set_parameter_block_constant(self.session.log_scale) - if not self.session.imu_options.optimize_gravity: + if not self.imu_options.optimize_gravity: problem.set_parameter_block_constant(self.session.gravity) - if not self.session.imu_options.optimize_imu_from_rig: + if not self.imu_options.optimize_imu_from_rig: problem.set_parameter_block_constant(self.session.imu_from_rig.rotation.quat) problem.set_parameter_block_constant(self.session.imu_from_rig.translation) - if not self.session.imu_options.optimize_bias: + if not self.imu_options.optimize_bias: constant_idxs = np.arange(3, 9) for frame_id in self.session.imu_states.keys(): problem.set_manifold( From 349098332d59696d73c0dc46d365b94ecf15f428 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 22:55:30 +0200 Subject: [PATCH 307/665] res manager --- lamaria/rig/optim/residual_manager.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 0d8c60e..81aafd0 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -17,14 +17,15 @@ def __init__( self.imu_options = imu_options self.session = session - @classmethod + @staticmethod def add( - cls, + imu_options: OptIMUOptions, problem, session: SingleSeqSession ): """Entry point for adding IMU residuals to the problem.""" - return cls(session).add_residuals(problem) + res_manager = IMUResidualManager(imu_options, session) + return res_manager.add_residuals(problem) def add_residuals(self, problem): """Add IMU residuals to the optimization problem""" From b7266450b710ebe2cda5eddf7a650feac6defdbe Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 22:56:37 +0200 Subject: [PATCH 308/665] static for est to colmap --- lamaria/rig/keyframing/to_colmap.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/rig/keyframing/to_colmap.py index 76c4fa3..a2479c4 100644 --- a/lamaria/rig/keyframing/to_colmap.py +++ b/lamaria/rig/keyframing/to_colmap.py @@ -56,10 +56,9 @@ def __init__(self, options: EstimateToColmapOptions): self._right_imu_sid: StreamId | None = None self._per_frame_data: Dict[int, PerFrameData] = {} - - @classmethod + + @staticmethod def convert( - cls, options: EstimateToColmapOptions, vrs: Path, images: Path, @@ -67,7 +66,8 @@ def convert( mps_folder: Optional[Path] = None, ) -> LamariaReconstruction: """Entry point to run estimate/MPS to colmap conversion.""" - return cls(options).process( + to_colmap = EstimateToColmap(options) + return to_colmap.process( vrs, images, estimate, From c09cf43b58eee6d69398cc2a35774a8aad410556 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 23:05:18 +0200 Subject: [PATCH 309/665] imu res manager --- lamaria/rig/optim/iterative_global_ba.py | 7 +++++-- lamaria/rig/optim/residual_manager.py | 2 +- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 0b31662..29acdad 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -64,7 +64,6 @@ def solve( ba_config, self.session.data.reconstruction ) - imu_manager = IMUResidualManager(self.session) problem = bundle_adjuster.problem @@ -74,7 +73,11 @@ def solve( ) pyceres_solver_options = pyceres.SolverOptions(solver_options) - # problem = imu_manager.add_residuals(problem) + problem = IMUResidualManager.add( + vi_options.imu, + self.session, + problem + ) # problem = apply_constraints(problem, self.session) # Setup solver diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 81aafd0..11bf712 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -20,8 +20,8 @@ def __init__( @staticmethod def add( imu_options: OptIMUOptions, + session: SingleSeqSession, problem, - session: SingleSeqSession ): """Entry point for adding IMU residuals to the problem.""" res_manager = IMUResidualManager(imu_options, session) From 6fc4118c4051e0a4ff4dcf0b19f9f7f869e02b65 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 23:08:42 +0200 Subject: [PATCH 310/665] lamaria recon --- lamaria/rig/lamaria_reconstruction.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/lamaria_reconstruction.py b/lamaria/rig/lamaria_reconstruction.py index 0744b25..639f045 100644 --- a/lamaria/rig/lamaria_reconstruction.py +++ b/lamaria/rig/lamaria_reconstruction.py @@ -9,13 +9,12 @@ def __init__(self) -> None: self.timestamps: Dict[int, int] = {} self.imu_measurements = pycolmap.ImuMeasurements([]) - @classmethod + @staticmethod def read( - cls, input_folder: Path, ) -> "LamariaReconstruction": assert input_folder.exists(), f"Input folder {input_folder} does not exist" - instance = cls() + instance = LamariaReconstruction() instance.reconstruction = pycolmap.Reconstruction(input_folder) ts_path = input_folder / "timestamps.txt" From 9cba491069539dcf8dc55a28806caecb9edcd77b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 23:09:13 +0200 Subject: [PATCH 311/665] static method reverts --- lamaria/rig/optim/iterative_global_ba.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 29acdad..1f5b147 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -35,16 +35,16 @@ class VIBundleAdjuster: def __init__(self, session: SingleSeqSession): self.session = session - @classmethod + @staticmethod def run( - cls, vi_options: VIOptimizerOptions, ba_options: pycolmap.BundleAdjustmentOptions, ba_config: pycolmap.BundleAdjustmentConfig, session: SingleSeqSession ): """Entry point for running VI bundle adjustment.""" - summary, problem = cls(session).solve( + vi_ba = VIBundleAdjuster(session) + summary, problem = vi_ba.solve( vi_options, ba_options, ba_config @@ -111,16 +111,16 @@ class GlobalBundleAdjustment: def __init__(self, session: SingleSeqSession): self.session = session - @classmethod + @staticmethod def run( - cls, vi_options: VIOptimizerOptions, pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, session: SingleSeqSession, ): """Entry point for running global bundle adjustment.""" - return cls(session).adjust( + gba = GlobalBundleAdjustment(session) + return gba.adjust( vi_options, pipeline_options, mapper, @@ -190,16 +190,16 @@ class IterativeRefinement: def __init__(self, session: SingleSeqSession): self.session = session - @classmethod + @staticmethod def run( - cls, vi_options: VIOptimizerOptions, pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, session: SingleSeqSession, ): """Entry point for running iterative refinement""" - return cls(session).refine( + iter_refiner = IterativeRefinement(session) + return iter_refiner.refine( vi_options, pipeline_options, mapper, From badcb27c6721e335c6c286acb3afe6f8b01fbb0e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 23:09:27 +0200 Subject: [PATCH 312/665] static method reverts again --- lamaria/rig/optim/vi_optimization.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/rig/optim/vi_optimization.py index 30f9700..428e56d 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/rig/optim/vi_optimization.py @@ -19,16 +19,16 @@ def __init__( self.triangulator_options = triangulator_options self.session = session - @classmethod + @staticmethod def optimize( - cls, vi_options: VIOptimizerOptions, triangulator_options: TriangulatorOptions, session: SingleSeqSession, database_path: Path, ) -> pycolmap.Reconstruction: """Entry point for running full VI optimization""" - return cls(vi_options, triangulator_options, session).process(database_path) + optimizer = VIOptimizer(vi_options, triangulator_options, session) + return optimizer.process(database_path) def process( self, From 28eb8b456eb38f813e476cb6ac242628dcbd9429 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 23:12:05 +0200 Subject: [PATCH 313/665] tqdm --- lamaria/rig/optim/residual_manager.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index 11bf712..ca190c3 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -1,6 +1,7 @@ import numpy as np import pyceres import pycolmap +from tqdm import tqdm from ... import logger from .session import SingleSeqSession @@ -33,7 +34,10 @@ def add_residuals(self, problem): frame_ids = sorted(self.session.data.reconstruction.frames.keys()) - for k in range(len(self.session.preintegrated_imu_measurements)): + for k in tqdm( + range(len(self.session.preintegrated_imu_measurements)), + desc="Adding IMU residuals" + ): i = frame_ids[k] j = frame_ids[k + 1] frame_i = self.session.data.reconstruction.frames[i] From 556a4a895d5278950e955a47b52dc53b16fabf19 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 23:13:21 +0200 Subject: [PATCH 314/665] unncessart step --- lamaria/rig/optim/residual_manager.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual_manager.py index ca190c3..4a267c4 100644 --- a/lamaria/rig/optim/residual_manager.py +++ b/lamaria/rig/optim/residual_manager.py @@ -65,7 +65,7 @@ def add_residuals(self, problem): ) self._setup_manifolds_and_constraints(problem) - logger.info("Added IMU residuals to the problem") + return problem def _setup_manifolds_and_constraints(self, problem): From 9be920f829ddff2ad590c9b85c41d54d1fe11ea0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 23:20:52 +0200 Subject: [PATCH 315/665] res --- lamaria/rig/optim/{residual_manager.py => residual.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename lamaria/rig/optim/{residual_manager.py => residual.py} (100%) diff --git a/lamaria/rig/optim/residual_manager.py b/lamaria/rig/optim/residual.py similarity index 100% rename from lamaria/rig/optim/residual_manager.py rename to lamaria/rig/optim/residual.py From bf4b8e8bcb54774abe93cfa889e112dc3626490d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Thu, 25 Sep 2025 23:21:21 +0200 Subject: [PATCH 316/665] fix paths --- lamaria/rig/optim/iterative_global_ba.py | 2 +- lamaria/rig/optim/residual.py | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/rig/optim/iterative_global_ba.py index 1f5b147..5e865a0 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/rig/optim/iterative_global_ba.py @@ -5,7 +5,7 @@ from ... import logger from .session import SingleSeqSession -from .residual_manager import IMUResidualManager +from .residual import IMUResidualManager from .callback import RefinementCallback from ...config.options import VIOptimizerOptions diff --git a/lamaria/rig/optim/residual.py b/lamaria/rig/optim/residual.py index 4a267c4..7727bb2 100644 --- a/lamaria/rig/optim/residual.py +++ b/lamaria/rig/optim/residual.py @@ -3,7 +3,6 @@ import pycolmap from tqdm import tqdm -from ... import logger from .session import SingleSeqSession from ...config.options import OptIMUOptions From 0b31ce7752b0cb9f84091a92f85bb581b5a7c4a7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 00:08:04 +0200 Subject: [PATCH 317/665] bugfix --- lamaria/rig/keyframing/keyframe_selection.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/rig/keyframing/keyframe_selection.py index 020cd7c..6392bd2 100644 --- a/lamaria/rig/keyframing/keyframe_selection.py +++ b/lamaria/rig/keyframing/keyframe_selection.py @@ -241,7 +241,7 @@ def copy_images_to_keyframes_dir( for data_id in frame.data_ids: image = self.init_recons.images[data_id.id] - subdir = "left" if "1201-1" in image.name else "right" + subdir = "left" if image.name.startswith("1201-1") else "right" src_path = images / subdir / image.name dst_path = output / image.name From c6ac73e2a88c22360803ecf4acadcd17180a9dac Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 01:29:43 +0200 Subject: [PATCH 318/665] eres --- lamaria/rig/optim/residual.py | 148 ++++++++++++++++------------------ 1 file changed, 71 insertions(+), 77 deletions(-) diff --git a/lamaria/rig/optim/residual.py b/lamaria/rig/optim/residual.py index 7727bb2..b8d7e38 100644 --- a/lamaria/rig/optim/residual.py +++ b/lamaria/rig/optim/residual.py @@ -7,86 +7,80 @@ from ...config.options import OptIMUOptions -class IMUResidualManager: - """Handles IMU residual setup and constraints""" - def __init__( - self, - imu_options: OptIMUOptions, - session: SingleSeqSession - ): - self.imu_options = imu_options - self.session = session - - @staticmethod - def add( - imu_options: OptIMUOptions, - session: SingleSeqSession, - problem, - ): - """Entry point for adding IMU residuals to the problem.""" - res_manager = IMUResidualManager(imu_options, session) - return res_manager.add_residuals(problem) +def add_imu_residuals_to_problem( + imu_options: OptIMUOptions, + session: SingleSeqSession, + problem, +): + loss = pyceres.TrivialLoss() - def add_residuals(self, problem): - """Add IMU residuals to the optimization problem""" - loss = pyceres.TrivialLoss() - - frame_ids = sorted(self.session.data.reconstruction.frames.keys()) + frame_ids = sorted(session.data.reconstruction.frames.keys()) - for k in tqdm( - range(len(self.session.preintegrated_imu_measurements)), - desc="Adding IMU residuals" - ): - i = frame_ids[k] - j = frame_ids[k + 1] - frame_i = self.session.data.reconstruction.frames[i] - frame_j = self.session.data.reconstruction.frames[j] - i_from_world = frame_i.rig_from_world - j_from_world = frame_j.rig_from_world - - integrated_m = self.session.preintegrated_imu_measurements[i] + for k in tqdm( + range(len(session.preintegrated_imu_measurements)), + desc="Adding IMU residuals" + ): + i = frame_ids[k] + j = frame_ids[k + 1] + frame_i = session.data.reconstruction.frames[i] + frame_j = session.data.reconstruction.frames[j] + i_from_world = frame_i.rig_from_world + j_from_world = frame_j.rig_from_world - problem.add_residual_block( - pycolmap.PreintegratedImuMeasurementCost(integrated_m), - loss, - [ - self.session.imu_from_rig.rotation.quat, - self.session.imu_from_rig.translation, - self.session.log_scale, - self.session.gravity, - i_from_world.rotation.quat, - i_from_world.translation, - self.session.imu_states[i].data, - j_from_world.rotation.quat, - j_from_world.translation, - self.session.imu_states[j].data, - ], - ) + integrated_m = session.preintegrated_imu_measurements[i] - self._setup_manifolds_and_constraints(problem) + problem.add_residual_block( + pycolmap.PreintegratedImuMeasurementCost(integrated_m), + loss, + [ + session.imu_from_rig.rotation.quat, + session.imu_from_rig.translation, + session.log_scale, + session.gravity, + i_from_world.rotation.quat, + i_from_world.translation, + session.imu_states[i].data, + j_from_world.rotation.quat, + j_from_world.translation, + session.imu_states[j].data, + ], + ) + + problem = setup_manifolds_and_constraints( + imu_options, + session, + problem, + ) - return problem + return problem + - def _setup_manifolds_and_constraints(self, problem): - """Setup manifolds and parameter constraints""" - problem.set_manifold(self.session.gravity, pyceres.SphereManifold(3)) - problem.set_manifold( - self.session.imu_from_rig.rotation.quat, - pyceres.EigenQuaternionManifold() - ) - - # Apply optimization constraints based on configuration - if not self.imu_options.optimize_scale: - problem.set_parameter_block_constant(self.session.log_scale) - if not self.imu_options.optimize_gravity: - problem.set_parameter_block_constant(self.session.gravity) - if not self.imu_options.optimize_imu_from_rig: - problem.set_parameter_block_constant(self.session.imu_from_rig.rotation.quat) - problem.set_parameter_block_constant(self.session.imu_from_rig.translation) - if not self.imu_options.optimize_bias: - constant_idxs = np.arange(3, 9) - for frame_id in self.session.imu_states.keys(): - problem.set_manifold( - self.session.imu_states[frame_id].data, - pyceres.SubsetManifold(9, constant_idxs), - ) \ No newline at end of file +def setup_manifolds_and_constraints( + imu_options: OptIMUOptions, + session: SingleSeqSession, + problem, +): + """Setup manifolds and parameter constraints""" + problem.set_manifold(session.gravity, pyceres.SphereManifold(3)) + problem.set_manifold( + session.imu_from_rig.rotation.quat, + pyceres.EigenQuaternionManifold() + ) + + # Apply optimization constraints based on configuration + if not imu_options.optimize_scale: + problem.set_parameter_block_constant(session.log_scale) + if not imu_options.optimize_gravity: + problem.set_parameter_block_constant(session.gravity) + if not imu_options.optimize_imu_from_rig: + problem.set_parameter_block_constant(session.imu_from_rig.rotation.quat) + problem.set_parameter_block_constant(session.imu_from_rig.translation) + if not imu_options.optimize_bias: + constant_idxs = np.arange(3, 9) + for frame_id in session.imu_states.keys(): + problem.set_manifold( + session.imu_states[frame_id].data, + pyceres.SubsetManifold(9, constant_idxs), + ) + + return problem \ No newline at end of file From a5d7194f70e694b27c4f35d437b081b26ea9a6cc Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 10:26:18 +0200 Subject: [PATCH 319/665] renaming --- lamaria/config/helpers.py | 27 ------ lamaria/config/options.py | 10 ++- lamaria/eval/sparse_evaluation.py | 1 + .../keyframing/keyframe_selection.py | 0 .../{rig => pipeline}/keyframing/to_colmap.py | 0 .../lamaria_reconstruction.py | 0 lamaria/{rig => pipeline}/optim/callback.py | 0 lamaria/{rig => pipeline}/optim/imu.py | 0 .../optim/iterative_global_ba.py | 87 ++++++++++--------- lamaria/{rig => pipeline}/optim/residual.py | 0 lamaria/{rig => pipeline}/optim/session.py | 0 .../{rig => pipeline}/optim/triangulation.py | 0 .../optim/vi_optimization.py | 4 +- run_pipeline.py | 12 +-- 14 files changed, 63 insertions(+), 78 deletions(-) delete mode 100644 lamaria/config/helpers.py rename lamaria/{rig => pipeline}/keyframing/keyframe_selection.py (100%) rename lamaria/{rig => pipeline}/keyframing/to_colmap.py (100%) rename lamaria/{rig => pipeline}/lamaria_reconstruction.py (100%) rename lamaria/{rig => pipeline}/optim/callback.py (100%) rename lamaria/{rig => pipeline}/optim/imu.py (100%) rename lamaria/{rig => pipeline}/optim/iterative_global_ba.py (81%) rename lamaria/{rig => pipeline}/optim/residual.py (100%) rename lamaria/{rig => pipeline}/optim/session.py (100%) rename lamaria/{rig => pipeline}/optim/triangulation.py (100%) rename lamaria/{rig => pipeline}/optim/vi_optimization.py (97%) diff --git a/lamaria/config/helpers.py b/lamaria/config/helpers.py deleted file mode 100644 index eff5d54..0000000 --- a/lamaria/config/helpers.py +++ /dev/null @@ -1,27 +0,0 @@ -# options.py helper functions -from __future__ import annotations -from pathlib import Path -from typing import Optional -from omegaconf import OmegaConf - -def _p( - x: Optional[str] | Optional[Path], - root: Optional[Path] = None -) -> Optional[Path]: - - if x is None: - return None - x = Path(x) - if root is not None and not x.is_absolute(): - return (root / x).resolve() - return x.resolve() - -def _structured_merge_to_obj(cls, section) -> object: - """ - Merge a YAML section onto a structured - config made from the dataclass `cls`, - then return a dataclass instance. - """ - base = OmegaConf.structured(cls) - merged = OmegaConf.merge(base, section or {}) - return OmegaConf.to_object(merged) \ No newline at end of file diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 2014ffe..5768ec3 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -6,7 +6,15 @@ import pycolmap from omegaconf import OmegaConf, open_dict -from .helpers import _structured_merge_to_obj +def _structured_merge_to_obj(cls, section) -> object: + """ + Merge a YAML section onto a structured + config made from the dataclass `cls`, + then return a dataclass instance. + """ + base = OmegaConf.structured(cls) + merged = OmegaConf.merge(base, section or {}) + return OmegaConf.to_object(merged) # General options diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 634cc7c..309059b 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -14,6 +14,7 @@ get_cps_for_initial_alignment, run_control_point_triangulation_from_json, ) +# move these into this script here. from ..utils.sparse_eval import ( create_variables_for_sparse_evaluation, get_problem_for_sparse_alignment, diff --git a/lamaria/rig/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py similarity index 100% rename from lamaria/rig/keyframing/keyframe_selection.py rename to lamaria/pipeline/keyframing/keyframe_selection.py diff --git a/lamaria/rig/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py similarity index 100% rename from lamaria/rig/keyframing/to_colmap.py rename to lamaria/pipeline/keyframing/to_colmap.py diff --git a/lamaria/rig/lamaria_reconstruction.py b/lamaria/pipeline/lamaria_reconstruction.py similarity index 100% rename from lamaria/rig/lamaria_reconstruction.py rename to lamaria/pipeline/lamaria_reconstruction.py diff --git a/lamaria/rig/optim/callback.py b/lamaria/pipeline/optim/callback.py similarity index 100% rename from lamaria/rig/optim/callback.py rename to lamaria/pipeline/optim/callback.py diff --git a/lamaria/rig/optim/imu.py b/lamaria/pipeline/optim/imu.py similarity index 100% rename from lamaria/rig/optim/imu.py rename to lamaria/pipeline/optim/imu.py diff --git a/lamaria/rig/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py similarity index 81% rename from lamaria/rig/optim/iterative_global_ba.py rename to lamaria/pipeline/optim/iterative_global_ba.py index 5e865a0..f3c41af 100644 --- a/lamaria/rig/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -5,7 +5,7 @@ from ... import logger from .session import SingleSeqSession -from .residual import IMUResidualManager +from .residual import add_imu_residuals_to_problem from .callback import RefinementCallback from ...config.options import VIOptimizerOptions @@ -40,49 +40,52 @@ def run( vi_options: VIOptimizerOptions, ba_options: pycolmap.BundleAdjustmentOptions, ba_config: pycolmap.BundleAdjustmentConfig, - session: SingleSeqSession + mapper: pycolmap.IncrementalMapper, + session: SingleSeqSession, + callback: RefinementCallback = None, ): """Entry point for running VI bundle adjustment.""" vi_ba = VIBundleAdjuster(session) - summary, problem = vi_ba.solve( + vi_ba.solve( vi_options, ba_options, - ba_config + ba_config, + mapper, + callback, ) - return summary, problem - def solve( self, vi_options: VIOptimizerOptions, ba_options: pycolmap.BundleAdjustmentOptions, ba_config: pycolmap.BundleAdjustmentConfig, + mapper: pycolmap.IncrementalMapper, + callback: RefinementCallback = None, ): """Solves the VI bundle adjustment problem.""" bundle_adjuster = pycolmap.create_default_bundle_adjuster( ba_options, ba_config, - self.session.data.reconstruction + mapper.reconstruction, ) problem = bundle_adjuster.problem - + solver_options = ba_options.create_solver_options( ba_config, - problem + bundle_adjuster.problem ) pyceres_solver_options = pyceres.SolverOptions(solver_options) - problem = IMUResidualManager.add( + problem = add_imu_residuals_to_problem( vi_options.imu, self.session, - problem + problem, ) # problem = apply_constraints(problem, self.session) - # Setup solver + # Setup callback if needed if vi_options.optim.use_callback: - callback = self._init_callback() pyceres_solver_options.callbacks = [callback] pyceres_solver_options.minimizer_progress_to_stdout = vi_options.optim.minimizer_progress_to_stdout @@ -91,18 +94,8 @@ def solve( # Solve summary = pyceres.SolverSummary() - pyceres.solve(pyceres_solver_options, problem, summary) + pyceres.solve(pyceres_solver_options, bundle_adjuster.problem, summary) print(summary.BriefReport()) - - return summary, problem - - def _init_callback(self): - """Initialize the refinement callback to check pose changes.""" - frame_ids = sorted(self.session.data.reconstruction.frames.keys()) - poses = list(self.session.data.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) - callback = RefinementCallback(poses) - - return callback class GlobalBundleAdjustment: @@ -117,13 +110,15 @@ def run( pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, session: SingleSeqSession, + callback = None, ): """Entry point for running global bundle adjustment.""" gba = GlobalBundleAdjustment(session) - return gba.adjust( + gba.adjust( vi_options, pipeline_options, mapper, + callback, ) def adjust( @@ -131,11 +126,11 @@ def adjust( vi_options: VIOptimizerOptions, pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, + callback: RefinementCallback = None, ): - reconstruction = mapper.reconstruction - assert reconstruction is not None + assert mapper.reconstruction is not None - reg_image_ids = reconstruction.reg_image_ids() + reg_image_ids = mapper.reconstruction.reg_image_ids() if len(reg_image_ids) < 2: logger.warning("At least two images must be registered for global bundle-adjustment") @@ -149,22 +144,22 @@ def adjust( # Setting up bundle adjustment configuration ba_config = pycolmap.BundleAdjustmentConfig() - for frame_id in reconstruction.reg_frame_ids(): - frame = reconstruction.frame(frame_id) + for frame_id in mapper.reconstruction.reg_frame_ids(): + frame = mapper.reconstruction.frame(frame_id) for data_id in frame.data_ids: if data_id.sensor_id.type != pycolmap.SensorType.CAMERA: continue ba_config.add_image(data_id.id) # Run bundle adjustment - _, _ = VIBundleAdjuster.run( + VIBundleAdjuster.run( vi_options, ba_options, ba_config, - self.session + mapper, + self.session, + callback ) - - return reconstruction def _configure_ba_options(self, pipeline_options, num_reg_images): """Configure bundle adjustment options based on number of registered images""" @@ -199,7 +194,7 @@ def run( ): """Entry point for running iterative refinement""" iter_refiner = IterativeRefinement(session) - return iter_refiner.refine( + iter_refiner.refine( vi_options, pipeline_options, mapper, @@ -211,8 +206,6 @@ def refine( pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, ): - reconstruction = mapper.reconstruction - # Configure triangulation options tri_options = pipeline_options.get_triangulation() mapper.complete_and_merge_tracks(tri_options) @@ -224,19 +217,23 @@ def refine( # Configure mapper options mapper_options = pipeline_options.get_mapper() + if vi_options.optim.use_callback: + callback = self._init_callback(mapper) + # Iterative refinement for i in range(pipeline_options.ba_global_max_refinements): - num_observations = reconstruction.compute_num_observations() + num_observations = mapper.reconstruction.compute_num_observations() - reconstruction = GlobalBundleAdjustment.run( + GlobalBundleAdjustment.run( vi_options, pipeline_options, mapper, - self.session + self.session, + callback, ) if vi_options.optim.normalize_reconstruction: - reconstruction.normalize() + mapper.reconstruction.normalize() num_changed_observations = mapper.complete_and_merge_tracks(tri_options) num_changed_observations += mapper.filter_points(mapper_options) @@ -247,4 +244,10 @@ def refine( if changed < pipeline_options.ba_global_max_refinement_change: break - return reconstruction \ No newline at end of file + def _init_callback(self, mapper: pycolmap.IncrementalMapper): + """Initialize the refinement callback to check pose changes.""" + frame_ids = sorted(mapper.reconstruction.frames.keys()) + poses = list(mapper.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) + callback = RefinementCallback(poses) + + return callback \ No newline at end of file diff --git a/lamaria/rig/optim/residual.py b/lamaria/pipeline/optim/residual.py similarity index 100% rename from lamaria/rig/optim/residual.py rename to lamaria/pipeline/optim/residual.py diff --git a/lamaria/rig/optim/session.py b/lamaria/pipeline/optim/session.py similarity index 100% rename from lamaria/rig/optim/session.py rename to lamaria/pipeline/optim/session.py diff --git a/lamaria/rig/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py similarity index 100% rename from lamaria/rig/optim/triangulation.py rename to lamaria/pipeline/optim/triangulation.py diff --git a/lamaria/rig/optim/vi_optimization.py b/lamaria/pipeline/optim/vi_optimization.py similarity index 97% rename from lamaria/rig/optim/vi_optimization.py rename to lamaria/pipeline/optim/vi_optimization.py index 428e56d..e53fb9d 100644 --- a/lamaria/rig/optim/vi_optimization.py +++ b/lamaria/pipeline/optim/vi_optimization.py @@ -45,14 +45,14 @@ def process( mapper = self._setup_incremental_mapper(database_path) pipeline_options = self._get_incremental_pipeline_options() - reconstruction = IterativeRefinement.run( + IterativeRefinement.run( self.vi_options, pipeline_options, mapper, self.session ) - return reconstruction + return mapper.reconstruction def _setup_incremental_mapper(self, database_path: Path): """Setup the COLMAP incremental mapper""" diff --git a/run_pipeline.py b/run_pipeline.py index 86f110d..0937547 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -4,12 +4,12 @@ from typing import Optional from pathlib import Path -from lamaria.rig.lamaria_reconstruction import LamariaReconstruction -from lamaria.rig.keyframing.to_colmap import EstimateToColmap -from lamaria.rig.keyframing.keyframe_selection import KeyframeSelector -from lamaria.rig.optim.triangulation import run as triangulate -from lamaria.rig.optim.session import SingleSeqSession -from lamaria.rig.optim.vi_optimization import VIOptimizer +from lamaria.pipeline.lamaria_reconstruction import LamariaReconstruction +from lamaria.pipeline.keyframing.to_colmap import EstimateToColmap +from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector +from lamaria.pipeline.optim.triangulation import run as triangulate +from lamaria.pipeline.optim.session import SingleSeqSession +from lamaria.pipeline.optim.vi_optimization import VIOptimizer from lamaria.config.pipeline import PipelineOptions from lamaria.config.options import ( EstimateToColmapOptions, From f9b9d1162eb0087ec32171e78f46d28ff0cd2f76 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 10:26:44 +0200 Subject: [PATCH 320/665] nuused --- lamaria/config/options.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 5768ec3..ea574d7 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -2,8 +2,6 @@ from dataclasses import dataclass, field, replace from typing import Optional -from pathlib import Path -import pycolmap from omegaconf import OmegaConf, open_dict def _structured_merge_to_obj(cls, section) -> object: From 633d6c2716e7f60f58e26c0c7b62ff08646e0cc9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 10:27:33 +0200 Subject: [PATCH 321/665] cp --- lamaria/utils/control_point.py | 20 -------------------- 1 file changed, 20 deletions(-) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 78be0ac..9e940e1 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -96,26 +96,6 @@ def transform_triangulated_control_points(control_points: Dict, r, t, scale): return control_points -def plot_ratio_of_inliers(control_points: Dict, save_folder: str): - tag_id_to_inlier_ratio = {} - for tag_id, cp in control_points.items(): - ratio = cp["inlier_ratio"] - tag_id_to_inlier_ratio[tag_id] = ratio - - sorted_tag_ids = sorted(tag_id_to_inlier_ratio.keys()) - sorted_ratios = [ - tag_id_to_inlier_ratio[tag_id] for tag_id in sorted_tag_ids - ] - - plt.bar(sorted_tag_ids, sorted_ratios, align="center") - plt.xticks(sorted_tag_ids, sorted_tag_ids, rotation=45) - plt.xlabel("Tag ID") - plt.ylabel("Inlier ratio") - plt.title("Inlier ratio for each tag after triangulation") - plt.savefig(os.path.join(save_folder, "inlier_ratio.png")) - plt.close() - - def run_control_point_triangulation_from_json( reconstruction_path: Path, cp_json_file: Path, From 4afd0d21e1126d7a312bc0f9570cc21222eb3bd7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 10:32:29 +0200 Subject: [PATCH 322/665] callback passed in --- lamaria/pipeline/optim/iterative_global_ba.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index f3c41af..f3a582d 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -110,7 +110,7 @@ def run( pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, session: SingleSeqSession, - callback = None, + callback: RefinementCallback = None, ): """Entry point for running global bundle adjustment.""" gba = GlobalBundleAdjustment(session) @@ -205,6 +205,7 @@ def refine( vi_options: VIOptimizerOptions, pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, + callback: RefinementCallback = None, ): # Configure triangulation options tri_options = pipeline_options.get_triangulation() From f405bbed0f1bb477164f640d91c73a728e6803c9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 10:38:42 +0200 Subject: [PATCH 323/665] rm sparse eval --- lamaria/utils/sparse_eval.py | 111 ----------------------------------- 1 file changed, 111 deletions(-) delete mode 100644 lamaria/utils/sparse_eval.py diff --git a/lamaria/utils/sparse_eval.py b/lamaria/utils/sparse_eval.py deleted file mode 100644 index 605db12..0000000 --- a/lamaria/utils/sparse_eval.py +++ /dev/null @@ -1,111 +0,0 @@ -import copy - -import numpy as np -import pycolmap -import pyceres -import pycolmap.cost_functions -from typing import Dict - -from lamaria import logger - -def update_sim3d_scale(variables: Dict): - if "log_scale" not in variables: - raise ValueError("log_scale not found in variables") - - log_scale = copy.deepcopy(variables["log_scale"]) - variables["sim3d"].scale = np.exp(log_scale) - -def create_variables_for_sparse_evaluation( - control_points: Dict, - sim3d: pycolmap.Sim3d, - cp_reproj_std: float = 1.0 -) -> Dict: - - variables = {} - variables["control_points"] = copy.deepcopy(control_points) - variables["sim3d"] = copy.deepcopy(sim3d) - variables["cp_reproj_std"] = cp_reproj_std - scale = copy.deepcopy(variables["sim3d"].scale) - variables["log_scale"] = np.array(np.log(scale), dtype=np.float64) - - return variables - - -def get_problem_for_sparse_alignment( - reconstruction: pycolmap.Reconstruction, - variables: Dict, -): - problem = pyceres.Problem() - problem = add_alignment_residuals( - problem, - reconstruction, - variables, - ) - solver_options = pyceres.SolverOptions() - solver_options.minimizer_progress_to_stdout = True - summary = pyceres.SolverSummary() - - return problem, solver_options, summary - - -def add_alignment_residuals( - problem, - reconstruction: pycolmap.Reconstruction, - variables: Dict, -) -> pyceres.Problem: - - if ( - variables["control_points"] is not None - and variables["sim3d"] is not None - ): - loss = pyceres.TrivialLoss() - for tag_id, cp in variables["control_points"].items(): - if cp["triangulated"] is None: - logger.info(f"Control point {tag_id} not triangulated") - continue - for image_id_and_point2d in cp["image_id_and_point2d"]: - image_id, point2d = image_id_and_point2d - image = reconstruction.images[image_id] - pose = image.cam_from_world() - camera = reconstruction.cameras[image.camera_id] - - point2d = np.asarray(point2d, dtype=np.float64).reshape(2, 1) - point2d_cov = np.eye(2) * pow(variables["cp_reproj_std"], 2) - cost = pycolmap.cost_functions.ReprojErrorCost( - camera.model, - point2d_cov, - point2d, - pose, - ) - problem.add_residual_block( - cost, loss, [cp["triangulated"], camera.params] - ) - problem.set_parameter_block_constant(camera.params) - - for tag_id, cp in variables["control_points"].items(): - if cp["triangulated"] is None: - logger.info(f"Control point {tag_id} not triangulated") - continue - cost = pycolmap.cost_functions.Point3DAlignmentCost( - cp["covariance"], - cp["topo"], - ) - problem.add_residual_block( - cost, - loss, - [ - cp["triangulated"], - variables["sim3d"].rotation.quat, - variables["sim3d"].translation, - variables["log_scale"], - ], - ) - - logger.info(f"Added Point3dAlignmentCost and ReprojErrorCost costs") - - problem.set_manifold( - variables["sim3d"].rotation.quat, - pyceres.EigenQuaternionManifold(), - ) - - return problem From ead333a5cfa07adf6c5dd8c2ed1feb485272c46f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 10:39:02 +0200 Subject: [PATCH 324/665] spars eevla --- lamaria/eval/sparse_evaluation.py | 114 ++++++++++++++++++++++++++++-- 1 file changed, 107 insertions(+), 7 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 309059b..2f94e68 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -1,11 +1,13 @@ import copy import os import argparse +import numpy as np +from typing import Dict from pathlib import Path -import numpy as np import pyceres import pycolmap +import pycolmap.cost_functions from .. import logger @@ -14,12 +16,110 @@ get_cps_for_initial_alignment, run_control_point_triangulation_from_json, ) -# move these into this script here. -from ..utils.sparse_eval import ( - create_variables_for_sparse_evaluation, - get_problem_for_sparse_alignment, - update_sim3d_scale, -) + + +def update_sim3d_scale(variables: Dict): + if "log_scale" not in variables: + raise ValueError("log_scale not found in variables") + + log_scale = copy.deepcopy(variables["log_scale"]) + variables["sim3d"].scale = np.exp(log_scale) + + +def create_variables_for_sparse_evaluation( + control_points: Dict, + sim3d: pycolmap.Sim3d, + cp_reproj_std: float = 1.0 +) -> Dict: + + variables = {} + variables["control_points"] = copy.deepcopy(control_points) + variables["sim3d"] = copy.deepcopy(sim3d) + variables["cp_reproj_std"] = cp_reproj_std + scale = copy.deepcopy(variables["sim3d"].scale) + variables["log_scale"] = np.array(np.log(scale), dtype=np.float64) + + return variables + + +def get_problem_for_sparse_alignment( + reconstruction: pycolmap.Reconstruction, + variables: Dict, +): + problem = pyceres.Problem() + problem = add_alignment_residuals( + problem, + reconstruction, + variables, + ) + solver_options = pyceres.SolverOptions() + solver_options.minimizer_progress_to_stdout = True + summary = pyceres.SolverSummary() + + return problem, solver_options, summary + + +def add_alignment_residuals( + problem, + reconstruction: pycolmap.Reconstruction, + variables: Dict, +) -> pyceres.Problem: + + if ( + variables["control_points"] is not None + and variables["sim3d"] is not None + ): + loss = pyceres.TrivialLoss() + for tag_id, cp in variables["control_points"].items(): + if cp["triangulated"] is None: + logger.info(f"Control point {tag_id} not triangulated") + continue + for image_id_and_point2d in cp["image_id_and_point2d"]: + image_id, point2d = image_id_and_point2d + image = reconstruction.images[image_id] + pose = image.cam_from_world() + camera = reconstruction.cameras[image.camera_id] + + point2d = np.asarray(point2d, dtype=np.float64).reshape(2, 1) + point2d_cov = np.eye(2) * pow(variables["cp_reproj_std"], 2) + cost = pycolmap.cost_functions.ReprojErrorCost( + camera.model, + point2d_cov, + point2d, + pose, + ) + problem.add_residual_block( + cost, loss, [cp["triangulated"], camera.params] + ) + problem.set_parameter_block_constant(camera.params) + + for tag_id, cp in variables["control_points"].items(): + if cp["triangulated"] is None: + logger.info(f"Control point {tag_id} not triangulated") + continue + cost = pycolmap.cost_functions.Point3DAlignmentCost( + cp["covariance"], + cp["topo"], + ) + problem.add_residual_block( + cost, + loss, + [ + cp["triangulated"], + variables["sim3d"].rotation.quat, + variables["sim3d"].translation, + variables["log_scale"], + ], + ) + + logger.info(f"Added Point3dAlignmentCost and ReprojErrorCost costs") + + problem.set_manifold( + variables["sim3d"].rotation.quat, + pyceres.EigenQuaternionManifold(), + ) + + return problem def run_baseline_evaluation( From 5d7169018d5857bacebc84487a0fd16036f4ef69 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 10:41:00 +0200 Subject: [PATCH 325/665] use log scale --- lamaria/eval/sparse_evaluation.py | 1 + 1 file changed, 1 insertion(+) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 2f94e68..d760860 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -100,6 +100,7 @@ def add_alignment_residuals( cost = pycolmap.cost_functions.Point3DAlignmentCost( cp["covariance"], cp["topo"], + use_log_scale=True, ) problem.add_residual_block( cost, From c73b0349625dce99a291f53d4f0e2589ff47d78a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 14:21:52 +0200 Subject: [PATCH 326/665] switch on using callback --- defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/defaults.yaml b/defaults.yaml index c9a7515..ffc9738 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -28,7 +28,7 @@ triangulation: optimization: general: - use_callback: false + use_callback: true max_num_iterations: 10 normalize_reconstruction: false minimizer_progress_to_stdout: true From 8bef034b45c62f2bfe599742713a59901f2d3183 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 14:22:51 +0200 Subject: [PATCH 327/665] updating iterative global ba --- lamaria/pipeline/optim/iterative_global_ba.py | 31 ++++++------------- 1 file changed, 10 insertions(+), 21 deletions(-) diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index f3a582d..764222f 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -42,7 +42,6 @@ def run( ba_config: pycolmap.BundleAdjustmentConfig, mapper: pycolmap.IncrementalMapper, session: SingleSeqSession, - callback: RefinementCallback = None, ): """Entry point for running VI bundle adjustment.""" vi_ba = VIBundleAdjuster(session) @@ -51,7 +50,6 @@ def run( ba_options, ba_config, mapper, - callback, ) def solve( @@ -60,7 +58,6 @@ def solve( ba_options: pycolmap.BundleAdjustmentOptions, ba_config: pycolmap.BundleAdjustmentConfig, mapper: pycolmap.IncrementalMapper, - callback: RefinementCallback = None, ): """Solves the VI bundle adjustment problem.""" bundle_adjuster = pycolmap.create_default_bundle_adjuster( @@ -86,6 +83,7 @@ def solve( # Setup callback if needed if vi_options.optim.use_callback: + callback = self._init_callback(mapper) pyceres_solver_options.callbacks = [callback] pyceres_solver_options.minimizer_progress_to_stdout = vi_options.optim.minimizer_progress_to_stdout @@ -96,6 +94,14 @@ def solve( summary = pyceres.SolverSummary() pyceres.solve(pyceres_solver_options, bundle_adjuster.problem, summary) print(summary.BriefReport()) + + def _init_callback(self, mapper: pycolmap.IncrementalMapper): + """Initialize the refinement callback to check pose changes.""" + frame_ids = sorted(mapper.reconstruction.frames.keys()) + poses = list(mapper.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) + + callback = RefinementCallback(poses) + return callback class GlobalBundleAdjustment: @@ -110,7 +116,6 @@ def run( pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, session: SingleSeqSession, - callback: RefinementCallback = None, ): """Entry point for running global bundle adjustment.""" gba = GlobalBundleAdjustment(session) @@ -118,7 +123,6 @@ def run( vi_options, pipeline_options, mapper, - callback, ) def adjust( @@ -126,7 +130,6 @@ def adjust( vi_options: VIOptimizerOptions, pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, - callback: RefinementCallback = None, ): assert mapper.reconstruction is not None @@ -158,7 +161,6 @@ def adjust( ba_config, mapper, self.session, - callback ) def _configure_ba_options(self, pipeline_options, num_reg_images): @@ -205,7 +207,6 @@ def refine( vi_options: VIOptimizerOptions, pipeline_options: pycolmap.IncrementalPipelineOptions, mapper: pycolmap.IncrementalMapper, - callback: RefinementCallback = None, ): # Configure triangulation options tri_options = pipeline_options.get_triangulation() @@ -218,9 +219,6 @@ def refine( # Configure mapper options mapper_options = pipeline_options.get_mapper() - if vi_options.optim.use_callback: - callback = self._init_callback(mapper) - # Iterative refinement for i in range(pipeline_options.ba_global_max_refinements): num_observations = mapper.reconstruction.compute_num_observations() @@ -230,7 +228,6 @@ def refine( pipeline_options, mapper, self.session, - callback, ) if vi_options.optim.normalize_reconstruction: @@ -243,12 +240,4 @@ def refine( logging.verbose(1, f"=> Changed observations: {changed:.6f}") if changed < pipeline_options.ba_global_max_refinement_change: - break - - def _init_callback(self, mapper: pycolmap.IncrementalMapper): - """Initialize the refinement callback to check pose changes.""" - frame_ids = sorted(mapper.reconstruction.frames.keys()) - poses = list(mapper.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) - callback = RefinementCallback(poses) - - return callback \ No newline at end of file + break \ No newline at end of file From 4ba092faa69e1d653980375df6fdb7ff82e6d1db Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Fri, 26 Sep 2025 15:41:02 +0200 Subject: [PATCH 328/665] bias opt --- defaults.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/defaults.yaml b/defaults.yaml index ffc9738..e4a87ff 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -45,7 +45,7 @@ optimization: optimize_scale: false optimize_gravity: false optimize_imu_from_rig: false - optimize_bias: false + optimize_bias: true gyro_infl: 1.0 acc_infl: 1.0 integration_noise_density: 0.05 From 2b225dcd1d94798a4e8d280cc72cd147a41da978 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 12:47:13 +0200 Subject: [PATCH 329/665] ruff edits --- lamaria/config/options.py | 65 ++--- lamaria/config/pipeline.py | 48 ++-- .../eval/create_empty_recon_from_estimate.py | 63 ++--- lamaria/eval/sparse_evaluation.py | 35 +-- .../pipeline/keyframing/keyframe_selection.py | 91 +++--- lamaria/pipeline/keyframing/to_colmap.py | 258 +++++++++--------- lamaria/pipeline/lamaria_reconstruction.py | 38 ++- lamaria/pipeline/optim/callback.py | 11 +- lamaria/pipeline/optim/imu.py | 51 ++-- lamaria/pipeline/optim/iterative_global_ba.py | 103 ++++--- lamaria/pipeline/optim/residual.py | 21 +- lamaria/pipeline/optim/session.py | 18 +- lamaria/pipeline/optim/triangulation.py | 68 +++-- lamaria/pipeline/optim/vi_optimization.py | 59 ++-- lamaria/utils/camera.py | 38 ++- lamaria/utils/control_point.py | 42 +-- lamaria/utils/estimate.py | 95 ++++--- lamaria/utils/general.py | 38 ++- lamaria/utils/imu.py | 46 ++-- lamaria/utils/metrics.py | 27 +- lamaria/utils/transformation.py | 69 ++--- run_pipeline.py | 76 +++--- tools/asl_folder_to_rosbag.py | 59 ++-- tools/download_lamaria.py | 91 +++--- tools/undistort_asl_folder.py | 30 +- tools/vrs_to_asl_folder.py | 67 +++-- 26 files changed, 873 insertions(+), 734 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index ea574d7..1f06ed1 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -2,8 +2,10 @@ from dataclasses import dataclass, field, replace from typing import Optional + from omegaconf import OmegaConf, open_dict + def _structured_merge_to_obj(cls, section) -> object: """ Merge a YAML section onto a structured @@ -19,17 +21,18 @@ def _structured_merge_to_obj(cls, section) -> object: @dataclass(slots=True) class MPSOptions: use_mps: bool = False - use_online_calibration: bool = False # when use_mps is true (for online calib file) - has_slam_drops: bool = False # check vrs json metadata file for each sequence + use_online_calibration: bool = ( + False # when use_mps is true (for online calib file) + ) + has_slam_drops: bool = ( + False # check vrs json metadata file for each sequence + ) @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> MPSOptions: + def load(cls, cfg: Optional[OmegaConf] = None) -> MPSOptions: if cfg is None: return cls() - + return _structured_merge_to_obj(cls, cfg) @@ -41,13 +44,10 @@ class SensorOptions: camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> "SensorOptions": + def load(cls, cfg: Optional[OmegaConf] = None) -> SensorOptions: if cfg is None: return cls() - + obj: SensorOptions = _structured_merge_to_obj(cls, cfg) return obj @@ -60,34 +60,30 @@ class EstimateToColmapOptions: @classmethod def load( - cls, + cls, cfg_mps: Optional[OmegaConf] = None, cfg_sensor: Optional[OmegaConf] = None, ) -> EstimateToColmapOptions: - if cfg_mps is None or cfg_sensor is None: return cls() - + base = cls() return replace( base, mps=MPSOptions.load(cfg_mps), - sensor=SensorOptions.load(cfg_sensor) + sensor=SensorOptions.load(cfg_sensor), ) # Keyframing options @dataclass(slots=True) class KeyframeSelectorOptions: - max_rotation: float = 20.0 # degrees - max_distance: float = 1.0 # meters - max_elapsed: int = int(1e9) # 1 second in ns + max_rotation: float = 20.0 # degrees + max_distance: float = 1.0 # meters + max_elapsed: int = int(1e9) # 1 second in ns @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> "KeyframeSelectorOptions": + def load(cls, cfg: Optional[OmegaConf] = None) -> KeyframeSelectorOptions: if cfg is None: return cls() @@ -95,7 +91,7 @@ def load( with open_dict(cfg): if "max_elapsed" in cfg and isinstance(cfg.max_elapsed, float): cfg.max_elapsed = int(cfg.max_elapsed) - + obj: KeyframeSelectorOptions = _structured_merge_to_obj(cls, cfg) return obj @@ -117,25 +113,23 @@ class TriangulatorOptions: filter_min_tri_angle: float = 1.5 @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> "TriangulatorOptions": + def load(cls, cfg: Optional[OmegaConf] = None) -> TriangulatorOptions: if cfg is None: return cls() - + return _structured_merge_to_obj(cls, cfg) # Optimization options @dataclass(slots=True) class OptCamOptions: - feature_std: float = 1.0 # in pixels + feature_std: float = 1.0 # in pixels optimize_focal_length: bool = False optimize_principal_point: bool = False optimize_extra_params: bool = False optimize_cam_from_rig: bool = False + @dataclass(slots=True) class OptIMUOptions: gyro_infl: float = 1.0 @@ -147,6 +141,7 @@ class OptIMUOptions: optimize_imu_from_rig: bool = False optimize_bias: bool = False + @dataclass(slots=True) class OptOptions: use_callback: bool = True @@ -155,6 +150,7 @@ class OptOptions: minimizer_progress_to_stdout: bool = True update_state_every_iteration: bool = True + @dataclass(slots=True) class VIOptimizerOptions: cam: OptCamOptions = field(default_factory=OptCamOptions) @@ -162,13 +158,10 @@ class VIOptimizerOptions: optim: OptOptions = field(default_factory=OptOptions) @classmethod - def load( - cls, - cfg: Optional[OmegaConf] = None - ) -> "VIOptimizerOptions": + def load(cls, cfg: Optional[OmegaConf] = None) -> VIOptimizerOptions: if cfg is None: return cls() - + base = cls() cam = _structured_merge_to_obj(OptCamOptions, cfg.cam) imu = _structured_merge_to_obj(OptIMUOptions, cfg.imu) @@ -179,4 +172,4 @@ def load( cam=cam, imu=imu, optim=optim, - ) \ No newline at end of file + ) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 22900b6..b988606 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -1,19 +1,26 @@ +from collections.abc import Sequence from pathlib import Path -from typing import Optional, Sequence -from omegaconf import OmegaConf, DictConfig +from typing import Optional + +from omegaconf import DictConfig, OmegaConf from .options import ( EstimateToColmapOptions, - VIOptimizerOptions, - TriangulatorOptions, KeyframeSelectorOptions, + TriangulatorOptions, + VIOptimizerOptions, ) + class PipelineOptions: def __init__(self) -> None: self._output_path: Path = Path("output/") - self._estimate_to_colmap_options: EstimateToColmapOptions = EstimateToColmapOptions() - self._keyframing_options: KeyframeSelectorOptions = KeyframeSelectorOptions() + self._estimate_to_colmap_options: EstimateToColmapOptions = ( + EstimateToColmapOptions() + ) + self._keyframing_options: KeyframeSelectorOptions = ( + KeyframeSelectorOptions() + ) self._triangulator_options: TriangulatorOptions = TriangulatorOptions() self._vi_optimizer_options: VIOptimizerOptions = VIOptimizerOptions() @@ -25,7 +32,9 @@ def load( """Load configuration from a YAML file and apply any overrides.""" cfg = OmegaConf.load(str(yaml)) if cli_overrides: - cfg = OmegaConf.merge(cfg, OmegaConf.from_dotlist(list(cli_overrides))) + cfg = OmegaConf.merge( + cfg, OmegaConf.from_dotlist(list(cli_overrides)) + ) OmegaConf.resolve(cfg) self._update_from_cfg(cfg) @@ -47,38 +56,38 @@ def _update_from_cfg(self, cfg: DictConfig) -> None: def output_path(self) -> Path: """Get the parent output path.""" return self._output_path - + @output_path.setter def output_path(self, path: Path) -> None: """Set the parent output path.""" self._output_path = path - + # Properties for estimate to COLMAP @property def estimate_to_colmap_options(self) -> EstimateToColmapOptions: return self._estimate_to_colmap_options - + @property def images(self) -> Path: return self._output_path / "images" - + @property def colmap_model(self) -> Path: return self._output_path / "initial_recon" - + # Properties for keyframing @property def keyframing_options(self) -> KeyframeSelectorOptions: return self._keyframing_options - + @property def keyframes(self) -> Path: return self._output_path / "keyframes" - + @property def kf_model(self) -> Path: return self._output_path / "keyframed_recon" - + # Properties for triangulation @property def triangulator_options(self) -> TriangulatorOptions: @@ -87,21 +96,20 @@ def triangulator_options(self) -> TriangulatorOptions: @property def hloc(self) -> Path: return self._output_path / "hloc" - + @property def pairs_file(self) -> Path: return self._output_path / "hloc" / "pairs.txt" - + @property def tri_model(self) -> Path: return self._output_path / "triangulated_recon" - + # Properties for visual-inertial optimization @property def vi_optimizer_options(self) -> VIOptimizerOptions: return self._vi_optimizer_options - + @property def optim_model(self) -> Path: return self._output_path / "optim_recon" - \ No newline at end of file diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index 97aa1f8..9038025 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -10,13 +10,13 @@ RIGHT_CAMERA_STREAM_LABEL, add_cameras_to_reconstruction, ) -from ..utils.general import ( - find_closest_timestamp, - delete_files_in_folder, -) from ..utils.estimate import ( round_ns, ) +from ..utils.general import ( + delete_files_in_folder, + find_closest_timestamp, +) from ..utils.transformation import ( get_t_imu_camera_from_json, ) @@ -31,7 +31,7 @@ def add_images_to_reconstruction( ): """Add images to an existing empty reconstruction from a pose estimate file.""" pose_data = [] - with open(estimate_file, "r") as f: + with open(estimate_file) as f: lines = f.readlines() if len(lines) == 0: @@ -47,27 +47,25 @@ def add_images_to_reconstruction( timestamp = round_ns(parts[0]) - tvec = np.array( - [float(parts[1]), - float(parts[2]), - float(parts[3])]) - q_xyzw = np.array([ - float(parts[4]), - float(parts[5]), - float(parts[6]), - float(parts[7]), - ]) - T_world_device = pycolmap.Rigid3d(pycolmap.Rotation3d(q_xyzw), - tvec) + tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) + q_xyzw = np.array( + [ + float(parts[4]), + float(parts[5]), + float(parts[6]), + float(parts[7]), + ] + ) + T_world_device = pycolmap.Rigid3d(pycolmap.Rotation3d(q_xyzw), tvec) pose_data.append((timestamp, T_world_device)) - with open(cp_json_file, "r") as f: + with open(cp_json_file) as f: cp_data = json.load(f) image_id = 1 rig = reconstruction.rig(rig_id=1) - + # if slam_input_imu is 1, then the poses are IMU poses # otherwise, the poses are left camera poses (monocular-cam0) (rig poses) if slam_input_imu == 1: @@ -82,12 +80,15 @@ def add_images_to_reconstruction( for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: ts_data = cp_data["timestamps"][label] ts_data_processed[label] = {int(k): v for k, v in ts_data.items()} - ts_data_processed[label]["sorted_keys"] = sorted(ts_data_processed[label].keys()) - - for i, (timestamp, pose) in tqdm(enumerate(pose_data), - total=len(pose_data), - desc="Adding images to reconstruction"): + ts_data_processed[label]["sorted_keys"] = sorted( + ts_data_processed[label].keys() + ) + for i, (timestamp, pose) in tqdm( + enumerate(pose_data), + total=len(pose_data), + desc="Adding images to reconstruction", + ): T_world_rig = pose * transform frame = pycolmap.Frame() frame.rig_id = rig.rig_id @@ -96,13 +97,13 @@ def add_images_to_reconstruction( images_to_add = [] - for label, camera_id in [(LEFT_CAMERA_STREAM_LABEL, 1), - (RIGHT_CAMERA_STREAM_LABEL, 2)]: - + for label, camera_id in [ + (LEFT_CAMERA_STREAM_LABEL, 1), + (RIGHT_CAMERA_STREAM_LABEL, 2), + ]: source_timestamps = ts_data_processed[label]["sorted_keys"] closest_timestamp = find_closest_timestamp( - source_timestamps, - timestamp + source_timestamps, timestamp ) if closest_timestamp is None: raise ValueError @@ -120,7 +121,7 @@ def add_images_to_reconstruction( images_to_add.append(im) image_id += 1 - + reconstruction.add_frame(frame) for im in images_to_add: reconstruction.add_image(im) @@ -135,7 +136,7 @@ def create_baseline_reconstruction( ): """Create a baseline reconstruction from a pose estimate file. The pose estimate file is assumed to be in the format: - + timestamp(ns) tx ty tz q_x q_y q_z q_w Args: diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index d760860..1cd0333 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -1,16 +1,15 @@ +import argparse import copy import os -import argparse -import numpy as np +from pathlib import Path from typing import Dict -from pathlib import Path +import numpy as np import pyceres import pycolmap import pycolmap.cost_functions from .. import logger - from ..utils.control_point import ( construct_control_points_from_json, get_cps_for_initial_alignment, @@ -27,18 +26,15 @@ def update_sim3d_scale(variables: Dict): def create_variables_for_sparse_evaluation( - control_points: Dict, - sim3d: pycolmap.Sim3d, - cp_reproj_std: float = 1.0 + control_points: Dict, sim3d: pycolmap.Sim3d, cp_reproj_std: float = 1.0 ) -> Dict: - variables = {} variables["control_points"] = copy.deepcopy(control_points) variables["sim3d"] = copy.deepcopy(sim3d) variables["cp_reproj_std"] = cp_reproj_std scale = copy.deepcopy(variables["sim3d"].scale) variables["log_scale"] = np.array(np.log(scale), dtype=np.float64) - + return variables @@ -64,7 +60,6 @@ def add_alignment_residuals( reconstruction: pycolmap.Reconstruction, variables: Dict, ) -> pyceres.Problem: - if ( variables["control_points"] is not None and variables["sim3d"] is not None @@ -79,7 +74,7 @@ def add_alignment_residuals( image = reconstruction.images[image_id] pose = image.cam_from_world() camera = reconstruction.cameras[image.camera_id] - + point2d = np.asarray(point2d, dtype=np.float64).reshape(2, 1) point2d_cov = np.eye(2) * pow(variables["cp_reproj_std"], 2) cost = pycolmap.cost_functions.ReprojErrorCost( @@ -113,7 +108,7 @@ def add_alignment_residuals( ], ) - logger.info(f"Added Point3dAlignmentCost and ReprojErrorCost costs") + logger.info("Added Point3dAlignmentCost and ReprojErrorCost costs") problem.set_manifold( variables["sim3d"].rotation.quat, @@ -129,14 +124,15 @@ def run_baseline_evaluation( output_path: Path, cp_reproj_std=1.0, ): - output_path.mkdir(parents=True, exist_ok=True) - + aligned_transformed_folder = output_path / "aligned_transformed" aligned_transformed_folder.mkdir(parents=True, exist_ok=True) - + control_points = construct_control_points_from_json(cp_json_file) - assert control_points is not None, "Control points could not be constructed from JSON" + assert control_points is not None, ( + "Control points could not be constructed from JSON" + ) run_control_point_triangulation_from_json( reconstruction_path, @@ -169,11 +165,10 @@ def run_baseline_evaluation( robust_sim3d, cp_reproj_std, ) - + reconstruction = pycolmap.Reconstruction(reconstruction_path) problem, solver_options, summary = get_problem_for_sparse_alignment( - reconstruction, - variables + reconstruction, variables ) pyceres.solve(solver_options, problem, summary) print(summary.BriefReport()) @@ -264,5 +259,5 @@ def run_baseline_evaluation( Path(args.output_path), args.cp_reproj_std, ) - + logger.info(f"Evaluation completed? {state}. Message: {msg}") diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 6392bd2..d49ef79 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -1,21 +1,21 @@ from __future__ import annotations import shutil -import numpy as np -from pathlib import Path from copy import deepcopy -from typing import Optional, Dict +from pathlib import Path +from typing import Dict, Optional +import numpy as np import pycolmap -from ..lamaria_reconstruction import LamariaReconstruction from ...config.options import KeyframeSelectorOptions from ...utils.transformation import get_magnitude_from_transform +from ..lamaria_reconstruction import LamariaReconstruction class KeyframeSelector: """Class to perform keyframe selection on a LamariaReconstruction object.""" - + def __init__( self, options: KeyframeSelectorOptions, @@ -23,8 +23,8 @@ def __init__( ): self.options = options self.init_data: LamariaReconstruction = data - self.init_recons = data.reconstruction # pycolmap.Reconstruction - self.timestamps = data.timestamps # frame id to timestamp mapping + self.init_recons = data.reconstruction # pycolmap.Reconstruction + self.timestamps = data.timestamps # frame id to timestamp mapping self.keyframed_data: LamariaReconstruction = LamariaReconstruction() self.keyframe_frame_ids: Optional[Dict[int, int]] = None @@ -36,14 +36,14 @@ def run( original_image_dir: Path, keyframes_dir: Path, ) -> LamariaReconstruction: - """ Entry point to run keyframing and copy keyframes into keyframe directory.""" - + """Entry point to run keyframing and copy keyframes into keyframe directory.""" + selector = KeyframeSelector(options, data) kf_recon = selector.run_keyframing() selector.copy_images_to_keyframes_dir(original_image_dir, keyframes_dir) return kf_recon - + def _select_keyframes(self): self.keyframe_frame_ids: Dict[int, int] = {} dr_dt = np.array([0.0, 0.0]) @@ -52,34 +52,45 @@ def _select_keyframes(self): init_frame_ids = sorted(self.init_recons.frames.keys()) new_frame_id = 1 - for i, (prev, curr) in enumerate(zip(init_frame_ids[:-1], init_frame_ids[1:])): + for i, (prev, curr) in enumerate( + zip(init_frame_ids[:-1], init_frame_ids[1:]) + ): if i == 0: self.keyframe_frame_ids[new_frame_id] = prev new_frame_id += 1 continue - current_rig_from_world = self.init_recons.frames[curr].rig_from_world - previous_rig_from_world = self.init_recons.frames[prev].rig_from_world - current_rig_from_previous_rig = current_rig_from_world * previous_rig_from_world.inverse() - - dr_dt += np.array(get_magnitude_from_transform(current_rig_from_previous_rig)) + current_rig_from_world = self.init_recons.frames[ + curr + ].rig_from_world + previous_rig_from_world = self.init_recons.frames[ + prev + ].rig_from_world + current_rig_from_previous_rig = ( + current_rig_from_world * previous_rig_from_world.inverse() + ) + + dr_dt += np.array( + get_magnitude_from_transform(current_rig_from_previous_rig) + ) dts += self.timestamps[curr] - self.timestamps[prev] - if dr_dt[0] > self.options.max_rotation or \ - dr_dt[1] > self.options.max_distance or \ - dts > self.options.max_elapsed: - + if ( + dr_dt[0] > self.options.max_rotation + or dr_dt[1] > self.options.max_distance + or dts > self.options.max_elapsed + ): self.keyframe_frame_ids[new_frame_id] = curr new_frame_id += 1 dr_dt = np.array([0.0, 0.0]) dts = 0.0 - + def _build_device_keyframed_reconstruction(self): old_rig = self.init_recons.rigs[1] new_rig = pycolmap.Rig(rig_id=1) camera_id = 1 - cam_map = {} # new to old - + cam_map = {} # new to old + ref_sensor_id = old_rig.ref_sensor_id.id cam_map[ref_sensor_id] = camera_id new_ref_sensor = self._clone_camera(ref_sensor_id, camera_id) @@ -94,13 +105,13 @@ def _build_device_keyframed_reconstruction(self): new_sensor_from_rig = deepcopy(sensor_from_rig) self.keyframed_data.reconstruction.add_camera(new_sensor) new_rig.add_sensor(new_sensor.sensor_id, new_sensor_from_rig) - + self.keyframed_data.reconstruction.add_rig(new_rig) image_id = 1 for new_fid, frame_id in self.keyframe_frame_ids.items(): old_frame = self.init_recons.frames[frame_id] - + new_frame = pycolmap.Frame() new_frame.rig_id = 1 new_frame.frame_id = new_fid @@ -129,7 +140,9 @@ def _build_device_keyframed_reconstruction(self): for img in images_to_add: self.keyframed_data.reconstruction.add_image(img) - def _clone_camera(self, old_camera_id: int, new_camera_id: int) -> pycolmap.Camera: + def _clone_camera( + self, old_camera_id: int, new_camera_id: int + ) -> pycolmap.Camera: old_camera = self.init_recons.cameras[old_camera_id] new_camera = pycolmap.Camera( model=old_camera.model, @@ -150,7 +163,7 @@ def _build_online_keyframed_reconstruction(self): old_rig = self.init_recons.rigs[old_rig_id] cam_id_map = {} - + # IMU cosplaying as a dummy camera old_ref_sensor_id = old_rig.ref_sensor_id.id new_ref_sensor = self._clone_camera(old_ref_sensor_id, camera_id) @@ -169,7 +182,7 @@ def _build_online_keyframed_reconstruction(self): self.keyframed_data.reconstruction.add_camera(new_sensor) cam_id_map[old_sensor_id] = camera_id camera_id += 1 - + new_sensor_from_rig = deepcopy(sensor_from_rig) new_rig.add_sensor(new_sensor.sensor_id, new_sensor_from_rig) @@ -196,22 +209,22 @@ def _build_online_keyframed_reconstruction(self): new_frame.add_data_id(new_image.data_id) images_to_add.append(new_image) image_id += 1 - + self.keyframed_data.reconstruction.add_frame(new_frame) for img in images_to_add: self.keyframed_data.reconstruction.add_image(img) def run_keyframing(self) -> LamariaReconstruction: - """ Function to run keyframing on lamaria reconstruction.""" + """Function to run keyframing on lamaria reconstruction.""" self._select_keyframes() - if len(self.init_recons.rigs.keys()) == 1: # device rig has been added + if len(self.init_recons.rigs.keys()) == 1: # device rig has been added self._build_device_keyframed_reconstruction() else: self._build_online_keyframed_reconstruction() - + # set timestamps keys with new frame ids self.keyframed_data.timestamps = { - new_fid: self.timestamps[old_fid] + new_fid: self.timestamps[old_fid] for new_fid, old_fid in self.keyframe_frame_ids.items() } @@ -224,12 +237,14 @@ def copy_images_to_keyframes_dir( images: Path, output: Path, ) -> Path: - """ Copy images corresponding to keyframes to a separate directory. + """Copy images corresponding to keyframes to a separate directory. Images are expected to be in `images/left` and `images/right` subdirectories. Check: `extract_images_from_vrs` in `lamaria/utils/general.py` for more details. """ if self.keyframe_frame_ids is None: - raise ValueError("Keyframes not selected yet. Run `run_keyframing` first.") + raise ValueError( + "Keyframes not selected yet. Run `run_keyframing` first." + ) if output.exists() and any(output.iterdir()): shutil.rmtree(output) @@ -240,11 +255,11 @@ def copy_images_to_keyframes_dir( frame = self.init_recons.frames[frame_id] for data_id in frame.data_ids: image = self.init_recons.images[data_id.id] - + subdir = "left" if image.name.startswith("1201-1") else "right" src_path = images / subdir / image.name dst_path = output / image.name - + shutil.copy2(src_path, dst_path) - return output \ No newline at end of file + return output diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index a2479c4..03165bc 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -1,27 +1,16 @@ -from typing import List, Tuple, Dict, Optional -from pathlib import Path -import pycolmap -from dataclasses import dataclass from bisect import bisect_left +from dataclasses import dataclass +from pathlib import Path +from typing import Dict, Optional, Tuple import projectaria_tools.core.mps as mps +import pycolmap from projectaria_tools.core import data_provider from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions from projectaria_tools.core.stream_id import StreamId from ... import logger -from ..lamaria_reconstruction import LamariaReconstruction from ...config.options import EstimateToColmapOptions -from ...utils.general import ( - get_matched_timestamps, - extract_images_from_vrs, -) -from ...utils.transformation import ( - get_t_imu_camera, - rigid3d_from_transform, - get_closed_loop_data_from_mps, - get_mps_poses_for_timestamps, -) from ...utils.camera import ( camera_colmap_from_calib, ) @@ -30,9 +19,21 @@ get_estimate_timestamps, get_rig_from_worlds_from_estimate, ) +from ...utils.general import ( + extract_images_from_vrs, + get_matched_timestamps, +) from ...utils.imu import ( get_imu_data_from_vrs, ) +from ...utils.transformation import ( + get_closed_loop_data_from_mps, + get_mps_poses_for_timestamps, + get_t_imu_camera, + rigid3d_from_transform, +) +from ..lamaria_reconstruction import LamariaReconstruction + @dataclass class PerFrameData: @@ -56,7 +57,6 @@ def __init__(self, options: EstimateToColmapOptions): self._right_imu_sid: StreamId | None = None self._per_frame_data: Dict[int, PerFrameData] = {} - @staticmethod def convert( options: EstimateToColmapOptions, @@ -67,12 +67,7 @@ def convert( ) -> LamariaReconstruction: """Entry point to run estimate/MPS to colmap conversion.""" to_colmap = EstimateToColmap(options) - return to_colmap.process( - vrs, - images, - estimate, - mps_folder - ) + return to_colmap.process(vrs, images, estimate, mps_folder) def process( self, @@ -81,7 +76,6 @@ def process( estimate: Optional[Path] = None, mps_folder: Optional[Path] = None, ) -> LamariaReconstruction: - self._init_data(vrs, images, estimate, mps_folder) if self.options.mps.use_online_calibration and self.options.mps.use_mps: @@ -94,21 +88,23 @@ def process( # IMU + timestamps ms = self._get_rectified_imu_data(mps_folder) self.data.imu_measurements = ms - self.data.timestamps = {fid: pfd.left_ts for fid, pfd in self._per_frame_data.items()} + self.data.timestamps = { + fid: pfd.left_ts for fid, pfd in self._per_frame_data.items() + } return self.data - + # -------- internal methods -------- def _init_data( self, vrs: Path, image_folder: Path, estimate: Optional[Path] = None, - mps_folder: Optional[Path] = None + mps_folder: Optional[Path] = None, ) -> None: """Initializes data providers and extracts images, timestamps and builds per-frame data object. Per-frame data is used to create the initial Lamaria reconstruction. """ - + # Initialize VRS data provider self._vrs_provider = data_provider.create_vrs_data_provider( vrs.as_posix() @@ -118,11 +114,15 @@ def _init_data( self._left_cam_sid = StreamId(self.options.sensor.left_cam_stream_id) self._right_cam_sid = StreamId(self.options.sensor.right_cam_stream_id) self._right_imu_sid = StreamId(self.options.sensor.right_imu_stream_id) - + # Initialize MPS data provider if needed if self.options.mps.use_mps: - assert mps_folder is not None, "MPS folder path must be provided if using MPS" - data_paths = mps.MpsDataPathsProvider(mps_folder.as_posix()).get_data_paths() + assert mps_folder is not None, ( + "MPS folder path must be provided if using MPS" + ) + data_paths = mps.MpsDataPathsProvider( + mps_folder.as_posix() + ).get_data_paths() self._mps_data_provider = mps.MpsDataProvider(data_paths) # Extract images from VRS file @@ -137,55 +137,51 @@ def _init_data( if self.options.mps.use_mps: timestamps = self._get_mps_timestamps() closed_loop_data = get_closed_loop_data_from_mps(mps_folder) - pose_timestamps = [ l for l, _ in timestamps ] - mps_poses = get_mps_poses_for_timestamps(closed_loop_data, pose_timestamps) + pose_timestamps = [l for l, _ in timestamps] + mps_poses = get_mps_poses_for_timestamps( + closed_loop_data, pose_timestamps + ) self._per_frame_data = self._build_per_frame_data_from_mps( - images, - timestamps, - mps_poses + images, timestamps, mps_poses ) else: - assert estimate is not None, "Estimate path must be provided if not using MPS" + assert estimate is not None, ( + "Estimate path must be provided if not using MPS" + ) flag = check_estimate_format(estimate) if not flag: raise ValueError("Estimate file format is incorrect.") timestamps = get_estimate_timestamps(estimate) if len(images) != len(timestamps): - images, timestamps = self._match_estimate_ts_to_images(images, timestamps) - + images, timestamps = self._match_estimate_ts_to_images( + images, timestamps + ) + rig_from_worlds = get_rig_from_worlds_from_estimate( estimate, ) self._per_frame_data = self._build_per_frame_data_from_estimate( - images, - timestamps, - rig_from_worlds + images, timestamps, rig_from_worlds ) def _build_per_frame_data_from_mps( - self, - images, - timestamps, - mps_poses + self, images, timestamps, mps_poses ) -> Dict[int, PerFrameData]: - per_frame_data: Dict[int, PerFrameData] = {} imu_stream_label = self._vrs_provider.get_label_from_stream_id( self._right_imu_sid ) - + if not self.options.mps.use_online_calibration: device_calibration = self._vrs_provider.get_device_calibration() - imu_calib = device_calibration.get_imu_calib( - imu_stream_label - ) + imu_calib = device_calibration.get_imu_calib(imu_stream_label) frame_id = 1 - for (left_img, right_img), (left_ts, right_ts), t_world_device \ - in zip(images, timestamps, mps_poses): - + for (left_img, right_img), (left_ts, right_ts), t_world_device in zip( + images, timestamps, mps_poses + ): if t_world_device is None: continue @@ -200,7 +196,7 @@ def _build_per_frame_data_from_mps( if calib.get_label() == imu_stream_label: imu_calib = calib break - + t_device_imu = imu_calib.get_transform_device_imu() t_world_imu = t_world_device @ t_device_imu t_imu_world = t_world_imu.inverse() @@ -211,7 +207,7 @@ def _build_per_frame_data_from_mps( right_ts=right_ts, left_img=left_img, right_img=right_img, - rig_from_world=rig_from_world + rig_from_world=rig_from_world, ) per_frame_data[frame_id] = pfd frame_id += 1 @@ -219,44 +215,46 @@ def _build_per_frame_data_from_mps( return per_frame_data def _build_per_frame_data_from_estimate( - self, - images, - timestamps, - rig_from_worlds + self, images, timestamps, rig_from_worlds ) -> Dict[int, PerFrameData]: - per_frame_data: Dict[int, PerFrameData] = {} - assert len(images) == len(timestamps) == len(rig_from_worlds), \ + assert len(images) == len(timestamps) == len(rig_from_worlds), ( "Number of images, timestamps and poses must be equal" - + ) + frame_id = 1 - - for (left_img, right_img), ts, rig_from_world \ - in zip(images, timestamps, rig_from_worlds): + + for (left_img, right_img), ts, rig_from_world in zip( + images, timestamps, rig_from_worlds + ): pfd = PerFrameData( left_ts=ts, right_ts=ts, left_img=left_img, right_img=right_img, - rig_from_world=rig_from_world + rig_from_world=rig_from_world, ) per_frame_data[frame_id] = pfd frame_id += 1 - + return per_frame_data - - def _images_from_vrs(self, folder: Path, wrt_to: Path, ext: str =".jpg") -> List[Path]: + + def _images_from_vrs( + self, folder: Path, wrt_to: Path, ext: str = ".jpg" + ) -> list[Path]: if not folder.is_dir(): return [] images = sorted(n for n in folder.iterdir() if n.suffix == ext) images = [n.relative_to(wrt_to) for n in images] return images - def _ts_from_vrs(self, sid: StreamId) -> List[int]: + def _ts_from_vrs(self, sid: StreamId) -> list[int]: """Timestamps in nanoseconds""" - return sorted(self._vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME)) + return sorted( + self._vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME) + ) - def _get_images(self, images: Path) -> List[Tuple[Path, Path]]: + def _get_images(self, images: Path) -> list[Tuple[Path, Path]]: left_img_dir = images / "left" right_img_dir = images / "right" @@ -265,11 +263,13 @@ def _get_images(self, images: Path) -> List[Tuple[Path, Path]]: return list(zip(left_images, right_images)) - def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: + def _get_mps_timestamps(self, max_diff=1e6) -> list[Tuple[int, int]]: L = self._ts_from_vrs(self._left_cam_sid) R = self._ts_from_vrs(self._right_cam_sid) if not self.options.mps.has_slam_drops: - assert len(L) == len(R), "Unequal number of left and right timestamps" + assert len(L) == len(R), ( + "Unequal number of left and right timestamps" + ) matched = list(zip(L, R)) if not all(abs(l - r) < max_diff for l, r in matched): logger.warning( @@ -279,32 +279,34 @@ def _get_mps_timestamps(self, max_diff=1e6) -> List[Tuple[int, int]]: matched = get_matched_timestamps(L, R, max_diff) return matched - + def _match_estimate_ts_to_images( self, - images: List[Tuple[Path, Path]], - est_timestamps: List[int], - max_diff: int = 1000000, # 1 ms - ) -> Tuple[List[Tuple[Path, Path]], List[int]]: - + images: list[Tuple[Path, Path]], + est_timestamps: list[int], + max_diff: int = 1000000, # 1 ms + ) -> Tuple[list[Tuple[Path, Path]], list[int]]: left_ts = self._ts_from_vrs(self._left_cam_sid) - assert len(images) == len(left_ts), \ + assert len(images) == len(left_ts), ( "Number of images and left timestamps must be equal" - + ) + order = sorted(range(len(left_ts)), key=lambda i: left_ts[i]) left_ts = [left_ts[i] for i in order] images = [images[i] for i in order] - - matched_images: List[Tuple[Path, Path]] = [] - matched_timestamps: List[int] = [] + + matched_images: list[Tuple[Path, Path]] = [] + matched_timestamps: list[int] = [] # estimate timestamps will be in nanoseconds like vrs timestamps for est in est_timestamps: idx = bisect_left(left_ts, est) cand_idxs = [] - if idx > 0: cand_idxs.append(idx - 1) - if idx < len(left_ts): cand_idxs.append(idx) + if idx > 0: + cand_idxs.append(idx - 1) + if idx < len(left_ts): + cand_idxs.append(idx) if not cand_idxs: continue @@ -315,23 +317,38 @@ def _match_estimate_ts_to_images( matched_images.append(images[best]) matched_timestamps.append(left_ts[best]) - + return matched_images, matched_timestamps - def _get_dummy_imu_params(self) -> Tuple[int, int, List[float]]: + def _get_dummy_imu_params(self) -> Tuple[int, int, list[float]]: """Generates dummy IMU camera parameters for COLMAP.""" width = 640 height = 480 - random_params = [241.604, 241.604, 322.895, 240.444, \ - 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, \ - 0.0, 0.0, 0.0, 0.0, 0.0] - + random_params = [ + 241.604, + 241.604, + 322.895, + 240.444, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + ] + return width, height, random_params def _add_device_sensors(self) -> None: """Adds a new rig with device calibrated sensors. The rig is consistent across all frames - + Camera ID layout: rig_id=1 -> (imu=1, left=2, right=3) """ @@ -339,10 +356,8 @@ def _add_device_sensors(self) -> None: imu_stream_label = self._vrs_provider.get_label_from_stream_id( self._right_imu_sid ) - imu_calib = device_calibration.get_imu_calib( - imu_stream_label - ) - + imu_calib = device_calibration.get_imu_calib(imu_stream_label) + rig = pycolmap.Rig(rig_id=1) w, h, p = self._get_dummy_imu_params() @@ -357,16 +372,9 @@ def _add_device_sensors(self) -> None: self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) - for cam_id, sid in \ - [(2, self._left_cam_sid), - (3, self._right_cam_sid) - ]: - stream_label = self._vrs_provider.get_label_from_stream_id( - sid - ) - camera_calib = device_calibration.get_camera_calib( - stream_label - ) + for cam_id, sid in [(2, self._left_cam_sid), (3, self._right_cam_sid)]: + stream_label = self._vrs_provider.get_label_from_stream_id(sid) + camera_calib = device_calibration.get_camera_calib(stream_label) cam = camera_colmap_from_calib(camera_calib) cam.camera_id = cam_id @@ -376,10 +384,10 @@ def _add_device_sensors(self) -> None: ) t_camera_imu = t_imu_camera.inverse() sensor_from_rig = rigid3d_from_transform(t_camera_imu) - + self.data.reconstruction.add_camera(cam) rig.add_sensor(cam.sensor_id, sensor_from_rig) - + self.data.reconstruction.add_rig(rig) def _add_online_sensors(self) -> None: @@ -424,15 +432,9 @@ def _add_online_sensors(self) -> None: imu_calib = calib break - for sid in \ - [self._left_cam_sid, self._right_cam_sid - ]: - stream_label = self._vrs_provider.get_label_from_stream_id( - sid - ) - camera_calib = calibration.get_camera_calib( - stream_label - ) + for sid in [self._left_cam_sid, self._right_cam_sid]: + stream_label = self._vrs_provider.get_label_from_stream_id(sid) + camera_calib = calibration.get_camera_calib(stream_label) cam = camera_colmap_from_calib(camera_calib) cam.camera_id = sensor_id sensor_id += 1 @@ -459,7 +461,7 @@ def _add_device_frames(self) -> None: frame.rig_id = rig.rig_id frame.frame_id = fid frame.rig_from_world = pfd.rig_from_world - + images_to_add = [] for cam_id, img_path in [(2, pfd.left_img), (3, pfd.right_img)]: im = pycolmap.Image( @@ -479,7 +481,7 @@ def _add_device_frames(self) -> None: def _add_online_frames(self) -> None: """Adds frame data for each rig, each rig has its own online calibrated sensors - + Frame ID layout: fid=1 -> (imu=1, left=2, right=3), (image IDs: 1, 2); fid=2 -> (imu=4, left=5, right=6), (image IDs: 3, 4); @@ -500,7 +502,10 @@ def _add_online_frames(self) -> None: left_cam_id = 3 * fid - 1 right_cam_id = 3 * fid - for cam_id, img_path in [(left_cam_id, pfd.left_img), (right_cam_id, pfd.right_img)]: + for cam_id, img_path in [ + (left_cam_id, pfd.left_img), + (right_cam_id, pfd.right_img), + ]: im = pycolmap.Image( str(img_path), pycolmap.Point2DList(), @@ -511,7 +516,7 @@ def _add_online_frames(self) -> None: frame.add_data_id(im.data_id) images_to_add.append(im) image_id += 1 - + self.data.reconstruction.add_frame(frame) for im in images_to_add: self.data.reconstruction.add_image(im) @@ -521,9 +526,10 @@ def _get_rectified_imu_data( mps_folder: Optional[Path] = None, ) -> pycolmap.ImuMeasurements: """Generates rectified IMU data from VRS file""" - if self.options.mps.use_online_calibration \ - and self.options.mps.use_mps: - assert mps_folder is not None, "MPS folder path must be provided if using MPS" + if self.options.mps.use_online_calibration and self.options.mps.use_mps: + assert mps_folder is not None, ( + "MPS folder path must be provided if using MPS" + ) ms = get_imu_data_from_vrs( self._vrs_provider, mps_folder, diff --git a/lamaria/pipeline/lamaria_reconstruction.py b/lamaria/pipeline/lamaria_reconstruction.py index 639f045..98fda19 100644 --- a/lamaria/pipeline/lamaria_reconstruction.py +++ b/lamaria/pipeline/lamaria_reconstruction.py @@ -1,7 +1,9 @@ +from pathlib import Path +from typing import Dict + import numpy as np import pycolmap -from typing import Dict -from pathlib import Path + class LamariaReconstruction: def __init__(self) -> None: @@ -13,13 +15,17 @@ def __init__(self) -> None: def read( input_folder: Path, ) -> "LamariaReconstruction": - assert input_folder.exists(), f"Input folder {input_folder} does not exist" + assert input_folder.exists(), ( + f"Input folder {input_folder} does not exist" + ) instance = LamariaReconstruction() instance.reconstruction = pycolmap.Reconstruction(input_folder) - + ts_path = input_folder / "timestamps.txt" - assert ts_path.exists(), f"Timestamps file {ts_path} does not exist in {input_folder}" - with open(ts_path, 'r') as f: + assert ts_path.exists(), ( + f"Timestamps file {ts_path} does not exist in {input_folder}" + ) + with open(ts_path) as f: lines = f.readlines() instance.timestamps = {} for line in lines: @@ -27,14 +33,17 @@ def read( continue frame_id, ts = line.strip().split() instance.timestamps[int(frame_id)] = int(ts) - + rectified_imu_data_npy = input_folder / "rectified_imu_data.npy" - assert rectified_imu_data_npy.exists(), \ + assert rectified_imu_data_npy.exists(), ( f"Rectified IMU data file {rectified_imu_data_npy} \ does not exist in {input_folder}" + ) rectified_imu_data = np.load(rectified_imu_data_npy, allow_pickle=True) - instance.imu_measurements = pycolmap.ImuMeasurements(rectified_imu_data.tolist()) - + instance.imu_measurements = pycolmap.ImuMeasurements( + rectified_imu_data.tolist() + ) + return instance def write( @@ -43,19 +52,20 @@ def write( ) -> None: output_folder.mkdir(parents=True, exist_ok=True) self.reconstruction.write(output_folder.as_posix()) - + ts_path = output_folder / "timestamps.txt" frame_ids = sorted(self.timestamps.keys()) # sanity check of frame ids in reconstruction and timestamps recon_frame_ids = np.array(sorted(self.reconstruction.frames.keys())) - assert np.array_equal(np.array(frame_ids), recon_frame_ids), \ + assert np.array_equal(np.array(frame_ids), recon_frame_ids), ( "Frame IDs in reconstruction and timestamps do not match" + ) - with open(ts_path, 'w') as f: + with open(ts_path, "w") as f: f.write("# FrameID Timestamp(ns)\n") for frame_id in frame_ids: f.write(f"{frame_id} {self.timestamps[frame_id]}\n") rectified_imu_data_npy = output_folder / "rectified_imu_data.npy" - np.save(rectified_imu_data_npy, self.imu_measurements.data) \ No newline at end of file + np.save(rectified_imu_data_npy, self.imu_measurements.data) diff --git a/lamaria/pipeline/optim/callback.py b/lamaria/pipeline/optim/callback.py index 4e14677..816a221 100644 --- a/lamaria/pipeline/optim/callback.py +++ b/lamaria/pipeline/optim/callback.py @@ -1,16 +1,17 @@ - from copy import deepcopy -from typing import List, Tuple +from typing import Tuple + import numpy as np -import pycolmap import pyceres +import pycolmap from ... import logger + class RefinementCallback(pyceres.IterationCallback): def __init__( self, - poses: List[pycolmap.Rigid3d], + poses: list[pycolmap.Rigid3d], min_pose_change: Tuple[float, float] = (0.001, 0.000001), min_iterations: int = 2, ): @@ -46,4 +47,4 @@ def __call__(self, summary: pyceres.IterationSummary): q99 <= self.min_pose_change ): return pyceres.CallbackReturnType.SOLVER_TERMINATE_SUCCESSFULLY - return pyceres.CallbackReturnType.SOLVER_CONTINUE \ No newline at end of file + return pyceres.CallbackReturnType.SOLVER_CONTINUE diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 963ff28..52f7f03 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -1,10 +1,9 @@ -import numpy as np -import pycolmap from typing import Dict +import numpy as np +import pycolmap from tqdm import tqdm -from ... import logger from ...config.options import OptIMUOptions from ..lamaria_reconstruction import LamariaReconstruction @@ -13,24 +12,27 @@ def load_preintegrated_imu_measurements( options: OptIMUOptions, data: LamariaReconstruction, ) -> Dict[int, pycolmap.PreintegratedImuMeasurement]: - preintegrated_measurements = {} imu_measurements = data.imu_measurements - + colmap_imu_opts = pycolmap.ImuPreintegrationOptions() - colmap_imu_opts.integration_noise_density = options.integration_noise_density + colmap_imu_opts.integration_noise_density = ( + options.integration_noise_density + ) imu_calib = load_imu_calibration(options.gyro_infl, options.acc_infl) frame_ids = sorted(data.reconstruction.frames.keys()) timestamps = [data.timestamps[fid] for fid in frame_ids] - assert len(frame_ids) >= 2, "Need at least two frames to compute preinteg measurements" + assert len(frame_ids) >= 2, ( + "Need at least two frames to compute preinteg measurements" + ) ts_sec = np.asarray(timestamps, dtype=np.float64) / 1e9 for k in tqdm( - range(len(frame_ids) - 1), # skip the last frame - desc="Loading preintegrated measurements" + range(len(frame_ids) - 1), # skip the last frame + desc="Loading preintegrated measurements", ): i = frame_ids[k] t1, t2 = ts_sec[k], ts_sec[k + 1] @@ -48,10 +50,11 @@ def load_preintegrated_imu_measurements( return preintegrated_measurements + def load_imu_states( data: LamariaReconstruction, ) -> Dict[int, pycolmap.ImuState]: - imu_states = {} + imu_states = {} frame_ids = sorted(data.reconstruction.frames.keys()) timestamps = [data.timestamps[fid] for fid in frame_ids] @@ -60,34 +63,31 @@ def load_imu_states( ts_sec = np.asarray(timestamps, dtype=np.float64) / 1e9 - for k in tqdm( - range(len(frame_ids) - 1), - desc="Loading IMU states" - ): + for k in tqdm(range(len(frame_ids) - 1), desc="Loading IMU states"): i = frame_ids[k] j = frame_ids[k + 1] - + t1, t2 = ts_sec[k], ts_sec[k + 1] dt = t2 - t1 if dt == 0: raise ValueError(f"Zero dt between frames {i} and {j}") - + pi = data.reconstruction.frames[i].rig_from_world.inverse().translation pj = data.reconstruction.frames[j].rig_from_world.inverse().translation vel = (pj - pi) / dt imu_states[i] = pycolmap.ImuState() imu_states[i].set_velocity(vel) - + imu_states[frame_ids[-1]] = pycolmap.ImuState() vel = imu_states[frame_ids[-2]].velocity imu_states[frame_ids[-1]].set_velocity(vel) return imu_states + def load_imu_calibration( - gyro_infl: float = 1.0, - acc_infl: float = 1.0 + gyro_infl: float = 1.0, acc_infl: float = 1.0 ) -> pycolmap.ImuCalibration: """Load Aria IMU calibration parameters. Here: https://facebookresearch.github.io/projectaria_tools/docs/tech_insights""" @@ -97,14 +97,9 @@ def load_imu_calibration( imu_calib.acc_noise_density = ( 0.8e-4 * imu_calib.gravity_magnitude * acc_infl ) - imu_calib.gyro_noise_density = ( - 1e-2 * (np.pi / 180.0) * gyro_infl - ) + imu_calib.gyro_noise_density = 1e-2 * (np.pi / 180.0) * gyro_infl imu_calib.acc_bias_random_walk_sigma = ( - 3.5e-5 - * imu_calib.gravity_magnitude - * np.sqrt(353) - * acc_infl + 3.5e-5 * imu_calib.gravity_magnitude * np.sqrt(353) * acc_infl ) # accel_right BW = 353 imu_calib.gyro_bias_random_walk_sigma = ( 1.3e-3 * (np.pi / 180.0) * np.sqrt(116) * gyro_infl @@ -112,5 +107,5 @@ def load_imu_calibration( imu_calib.acc_saturation_max = 8.0 * imu_calib.gravity_magnitude imu_calib.gyro_saturation_max = 1000.0 * (np.pi / 180.0) imu_calib.imu_rate = 1000.0 - - return imu_calib \ No newline at end of file + + return imu_calib diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index 764222f..c19aa08 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -1,25 +1,29 @@ +import numpy as np +import pyceres import pycolmap from pycolmap import logging -import pyceres -import numpy as np from ... import logger -from .session import SingleSeqSession -from .residual import add_imu_residuals_to_problem -from .callback import RefinementCallback from ...config.options import VIOptimizerOptions +from .callback import RefinementCallback +from .residual import add_imu_residuals_to_problem +from .session import SingleSeqSession def apply_constraints(problem, session: SingleSeqSession): """Apply rig constraints to the problem for fixing gauge freedom.""" # Fix the first rig pose frame_ids = sorted(session.data.reconstruction.frames.keys()) - first_frame_rfw = session.data.reconstruction.frames[frame_ids[0]].rig_from_world + first_frame_rfw = session.data.reconstruction.frames[ + frame_ids[0] + ].rig_from_world problem.set_parameter_block_constant(first_frame_rfw.rotation.quat) problem.set_parameter_block_constant(first_frame_rfw.translation) # Fix 1 DoF translation of the second rig - second_frame_rfw = session.data.reconstruction.frames[frame_ids[1]].rig_from_world + second_frame_rfw = session.data.reconstruction.frames[ + frame_ids[1] + ].rig_from_world problem.set_manifold( second_frame_rfw.translation, pyceres.SubsetManifold(3, np.array([0])), @@ -28,10 +32,10 @@ def apply_constraints(problem, session: SingleSeqSession): class VIBundleAdjuster: - """Visual-Inertial Bundle Adjuster class that - adds visual and IMU residuals to the + """Visual-Inertial Bundle Adjuster class that + adds visual and IMU residuals to the optimization problem.""" - + def __init__(self, session: SingleSeqSession): self.session = session @@ -65,40 +69,48 @@ def solve( ba_config, mapper.reconstruction, ) - + problem = bundle_adjuster.problem solver_options = ba_options.create_solver_options( - ba_config, - bundle_adjuster.problem + ba_config, bundle_adjuster.problem ) pyceres_solver_options = pyceres.SolverOptions(solver_options) - + problem = add_imu_residuals_to_problem( vi_options.imu, self.session, problem, ) # problem = apply_constraints(problem, self.session) - + # Setup callback if needed if vi_options.optim.use_callback: callback = self._init_callback(mapper) pyceres_solver_options.callbacks = [callback] - pyceres_solver_options.minimizer_progress_to_stdout = vi_options.optim.minimizer_progress_to_stdout - pyceres_solver_options.update_state_every_iteration = vi_options.optim.update_state_every_iteration - pyceres_solver_options.max_num_iterations = vi_options.optim.max_num_iterations - + pyceres_solver_options.minimizer_progress_to_stdout = ( + vi_options.optim.minimizer_progress_to_stdout + ) + pyceres_solver_options.update_state_every_iteration = ( + vi_options.optim.update_state_every_iteration + ) + pyceres_solver_options.max_num_iterations = ( + vi_options.optim.max_num_iterations + ) + # Solve summary = pyceres.SolverSummary() pyceres.solve(pyceres_solver_options, bundle_adjuster.problem, summary) print(summary.BriefReport()) - + def _init_callback(self, mapper: pycolmap.IncrementalMapper): """Initialize the refinement callback to check pose changes.""" frame_ids = sorted(mapper.reconstruction.frames.keys()) - poses = list(mapper.reconstruction.frames[frame_id].rig_from_world for frame_id in frame_ids) + poses = list( + mapper.reconstruction.frames[frame_id].rig_from_world + for frame_id in frame_ids + ) callback = RefinementCallback(poses) return callback @@ -106,7 +118,7 @@ def _init_callback(self, mapper: pycolmap.IncrementalMapper): class GlobalBundleAdjustment: """Global bundle adjustment with visual-inertial constraints.""" - + def __init__(self, session: SingleSeqSession): self.session = session @@ -124,7 +136,7 @@ def run( pipeline_options, mapper, ) - + def adjust( self, vi_options: VIOptimizerOptions, @@ -132,19 +144,20 @@ def adjust( mapper: pycolmap.IncrementalMapper, ): assert mapper.reconstruction is not None - + reg_image_ids = mapper.reconstruction.reg_image_ids() if len(reg_image_ids) < 2: - logger.warning("At least two images must be registered for global bundle-adjustment") + logger.warning( + "At least two images must be registered for global bundle-adjustment" + ) ba_options = self._configure_ba_options( - pipeline_options, - len(reg_image_ids) + pipeline_options, len(reg_image_ids) ) # Avoid negative depths mapper.observation_manager.filter_observations_with_negative_depth() - + # Setting up bundle adjustment configuration ba_config = pycolmap.BundleAdjustmentConfig() for frame_id in mapper.reconstruction.reg_frame_ids(): @@ -153,7 +166,7 @@ def adjust( if data_id.sensor_id.type != pycolmap.SensorType.CAMERA: continue ba_config.add_image(data_id.id) - + # Run bundle adjustment VIBundleAdjuster.run( vi_options, @@ -162,13 +175,13 @@ def adjust( mapper, self.session, ) - + def _configure_ba_options(self, pipeline_options, num_reg_images): """Configure bundle adjustment options based on number of registered images""" ba_options = pipeline_options.get_global_bundle_adjustment() ba_options.print_summary = True - ba_options.refine_rig_from_world = True # Refine rig poses - + ba_options.refine_rig_from_world = True # Refine rig poses + # Use stricter convergence criteria for first registered images if num_reg_images < 10: ba_options.solver_options.function_tolerance /= 10 @@ -183,10 +196,10 @@ def _configure_ba_options(self, pipeline_options, num_reg_images): class IterativeRefinement: """Iterative global refinement through repeated global bundle adjustments.""" - + def __init__(self, session: SingleSeqSession): self.session = session - + @staticmethod def run( vi_options: VIOptimizerOptions, @@ -213,12 +226,13 @@ def refine( mapper.complete_and_merge_tracks(tri_options) num_retriangulated_observations = mapper.retriangulate(tri_options) logging.verbose( - 1, f"=> Retriangulated observations: {num_retriangulated_observations}" + 1, + f"=> Retriangulated observations: {num_retriangulated_observations}", ) # Configure mapper options mapper_options = pipeline_options.get_mapper() - + # Iterative refinement for i in range(pipeline_options.ba_global_max_refinements): num_observations = mapper.reconstruction.compute_num_observations() @@ -232,12 +246,17 @@ def refine( if vi_options.optim.normalize_reconstruction: mapper.reconstruction.normalize() - - num_changed_observations = mapper.complete_and_merge_tracks(tri_options) + + num_changed_observations = mapper.complete_and_merge_tracks( + tri_options + ) num_changed_observations += mapper.filter_points(mapper_options) - changed = (num_changed_observations / num_observations - if num_observations > 0 else 0) - + changed = ( + num_changed_observations / num_observations + if num_observations > 0 + else 0 + ) + logging.verbose(1, f"=> Changed observations: {changed:.6f}") if changed < pipeline_options.ba_global_max_refinement_change: - break \ No newline at end of file + break diff --git a/lamaria/pipeline/optim/residual.py b/lamaria/pipeline/optim/residual.py index b8d7e38..6dbcd17 100644 --- a/lamaria/pipeline/optim/residual.py +++ b/lamaria/pipeline/optim/residual.py @@ -3,8 +3,8 @@ import pycolmap from tqdm import tqdm -from .session import SingleSeqSession from ...config.options import OptIMUOptions +from .session import SingleSeqSession def add_imu_residuals_to_problem( @@ -13,12 +13,12 @@ def add_imu_residuals_to_problem( problem, ): loss = pyceres.TrivialLoss() - + frame_ids = sorted(session.data.reconstruction.frames.keys()) - + for k in tqdm( range(len(session.preintegrated_imu_measurements)), - desc="Adding IMU residuals" + desc="Adding IMU residuals", ): i = frame_ids[k] j = frame_ids[k + 1] @@ -45,7 +45,7 @@ def add_imu_residuals_to_problem( session.imu_states[j].data, ], ) - + problem = setup_manifolds_and_constraints( imu_options, session, @@ -53,7 +53,7 @@ def add_imu_residuals_to_problem( ) return problem - + def setup_manifolds_and_constraints( imu_options: OptIMUOptions, @@ -63,10 +63,9 @@ def setup_manifolds_and_constraints( """Setup manifolds and parameter constraints""" problem.set_manifold(session.gravity, pyceres.SphereManifold(3)) problem.set_manifold( - session.imu_from_rig.rotation.quat, - pyceres.EigenQuaternionManifold() + session.imu_from_rig.rotation.quat, pyceres.EigenQuaternionManifold() ) - + # Apply optimization constraints based on configuration if not imu_options.optimize_scale: problem.set_parameter_block_constant(session.log_scale) @@ -82,5 +81,5 @@ def setup_manifolds_and_constraints( session.imu_states[frame_id].data, pyceres.SubsetManifold(9, constant_idxs), ) - - return problem \ No newline at end of file + + return problem diff --git a/lamaria/pipeline/optim/session.py b/lamaria/pipeline/optim/session.py index a066e81..2a3be7f 100644 --- a/lamaria/pipeline/optim/session.py +++ b/lamaria/pipeline/optim/session.py @@ -1,13 +1,15 @@ from __future__ import annotations -import pycolmap + import numpy as np +import pycolmap +from ...config.options import OptIMUOptions +from ..lamaria_reconstruction import LamariaReconstruction from .imu import ( load_imu_states, load_preintegrated_imu_measurements, ) -from ...config.options import OptIMUOptions -from ..lamaria_reconstruction import LamariaReconstruction + class SingleSeqSession: def __init__( @@ -19,12 +21,10 @@ def __init__( self._init_imu_data(imu_options) def _init_imu_data(self, imu_options): - self.preintegrated_imu_measurements = \ - load_preintegrated_imu_measurements( - imu_options, - self.data - ) + self.preintegrated_imu_measurements = ( + load_preintegrated_imu_measurements(imu_options, self.data) + ) self.imu_states = load_imu_states(self.data) self.imu_from_rig = pycolmap.Rigid3d() self.gravity = np.array([0.0, 0.0, -1.0]) - self.log_scale = np.array([0.0]) \ No newline at end of file + self.log_scale = np.array([0.0]) diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index fac9efa..7538035 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -4,12 +4,11 @@ from pathlib import Path import pycolmap - from hloc import ( extract_features, match_features, pairs_from_retrieval, - triangulation + triangulation, ) from ... import logger @@ -19,13 +18,18 @@ def set_colmap_triangulation_options( options: TriangulatorOptions, ) -> pycolmap.IncrementalPipelineOptions: - colmap_options = pycolmap.IncrementalPipelineOptions() - colmap_options.triangulation.merge_max_reproj_error = options.merge_max_reproj_error - colmap_options.triangulation.complete_max_reproj_error = options.complete_max_reproj_error + colmap_options.triangulation.merge_max_reproj_error = ( + options.merge_max_reproj_error + ) + colmap_options.triangulation.complete_max_reproj_error = ( + options.complete_max_reproj_error + ) colmap_options.triangulation.min_angle = options.min_angle - colmap_options.mapper.filter_max_reproj_error = options.filter_max_reproj_error + colmap_options.mapper.filter_max_reproj_error = ( + options.filter_max_reproj_error + ) colmap_options.mapper.filter_min_tri_angle = options.filter_min_tri_angle return colmap_options @@ -55,17 +59,20 @@ def pairs_from_frames(recon: pycolmap.Reconstruction): return frame_pairs, adj_pairs + def postprocess_pairs_with_reconstruction( - sfm_pairs_file: Path, - reconstruction: pycolmap.Reconstruction | Path + sfm_pairs_file: Path, reconstruction: pycolmap.Reconstruction | Path ): - recon = (reconstruction if isinstance(reconstruction, pycolmap.Reconstruction) - else pycolmap.Reconstruction(reconstruction.as_posix())) + recon = ( + reconstruction + if isinstance(reconstruction, pycolmap.Reconstruction) + else pycolmap.Reconstruction(reconstruction.as_posix()) + ) frame_pairs, adj_pairs = pairs_from_frames(recon) existing = set() - with open(sfm_pairs_file, "r") as f: + with open(sfm_pairs_file) as f: for line in f: a, b = line.strip().split() existing.add((a, b)) @@ -80,34 +87,43 @@ def postprocess_pairs_with_reconstruction( def run( options: TriangulatorOptions, - reference_model: Path, # reconstruction path + reference_model: Path, # reconstruction path keyframes: Path, hloc_dir: Path, pairs_path: Path, triangulated_model_path: Path, ) -> Path: - if not keyframes.exists(): raise FileNotFoundError(f"keyframes_dir not found at {keyframes}") - + hloc_dir.mkdir(parents=True, exist_ok=True) if not reference_model.exists(): - raise FileNotFoundError(f"reference_model not found at {reference_model}") + raise FileNotFoundError( + f"reference_model not found at {reference_model}" + ) retrieval_conf = extract_features.confs[options.retrieval_conf] - feature_conf = extract_features.confs[options.feature_conf] - matcher_conf = match_features.confs[options.matcher_conf] - - logger.info("HLOC confs: retrieval=%s, features=%s, matcher=%s", - options.retrieval_conf, - options.feature_conf, - options.matcher_conf) + feature_conf = extract_features.confs[options.feature_conf] + matcher_conf = match_features.confs[options.matcher_conf] + + logger.info( + "HLOC confs: retrieval=%s, features=%s, matcher=%s", + options.retrieval_conf, + options.feature_conf, + options.matcher_conf, + ) - retrieval_path = extract_features.main(retrieval_conf, image_dir=keyframes, export_dir=hloc_dir) - features_path = extract_features.main(feature_conf, image_dir=keyframes, export_dir=hloc_dir) + retrieval_path = extract_features.main( + retrieval_conf, image_dir=keyframes, export_dir=hloc_dir + ) + features_path = extract_features.main( + feature_conf, image_dir=keyframes, export_dir=hloc_dir + ) - pairs_from_retrieval.main(retrieval_path, pairs_path, options.num_retrieval_matches) + pairs_from_retrieval.main( + retrieval_path, pairs_path, options.num_retrieval_matches + ) postprocess_pairs_with_reconstruction(pairs_path, reference_model) matches_path = match_features.main( @@ -129,4 +145,4 @@ def run( mapper_options=colmap_opts, ) - return triangulated_model_path \ No newline at end of file + return triangulated_model_path diff --git a/lamaria/pipeline/optim/vi_optimization.py b/lamaria/pipeline/optim/vi_optimization.py index e53fb9d..fad05ee 100644 --- a/lamaria/pipeline/optim/vi_optimization.py +++ b/lamaria/pipeline/optim/vi_optimization.py @@ -1,14 +1,15 @@ -import pycolmap from pathlib import Path -from .session import SingleSeqSession +import pycolmap + +from ...config.options import TriangulatorOptions, VIOptimizerOptions from .iterative_global_ba import IterativeRefinement -from ...config.options import VIOptimizerOptions, TriangulatorOptions +from .session import SingleSeqSession class VIOptimizer: """Main Visual-Inertial Optimizer Class""" - + def __init__( self, vi_options: VIOptimizerOptions, @@ -29,27 +30,21 @@ def optimize( """Entry point for running full VI optimization""" optimizer = VIOptimizer(vi_options, triangulator_options, session) return optimizer.process(database_path) - - def process( - self, - database_path: Path - ) -> pycolmap.Reconstruction: + + def process(self, database_path: Path) -> pycolmap.Reconstruction: """Optimize the reconstruction using VI optimization""" if not database_path.exists(): raise FileNotFoundError(f"Database not found: {database_path}") - + if not self.session.data.reconstruction.reg_image_ids(): raise ValueError("Reconstruction has no registered images.") - + mapper = self._setup_incremental_mapper(database_path) pipeline_options = self._get_incremental_pipeline_options() IterativeRefinement.run( - self.vi_options, - pipeline_options, - mapper, - self.session + self.vi_options, pipeline_options, mapper, self.session ) return mapper.reconstruction @@ -57,8 +52,10 @@ def process( def _setup_incremental_mapper(self, database_path: Path): """Setup the COLMAP incremental mapper""" database = pycolmap.Database.open(database_path) - image_names = [self.session.data.reconstruction.images[image_id].name - for image_id in self.session.data.reconstruction.reg_image_ids()] + image_names = [ + self.session.data.reconstruction.images[image_id].name + for image_id in self.session.data.reconstruction.reg_image_ids() + ] database_cache = pycolmap.DatabaseCache.create( database, 15, False, set(image_names) ) @@ -70,7 +67,7 @@ def _get_incremental_pipeline_options(self): """Get incremental pipeline options for COLMAP bundle adjustment""" pipeline_options = pycolmap.IncrementalPipelineOptions() pipeline_options.fix_existing_frames = False - + if not self.vi_options.cam.optimize_cam_from_rig: pipeline_options.ba_refine_sensor_from_rig = False if not self.vi_options.cam.optimize_focal_length: @@ -81,11 +78,21 @@ def _get_incremental_pipeline_options(self): pipeline_options.ba_refine_extra_params = False # Setting up triangulation and mapper options - pipeline_options.triangulation.merge_max_reproj_error = self.triangulator_options.merge_max_reproj_error - pipeline_options.triangulation.complete_max_reproj_error = self.triangulator_options.complete_max_reproj_error - pipeline_options.triangulation.min_angle = self.triangulator_options.min_angle - - pipeline_options.mapper.filter_max_reproj_error = self.triangulator_options.filter_max_reproj_error - pipeline_options.mapper.filter_min_tri_angle = self.triangulator_options.filter_min_tri_angle - - return pipeline_options \ No newline at end of file + pipeline_options.triangulation.merge_max_reproj_error = ( + self.triangulator_options.merge_max_reproj_error + ) + pipeline_options.triangulation.complete_max_reproj_error = ( + self.triangulator_options.complete_max_reproj_error + ) + pipeline_options.triangulation.min_angle = ( + self.triangulator_options.min_angle + ) + + pipeline_options.mapper.filter_max_reproj_error = ( + self.triangulator_options.filter_max_reproj_error + ) + pipeline_options.mapper.filter_min_tri_angle = ( + self.triangulator_options.filter_min_tri_angle + ) + + return pipeline_options diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py index 2c31729..2afe7e5 100644 --- a/lamaria/utils/camera.py +++ b/lamaria/utils/camera.py @@ -1,16 +1,13 @@ - import json -import numpy as np -import pycolmap from pathlib import Path -from typing import List -from projectaria_tools.core.stream_id import StreamId +import numpy as np +import pycolmap from projectaria_tools.core.calibration import CameraCalibration +from projectaria_tools.core.stream_id import StreamId from .transformation import get_t_cam_a_cam_b_from_json - ARIA_CAMERAS = [("cam0", "camera-slam-left"), ("cam1", "camera-slam-right")] LEFT_CAMERA_STREAM_ID = StreamId("1201-1") RIGHT_CAMERA_STREAM_ID = StreamId("1201-2") @@ -18,14 +15,13 @@ RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" - def add_cameras_to_reconstruction( reconstruction: pycolmap.Reconstruction, calibration_file: Path, ) -> None: - """ Add Aria cameras to COLMAP reconstruction from calibration json file found on website: + """Add Aria cameras to COLMAP reconstruction from calibration json file found on website: https://lamaria.ethz.ch/slam_datasets - + Args: reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction to which cameras will be added calibration_file (Path): Path to the Aria calibration json file @@ -49,26 +45,26 @@ def add_cameras_to_reconstruction( sensor1 = pycolmap.sensor_t(id=2, type=pycolmap.SensorType.CAMERA) sensor_from_rig = get_t_cam_a_cam_b_from_json( calibration_file=calibration_file, - camera_a_label="cam1", # right - camera_b_label="cam0", # left + camera_a_label="cam1", # right + camera_b_label="cam0", # left ) rig.add_sensor(sensor1, sensor_from_rig) - + reconstruction.add_rig(rig) def get_camera_params_for_colmap( camera_calibration: CameraCalibration, camera_model: str, -) -> List[float]: - """ +) -> list[float]: + """ Convert Aria CameraCalibration to COLMAP camera parameters. Supported models: OPENCV_FISHEYE, FULL_OPENCV, RAD_TAN_THIN_PRISM_FISHEYE Args: camera_calibration (CameraCalibration): The projectaria_tools CameraCalibration object camera_model (str): The COLMAP camera model to use Returns: - List[float]: The camera parameters in COLMAP format + list[float]: The camera parameters in COLMAP format """ # params = [f_u {f_v} c_u c_v [k_0: k_{numK-1}] # {p_0 p_1} {s_0 s_1 s_2 s_3}] @@ -108,7 +104,9 @@ def get_camera_params_for_colmap( def camera_colmap_from_calib(calib: CameraCalibration) -> pycolmap.Camera: """Loads pycolmap camera from Aria CameraCalibration object""" if calib.get_model_name().name != "FISHEYE624": - raise ValueError(f"Unsupported Aria model {calib.get_model_name().name}") + raise ValueError( + f"Unsupported Aria model {calib.get_model_name().name}" + ) model = "RAD_TAN_THIN_PRISM_FISHEYE" params = get_camera_params_for_colmap(calib, model) width, height = calib.get_image_size() @@ -121,8 +119,8 @@ def camera_colmap_from_calib(calib: CameraCalibration) -> pycolmap.Camera: def camera_colmap_from_json( - calibration_file: Path, # open sourced aria calibration files - camera_label: str + calibration_file: Path, # open sourced aria calibration files + camera_label: str, ) -> pycolmap.Camera: """Loads pycolmap camera from Aria calibration json file found on website: https://lamaria.ethz.ch/slam_datasets""" @@ -131,7 +129,7 @@ def camera_colmap_from_json( camera_data = calib[camera_label] if camera_data["model"] != "RAD_TAN_THIN_PRISM_FISHEYE": raise ValueError(f"Unsupported Aria model {camera_data['model']}") - + model = "RAD_TAN_THIN_PRISM_FISHEYE" params = camera_data["params"] width = camera_data["resolution"]["width"] @@ -141,4 +139,4 @@ def camera_colmap_from_json( width=width, height=height, params=params, - ) \ No newline at end of file + ) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 9e940e1..966ce8c 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -1,16 +1,14 @@ import json -import os from pathlib import Path +from typing import Dict -import matplotlib.pyplot as plt import numpy as np import pycolmap from tqdm import tqdm -from typing import Dict, List from .general import ( - get_image_names_to_ids, CUSTOM_ORIGIN_COORDINATES, + get_image_names_to_ids, ) @@ -21,8 +19,8 @@ def construct_control_points_from_json( Args: cp_json_file (Path): Path to the sparse GT JSON file """ - - cp_data = json.load(open(cp_json_file, 'r')) + + cp_data = json.load(open(cp_json_file)) control_points = {} for geo_id, data in cp_data["control_points"].items(): tag_ids = data["tag_id"] @@ -30,24 +28,28 @@ def construct_control_points_from_json( unc = data["uncertainty"] if measurement[2] == None: - assert unc[2] == None, "Uncertainty for z coordinate should be None if measurement is None" + assert unc[2] == None, ( + "Uncertainty for z coordinate should be None if measurement is None" + ) measurement[2] = CUSTOM_ORIGIN_COORDINATES[2] - unc[2] = 1e9 # some large number - - translated_measurement = np.array(measurement) - np.array(CUSTOM_ORIGIN_COORDINATES) + unc[2] = 1e9 # some large number + + translated_measurement = np.array(measurement) - np.array( + CUSTOM_ORIGIN_COORDINATES + ) # those without height will have 0 height and large uncertainty in z for tag_id in tag_ids: control_points[tag_id] = { "control_point": geo_id, "topo": translated_measurement, - "covariance": np.diag(np.square(unc)) + "covariance": np.diag(np.square(unc)), } - + return control_points -def check_3d_error_bet_triang_and_topo(triangulated: List, topo: List): +def check_3d_error_bet_triang_and_topo(triangulated: list, topo: list): """Calculate L2 error between triangulated and topo points Args: triangulated (list): list of triangulated points @@ -62,7 +64,7 @@ def check_3d_error_bet_triang_and_topo(triangulated: List, topo: List): return errors -def check_2d_error_bet_triang_and_topo(triangulated: List, topo: List): +def check_2d_error_bet_triang_and_topo(triangulated: list, topo: list): """Calculate L2 error between triangulated and topo points Args: triangulated (list): list of 3d triangulated points @@ -99,13 +101,15 @@ def transform_triangulated_control_points(control_points: Dict, r, t, scale): def run_control_point_triangulation_from_json( reconstruction_path: Path, cp_json_file: Path, - control_points: Dict, # edits control_points in place + control_points: Dict, # edits control_points in place ) -> None: rec = pycolmap.Reconstruction(reconstruction_path) - image_names_to_ids = get_image_names_to_ids(reconstruction_path=reconstruction_path) + image_names_to_ids = get_image_names_to_ids( + reconstruction_path=reconstruction_path + ) - with open(cp_json_file, "r") as file: + with open(cp_json_file) as file: data = json.load(file) image_data = data["images"] @@ -153,9 +157,7 @@ def run_control_point_triangulation_from_json( }, ) except Exception as e: - print( - f"Error in triangulating control point {geo_id}: {e}" - ) + print(f"Error in triangulating control point {geo_id}: {e}") output = None if output is None: diff --git a/lamaria/utils/estimate.py b/lamaria/utils/estimate.py index 7ae994a..c571f54 100644 --- a/lamaria/utils/estimate.py +++ b/lamaria/utils/estimate.py @@ -1,8 +1,8 @@ +from decimal import ROUND_HALF_UP, Decimal from pathlib import Path -from typing import List + import numpy as np import pycolmap -from decimal import Decimal, ROUND_HALF_UP def round_ns(x: str | int | float) -> int: @@ -14,82 +14,107 @@ def round_ns(x: str | int | float) -> int: def get_rig_from_worlds_from_estimate( - estimate_path: Path -) -> List[pycolmap.Rigid3d]: + estimate_path: Path, +) -> list[pycolmap.Rigid3d]: """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - + rig_from_worlds = [] - with open(estimate_path, "r") as f: + with open(estimate_path) as f: lines = f.readlines() for line in lines: if line.startswith("#"): continue - + parts = line.strip().split() if len(parts) != 8: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values.") + raise ValueError( + f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values." + ) try: - tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) - qvec = np.array([float(parts[4]), float(parts[5]), float(parts[6]), float(parts[7])]) + tvec = np.array( + [float(parts[1]), float(parts[2]), float(parts[3])] + ) + qvec = np.array( + [ + float(parts[4]), + float(parts[5]), + float(parts[6]), + float(parts[7]), + ] + ) except ValueError: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number.") + raise ValueError( + f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number." + ) pose = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) rig_from_world = pose.inverse() rig_from_worlds.append(rig_from_world) - + return rig_from_worlds def check_estimate_format(estimate_path: Path) -> bool: """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - with open(estimate_path, "r") as f: + with open(estimate_path) as f: lines = f.readlines() lines = [line for line in lines if not line.startswith("#")] if not lines: - raise ValueError(f"Estimate file {estimate_path} is empty \ - or has no valid lines.") + raise ValueError( + f"Estimate file {estimate_path} is empty \ + or has no valid lines." + ) for line in lines: parts = line.strip().split() if len(parts) != 8: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values.") - + raise ValueError( + f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values." + ) + try: [float(part) for part in parts] except ValueError: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number.") - + raise ValueError( + f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number." + ) + return True -def get_estimate_timestamps(estimate_path: Path) -> List[int]: +def get_estimate_timestamps(estimate_path: Path) -> list[int]: """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" timestamps = [] - with open(estimate_path, "r") as f: + with open(estimate_path) as f: lines = f.readlines() lines = [line for line in lines if not line.startswith("#")] if not lines: - raise ValueError(f"Estimate file {estimate_path} is empty \ - or has no valid lines.") + raise ValueError( + f"Estimate file {estimate_path} is empty \ + or has no valid lines." + ) for line in lines: parts = line.strip().split() if len(parts) != 8: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values.") - + raise ValueError( + f"Estimate file {estimate_path} has invalid format. \ + Each line must have 8 values." + ) + try: ts = round_ns(parts[0]) except ValueError: - raise ValueError(f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number.") - + raise ValueError( + f"Estimate file {estimate_path} has invalid format. \ + Each value must be a number." + ) + timestamps.append(ts) - - return timestamps \ No newline at end of file + + return timestamps diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index a1b9c53..9390c17 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -1,24 +1,22 @@ import os -import pycolmap -from pathlib import Path -from typing import List, Tuple, Dict import shutil -from bisect import bisect_left -from typing import List import subprocess +from bisect import bisect_left +from pathlib import Path +from typing import Dict, Tuple -from lamaria import logger +import pycolmap +from lamaria import logger CUSTOM_ORIGIN_COORDINATES = (2683594.4120000005, 1247727.7470000014, 417.307) def find_closest_timestamp( - timestamps: list, + timestamps: list, target_ts: int, max_diff: float, ) -> int | None: - """Timestamps must be in nano seconds""" index = bisect_left(timestamps, target_ts) if index == 0: @@ -39,21 +37,24 @@ def find_closest_timestamp( def get_matched_timestamps( - left_timestamps: List[int], - right_timestamps: List[int], + left_timestamps: list[int], + right_timestamps: list[int], max_diff: float, -) -> List[Tuple[int, int]]: - +) -> list[Tuple[int, int]]: matched_timestamps = [] - assert all(isinstance(ts, int) for ts in left_timestamps), \ + assert all(isinstance(ts, int) for ts in left_timestamps), ( "Left timestamps must be integers" - assert all(isinstance(ts, int) for ts in right_timestamps), \ + ) + assert all(isinstance(ts, int) for ts in right_timestamps), ( "Right timestamps must be integers" + ) if len(left_timestamps) < len(right_timestamps): for lts in left_timestamps: - closest_rts = find_closest_timestamp(right_timestamps, lts, max_diff) + closest_rts = find_closest_timestamp( + right_timestamps, lts, max_diff + ) if closest_rts is not None: matched_timestamps.append((lts, closest_rts)) else: @@ -128,10 +129,7 @@ def extract_images_from_vrs( logger.info("Done!") -def get_image_names_to_ids( - reconstruction_path: Path -) -> Dict[str, int]: - +def get_image_names_to_ids(reconstruction_path: Path) -> Dict[str, int]: recon = pycolmap.Reconstruction(reconstruction_path) image_names_to_ids = {} @@ -139,4 +137,4 @@ def get_image_names_to_ids( image_name = recon.images[image_id].name image_names_to_ids[image_name] = image_id - return image_names_to_ids \ No newline at end of file + return image_names_to_ids diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index b29bd7e..fcdd423 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -1,10 +1,11 @@ -import pycolmap -from typing import Optional from pathlib import Path -from tqdm import tqdm -from projectaria_tools.core import mps, data_provider +from typing import Optional + +import pycolmap +from projectaria_tools.core import data_provider, mps from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions from projectaria_tools.core.stream_id import StreamId +from tqdm import tqdm from lamaria.utils.general import ( find_closest_timestamp, @@ -14,16 +15,15 @@ RIGHT_IMU_STREAM_LABEL = "imu-right" - def get_online_params_for_imu_from_mps( - online_calibs_file: Path, - stream_label: str, - num_error: float = 1e6 + online_calibs_file: Path, stream_label: str, num_error: float = 1e6 ): online_calibs = mps.read_online_calibration(online_calibs_file.as_posix()) online_imu_calibs = {} num_error = int(num_error) - for calib in tqdm(online_calibs, desc="Reading online IMU calibration data"): + for calib in tqdm( + online_calibs, desc="Reading online IMU calibration data" + ): for imuCalib in calib.imu_calibs: if imuCalib.get_label() == stream_label: # calib timestamp in microseconds @@ -39,23 +39,23 @@ def get_imu_data_from_vrs( vrs_provider: data_provider.VrsDataProvider, mps_folder: Optional[Path] = None, ) -> pycolmap.ImuMeasurements: - """ Get rectified IMU data from VRS file. If mps_folder is provided, use online - calibration data from MPS folder. Otherwise, use device calibration from VRS file. """ + """Get rectified IMU data from VRS file. If mps_folder is provided, use online + calibration data from MPS folder. Otherwise, use device calibration from VRS file.""" imu_timestamps = sorted( vrs_provider.get_timestamps_ns( - RIGHT_IMU_STREAM_ID, - TimeDomain.DEVICE_TIME + RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME ) ) - imu_stream_label = vrs_provider.get_label_from_stream_id(RIGHT_IMU_STREAM_ID) + imu_stream_label = vrs_provider.get_label_from_stream_id( + RIGHT_IMU_STREAM_ID + ) if mps_folder is not None: online_calibs_file = mps_folder / "slam" / "online_calibration.jsonl" online_imu_calibs = get_online_params_for_imu_from_mps( - online_calibs_file, - imu_stream_label + online_calibs_file, imu_stream_label ) - acceptable_diff_ms = 1 # 1 milliseconds + acceptable_diff_ms = 1 # 1 milliseconds calib_timestamps = sorted(online_imu_calibs.keys()) else: device_calib = vrs_provider.get_device_calibration() @@ -66,16 +66,16 @@ def get_imu_data_from_vrs( if mps_folder is not None: quantized_timestamp = timestamp // int(1e6) closest_ts = find_closest_timestamp( - calib_timestamps, - quantized_timestamp, - acceptable_diff_ms + calib_timestamps, quantized_timestamp, acceptable_diff_ms ) if closest_ts not in online_imu_calibs: - raise ValueError(f"No calibration found for timestamp {timestamp}") + raise ValueError( + f"No calibration found for timestamp {timestamp}" + ) calibration = online_imu_calibs[closest_ts] - + imu_data = vrs_provider.get_imu_data_by_time_ns( RIGHT_IMU_STREAM_ID, timestamp, @@ -94,4 +94,4 @@ def get_imu_data_from_vrs( pycolmap.ImuMeasurement(ts, rectified_acc, rectified_gyro) ) - return ms \ No newline at end of file + return ms diff --git a/lamaria/utils/metrics.py b/lamaria/utils/metrics.py index fb28275..c3b3615 100644 --- a/lamaria/utils/metrics.py +++ b/lamaria/utils/metrics.py @@ -1,31 +1,25 @@ from pathlib import Path + import numpy as np import pycolmap from scipy.interpolate import interp1d -from typing import List def get_sim3_from_sparse_evaluation( - sparse_evaluation_npy: Path + sparse_evaluation_npy: Path, ) -> pycolmap.Sim3d: data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() sim3 = data_sparse["full_alignment"]["sim3"] return sim3 -def get_all_tag_ids( - sparse_evaluation_npy: Path -) -> List[str]: - +def get_all_tag_ids(sparse_evaluation_npy: Path) -> list[str]: data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() tag_ids = sorted(list(data_sparse["control_points"].keys())) return tag_ids -def calculate_2d_alignment_errors( - sparse_evaluation_npy: Path -) -> List[float]: - +def calculate_2d_alignment_errors(sparse_evaluation_npy: Path) -> list[float]: data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() tag_ids = get_all_tag_ids(sparse_evaluation_npy) err_2d = [ @@ -79,20 +73,17 @@ def calculate_score_piecewise(errors): return S_j -def calculate_score_from_alignment_data( - sparse_evaluation_npy: Path -) -> float: - +def calculate_score_from_alignment_data(sparse_evaluation_npy: Path) -> float: tag_ids = get_all_tag_ids(sparse_evaluation_npy) err_2d = calculate_2d_alignment_errors(sparse_evaluation_npy) if len(err_2d) == 0: raise ValueError("No valid control points found.") - assert len(err_2d) == len( - tag_ids - ), "Mismatch in number of 2D CPs and errors." + assert len(err_2d) == len(tag_ids), ( + "Mismatch in number of 2D CPs and errors." + ) S_2d = calculate_score_piecewise(err_2d) - return S_2d \ No newline at end of file + return S_2d diff --git a/lamaria/utils/transformation.py b/lamaria/utils/transformation.py index c1d5f69..7c524c2 100644 --- a/lamaria/utils/transformation.py +++ b/lamaria/utils/transformation.py @@ -1,28 +1,29 @@ -from pathlib import Path import json -import pycolmap -from typing import Tuple, List -from scipy.spatial.transform import Rotation -import numpy as np +from pathlib import Path +from typing import Tuple +import numpy as np +import pycolmap from projectaria_tools.core import mps -from projectaria_tools.core.mps.utils import get_nearest_pose from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration +from projectaria_tools.core.mps.utils import get_nearest_pose +from scipy.spatial.transform import Rotation - -def get_closed_loop_data_from_mps(mps_path: Path) -> List[mps.ClosedLoopTrajectoryPose]: - """ Get closed loop trajectory data from MPS folder.""" +def get_closed_loop_data_from_mps( + mps_path: Path, +) -> list[mps.ClosedLoopTrajectoryPose]: + """Get closed loop trajectory data from MPS folder.""" closed_loop_traj_file = mps_path / "slam" / "closed_loop_trajectory.csv" data = mps.read_closed_loop_trajectory(closed_loop_traj_file.as_posix()) return data def get_mps_poses_for_timestamps( - trajectory_data: List[mps.ClosedLoopTrajectoryPose], - timestamps: List[int], -) -> List: - """ Get T_world_device for a list of device timestamps in nanoseconds using MPS trajectory data. + trajectory_data: list[mps.ClosedLoopTrajectoryPose], + timestamps: list[int], +) -> list: + """Get T_world_device for a list of device timestamps in nanoseconds using MPS trajectory data. Returns None for timestamps where no trajectory data is found.""" poses = [] if trajectory_data: @@ -38,21 +39,21 @@ def get_mps_poses_for_timestamps( def get_t_rig_world_for_device_time_ns( - trajectory_data: List[mps.ClosedLoopTrajectoryPose], + trajectory_data: list[mps.ClosedLoopTrajectoryPose], device_time_ns: int, imu_calibration: ImuCalibration, ): - """ Get T_rig_world (rig is right IMU sensor) for a given device time in nanoseconds using MPS trajectory data and IMU calibration. + """Get T_rig_world (rig is right IMU sensor) for a given device time in nanoseconds using MPS trajectory data and IMU calibration. Returns None if no trajectory data is found for the given timestamp.""" if trajectory_data: pose_information = get_nearest_pose(trajectory_data, device_time_ns) if pose_information: t_world_device = pose_information.transform_world_device t_device_imu = imu_calibration.get_transform_device_imu() - assert ( - t_device_imu is not None - ), f"No t_device_imu found for device time {device_time_ns}, \ + assert t_device_imu is not None, ( + f"No t_device_imu found for device time {device_time_ns}, \ check imu calibration" + ) t_world_imu = t_world_device @ t_device_imu t_imu_world = t_world_imu.inverse() @@ -70,18 +71,18 @@ def get_t_imu_camera( return_qt=False, return_matrix=False, ): - """ Get T_imu_camera from Aria calibrations. Either return as qvec,tvec or 4x4 matrix. + """Get T_imu_camera from Aria calibrations. Either return as qvec,tvec or 4x4 matrix. If neither return_qt or return_matrix is True, returns as projectaria_tools Rigid3d object.""" - + t_device_cam = camera_calib.get_transform_device_camera() t_device_imu = imu_calib.get_transform_device_imu() t_imu_device = t_device_imu.inverse() t_imu_cam = t_imu_device @ t_device_cam - assert not ( - return_qt and return_matrix - ), "Only one of return_qt or return_matrix can be True" + assert not (return_qt and return_matrix), ( + "Only one of return_qt or return_matrix can be True" + ) if return_qt: qvec, tvec = get_qvec_and_tvec_from_transform(t_imu_cam) @@ -94,7 +95,9 @@ def get_t_imu_camera( return t_imu_cam -def get_qvec_and_tvec_from_transform(transform) -> Tuple[np.ndarray, np.ndarray]: +def get_qvec_and_tvec_from_transform( + transform, +) -> Tuple[np.ndarray, np.ndarray]: """Converts projectaria_tools Rigid3d to qvec and tvec. Returns qvec in format x,y,z,w and tvec in format x,y,z""" # to_quat() returns in wxyz format @@ -110,13 +113,15 @@ def get_qvec_and_tvec_from_transform(transform) -> Tuple[np.ndarray, np.ndarray] def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: - """ Converts projectaria_tools Rigid3d to pycolmap Rigid3d""" + """Converts projectaria_tools Rigid3d to pycolmap Rigid3d""" q, t = get_qvec_and_tvec_from_transform(transform) return pycolmap.Rigid3d(pycolmap.Rotation3d(q), t) -def get_magnitude_from_transform(transform: pycolmap.Rigid3d) -> Tuple[float, float]: - """ Returns rotation (in degrees) and translation (in meters) magnitudes from a Rigid3d transform""" +def get_magnitude_from_transform( + transform: pycolmap.Rigid3d, +) -> Tuple[float, float]: + """Returns rotation (in degrees) and translation (in meters) magnitudes from a Rigid3d transform""" translation = transform.translation quat_xyzw = transform.rotation.quat rotation = Rotation.from_quat(quat_xyzw) @@ -131,7 +136,7 @@ def get_t_cam_a_cam_b_from_json( camera_a_label: str, camera_b_label: str, ) -> pycolmap.Rigid3d: - """ Get T_cam_a_cam_b from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) + """Get T_cam_a_cam_b from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) for given camera labels.""" calib = json.load(calibration_file.open("r")) @@ -158,11 +163,11 @@ def get_t_imu_camera_from_json( calibration_file: Path, camera_label: str, ) -> pycolmap.Rigid3d: - """ Get T_imu_camera from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) + """Get T_imu_camera from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) for a given camera label.""" - + calib = json.load(calibration_file.open("r")) - + # body is right imu of Aria, therefore T_b_s is T_imu_camera t_body_cam = calib[camera_label]["T_b_s"] t_imu_camera = pycolmap.Rigid3d( @@ -170,4 +175,4 @@ def get_t_imu_camera_from_json( t_body_cam["tvec"], ) - return t_imu_camera \ No newline at end of file + return t_imu_camera diff --git a/run_pipeline.py b/run_pipeline.py index 0937547..4ae55cd 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -1,22 +1,23 @@ -import pycolmap -import shutil import argparse -from typing import Optional +import shutil from pathlib import Path +from typing import Optional + +import pycolmap -from lamaria.pipeline.lamaria_reconstruction import LamariaReconstruction -from lamaria.pipeline.keyframing.to_colmap import EstimateToColmap -from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector -from lamaria.pipeline.optim.triangulation import run as triangulate -from lamaria.pipeline.optim.session import SingleSeqSession -from lamaria.pipeline.optim.vi_optimization import VIOptimizer -from lamaria.config.pipeline import PipelineOptions from lamaria.config.options import ( EstimateToColmapOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, ) +from lamaria.config.pipeline import PipelineOptions +from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector +from lamaria.pipeline.keyframing.to_colmap import EstimateToColmap +from lamaria.pipeline.lamaria_reconstruction import LamariaReconstruction +from lamaria.pipeline.optim.session import SingleSeqSession +from lamaria.pipeline.optim.triangulation import run as triangulate +from lamaria.pipeline.optim.vi_optimization import VIOptimizer def run_estimate_to_colmap( @@ -26,11 +27,10 @@ def run_estimate_to_colmap( estimate: Path, colmap_model: Path, ) -> LamariaReconstruction: - if colmap_model.exists(): lamaria_recon = LamariaReconstruction.read(colmap_model) return lamaria_recon - + colmap_model.mkdir(parents=True, exist_ok=True) lamaria_recon = EstimateToColmap.convert( @@ -51,11 +51,10 @@ def run_mps_to_colmap( mps_folder: Path, colmap_model: Path, ) -> LamariaReconstruction: - if colmap_model.exists(): lamaria_recon = LamariaReconstruction.read(colmap_model) return lamaria_recon - + colmap_model.mkdir(parents=True, exist_ok=True) lamaria_recon = EstimateToColmap.convert( @@ -76,7 +75,6 @@ def run_keyframe_selection( keyframes: Path, kf_model: Path, ) -> LamariaReconstruction: - if isinstance(input, Path): input_recon = LamariaReconstruction.read(input) else: @@ -85,7 +83,7 @@ def run_keyframe_selection( if kf_model.exists(): kf_lamaria_recon = LamariaReconstruction.read(kf_model) return kf_lamaria_recon - + kf_model.mkdir(parents=True, exist_ok=True) kf_lamaria_recon = KeyframeSelector.run( @@ -94,7 +92,7 @@ def run_keyframe_selection( images, keyframes, ) - + kf_lamaria_recon.write(kf_model) return kf_lamaria_recon @@ -102,7 +100,7 @@ def run_keyframe_selection( def run_triangulation( options: TriangulatorOptions, - input: Path, # path to LamariaReconstruction + input: Path, # path to LamariaReconstruction keyframes: Path, hloc: Path, pairs_file: Path, @@ -110,9 +108,9 @@ def run_triangulation( ) -> LamariaReconstruction: if not isinstance(input, Path): raise ValueError("Input must be a Path to the reconstruction") - + assert input.exists(), f"input reconstruction path {input} does not exist" - + if tri_model.exists(): tri_lamaria_recon = LamariaReconstruction.read(tri_model) return tri_lamaria_recon @@ -141,22 +139,24 @@ def run_triangulation( def run_optimization( vi_options: VIOptimizerOptions, triangulator_options: TriangulatorOptions, - input: Path, # path to LamariaReconstruction + input: Path, # path to LamariaReconstruction optim_model: Path, ) -> LamariaReconstruction: if not isinstance(input, Path): raise ValueError("Input must be a Path to the reconstruction") - + db_path = input / "database.db" - assert db_path.exists(), f"Database path {db_path} does not exist in input reconstruction" - + assert db_path.exists(), ( + f"Database path {db_path} does not exist in input reconstruction" + ) + if optim_model.exists(): shutil.rmtree(optim_model) - + optim_model.mkdir(parents=True, exist_ok=True) db_dst = optim_model / "database.db" shutil.copy(db_path, db_dst) - + init_lamaria_recon = LamariaReconstruction.read(input) session = SingleSeqSession( vi_options.imu, @@ -164,10 +164,7 @@ def run_optimization( ) optimized_recon = VIOptimizer.optimize( - vi_options, - triangulator_options, - session, - db_dst + vi_options, triangulator_options, session, db_dst ) optim_lamaria_recon = LamariaReconstruction() @@ -192,9 +189,10 @@ def run_pipeline( # Estimate to COLMAP est_options = options.estimate_to_colmap_options if not est_options.mps.use_mps: - assert estimate is not None \ - and estimate.exists(), "Estimate path must be provided if not using MPS" - + assert estimate is not None and estimate.exists(), ( + "Estimate path must be provided if not using MPS" + ) + _ = run_estimate_to_colmap( est_options, vrs, @@ -203,9 +201,10 @@ def run_pipeline( options.colmap_model, ) else: - assert mps_folder is not None \ - and mps_folder.exists(), "MPS folder path must be provided if using MPS" - + assert mps_folder is not None and mps_folder.exists(), ( + "MPS folder path must be provided if using MPS" + ) + _ = run_mps_to_colmap( est_options, vrs, @@ -244,6 +243,7 @@ def run_pipeline( options.optim_model, ) + if __name__ == "__main__": parser = argparse.ArgumentParser(description="Run full pipeline.") parser.add_argument( @@ -282,7 +282,9 @@ def run_pipeline( if args.estimate is None and args.mps_folder is None: parser.error("Either --estimate or --mps_folder must be provided.") if args.estimate is not None and args.mps_folder is not None: - parser.error("Only one of --estimate or --mps_folder should be provided.") + parser.error( + "Only one of --estimate or --mps_folder should be provided." + ) options = PipelineOptions() options.load(args.config) diff --git a/tools/asl_folder_to_rosbag.py b/tools/asl_folder_to_rosbag.py index 163cc55..e535ed6 100644 --- a/tools/asl_folder_to_rosbag.py +++ b/tools/asl_folder_to_rosbag.py @@ -4,7 +4,7 @@ import csv from dataclasses import dataclass from pathlib import Path -from typing import List, Tuple +from typing import Tuple import cv2 import rosbag @@ -15,6 +15,7 @@ NS_TO_S = 1e-9 + @dataclass(frozen=True) class CamSample: ts_ns: int @@ -22,6 +23,7 @@ class CamSample: topic: str frame_id: str + @dataclass(frozen=True) class ImuSample: ts_ns: int @@ -30,16 +32,19 @@ class ImuSample: topic: str frame_id: str + def _is_int(s: str) -> bool: try: int(s) return True except Exception: return False - -def _read_cam_csv(csv_path: Path, images_dir: Path, topic: str, frame_id: str) -> List[CamSample]: - samples: List[CamSample] = [] + +def _read_cam_csv( + csv_path: Path, images_dir: Path, topic: str, frame_id: str +) -> list[CamSample]: + samples: list[CamSample] = [] with csv_path.open("r", newline="") as f: reader = csv.reader(f) for row in reader: @@ -49,12 +54,15 @@ def _read_cam_csv(csv_path: Path, images_dir: Path, topic: str, frame_id: str) - continue ts_ns = int(row[0]) img_rel = row[1] - samples.append(CamSample(ts_ns, images_dir / img_rel, topic, frame_id)) - + samples.append( + CamSample(ts_ns, images_dir / img_rel, topic, frame_id) + ) + return samples -def _read_imu_csv(csv_path: Path, topic: str, frame_id: str) -> List[ImuSample]: - samples: List[ImuSample] = [] + +def _read_imu_csv(csv_path: Path, topic: str, frame_id: str) -> list[ImuSample]: + samples: list[ImuSample] = [] with csv_path.open("r", newline="") as f: reader = csv.reader(f) for row in reader: @@ -65,8 +73,10 @@ def _read_imu_csv(csv_path: Path, topic: str, frame_id: str) -> List[ImuSample]: ts_ns = int(row[0]) wx, wy, wz = (float(x) for x in row[1:4]) ax, ay, az = (float(x) for x in row[4:7]) - samples.append(ImuSample(ts_ns, (wx, wy, wz), (ax, ay, az), topic, frame_id)) - + samples.append( + ImuSample(ts_ns, (wx, wy, wz), (ax, ay, az), topic, frame_id) + ) + return samples @@ -80,7 +90,6 @@ def asl_to_rosbag( cam1_frame: str = "cam1", imu_frame: str = "imu0", ) -> None: - aria = input_asl_folder / "aria" cam0_dir, cam1_dir, imu_dir = aria / "cam0", aria / "cam1", aria / "imu0" @@ -89,10 +98,14 @@ def asl_to_rosbag( if not imu_dir.exists(): raise FileNotFoundError(f"Missing IMU folder: {imu_dir}") - cam0 = _read_cam_csv(cam0_dir / "data.csv", cam0_dir / "data", cam0_topic, cam0_frame) + cam0 = _read_cam_csv( + cam0_dir / "data.csv", cam0_dir / "data", cam0_topic, cam0_frame + ) cam1 = [] if cam1_dir.exists() and (cam1_dir / "data.csv").exists(): - cam1 = _read_cam_csv(cam1_dir / "data.csv", cam1_dir / "data", cam1_topic, cam1_frame) + cam1 = _read_cam_csv( + cam1_dir / "data.csv", cam1_dir / "data", cam1_topic, cam1_frame + ) imu = _read_imu_csv(imu_dir / "data.csv", imu_topic, imu_frame) if not cam0: @@ -110,9 +123,13 @@ def asl_to_rosbag( bridge = CvBridge() bag = rosbag.Bag(str(output_rosbag), "w") - print(f"[asl_to_rosbag] Writing {len(bag_timeline):,} messages -> {output_rosbag}") + print( + f"[asl_to_rosbag] Writing {len(bag_timeline):,} messages -> {output_rosbag}" + ) - for ts_ns, kind, sample in tqdm(bag_timeline, desc="Writing bag", unit="msg"): + for ts_ns, kind, sample in tqdm( + bag_timeline, desc="Writing bag", unit="msg" + ): stamp = rospy.Time.from_sec(ts_ns * NS_TO_S) if kind == "cam": @@ -131,8 +148,16 @@ def asl_to_rosbag( imu_msg.header.frame_id = sample.frame_id wx, wy, wz = sample.gyro ax, ay, az = sample.accel - imu_msg.angular_velocity.x, imu_msg.angular_velocity.y, imu_msg.angular_velocity.z = wx, wy, wz - imu_msg.linear_acceleration.x, imu_msg.linear_acceleration.y, imu_msg.linear_acceleration.z = ax, ay, az + ( + imu_msg.angular_velocity.x, + imu_msg.angular_velocity.y, + imu_msg.angular_velocity.z, + ) = wx, wy, wz + ( + imu_msg.linear_acceleration.x, + imu_msg.linear_acceleration.y, + imu_msg.linear_acceleration.z, + ) = ax, ay, az imu_msg.orientation_covariance[0] = -1 imu_msg.angular_velocity_covariance[0] = -1 diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 135ba0c..2effc75 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -3,8 +3,10 @@ import argparse import re import sys +from collections.abc import Iterable from pathlib import Path -from typing import Dict, List, Tuple, Iterable +from typing import Dict, Tuple + import requests from bs4 import BeautifulSoup from tqdm import tqdm @@ -13,7 +15,7 @@ FOLDERS = [ "raw_data", - "aria_calibrations", + "aria_calibrations", "asl_folder", "pinhole_calibrations", "rosbag", @@ -34,7 +36,8 @@ ], } -def fetch_index(full_url: str) -> List[str]: + +def fetch_index(full_url: str) -> list[str]: """Return list of hrefs on an Apache index page (files and folders).""" r = requests.get(full_url, timeout=30) r.raise_for_status() @@ -51,11 +54,13 @@ def fetch_index(full_url: str) -> List[str]: return hrefs -def build_catalog(base_url: str) -> Dict[str, List[Tuple[str, str]]]: +def build_catalog(base_url: str) -> Dict[str, list[Tuple[str, str]]]: catalog = {} for folder in FOLDERS: entries = [] - subfolders = GT_SUBFOLDERS if folder == "ground_truth" else DEFAULT_SUBFOLDERS + subfolders = ( + GT_SUBFOLDERS if folder == "ground_truth" else DEFAULT_SUBFOLDERS + ) for sub in subfolders: url = base_url.rstrip("/") + "/" + folder + "/" + sub try: @@ -70,27 +75,29 @@ def build_catalog(base_url: str) -> Dict[str, List[Tuple[str, str]]]: catalog[folder] = entries return catalog -def names_from_listing(files: Iterable[str]) -> List[str]: + +def names_from_listing(files: Iterable[str]) -> list[str]: names = set() - pattern = ( - r"\.(zip|tar|tar\.gz|tgz|7z|bag|vrs|json|txt|csv|tar\.xz)$" - ) + pattern = r"\.(zip|tar|tar\.gz|tgz|7z|bag|vrs|json|txt|csv|tar\.xz)$" for f in files: f = f.rstrip("/") name = re.split(pattern, f, maxsplit=1, flags=re.IGNORECASE)[0] names.add(name) return sorted(names) -def derive_splits(catalog: Dict[str, List[Tuple[str, str]]]) -> Tuple[List[str], List[str]]: + +def derive_splits( + catalog: Dict[str, list[Tuple[str, str]]], +) -> Tuple[list[str], list[str]]: raw_entries = catalog.get("raw_data", []) train_files = [fname for (sub, fname) in raw_entries if sub == "training/"] - test_files = [fname for (sub, fname) in raw_entries if sub == "test/"] + test_files = [fname for (sub, fname) in raw_entries if sub == "test/"] train = sorted(names_from_listing(train_files)) - test = sorted(names_from_listing(test_files)) + test = sorted(names_from_listing(test_files)) return train, test -def raw_split_map(catalog: Dict[str, List[Tuple[str, str]]]) -> Dict[str, str]: +def raw_split_map(catalog: Dict[str, list[Tuple[str, str]]]) -> Dict[str, str]: mapping: Dict[str, str] = {} for sub, fname in catalog.get("raw_data", []): if sub not in ("training/", "test/"): @@ -104,14 +111,13 @@ def raw_split_map(catalog: Dict[str, List[Tuple[str, str]]]) -> Dict[str, str]: return mapping - def pick_files_for_sequence( - catalog: Dict[str, List[Tuple[str, str]]], + catalog: Dict[str, list[Tuple[str, str]]], sequence: str, - folders: List[str], + folders: list[str], split: str | None, -) -> List[Tuple[str, str, str]]: - matches: List[Tuple[str, str, str]] = [] +) -> list[Tuple[str, str, str]]: + matches: list[Tuple[str, str, str]] = [] for folder in folders: for sub, fname in catalog.get(folder, []): if folder != "ground_truth" and split is not None and sub != split: @@ -160,15 +166,18 @@ def download_file( if total is not None: total_to_show = total - existing if "Range" in headers else total - with open(dest, mode) as f, tqdm( - total=total_to_show, - unit="B", - unit_scale=True, - unit_divisor=1024, - initial=0, - desc=dest.name, - leave=False, - ) as pbar: + with ( + open(dest, mode) as f, + tqdm( + total=total_to_show, + unit="B", + unit_scale=True, + unit_divisor=1024, + initial=0, + desc=dest.name, + leave=False, + ) as pbar, + ): for chunk in r.iter_content(chunk_size=chunk_size): if chunk: f.write(chunk) @@ -200,7 +209,9 @@ def main(): help="Sequence names (required for --set specific). Example: R_01_easy sequence_3_17", ) parser.add_argument( - "--out-dir", default="out_dir", help="Root output folder (script will create out_dir/lamaria)" + "--out-dir", + default="out_dir", + help="Root output folder (script will create out_dir/lamaria)", ) args = parser.parse_args() @@ -221,7 +232,9 @@ def main(): global_split = "test/" else: if not args.sequences: - print("[error] --set specific requires --sequences", file=sys.stderr) + print( + "[error] --set specific requires --sequences", file=sys.stderr + ) sys.exit(2) target_sequences = args.sequences global_split = None # per-sequence @@ -238,7 +251,9 @@ def main(): else: seq_split = split_lookup.get(seq) if seq_split is None: - raise ValueError(f"Could not determine split for sequence: {seq}") + raise ValueError( + f"Could not determine split for sequence: {seq}" + ) if seq_split in ("training/", "test/"): split_folder = "training" if seq_split == "training/" else "test" @@ -252,7 +267,10 @@ def main(): ensure_dir(seq_root) selected = pick_files_for_sequence( - catalog, seq, folders, split=(seq_split if seq_split in ("training/", "test/") else None) + catalog, + seq, + folders, + split=(seq_split if seq_split in ("training/", "test/") else None), ) if seq_split == "training/": @@ -286,10 +304,15 @@ def main(): try: download_file(url, dest, sess) except Exception as e: - print(f"[error] Failed: {url} -> {dest}\n {e}", file=sys.stderr) + print( + f"[error] Failed: {url} -> {dest}\n {e}", + file=sys.stderr, + ) - print("\n[done] All downloads attempted. Files stored under:", root.resolve()) + print( + "\n[done] All downloads attempted. Files stored under:", root.resolve() + ) if __name__ == "__main__": - main() \ No newline at end of file + main() diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index 22bbdb7..52859b0 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -70,10 +70,7 @@ def write_cameras_json(cameras: Dict[int | str, pycolmap.Camera], path: Path): def undistort_asl( - calibration_file: Path, - asl_path: Path, - output_asl_path: Path, - **kwargs + calibration_file: Path, asl_path: Path, output_asl_path: Path, **kwargs ): if output_asl_path.exists(): raise ValueError(f"{output_asl_path=} already exists.") @@ -108,15 +105,16 @@ def undistort_asl( ) image_id += 1 colmap_images[key].append(im) - - zipped_images = list( - zip(*[colmap_images[key] for key, _ in ARIA_CAMERAS]) - ) - - for j, (left_im, right_im) in enumerate(tqdm( - zipped_images, total=len(zipped_images), - desc="Adding images to reconstruction" - )): + + zipped_images = list(zip(*[colmap_images[key] for key, _ in ARIA_CAMERAS])) + + for j, (left_im, right_im) in enumerate( + tqdm( + zipped_images, + total=len(zipped_images), + desc="Adding images to reconstruction", + ) + ): frame = pycolmap.Frame() frame.rig_id = rig.rig_id frame.frame_id = j + 1 @@ -128,7 +126,7 @@ def undistort_asl( recon.add_frame(frame) recon.add_image(left_im) recon.add_image(right_im) - + with tempfile.TemporaryDirectory() as temp_rec_path: recon.write(temp_rec_path) cameras_undist = undistort_reconstruction( @@ -137,7 +135,7 @@ def undistort_asl( # Copy the undistorted cameras in json. cameras_undist = { - key: cameras_undist[i+1] for i, (key, _) in enumerate(ARIA_CAMERAS) + key: cameras_undist[i + 1] for i, (key, _) in enumerate(ARIA_CAMERAS) } write_cameras_json( cameras_undist, output_asl_path / "aria" / "cameras.json" @@ -159,7 +157,7 @@ def undistort_asl( parser.add_argument("--output_asl_path", type=Path, required=True) parser.add_argument("--ratio_blank_pixels", type=float, default=0.2) args = parser.parse_args() - + undistort_asl( args.calibration_file, args.asl_path, diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index a0fa25c..a8413f3 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -2,17 +2,21 @@ import csv import os from pathlib import Path -from typing import List, Tuple +from typing import Tuple from projectaria_tools.core import data_provider from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions from tqdm import tqdm from lamaria import logger -from lamaria.utils.general import ( +from lamaria.utils.imu import ( + RIGHT_IMU_STREAM_ID, +) +from lamaria.utils.camera import ( LEFT_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, - IMU_STREAM_ID, +) +from lamaria.utils.general import ( extract_images_from_vrs, get_matched_timestamps, ) @@ -20,9 +24,9 @@ def remove_images_when_slam_drops( image_folder: Path, - left_timestamps: List[int], - right_timestamps: List[int], - matched_timestamps: List[Tuple[int, int]], + left_timestamps: list[int], + right_timestamps: list[int], + matched_timestamps: list[Tuple[int, int]], left_subfolder_name="cam0/data", right_subfolder_name="cam1/data", ): @@ -71,18 +75,25 @@ def rename_images_in_folder( left_subfolder_name="cam0/data", right_subfolder_name="cam1/data", image_extension=".jpg", -) -> List[int]: - +) -> list[int]: for subfolder in [left_subfolder_name, right_subfolder_name]: subfolder_path = aria_folder / subfolder if not subfolder_path.exists() and not subfolder_path.is_dir(): - raise ValueError(f"{subfolder_path} does not exist or is not a directory") + raise ValueError( + f"{subfolder_path} does not exist or is not a directory" + ) - original_images = sorted([f for f in os.listdir(subfolder_path) if f.endswith(image_extension)]) + original_images = sorted( + [ + f + for f in os.listdir(subfolder_path) + if f.endswith(image_extension) + ] + ) if len(original_images) == 0: raise ValueError(f"No images found in {subfolder_path}") - + if len(original_images) != len(image_timestamps): raise ValueError( f"Number of images {len(original_images)} \ @@ -98,7 +109,7 @@ def rename_images_in_folder( return image_timestamps -def write_image_timestamps_to_txt(image_timestamps: List, txt_file: Path): +def write_image_timestamps_to_txt(image_timestamps: list, txt_file: Path): with open(txt_file, "w") as f: for timestamp in image_timestamps: f.write(f"{timestamp}\n") @@ -127,14 +138,14 @@ def write_image_csv(image_timestamps, cam_folder): def write_imu_data_to_csv(vrs_provider, csv_file): imu_timestamps = vrs_provider.get_timestamps_ns( - IMU_STREAM_ID, TimeDomain.DEVICE_TIME + RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME ) last_timestamp = None if os.path.exists(csv_file): - with open(csv_file, "r") as f: + with open(csv_file) as f: last_row = None - for last_row in csv.reader(f): + for _last_row in csv.reader(f): pass if last_row is not None: last_timestamp = int(last_row[0]) @@ -150,7 +161,7 @@ def write_imu_data_to_csv(vrs_provider, csv_file): writer = csv.writer(f) for timestamp in tqdm(imu_timestamps, desc="Appending IMU data to CSV"): imu_data = vrs_provider.get_imu_data_by_time_ns( - IMU_STREAM_ID, + RIGHT_IMU_STREAM_ID, timestamp, TimeDomain.DEVICE_TIME, TimeQueryOptions.CLOSEST, @@ -172,13 +183,11 @@ def write_imu_data_to_csv(vrs_provider, csv_file): def form_aria_asl_folder( - vrs_file: Path, - output_asl_folder: Path, - has_slam_drops=False + vrs_file: Path, output_asl_folder: Path, has_slam_drops=False ): if output_asl_folder.exists(): raise ValueError(f"{output_asl_folder=} already exists.") - + aria_folder = output_asl_folder / "aria" aria_folder.mkdir(parents=True, exist_ok=True) @@ -189,9 +198,7 @@ def form_aria_asl_folder( image_timestamps = vrs_provider.get_timestamps_ns( LEFT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME ) - assert ( - len(image_timestamps) > 0 - ), "No timestamps found" + assert len(image_timestamps) > 0, "No timestamps found" right_image_timestamps = None matched_timestamps = None @@ -199,16 +206,16 @@ def form_aria_asl_folder( right_image_timestamps = vrs_provider.get_timestamps_ns( RIGHT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME ) - assert ( - len(right_image_timestamps) > 0 - ), "No right camera image timestamps found" - assert len(right_image_timestamps) != len( - image_timestamps - ), "Left and right camera image timestamps are the same" + assert len(right_image_timestamps) > 0, ( + "No right camera image timestamps found" + ) + assert len(right_image_timestamps) != len(image_timestamps), ( + "Left and right camera image timestamps are the same" + ) matched_timestamps = get_matched_timestamps( left_timestamps=image_timestamps, right_timestamps=right_image_timestamps, - max_diff=1e6, # 1 ms in nanoseconds + max_diff=1e6, # 1 ms in nanoseconds ) assert len(matched_timestamps) > 0, "No matched timestamps found" From 14e46c2e749fb73ef2e3528562137ae410862d91 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 12:49:14 +0200 Subject: [PATCH 330/665] ruff edit --- tools/vrs_to_asl_folder.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index a8413f3..8b4dcda 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -9,9 +9,6 @@ from tqdm import tqdm from lamaria import logger -from lamaria.utils.imu import ( - RIGHT_IMU_STREAM_ID, -) from lamaria.utils.camera import ( LEFT_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, @@ -20,6 +17,9 @@ extract_images_from_vrs, get_matched_timestamps, ) +from lamaria.utils.imu import ( + RIGHT_IMU_STREAM_ID, +) def remove_images_when_slam_drops( From 4b0101535c4936d22092baa0293d5b693ba38649 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 12:53:41 +0200 Subject: [PATCH 331/665] ruff edits --- lamaria/pipeline/keyframing/to_colmap.py | 12 ++++++------ lamaria/pipeline/optim/callback.py | 2 +- lamaria/utils/general.py | 2 +- lamaria/utils/transformation.py | 4 ++-- tools/asl_folder_to_rosbag.py | 4 ++-- tools/download_lamaria.py | 14 +++++++------- tools/vrs_to_asl_folder.py | 2 +- 7 files changed, 20 insertions(+), 20 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index 03165bc..579492f 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -254,7 +254,7 @@ def _ts_from_vrs(self, sid: StreamId) -> list[int]: self._vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME) ) - def _get_images(self, images: Path) -> list[Tuple[Path, Path]]: + def _get_images(self, images: Path) -> list[tuple[Path, Path]]: left_img_dir = images / "left" right_img_dir = images / "right" @@ -263,7 +263,7 @@ def _get_images(self, images: Path) -> list[Tuple[Path, Path]]: return list(zip(left_images, right_images)) - def _get_mps_timestamps(self, max_diff=1e6) -> list[Tuple[int, int]]: + def _get_mps_timestamps(self, max_diff=1e6) -> list[tuple[int, int]]: L = self._ts_from_vrs(self._left_cam_sid) R = self._ts_from_vrs(self._right_cam_sid) if not self.options.mps.has_slam_drops: @@ -282,10 +282,10 @@ def _get_mps_timestamps(self, max_diff=1e6) -> list[Tuple[int, int]]: def _match_estimate_ts_to_images( self, - images: list[Tuple[Path, Path]], + images: list[tuple[Path, Path]], est_timestamps: list[int], max_diff: int = 1000000, # 1 ms - ) -> Tuple[list[Tuple[Path, Path]], list[int]]: + ) -> tuple[list[tuple[Path, Path]], list[int]]: left_ts = self._ts_from_vrs(self._left_cam_sid) assert len(images) == len(left_ts), ( "Number of images and left timestamps must be equal" @@ -295,7 +295,7 @@ def _match_estimate_ts_to_images( left_ts = [left_ts[i] for i in order] images = [images[i] for i in order] - matched_images: list[Tuple[Path, Path]] = [] + matched_images: list[tuple[Path, Path]] = [] matched_timestamps: list[int] = [] # estimate timestamps will be in nanoseconds like vrs timestamps @@ -320,7 +320,7 @@ def _match_estimate_ts_to_images( return matched_images, matched_timestamps - def _get_dummy_imu_params(self) -> Tuple[int, int, list[float]]: + def _get_dummy_imu_params(self) -> tuple[int, int, list[float]]: """Generates dummy IMU camera parameters for COLMAP.""" width = 640 height = 480 diff --git a/lamaria/pipeline/optim/callback.py b/lamaria/pipeline/optim/callback.py index 816a221..3a0ba45 100644 --- a/lamaria/pipeline/optim/callback.py +++ b/lamaria/pipeline/optim/callback.py @@ -12,7 +12,7 @@ class RefinementCallback(pyceres.IterationCallback): def __init__( self, poses: list[pycolmap.Rigid3d], - min_pose_change: Tuple[float, float] = (0.001, 0.000001), + min_pose_change: tuple[float, float] = (0.001, 0.000001), min_iterations: int = 2, ): pyceres.IterationCallback.__init__(self) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 9390c17..f18a00d 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -40,7 +40,7 @@ def get_matched_timestamps( left_timestamps: list[int], right_timestamps: list[int], max_diff: float, -) -> list[Tuple[int, int]]: +) -> list[tuple[int, int]]: matched_timestamps = [] assert all(isinstance(ts, int) for ts in left_timestamps), ( diff --git a/lamaria/utils/transformation.py b/lamaria/utils/transformation.py index 7c524c2..6368977 100644 --- a/lamaria/utils/transformation.py +++ b/lamaria/utils/transformation.py @@ -97,7 +97,7 @@ def get_t_imu_camera( def get_qvec_and_tvec_from_transform( transform, -) -> Tuple[np.ndarray, np.ndarray]: +) -> tuple[np.ndarray, np.ndarray]: """Converts projectaria_tools Rigid3d to qvec and tvec. Returns qvec in format x,y,z,w and tvec in format x,y,z""" # to_quat() returns in wxyz format @@ -120,7 +120,7 @@ def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: def get_magnitude_from_transform( transform: pycolmap.Rigid3d, -) -> Tuple[float, float]: +) -> tuple[float, float]: """Returns rotation (in degrees) and translation (in meters) magnitudes from a Rigid3d transform""" translation = transform.translation quat_xyzw = transform.rotation.quat diff --git a/tools/asl_folder_to_rosbag.py b/tools/asl_folder_to_rosbag.py index e535ed6..8c0e5177 100644 --- a/tools/asl_folder_to_rosbag.py +++ b/tools/asl_folder_to_rosbag.py @@ -27,8 +27,8 @@ class CamSample: @dataclass(frozen=True) class ImuSample: ts_ns: int - gyro: Tuple[float, float, float] - accel: Tuple[float, float, float] + gyro: tuple[float, float, float] + accel: tuple[float, float, float] topic: str frame_id: str diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 2effc75..3d2d17f 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -54,7 +54,7 @@ def fetch_index(full_url: str) -> list[str]: return hrefs -def build_catalog(base_url: str) -> Dict[str, list[Tuple[str, str]]]: +def build_catalog(base_url: str) -> Dict[str, list[tuple[str, str]]]: catalog = {} for folder in FOLDERS: entries = [] @@ -87,8 +87,8 @@ def names_from_listing(files: Iterable[str]) -> list[str]: def derive_splits( - catalog: Dict[str, list[Tuple[str, str]]], -) -> Tuple[list[str], list[str]]: + catalog: Dict[str, list[tuple[str, str]]], +) -> tuple[list[str], list[str]]: raw_entries = catalog.get("raw_data", []) train_files = [fname for (sub, fname) in raw_entries if sub == "training/"] test_files = [fname for (sub, fname) in raw_entries if sub == "test/"] @@ -97,7 +97,7 @@ def derive_splits( return train, test -def raw_split_map(catalog: Dict[str, list[Tuple[str, str]]]) -> Dict[str, str]: +def raw_split_map(catalog: Dict[str, list[tuple[str, str]]]) -> Dict[str, str]: mapping: Dict[str, str] = {} for sub, fname in catalog.get("raw_data", []): if sub not in ("training/", "test/"): @@ -112,12 +112,12 @@ def raw_split_map(catalog: Dict[str, list[Tuple[str, str]]]) -> Dict[str, str]: def pick_files_for_sequence( - catalog: Dict[str, list[Tuple[str, str]]], + catalog: Dict[str, list[tuple[str, str]]], sequence: str, folders: list[str], split: str | None, -) -> list[Tuple[str, str, str]]: - matches: list[Tuple[str, str, str]] = [] +) -> list[tuple[str, str, str]]: + matches: list[tuple[str, str, str]] = [] for folder in folders: for sub, fname in catalog.get(folder, []): if folder != "ground_truth" and split is not None and sub != split: diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index 8b4dcda..d347434 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -26,7 +26,7 @@ def remove_images_when_slam_drops( image_folder: Path, left_timestamps: list[int], right_timestamps: list[int], - matched_timestamps: list[Tuple[int, int]], + matched_timestamps: list[tuple[int, int]], left_subfolder_name="cam0/data", right_subfolder_name="cam1/data", ): From 41c72b788a363e9d69937bda198e5d5d3ac2da64 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 12:54:13 +0200 Subject: [PATCH 332/665] ruff --- lamaria/pipeline/keyframing/to_colmap.py | 2 +- lamaria/pipeline/optim/callback.py | 1 - lamaria/utils/general.py | 2 +- lamaria/utils/transformation.py | 1 - tools/asl_folder_to_rosbag.py | 1 - tools/download_lamaria.py | 2 +- tools/vrs_to_asl_folder.py | 1 - 7 files changed, 3 insertions(+), 7 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index 579492f..5e545c1 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -1,7 +1,7 @@ from bisect import bisect_left from dataclasses import dataclass from pathlib import Path -from typing import Dict, Optional, Tuple +from typing import Dict, Optional import projectaria_tools.core.mps as mps import pycolmap diff --git a/lamaria/pipeline/optim/callback.py b/lamaria/pipeline/optim/callback.py index 3a0ba45..e888560 100644 --- a/lamaria/pipeline/optim/callback.py +++ b/lamaria/pipeline/optim/callback.py @@ -1,5 +1,4 @@ from copy import deepcopy -from typing import Tuple import numpy as np import pyceres diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index f18a00d..54a498e 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -3,7 +3,7 @@ import subprocess from bisect import bisect_left from pathlib import Path -from typing import Dict, Tuple +from typing import Dict import pycolmap diff --git a/lamaria/utils/transformation.py b/lamaria/utils/transformation.py index 6368977..b00ed87 100644 --- a/lamaria/utils/transformation.py +++ b/lamaria/utils/transformation.py @@ -1,6 +1,5 @@ import json from pathlib import Path -from typing import Tuple import numpy as np import pycolmap diff --git a/tools/asl_folder_to_rosbag.py b/tools/asl_folder_to_rosbag.py index 8c0e5177..32ca307 100644 --- a/tools/asl_folder_to_rosbag.py +++ b/tools/asl_folder_to_rosbag.py @@ -4,7 +4,6 @@ import csv from dataclasses import dataclass from pathlib import Path -from typing import Tuple import cv2 import rosbag diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 3d2d17f..8eb28fc 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -5,7 +5,7 @@ import sys from collections.abc import Iterable from pathlib import Path -from typing import Dict, Tuple +from typing import Dict import requests from bs4 import BeautifulSoup diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index d347434..fbe2d81 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -2,7 +2,6 @@ import csv import os from pathlib import Path -from typing import Tuple from projectaria_tools.core import data_provider from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions From 5d6d3052b4ab4809f1b11db07af1585ea23a1786 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 12:56:41 +0200 Subject: [PATCH 333/665] ruff edits --- lamaria/__init__.py | 2 +- lamaria/eval/sparse_evaluation.py | 10 +++++----- lamaria/pipeline/keyframing/keyframe_selection.py | 4 ++-- lamaria/pipeline/keyframing/to_colmap.py | 10 +++++----- lamaria/pipeline/lamaria_reconstruction.py | 2 +- lamaria/pipeline/optim/imu.py | 4 ++-- lamaria/utils/control_point.py | 8 ++++---- lamaria/utils/general.py | 2 +- tools/download_lamaria.py | 10 +++++----- tools/undistort_asl_folder.py | 4 ++-- 10 files changed, 28 insertions(+), 28 deletions(-) diff --git a/lamaria/__init__.py b/lamaria/__init__.py index c1dd40c..9a89983 100644 --- a/lamaria/__init__.py +++ b/lamaria/__init__.py @@ -10,4 +10,4 @@ logger = logging.getLogger(__name__) logger.setLevel(logging.INFO) logger.addHandler(handler) -logger.propagate = False \ No newline at end of file +logger.propagate = False diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 1cd0333..60205f6 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -17,7 +17,7 @@ ) -def update_sim3d_scale(variables: Dict): +def update_sim3d_scale(variables: dict): if "log_scale" not in variables: raise ValueError("log_scale not found in variables") @@ -26,8 +26,8 @@ def update_sim3d_scale(variables: Dict): def create_variables_for_sparse_evaluation( - control_points: Dict, sim3d: pycolmap.Sim3d, cp_reproj_std: float = 1.0 -) -> Dict: + control_points: dict, sim3d: pycolmap.Sim3d, cp_reproj_std: float = 1.0 +) -> dict: variables = {} variables["control_points"] = copy.deepcopy(control_points) variables["sim3d"] = copy.deepcopy(sim3d) @@ -40,7 +40,7 @@ def create_variables_for_sparse_evaluation( def get_problem_for_sparse_alignment( reconstruction: pycolmap.Reconstruction, - variables: Dict, + variables: dict, ): problem = pyceres.Problem() problem = add_alignment_residuals( @@ -58,7 +58,7 @@ def get_problem_for_sparse_alignment( def add_alignment_residuals( problem, reconstruction: pycolmap.Reconstruction, - variables: Dict, + variables: dict, ) -> pyceres.Problem: if ( variables["control_points"] is not None diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index d49ef79..4573130 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -27,7 +27,7 @@ def __init__( self.timestamps = data.timestamps # frame id to timestamp mapping self.keyframed_data: LamariaReconstruction = LamariaReconstruction() - self.keyframe_frame_ids: Optional[Dict[int, int]] = None + self.keyframe_frame_ids: Optional[dict[int, int]] = None @staticmethod def run( @@ -45,7 +45,7 @@ def run( return kf_recon def _select_keyframes(self): - self.keyframe_frame_ids: Dict[int, int] = {} + self.keyframe_frame_ids: dict[int, int] = {} dr_dt = np.array([0.0, 0.0]) dts = 0.0 diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index 5e545c1..fe283ae 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -55,7 +55,7 @@ def __init__(self, options: EstimateToColmapOptions): self._left_cam_sid: StreamId | None = None self._right_cam_sid: StreamId | None = None self._right_imu_sid: StreamId | None = None - self._per_frame_data: Dict[int, PerFrameData] = {} + self._per_frame_data: dict[int, PerFrameData] = {} @staticmethod def convert( @@ -167,8 +167,8 @@ def _init_data( def _build_per_frame_data_from_mps( self, images, timestamps, mps_poses - ) -> Dict[int, PerFrameData]: - per_frame_data: Dict[int, PerFrameData] = {} + ) -> dict[int, PerFrameData]: + per_frame_data: dict[int, PerFrameData] = {} imu_stream_label = self._vrs_provider.get_label_from_stream_id( self._right_imu_sid ) @@ -216,8 +216,8 @@ def _build_per_frame_data_from_mps( def _build_per_frame_data_from_estimate( self, images, timestamps, rig_from_worlds - ) -> Dict[int, PerFrameData]: - per_frame_data: Dict[int, PerFrameData] = {} + ) -> dict[int, PerFrameData]: + per_frame_data: dict[int, PerFrameData] = {} assert len(images) == len(timestamps) == len(rig_from_worlds), ( "Number of images, timestamps and poses must be equal" ) diff --git a/lamaria/pipeline/lamaria_reconstruction.py b/lamaria/pipeline/lamaria_reconstruction.py index 98fda19..bb982f9 100644 --- a/lamaria/pipeline/lamaria_reconstruction.py +++ b/lamaria/pipeline/lamaria_reconstruction.py @@ -8,7 +8,7 @@ class LamariaReconstruction: def __init__(self) -> None: self.reconstruction = pycolmap.Reconstruction() - self.timestamps: Dict[int, int] = {} + self.timestamps: dict[int, int] = {} self.imu_measurements = pycolmap.ImuMeasurements([]) @staticmethod diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 52f7f03..5402df0 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -11,7 +11,7 @@ def load_preintegrated_imu_measurements( options: OptIMUOptions, data: LamariaReconstruction, -) -> Dict[int, pycolmap.PreintegratedImuMeasurement]: +) -> dict[int, pycolmap.PreintegratedImuMeasurement]: preintegrated_measurements = {} imu_measurements = data.imu_measurements @@ -53,7 +53,7 @@ def load_preintegrated_imu_measurements( def load_imu_states( data: LamariaReconstruction, -) -> Dict[int, pycolmap.ImuState]: +) -> dict[int, pycolmap.ImuState]: imu_states = {} frame_ids = sorted(data.reconstruction.frames.keys()) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 966ce8c..d86eb5e 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -14,7 +14,7 @@ def construct_control_points_from_json( cp_json_file: Path, -) -> Dict: +) -> dict: """Construct control points dict from JSON file Args: cp_json_file (Path): Path to the sparse GT JSON file @@ -89,7 +89,7 @@ def transform_points(points, r, t, scale): return transformed_points -def transform_triangulated_control_points(control_points: Dict, r, t, scale): +def transform_triangulated_control_points(control_points: dict, r, t, scale): for tag_id, cp in control_points.items(): triangulated_point = cp["triangulated"] triangulated_point = scale * r.apply(triangulated_point) + t @@ -101,7 +101,7 @@ def transform_triangulated_control_points(control_points: Dict, r, t, scale): def run_control_point_triangulation_from_json( reconstruction_path: Path, cp_json_file: Path, - control_points: Dict, # edits control_points in place + control_points: dict, # edits control_points in place ) -> None: rec = pycolmap.Reconstruction(reconstruction_path) @@ -175,7 +175,7 @@ def run_control_point_triangulation_from_json( control_points[tag_id]["image_id_and_point2d"] = image_ids_and_centers -def get_cps_for_initial_alignment(control_points: Dict): +def get_cps_for_initial_alignment(control_points: dict): triangulated_cp_alignment = [] topo_cp_alignment = [] for tag_id, cp in control_points.items(): diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 54a498e..b8d9c9e 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -129,7 +129,7 @@ def extract_images_from_vrs( logger.info("Done!") -def get_image_names_to_ids(reconstruction_path: Path) -> Dict[str, int]: +def get_image_names_to_ids(reconstruction_path: Path) -> dict[str, int]: recon = pycolmap.Reconstruction(reconstruction_path) image_names_to_ids = {} diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 8eb28fc..1c73891 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -54,7 +54,7 @@ def fetch_index(full_url: str) -> list[str]: return hrefs -def build_catalog(base_url: str) -> Dict[str, list[tuple[str, str]]]: +def build_catalog(base_url: str) -> dict[str, list[tuple[str, str]]]: catalog = {} for folder in FOLDERS: entries = [] @@ -87,7 +87,7 @@ def names_from_listing(files: Iterable[str]) -> list[str]: def derive_splits( - catalog: Dict[str, list[tuple[str, str]]], + catalog: dict[str, list[tuple[str, str]]], ) -> tuple[list[str], list[str]]: raw_entries = catalog.get("raw_data", []) train_files = [fname for (sub, fname) in raw_entries if sub == "training/"] @@ -97,8 +97,8 @@ def derive_splits( return train, test -def raw_split_map(catalog: Dict[str, list[tuple[str, str]]]) -> Dict[str, str]: - mapping: Dict[str, str] = {} +def raw_split_map(catalog: dict[str, list[tuple[str, str]]]) -> dict[str, str]: + mapping: dict[str, str] = {} for sub, fname in catalog.get("raw_data", []): if sub not in ("training/", "test/"): continue @@ -112,7 +112,7 @@ def raw_split_map(catalog: Dict[str, list[tuple[str, str]]]) -> Dict[str, str]: def pick_files_for_sequence( - catalog: Dict[str, list[tuple[str, str]]], + catalog: dict[str, list[tuple[str, str]]], sequence: str, folders: list[str], split: str | None, diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index 52859b0..f8f8310 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -22,7 +22,7 @@ def undistort_reconstruction( output_path: Path, ratio_blank_pixels: float = 0.2, verbose: bool = False, -) -> Dict[int, pycolmap.Camera]: +) -> dict[int, pycolmap.Camera]: with tempfile.TemporaryDirectory() as tmp_path: tmp_path = Path(tmp_path) @@ -59,7 +59,7 @@ def undistort_reconstruction( return cameras -def write_cameras_json(cameras: Dict[int | str, pycolmap.Camera], path: Path): +def write_cameras_json(cameras: dict[int | str, pycolmap.Camera], path: Path): camera_dicts = {} for key, c in cameras.items(): d = d = c.todict() From a457b13102baa16b64f46ab3fc9af66d6b5f75e3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 12:57:07 +0200 Subject: [PATCH 334/665] ruff edits --- lamaria/eval/sparse_evaluation.py | 1 - lamaria/pipeline/keyframing/keyframe_selection.py | 2 +- lamaria/pipeline/keyframing/to_colmap.py | 2 +- lamaria/pipeline/lamaria_reconstruction.py | 1 - lamaria/pipeline/optim/imu.py | 1 - lamaria/utils/control_point.py | 1 - lamaria/utils/general.py | 1 - tools/download_lamaria.py | 1 - tools/undistort_asl_folder.py | 1 - 9 files changed, 2 insertions(+), 9 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 60205f6..fe1bb02 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -2,7 +2,6 @@ import copy import os from pathlib import Path -from typing import Dict import numpy as np import pyceres diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 4573130..5eb5e5d 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -3,7 +3,7 @@ import shutil from copy import deepcopy from pathlib import Path -from typing import Dict, Optional +from typing import Optional import numpy as np import pycolmap diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index fe283ae..4ccb12b 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -1,7 +1,7 @@ from bisect import bisect_left from dataclasses import dataclass from pathlib import Path -from typing import Dict, Optional +from typing import Optional import projectaria_tools.core.mps as mps import pycolmap diff --git a/lamaria/pipeline/lamaria_reconstruction.py b/lamaria/pipeline/lamaria_reconstruction.py index bb982f9..00bc06e 100644 --- a/lamaria/pipeline/lamaria_reconstruction.py +++ b/lamaria/pipeline/lamaria_reconstruction.py @@ -1,5 +1,4 @@ from pathlib import Path -from typing import Dict import numpy as np import pycolmap diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 5402df0..8fc8580 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -1,4 +1,3 @@ -from typing import Dict import numpy as np import pycolmap diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index d86eb5e..149b425 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -1,6 +1,5 @@ import json from pathlib import Path -from typing import Dict import numpy as np import pycolmap diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index b8d9c9e..280132b 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -3,7 +3,6 @@ import subprocess from bisect import bisect_left from pathlib import Path -from typing import Dict import pycolmap diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 1c73891..8458c63 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -5,7 +5,6 @@ import sys from collections.abc import Iterable from pathlib import Path -from typing import Dict import requests from bs4 import BeautifulSoup diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index f8f8310..e6a60e6 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -5,7 +5,6 @@ import subprocess import tempfile from pathlib import Path -from typing import Dict import pycolmap from tqdm import tqdm From 8dc271e40e0d841d875c80b23c281c10b398d955 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 13:01:44 +0200 Subject: [PATCH 335/665] ruff edits --- lamaria/pipeline/optim/imu.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 8fc8580..f90929a 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -1,4 +1,3 @@ - import numpy as np import pycolmap from tqdm import tqdm From a55c7f00cb7b6b2537d8c80d58ed3a7cdc08ecea Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 13:04:06 +0200 Subject: [PATCH 336/665] options --- lamaria/config/options.py | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 1f06ed1..81a3f99 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -1,7 +1,6 @@ from __future__ import annotations from dataclasses import dataclass, field, replace -from typing import Optional from omegaconf import OmegaConf, open_dict @@ -29,7 +28,7 @@ class MPSOptions: ) @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> MPSOptions: + def load(cls, cfg: OmegaConf | None = None) -> MPSOptions: if cfg is None: return cls() @@ -44,7 +43,7 @@ class SensorOptions: camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> SensorOptions: + def load(cls, cfg: OmegaConf | None = None) -> SensorOptions: if cfg is None: return cls() @@ -61,8 +60,8 @@ class EstimateToColmapOptions: @classmethod def load( cls, - cfg_mps: Optional[OmegaConf] = None, - cfg_sensor: Optional[OmegaConf] = None, + cfg_mps: OmegaConf | None = None, + cfg_sensor: OmegaConf | None = None, ) -> EstimateToColmapOptions: if cfg_mps is None or cfg_sensor is None: return cls() @@ -83,7 +82,7 @@ class KeyframeSelectorOptions: max_elapsed: int = int(1e9) # 1 second in ns @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> KeyframeSelectorOptions: + def load(cls, cfg: OmegaConf | None = None) -> KeyframeSelectorOptions: if cfg is None: return cls() @@ -113,7 +112,7 @@ class TriangulatorOptions: filter_min_tri_angle: float = 1.5 @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> TriangulatorOptions: + def load(cls, cfg: OmegaConf | None = None) -> TriangulatorOptions: if cfg is None: return cls() @@ -158,7 +157,7 @@ class VIOptimizerOptions: optim: OptOptions = field(default_factory=OptOptions) @classmethod - def load(cls, cfg: Optional[OmegaConf] = None) -> VIOptimizerOptions: + def load(cls, cfg: OmegaConf | None = None) -> VIOptimizerOptions: if cfg is None: return cls() From 7f0a7af80c9c8cb1fd5916122a222ed597be7928 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 13:25:48 +0200 Subject: [PATCH 337/665] ruff fixes --- lamaria/config/pipeline.py | 2 +- lamaria/pipeline/keyframing/keyframe_selection.py | 2 +- lamaria/pipeline/keyframing/to_colmap.py | 14 +++++++------- lamaria/utils/imu.py | 2 +- run_pipeline.py | 4 ++-- 5 files changed, 12 insertions(+), 12 deletions(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index b988606..409a372 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -27,7 +27,7 @@ def __init__(self) -> None: def load( self, yaml: Path | str, - cli_overrides: Optional[Sequence[str]] = None, + cli_overrides: Sequence[str] | None = None, ) -> None: """Load configuration from a YAML file and apply any overrides.""" cfg = OmegaConf.load(str(yaml)) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 5eb5e5d..4a65304 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -27,7 +27,7 @@ def __init__( self.timestamps = data.timestamps # frame id to timestamp mapping self.keyframed_data: LamariaReconstruction = LamariaReconstruction() - self.keyframe_frame_ids: Optional[dict[int, int]] = None + self.keyframe_frame_ids: dict[int, int] = {} @staticmethod def run( diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index 4ccb12b..540363a 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -62,8 +62,8 @@ def convert( options: EstimateToColmapOptions, vrs: Path, images: Path, - estimate: Optional[Path] = None, - mps_folder: Optional[Path] = None, + estimate: Path | None = None, + mps_folder: Path | None = None, ) -> LamariaReconstruction: """Entry point to run estimate/MPS to colmap conversion.""" to_colmap = EstimateToColmap(options) @@ -73,8 +73,8 @@ def process( self, vrs: Path, images: Path, - estimate: Optional[Path] = None, - mps_folder: Optional[Path] = None, + estimate: Path | None = None, + mps_folder: Path | None = None, ) -> LamariaReconstruction: self._init_data(vrs, images, estimate, mps_folder) @@ -98,8 +98,8 @@ def _init_data( self, vrs: Path, image_folder: Path, - estimate: Optional[Path] = None, - mps_folder: Optional[Path] = None, + estimate: Path | None = None, + mps_folder: Path | None = None, ) -> None: """Initializes data providers and extracts images, timestamps and builds per-frame data object. Per-frame data is used to create the initial Lamaria reconstruction. @@ -523,7 +523,7 @@ def _add_online_frames(self) -> None: def _get_rectified_imu_data( self, - mps_folder: Optional[Path] = None, + mps_folder: Path | None = None, ) -> pycolmap.ImuMeasurements: """Generates rectified IMU data from VRS file""" if self.options.mps.use_online_calibration and self.options.mps.use_mps: diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index fcdd423..70bda60 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -37,7 +37,7 @@ def get_online_params_for_imu_from_mps( def get_imu_data_from_vrs( vrs_provider: data_provider.VrsDataProvider, - mps_folder: Optional[Path] = None, + mps_folder: Path | None = None, ) -> pycolmap.ImuMeasurements: """Get rectified IMU data from VRS file. If mps_folder is provided, use online calibration data from MPS folder. Otherwise, use device calibration from VRS file.""" diff --git a/run_pipeline.py b/run_pipeline.py index 4ae55cd..192d25f 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -178,8 +178,8 @@ def run_pipeline( options: PipelineOptions, vrs: Path, output_path: Path, - estimate: Optional[Path] = None, - mps_folder: Optional[Path] = None, + estimate: Path | None = None, + mps_folder: Path | None = None, ): # Setting output path for entire pipeline options.output_path = output_path From 5dc6cae0efef2a33af4625fb61d404858654170e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 13:26:41 +0200 Subject: [PATCH 338/665] ruff fixes --- lamaria/config/pipeline.py | 1 - lamaria/pipeline/keyframing/keyframe_selection.py | 1 - lamaria/pipeline/keyframing/to_colmap.py | 1 - lamaria/utils/imu.py | 1 - run_pipeline.py | 1 - 5 files changed, 5 deletions(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 409a372..dd4de11 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -1,6 +1,5 @@ from collections.abc import Sequence from pathlib import Path -from typing import Optional from omegaconf import DictConfig, OmegaConf diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 4a65304..1796e1f 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -3,7 +3,6 @@ import shutil from copy import deepcopy from pathlib import Path -from typing import Optional import numpy as np import pycolmap diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index 540363a..d36a566 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -1,7 +1,6 @@ from bisect import bisect_left from dataclasses import dataclass from pathlib import Path -from typing import Optional import projectaria_tools.core.mps as mps import pycolmap diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index 70bda60..608874d 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -1,5 +1,4 @@ from pathlib import Path -from typing import Optional import pycolmap from projectaria_tools.core import data_provider, mps diff --git a/run_pipeline.py b/run_pipeline.py index 192d25f..77fa107 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -1,7 +1,6 @@ import argparse import shutil from pathlib import Path -from typing import Optional import pycolmap From 09c49d1d57bfbf88bca5831cd241799ee7a6b857 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 13:59:46 +0200 Subject: [PATCH 339/665] more ruff fixes --- lamaria/pipeline/keyframing/to_colmap.py | 6 +- lamaria/utils/control_point.py | 9 +-- lamaria/utils/estimate.py | 78 +++++++++++++----------- lamaria/utils/general.py | 4 +- lamaria/utils/imu.py | 5 +- lamaria/utils/transformation.py | 25 +++++--- tools/asl_folder_to_rosbag.py | 3 +- tools/download_lamaria.py | 15 +++-- 8 files changed, 88 insertions(+), 57 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index d36a566..f6306c1 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -147,9 +147,9 @@ def _init_data( assert estimate is not None, ( "Estimate path must be provided if not using MPS" ) - flag = check_estimate_format(estimate) - if not flag: - raise ValueError("Estimate file format is incorrect.") + + # Raises error if estimate file is invalid + check_estimate_format(estimate) timestamps = get_estimate_timestamps(estimate) if len(images) != len(timestamps): diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 149b425..5fc89ad 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -26,9 +26,10 @@ def construct_control_points_from_json( measurement = data["measurement"] unc = data["uncertainty"] - if measurement[2] == None: - assert unc[2] == None, ( - "Uncertainty for z coordinate should be None if measurement is None" + if measurement[2] is None: + assert unc[2] is None, ( + "Uncertainty for z coordinate " + "should be None if measurement is None" ) measurement[2] = CUSTOM_ORIGIN_COORDINATES[2] unc[2] = 1e9 # some large number @@ -89,7 +90,7 @@ def transform_points(points, r, t, scale): def transform_triangulated_control_points(control_points: dict, r, t, scale): - for tag_id, cp in control_points.items(): + for _tag_id, cp in control_points.items(): triangulated_point = cp["triangulated"] triangulated_point = scale * r.apply(triangulated_point) + t cp["triangulated"] = triangulated_point diff --git a/lamaria/utils/estimate.py b/lamaria/utils/estimate.py index c571f54..b9795cd 100644 --- a/lamaria/utils/estimate.py +++ b/lamaria/utils/estimate.py @@ -18,18 +18,20 @@ def get_rig_from_worlds_from_estimate( ) -> list[pycolmap.Rigid3d]: """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - rig_from_worlds = [] + rig_from_worlds: list[pycolmap.Rigid3d] = [] + with open(estimate_path) as f: lines = f.readlines() - for line in lines: - if line.startswith("#"): + for lineno, line in enumerate(lines, start=1): + line = line.strip() + if not line or line.startswith("#"): continue - parts = line.strip().split() + parts = line.split() if len(parts) != 8: raise ValueError( - f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values." + f"{estimate_path}:{lineno}: " + f"expected 8 values, got {len(parts)}" ) try: @@ -44,11 +46,11 @@ def get_rig_from_worlds_from_estimate( float(parts[7]), ] ) - except ValueError: + except ValueError as e: raise ValueError( - f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number." - ) + f"{estimate_path}:{lineno}: " + f"expected a number, got {parts!r}" + ) from e pose = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) rig_from_world = pose.inverse() @@ -59,32 +61,36 @@ def get_rig_from_worlds_from_estimate( def check_estimate_format(estimate_path: Path) -> bool: """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" + + exists_lines = False with open(estimate_path) as f: lines = f.readlines() - lines = [line for line in lines if not line.startswith("#")] - if not lines: - raise ValueError( - f"Estimate file {estimate_path} is empty \ - or has no valid lines." - ) + for lineno, line in enumerate(lines, start=1): + line = line.strip() + if not line or line.startswith("#"): + continue - for line in lines: - parts = line.strip().split() + exists_lines = True + + parts = line.split() if len(parts) != 8: raise ValueError( - f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values." + f"{estimate_path}:{lineno}: expected " + f"8 values, got {len(parts)}" ) try: [float(part) for part in parts] - except ValueError: + except ValueError as e: raise ValueError( - f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number." - ) + f"{estimate_path}:{lineno}: " + f"expected a number, got {parts!r}" + ) from e - return True + if not exists_lines: + raise ValueError( + f"Estimate file {estimate_path} is empty or has no valid lines." + ) def get_estimate_timestamps(estimate_path: Path) -> list[int]: @@ -96,24 +102,28 @@ def get_estimate_timestamps(estimate_path: Path) -> list[int]: if not lines: raise ValueError( f"Estimate file {estimate_path} is empty \ - or has no valid lines." + or has no valid lines." ) - for line in lines: - parts = line.strip().split() + for lineno, line in enumerate(lines, start=1): + line = line.strip() + if not line or line.startswith("#"): + continue + + parts = line.split() if len(parts) != 8: raise ValueError( - f"Estimate file {estimate_path} has invalid format. \ - Each line must have 8 values." + f"{estimate_path}:{lineno}: " + f"expected 8 values, got {len(parts)}" ) try: ts = round_ns(parts[0]) - except ValueError: + except ValueError as e: raise ValueError( - f"Estimate file {estimate_path} has invalid format. \ - Each value must be a number." - ) + f"{estimate_path}:{lineno}: " + f"expected a number, got {parts[0]!r}" + ) from e timestamps.append(ts) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 280132b..2d9cedb 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -79,7 +79,7 @@ def delete_files_in_folder(folder, exclude_pattern=None): elif os.path.isdir(file_path): shutil.rmtree(file_path) except Exception as e: - print("Failed to delete %s. Reason: %s" % (file_path, e)) + print(f"Failed to delete {file_path}. Reason: {e}") else: os.makedirs(folder, exist_ok=True) @@ -132,7 +132,7 @@ def get_image_names_to_ids(reconstruction_path: Path) -> dict[str, int]: recon = pycolmap.Reconstruction(reconstruction_path) image_names_to_ids = {} - for image_id in recon.images.keys(): + for image_id in recon.images: image_name = recon.images[image_id].name image_names_to_ids[image_name] = image_id diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index 608874d..9ac9d03 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -38,8 +38,9 @@ def get_imu_data_from_vrs( vrs_provider: data_provider.VrsDataProvider, mps_folder: Path | None = None, ) -> pycolmap.ImuMeasurements: - """Get rectified IMU data from VRS file. If mps_folder is provided, use online - calibration data from MPS folder. Otherwise, use device calibration from VRS file.""" + """Get rectified IMU data from VRS file. + If mps_folder is provided, use online calibration data + from MPS folder. Otherwise, use device calibration from VRS file.""" imu_timestamps = sorted( vrs_provider.get_timestamps_ns( RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME diff --git a/lamaria/utils/transformation.py b/lamaria/utils/transformation.py index b00ed87..42a7903 100644 --- a/lamaria/utils/transformation.py +++ b/lamaria/utils/transformation.py @@ -22,8 +22,11 @@ def get_mps_poses_for_timestamps( trajectory_data: list[mps.ClosedLoopTrajectoryPose], timestamps: list[int], ) -> list: - """Get T_world_device for a list of device timestamps in nanoseconds using MPS trajectory data. - Returns None for timestamps where no trajectory data is found.""" + """Get T_world_device for a list of device timestamps + in nanoseconds using MPS trajectory data. + Returns None for timestamps where + no trajectory data is found. + """ poses = [] if trajectory_data: for ts in timestamps: @@ -42,8 +45,10 @@ def get_t_rig_world_for_device_time_ns( device_time_ns: int, imu_calibration: ImuCalibration, ): - """Get T_rig_world (rig is right IMU sensor) for a given device time in nanoseconds using MPS trajectory data and IMU calibration. - Returns None if no trajectory data is found for the given timestamp.""" + """Get T_rig_world (rig is right IMU sensor) for a given device time + in nanoseconds using MPS trajectory data and IMU calibration. + Returns None if no trajectory data is found for the given timestamp. + """ if trajectory_data: pose_information = get_nearest_pose(trajectory_data, device_time_ns) if pose_information: @@ -70,8 +75,11 @@ def get_t_imu_camera( return_qt=False, return_matrix=False, ): - """Get T_imu_camera from Aria calibrations. Either return as qvec,tvec or 4x4 matrix. - If neither return_qt or return_matrix is True, returns as projectaria_tools Rigid3d object.""" + """Get T_imu_camera from Aria calibrations. + Either return as qvec,tvec or 4x4 matrix. + If neither return_qt or return_matrix is True, + returns as projectaria_tools Rigid3d object. + """ t_device_cam = camera_calib.get_transform_device_camera() t_device_imu = imu_calib.get_transform_device_imu() @@ -120,7 +128,10 @@ def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: def get_magnitude_from_transform( transform: pycolmap.Rigid3d, ) -> tuple[float, float]: - """Returns rotation (in degrees) and translation (in meters) magnitudes from a Rigid3d transform""" + """Returns rotation (in degrees) and + translation (in meters) magnitudes + from a Rigid3d transform + """ translation = transform.translation quat_xyzw = transform.rotation.quat rotation = Rotation.from_quat(quat_xyzw) diff --git a/tools/asl_folder_to_rosbag.py b/tools/asl_folder_to_rosbag.py index 32ca307..e5fb5d7 100644 --- a/tools/asl_folder_to_rosbag.py +++ b/tools/asl_folder_to_rosbag.py @@ -123,7 +123,8 @@ def asl_to_rosbag( bag = rosbag.Bag(str(output_rosbag), "w") print( - f"[asl_to_rosbag] Writing {len(bag_timeline):,} messages -> {output_rosbag}" + f"[asl_to_rosbag] Writing {len(bag_timeline):,} " + f"messages -> {output_rosbag}" ) for ts_ns, kind, sample in tqdm( diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 8458c63..50451b6 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -184,7 +184,8 @@ def download_file( if total is not None and dest.stat().st_size != total: print( - f"[warn] Size mismatch for {dest} (expected {total}, got {dest.stat().st_size})" + f"[warn] Size mismatch for {dest} " + f"(expected {total}, got {dest.stat().st_size})" ) @@ -194,7 +195,10 @@ def main(): "--set", choices=["training", "test", "specific"], required=True, - help="What to download: training sequences, test sequences, or a specific list", + help=( + "What to download: training sequences, " + "test sequences, or a specific list", + ), ) parser.add_argument( "--type", @@ -205,7 +209,10 @@ def main(): parser.add_argument( "--sequences", nargs="+", - help="Sequence names (required for --set specific). Example: R_01_easy sequence_3_17", + help=( + "Sequence names (required for --set specific).\n" + "Example: R_01_easy sequence_3_17" + ), ) parser.add_argument( "--out-dir", @@ -298,7 +305,7 @@ def main(): print("\n[download] Starting downloads.") with requests.Session() as sess: - for _area, _sub, fname, url, dest in plan: + for _area, _sub, _fname, url, dest in plan: print(f"[get] {url}") try: download_file(url, dest, sess) From 781bd0fe86e663751a1138940787fcf8ecc4e164 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 14:09:52 +0200 Subject: [PATCH 340/665] final ruff edits --- .../eval/create_empty_recon_from_estimate.py | 18 ++++++++++++----- .../pipeline/keyframing/keyframe_selection.py | 13 ++++++++---- lamaria/pipeline/keyframing/to_colmap.py | 20 ++++++++++++------- lamaria/pipeline/optim/iterative_global_ba.py | 13 +++++++----- lamaria/pipeline/optim/residual.py | 2 +- lamaria/pipeline/optim/triangulation.py | 2 +- lamaria/utils/camera.py | 14 ++++++++----- lamaria/utils/control_point.py | 3 ++- 8 files changed, 56 insertions(+), 29 deletions(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index 9038025..d47bc97 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -29,7 +29,8 @@ def add_images_to_reconstruction( device_calibration_json: Path, slam_input_imu: int = 1, ): - """Add images to an existing empty reconstruction from a pose estimate file.""" + """Add images to an existing empty + reconstruction from a pose estimate file.""" pose_data = [] with open(estimate_file) as f: lines = f.readlines() @@ -141,11 +142,18 @@ def create_baseline_reconstruction( Args: estimate_file (Path): Path to the pose estimate file. + cp_json_file (Path): Path to the sparse GT json file. - device_calibration_json (Path): Path to the Aria device calibration json file. - output_path (Path): Path to the output folder where the reconstruction will be saved. - slam_input_imu (int, optional): If 1, the poses in the estimate file are IMU poses. - If 0, the poses are left camera poses (monocular-cam0). + + device_calibration_json (Path): + Path to the Aria device calibration json file. + + output_path (Path): Path to the output folder + where the reconstruction will be saved. + + slam_input_imu (int, optional): + If 1, the poses in the estimate file are IMU poses. + If 0, the poses are left camera poses (monocular-cam0). """ recon_path = output_path / "reconstruction" recon_path.mkdir(parents=True, exist_ok=True) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 1796e1f..3de887e 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -35,7 +35,9 @@ def run( original_image_dir: Path, keyframes_dir: Path, ) -> LamariaReconstruction: - """Entry point to run keyframing and copy keyframes into keyframe directory.""" + """Entry point to run keyframing and + copy keyframes into keyframe directory. + """ selector = KeyframeSelector(options, data) kf_recon = selector.run_keyframing() @@ -236,9 +238,12 @@ def copy_images_to_keyframes_dir( images: Path, output: Path, ) -> Path: - """Copy images corresponding to keyframes to a separate directory. - Images are expected to be in `images/left` and `images/right` subdirectories. - Check: `extract_images_from_vrs` in `lamaria/utils/general.py` for more details. + """Copy images corresponding to + keyframes to a separate directory. + Images are expected to be in `images/left` + and `images/right` subdirectories. + Check: `extract_images_from_vrs` in + `lamaria/utils/general.py` for more details. """ if self.keyframe_frame_ids is None: raise ValueError( diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_colmap.py index f6306c1..c9b6913 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_colmap.py @@ -100,7 +100,8 @@ def _init_data( estimate: Path | None = None, mps_folder: Path | None = None, ) -> None: - """Initializes data providers and extracts images, timestamps and builds per-frame data object. + """Initializes data providers and extracts images, timestamps + and builds per-frame data object. Per-frame data is used to create the initial Lamaria reconstruction. """ @@ -136,7 +137,7 @@ def _init_data( if self.options.mps.use_mps: timestamps = self._get_mps_timestamps() closed_loop_data = get_closed_loop_data_from_mps(mps_folder) - pose_timestamps = [l for l, _ in timestamps] + pose_timestamps = [left for left, _ in timestamps] mps_poses = get_mps_poses_for_timestamps( closed_loop_data, pose_timestamps ) @@ -270,9 +271,10 @@ def _get_mps_timestamps(self, max_diff=1e6) -> list[tuple[int, int]]: "Unequal number of left and right timestamps" ) matched = list(zip(L, R)) - if not all(abs(l - r) < max_diff for l, r in matched): + if not all(abs(left - right) < max_diff for left, right in matched): logger.warning( - f"Left and right timestamps differ by more than {max_diff} ns" + f"Left and right timestamps differ " + f"by more than {max_diff} ns" ) else: matched = get_matched_timestamps(L, R, max_diff) @@ -451,7 +453,9 @@ def _add_online_sensors(self) -> None: self.data.reconstruction.add_rig(rig) def _add_device_frames(self) -> None: - """Adds frame data for each rig, all rigs share same device calibrated sensors""" + """Adds frame data for each rig, + all rigs share same device calibrated sensors + """ image_id = 1 rig = self.data.reconstruction.rigs[1] @@ -479,7 +483,8 @@ def _add_device_frames(self) -> None: self.data.reconstruction.add_image(im) def _add_online_frames(self) -> None: - """Adds frame data for each rig, each rig has its own online calibrated sensors + """Adds frame data for each rig, each rig has + its own online calibrated sensors Frame ID layout: fid=1 -> (imu=1, left=2, right=3), (image IDs: 1, 2); @@ -497,7 +502,8 @@ def _add_online_frames(self) -> None: images_to_add = [] # Camera ID layout from _add_online_sensors(): - # fid=1 -> (imu=1, left=2, right=3); fid=2 -> (imu=4, left=5, right=6); ... + # fid=1 -> (imu=1, left=2, right=3); + # fid=2 -> (imu=4, left=5, right=6); ... left_cam_id = 3 * fid - 1 right_cam_id = 3 * fid diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index c19aa08..70ee6a1 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -148,7 +148,8 @@ def adjust( reg_image_ids = mapper.reconstruction.reg_image_ids() if len(reg_image_ids) < 2: logger.warning( - "At least two images must be registered for global bundle-adjustment" + "At least two images must be " + "registered for global bundle-adjustment" ) ba_options = self._configure_ba_options( @@ -177,7 +178,9 @@ def adjust( ) def _configure_ba_options(self, pipeline_options, num_reg_images): - """Configure bundle adjustment options based on number of registered images""" + """Configure bundle adjustment options based on + number of registered images and pipeline options. + """ ba_options = pipeline_options.get_global_bundle_adjustment() ba_options.print_summary = True ba_options.refine_rig_from_world = True # Refine rig poses @@ -224,17 +227,17 @@ def refine( # Configure triangulation options tri_options = pipeline_options.get_triangulation() mapper.complete_and_merge_tracks(tri_options) - num_retriangulated_observations = mapper.retriangulate(tri_options) + num_retri_obs = mapper.retriangulate(tri_options) logging.verbose( 1, - f"=> Retriangulated observations: {num_retriangulated_observations}", + f"=> Retriangulated observations: {num_retri_obs}", ) # Configure mapper options mapper_options = pipeline_options.get_mapper() # Iterative refinement - for i in range(pipeline_options.ba_global_max_refinements): + for _i in range(pipeline_options.ba_global_max_refinements): num_observations = mapper.reconstruction.compute_num_observations() GlobalBundleAdjustment.run( diff --git a/lamaria/pipeline/optim/residual.py b/lamaria/pipeline/optim/residual.py index 6dbcd17..7b11c5e 100644 --- a/lamaria/pipeline/optim/residual.py +++ b/lamaria/pipeline/optim/residual.py @@ -76,7 +76,7 @@ def setup_manifolds_and_constraints( problem.set_parameter_block_constant(session.imu_from_rig.translation) if not imu_options.optimize_bias: constant_idxs = np.arange(3, 9) - for frame_id in session.imu_states.keys(): + for frame_id in session.imu_states: problem.set_manifold( session.imu_states[frame_id].data, pyceres.SubsetManifold(9, constant_idxs), diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index 7538035..ce7c421 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -53,7 +53,7 @@ def pairs_from_frames(recon: pycolmap.Reconstruction): by_index[k].append(n) adj_pairs = set() - for idx, seq in by_index.items(): + for _idx, seq in by_index.items(): for a, b in zip(seq[:-1], seq[1:]): adj_pairs.add((a, b)) diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py index 2afe7e5..90600f3 100644 --- a/lamaria/utils/camera.py +++ b/lamaria/utils/camera.py @@ -19,12 +19,15 @@ def add_cameras_to_reconstruction( reconstruction: pycolmap.Reconstruction, calibration_file: Path, ) -> None: - """Add Aria cameras to COLMAP reconstruction from calibration json file found on website: - https://lamaria.ethz.ch/slam_datasets + """Add Aria cameras to COLMAP reconstruction from calibration + json file found on website: https://lamaria.ethz.ch/slam_datasets Args: - reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction to which cameras will be added - calibration_file (Path): Path to the Aria calibration json file + reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction + to which cameras will be added + + calibration_file (Path): + Path to the Aria calibration json file """ for i, (key, _) in enumerate(ARIA_CAMERAS): @@ -61,7 +64,8 @@ def get_camera_params_for_colmap( Convert Aria CameraCalibration to COLMAP camera parameters. Supported models: OPENCV_FISHEYE, FULL_OPENCV, RAD_TAN_THIN_PRISM_FISHEYE Args: - camera_calibration (CameraCalibration): The projectaria_tools CameraCalibration object + camera_calibration (CameraCalibration): + The projectaria_tools CameraCalibration object camera_model (str): The COLMAP camera model to use Returns: list[float]: The camera parameters in COLMAP format diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 5fc89ad..d6a8604 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -18,8 +18,9 @@ def construct_control_points_from_json( Args: cp_json_file (Path): Path to the sparse GT JSON file """ + with open(cp_json_file) as file: + cp_data = json.load(file) - cp_data = json.load(open(cp_json_file)) control_points = {} for geo_id, data in cp_data["control_points"].items(): tag_ids = data["tag_id"] From ef0b3d7e62319c43e4c37c378718e1b907d79a0c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 14:20:38 +0200 Subject: [PATCH 341/665] incorporating underscore suggestion --- lamaria/pipeline/optim/iterative_global_ba.py | 2 +- lamaria/pipeline/optim/triangulation.py | 2 +- lamaria/utils/control_point.py | 2 +- tools/download_lamaria.py | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index 70ee6a1..bb0dede 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -237,7 +237,7 @@ def refine( mapper_options = pipeline_options.get_mapper() # Iterative refinement - for _i in range(pipeline_options.ba_global_max_refinements): + for _ in range(pipeline_options.ba_global_max_refinements): num_observations = mapper.reconstruction.compute_num_observations() GlobalBundleAdjustment.run( diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index ce7c421..96b0f43 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -53,7 +53,7 @@ def pairs_from_frames(recon: pycolmap.Reconstruction): by_index[k].append(n) adj_pairs = set() - for _idx, seq in by_index.items(): + for _, seq in by_index.items(): for a, b in zip(seq[:-1], seq[1:]): adj_pairs.add((a, b)) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index d6a8604..7ad7067 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -91,7 +91,7 @@ def transform_points(points, r, t, scale): def transform_triangulated_control_points(control_points: dict, r, t, scale): - for _tag_id, cp in control_points.items(): + for _, cp in control_points.items(): triangulated_point = cp["triangulated"] triangulated_point = scale * r.apply(triangulated_point) + t cp["triangulated"] = triangulated_point diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 50451b6..ccd7b04 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -305,7 +305,7 @@ def main(): print("\n[download] Starting downloads.") with requests.Session() as sess: - for _area, _sub, _fname, url, dest in plan: + for _, _, _, url, dest in plan: print(f"[get] {url}") try: download_file(url, dest, sess) From af4436352b5a623bc964380d882b68803fe02153 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 14:35:01 +0200 Subject: [PATCH 342/665] sugg: to lamaria instead of to colmap --- lamaria/config/options.py | 4 ++-- lamaria/config/pipeline.py | 10 ++++----- ...colmap.py => to_lamaria_reconstruction.py} | 10 ++++----- run_pipeline.py | 22 +++++++++---------- 4 files changed, 23 insertions(+), 23 deletions(-) rename lamaria/pipeline/keyframing/{to_colmap.py => to_lamaria_reconstruction.py} (98%) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 81a3f99..8ed468e 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -53,7 +53,7 @@ def load(cls, cfg: OmegaConf | None = None) -> SensorOptions: # Estimate to COLMAP options @dataclass(slots=True) -class EstimateToColmapOptions: +class EstimateToLamariaOptions: mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) @@ -62,7 +62,7 @@ def load( cls, cfg_mps: OmegaConf | None = None, cfg_sensor: OmegaConf | None = None, - ) -> EstimateToColmapOptions: + ) -> EstimateToLamariaOptions: if cfg_mps is None or cfg_sensor is None: return cls() diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index dd4de11..e0162b0 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -4,7 +4,7 @@ from omegaconf import DictConfig, OmegaConf from .options import ( - EstimateToColmapOptions, + EstimateToLamariaOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, @@ -14,8 +14,8 @@ class PipelineOptions: def __init__(self) -> None: self._output_path: Path = Path("output/") - self._estimate_to_colmap_options: EstimateToColmapOptions = ( - EstimateToColmapOptions() + self._estimate_to_colmap_options: EstimateToLamariaOptions = ( + EstimateToLamariaOptions() ) self._keyframing_options: KeyframeSelectorOptions = ( KeyframeSelectorOptions() @@ -40,7 +40,7 @@ def load( def _update_from_cfg(self, cfg: DictConfig) -> None: """Update object attributes from a config.""" - self._estimate_to_colmap_options = EstimateToColmapOptions.load( + self._estimate_to_colmap_options = EstimateToLamariaOptions.load( cfg.mps, cfg.sensor, ) @@ -63,7 +63,7 @@ def output_path(self, path: Path) -> None: # Properties for estimate to COLMAP @property - def estimate_to_colmap_options(self) -> EstimateToColmapOptions: + def estimate_to_colmap_options(self) -> EstimateToLamariaOptions: return self._estimate_to_colmap_options @property diff --git a/lamaria/pipeline/keyframing/to_colmap.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py similarity index 98% rename from lamaria/pipeline/keyframing/to_colmap.py rename to lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index c9b6913..6992fcf 100644 --- a/lamaria/pipeline/keyframing/to_colmap.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -9,7 +9,7 @@ from projectaria_tools.core.stream_id import StreamId from ... import logger -from ...config.options import EstimateToColmapOptions +from ...config.options import EstimateToLamariaOptions from ...utils.camera import ( camera_colmap_from_calib, ) @@ -43,10 +43,10 @@ class PerFrameData: rig_from_world: pycolmap.Rigid3d -class EstimateToColmap: +class EstimateToLamaria: """Converts estimate or MPS data to COLMAP format.""" - def __init__(self, options: EstimateToColmapOptions): + def __init__(self, options: EstimateToLamariaOptions): self.options = options self.data: LamariaReconstruction = LamariaReconstruction() self._vrs_provider = None @@ -58,14 +58,14 @@ def __init__(self, options: EstimateToColmapOptions): @staticmethod def convert( - options: EstimateToColmapOptions, + options: EstimateToLamariaOptions, vrs: Path, images: Path, estimate: Path | None = None, mps_folder: Path | None = None, ) -> LamariaReconstruction: """Entry point to run estimate/MPS to colmap conversion.""" - to_colmap = EstimateToColmap(options) + to_colmap = EstimateToLamaria(options) return to_colmap.process(vrs, images, estimate, mps_folder) def process( diff --git a/run_pipeline.py b/run_pipeline.py index 77fa107..1bbf08c 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -5,22 +5,22 @@ import pycolmap from lamaria.config.options import ( - EstimateToColmapOptions, + EstimateToLamariaOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, ) from lamaria.config.pipeline import PipelineOptions from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector -from lamaria.pipeline.keyframing.to_colmap import EstimateToColmap +from lamaria.pipeline.keyframing.to_lamaria_reconstruction import EstimateToLamaria from lamaria.pipeline.lamaria_reconstruction import LamariaReconstruction from lamaria.pipeline.optim.session import SingleSeqSession from lamaria.pipeline.optim.triangulation import run as triangulate from lamaria.pipeline.optim.vi_optimization import VIOptimizer -def run_estimate_to_colmap( - options: EstimateToColmapOptions, +def run_estimate_to_lamaria( + options: EstimateToLamariaOptions, vrs: Path, images: Path, estimate: Path, @@ -32,7 +32,7 @@ def run_estimate_to_colmap( colmap_model.mkdir(parents=True, exist_ok=True) - lamaria_recon = EstimateToColmap.convert( + lamaria_recon = EstimateToLamaria.convert( options, vrs, images, @@ -43,8 +43,8 @@ def run_estimate_to_colmap( return lamaria_recon -def run_mps_to_colmap( - options: EstimateToColmapOptions, +def run_mps_to_lamaria( + options: EstimateToLamariaOptions, vrs: Path, images: Path, mps_folder: Path, @@ -56,7 +56,7 @@ def run_mps_to_colmap( colmap_model.mkdir(parents=True, exist_ok=True) - lamaria_recon = EstimateToColmap.convert( + lamaria_recon = EstimateToLamaria.convert( options, vrs, images, @@ -185,14 +185,14 @@ def run_pipeline( if not output_path.exists(): output_path.mkdir(parents=True, exist_ok=True) - # Estimate to COLMAP + # Estimate to Lamaria Reconstruction est_options = options.estimate_to_colmap_options if not est_options.mps.use_mps: assert estimate is not None and estimate.exists(), ( "Estimate path must be provided if not using MPS" ) - _ = run_estimate_to_colmap( + _ = run_estimate_to_lamaria( est_options, vrs, options.images, @@ -204,7 +204,7 @@ def run_pipeline( "MPS folder path must be provided if using MPS" ) - _ = run_mps_to_colmap( + _ = run_mps_to_lamaria( est_options, vrs, options.images, From 13d22ed0bf6a0563458683cb489f22422a04c549 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 14:44:05 +0200 Subject: [PATCH 343/665] sugg: to lamaria (comments) --- lamaria/pipeline/lamaria_reconstruction.py | 17 +++++++++++++++++ run_pipeline.py | 8 +++++++- 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/lamaria/pipeline/lamaria_reconstruction.py b/lamaria/pipeline/lamaria_reconstruction.py index 00bc06e..6f5c9e6 100644 --- a/lamaria/pipeline/lamaria_reconstruction.py +++ b/lamaria/pipeline/lamaria_reconstruction.py @@ -5,6 +5,23 @@ class LamariaReconstruction: + """Custom class to hold COLMAP reconstruction data along with + timestamps and IMU measurements. + + Attributes: + reconstruction (pycolmap.Reconstruction): + The COLMAP reconstruction object. This object contains all the + 3D points, cameras (intrinsics, extrinsics), and images. + Additionally holds a dummy camera, with no associated images, + to serve as a placeholder for the IMU. + + timestamps (dict[int, int]): A dictionary mapping reconstruction + frame IDs to their corresponding timestamps in nanoseconds. + + imu_measurements (pycolmap.ImuMeasurements): The factory/online + rectified IMU measurements generated from input VRS file. + """ + def __init__(self) -> None: self.reconstruction = pycolmap.Reconstruction() self.timestamps: dict[int, int] = {} diff --git a/run_pipeline.py b/run_pipeline.py index 1bbf08c..07bdca6 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -12,7 +12,9 @@ ) from lamaria.config.pipeline import PipelineOptions from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector -from lamaria.pipeline.keyframing.to_lamaria_reconstruction import EstimateToLamaria +from lamaria.pipeline.keyframing.to_lamaria_reconstruction import ( + EstimateToLamaria, +) from lamaria.pipeline.lamaria_reconstruction import LamariaReconstruction from lamaria.pipeline.optim.session import SingleSeqSession from lamaria.pipeline.optim.triangulation import run as triangulate @@ -26,6 +28,9 @@ def run_estimate_to_lamaria( estimate: Path, colmap_model: Path, ) -> LamariaReconstruction: + """Function to convert a general input + estimate file to a LamariaReconstruction. + """ if colmap_model.exists(): lamaria_recon = LamariaReconstruction.read(colmap_model) return lamaria_recon @@ -50,6 +55,7 @@ def run_mps_to_lamaria( mps_folder: Path, colmap_model: Path, ) -> LamariaReconstruction: + """Function to convert MPS estimate to a LamariaReconstruction.""" if colmap_model.exists(): lamaria_recon = LamariaReconstruction.read(colmap_model) return lamaria_recon From 4ad2ca5c65ca353658f3ecf0100f6e70f9432dd2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 15:02:30 +0200 Subject: [PATCH 344/665] sugg: output path in defaults --- defaults.yaml | 2 -- 1 file changed, 2 deletions(-) diff --git a/defaults.yaml b/defaults.yaml index e4a87ff..39c9c35 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -1,7 +1,5 @@ # Default configuration for run_pipeline.py -output_path: /output - sensor: camera_model: RAD_TAN_THIN_PRISM_FISHEYE From 6261598a57b541c28346f448f34305fb8321967d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:36:38 +0200 Subject: [PATCH 345/665] paths --- lamaria/config/pipeline.py | 6 +++--- run_pipeline.py | 38 +++++++++++++++++++------------------- 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index e0162b0..b401c26 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -80,7 +80,7 @@ def keyframing_options(self) -> KeyframeSelectorOptions: return self._keyframing_options @property - def keyframes(self) -> Path: + def keyframes_path(self) -> Path: return self._output_path / "keyframes" @property @@ -101,7 +101,7 @@ def pairs_file(self) -> Path: return self._output_path / "hloc" / "pairs.txt" @property - def tri_model(self) -> Path: + def tri_model_path(self) -> Path: return self._output_path / "triangulated_recon" # Properties for visual-inertial optimization @@ -110,5 +110,5 @@ def vi_optimizer_options(self) -> VIOptimizerOptions: return self._vi_optimizer_options @property - def optim_model(self) -> Path: + def optim_model_path(self) -> Path: return self._output_path / "optim_recon" diff --git a/run_pipeline.py b/run_pipeline.py index 07bdca6..e8ca612 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -77,7 +77,7 @@ def run_keyframe_selection( options: KeyframeSelectorOptions, input: Path | LamariaReconstruction, images: Path, - keyframes: Path, + keyframes_path: Path, kf_model: Path, ) -> LamariaReconstruction: if isinstance(input, Path): @@ -95,7 +95,7 @@ def run_keyframe_selection( options, input_recon, images, - keyframes, + keyframes_path, ) kf_lamaria_recon.write(kf_model) @@ -106,27 +106,27 @@ def run_keyframe_selection( def run_triangulation( options: TriangulatorOptions, input: Path, # path to LamariaReconstruction - keyframes: Path, + keyframes_path: Path, hloc: Path, pairs_file: Path, - tri_model: Path, + tri_model_path: Path, ) -> LamariaReconstruction: if not isinstance(input, Path): raise ValueError("Input must be a Path to the reconstruction") assert input.exists(), f"input reconstruction path {input} does not exist" - if tri_model.exists(): - tri_lamaria_recon = LamariaReconstruction.read(tri_model) + if tri_model_path.exists(): + tri_lamaria_recon = LamariaReconstruction.read(tri_model_path) return tri_lamaria_recon triangulated_model_path = triangulate( options, input, - keyframes, + keyframes_path, hloc, pairs_file, - tri_model, + tri_model_path, ) input_lamaria_recon = LamariaReconstruction.read(input) @@ -145,7 +145,7 @@ def run_optimization( vi_options: VIOptimizerOptions, triangulator_options: TriangulatorOptions, input: Path, # path to LamariaReconstruction - optim_model: Path, + optim_model_path: Path, ) -> LamariaReconstruction: if not isinstance(input, Path): raise ValueError("Input must be a Path to the reconstruction") @@ -155,11 +155,11 @@ def run_optimization( f"Database path {db_path} does not exist in input reconstruction" ) - if optim_model.exists(): - shutil.rmtree(optim_model) + if optim_model_path.exists(): + shutil.rmtree(optim_model_path) - optim_model.mkdir(parents=True, exist_ok=True) - db_dst = optim_model / "database.db" + optim_model_path.mkdir(parents=True, exist_ok=True) + db_dst = optim_model_path / "database.db" shutil.copy(db_path, db_dst) init_lamaria_recon = LamariaReconstruction.read(input) @@ -176,7 +176,7 @@ def run_optimization( optim_lamaria_recon.reconstruction = optimized_recon optim_lamaria_recon.timestamps = init_lamaria_recon.timestamps optim_lamaria_recon.imu_measurements = init_lamaria_recon.imu_measurements - optim_lamaria_recon.write(optim_model) + optim_lamaria_recon.write(optim_model_path) def run_pipeline( @@ -224,7 +224,7 @@ def run_pipeline( kf_options, options.colmap_model, options.images, - options.keyframes, + options.keyframes_path, options.kf_model, ) @@ -233,10 +233,10 @@ def run_pipeline( _ = run_triangulation( tri_options, options.kf_model, - options.keyframes, + options.keyframes_path, options.hloc, options.pairs_file, - options.tri_model, + options.tri_model_path, ) # Visual-Inertial Optimization @@ -244,8 +244,8 @@ def run_pipeline( _ = run_optimization( vi_options, tri_options, - options.tri_model, - options.optim_model, + options.tri_model_path, + options.optim_model_path, ) From c4d2ef25be42a6907db593cf50bd68fff5a53499 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:37:21 +0200 Subject: [PATCH 346/665] paths --- lamaria/pipeline/keyframing/keyframe_selection.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 3de887e..d05e18e 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -32,8 +32,8 @@ def __init__( def run( options: KeyframeSelectorOptions, data: LamariaReconstruction, - original_image_dir: Path, - keyframes_dir: Path, + images_path: Path, + keyframes_path: Path, ) -> LamariaReconstruction: """Entry point to run keyframing and copy keyframes into keyframe directory. @@ -41,7 +41,7 @@ def run( selector = KeyframeSelector(options, data) kf_recon = selector.run_keyframing() - selector.copy_images_to_keyframes_dir(original_image_dir, keyframes_dir) + selector.copy_images_to_keyframes_dir(images_path, keyframes_path) return kf_recon From cba0a9a1faa450e370960375117806c87aaae6e9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:38:58 +0200 Subject: [PATCH 347/665] _add_images --- lamaria/eval/create_empty_recon_from_estimate.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index d47bc97..a729b8a 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -22,7 +22,7 @@ ) -def add_images_to_reconstruction( +def _add_images_to_reconstruction( reconstruction: pycolmap.Reconstruction, estimate_file: Path, cp_json_file: Path, @@ -165,7 +165,7 @@ def create_baseline_reconstruction( device_calibration_json, ) - add_images_to_reconstruction( + _add_images_to_reconstruction( reconstruction, estimate_file, cp_json_file, From 7f5cdbed0817026ae01d3cd9064a02329103d8db Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:39:29 +0200 Subject: [PATCH 348/665] paths --- lamaria/pipeline/optim/triangulation.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index 96b0f43..6470acd 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -88,13 +88,13 @@ def postprocess_pairs_with_reconstruction( def run( options: TriangulatorOptions, reference_model: Path, # reconstruction path - keyframes: Path, + keyframes_path: Path, hloc_dir: Path, pairs_path: Path, triangulated_model_path: Path, ) -> Path: - if not keyframes.exists(): - raise FileNotFoundError(f"keyframes_dir not found at {keyframes}") + if not keyframes_path.exists(): + raise FileNotFoundError(f"keyframes not found at {keyframes_path}") hloc_dir.mkdir(parents=True, exist_ok=True) @@ -115,10 +115,10 @@ def run( ) retrieval_path = extract_features.main( - retrieval_conf, image_dir=keyframes, export_dir=hloc_dir + retrieval_conf, image_dir=keyframes_path, export_dir=hloc_dir ) features_path = extract_features.main( - feature_conf, image_dir=keyframes, export_dir=hloc_dir + feature_conf, image_dir=keyframes_path, export_dir=hloc_dir ) pairs_from_retrieval.main( @@ -138,7 +138,7 @@ def run( _ = triangulation.main( sfm_dir=triangulated_model_path, reference_model=reference_model, - image_dir=keyframes, + image_dir=keyframes_path, pairs=pairs_path, features=features_path, matches=matches_path, From ed2bcf095c80919294d539e703875f1baad4780f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:41:57 +0200 Subject: [PATCH 349/665] import --- tools/undistort_asl_folder.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index e6a60e6..5f4f77a 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -9,7 +9,7 @@ import pycolmap from tqdm import tqdm -from lamaria.utils.general import ( +from lamaria.utils.camera import ( ARIA_CAMERAS, add_cameras_to_reconstruction, ) From 75714e91754aca38640512eb00f3121cf279477b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:47:50 +0200 Subject: [PATCH 350/665] run pipeline --- run_pipeline.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index e8ca612..95ada03 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -107,7 +107,7 @@ def run_triangulation( options: TriangulatorOptions, input: Path, # path to LamariaReconstruction keyframes_path: Path, - hloc: Path, + hloc_path: Path, pairs_file: Path, tri_model_path: Path, ) -> LamariaReconstruction: @@ -124,7 +124,7 @@ def run_triangulation( options, input, keyframes_path, - hloc, + hloc_path, pairs_file, tri_model_path, ) @@ -234,7 +234,7 @@ def run_pipeline( tri_options, options.kf_model, options.keyframes_path, - options.hloc, + options.hloc_path, options.pairs_file, options.tri_model_path, ) From 3858eb059fcbefb2458541e3b9d0984fc453b469 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:47:57 +0200 Subject: [PATCH 351/665] hloc path --- lamaria/config/pipeline.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index b401c26..b8f46f0 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -93,7 +93,7 @@ def triangulator_options(self) -> TriangulatorOptions: return self._triangulator_options @property - def hloc(self) -> Path: + def hloc_path(self) -> Path: return self._output_path / "hloc" @property From 29d5d3b342519bab5adbe1db6de8ea2c64c3360a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:54:01 +0200 Subject: [PATCH 352/665] paths --- lamaria/pipeline/optim/triangulation.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index 6470acd..4d14986 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -89,14 +89,14 @@ def run( options: TriangulatorOptions, reference_model: Path, # reconstruction path keyframes_path: Path, - hloc_dir: Path, + hloc_path: Path, pairs_path: Path, triangulated_model_path: Path, ) -> Path: if not keyframes_path.exists(): raise FileNotFoundError(f"keyframes not found at {keyframes_path}") - hloc_dir.mkdir(parents=True, exist_ok=True) + hloc_path.mkdir(parents=True, exist_ok=True) if not reference_model.exists(): raise FileNotFoundError( @@ -115,10 +115,10 @@ def run( ) retrieval_path = extract_features.main( - retrieval_conf, image_dir=keyframes_path, export_dir=hloc_dir + retrieval_conf, image_dir=keyframes_path, export_dir=hloc_path ) features_path = extract_features.main( - feature_conf, image_dir=keyframes_path, export_dir=hloc_dir + feature_conf, image_dir=keyframes_path, export_dir=hloc_path ) pairs_from_retrieval.main( @@ -130,7 +130,7 @@ def run( conf=matcher_conf, pairs=pairs_path, features=feature_conf["output"], - export_dir=hloc_dir, + export_dir=hloc_path, ) colmap_opts = set_colmap_triangulation_options(options) From d7a9496f505596d22dbf2ed31e383ab14e6bee36 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:55:23 +0200 Subject: [PATCH 353/665] colmap model path --- run_pipeline.py | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index 95ada03..b2cd822 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -26,16 +26,16 @@ def run_estimate_to_lamaria( vrs: Path, images: Path, estimate: Path, - colmap_model: Path, + colmap_model_path: Path, ) -> LamariaReconstruction: """Function to convert a general input estimate file to a LamariaReconstruction. """ - if colmap_model.exists(): - lamaria_recon = LamariaReconstruction.read(colmap_model) + if colmap_model_path.exists(): + lamaria_recon = LamariaReconstruction.read(colmap_model_path) return lamaria_recon - colmap_model.mkdir(parents=True, exist_ok=True) + colmap_model_path.mkdir(parents=True, exist_ok=True) lamaria_recon = EstimateToLamaria.convert( options, @@ -43,7 +43,7 @@ def run_estimate_to_lamaria( images, estimate, ) - lamaria_recon.write(colmap_model) + lamaria_recon.write(colmap_model_path) return lamaria_recon @@ -53,14 +53,14 @@ def run_mps_to_lamaria( vrs: Path, images: Path, mps_folder: Path, - colmap_model: Path, + colmap_model_path: Path, ) -> LamariaReconstruction: """Function to convert MPS estimate to a LamariaReconstruction.""" - if colmap_model.exists(): - lamaria_recon = LamariaReconstruction.read(colmap_model) + if colmap_model_path.exists(): + lamaria_recon = LamariaReconstruction.read(colmap_model_path) return lamaria_recon - colmap_model.mkdir(parents=True, exist_ok=True) + colmap_model_path.mkdir(parents=True, exist_ok=True) lamaria_recon = EstimateToLamaria.convert( options, @@ -68,7 +68,7 @@ def run_mps_to_lamaria( images, mps_folder, ) - lamaria_recon.write(colmap_model) + lamaria_recon.write(colmap_model_path) return lamaria_recon @@ -203,7 +203,7 @@ def run_pipeline( vrs, options.images, estimate, - options.colmap_model, + options.colmap_model_path, ) else: assert mps_folder is not None and mps_folder.exists(), ( @@ -215,14 +215,14 @@ def run_pipeline( vrs, options.images, mps_folder, - options.colmap_model, + options.colmap_model_path, ) # Keyframe Selection kf_options = options.keyframing_options _ = run_keyframe_selection( kf_options, - options.colmap_model, + options.colmap_model_path, options.images, options.keyframes_path, options.kf_model, From 0be89e2d17f4d3e521fa201b372d9c9b8591d686 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 18:55:30 +0200 Subject: [PATCH 354/665] colmap model path --- lamaria/config/pipeline.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index b8f46f0..da2d65a 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -71,7 +71,7 @@ def images(self) -> Path: return self._output_path / "images" @property - def colmap_model(self) -> Path: + def colmap_model_path(self) -> Path: return self._output_path / "initial_recon" # Properties for keyframing From 34c1a1a80a9074f06026717eb31ce6c1a7c5edd8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 19:01:33 +0200 Subject: [PATCH 355/665] paths --- lamaria/config/pipeline.py | 4 +-- .../pipeline/keyframing/keyframe_selection.py | 4 +-- .../keyframing/to_lamaria_reconstruction.py | 14 ++++---- run_pipeline.py | 32 +++++++++---------- 4 files changed, 27 insertions(+), 27 deletions(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index da2d65a..263e3ef 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -67,7 +67,7 @@ def estimate_to_colmap_options(self) -> EstimateToLamariaOptions: return self._estimate_to_colmap_options @property - def images(self) -> Path: + def images_path(self) -> Path: return self._output_path / "images" @property @@ -84,7 +84,7 @@ def keyframes_path(self) -> Path: return self._output_path / "keyframes" @property - def kf_model(self) -> Path: + def kf_model_path(self) -> Path: return self._output_path / "keyframed_recon" # Properties for triangulation diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index d05e18e..219de82 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -235,7 +235,7 @@ def run_keyframing(self) -> LamariaReconstruction: def copy_images_to_keyframes_dir( self, - images: Path, + images_path: Path, output: Path, ) -> Path: """Copy images corresponding to @@ -261,7 +261,7 @@ def copy_images_to_keyframes_dir( image = self.init_recons.images[data_id.id] subdir = "left" if image.name.startswith("1201-1") else "right" - src_path = images / subdir / image.name + src_path = images_path / subdir / image.name dst_path = output / image.name shutil.copy2(src_path, dst_path) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 6992fcf..8e156c4 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -60,22 +60,22 @@ def __init__(self, options: EstimateToLamariaOptions): def convert( options: EstimateToLamariaOptions, vrs: Path, - images: Path, + images_path: Path, estimate: Path | None = None, mps_folder: Path | None = None, ) -> LamariaReconstruction: """Entry point to run estimate/MPS to colmap conversion.""" to_colmap = EstimateToLamaria(options) - return to_colmap.process(vrs, images, estimate, mps_folder) + return to_colmap.process(vrs, images_path, estimate, mps_folder) def process( self, vrs: Path, - images: Path, + images_path: Path, estimate: Path | None = None, mps_folder: Path | None = None, ) -> LamariaReconstruction: - self._init_data(vrs, images, estimate, mps_folder) + self._init_data(vrs, images_path, estimate, mps_folder) if self.options.mps.use_online_calibration and self.options.mps.use_mps: self._add_online_sensors() @@ -254,9 +254,9 @@ def _ts_from_vrs(self, sid: StreamId) -> list[int]: self._vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME) ) - def _get_images(self, images: Path) -> list[tuple[Path, Path]]: - left_img_dir = images / "left" - right_img_dir = images / "right" + def _get_images(self, images_path: Path) -> list[tuple[Path, Path]]: + left_img_dir = images_path / "left" + right_img_dir = images_path / "right" left_images = self._images_from_vrs(left_img_dir, left_img_dir) right_images = self._images_from_vrs(right_img_dir, right_img_dir) diff --git a/run_pipeline.py b/run_pipeline.py index b2cd822..6ab7ba3 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -24,7 +24,7 @@ def run_estimate_to_lamaria( options: EstimateToLamariaOptions, vrs: Path, - images: Path, + images_path: Path, estimate: Path, colmap_model_path: Path, ) -> LamariaReconstruction: @@ -40,7 +40,7 @@ def run_estimate_to_lamaria( lamaria_recon = EstimateToLamaria.convert( options, vrs, - images, + images_path, estimate, ) lamaria_recon.write(colmap_model_path) @@ -51,7 +51,7 @@ def run_estimate_to_lamaria( def run_mps_to_lamaria( options: EstimateToLamariaOptions, vrs: Path, - images: Path, + images_path: Path, mps_folder: Path, colmap_model_path: Path, ) -> LamariaReconstruction: @@ -65,7 +65,7 @@ def run_mps_to_lamaria( lamaria_recon = EstimateToLamaria.convert( options, vrs, - images, + images_path, mps_folder, ) lamaria_recon.write(colmap_model_path) @@ -76,29 +76,29 @@ def run_mps_to_lamaria( def run_keyframe_selection( options: KeyframeSelectorOptions, input: Path | LamariaReconstruction, - images: Path, + images_path: Path, keyframes_path: Path, - kf_model: Path, + kf_model_path: Path, ) -> LamariaReconstruction: if isinstance(input, Path): input_recon = LamariaReconstruction.read(input) else: input_recon = input - if kf_model.exists(): - kf_lamaria_recon = LamariaReconstruction.read(kf_model) + if kf_model_path.exists(): + kf_lamaria_recon = LamariaReconstruction.read(kf_model_path) return kf_lamaria_recon - kf_model.mkdir(parents=True, exist_ok=True) + kf_model_path.mkdir(parents=True, exist_ok=True) kf_lamaria_recon = KeyframeSelector.run( options, input_recon, - images, + images_path, keyframes_path, ) - kf_lamaria_recon.write(kf_model) + kf_lamaria_recon.write(kf_model_path) return kf_lamaria_recon @@ -201,7 +201,7 @@ def run_pipeline( _ = run_estimate_to_lamaria( est_options, vrs, - options.images, + options.images_path, estimate, options.colmap_model_path, ) @@ -213,7 +213,7 @@ def run_pipeline( _ = run_mps_to_lamaria( est_options, vrs, - options.images, + options.images_path, mps_folder, options.colmap_model_path, ) @@ -223,16 +223,16 @@ def run_pipeline( _ = run_keyframe_selection( kf_options, options.colmap_model_path, - options.images, + options.images_path, options.keyframes_path, - options.kf_model, + options.kf_model_path, ) # Triangulation tri_options = options.triangulator_options _ = run_triangulation( tri_options, - options.kf_model, + options.kf_model_path, options.keyframes_path, options.hloc_path, options.pairs_file, From 7e66823ad605dd2d3f0f08bde93a67ab4e2df303 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 19:07:38 +0200 Subject: [PATCH 356/665] readme (for sugg incorp) --- README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 3f1b51f..d92ea80 100644 --- a/README.md +++ b/README.md @@ -1 +1,3 @@ -# lamaria \ No newline at end of file +# Benchmarking Egocentric Visual-Inertial SLAM at City Scale + +### Downloading the dataset \ No newline at end of file From 20e8ba34ced50db682936ff42ec48e9743360fc8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 19:08:41 +0200 Subject: [PATCH 357/665] tools discussion readme --- README.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index d92ea80..72c178e 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,6 @@ # Benchmarking Egocentric Visual-Inertial SLAM at City Scale -### Downloading the dataset \ No newline at end of file +### Downloading the dataset + + +### Additional tools \ No newline at end of file From 200de12f5004d0c65b45234862117ffd4e55e8aa Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 19:21:02 +0200 Subject: [PATCH 358/665] logging statements --- lamaria/eval/sparse_evaluation.py | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index fe1bb02..230b344 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -144,14 +144,18 @@ def run_baseline_evaluation( ) if triangulated_cp_alignment is None or topo_cp_alignment is None: - return (False, "Not enough control points for INITIAL alignment") + logger.error( + "Not enough control points for initial alignment" + ) + return False ret = pycolmap.estimate_sim3d_robust( triangulated_cp_alignment, topo_cp_alignment, {"max_error": 5} ) if ret is None: - return (False, "Failed to estimate robust sim3d") + logger.error("Failed to estimate robust sim3d") + return False robust_sim3d = ret["tgt_from_src"] @@ -219,7 +223,8 @@ def run_baseline_evaluation( np.save(os.path.join(output_path, "sparse_evaluation.npy"), output_data) - return (True, "Sparse evaluation completed successfully") + logger.info("Sparse evaluation completed successfully") + return True if __name__ == "__main__": From a54524c2874288c8d793cb39bda547c931cab9b7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 19:22:25 +0200 Subject: [PATCH 359/665] rm logging outside fn --- lamaria/eval/sparse_evaluation.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 230b344..6877f19 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -257,11 +257,9 @@ def run_baseline_evaluation( ) args = parser.parse_args() - state, msg = run_baseline_evaluation( + _ = run_baseline_evaluation( Path(args.reconstruction_path), Path(args.cp_json_file), Path(args.output_path), args.cp_reproj_std, ) - - logger.info(f"Evaluation completed? {state}. Message: {msg}") From 4fddfb3f70979abf6335070b5cacc44d4ef0f522 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 19:55:37 +0200 Subject: [PATCH 360/665] None imu measurements instead of empty pycolmap.Imu --- lamaria/pipeline/lamaria_reconstruction.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/pipeline/lamaria_reconstruction.py b/lamaria/pipeline/lamaria_reconstruction.py index 6f5c9e6..c8cf7a9 100644 --- a/lamaria/pipeline/lamaria_reconstruction.py +++ b/lamaria/pipeline/lamaria_reconstruction.py @@ -25,7 +25,7 @@ class LamariaReconstruction: def __init__(self) -> None: self.reconstruction = pycolmap.Reconstruction() self.timestamps: dict[int, int] = {} - self.imu_measurements = pycolmap.ImuMeasurements([]) + self.imu_measurements = None @staticmethod def read( From c39a1f80f94b0b3f6ac0ae2302751054b14f0f01 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 19:55:54 +0200 Subject: [PATCH 361/665] kf linter issue? --- lamaria/pipeline/keyframing/keyframe_selection.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 219de82..f7de37f 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -21,11 +21,11 @@ def __init__( data: LamariaReconstruction, ): self.options = options - self.init_data: LamariaReconstruction = data + self.init_data = data self.init_recons = data.reconstruction # pycolmap.Reconstruction self.timestamps = data.timestamps # frame id to timestamp mapping - self.keyframed_data: LamariaReconstruction = LamariaReconstruction() + self.keyframed_data = LamariaReconstruction() self.keyframe_frame_ids: dict[int, int] = {} @staticmethod From 56f52448a53c8f61eff278385623bfb8ec41ae5f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 19:59:44 +0200 Subject: [PATCH 362/665] preintegrate --- lamaria/pipeline/optim/imu.py | 2 +- lamaria/pipeline/optim/session.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index f90929a..2e33b4b 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -6,7 +6,7 @@ from ..lamaria_reconstruction import LamariaReconstruction -def load_preintegrated_imu_measurements( +def preintegrate_imu_measurements( options: OptIMUOptions, data: LamariaReconstruction, ) -> dict[int, pycolmap.PreintegratedImuMeasurement]: diff --git a/lamaria/pipeline/optim/session.py b/lamaria/pipeline/optim/session.py index 2a3be7f..f46c197 100644 --- a/lamaria/pipeline/optim/session.py +++ b/lamaria/pipeline/optim/session.py @@ -7,7 +7,7 @@ from ..lamaria_reconstruction import LamariaReconstruction from .imu import ( load_imu_states, - load_preintegrated_imu_measurements, + preintegrate_imu_measurements, ) @@ -22,7 +22,7 @@ def __init__( def _init_imu_data(self, imu_options): self.preintegrated_imu_measurements = ( - load_preintegrated_imu_measurements(imu_options, self.data) + preintegrate_imu_measurements(imu_options, self.data) ) self.imu_states = load_imu_states(self.data) self.imu_from_rig = pycolmap.Rigid3d() From f14754009d014499808bc00bfd98d406eba07fed Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:02:33 +0200 Subject: [PATCH 363/665] mv functions --- lamaria/pipeline/optim/imu.py | 80 +++++++++++++++++++++++++++++++++++ 1 file changed, 80 insertions(+) diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 2e33b4b..5066ac6 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -1,9 +1,11 @@ import numpy as np import pycolmap +import pyceres from tqdm import tqdm from ...config.options import OptIMUOptions from ..lamaria_reconstruction import LamariaReconstruction +from .session import SingleSeqSession def preintegrate_imu_measurements( @@ -107,3 +109,81 @@ def load_imu_calibration( imu_calib.imu_rate = 1000.0 return imu_calib + + +def add_imu_residuals_to_problem( + imu_options: OptIMUOptions, + session: SingleSeqSession, + problem, +): + loss = pyceres.TrivialLoss() + + frame_ids = sorted(session.data.reconstruction.frames.keys()) + + for k in tqdm( + range(len(session.preintegrated_imu_measurements)), + desc="Adding IMU residuals", + ): + i = frame_ids[k] + j = frame_ids[k + 1] + frame_i = session.data.reconstruction.frames[i] + frame_j = session.data.reconstruction.frames[j] + i_from_world = frame_i.rig_from_world + j_from_world = frame_j.rig_from_world + + integrated_m = session.preintegrated_imu_measurements[i] + + problem.add_residual_block( + pycolmap.PreintegratedImuMeasurementCost(integrated_m), + loss, + [ + session.imu_from_rig.rotation.quat, + session.imu_from_rig.translation, + session.log_scale, + session.gravity, + i_from_world.rotation.quat, + i_from_world.translation, + session.imu_states[i].data, + j_from_world.rotation.quat, + j_from_world.translation, + session.imu_states[j].data, + ], + ) + + problem = setup_manifolds_and_constraints( + imu_options, + session, + problem, + ) + + return problem + + +def setup_manifolds_and_constraints( + imu_options: OptIMUOptions, + session: SingleSeqSession, + problem, +): + """Setup manifolds and parameter constraints""" + problem.set_manifold(session.gravity, pyceres.SphereManifold(3)) + problem.set_manifold( + session.imu_from_rig.rotation.quat, pyceres.EigenQuaternionManifold() + ) + + # Apply optimization constraints based on configuration + if not imu_options.optimize_scale: + problem.set_parameter_block_constant(session.log_scale) + if not imu_options.optimize_gravity: + problem.set_parameter_block_constant(session.gravity) + if not imu_options.optimize_imu_from_rig: + problem.set_parameter_block_constant(session.imu_from_rig.rotation.quat) + problem.set_parameter_block_constant(session.imu_from_rig.translation) + if not imu_options.optimize_bias: + constant_idxs = np.arange(3, 9) + for frame_id in session.imu_states: + problem.set_manifold( + session.imu_states[frame_id].data, + pyceres.SubsetManifold(9, constant_idxs), + ) + + return problem \ No newline at end of file From 69343928f2a9851caf012beb989dad534df41c44 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:02:54 +0200 Subject: [PATCH 364/665] residual --- lamaria/pipeline/optim/residual.py | 85 ------------------------------ 1 file changed, 85 deletions(-) delete mode 100644 lamaria/pipeline/optim/residual.py diff --git a/lamaria/pipeline/optim/residual.py b/lamaria/pipeline/optim/residual.py deleted file mode 100644 index 7b11c5e..0000000 --- a/lamaria/pipeline/optim/residual.py +++ /dev/null @@ -1,85 +0,0 @@ -import numpy as np -import pyceres -import pycolmap -from tqdm import tqdm - -from ...config.options import OptIMUOptions -from .session import SingleSeqSession - - -def add_imu_residuals_to_problem( - imu_options: OptIMUOptions, - session: SingleSeqSession, - problem, -): - loss = pyceres.TrivialLoss() - - frame_ids = sorted(session.data.reconstruction.frames.keys()) - - for k in tqdm( - range(len(session.preintegrated_imu_measurements)), - desc="Adding IMU residuals", - ): - i = frame_ids[k] - j = frame_ids[k + 1] - frame_i = session.data.reconstruction.frames[i] - frame_j = session.data.reconstruction.frames[j] - i_from_world = frame_i.rig_from_world - j_from_world = frame_j.rig_from_world - - integrated_m = session.preintegrated_imu_measurements[i] - - problem.add_residual_block( - pycolmap.PreintegratedImuMeasurementCost(integrated_m), - loss, - [ - session.imu_from_rig.rotation.quat, - session.imu_from_rig.translation, - session.log_scale, - session.gravity, - i_from_world.rotation.quat, - i_from_world.translation, - session.imu_states[i].data, - j_from_world.rotation.quat, - j_from_world.translation, - session.imu_states[j].data, - ], - ) - - problem = setup_manifolds_and_constraints( - imu_options, - session, - problem, - ) - - return problem - - -def setup_manifolds_and_constraints( - imu_options: OptIMUOptions, - session: SingleSeqSession, - problem, -): - """Setup manifolds and parameter constraints""" - problem.set_manifold(session.gravity, pyceres.SphereManifold(3)) - problem.set_manifold( - session.imu_from_rig.rotation.quat, pyceres.EigenQuaternionManifold() - ) - - # Apply optimization constraints based on configuration - if not imu_options.optimize_scale: - problem.set_parameter_block_constant(session.log_scale) - if not imu_options.optimize_gravity: - problem.set_parameter_block_constant(session.gravity) - if not imu_options.optimize_imu_from_rig: - problem.set_parameter_block_constant(session.imu_from_rig.rotation.quat) - problem.set_parameter_block_constant(session.imu_from_rig.translation) - if not imu_options.optimize_bias: - constant_idxs = np.arange(3, 9) - for frame_id in session.imu_states: - problem.set_manifold( - session.imu_states[frame_id].data, - pyceres.SubsetManifold(9, constant_idxs), - ) - - return problem From b365240d645de92683b2b3d0d5fe7dfe4a8ce681 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:03:32 +0200 Subject: [PATCH 365/665] imu mv --- lamaria/pipeline/optim/iterative_global_ba.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index bb0dede..e09201b 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -6,7 +6,7 @@ from ... import logger from ...config.options import VIOptimizerOptions from .callback import RefinementCallback -from .residual import add_imu_residuals_to_problem +from .imu import add_imu_residuals_to_problem from .session import SingleSeqSession From 74c075628360dfcd10cfdd3abc9e9c4fe9df5468 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:21:22 +0200 Subject: [PATCH 366/665] constants.py --- lamaria/utils/constants.py | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) create mode 100644 lamaria/utils/constants.py diff --git a/lamaria/utils/constants.py b/lamaria/utils/constants.py new file mode 100644 index 0000000..c62173a --- /dev/null +++ b/lamaria/utils/constants.py @@ -0,0 +1,16 @@ + +from projectaria_tools.core.stream_id import StreamId + +# ASL folder name, stream label for Aria cameras +ARIA_CAMERAS: list = [("cam0", "camera-slam-left"), + ("cam1", "camera-slam-right")] + +# Aria camera constants +LEFT_CAMERA_STREAM_ID = StreamId("1201-1") +RIGHT_CAMERA_STREAM_ID = StreamId("1201-2") +LEFT_CAMERA_STREAM_LABEL = "camera-slam-left" +RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" + +# Right Aria IMU constants +RIGHT_IMU_STREAM_ID = StreamId("1202-1") +RIGHT_IMU_STREAM_LABEL = "imu-right" \ No newline at end of file From a8a438baa958cbf119c2cf58df8d9163ef2f9703 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:21:49 +0200 Subject: [PATCH 367/665] mv constants --- lamaria/utils/camera.py | 7 ------- lamaria/utils/imu.py | 4 ---- 2 files changed, 11 deletions(-) diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py index 90600f3..86a7ee0 100644 --- a/lamaria/utils/camera.py +++ b/lamaria/utils/camera.py @@ -4,16 +4,9 @@ import numpy as np import pycolmap from projectaria_tools.core.calibration import CameraCalibration -from projectaria_tools.core.stream_id import StreamId from .transformation import get_t_cam_a_cam_b_from_json -ARIA_CAMERAS = [("cam0", "camera-slam-left"), ("cam1", "camera-slam-right")] -LEFT_CAMERA_STREAM_ID = StreamId("1201-1") -RIGHT_CAMERA_STREAM_ID = StreamId("1201-2") -LEFT_CAMERA_STREAM_LABEL = "camera-slam-left" -RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" - def add_cameras_to_reconstruction( reconstruction: pycolmap.Reconstruction, diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index 9ac9d03..efcb7fd 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -3,16 +3,12 @@ import pycolmap from projectaria_tools.core import data_provider, mps from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions -from projectaria_tools.core.stream_id import StreamId from tqdm import tqdm from lamaria.utils.general import ( find_closest_timestamp, ) -RIGHT_IMU_STREAM_ID = StreamId("1202-1") -RIGHT_IMU_STREAM_LABEL = "imu-right" - def get_online_params_for_imu_from_mps( online_calibs_file: Path, stream_label: str, num_error: float = 1e6 From 3689ae531e83179a6bc7e54bc34f06afef32cfcb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:21:56 +0200 Subject: [PATCH 368/665] rm constant --- tools/asl_folder_to_rosbag.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/tools/asl_folder_to_rosbag.py b/tools/asl_folder_to_rosbag.py index e5fb5d7..14428fa 100644 --- a/tools/asl_folder_to_rosbag.py +++ b/tools/asl_folder_to_rosbag.py @@ -12,8 +12,6 @@ from sensor_msgs.msg import Imu from tqdm import tqdm -NS_TO_S = 1e-9 - @dataclass(frozen=True) class CamSample: From e407b882eadedf3ff7ef91b103c6fad6b5d91662 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:22:21 +0200 Subject: [PATCH 369/665] rm unnecessary constant --- tools/asl_folder_to_rosbag.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/asl_folder_to_rosbag.py b/tools/asl_folder_to_rosbag.py index 14428fa..4c59033 100644 --- a/tools/asl_folder_to_rosbag.py +++ b/tools/asl_folder_to_rosbag.py @@ -128,7 +128,7 @@ def asl_to_rosbag( for ts_ns, kind, sample in tqdm( bag_timeline, desc="Writing bag", unit="msg" ): - stamp = rospy.Time.from_sec(ts_ns * NS_TO_S) + stamp = rospy.Time.from_sec(ts_ns * 1e-9) if kind == "cam": cv_image = cv2.imread(str(sample.path), cv2.IMREAD_GRAYSCALE) From 312757567980942d4adf6dbb465af8c9dde661d0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:23:41 +0200 Subject: [PATCH 370/665] constants in undistort asl --- tools/undistort_asl_folder.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index 5f4f77a..14eaf9f 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -10,9 +10,9 @@ from tqdm import tqdm from lamaria.utils.camera import ( - ARIA_CAMERAS, add_cameras_to_reconstruction, ) +import lamaria.utils.constants as constant def undistort_reconstruction( @@ -88,7 +88,7 @@ def undistort_asl( image_id = 1 rig = recon.rig(rig_id=1) colmap_images = {} - for i, (key, _) in enumerate(ARIA_CAMERAS): + for i, (key, _) in enumerate(constant.ARIA_CAMERAS): cam = recon.cameras[i + 1] image_names = sorted( p.relative_to(asl_path) @@ -105,7 +105,7 @@ def undistort_asl( image_id += 1 colmap_images[key].append(im) - zipped_images = list(zip(*[colmap_images[key] for key, _ in ARIA_CAMERAS])) + zipped_images = list(zip(*[colmap_images[key] for key, _ in constant.ARIA_CAMERAS])) for j, (left_im, right_im) in enumerate( tqdm( @@ -134,7 +134,7 @@ def undistort_asl( # Copy the undistorted cameras in json. cameras_undist = { - key: cameras_undist[i + 1] for i, (key, _) in enumerate(ARIA_CAMERAS) + key: cameras_undist[i + 1] for i, (key, _) in enumerate(constant.ARIA_CAMERAS) } write_cameras_json( cameras_undist, output_asl_path / "aria" / "cameras.json" From 2974b6d7d2978411b09eafd1d757b378cab7cad7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:25:24 +0200 Subject: [PATCH 371/665] vrs to asl --- tools/vrs_to_asl_folder.py | 19 +++++++------------ 1 file changed, 7 insertions(+), 12 deletions(-) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index fbe2d81..c419613 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -8,17 +8,11 @@ from tqdm import tqdm from lamaria import logger -from lamaria.utils.camera import ( - LEFT_CAMERA_STREAM_ID, - RIGHT_CAMERA_STREAM_ID, -) from lamaria.utils.general import ( extract_images_from_vrs, get_matched_timestamps, ) -from lamaria.utils.imu import ( - RIGHT_IMU_STREAM_ID, -) +import lamaria.utils.constants as constant def remove_images_when_slam_drops( @@ -137,14 +131,15 @@ def write_image_csv(image_timestamps, cam_folder): def write_imu_data_to_csv(vrs_provider, csv_file): imu_timestamps = vrs_provider.get_timestamps_ns( - RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME + constant.RIGHT_IMU_STREAM_ID, + TimeDomain.DEVICE_TIME ) last_timestamp = None if os.path.exists(csv_file): with open(csv_file) as f: last_row = None - for _last_row in csv.reader(f): + for _ in csv.reader(f): pass if last_row is not None: last_timestamp = int(last_row[0]) @@ -160,7 +155,7 @@ def write_imu_data_to_csv(vrs_provider, csv_file): writer = csv.writer(f) for timestamp in tqdm(imu_timestamps, desc="Appending IMU data to CSV"): imu_data = vrs_provider.get_imu_data_by_time_ns( - RIGHT_IMU_STREAM_ID, + constant.RIGHT_IMU_STREAM_ID, timestamp, TimeDomain.DEVICE_TIME, TimeQueryOptions.CLOSEST, @@ -195,7 +190,7 @@ def form_aria_asl_folder( # Get all image timestamps (in ns) image_timestamps = vrs_provider.get_timestamps_ns( - LEFT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME + constant.LEFT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME ) assert len(image_timestamps) > 0, "No timestamps found" @@ -203,7 +198,7 @@ def form_aria_asl_folder( matched_timestamps = None if has_slam_drops: right_image_timestamps = vrs_provider.get_timestamps_ns( - RIGHT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME + constant.RIGHT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME ) assert len(right_image_timestamps) > 0, ( "No right camera image timestamps found" From 2e50a3c5d1afa255edd5601ceb71a14e465562db Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:27:35 +0200 Subject: [PATCH 372/665] constants --- lamaria/utils/camera.py | 1 + tools/undistort_asl_folder.py | 10 ++++++---- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py index 86a7ee0..52644b9 100644 --- a/lamaria/utils/camera.py +++ b/lamaria/utils/camera.py @@ -6,6 +6,7 @@ from projectaria_tools.core.calibration import CameraCalibration from .transformation import get_t_cam_a_cam_b_from_json +from .constants import ARIA_CAMERAS def add_cameras_to_reconstruction( diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index 14eaf9f..3e1ee3c 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -12,7 +12,9 @@ from lamaria.utils.camera import ( add_cameras_to_reconstruction, ) -import lamaria.utils.constants as constant +from lamaria.utils.constants import ( + ARIA_CAMERAS, +) def undistort_reconstruction( @@ -88,7 +90,7 @@ def undistort_asl( image_id = 1 rig = recon.rig(rig_id=1) colmap_images = {} - for i, (key, _) in enumerate(constant.ARIA_CAMERAS): + for i, (key, _) in enumerate(ARIA_CAMERAS): cam = recon.cameras[i + 1] image_names = sorted( p.relative_to(asl_path) @@ -105,7 +107,7 @@ def undistort_asl( image_id += 1 colmap_images[key].append(im) - zipped_images = list(zip(*[colmap_images[key] for key, _ in constant.ARIA_CAMERAS])) + zipped_images = list(zip(*[colmap_images[key] for key, _ in ARIA_CAMERAS])) for j, (left_im, right_im) in enumerate( tqdm( @@ -134,7 +136,7 @@ def undistort_asl( # Copy the undistorted cameras in json. cameras_undist = { - key: cameras_undist[i + 1] for i, (key, _) in enumerate(constant.ARIA_CAMERAS) + key: cameras_undist[i + 1] for i, (key, _) in enumerate(ARIA_CAMERAS) } write_cameras_json( cameras_undist, output_asl_path / "aria" / "cameras.json" From 4a0d0367b01a618921da6cf40d81a89825ec4d60 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:28:33 +0200 Subject: [PATCH 373/665] const --- tools/vrs_to_asl_folder.py | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index c419613..5b7dfdf 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -12,7 +12,11 @@ extract_images_from_vrs, get_matched_timestamps, ) -import lamaria.utils.constants as constant +from lamaria.utils.constants import ( + LEFT_CAMERA_STREAM_ID, + RIGHT_CAMERA_STREAM_ID, + RIGHT_IMU_STREAM_ID, +) def remove_images_when_slam_drops( @@ -131,7 +135,7 @@ def write_image_csv(image_timestamps, cam_folder): def write_imu_data_to_csv(vrs_provider, csv_file): imu_timestamps = vrs_provider.get_timestamps_ns( - constant.RIGHT_IMU_STREAM_ID, + RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME ) @@ -155,7 +159,7 @@ def write_imu_data_to_csv(vrs_provider, csv_file): writer = csv.writer(f) for timestamp in tqdm(imu_timestamps, desc="Appending IMU data to CSV"): imu_data = vrs_provider.get_imu_data_by_time_ns( - constant.RIGHT_IMU_STREAM_ID, + RIGHT_IMU_STREAM_ID, timestamp, TimeDomain.DEVICE_TIME, TimeQueryOptions.CLOSEST, @@ -190,7 +194,7 @@ def form_aria_asl_folder( # Get all image timestamps (in ns) image_timestamps = vrs_provider.get_timestamps_ns( - constant.LEFT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME + LEFT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME ) assert len(image_timestamps) > 0, "No timestamps found" @@ -198,7 +202,7 @@ def form_aria_asl_folder( matched_timestamps = None if has_slam_drops: right_image_timestamps = vrs_provider.get_timestamps_ns( - constant.RIGHT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME + RIGHT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME ) assert len(right_image_timestamps) > 0, ( "No right camera image timestamps found" From cba4d4a00c7fc99024cc7c9d552a406e78c964b8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:29:25 +0200 Subject: [PATCH 374/665] const --- lamaria/utils/constants.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lamaria/utils/constants.py b/lamaria/utils/constants.py index c62173a..7b47b38 100644 --- a/lamaria/utils/constants.py +++ b/lamaria/utils/constants.py @@ -13,4 +13,7 @@ # Right Aria IMU constants RIGHT_IMU_STREAM_ID = StreamId("1202-1") -RIGHT_IMU_STREAM_LABEL = "imu-right" \ No newline at end of file +RIGHT_IMU_STREAM_LABEL = "imu-right" + +# Custom origin coordinates (LV95 / LN02) for translating large CP coordinates +CUSTOM_ORIGIN_COORDINATES = (2683594.4120000005, 1247727.7470000014, 417.307) \ No newline at end of file From 579b5b8ec684b51370beea6635afa060e4ca5539 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:30:38 +0200 Subject: [PATCH 375/665] custom origin --- lamaria/utils/control_point.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 7ad7067..35ce3c7 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -6,9 +6,11 @@ from tqdm import tqdm from .general import ( - CUSTOM_ORIGIN_COORDINATES, get_image_names_to_ids, ) +from .constants import ( + CUSTOM_ORIGIN_COORDINATES, +) def construct_control_points_from_json( From ccd2c4ad2a9b236d972dcba4077c6420e2950d5c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:31:28 +0200 Subject: [PATCH 376/665] consts --- lamaria/eval/create_empty_recon_from_estimate.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index a729b8a..4d0e57c 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -6,9 +6,11 @@ from tqdm import tqdm from ..utils.camera import ( + add_cameras_to_reconstruction, +) +from ..utils.constants import ( LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL, - add_cameras_to_reconstruction, ) from ..utils.estimate import ( round_ns, From 02ae5138fead05d135edbfccbc83bc933f0c4d54 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:31:35 +0200 Subject: [PATCH 377/665] mv consts --- lamaria/utils/general.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 2d9cedb..bef770c 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -8,8 +8,6 @@ from lamaria import logger -CUSTOM_ORIGIN_COORDINATES = (2683594.4120000005, 1247727.7470000014, 417.307) - def find_closest_timestamp( timestamps: list, From 352ee092100a2897f243d60338ffd8d41d94aa9d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:33:15 +0200 Subject: [PATCH 378/665] imu --- lamaria/utils/imu.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index efcb7fd..5f71fc1 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -5,9 +5,12 @@ from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions from tqdm import tqdm -from lamaria.utils.general import ( +from .general import ( find_closest_timestamp, ) +from .constants import ( + RIGHT_IMU_STREAM_ID, +) def get_online_params_for_imu_from_mps( From f105b9484f3ca5e04f83fec2ca39dda0bd7c90b2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:34:59 +0200 Subject: [PATCH 379/665] rel import --- lamaria/utils/general.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index bef770c..509937e 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -6,7 +6,7 @@ import pycolmap -from lamaria import logger +from .. import logger def find_closest_timestamp( From 44b06e4d0b42152ee8cdbdbd4ab2e5e54b06ed82 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:44:33 +0200 Subject: [PATCH 380/665] remove constaints function, shifting to pycolmap --- lamaria/pipeline/optim/iterative_global_ba.py | 22 ------------------- 1 file changed, 22 deletions(-) diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index e09201b..b22027a 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -10,27 +10,6 @@ from .session import SingleSeqSession -def apply_constraints(problem, session: SingleSeqSession): - """Apply rig constraints to the problem for fixing gauge freedom.""" - # Fix the first rig pose - frame_ids = sorted(session.data.reconstruction.frames.keys()) - first_frame_rfw = session.data.reconstruction.frames[ - frame_ids[0] - ].rig_from_world - problem.set_parameter_block_constant(first_frame_rfw.rotation.quat) - problem.set_parameter_block_constant(first_frame_rfw.translation) - - # Fix 1 DoF translation of the second rig - second_frame_rfw = session.data.reconstruction.frames[ - frame_ids[1] - ].rig_from_world - problem.set_manifold( - second_frame_rfw.translation, - pyceres.SubsetManifold(3, np.array([0])), - ) - return problem - - class VIBundleAdjuster: """Visual-Inertial Bundle Adjuster class that adds visual and IMU residuals to the @@ -82,7 +61,6 @@ def solve( self.session, problem, ) - # problem = apply_constraints(problem, self.session) # Setup callback if needed if vi_options.optim.use_callback: From fcd449f506d8a4b8378b5f46de68de4869d26f31 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:54:36 +0200 Subject: [PATCH 381/665] t_imu_camera upd --- lamaria/utils/transformation.py | 22 +++++----------------- 1 file changed, 5 insertions(+), 17 deletions(-) diff --git a/lamaria/utils/transformation.py b/lamaria/utils/transformation.py index 42a7903..3ce3cf6 100644 --- a/lamaria/utils/transformation.py +++ b/lamaria/utils/transformation.py @@ -72,13 +72,9 @@ def get_t_rig_world_for_device_time_ns( def get_t_imu_camera( imu_calib: ImuCalibration, camera_calib: CameraCalibration, - return_qt=False, - return_matrix=False, -): +) -> pycolmap.Rigid3d: """Get T_imu_camera from Aria calibrations. - Either return as qvec,tvec or 4x4 matrix. - If neither return_qt or return_matrix is True, - returns as projectaria_tools Rigid3d object. + Returns pycolmap.Rigid3d transform. """ t_device_cam = camera_calib.get_transform_device_camera() @@ -87,19 +83,11 @@ def get_t_imu_camera( t_imu_cam = t_imu_device @ t_device_cam - assert not (return_qt and return_matrix), ( - "Only one of return_qt or return_matrix can be True" + colmap_t_imu_cam = rigid3d_from_transform( + t_imu_cam ) - if return_qt: - qvec, tvec = get_qvec_and_tvec_from_transform(t_imu_cam) - return qvec, tvec - - if return_matrix: - t_imu_cam_matrix = t_imu_cam.to_matrix() - return t_imu_cam_matrix - - return t_imu_cam + return colmap_t_imu_cam def get_qvec_and_tvec_from_transform( From 7c3473ebf4416bafa6a110581d3a738c84b1741a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:56:06 +0200 Subject: [PATCH 382/665] t_imu_camera update --- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 8e156c4..635e81d 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -383,8 +383,7 @@ def _add_device_sensors(self) -> None: imu_calib, camera_calib, ) - t_camera_imu = t_imu_camera.inverse() - sensor_from_rig = rigid3d_from_transform(t_camera_imu) + sensor_from_rig = t_imu_camera.inverse() self.data.reconstruction.add_camera(cam) rig.add_sensor(cam.sensor_id, sensor_from_rig) @@ -444,8 +443,7 @@ def _add_online_sensors(self) -> None: imu_calib, camera_calib, ) - t_camera_imu = t_imu_camera.inverse() - sensor_from_rig = rigid3d_from_transform(t_camera_imu) + sensor_from_rig = t_imu_camera.inverse() self.data.reconstruction.add_camera(cam) rig.add_sensor(cam.sensor_id, sensor_from_rig) From 20f3b227af05b869e7df323e564a18d5428500c1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 20:57:58 +0200 Subject: [PATCH 383/665] ruff --- lamaria/eval/sparse_evaluation.py | 4 +--- lamaria/pipeline/optim/imu.py | 4 ++-- lamaria/pipeline/optim/iterative_global_ba.py | 1 - lamaria/pipeline/optim/session.py | 4 ++-- lamaria/utils/camera.py | 2 +- lamaria/utils/constants.py | 9 +++++---- lamaria/utils/control_point.py | 6 +++--- lamaria/utils/imu.py | 6 +++--- lamaria/utils/transformation.py | 4 +--- tools/vrs_to_asl_folder.py | 11 +++++------ 10 files changed, 23 insertions(+), 28 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 6877f19..7f9ad54 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -144,9 +144,7 @@ def run_baseline_evaluation( ) if triangulated_cp_alignment is None or topo_cp_alignment is None: - logger.error( - "Not enough control points for initial alignment" - ) + logger.error("Not enough control points for initial alignment") return False ret = pycolmap.estimate_sim3d_robust( diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 5066ac6..84ea2e3 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -1,6 +1,6 @@ import numpy as np -import pycolmap import pyceres +import pycolmap from tqdm import tqdm from ...config.options import OptIMUOptions @@ -186,4 +186,4 @@ def setup_manifolds_and_constraints( pyceres.SubsetManifold(9, constant_idxs), ) - return problem \ No newline at end of file + return problem diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index b22027a..9c9a8b2 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -1,4 +1,3 @@ -import numpy as np import pyceres import pycolmap from pycolmap import logging diff --git a/lamaria/pipeline/optim/session.py b/lamaria/pipeline/optim/session.py index f46c197..d72b970 100644 --- a/lamaria/pipeline/optim/session.py +++ b/lamaria/pipeline/optim/session.py @@ -21,8 +21,8 @@ def __init__( self._init_imu_data(imu_options) def _init_imu_data(self, imu_options): - self.preintegrated_imu_measurements = ( - preintegrate_imu_measurements(imu_options, self.data) + self.preintegrated_imu_measurements = preintegrate_imu_measurements( + imu_options, self.data ) self.imu_states = load_imu_states(self.data) self.imu_from_rig = pycolmap.Rigid3d() diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py index 52644b9..8bc4ee1 100644 --- a/lamaria/utils/camera.py +++ b/lamaria/utils/camera.py @@ -5,8 +5,8 @@ import pycolmap from projectaria_tools.core.calibration import CameraCalibration -from .transformation import get_t_cam_a_cam_b_from_json from .constants import ARIA_CAMERAS +from .transformation import get_t_cam_a_cam_b_from_json def add_cameras_to_reconstruction( diff --git a/lamaria/utils/constants.py b/lamaria/utils/constants.py index 7b47b38..6730858 100644 --- a/lamaria/utils/constants.py +++ b/lamaria/utils/constants.py @@ -1,9 +1,10 @@ - from projectaria_tools.core.stream_id import StreamId # ASL folder name, stream label for Aria cameras -ARIA_CAMERAS: list = [("cam0", "camera-slam-left"), - ("cam1", "camera-slam-right")] +ARIA_CAMERAS: list = [ + ("cam0", "camera-slam-left"), + ("cam1", "camera-slam-right"), +] # Aria camera constants LEFT_CAMERA_STREAM_ID = StreamId("1201-1") @@ -16,4 +17,4 @@ RIGHT_IMU_STREAM_LABEL = "imu-right" # Custom origin coordinates (LV95 / LN02) for translating large CP coordinates -CUSTOM_ORIGIN_COORDINATES = (2683594.4120000005, 1247727.7470000014, 417.307) \ No newline at end of file +CUSTOM_ORIGIN_COORDINATES = (2683594.4120000005, 1247727.7470000014, 417.307) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 35ce3c7..980b06c 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -5,12 +5,12 @@ import pycolmap from tqdm import tqdm -from .general import ( - get_image_names_to_ids, -) from .constants import ( CUSTOM_ORIGIN_COORDINATES, ) +from .general import ( + get_image_names_to_ids, +) def construct_control_points_from_json( diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py index 5f71fc1..9914a37 100644 --- a/lamaria/utils/imu.py +++ b/lamaria/utils/imu.py @@ -5,12 +5,12 @@ from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions from tqdm import tqdm -from .general import ( - find_closest_timestamp, -) from .constants import ( RIGHT_IMU_STREAM_ID, ) +from .general import ( + find_closest_timestamp, +) def get_online_params_for_imu_from_mps( diff --git a/lamaria/utils/transformation.py b/lamaria/utils/transformation.py index 3ce3cf6..541bb8f 100644 --- a/lamaria/utils/transformation.py +++ b/lamaria/utils/transformation.py @@ -83,9 +83,7 @@ def get_t_imu_camera( t_imu_cam = t_imu_device @ t_device_cam - colmap_t_imu_cam = rigid3d_from_transform( - t_imu_cam - ) + colmap_t_imu_cam = rigid3d_from_transform(t_imu_cam) return colmap_t_imu_cam diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index 5b7dfdf..ca23ae1 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -8,15 +8,15 @@ from tqdm import tqdm from lamaria import logger -from lamaria.utils.general import ( - extract_images_from_vrs, - get_matched_timestamps, -) from lamaria.utils.constants import ( LEFT_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, RIGHT_IMU_STREAM_ID, ) +from lamaria.utils.general import ( + extract_images_from_vrs, + get_matched_timestamps, +) def remove_images_when_slam_drops( @@ -135,8 +135,7 @@ def write_image_csv(image_timestamps, cam_folder): def write_imu_data_to_csv(vrs_provider, csv_file): imu_timestamps = vrs_provider.get_timestamps_ns( - RIGHT_IMU_STREAM_ID, - TimeDomain.DEVICE_TIME + RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME ) last_timestamp = None From 32464a1dd9a287aa62d0ae127d846a5abf213758 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:00:11 +0200 Subject: [PATCH 384/665] doc string --- tools/asl_folder_to_rosbag.py | 2 +- tools/undistort_asl_folder.py | 21 ++++++++++++++++++--- 2 files changed, 19 insertions(+), 4 deletions(-) diff --git a/tools/asl_folder_to_rosbag.py b/tools/asl_folder_to_rosbag.py index 4c59033..5abd907 100644 --- a/tools/asl_folder_to_rosbag.py +++ b/tools/asl_folder_to_rosbag.py @@ -169,7 +169,7 @@ def asl_to_rosbag( if __name__ == "__main__": parser = argparse.ArgumentParser() parser.add_argument( - "--input_asl_folder", type=Path, required=True, help="Input folder" + "--input_asl_folder", type=Path, required=True, help="Input ASL folder" ) parser.add_argument( "--output_rosbag", type=Path, required=True, help="Output rosbag file" diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index 3e1ee3c..143f9b8 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -153,9 +153,24 @@ def undistort_asl( if __name__ == "__main__": parser = argparse.ArgumentParser() - parser.add_argument("--calibration_file", type=Path, required=True) - parser.add_argument("--asl_path", type=Path, required=True) - parser.add_argument("--output_asl_path", type=Path, required=True) + parser.add_argument( + "--calibration_file", + type=Path, + required=True, + help="Path to Aria calibration json file", + ) + parser.add_argument( + "--asl_path", + type=Path, + required=True, + help="Path to input Aria distorted ASL folder", + ) + parser.add_argument( + "--output_asl_path", + type=Path, + required=True, + help="Path to output undistorted ASL folder", + ) parser.add_argument("--ratio_blank_pixels", type=float, default=0.2) args = parser.parse_args() From 197092dec62d77609e9817c5876bfb1aa5b78dba Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:00:49 +0200 Subject: [PATCH 385/665] doc strings --- tools/vrs_to_asl_folder.py | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index ca23ae1..a8f3641 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -261,8 +261,18 @@ def form_aria_asl_folder( if __name__ == "__main__": args = argparse.ArgumentParser() - args.add_argument("--vrs_file", type=Path, required=True) - args.add_argument("--output_asl_folder", type=Path, required=True) + args.add_argument( + "--vrs_file", + type=Path, + required=True, + help="Path to input VRS file", + ) + args.add_argument( + "--output_asl_folder", + type=Path, + required=True, + help="Path to output ASL folder", + ) args.add_argument( "--has_slam_drops", action="store_true", From fda1aa074543b6ddbb9ab2da20ba1f853b4746dc Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:06:22 +0200 Subject: [PATCH 386/665] struct folder: lamaria recons --- lamaria/pipeline/keyframing/keyframe_selection.py | 2 +- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 2 +- lamaria/pipeline/optim/imu.py | 2 +- lamaria/pipeline/optim/session.py | 2 +- lamaria/{pipeline => structs}/lamaria_reconstruction.py | 0 run_pipeline.py | 2 +- 6 files changed, 5 insertions(+), 5 deletions(-) rename lamaria/{pipeline => structs}/lamaria_reconstruction.py (100%) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index f7de37f..419dc23 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -9,7 +9,7 @@ from ...config.options import KeyframeSelectorOptions from ...utils.transformation import get_magnitude_from_transform -from ..lamaria_reconstruction import LamariaReconstruction +from ...structs.lamaria_reconstruction import LamariaReconstruction class KeyframeSelector: diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 635e81d..c723540 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -31,7 +31,7 @@ get_t_imu_camera, rigid3d_from_transform, ) -from ..lamaria_reconstruction import LamariaReconstruction +from ...structs.lamaria_reconstruction import LamariaReconstruction @dataclass diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 84ea2e3..9206b16 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -4,7 +4,7 @@ from tqdm import tqdm from ...config.options import OptIMUOptions -from ..lamaria_reconstruction import LamariaReconstruction +from ...structs.lamaria_reconstruction import LamariaReconstruction from .session import SingleSeqSession diff --git a/lamaria/pipeline/optim/session.py b/lamaria/pipeline/optim/session.py index d72b970..597b031 100644 --- a/lamaria/pipeline/optim/session.py +++ b/lamaria/pipeline/optim/session.py @@ -4,7 +4,7 @@ import pycolmap from ...config.options import OptIMUOptions -from ..lamaria_reconstruction import LamariaReconstruction +from ...structs.lamaria_reconstruction import LamariaReconstruction from .imu import ( load_imu_states, preintegrate_imu_measurements, diff --git a/lamaria/pipeline/lamaria_reconstruction.py b/lamaria/structs/lamaria_reconstruction.py similarity index 100% rename from lamaria/pipeline/lamaria_reconstruction.py rename to lamaria/structs/lamaria_reconstruction.py diff --git a/run_pipeline.py b/run_pipeline.py index 6ab7ba3..cb05ccf 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -15,7 +15,7 @@ from lamaria.pipeline.keyframing.to_lamaria_reconstruction import ( EstimateToLamaria, ) -from lamaria.pipeline.lamaria_reconstruction import LamariaReconstruction +from lamaria.structs.lamaria_reconstruction import LamariaReconstruction from lamaria.pipeline.optim.session import SingleSeqSession from lamaria.pipeline.optim.triangulation import run as triangulate from lamaria.pipeline.optim.vi_optimization import VIOptimizer From 211c5384df42d53458921c412f04f526b8161852 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:39:52 +0200 Subject: [PATCH 387/665] estimate class --- lamaria/structs/estimate.py | 104 ++++++++++++++++++++++++++++++++++++ 1 file changed, 104 insertions(+) create mode 100644 lamaria/structs/estimate.py diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py new file mode 100644 index 0000000..e259513 --- /dev/null +++ b/lamaria/structs/estimate.py @@ -0,0 +1,104 @@ +from decimal import ROUND_HALF_UP, Decimal +from pathlib import Path + +import numpy as np +import pycolmap + + +def _round_ns(x: str | int | float) -> int: + # works for "5120...274.999939", "5.12e11", or ints + if isinstance(x, int): + return x + s = str(x) + return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) + + +class Estimate: + """ + Loads and stores an 'estimate' text file with rows: + ts t_x t_y t_z q_x q_y q_z q_w + Blank lines and lines starting with '#' are ignored. + + By default, poses are returned as rig_from_world + (i.e., inverse of world_from_rig) to satisfy COLMAP format. + """ + + def __init__(self, invert_poses: bool = True) -> None: + self.invert_poses = invert_poses + self.path: Path | None = None + self._timestamps: list[int] = [] + self._poses: list[pycolmap.Rigid3d] = [] + + def load_from_file(self, path: str | Path) -> "Estimate": + """Parse the file, validate format, populate timestamps & poses.""" + self.clear() + self.path = Path(path) + + with open(self.path, "r") as f: + lines = f.readlines() + + self._parse(lines) # raises error if format is invalid + return self + + @property + def timestamps(self) -> list[int]: + self._ensure_loaded() + return self._timestamps + + @property + def poses(self) -> list[pycolmap.Rigid3d]: + self._ensure_loaded() + return self._poses + + def as_dict(self) -> dict[int, pycolmap.Rigid3d]: + self._ensure_loaded() + return dict(zip(self._timestamps, self._poses, strict=True)) + + def __len__(self) -> int: + return len(self._timestamps) + + def is_loaded(self) -> bool: + return len(self._timestamps) > 0 + + def clear(self) -> None: + self._timestamps.clear() + self._poses.clear() + + def _ensure_loaded(self) -> None: + if not self._timestamps or not self._poses: + raise RuntimeError("Estimate not loaded. Call load_from_file() first.") + + def _parse(self, lines: list[str]) -> None: + ts_list: list[int] = [] + pose_list: list[pycolmap.Rigid3d] = [] + exists_lines = False + for lineno, line in enumerate(lines, start=1): + line = line.strip() + if not line or line.startswith("#"): + continue + + exists_lines = True + parts = line.split() + if len(parts) != 8: + raise ValueError(f"{lineno}: expected 8 values, got {len(parts)}") + + try: + ts = _round_ns(parts[0]) + tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) + qvec = np.array([float(parts[4]), float(parts[5]), + float(parts[6]), float(parts[7])]) + + except ValueError as e: + raise ValueError(f"{lineno}: non-numeric value in {parts!r}") from e + + world_from_rig = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) + pose = world_from_rig.inverse() if self.invert_poses else world_from_rig + + ts_list.append(ts) + pose_list.append(pose) + + if not exists_lines: + raise ValueError("No valid lines found in estimate file.") + + self._timestamps = ts_list + self._poses = pose_list \ No newline at end of file From 3b994d34da02831c95731326e62d28dbc1151225 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:40:28 +0200 Subject: [PATCH 388/665] rm estimate utils --- lamaria/utils/estimate.py | 130 -------------------------------------- 1 file changed, 130 deletions(-) delete mode 100644 lamaria/utils/estimate.py diff --git a/lamaria/utils/estimate.py b/lamaria/utils/estimate.py deleted file mode 100644 index b9795cd..0000000 --- a/lamaria/utils/estimate.py +++ /dev/null @@ -1,130 +0,0 @@ -from decimal import ROUND_HALF_UP, Decimal -from pathlib import Path - -import numpy as np -import pycolmap - - -def round_ns(x: str | int | float) -> int: - # works for "5120...274.999939", "5.12e11", or ints - if isinstance(x, int): - return x - s = str(x) - return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) - - -def get_rig_from_worlds_from_estimate( - estimate_path: Path, -) -> list[pycolmap.Rigid3d]: - """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - - rig_from_worlds: list[pycolmap.Rigid3d] = [] - - with open(estimate_path) as f: - lines = f.readlines() - for lineno, line in enumerate(lines, start=1): - line = line.strip() - if not line or line.startswith("#"): - continue - - parts = line.split() - if len(parts) != 8: - raise ValueError( - f"{estimate_path}:{lineno}: " - f"expected 8 values, got {len(parts)}" - ) - - try: - tvec = np.array( - [float(parts[1]), float(parts[2]), float(parts[3])] - ) - qvec = np.array( - [ - float(parts[4]), - float(parts[5]), - float(parts[6]), - float(parts[7]), - ] - ) - except ValueError as e: - raise ValueError( - f"{estimate_path}:{lineno}: " - f"expected a number, got {parts!r}" - ) from e - - pose = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) - rig_from_world = pose.inverse() - rig_from_worlds.append(rig_from_world) - - return rig_from_worlds - - -def check_estimate_format(estimate_path: Path) -> bool: - """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - - exists_lines = False - with open(estimate_path) as f: - lines = f.readlines() - for lineno, line in enumerate(lines, start=1): - line = line.strip() - if not line or line.startswith("#"): - continue - - exists_lines = True - - parts = line.split() - if len(parts) != 8: - raise ValueError( - f"{estimate_path}:{lineno}: expected " - f"8 values, got {len(parts)}" - ) - - try: - [float(part) for part in parts] - except ValueError as e: - raise ValueError( - f"{estimate_path}:{lineno}: " - f"expected a number, got {parts!r}" - ) from e - - if not exists_lines: - raise ValueError( - f"Estimate file {estimate_path} is empty or has no valid lines." - ) - - -def get_estimate_timestamps(estimate_path: Path) -> list[int]: - """Estimate file format: ts t_x t_y t_z q_x q_y q_z q_w""" - timestamps = [] - with open(estimate_path) as f: - lines = f.readlines() - lines = [line for line in lines if not line.startswith("#")] - if not lines: - raise ValueError( - f"Estimate file {estimate_path} is empty \ - or has no valid lines." - ) - - for lineno, line in enumerate(lines, start=1): - line = line.strip() - if not line or line.startswith("#"): - continue - - parts = line.split() - if len(parts) != 8: - raise ValueError( - f"{estimate_path}:{lineno}: " - f"expected 8 values, got {len(parts)}" - ) - - try: - ts = round_ns(parts[0]) - except ValueError as e: - raise ValueError( - f"{estimate_path}:{lineno}: " - f"expected a number, got {parts[0]!r}" - ) from e - - timestamps.append(ts) - - return timestamps From 7d570ed7e8e4a49287531fd8e714e0b4ac2b4b20 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:45:52 +0200 Subject: [PATCH 389/665] to lamaria upd with estimate file --- .../keyframing/to_lamaria_reconstruction.py | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index c723540..07dfc6c 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -10,13 +10,12 @@ from ... import logger from ...config.options import EstimateToLamariaOptions +from ...structs.lamaria_reconstruction import LamariaReconstruction from ...utils.camera import ( camera_colmap_from_calib, ) -from ...utils.estimate import ( - check_estimate_format, - get_estimate_timestamps, - get_rig_from_worlds_from_estimate, +from ...structs.estimate import ( + Estimate, ) from ...utils.general import ( extract_images_from_vrs, @@ -31,7 +30,6 @@ get_t_imu_camera, rigid3d_from_transform, ) -from ...structs.lamaria_reconstruction import LamariaReconstruction @dataclass @@ -150,17 +148,16 @@ def _init_data( ) # Raises error if estimate file is invalid - check_estimate_format(estimate) + est = Estimate(invert_poses=True) + est.load_from_file(estimate) - timestamps = get_estimate_timestamps(estimate) + timestamps = est.timestamps if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images( images, timestamps ) - rig_from_worlds = get_rig_from_worlds_from_estimate( - estimate, - ) + rig_from_worlds = est.poses self._per_frame_data = self._build_per_frame_data_from_estimate( images, timestamps, rig_from_worlds ) From a7167638f3c30cbc496b7076a3c8ce5cc8db892e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:46:02 +0200 Subject: [PATCH 390/665] ruff --- lamaria/structs/estimate.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index e259513..ab93369 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -19,7 +19,7 @@ class Estimate: ts t_x t_y t_z q_x q_y q_z q_w Blank lines and lines starting with '#' are ignored. - By default, poses are returned as rig_from_world + By default, poses are returned as rig_from_world (i.e., inverse of world_from_rig) to satisfy COLMAP format. """ From 6d7cd9144a786d3d63849f96f822d71936a4c70d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:46:08 +0200 Subject: [PATCH 391/665] ruff --- tools/vrs_to_asl_folder.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index a8f3641..d05dac2 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -262,8 +262,8 @@ def form_aria_asl_folder( args = argparse.ArgumentParser() args.add_argument( - "--vrs_file", - type=Path, + "--vrs_file", + type=Path, required=True, help="Path to input VRS file", ) From db0622e3468f761de8522d1ca80fcf646432e4c7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:46:18 +0200 Subject: [PATCH 392/665] kf selections --- lamaria/pipeline/keyframing/keyframe_selection.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 419dc23..234ce6d 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -8,8 +8,8 @@ import pycolmap from ...config.options import KeyframeSelectorOptions -from ...utils.transformation import get_magnitude_from_transform from ...structs.lamaria_reconstruction import LamariaReconstruction +from ...utils.transformation import get_magnitude_from_transform class KeyframeSelector: From 5ac011eca08ef2cb7704a85761e33d4d82d775b3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:46:31 +0200 Subject: [PATCH 393/665] ruff --- lamaria/structs/estimate.py | 56 ++++++++++++++++++++++++------------- 1 file changed, 37 insertions(+), 19 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index ab93369..078dbc4 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -34,12 +34,12 @@ def load_from_file(self, path: str | Path) -> "Estimate": self.clear() self.path = Path(path) - with open(self.path, "r") as f: + with open(self.path) as f: lines = f.readlines() self._parse(lines) # raises error if format is invalid return self - + @property def timestamps(self) -> list[int]: self._ensure_loaded() @@ -49,14 +49,14 @@ def timestamps(self) -> list[int]: def poses(self) -> list[pycolmap.Rigid3d]: self._ensure_loaded() return self._poses - + def as_dict(self) -> dict[int, pycolmap.Rigid3d]: self._ensure_loaded() return dict(zip(self._timestamps, self._poses, strict=True)) - + def __len__(self) -> int: return len(self._timestamps) - + def is_loaded(self) -> bool: return len(self._timestamps) > 0 @@ -66,8 +66,10 @@ def clear(self) -> None: def _ensure_loaded(self) -> None: if not self._timestamps or not self._poses: - raise RuntimeError("Estimate not loaded. Call load_from_file() first.") - + raise RuntimeError( + "Estimate not loaded. Call load_from_file() first." + ) + def _parse(self, lines: list[str]) -> None: ts_list: list[int] = [] pose_list: list[pycolmap.Rigid3d] = [] @@ -76,29 +78,45 @@ def _parse(self, lines: list[str]) -> None: line = line.strip() if not line or line.startswith("#"): continue - + exists_lines = True parts = line.split() if len(parts) != 8: - raise ValueError(f"{lineno}: expected 8 values, got {len(parts)}") - + raise ValueError( + f"{lineno}: expected 8 values, got {len(parts)}" + ) + try: ts = _round_ns(parts[0]) - tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) - qvec = np.array([float(parts[4]), float(parts[5]), - float(parts[6]), float(parts[7])]) - + tvec = np.array( + [float(parts[1]), float(parts[2]), float(parts[3])] + ) + qvec = np.array( + [ + float(parts[4]), + float(parts[5]), + float(parts[6]), + float(parts[7]), + ] + ) + except ValueError as e: - raise ValueError(f"{lineno}: non-numeric value in {parts!r}") from e - + raise ValueError( + f"{lineno}: non-numeric value in {parts!r}" + ) from e + world_from_rig = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) - pose = world_from_rig.inverse() if self.invert_poses else world_from_rig + pose = ( + world_from_rig.inverse() + if self.invert_poses + else world_from_rig + ) ts_list.append(ts) pose_list.append(pose) if not exists_lines: raise ValueError("No valid lines found in estimate file.") - + self._timestamps = ts_list - self._poses = pose_list \ No newline at end of file + self._poses = pose_list From 78f0e411f383f4249c7714394116b33114edd37d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:51:19 +0200 Subject: [PATCH 394/665] as tuples in estimate --- lamaria/structs/estimate.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 078dbc4..1131276 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -50,7 +50,13 @@ def poses(self) -> list[pycolmap.Rigid3d]: self._ensure_loaded() return self._poses + def as_tuples(self) -> list[tuple[int, pycolmap.Rigid3d]]: + """Return a list of (timestamp, pose) tuples.""" + self._ensure_loaded() + return list(zip(self._timestamps, self._poses, strict=True)) + def as_dict(self) -> dict[int, pycolmap.Rigid3d]: + """Return a dict mapping timestamp to pose.""" self._ensure_loaded() return dict(zip(self._timestamps, self._poses, strict=True)) From b8ede7324e68ca8ab2286f2af12f45ad9a16fd1d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:51:52 +0200 Subject: [PATCH 395/665] create empty recon upd with estimate object --- .../eval/create_empty_recon_from_estimate.py | 38 +++---------------- 1 file changed, 6 insertions(+), 32 deletions(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index 4d0e57c..9b74605 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -5,6 +5,9 @@ import pycolmap from tqdm import tqdm +from ..structs.estimate import ( + Estimate, +) from ..utils.camera import ( add_cameras_to_reconstruction, ) @@ -12,9 +15,6 @@ LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL, ) -from ..utils.estimate import ( - round_ns, -) from ..utils.general import ( delete_files_in_folder, find_closest_timestamp, @@ -33,35 +33,9 @@ def _add_images_to_reconstruction( ): """Add images to an existing empty reconstruction from a pose estimate file.""" - pose_data = [] - with open(estimate_file) as f: - lines = f.readlines() - - if len(lines) == 0: - return reconstruction - - if "#" in lines[0]: - lines = lines[1:] - - for line in lines: - parts = line.split() - if len(parts) < 8: - continue - - timestamp = round_ns(parts[0]) - - tvec = np.array([float(parts[1]), float(parts[2]), float(parts[3])]) - q_xyzw = np.array( - [ - float(parts[4]), - float(parts[5]), - float(parts[6]), - float(parts[7]), - ] - ) - T_world_device = pycolmap.Rigid3d(pycolmap.Rotation3d(q_xyzw), tvec) - - pose_data.append((timestamp, T_world_device)) + est = Estimate(invert_poses=False) + est.load_from_file(estimate_file) + pose_data = est.as_tuples() with open(cp_json_file) as f: cp_data = json.load(f) From 90141021b780b5511b9e1883e04500f643168f01 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 21:52:07 +0200 Subject: [PATCH 396/665] structs --- run_pipeline.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/run_pipeline.py b/run_pipeline.py index cb05ccf..776a433 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -15,10 +15,10 @@ from lamaria.pipeline.keyframing.to_lamaria_reconstruction import ( EstimateToLamaria, ) -from lamaria.structs.lamaria_reconstruction import LamariaReconstruction from lamaria.pipeline.optim.session import SingleSeqSession from lamaria.pipeline.optim.triangulation import run as triangulate from lamaria.pipeline.optim.vi_optimization import VIOptimizer +from lamaria.structs.lamaria_reconstruction import LamariaReconstruction def run_estimate_to_lamaria( From a6bbb04acd4bfd2a6f23766e47b8b92a61ea265d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 23:46:07 +0200 Subject: [PATCH 397/665] upd options --- lamaria/config/options.py | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 8ed468e..92a4bbb 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -19,13 +19,9 @@ def _structured_merge_to_obj(cls, section) -> object: # General options @dataclass(slots=True) class MPSOptions: - use_mps: bool = False use_online_calibration: bool = ( False # when use_mps is true (for online calib file) ) - has_slam_drops: bool = ( - False # check vrs json metadata file for each sequence - ) @classmethod def load(cls, cfg: OmegaConf | None = None) -> MPSOptions: @@ -41,6 +37,9 @@ class SensorOptions: right_cam_stream_id: str = "1201-2" right_imu_stream_id: str = "1202-1" camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" + has_slam_drops: bool = ( + False # check vrs json metadata file for each sequence + ) @classmethod def load(cls, cfg: OmegaConf | None = None) -> SensorOptions: From 2b1784c0113180c2910d768033c5c2de8549c875 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 23:46:15 +0200 Subject: [PATCH 398/665] defs --- defaults.yaml | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/defaults.yaml b/defaults.yaml index 39c9c35..7fd604a 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -2,6 +2,7 @@ sensor: camera_model: RAD_TAN_THIN_PRISM_FISHEYE + has_slam_drops: false keyframing: max_rotation: 20.0 @@ -49,6 +50,4 @@ optimization: integration_noise_density: 0.05 mps: - use_mps: false - use_online_calibration: false # relevant only when use_mps is true (for online calib file) - has_slam_drops: false + use_online_calibration: false # relevant only when mps folder is used From 80ed5a95db4579cd680845abee878abdaf5cf059 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 23:53:11 +0200 Subject: [PATCH 399/665] pipeline upd without use_mps --- run_pipeline.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index 776a433..712e69e 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -191,10 +191,12 @@ def run_pipeline( if not output_path.exists(): output_path.mkdir(parents=True, exist_ok=True) + src = "estimate" if estimate is not None else "mps" + # Estimate to Lamaria Reconstruction est_options = options.estimate_to_colmap_options - if not est_options.mps.use_mps: - assert estimate is not None and estimate.exists(), ( + if src == "estimate": + assert estimate.exists(), ( "Estimate path must be provided if not using MPS" ) @@ -206,7 +208,7 @@ def run_pipeline( options.colmap_model_path, ) else: - assert mps_folder is not None and mps_folder.exists(), ( + assert mps_folder.exists(), ( "MPS folder path must be provided if using MPS" ) From bd37800e94f58a56e1fb3f2e6892cb56c409b87a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sat, 27 Sep 2025 23:54:06 +0200 Subject: [PATCH 400/665] rm use_mps entirely --- .../keyframing/to_lamaria_reconstruction.py | 17 +++++------------ 1 file changed, 5 insertions(+), 12 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 07dfc6c..47c09bd 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -75,7 +75,7 @@ def process( ) -> LamariaReconstruction: self._init_data(vrs, images_path, estimate, mps_folder) - if self.options.mps.use_online_calibration and self.options.mps.use_mps: + if self.options.mps.use_online_calibration: self._add_online_sensors() self._add_online_frames() else: @@ -114,10 +114,7 @@ def _init_data( self._right_imu_sid = StreamId(self.options.sensor.right_imu_stream_id) # Initialize MPS data provider if needed - if self.options.mps.use_mps: - assert mps_folder is not None, ( - "MPS folder path must be provided if using MPS" - ) + if mps_folder is not None: data_paths = mps.MpsDataPathsProvider( mps_folder.as_posix() ).get_data_paths() @@ -132,7 +129,7 @@ def _init_data( images = self._get_images(image_folder) # Get timestamps and build per-frame data - if self.options.mps.use_mps: + if estimate is None: timestamps = self._get_mps_timestamps() closed_loop_data = get_closed_loop_data_from_mps(mps_folder) pose_timestamps = [left for left, _ in timestamps] @@ -143,10 +140,6 @@ def _init_data( images, timestamps, mps_poses ) else: - assert estimate is not None, ( - "Estimate path must be provided if not using MPS" - ) - # Raises error if estimate file is invalid est = Estimate(invert_poses=True) est.load_from_file(estimate) @@ -263,7 +256,7 @@ def _get_images(self, images_path: Path) -> list[tuple[Path, Path]]: def _get_mps_timestamps(self, max_diff=1e6) -> list[tuple[int, int]]: L = self._ts_from_vrs(self._left_cam_sid) R = self._ts_from_vrs(self._right_cam_sid) - if not self.options.mps.has_slam_drops: + if not self.options.sensor.has_slam_drops: assert len(L) == len(R), ( "Unequal number of left and right timestamps" ) @@ -526,7 +519,7 @@ def _get_rectified_imu_data( mps_folder: Path | None = None, ) -> pycolmap.ImuMeasurements: """Generates rectified IMU data from VRS file""" - if self.options.mps.use_online_calibration and self.options.mps.use_mps: + if self.options.mps.use_online_calibration: assert mps_folder is not None, ( "MPS folder path must be provided if using MPS" ) From fa8cc0aa96a0d90cb96fb8cb9caf1fd0216e98cd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:17:41 +0200 Subject: [PATCH 401/665] rm camera transformation --- lamaria/utils/camera.py | 140 ------------------------- lamaria/utils/transformation.py | 174 -------------------------------- 2 files changed, 314 deletions(-) delete mode 100644 lamaria/utils/camera.py delete mode 100644 lamaria/utils/transformation.py diff --git a/lamaria/utils/camera.py b/lamaria/utils/camera.py deleted file mode 100644 index 8bc4ee1..0000000 --- a/lamaria/utils/camera.py +++ /dev/null @@ -1,140 +0,0 @@ -import json -from pathlib import Path - -import numpy as np -import pycolmap -from projectaria_tools.core.calibration import CameraCalibration - -from .constants import ARIA_CAMERAS -from .transformation import get_t_cam_a_cam_b_from_json - - -def add_cameras_to_reconstruction( - reconstruction: pycolmap.Reconstruction, - calibration_file: Path, -) -> None: - """Add Aria cameras to COLMAP reconstruction from calibration - json file found on website: https://lamaria.ethz.ch/slam_datasets - - Args: - reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction - to which cameras will be added - - calibration_file (Path): - Path to the Aria calibration json file - """ - - for i, (key, _) in enumerate(ARIA_CAMERAS): - cam = camera_colmap_from_json( - calibration_file=calibration_file, - camera_label=key, - ) - cam.camera_id = i + 1 - reconstruction.add_camera(cam) - - rig = pycolmap.Rig(rig_id=1) - ref_sensor = pycolmap.sensor_t( - id=1, # left camera is the rig - type=pycolmap.SensorType.CAMERA, - ) - rig.add_ref_sensor(ref_sensor) - - sensor1 = pycolmap.sensor_t(id=2, type=pycolmap.SensorType.CAMERA) - sensor_from_rig = get_t_cam_a_cam_b_from_json( - calibration_file=calibration_file, - camera_a_label="cam1", # right - camera_b_label="cam0", # left - ) - rig.add_sensor(sensor1, sensor_from_rig) - - reconstruction.add_rig(rig) - - -def get_camera_params_for_colmap( - camera_calibration: CameraCalibration, - camera_model: str, -) -> list[float]: - """ - Convert Aria CameraCalibration to COLMAP camera parameters. - Supported models: OPENCV_FISHEYE, FULL_OPENCV, RAD_TAN_THIN_PRISM_FISHEYE - Args: - camera_calibration (CameraCalibration): - The projectaria_tools CameraCalibration object - camera_model (str): The COLMAP camera model to use - Returns: - list[float]: The camera parameters in COLMAP format - """ - # params = [f_u {f_v} c_u c_v [k_0: k_{numK-1}] - # {p_0 p_1} {s_0 s_1 s_2 s_3}] - # projection_params is a 15 length vector, - # starting with focal length, pp, extra coeffs - camera_params = camera_calibration.get_projection_params() - f_x, f_y, c_x, c_y = ( - camera_params[0], - camera_params[0], - camera_params[1], - camera_params[2], - ) - - p2, p1 = camera_params[-5], camera_params[-6] - - k1, k2, k3, k4, k5, k6 = camera_params[3:9] - - # FULL_OPENCV model format: - # fx, fy, cx, cy, k1, k2, p1, p2, k3, k4, k5, k6 - - # OPENCV_FISHEYE model format: - # fx, fy, cx, cy, k1, k2, k3, k4 - - if camera_model == "OPENCV_FISHEYE": - params = [f_x, f_y, c_x, c_y, k1, k2, k3, k4] - elif camera_model == "FULL_OPENCV": - params = [f_x, f_y, c_x, c_y, k1, k2, p1, p2, k3, k4, k5, k6] - elif camera_model == "RAD_TAN_THIN_PRISM_FISHEYE": - aria_fisheye_params = camera_params - focal_length = aria_fisheye_params[0] - aria_fisheye_params = np.insert(aria_fisheye_params, 0, focal_length) - params = aria_fisheye_params - - return params - - -def camera_colmap_from_calib(calib: CameraCalibration) -> pycolmap.Camera: - """Loads pycolmap camera from Aria CameraCalibration object""" - if calib.get_model_name().name != "FISHEYE624": - raise ValueError( - f"Unsupported Aria model {calib.get_model_name().name}" - ) - model = "RAD_TAN_THIN_PRISM_FISHEYE" - params = get_camera_params_for_colmap(calib, model) - width, height = calib.get_image_size() - return pycolmap.Camera( - model=model, - width=width, - height=height, - params=params, - ) - - -def camera_colmap_from_json( - calibration_file: Path, # open sourced aria calibration files - camera_label: str, -) -> pycolmap.Camera: - """Loads pycolmap camera from Aria calibration json file found on website: - https://lamaria.ethz.ch/slam_datasets""" - - calib = json.load(calibration_file.open("r")) - camera_data = calib[camera_label] - if camera_data["model"] != "RAD_TAN_THIN_PRISM_FISHEYE": - raise ValueError(f"Unsupported Aria model {camera_data['model']}") - - model = "RAD_TAN_THIN_PRISM_FISHEYE" - params = camera_data["params"] - width = camera_data["resolution"]["width"] - height = camera_data["resolution"]["height"] - return pycolmap.Camera( - model=model, - width=width, - height=height, - params=params, - ) diff --git a/lamaria/utils/transformation.py b/lamaria/utils/transformation.py deleted file mode 100644 index 541bb8f..0000000 --- a/lamaria/utils/transformation.py +++ /dev/null @@ -1,174 +0,0 @@ -import json -from pathlib import Path - -import numpy as np -import pycolmap -from projectaria_tools.core import mps -from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration -from projectaria_tools.core.mps.utils import get_nearest_pose -from scipy.spatial.transform import Rotation - - -def get_closed_loop_data_from_mps( - mps_path: Path, -) -> list[mps.ClosedLoopTrajectoryPose]: - """Get closed loop trajectory data from MPS folder.""" - closed_loop_traj_file = mps_path / "slam" / "closed_loop_trajectory.csv" - data = mps.read_closed_loop_trajectory(closed_loop_traj_file.as_posix()) - return data - - -def get_mps_poses_for_timestamps( - trajectory_data: list[mps.ClosedLoopTrajectoryPose], - timestamps: list[int], -) -> list: - """Get T_world_device for a list of device timestamps - in nanoseconds using MPS trajectory data. - Returns None for timestamps where - no trajectory data is found. - """ - poses = [] - if trajectory_data: - for ts in timestamps: - pose_information = get_nearest_pose(trajectory_data, ts) - if pose_information: - t_world_device = pose_information.transform_world_device - poses.append(t_world_device) - else: - poses.append(None) - - return poses - - -def get_t_rig_world_for_device_time_ns( - trajectory_data: list[mps.ClosedLoopTrajectoryPose], - device_time_ns: int, - imu_calibration: ImuCalibration, -): - """Get T_rig_world (rig is right IMU sensor) for a given device time - in nanoseconds using MPS trajectory data and IMU calibration. - Returns None if no trajectory data is found for the given timestamp. - """ - if trajectory_data: - pose_information = get_nearest_pose(trajectory_data, device_time_ns) - if pose_information: - t_world_device = pose_information.transform_world_device - t_device_imu = imu_calibration.get_transform_device_imu() - assert t_device_imu is not None, ( - f"No t_device_imu found for device time {device_time_ns}, \ - check imu calibration" - ) - - t_world_imu = t_world_device @ t_device_imu - t_imu_world = t_world_imu.inverse() - - return t_imu_world - else: - return None - else: - raise ValueError("No trajectory data found") - - -def get_t_imu_camera( - imu_calib: ImuCalibration, - camera_calib: CameraCalibration, -) -> pycolmap.Rigid3d: - """Get T_imu_camera from Aria calibrations. - Returns pycolmap.Rigid3d transform. - """ - - t_device_cam = camera_calib.get_transform_device_camera() - t_device_imu = imu_calib.get_transform_device_imu() - t_imu_device = t_device_imu.inverse() - - t_imu_cam = t_imu_device @ t_device_cam - - colmap_t_imu_cam = rigid3d_from_transform(t_imu_cam) - - return colmap_t_imu_cam - - -def get_qvec_and_tvec_from_transform( - transform, -) -> tuple[np.ndarray, np.ndarray]: - """Converts projectaria_tools Rigid3d to qvec and tvec. - Returns qvec in format x,y,z,w and tvec in format x,y,z""" - # to_quat() returns in wxyz format - # https://github.com/facebookresearch/projectaria_tools/blob/867105e65cadbe777db355a407d90533c71d2d06/core/python/sophus/SO3PyBind.h#L161 - qvec = transform.rotation().to_quat()[0] - tvec = transform.translation()[0] - - qvec = np.roll( - qvec, -1 - ) # change from w,x,y,z to x,y,z,w for pycolmap format - - return np.array(qvec), np.array(tvec) - - -def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: - """Converts projectaria_tools Rigid3d to pycolmap Rigid3d""" - q, t = get_qvec_and_tvec_from_transform(transform) - return pycolmap.Rigid3d(pycolmap.Rotation3d(q), t) - - -def get_magnitude_from_transform( - transform: pycolmap.Rigid3d, -) -> tuple[float, float]: - """Returns rotation (in degrees) and - translation (in meters) magnitudes - from a Rigid3d transform - """ - translation = transform.translation - quat_xyzw = transform.rotation.quat - rotation = Rotation.from_quat(quat_xyzw) - dr = np.rad2deg(rotation.magnitude()) - dt = np.linalg.norm(translation) - - return dr, dt - - -def get_t_cam_a_cam_b_from_json( - calibration_file: Path, - camera_a_label: str, - camera_b_label: str, -) -> pycolmap.Rigid3d: - """Get T_cam_a_cam_b from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) - for given camera labels.""" - - calib = json.load(calibration_file.open("r")) - - # body is right imu of Aria, therefore T_b_s is T_imu_camera - t_body_cam_a = calib[camera_a_label]["T_b_s"] - t_body_cam_b = calib[camera_b_label]["T_b_s"] - - t_imu_cam_a = pycolmap.Rigid3d( - pycolmap.Rotation3d(t_body_cam_a["qvec"]), - t_body_cam_a["tvec"], - ) - t_imu_cam_b = pycolmap.Rigid3d( - pycolmap.Rotation3d(t_body_cam_b["qvec"]), - t_body_cam_b["tvec"], - ) - - t_camera_a_camera_b = t_imu_cam_a.inverse() * t_imu_cam_b - - return t_camera_a_camera_b - - -def get_t_imu_camera_from_json( - calibration_file: Path, - camera_label: str, -) -> pycolmap.Rigid3d: - """Get T_imu_camera from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) - for a given camera label.""" - - calib = json.load(calibration_file.open("r")) - - # body is right imu of Aria, therefore T_b_s is T_imu_camera - t_body_cam = calib[camera_label]["T_b_s"] - t_imu_camera = pycolmap.Rigid3d( - pycolmap.Rotation3d(t_body_cam["qvec"]), - t_body_cam["tvec"], - ) - - return t_imu_camera From 421c81f77ec57b143fcf876bb7a7199e10427894 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:18:13 +0200 Subject: [PATCH 402/665] mv --- tools/undistort_asl_folder.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index 143f9b8..342fae7 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -9,7 +9,7 @@ import pycolmap from tqdm import tqdm -from lamaria.utils.camera import ( +from lamaria.utils.aria import ( add_cameras_to_reconstruction, ) from lamaria.utils.constants import ( From 43deb62fc44a2757d5e60f491a282c1eaf785b9c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:18:25 +0200 Subject: [PATCH 403/665] aria utils --- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 47c09bd..5e3e268 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -11,9 +11,6 @@ from ... import logger from ...config.options import EstimateToLamariaOptions from ...structs.lamaria_reconstruction import LamariaReconstruction -from ...utils.camera import ( - camera_colmap_from_calib, -) from ...structs.estimate import ( Estimate, ) @@ -24,11 +21,12 @@ from ...utils.imu import ( get_imu_data_from_vrs, ) -from ...utils.transformation import ( +from ...utils.aria import ( get_closed_loop_data_from_mps, get_mps_poses_for_timestamps, get_t_imu_camera, rigid3d_from_transform, + camera_colmap_from_calib ) From 397f63d6eda6a33c9e582e38aef7b679b0cb78e3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:18:33 +0200 Subject: [PATCH 404/665] aria utils --- lamaria/pipeline/keyframing/keyframe_selection.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 234ce6d..36a2060 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -9,7 +9,7 @@ from ...config.options import KeyframeSelectorOptions from ...structs.lamaria_reconstruction import LamariaReconstruction -from ...utils.transformation import get_magnitude_from_transform +from ...utils.aria import get_magnitude_from_transform class KeyframeSelector: From 2fd6bb601f5bc15953b773cc3e208fae244334a0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:18:44 +0200 Subject: [PATCH 405/665] aria utils --- lamaria/eval/create_empty_recon_from_estimate.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index 9b74605..b280af6 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -8,9 +8,6 @@ from ..structs.estimate import ( Estimate, ) -from ..utils.camera import ( - add_cameras_to_reconstruction, -) from ..utils.constants import ( LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL, @@ -19,8 +16,9 @@ delete_files_in_folder, find_closest_timestamp, ) -from ..utils.transformation import ( +from ..utils.aria import ( get_t_imu_camera_from_json, + add_cameras_to_reconstruction, ) From ece12f2283e00ecee7c6b31e20cc69f5d3ab7dd0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:25:22 +0200 Subject: [PATCH 406/665] imu rm --- lamaria/utils/imu.py | 96 -------------------------------------------- 1 file changed, 96 deletions(-) delete mode 100644 lamaria/utils/imu.py diff --git a/lamaria/utils/imu.py b/lamaria/utils/imu.py deleted file mode 100644 index 9914a37..0000000 --- a/lamaria/utils/imu.py +++ /dev/null @@ -1,96 +0,0 @@ -from pathlib import Path - -import pycolmap -from projectaria_tools.core import data_provider, mps -from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions -from tqdm import tqdm - -from .constants import ( - RIGHT_IMU_STREAM_ID, -) -from .general import ( - find_closest_timestamp, -) - - -def get_online_params_for_imu_from_mps( - online_calibs_file: Path, stream_label: str, num_error: float = 1e6 -): - online_calibs = mps.read_online_calibration(online_calibs_file.as_posix()) - online_imu_calibs = {} - num_error = int(num_error) - for calib in tqdm( - online_calibs, desc="Reading online IMU calibration data" - ): - for imuCalib in calib.imu_calibs: - if imuCalib.get_label() == stream_label: - # calib timestamp in microseconds - # convert to nanoseconds and then quantize to milliseconds - timestamp = int(calib.tracking_timestamp.total_seconds() * 1e9) - quantized_timestamp = timestamp // num_error - online_imu_calibs[quantized_timestamp] = imuCalib - - return online_imu_calibs - - -def get_imu_data_from_vrs( - vrs_provider: data_provider.VrsDataProvider, - mps_folder: Path | None = None, -) -> pycolmap.ImuMeasurements: - """Get rectified IMU data from VRS file. - If mps_folder is provided, use online calibration data - from MPS folder. Otherwise, use device calibration from VRS file.""" - imu_timestamps = sorted( - vrs_provider.get_timestamps_ns( - RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME - ) - ) - imu_stream_label = vrs_provider.get_label_from_stream_id( - RIGHT_IMU_STREAM_ID - ) - - if mps_folder is not None: - online_calibs_file = mps_folder / "slam" / "online_calibration.jsonl" - online_imu_calibs = get_online_params_for_imu_from_mps( - online_calibs_file, imu_stream_label - ) - acceptable_diff_ms = 1 # 1 milliseconds - calib_timestamps = sorted(online_imu_calibs.keys()) - else: - device_calib = vrs_provider.get_device_calibration() - calibration = device_calib.get_imu_calib(imu_stream_label) - - ms = pycolmap.ImuMeasurements() - for timestamp in tqdm(imu_timestamps, desc="Loading rect IMU data"): - if mps_folder is not None: - quantized_timestamp = timestamp // int(1e6) - closest_ts = find_closest_timestamp( - calib_timestamps, quantized_timestamp, acceptable_diff_ms - ) - - if closest_ts not in online_imu_calibs: - raise ValueError( - f"No calibration found for timestamp {timestamp}" - ) - - calibration = online_imu_calibs[closest_ts] - - imu_data = vrs_provider.get_imu_data_by_time_ns( - RIGHT_IMU_STREAM_ID, - timestamp, - TimeDomain.DEVICE_TIME, - TimeQueryOptions.CLOSEST, - ) - if imu_data.accel_valid and imu_data.gyro_valid: - rectified_acc = calibration.raw_to_rectified_accel( - imu_data.accel_msec2 - ) - rectified_gyro = calibration.raw_to_rectified_gyro( - imu_data.gyro_radsec - ) - ts = float(timestamp) / 1e9 # convert to seconds - ms.insert( - pycolmap.ImuMeasurement(ts, rectified_acc, rectified_gyro) - ) - - return ms From cef1e3f75e493bd399fc8fee9a6a8896f8ef5f09 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:25:33 +0200 Subject: [PATCH 407/665] imu refactor --- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 5e3e268..609c08e 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -18,15 +18,13 @@ extract_images_from_vrs, get_matched_timestamps, ) -from ...utils.imu import ( - get_imu_data_from_vrs, -) from ...utils.aria import ( get_closed_loop_data_from_mps, get_mps_poses_for_timestamps, get_t_imu_camera, rigid3d_from_transform, - camera_colmap_from_calib + camera_colmap_from_calib, + get_imu_data_from_vrs ) From 20827feacaf24b9d551b826669b82dc31eb1b5f3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:27:54 +0200 Subject: [PATCH 408/665] aria script to hold proj aria to colmap util fns --- .../eval/create_empty_recon_from_estimate.py | 1 - lamaria/utils/aria.py | 394 ++++++++++++++++++ 2 files changed, 394 insertions(+), 1 deletion(-) create mode 100644 lamaria/utils/aria.py diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index b280af6..897d792 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -1,7 +1,6 @@ import json from pathlib import Path -import numpy as np import pycolmap from tqdm import tqdm diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py new file mode 100644 index 0000000..ea2dbde --- /dev/null +++ b/lamaria/utils/aria.py @@ -0,0 +1,394 @@ +import json +from pathlib import Path +from tqdm import tqdm + +import numpy as np +import pycolmap +from projectaria_tools.core import mps, data_provider +from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration +from projectaria_tools.core.mps.utils import get_nearest_pose +from scipy.spatial.transform import Rotation + +from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID +from .general import find_closest_timestamp + + +# ----- Camera functions ----- # + +def add_cameras_to_reconstruction( + reconstruction: pycolmap.Reconstruction, + calibration_file: Path, +) -> None: + """Add Aria cameras to COLMAP reconstruction from calibration + json file found on website: https://lamaria.ethz.ch/slam_datasets + + Args: + reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction + to which cameras will be added + + calibration_file (Path): + Path to the Aria calibration json file + """ + + for i, (key, _) in enumerate(ARIA_CAMERAS): + cam = camera_colmap_from_json( + calibration_file=calibration_file, + camera_label=key, + ) + cam.camera_id = i + 1 + reconstruction.add_camera(cam) + + rig = pycolmap.Rig(rig_id=1) + ref_sensor = pycolmap.sensor_t( + id=1, # left camera is the rig + type=pycolmap.SensorType.CAMERA, + ) + rig.add_ref_sensor(ref_sensor) + + sensor1 = pycolmap.sensor_t(id=2, type=pycolmap.SensorType.CAMERA) + sensor_from_rig = get_t_cam_a_cam_b_from_json( + calibration_file=calibration_file, + camera_a_label="cam1", # right + camera_b_label="cam0", # left + ) + rig.add_sensor(sensor1, sensor_from_rig) + + reconstruction.add_rig(rig) + + +def get_camera_params_for_colmap( + camera_calibration: CameraCalibration, + camera_model: str, +) -> list[float]: + """ + Convert Aria CameraCalibration to COLMAP camera parameters. + Supported models: OPENCV_FISHEYE, FULL_OPENCV, RAD_TAN_THIN_PRISM_FISHEYE + Args: + camera_calibration (CameraCalibration): + The projectaria_tools CameraCalibration object + camera_model (str): The COLMAP camera model to use + Returns: + list[float]: The camera parameters in COLMAP format + """ + # params = [f_u {f_v} c_u c_v [k_0: k_{numK-1}] + # {p_0 p_1} {s_0 s_1 s_2 s_3}] + # projection_params is a 15 length vector, + # starting with focal length, pp, extra coeffs + camera_params = camera_calibration.get_projection_params() + f_x, f_y, c_x, c_y = ( + camera_params[0], + camera_params[0], + camera_params[1], + camera_params[2], + ) + + p2, p1 = camera_params[-5], camera_params[-6] + + k1, k2, k3, k4, k5, k6 = camera_params[3:9] + + # FULL_OPENCV model format: + # fx, fy, cx, cy, k1, k2, p1, p2, k3, k4, k5, k6 + + # OPENCV_FISHEYE model format: + # fx, fy, cx, cy, k1, k2, k3, k4 + + if camera_model == "OPENCV_FISHEYE": + params = [f_x, f_y, c_x, c_y, k1, k2, k3, k4] + elif camera_model == "FULL_OPENCV": + params = [f_x, f_y, c_x, c_y, k1, k2, p1, p2, k3, k4, k5, k6] + elif camera_model == "RAD_TAN_THIN_PRISM_FISHEYE": + aria_fisheye_params = camera_params + focal_length = aria_fisheye_params[0] + aria_fisheye_params = np.insert(aria_fisheye_params, 0, focal_length) + params = aria_fisheye_params + + return params + + +def camera_colmap_from_calib(calib: CameraCalibration) -> pycolmap.Camera: + """Loads pycolmap camera from Aria CameraCalibration object""" + if calib.get_model_name().name != "FISHEYE624": + raise ValueError( + f"Unsupported Aria model {calib.get_model_name().name}" + ) + model = "RAD_TAN_THIN_PRISM_FISHEYE" + params = get_camera_params_for_colmap(calib, model) + width, height = calib.get_image_size() + return pycolmap.Camera( + model=model, + width=width, + height=height, + params=params, + ) + + +def camera_colmap_from_json( + calibration_file: Path, # open sourced aria calibration files + camera_label: str, +) -> pycolmap.Camera: + """Loads pycolmap camera from Aria calibration json file found on website: + https://lamaria.ethz.ch/slam_datasets""" + + calib = json.load(calibration_file.open("r")) + camera_data = calib[camera_label] + if camera_data["model"] != "RAD_TAN_THIN_PRISM_FISHEYE": + raise ValueError(f"Unsupported Aria model {camera_data['model']}") + + model = "RAD_TAN_THIN_PRISM_FISHEYE" + params = camera_data["params"] + width = camera_data["resolution"]["width"] + height = camera_data["resolution"]["height"] + return pycolmap.Camera( + model=model, + width=width, + height=height, + params=params, + ) + +# ----- Transformation functions ----- # + +def get_closed_loop_data_from_mps( + mps_path: Path, +) -> list[mps.ClosedLoopTrajectoryPose]: + """Get closed loop trajectory data from MPS folder.""" + closed_loop_traj_file = mps_path / "slam" / "closed_loop_trajectory.csv" + data = mps.read_closed_loop_trajectory(closed_loop_traj_file.as_posix()) + return data + + +def get_mps_poses_for_timestamps( + trajectory_data: list[mps.ClosedLoopTrajectoryPose], + timestamps: list[int], +) -> list: + """Get T_world_device for a list of device timestamps + in nanoseconds using MPS trajectory data. + Returns None for timestamps where + no trajectory data is found. + """ + poses = [] + if trajectory_data: + for ts in timestamps: + pose_information = get_nearest_pose(trajectory_data, ts) + if pose_information: + t_world_device = pose_information.transform_world_device + poses.append(t_world_device) + else: + poses.append(None) + + return poses + + +def get_t_rig_world_for_device_time_ns( + trajectory_data: list[mps.ClosedLoopTrajectoryPose], + device_time_ns: int, + imu_calibration: ImuCalibration, +): + """Get T_rig_world (rig is right IMU sensor) for a given device time + in nanoseconds using MPS trajectory data and IMU calibration. + Returns None if no trajectory data is found for the given timestamp. + """ + if trajectory_data: + pose_information = get_nearest_pose(trajectory_data, device_time_ns) + if pose_information: + t_world_device = pose_information.transform_world_device + t_device_imu = imu_calibration.get_transform_device_imu() + assert t_device_imu is not None, ( + f"No t_device_imu found for device time {device_time_ns}, \ + check imu calibration" + ) + + t_world_imu = t_world_device @ t_device_imu + t_imu_world = t_world_imu.inverse() + + return t_imu_world + else: + return None + else: + raise ValueError("No trajectory data found") + + +def get_t_imu_camera( + imu_calib: ImuCalibration, + camera_calib: CameraCalibration, +) -> pycolmap.Rigid3d: + """Get T_imu_camera from Aria calibrations. + Returns pycolmap.Rigid3d transform. + """ + + t_device_cam = camera_calib.get_transform_device_camera() + t_device_imu = imu_calib.get_transform_device_imu() + t_imu_device = t_device_imu.inverse() + + t_imu_cam = t_imu_device @ t_device_cam + + colmap_t_imu_cam = rigid3d_from_transform(t_imu_cam) + + return colmap_t_imu_cam + + +def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: + """Converts projectaria_tools Rigid3d to pycolmap Rigid3d + + Note: to_quat() returns in wxyz format, but pycolmap.Rotation3d + expects xyzw format.""" + + # https://github.com/facebookresearch/projectaria_tools/blob/867105e65cadbe777db355a407d90533c71d2d06/core/python/sophus/SO3PyBind.h#L161 + + qvec = transform.rotation().to_quat()[0] + tvec = transform.translation()[0] + qvec = np.roll( + qvec, -1 + ) # change from w,x,y,z to x,y,z,w for pycolmap format + q = np.array(qvec) + t = np.array(tvec) + + return pycolmap.Rigid3d(pycolmap.Rotation3d(q), t) + + +def get_magnitude_from_transform( + transform: pycolmap.Rigid3d, +) -> tuple[float, float]: + """Returns rotation (in degrees) and + translation (in meters) magnitudes + from a Rigid3d transform + """ + translation = transform.translation + quat_xyzw = transform.rotation.quat + rotation = Rotation.from_quat(quat_xyzw) + dr = np.rad2deg(rotation.magnitude()) + dt = np.linalg.norm(translation) + + return dr, dt + + +def get_t_cam_a_cam_b_from_json( + calibration_file: Path, + camera_a_label: str, + camera_b_label: str, +) -> pycolmap.Rigid3d: + """Get T_cam_a_cam_b from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) + for given camera labels.""" + + calib = json.load(calibration_file.open("r")) + + # body is right imu of Aria, therefore T_b_s is T_imu_camera + t_body_cam_a = calib[camera_a_label]["T_b_s"] + t_body_cam_b = calib[camera_b_label]["T_b_s"] + + t_imu_cam_a = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam_a["qvec"]), + t_body_cam_a["tvec"], + ) + t_imu_cam_b = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam_b["qvec"]), + t_body_cam_b["tvec"], + ) + + t_camera_a_camera_b = t_imu_cam_a.inverse() * t_imu_cam_b + + return t_camera_a_camera_b + + +def get_t_imu_camera_from_json( + calibration_file: Path, + camera_label: str, +) -> pycolmap.Rigid3d: + """Get T_imu_camera from calibration json file (found on website: https://lamaria.ethz.ch/slam_datasets) + for a given camera label.""" + + calib = json.load(calibration_file.open("r")) + + # body is right imu of Aria, therefore T_b_s is T_imu_camera + t_body_cam = calib[camera_label]["T_b_s"] + t_imu_camera = pycolmap.Rigid3d( + pycolmap.Rotation3d(t_body_cam["qvec"]), + t_body_cam["tvec"], + ) + + return t_imu_camera + + +# ----- IMU functions ----- # + +def get_online_params_for_imu_from_mps( + online_calibs_file: Path, stream_label: str, num_error: float = 1e6 +): + online_calibs = mps.read_online_calibration(online_calibs_file.as_posix()) + online_imu_calibs = {} + num_error = int(num_error) + for calib in tqdm( + online_calibs, desc="Reading online IMU calibration data" + ): + for imuCalib in calib.imu_calibs: + if imuCalib.get_label() == stream_label: + # calib timestamp in microseconds + # convert to nanoseconds and then quantize to milliseconds + timestamp = int(calib.tracking_timestamp.total_seconds() * 1e9) + quantized_timestamp = timestamp // num_error + online_imu_calibs[quantized_timestamp] = imuCalib + + return online_imu_calibs + + +def get_imu_data_from_vrs( + vrs_provider: data_provider.VrsDataProvider, + mps_folder: Path | None = None, +) -> pycolmap.ImuMeasurements: + """Get rectified IMU data from VRS file. + If mps_folder is provided, use online calibration data + from MPS folder. Otherwise, use device calibration from VRS file.""" + imu_timestamps = sorted( + vrs_provider.get_timestamps_ns( + RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME + ) + ) + imu_stream_label = vrs_provider.get_label_from_stream_id( + RIGHT_IMU_STREAM_ID + ) + + if mps_folder is not None: + online_calibs_file = mps_folder / "slam" / "online_calibration.jsonl" + online_imu_calibs = get_online_params_for_imu_from_mps( + online_calibs_file, imu_stream_label + ) + acceptable_diff_ms = 1 # 1 milliseconds + calib_timestamps = sorted(online_imu_calibs.keys()) + else: + device_calib = vrs_provider.get_device_calibration() + calibration = device_calib.get_imu_calib(imu_stream_label) + + ms = pycolmap.ImuMeasurements() + for timestamp in tqdm(imu_timestamps, desc="Loading rect IMU data"): + if mps_folder is not None: + quantized_timestamp = timestamp // int(1e6) + closest_ts = find_closest_timestamp( + calib_timestamps, quantized_timestamp, acceptable_diff_ms + ) + + if closest_ts not in online_imu_calibs: + raise ValueError( + f"No calibration found for timestamp {timestamp}" + ) + + calibration = online_imu_calibs[closest_ts] + + imu_data = vrs_provider.get_imu_data_by_time_ns( + RIGHT_IMU_STREAM_ID, + timestamp, + TimeDomain.DEVICE_TIME, + TimeQueryOptions.CLOSEST, + ) + if imu_data.accel_valid and imu_data.gyro_valid: + rectified_acc = calibration.raw_to_rectified_accel( + imu_data.accel_msec2 + ) + rectified_gyro = calibration.raw_to_rectified_gyro( + imu_data.gyro_radsec + ) + ts = float(timestamp) / 1e9 # convert to seconds + ms.insert( + pycolmap.ImuMeasurement(ts, rectified_acc, rectified_gyro) + ) + + return ms From 3e089740eec9b91b26d74cfc4902273a138934d8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 00:28:40 +0200 Subject: [PATCH 409/665] ruff --- lamaria/eval/create_empty_recon_from_estimate.py | 8 ++++---- .../keyframing/to_lamaria_reconstruction.py | 14 +++++++------- lamaria/structs/estimate.py | 2 +- lamaria/utils/aria.py | 13 ++++++++----- 4 files changed, 20 insertions(+), 17 deletions(-) diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py index 897d792..a863368 100644 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ b/lamaria/eval/create_empty_recon_from_estimate.py @@ -7,6 +7,10 @@ from ..structs.estimate import ( Estimate, ) +from ..utils.aria import ( + add_cameras_to_reconstruction, + get_t_imu_camera_from_json, +) from ..utils.constants import ( LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL, @@ -15,10 +19,6 @@ delete_files_in_folder, find_closest_timestamp, ) -from ..utils.aria import ( - get_t_imu_camera_from_json, - add_cameras_to_reconstruction, -) def _add_images_to_reconstruction( diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 609c08e..5b1bdf9 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -10,21 +10,21 @@ from ... import logger from ...config.options import EstimateToLamariaOptions -from ...structs.lamaria_reconstruction import LamariaReconstruction from ...structs.estimate import ( Estimate, ) -from ...utils.general import ( - extract_images_from_vrs, - get_matched_timestamps, -) +from ...structs.lamaria_reconstruction import LamariaReconstruction from ...utils.aria import ( + camera_colmap_from_calib, get_closed_loop_data_from_mps, + get_imu_data_from_vrs, get_mps_poses_for_timestamps, get_t_imu_camera, rigid3d_from_transform, - camera_colmap_from_calib, - get_imu_data_from_vrs +) +from ...utils.general import ( + extract_images_from_vrs, + get_matched_timestamps, ) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 1131276..a1cac2c 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -54,7 +54,7 @@ def as_tuples(self) -> list[tuple[int, pycolmap.Rigid3d]]: """Return a list of (timestamp, pose) tuples.""" self._ensure_loaded() return list(zip(self._timestamps, self._poses, strict=True)) - + def as_dict(self) -> dict[int, pycolmap.Rigid3d]: """Return a dict mapping timestamp to pose.""" self._ensure_loaded() diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index ea2dbde..69f50a7 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -1,21 +1,21 @@ import json from pathlib import Path -from tqdm import tqdm import numpy as np import pycolmap -from projectaria_tools.core import mps, data_provider -from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from projectaria_tools.core import data_provider, mps from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration from projectaria_tools.core.mps.utils import get_nearest_pose +from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions from scipy.spatial.transform import Rotation +from tqdm import tqdm from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID from .general import find_closest_timestamp - # ----- Camera functions ----- # + def add_cameras_to_reconstruction( reconstruction: pycolmap.Reconstruction, calibration_file: Path, @@ -146,8 +146,10 @@ def camera_colmap_from_json( params=params, ) + # ----- Transformation functions ----- # + def get_closed_loop_data_from_mps( mps_path: Path, ) -> list[mps.ClosedLoopTrajectoryPose]: @@ -229,7 +231,7 @@ def get_t_imu_camera( def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: """Converts projectaria_tools Rigid3d to pycolmap Rigid3d - + Note: to_quat() returns in wxyz format, but pycolmap.Rotation3d expects xyzw format.""" @@ -311,6 +313,7 @@ def get_t_imu_camera_from_json( # ----- IMU functions ----- # + def get_online_params_for_imu_from_mps( online_calibs_file: Path, stream_label: str, num_error: float = 1e6 ): From d8c055c4cc03750b0050e336031f5b3037830190 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 01:14:06 +0200 Subject: [PATCH 410/665] docs --- lamaria/utils/control_point.py | 26 +++++++++++++++++++++++--- 1 file changed, 23 insertions(+), 3 deletions(-) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 980b06c..793a475 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -15,10 +15,16 @@ def construct_control_points_from_json( cp_json_file: Path, -) -> dict: - """Construct control points dict from JSON file +) -> dict[int, dict[str, object]]: + """ + Construct control points dict from a JSON file. + Args: - cp_json_file (Path): Path to the sparse GT JSON file + cp_json_file (Path): Path to the sparse GT JSON file. + + Returns: + Mapping + ``{ tag_id: {"control_point": str, "topo": ndarray(3,), "covariance": ndarray(3,3)} }``. """ with open(cp_json_file) as file: cp_data = json.load(file) @@ -106,6 +112,19 @@ def run_control_point_triangulation_from_json( cp_json_file: Path, control_points: dict, # edits control_points in place ) -> None: + """ + Triangulate control points from JSON file and add to control_points dict. + Updates `control_points` in place to add: + + - ``triangulated``: np.ndarray(3,) or None if triangulation fails + - ``inlier_ratio``: float + - ``image_id_and_point2d``: list of (image_id, [x, y]) tuples + of observations used for triangulation + Args: + reconstruction_path (Path): Path to the reconstruction folder + cp_json_file (Path): Path to the sparse GT JSON file + control_points (dict): Control points dictionary to be updated + """ rec = pycolmap.Reconstruction(reconstruction_path) image_names_to_ids = get_image_names_to_ids( @@ -179,6 +198,7 @@ def run_control_point_triangulation_from_json( def get_cps_for_initial_alignment(control_points: dict): + """Get control points with z != 0 for initial alignment""" triangulated_cp_alignment = [] topo_cp_alignment = [] for tag_id, cp in control_points.items(): From 4eb58f5f9921dea99f73ed25a10a2bef518147cf Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 01:15:10 +0200 Subject: [PATCH 411/665] sparse eval script updated --- lamaria/eval/sparse_evaluation.py | 42 ++++++++++++++++++++++++++++--- 1 file changed, 38 insertions(+), 4 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 7f9ad54..6928984 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -16,7 +16,9 @@ ) -def update_sim3d_scale(variables: dict): +def update_sim3d_scale(variables: dict) -> None: + """Update the scale of the sim3d in the variables dictionary + from the log_scale variable. Occurs in place.""" if "log_scale" not in variables: raise ValueError("log_scale not found in variables") @@ -27,6 +29,16 @@ def update_sim3d_scale(variables: dict): def create_variables_for_sparse_evaluation( control_points: dict, sim3d: pycolmap.Sim3d, cp_reproj_std: float = 1.0 ) -> dict: + """Create variables dictionary for sparse evaluation. + + Variables consists of - + - ```control_points```: Control points dictionary + - ```sim3d```: pycolmap.sim3d transformation + - ```cp_reproj_std```: Control point reprojection + - ```log scale``` (np.ndarray): Logarithm of the scale factor + (from sim3d.scale) + """ + variables = {} variables["control_points"] = copy.deepcopy(control_points) variables["sim3d"] = copy.deepcopy(sim3d) @@ -40,7 +52,18 @@ def create_variables_for_sparse_evaluation( def get_problem_for_sparse_alignment( reconstruction: pycolmap.Reconstruction, variables: dict, -): +) -> tuple: + """Create a Ceres problem for sparse alignment. + Args: + reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. + variables (dict): The variables dictionary from + create_variables_for_sparse_evaluation. + + Returns: + problem (pyceres.Problem): The Ceres problem. + solver_options (pyceres.SolverOptions): The solver options. + summary (pyceres.SolverSummary): The solver summary. + """ problem = pyceres.Problem() problem = add_alignment_residuals( problem, @@ -59,6 +82,17 @@ def add_alignment_residuals( reconstruction: pycolmap.Reconstruction, variables: dict, ) -> pyceres.Problem: + """Add alignment residuals to the Ceres problem. + + Variables consists of - + - ReprojErrorCost for each observation of each control point + - Point3DAlignmentCost for each control point + Args: + problem (pyceres.Problem): The Ceres problem. + reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. + variables (dict): The variables dictionary from + create_variables_for_sparse_evaluation. + """ if ( variables["control_points"] is not None and variables["sim3d"] is not None @@ -117,7 +151,7 @@ def add_alignment_residuals( return problem -def run_baseline_evaluation( +def run( reconstruction_path: Path, cp_json_file: Path, output_path: Path, @@ -255,7 +289,7 @@ def run_baseline_evaluation( ) args = parser.parse_args() - _ = run_baseline_evaluation( + _ = run( Path(args.reconstruction_path), Path(args.cp_json_file), Path(args.output_path), From 387757c303f9753ac5b2f434e7e53edff53f1db1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 01:19:00 +0200 Subject: [PATCH 412/665] sparse eval --- lamaria/eval/sparse_evaluation.py | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 6928984..f9b36bf 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -157,6 +157,20 @@ def run( output_path: Path, cp_reproj_std=1.0, ): + """Run sparse evaluation for sequences that observe control points. + + Args: + reconstruction_path (Path): Path to the COLMAP reconstruction that + contains the poses to be evaluated. + cp_json_file (Path): Path to the sparse GT JSON file containing control + point data. + output_path (Path): Path to the output folder where the evaluation results + will be saved. + cp_reproj_std (float): Control point reprojection standard deviation. + + Returns: + bool: True if the evaluation was successful, False otherwise. + """ output_path.mkdir(parents=True, exist_ok=True) aligned_transformed_folder = output_path / "aligned_transformed" From f971170e8c3e792e73f2b8ae60d9ebad0b25ffdb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 01:22:01 +0200 Subject: [PATCH 413/665] fix --- lamaria/eval/sparse_evaluation.py | 16 ++++++++-------- lamaria/utils/control_point.py | 7 ++++--- 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index f9b36bf..9958534 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -30,15 +30,15 @@ def create_variables_for_sparse_evaluation( control_points: dict, sim3d: pycolmap.Sim3d, cp_reproj_std: float = 1.0 ) -> dict: """Create variables dictionary for sparse evaluation. - + Variables consists of - - ```control_points```: Control points dictionary - ```sim3d```: pycolmap.sim3d transformation - - ```cp_reproj_std```: Control point reprojection - - ```log scale``` (np.ndarray): Logarithm of the scale factor + - ```cp_reproj_std```: Control point reprojection + - ```log scale``` (np.ndarray): Logarithm of the scale factor (from sim3d.scale) """ - + variables = {} variables["control_points"] = copy.deepcopy(control_points) variables["sim3d"] = copy.deepcopy(sim3d) @@ -56,9 +56,9 @@ def get_problem_for_sparse_alignment( """Create a Ceres problem for sparse alignment. Args: reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. - variables (dict): The variables dictionary from + variables (dict): The variables dictionary from create_variables_for_sparse_evaluation. - + Returns: problem (pyceres.Problem): The Ceres problem. solver_options (pyceres.SolverOptions): The solver options. @@ -83,14 +83,14 @@ def add_alignment_residuals( variables: dict, ) -> pyceres.Problem: """Add alignment residuals to the Ceres problem. - + Variables consists of - - ReprojErrorCost for each observation of each control point - Point3DAlignmentCost for each control point Args: problem (pyceres.Problem): The Ceres problem. reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. - variables (dict): The variables dictionary from + variables (dict): The variables dictionary from create_variables_for_sparse_evaluation. """ if ( diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 793a475..362bde6 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -23,8 +23,9 @@ def construct_control_points_from_json( cp_json_file (Path): Path to the sparse GT JSON file. Returns: - Mapping - ``{ tag_id: {"control_point": str, "topo": ndarray(3,), "covariance": ndarray(3,3)} }``. + control_points (dict): Control points dictionary of the form + ``{ tag_id: {"control_point": str, "topo": ndarray(3,), + "covariance": ndarray(3,3)} }``. """ with open(cp_json_file) as file: cp_data = json.load(file) @@ -115,7 +116,7 @@ def run_control_point_triangulation_from_json( """ Triangulate control points from JSON file and add to control_points dict. Updates `control_points` in place to add: - + - ``triangulated``: np.ndarray(3,) or None if triangulation fails - ``inlier_ratio``: float - ``image_id_and_point2d``: list of (image_id, [x, y]) tuples From 0b34023c471a6084632591b361e0bf7de1526a92 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 10:47:53 +0200 Subject: [PATCH 414/665] create empty recon via estimate class --- lamaria/structs/estimate.py | 174 +++++++++++++++++++++++++++++++++++- 1 file changed, 173 insertions(+), 1 deletion(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index a1cac2c..89265f5 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -1,9 +1,25 @@ from decimal import ROUND_HALF_UP, Decimal from pathlib import Path +from dataclasses import dataclass import numpy as np +import json +from tqdm import tqdm import pycolmap +from ..utils.aria import ( + add_cameras_to_reconstruction as _add_cams, + get_t_imu_camera_from_json, +) +from ..utils.constants import ( + LEFT_CAMERA_STREAM_LABEL, + RIGHT_CAMERA_STREAM_LABEL, +) +from ..utils.general import ( + delete_files_in_folder, + find_closest_timestamp, +) + def _round_ns(x: str | int | float) -> int: # works for "5120...274.999939", "5.12e11", or ints @@ -13,6 +29,15 @@ def _round_ns(x: str | int | float) -> int: return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) +@dataclass(slots=True) +class _BaselineCfg: + """Configuration for creating a baseline reconstruction.""" + cp_json_file: Path + device_calibration_json: Path + output_path: Path + uses_imu: bool = True # if False, uses monocular-cam0 poses + + class Estimate: """ Loads and stores an 'estimate' text file with rows: @@ -23,11 +48,14 @@ class Estimate: (i.e., inverse of world_from_rig) to satisfy COLMAP format. """ - def __init__(self, invert_poses: bool = True) -> None: + def __init__(self, invert_poses: bool = True, uses_imu: bool = True) -> None: self.invert_poses = invert_poses + # uses_imu controls default behavior for baseline recon creation + self.uses_imu = uses_imu self.path: Path | None = None self._timestamps: list[int] = [] self._poses: list[pycolmap.Rigid3d] = [] + self._baseline_cfg: _BaselineCfg | None = None def load_from_file(self, path: str | Path) -> "Estimate": """Parse the file, validate format, populate timestamps & poses.""" @@ -39,6 +67,62 @@ def load_from_file(self, path: str | Path) -> "Estimate": self._parse(lines) # raises error if format is invalid return self + + def configure_baseline_cfg( + self, + cp_json_file: str | Path, + device_calibration_json: str | Path, + output_path: str | Path, + uses_imu: bool | None = None, + ) -> "Estimate": + """ + Store config used by create_baseline_reconstruction(). + + use_imu: + If True, the poses in the estimate file are IMU poses. + If False, the poses are left camera poses (monocular-cam0). + """ + if uses_imu is None: + uses_imu = self.uses_imu + + self._baseline_cfg = _BaselineCfg( + Path(cp_json_file), + Path(device_calibration_json), + Path(output_path), + uses_imu, + ) + return self + + def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: + """ + Build a COLMAP reconstruction from this Estimate and the + parameters given via configure_baseline_cfg(). Writes to: + output_path / "reconstruction" + Returns pycolmap.Reconstruction. + """ + self._ensure_loaded() + if self._baseline_cfg is None: + raise RuntimeError( + "Baseline not configured. Call configure_baseline_cfg(...) first." + ) + + cfg = self._baseline_cfg + recon_path = cfg.output_path / "reconstruction" + recon_path.mkdir(parents=True, exist_ok=True) + delete_files_in_folder(recon_path) + + reconstruction = pycolmap.Reconstruction() + # Adds cameras and rig to the reconstruction + _add_cams(reconstruction, cfg.device_calibration_json) + reconstruction = self._add_images_to_reconstruction( + reconstruction, + cfg.cp_json_file, + cfg.device_calibration_json, + cfg.uses_imu, + ) + + reconstruction.write(str(recon_path)) + return reconstruction @property def timestamps(self) -> list[int]: @@ -76,6 +160,7 @@ def _ensure_loaded(self) -> None: "Estimate not loaded. Call load_from_file() first." ) + # Parses the file lines, populating self._timestamps and self._poses def _parse(self, lines: list[str]) -> None: ts_list: list[int] = [] pose_list: list[pycolmap.Rigid3d] = [] @@ -126,3 +211,90 @@ def _parse(self, lines: list[str]) -> None: self._timestamps = ts_list self._poses = pose_list + + def _add_images_to_reconstruction( + self, + reconstruction: pycolmap.Reconstruction, + cp_json_file: Path, + device_calibration_json: Path, + ) -> pycolmap.Reconstruction: + """Add images to an existing empty + reconstruction from this pose estimate.""" + pose_data = self.as_tuples() + + with open(cp_json_file) as f: + cp_data = json.load(f) + + image_id = 1 + rig = reconstruction.rig(rig_id=1) + + if self.uses_imu: + transform = get_t_imu_camera_from_json( + device_calibration_json=device_calibration_json, + camera_label="cam0", + ) + else: + transform = pycolmap.Rigid3d() + + ts_data_processed = {} + for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: + ts_data = cp_data["timestamps"][label] + ts_data_processed[label] = {int(k): v for k, v in ts_data.items()} + ts_data_processed[label]["sorted_keys"] = sorted( + ts_data_processed[label].keys() + ) + + for i, (timestamp, pose) in tqdm( + enumerate(pose_data), + total=len(pose_data), + desc="Adding images to reconstruction", + ): + if self.invert_poses: + # poses are in imu/cam_from_world format + T_world_rig = pose.inverse() * transform + else: + # poses are in world_from_cam/imu format + T_world_rig = pose * transform + + frame = pycolmap.Frame() + frame.rig_id = rig.rig_id + frame.frame_id = i + 1 + frame.rig_from_world = T_world_rig.inverse() + + images_to_add = [] + + for label, camera_id in [ + (LEFT_CAMERA_STREAM_LABEL, 1), + (RIGHT_CAMERA_STREAM_LABEL, 2), + ]: + source_timestamps = ts_data_processed[label]["sorted_keys"] + # offsets upto 1 ms (1e6 ns) + closest_timestamp = find_closest_timestamp( + source_timestamps, timestamp, max_diff=1e6 + ) + if closest_timestamp is None: + raise ValueError + + image_name = ts_data_processed[label][closest_timestamp] + + im = pycolmap.Image( + image_name, + pycolmap.Point2DList(), + camera_id, + image_id, + ) + im.frame_id = frame.frame_id + frame.add_data_id(im.data_id) + + images_to_add.append(im) + image_id += 1 + + reconstruction.add_frame(frame) + for im in images_to_add: + reconstruction.add_image(im) + + return reconstruction + + + + From b06029eb0fd8c67024d7e8d894b4f50f2135e74a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 10:50:03 +0200 Subject: [PATCH 415/665] est upd --- lamaria/structs/estimate.py | 38 ++++++++++++++++++------------------- 1 file changed, 19 insertions(+), 19 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 89265f5..2061de2 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -1,11 +1,11 @@ +import json +from dataclasses import dataclass from decimal import ROUND_HALF_UP, Decimal from pathlib import Path -from dataclasses import dataclass import numpy as np -import json -from tqdm import tqdm import pycolmap +from tqdm import tqdm from ..utils.aria import ( add_cameras_to_reconstruction as _add_cams, @@ -32,10 +32,11 @@ def _round_ns(x: str | int | float) -> int: @dataclass(slots=True) class _BaselineCfg: """Configuration for creating a baseline reconstruction.""" + cp_json_file: Path device_calibration_json: Path output_path: Path - uses_imu: bool = True # if False, uses monocular-cam0 poses + uses_imu: bool = True # if False, uses monocular-cam0 poses class Estimate: @@ -48,7 +49,9 @@ class Estimate: (i.e., inverse of world_from_rig) to satisfy COLMAP format. """ - def __init__(self, invert_poses: bool = True, uses_imu: bool = True) -> None: + def __init__( + self, invert_poses: bool = True, uses_imu: bool = True + ) -> None: self.invert_poses = invert_poses # uses_imu controls default behavior for baseline recon creation self.uses_imu = uses_imu @@ -67,7 +70,7 @@ def load_from_file(self, path: str | Path) -> "Estimate": self._parse(lines) # raises error if format is invalid return self - + def configure_baseline_cfg( self, cp_json_file: str | Path, @@ -78,7 +81,7 @@ def configure_baseline_cfg( """ Store config used by create_baseline_reconstruction(). - use_imu: + uses_imu: If True, the poses in the estimate file are IMU poses. If False, the poses are left camera poses (monocular-cam0). """ @@ -92,7 +95,7 @@ def configure_baseline_cfg( uses_imu, ) return self - + def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: """ Build a COLMAP reconstruction from this Estimate and the @@ -103,9 +106,10 @@ def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: self._ensure_loaded() if self._baseline_cfg is None: raise RuntimeError( - "Baseline not configured. Call configure_baseline_cfg(...) first." + "Baseline not configured. " + "Call configure_baseline_cfg(...) first." ) - + cfg = self._baseline_cfg recon_path = cfg.output_path / "reconstruction" recon_path.mkdir(parents=True, exist_ok=True) @@ -243,7 +247,7 @@ def _add_images_to_reconstruction( ts_data_processed[label]["sorted_keys"] = sorted( ts_data_processed[label].keys() ) - + for i, (timestamp, pose) in tqdm( enumerate(pose_data), total=len(pose_data), @@ -255,7 +259,7 @@ def _add_images_to_reconstruction( else: # poses are in world_from_cam/imu format T_world_rig = pose * transform - + frame = pycolmap.Frame() frame.rig_id = rig.rig_id frame.frame_id = i + 1 @@ -274,7 +278,7 @@ def _add_images_to_reconstruction( ) if closest_timestamp is None: raise ValueError - + image_name = ts_data_processed[label][closest_timestamp] im = pycolmap.Image( @@ -288,13 +292,9 @@ def _add_images_to_reconstruction( images_to_add.append(im) image_id += 1 - + reconstruction.add_frame(frame) for im in images_to_add: reconstruction.add_image(im) - - return reconstruction - - - + return reconstruction From 47ae286cdec977f2375496c101a3cfb73b2c576b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 10:50:43 +0200 Subject: [PATCH 416/665] renaming --- lamaria/structs/estimate.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 2061de2..5116be5 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -71,7 +71,7 @@ def load_from_file(self, path: str | Path) -> "Estimate": self._parse(lines) # raises error if format is invalid return self - def configure_baseline_cfg( + def setup_baseline_cfg( self, cp_json_file: str | Path, device_calibration_json: str | Path, @@ -99,7 +99,7 @@ def configure_baseline_cfg( def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: """ Build a COLMAP reconstruction from this Estimate and the - parameters given via configure_baseline_cfg(). Writes to: + parameters given via setup_baseline_cfg(). Writes to: output_path / "reconstruction" Returns pycolmap.Reconstruction. """ @@ -107,7 +107,7 @@ def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: if self._baseline_cfg is None: raise RuntimeError( "Baseline not configured. " - "Call configure_baseline_cfg(...) first." + "Call setup_baseline_cfg(...) first." ) cfg = self._baseline_cfg From 2830d5d0c9d6f2c9e3facc5183ad37a4a2ede42d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 10:51:21 +0200 Subject: [PATCH 417/665] rm create empty recon from est - mv to estimate class --- .../eval/create_empty_recon_from_estimate.py | 149 ------------------ 1 file changed, 149 deletions(-) delete mode 100644 lamaria/eval/create_empty_recon_from_estimate.py diff --git a/lamaria/eval/create_empty_recon_from_estimate.py b/lamaria/eval/create_empty_recon_from_estimate.py deleted file mode 100644 index a863368..0000000 --- a/lamaria/eval/create_empty_recon_from_estimate.py +++ /dev/null @@ -1,149 +0,0 @@ -import json -from pathlib import Path - -import pycolmap -from tqdm import tqdm - -from ..structs.estimate import ( - Estimate, -) -from ..utils.aria import ( - add_cameras_to_reconstruction, - get_t_imu_camera_from_json, -) -from ..utils.constants import ( - LEFT_CAMERA_STREAM_LABEL, - RIGHT_CAMERA_STREAM_LABEL, -) -from ..utils.general import ( - delete_files_in_folder, - find_closest_timestamp, -) - - -def _add_images_to_reconstruction( - reconstruction: pycolmap.Reconstruction, - estimate_file: Path, - cp_json_file: Path, - device_calibration_json: Path, - slam_input_imu: int = 1, -): - """Add images to an existing empty - reconstruction from a pose estimate file.""" - est = Estimate(invert_poses=False) - est.load_from_file(estimate_file) - pose_data = est.as_tuples() - - with open(cp_json_file) as f: - cp_data = json.load(f) - - image_id = 1 - rig = reconstruction.rig(rig_id=1) - - # if slam_input_imu is 1, then the poses are IMU poses - # otherwise, the poses are left camera poses (monocular-cam0) (rig poses) - if slam_input_imu == 1: - transform = get_t_imu_camera_from_json( - device_calibration_json=device_calibration_json, - camera_label="cam0", - ) - else: - transform = pycolmap.Rigid3d() - - ts_data_processed = {} - for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: - ts_data = cp_data["timestamps"][label] - ts_data_processed[label] = {int(k): v for k, v in ts_data.items()} - ts_data_processed[label]["sorted_keys"] = sorted( - ts_data_processed[label].keys() - ) - - for i, (timestamp, pose) in tqdm( - enumerate(pose_data), - total=len(pose_data), - desc="Adding images to reconstruction", - ): - T_world_rig = pose * transform - frame = pycolmap.Frame() - frame.rig_id = rig.rig_id - frame.frame_id = i + 1 - frame.rig_from_world = T_world_rig.inverse() - - images_to_add = [] - - for label, camera_id in [ - (LEFT_CAMERA_STREAM_LABEL, 1), - (RIGHT_CAMERA_STREAM_LABEL, 2), - ]: - source_timestamps = ts_data_processed[label]["sorted_keys"] - closest_timestamp = find_closest_timestamp( - source_timestamps, timestamp - ) - if closest_timestamp is None: - raise ValueError - - image_name = ts_data_processed[label][closest_timestamp] - - im = pycolmap.Image( - image_name, - pycolmap.Point2DList(), - camera_id, - image_id, - ) - im.frame_id = frame.frame_id - frame.add_data_id(im.data_id) - - images_to_add.append(im) - image_id += 1 - - reconstruction.add_frame(frame) - for im in images_to_add: - reconstruction.add_image(im) - - -def create_baseline_reconstruction( - estimate_file: Path, - cp_json_file: Path, - device_calibration_json: Path, - output_path: Path, - slam_input_imu: int = 1, -): - """Create a baseline reconstruction from a pose estimate file. - The pose estimate file is assumed to be in the format: - - timestamp(ns) tx ty tz q_x q_y q_z q_w - - Args: - estimate_file (Path): Path to the pose estimate file. - - cp_json_file (Path): Path to the sparse GT json file. - - device_calibration_json (Path): - Path to the Aria device calibration json file. - - output_path (Path): Path to the output folder - where the reconstruction will be saved. - - slam_input_imu (int, optional): - If 1, the poses in the estimate file are IMU poses. - If 0, the poses are left camera poses (monocular-cam0). - """ - recon_path = output_path / "reconstruction" - recon_path.mkdir(parents=True, exist_ok=True) - delete_files_in_folder(recon_path) - - reconstruction = pycolmap.Reconstruction() - add_cameras_to_reconstruction( - reconstruction, - device_calibration_json, - ) - - _add_images_to_reconstruction( - reconstruction, - estimate_file, - cp_json_file, - device_calibration_json, - slam_input_imu, - ) - - reconstruction.write(recon_path) From daff53044811c9b8c67ef5fa455027caac45d750 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 11:21:10 +0200 Subject: [PATCH 418/665] sparse eval clean up --- lamaria/eval/sparse_evaluation.py | 76 +++++++++++++++++++++++-------- 1 file changed, 57 insertions(+), 19 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 9958534..2fe851d 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -9,6 +9,7 @@ import pycolmap.cost_functions from .. import logger +from ..structs.estimate import Estimate from ..utils.control_point import ( construct_control_points_from_json, get_cps_for_initial_alignment, @@ -152,26 +153,48 @@ def add_alignment_residuals( def run( - reconstruction_path: Path, + estimate: Path, cp_json_file: Path, + device_calibration_json: Path, output_path: Path, + uses_imu: bool, cp_reproj_std=1.0, ): """Run sparse evaluation for sequences that observe control points. Args: - reconstruction_path (Path): Path to the COLMAP reconstruction that - contains the poses to be evaluated. - cp_json_file (Path): Path to the sparse GT JSON file containing control - point data. - output_path (Path): Path to the output folder where the evaluation results - will be saved. - cp_reproj_std (float): Control point reprojection standard deviation. + estimate (Path): Path to the pose estimate file. + cp_json_file (Path): Path to the sparse ground-truth JSON file + containing control point data. + device_calibration_json (Path): Path to the device calibration JSON. + output_path (Path): Directory where intermediate data and evaluation results will be saved. + uses_imu (bool): Whether poses are in IMU frame or cam0 (left camera) frame. + cp_reproj_std (float, optional): Control point reprojection standard + deviation. Defaults to 1.0. Returns: - bool: True if the evaluation was successful, False otherwise. + bool: True if the evaluation was successful, False otherwise. + + Notes: + Expected estimate file format (space-separated columns): + ``` + timestamp tx ty tz qx qy qz qw + ``` """ - output_path.mkdir(parents=True, exist_ok=True) + est = Estimate() + est.load_from_file(estimate) + if not est.is_loaded(): + logger.error("Estimate could not be loaded") + return False + + est.setup_baseline_cfg( + cp_json_file, + device_calibration_json, + output_path, + uses_imu, + ) + _ = est.create_baseline_reconstruction() + reconstruction_path = est.reconstruction_path aligned_transformed_folder = output_path / "aligned_transformed" aligned_transformed_folder.mkdir(parents=True, exist_ok=True) @@ -278,22 +301,35 @@ def run( description="Run baseline sparse evaluation" ) parser.add_argument( - "--reconstruction_path", - type=str, + "--estimate", + type=Path, required=True, - help="Path to the reconstruction folder", + help="Path to the pose estimate file produced by a specific method", ) parser.add_argument( "--cp_json_file", - type=str, + type=Path, required=True, help="Path to the sparse GT JSON file", ) + parser.add_argument( + "--device_calibration_json", + type=Path, + required=True, + help="Path to the Aria device calibration JSON file, found on the Lamaria website", + ) parser.add_argument( "--output_path", - type=str, + type=Path, required=True, - help="Path to the output folder", + help="Path to the output folder where intermediate data " + "and evaluation results will be saved", + ) + parser.add_argument( + "--uses_imu", + action="store_true", + help="Set if the poses are in IMU frame. If not set, " + "poses are assumed to be in cam0 (left camera) frame.", ) parser.add_argument( "--cp_reproj_std", @@ -304,8 +340,10 @@ def run( args = parser.parse_args() _ = run( - Path(args.reconstruction_path), - Path(args.cp_json_file), - Path(args.output_path), + args.estimate, + args.cp_json_file, + args.device_calibration_json, + args.output_path, + args.uses_imu, args.cp_reproj_std, ) From 370c58e4fb0efcfc6778947de4e5bf82ec9d7d51 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 11:21:44 +0200 Subject: [PATCH 419/665] estimate upd --- lamaria/structs/estimate.py | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 5116be5..0f6a953 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -65,6 +65,9 @@ def load_from_file(self, path: str | Path) -> "Estimate": self.clear() self.path = Path(path) + if not self.path.exists(): + raise FileNotFoundError(f"Estimate file not found: {self.path}") + with open(self.path) as f: lines = f.readlines() @@ -77,7 +80,7 @@ def setup_baseline_cfg( device_calibration_json: str | Path, output_path: str | Path, uses_imu: bool | None = None, - ) -> "Estimate": + ) -> None: """ Store config used by create_baseline_reconstruction(). @@ -94,7 +97,6 @@ def setup_baseline_cfg( Path(output_path), uses_imu, ) - return self def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: """ @@ -137,6 +139,12 @@ def timestamps(self) -> list[int]: def poses(self) -> list[pycolmap.Rigid3d]: self._ensure_loaded() return self._poses + + @property + def reconstruction_path(self) -> Path | None: + if self._baseline_cfg is None: + return None + return self._baseline_cfg.output_path / "reconstruction" def as_tuples(self) -> list[tuple[int, pycolmap.Rigid3d]]: """Return a list of (timestamp, pose) tuples.""" From 2cc054df04bc686f82959a759bc256f71b4e0a9c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 11:31:08 +0200 Subject: [PATCH 420/665] ruff --- lamaria/eval/sparse_evaluation.py | 11 +++++++---- lamaria/structs/estimate.py | 7 ++++--- 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 2fe851d..37f2b0f 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -167,8 +167,10 @@ def run( cp_json_file (Path): Path to the sparse ground-truth JSON file containing control point data. device_calibration_json (Path): Path to the device calibration JSON. - output_path (Path): Directory where intermediate data and evaluation results will be saved. - uses_imu (bool): Whether poses are in IMU frame or cam0 (left camera) frame. + output_path (Path): Directory where intermediate data and + evaluation results will be saved. + uses_imu (bool): Whether poses are in IMU frame + or cam0 (left camera) frame. cp_reproj_std (float, optional): Control point reprojection standard deviation. Defaults to 1.0. @@ -186,7 +188,7 @@ def run( if not est.is_loaded(): logger.error("Estimate could not be loaded") return False - + est.setup_baseline_cfg( cp_json_file, device_calibration_json, @@ -316,7 +318,8 @@ def run( "--device_calibration_json", type=Path, required=True, - help="Path to the Aria device calibration JSON file, found on the Lamaria website", + help="Path to the Aria device calibration JSON file, " + "found on the Lamaria website", ) parser.add_argument( "--output_path", diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 0f6a953..d0b5680 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -9,6 +9,8 @@ from ..utils.aria import ( add_cameras_to_reconstruction as _add_cams, +) +from ..utils.aria import ( get_t_imu_camera_from_json, ) from ..utils.constants import ( @@ -108,8 +110,7 @@ def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: self._ensure_loaded() if self._baseline_cfg is None: raise RuntimeError( - "Baseline not configured. " - "Call setup_baseline_cfg(...) first." + "Baseline not configured. Call setup_baseline_cfg(...) first." ) cfg = self._baseline_cfg @@ -139,7 +140,7 @@ def timestamps(self) -> list[int]: def poses(self) -> list[pycolmap.Rigid3d]: self._ensure_loaded() return self._poses - + @property def reconstruction_path(self) -> Path | None: if self._baseline_cfg is None: From ba372dbf64791d4bedb95671a25e8f7199a0730e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 12:43:07 +0200 Subject: [PATCH 421/665] cleaner interface --- lamaria/eval/sparse_evaluation.py | 2 +- lamaria/structs/estimate.py | 23 ++++++++--------------- 2 files changed, 9 insertions(+), 16 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 37f2b0f..bb195bc 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -183,7 +183,7 @@ def run( timestamp tx ty tz qx qy qz qw ``` """ - est = Estimate() + est = Estimate(invert_poses=False) est.load_from_file(estimate) if not est.is_loaded(): logger.error("Estimate could not be loaded") diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index d0b5680..c527f41 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -47,16 +47,14 @@ class Estimate: ts t_x t_y t_z q_x q_y q_z q_w Blank lines and lines starting with '#' are ignored. - By default, poses are returned as rig_from_world + By default, poses are calculated as rig_from_world (i.e., inverse of world_from_rig) to satisfy COLMAP format. """ def __init__( - self, invert_poses: bool = True, uses_imu: bool = True + self, invert_poses: bool = True ) -> None: self.invert_poses = invert_poses - # uses_imu controls default behavior for baseline recon creation - self.uses_imu = uses_imu self.path: Path | None = None self._timestamps: list[int] = [] self._poses: list[pycolmap.Rigid3d] = [] @@ -81,7 +79,7 @@ def setup_baseline_cfg( cp_json_file: str | Path, device_calibration_json: str | Path, output_path: str | Path, - uses_imu: bool | None = None, + uses_imu: bool, ) -> None: """ Store config used by create_baseline_reconstruction(). @@ -90,8 +88,6 @@ def setup_baseline_cfg( If True, the poses in the estimate file are IMU poses. If False, the poses are left camera poses (monocular-cam0). """ - if uses_imu is None: - uses_imu = self.uses_imu self._baseline_cfg = _BaselineCfg( Path(cp_json_file), @@ -122,10 +118,8 @@ def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: # Adds cameras and rig to the reconstruction _add_cams(reconstruction, cfg.device_calibration_json) reconstruction = self._add_images_to_reconstruction( + cfg, reconstruction, - cfg.cp_json_file, - cfg.device_calibration_json, - cfg.uses_imu, ) reconstruction.write(str(recon_path)) @@ -227,23 +221,22 @@ def _parse(self, lines: list[str]) -> None: def _add_images_to_reconstruction( self, + cfg: _BaselineCfg, reconstruction: pycolmap.Reconstruction, - cp_json_file: Path, - device_calibration_json: Path, ) -> pycolmap.Reconstruction: """Add images to an existing empty reconstruction from this pose estimate.""" pose_data = self.as_tuples() - with open(cp_json_file) as f: + with open(cfg.cp_json_file) as f: cp_data = json.load(f) image_id = 1 rig = reconstruction.rig(rig_id=1) - if self.uses_imu: + if cfg.uses_imu: transform = get_t_imu_camera_from_json( - device_calibration_json=device_calibration_json, + cfg.device_calibration_json, camera_label="cam0", ) else: From 75834f09c08644045851f4e32797d0f4dbc31b3a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 13:23:09 +0200 Subject: [PATCH 422/665] fix --- lamaria/config/options.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 92a4bbb..31a0df6 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -20,7 +20,7 @@ def _structured_merge_to_obj(cls, section) -> object: @dataclass(slots=True) class MPSOptions: use_online_calibration: bool = ( - False # when use_mps is true (for online calib file) + False # set to True if using MPS online calibration result ) @classmethod From 210f55ee5e7ab6416d5b728f42ffa87c52bf5706 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 13:39:15 +0200 Subject: [PATCH 423/665] naming --- lamaria/pipeline/optim/imu.py | 2 +- lamaria/pipeline/optim/session.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 9206b16..da40a8a 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -51,7 +51,7 @@ def preintegrate_imu_measurements( return preintegrated_measurements -def load_imu_states( +def initialize_imu_states( data: LamariaReconstruction, ) -> dict[int, pycolmap.ImuState]: imu_states = {} diff --git a/lamaria/pipeline/optim/session.py b/lamaria/pipeline/optim/session.py index 597b031..21cc7df 100644 --- a/lamaria/pipeline/optim/session.py +++ b/lamaria/pipeline/optim/session.py @@ -6,7 +6,7 @@ from ...config.options import OptIMUOptions from ...structs.lamaria_reconstruction import LamariaReconstruction from .imu import ( - load_imu_states, + initialize_imu_states, preintegrate_imu_measurements, ) @@ -24,7 +24,7 @@ def _init_imu_data(self, imu_options): self.preintegrated_imu_measurements = preintegrate_imu_measurements( imu_options, self.data ) - self.imu_states = load_imu_states(self.data) + self.imu_states = initialize_imu_states(self.data) self.imu_from_rig = pycolmap.Rigid3d() self.gravity = np.array([0.0, 0.0, -1.0]) self.log_scale = np.array([0.0]) From 0b45d8fbe9c5c06b55c6b19291d3446a5f3b1b5e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 13:50:39 +0200 Subject: [PATCH 424/665] rm dummy imu params --- .../keyframing/to_lamaria_reconstruction.py | 52 +++++++------------ 1 file changed, 19 insertions(+), 33 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 5b1bdf9..83c4b20 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -307,31 +307,6 @@ def _match_estimate_ts_to_images( return matched_images, matched_timestamps - def _get_dummy_imu_params(self) -> tuple[int, int, list[float]]: - """Generates dummy IMU camera parameters for COLMAP.""" - width = 640 - height = 480 - random_params = [ - 241.604, - 241.604, - 322.895, - 240.444, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - ] - - return width, height, random_params - def _add_device_sensors(self) -> None: """Adds a new rig with device calibrated sensors. The rig is consistent across all frames @@ -347,14 +322,19 @@ def _add_device_sensors(self) -> None: rig = pycolmap.Rig(rig_id=1) - w, h, p = self._get_dummy_imu_params() # DUMMY CAMERA FOR IMU, IMU ID is 1 imu = pycolmap.Camera( camera_id=1, model=self.options.sensor.camera_model, - width=w, - height=h, - params=p, + width=640, + height=480, + params=[ + 241.604, + 241.604, + 322.895, + 240.444, + ] + + [0.0] * 12, ) self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) @@ -396,14 +376,20 @@ def _add_online_sensors(self) -> None: continue rig = pycolmap.Rig(rig_id=fid) - w, h, p = self._get_dummy_imu_params() + # DUMMY CAMERA FOR IMU imu = pycolmap.Camera( camera_id=sensor_id, model=self.options.sensor.camera_model, - width=w, - height=h, - params=p, + width=640, + height=480, + params=[ + 241.604, + 241.604, + 322.895, + 240.444, + ] + + [0.0] * 12, ) self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) From 7ecafcbf34c8fce538df7cda8f0628bcf7bb15bb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 13:52:27 +0200 Subject: [PATCH 425/665] upd init --- lamaria/structs/estimate.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index c527f41..7861ff8 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -51,9 +51,7 @@ class Estimate: (i.e., inverse of world_from_rig) to satisfy COLMAP format. """ - def __init__( - self, invert_poses: bool = True - ) -> None: + def __init__(self, invert_poses: bool = True) -> None: self.invert_poses = invert_poses self.path: Path | None = None self._timestamps: list[int] = [] From 1cff2ed9d190938bdfec232d1fa11fa5fac4eaf8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:25:48 +0200 Subject: [PATCH 426/665] colmap links --- defaults.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/defaults.yaml b/defaults.yaml index 7fd604a..f563abc 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -16,12 +16,12 @@ triangulation: num_retrieval_matches: 5 # relaxed triangulation - # https://github.com/colmap/colmap/blob/dbdb3cd5a9a90a01b7e1096905ba2ffc34a68b82/src/colmap/sfm/incremental_triangulator.h + # https://github.com/colmap/colmap/tree/3.12.6/src/colmap/sfm/incremental_triangulator.h merge_max_reproj_error: 15.0 complete_max_reproj_error: 15.0 min_angle: 1.0 - - # https://github.com/colmap/colmap/blob/dbdb3cd5a9a90a01b7e1096905ba2ffc34a68b82/src/colmap/sfm/incremental_mapper.h + + # https://github.com/colmap/colmap/tree/3.12.6/src/colmap/sfm/incremental_mapper.h filter_max_reproj_error: 15.0 filter_min_tri_angle: 1.0 From 8fbeab2f6f133a8d2ca89814681bfbcd9288ad22 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:26:40 +0200 Subject: [PATCH 427/665] delete files from folder --- lamaria/structs/estimate.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 7861ff8..839a588 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -2,6 +2,7 @@ from dataclasses import dataclass from decimal import ROUND_HALF_UP, Decimal from pathlib import Path +import shutil import numpy as np import pycolmap @@ -18,7 +19,6 @@ RIGHT_CAMERA_STREAM_LABEL, ) from ..utils.general import ( - delete_files_in_folder, find_closest_timestamp, ) @@ -110,7 +110,7 @@ def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: cfg = self._baseline_cfg recon_path = cfg.output_path / "reconstruction" recon_path.mkdir(parents=True, exist_ok=True) - delete_files_in_folder(recon_path) + shutil.rmtree(recon_path) reconstruction = pycolmap.Reconstruction() # Adds cameras and rig to the reconstruction From 4c74190026e301d3bd4d0d55ee3438ed62bbc392 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:27:04 +0200 Subject: [PATCH 428/665] unused func --- lamaria/utils/general.py | 19 ------------------- 1 file changed, 19 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 509937e..f055003 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -63,25 +63,6 @@ def get_matched_timestamps( return matched_timestamps -def delete_files_in_folder(folder, exclude_pattern=None): - if os.path.isdir(folder): - for filename in os.listdir(folder): - file_path = os.path.join(folder, filename) - - if exclude_pattern is not None and exclude_pattern in filename: - continue - - try: - if os.path.isfile(file_path) or os.path.islink(file_path): - os.unlink(file_path) - elif os.path.isdir(file_path): - shutil.rmtree(file_path) - except Exception as e: - print(f"Failed to delete {file_path}. Reason: {e}") - else: - os.makedirs(folder, exist_ok=True) - - def extract_images_from_vrs( vrs_file: Path, image_folder: Path, From e5e949f0045a0f11ee0f056fb5b370f6de70f1c2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:27:49 +0200 Subject: [PATCH 429/665] ruff --- lamaria/structs/estimate.py | 2 +- lamaria/utils/general.py | 3 +-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 839a588..444a429 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -1,8 +1,8 @@ import json +import shutil from dataclasses import dataclass from decimal import ROUND_HALF_UP, Decimal from pathlib import Path -import shutil import numpy as np import pycolmap diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index f055003..1e8773b 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -1,4 +1,3 @@ -import os import shutil import subprocess from bisect import bisect_left @@ -90,7 +89,7 @@ def extract_images_from_vrs( output_dir = image_folder / camera output_dir.mkdir(parents=True, exist_ok=True) - delete_files_in_folder(output_dir) + shutil.rmtree(output_dir) logger.info( "Extracting images for camera %s in VRS %s", camera, vrs_file ) From 522bb5c6fae20754f3c16bc6c4149b23c51b3efa Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:30:40 +0200 Subject: [PATCH 430/665] clear unused fn --- lamaria/utils/control_point.py | 7 +------ lamaria/utils/general.py | 11 ----------- 2 files changed, 1 insertion(+), 17 deletions(-) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 362bde6..80b485b 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -8,9 +8,6 @@ from .constants import ( CUSTOM_ORIGIN_COORDINATES, ) -from .general import ( - get_image_names_to_ids, -) def construct_control_points_from_json( @@ -128,9 +125,7 @@ def run_control_point_triangulation_from_json( """ rec = pycolmap.Reconstruction(reconstruction_path) - image_names_to_ids = get_image_names_to_ids( - reconstruction_path=reconstruction_path - ) + image_names_to_ids = {image.name: image_id for image_id, image in rec.images.items()} with open(cp_json_file) as file: data = json.load(file) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 1e8773b..324824c 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -104,14 +104,3 @@ def extract_images_from_vrs( msg += "\n" + out.stdout.decode("utf-8") raise subprocess.SubprocessError(msg) logger.info("Done!") - - -def get_image_names_to_ids(reconstruction_path: Path) -> dict[str, int]: - recon = pycolmap.Reconstruction(reconstruction_path) - image_names_to_ids = {} - - for image_id in recon.images: - image_name = recon.images[image_id].name - image_names_to_ids[image_name] = image_id - - return image_names_to_ids From 1e31dc522dcf527c6fee30a021709ce533606af3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:31:19 +0200 Subject: [PATCH 431/665] ruff --- lamaria/utils/control_point.py | 4 +++- lamaria/utils/general.py | 2 -- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py index 80b485b..7285f93 100644 --- a/lamaria/utils/control_point.py +++ b/lamaria/utils/control_point.py @@ -125,7 +125,9 @@ def run_control_point_triangulation_from_json( """ rec = pycolmap.Reconstruction(reconstruction_path) - image_names_to_ids = {image.name: image_id for image_id, image in rec.images.items()} + image_names_to_ids = { + image.name: image_id for image_id, image in rec.images.items() + } with open(cp_json_file) as file: data = json.load(file) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 324824c..8fc0871 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -3,8 +3,6 @@ from bisect import bisect_left from pathlib import Path -import pycolmap - from .. import logger From 3a581ad14fc45405c0976ac137352d09d3e33290 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:33:49 +0200 Subject: [PATCH 432/665] mv extraction --- lamaria/utils/aria.py | 48 +++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 48 insertions(+) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 69f50a7..de23231 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -1,4 +1,6 @@ import json +import shutil +import subprocess from pathlib import Path import numpy as np @@ -10,6 +12,7 @@ from scipy.spatial.transform import Rotation from tqdm import tqdm +from .. import logger from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID from .general import find_closest_timestamp @@ -395,3 +398,48 @@ def get_imu_data_from_vrs( ) return ms + + +def extract_images_from_vrs( + vrs_file: Path, + image_folder: Path, + left_subfolder_name="left", + right_subfolder_name="right", + rgb_subfolder_name="rgb", + verbose: bool = False, + extract_rgb: bool = False, + extract_left: bool = True, + extract_right: bool = True, +): + for camera, stream_id in [ + (left_subfolder_name, "1201-1"), + (right_subfolder_name, "1201-2"), + (rgb_subfolder_name, "214-1"), + ]: + if camera == rgb_subfolder_name and not extract_rgb: + continue + + if camera == left_subfolder_name and not extract_left: + continue + + if camera == right_subfolder_name and not extract_right: + continue + + output_dir = image_folder / camera + output_dir.mkdir(parents=True, exist_ok=True) + shutil.rmtree(output_dir) + + logger.info( + "Extracting images for camera %s in VRS %s", camera, vrs_file + ) + cmd = f"vrs extract-images {vrs_file} --to {output_dir} + {stream_id}" + stdout = None if verbose else subprocess.PIPE + out = subprocess.run( + cmd, shell=True, stderr=subprocess.STDOUT, stdout=stdout + ) + if out.returncode: + msg = f"Command '{cmd}' returned {out.returncode}." + if out.stdout: + msg += "\n" + out.stdout.decode("utf-8") + raise subprocess.SubprocessError(msg) + logger.info("Done!") From 8ba0a6a303d0688d50a553d2eef146aa0649c9d9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:34:03 +0200 Subject: [PATCH 433/665] mv --- lamaria/utils/general.py | 49 ---------------------------------------- 1 file changed, 49 deletions(-) diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py index 8fc0871..6e9580c 100644 --- a/lamaria/utils/general.py +++ b/lamaria/utils/general.py @@ -1,9 +1,4 @@ -import shutil -import subprocess from bisect import bisect_left -from pathlib import Path - -from .. import logger def find_closest_timestamp( @@ -58,47 +53,3 @@ def get_matched_timestamps( matched_timestamps.append((closest_lts, rts)) return matched_timestamps - - -def extract_images_from_vrs( - vrs_file: Path, - image_folder: Path, - left_subfolder_name="left", - right_subfolder_name="right", - rgb_subfolder_name="rgb", - verbose: bool = False, - extract_rgb: bool = False, - extract_left: bool = True, - extract_right: bool = True, -): - for camera, stream_id in [ - (left_subfolder_name, "1201-1"), - (right_subfolder_name, "1201-2"), - (rgb_subfolder_name, "214-1"), - ]: - if camera == rgb_subfolder_name and not extract_rgb: - continue - - if camera == left_subfolder_name and not extract_left: - continue - - if camera == right_subfolder_name and not extract_right: - continue - - output_dir = image_folder / camera - output_dir.mkdir(parents=True, exist_ok=True) - shutil.rmtree(output_dir) - logger.info( - "Extracting images for camera %s in VRS %s", camera, vrs_file - ) - cmd = f"vrs extract-images {vrs_file} --to {output_dir} + {stream_id}" - stdout = None if verbose else subprocess.PIPE - out = subprocess.run( - cmd, shell=True, stderr=subprocess.STDOUT, stdout=stdout - ) - if out.returncode: - msg = f"Command '{cmd}' returned {out.returncode}." - if out.stdout: - msg += "\n" + out.stdout.decode("utf-8") - raise subprocess.SubprocessError(msg) - logger.info("Done!") From bfa807098dc6737d9d21c1e3301469a69847d658 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:35:05 +0200 Subject: [PATCH 434/665] vrs --- lamaria/utils/aria.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index de23231..edce62f 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -400,6 +400,9 @@ def get_imu_data_from_vrs( return ms +# ----- VRS utils ----- # + + def extract_images_from_vrs( vrs_file: Path, image_folder: Path, From beab16beac3d2a553bea591987ba4a3d2cae828d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:37:13 +0200 Subject: [PATCH 435/665] extract fix --- lamaria/pipeline/keyframing/keyframe_selection.py | 2 +- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 2 +- tools/vrs_to_asl_folder.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 36a2060..d38ae8e 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -243,7 +243,7 @@ def copy_images_to_keyframes_dir( Images are expected to be in `images/left` and `images/right` subdirectories. Check: `extract_images_from_vrs` in - `lamaria/utils/general.py` for more details. + `lamaria/utils/aria.py` for more details. """ if self.keyframe_frame_ids is None: raise ValueError( diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 83c4b20..ef5159d 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -16,6 +16,7 @@ from ...structs.lamaria_reconstruction import LamariaReconstruction from ...utils.aria import ( camera_colmap_from_calib, + extract_images_from_vrs, get_closed_loop_data_from_mps, get_imu_data_from_vrs, get_mps_poses_for_timestamps, @@ -23,7 +24,6 @@ rigid3d_from_transform, ) from ...utils.general import ( - extract_images_from_vrs, get_matched_timestamps, ) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index d05dac2..532aa24 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -8,13 +8,13 @@ from tqdm import tqdm from lamaria import logger +from lamaria.utils.aria import extract_images_from_vrs from lamaria.utils.constants import ( LEFT_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, RIGHT_IMU_STREAM_ID, ) from lamaria.utils.general import ( - extract_images_from_vrs, get_matched_timestamps, ) From 1185f6aba3c0536d5785b2070195e80e03df5088 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:40:01 +0200 Subject: [PATCH 436/665] del --- lamaria/utils/general.py | 55 ---------------------------------------- 1 file changed, 55 deletions(-) delete mode 100644 lamaria/utils/general.py diff --git a/lamaria/utils/general.py b/lamaria/utils/general.py deleted file mode 100644 index 6e9580c..0000000 --- a/lamaria/utils/general.py +++ /dev/null @@ -1,55 +0,0 @@ -from bisect import bisect_left - - -def find_closest_timestamp( - timestamps: list, - target_ts: int, - max_diff: float, -) -> int | None: - """Timestamps must be in nano seconds""" - index = bisect_left(timestamps, target_ts) - if index == 0: - return timestamps[0] - if index == len(timestamps): - return timestamps[-1] - before = timestamps[index - 1] - after = timestamps[index] - if abs(target_ts - before) < abs(target_ts - after): - closest = before - else: - closest = after - - if abs(target_ts - closest) > max_diff: - return None - - return closest - - -def get_matched_timestamps( - left_timestamps: list[int], - right_timestamps: list[int], - max_diff: float, -) -> list[tuple[int, int]]: - matched_timestamps = [] - - assert all(isinstance(ts, int) for ts in left_timestamps), ( - "Left timestamps must be integers" - ) - assert all(isinstance(ts, int) for ts in right_timestamps), ( - "Right timestamps must be integers" - ) - - if len(left_timestamps) < len(right_timestamps): - for lts in left_timestamps: - closest_rts = find_closest_timestamp( - right_timestamps, lts, max_diff - ) - if closest_rts is not None: - matched_timestamps.append((lts, closest_rts)) - else: - for rts in right_timestamps: - closest_lts = find_closest_timestamp(left_timestamps, rts, max_diff) - if closest_lts is not None: - matched_timestamps.append((closest_lts, rts)) - - return matched_timestamps From 05fa8ca3350dbe8b53869621e490a25d8e2a0ae7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:40:08 +0200 Subject: [PATCH 437/665] sync --- lamaria/utils/synchronization.py | 55 ++++++++++++++++++++++++++++++++ 1 file changed, 55 insertions(+) create mode 100644 lamaria/utils/synchronization.py diff --git a/lamaria/utils/synchronization.py b/lamaria/utils/synchronization.py new file mode 100644 index 0000000..6e9580c --- /dev/null +++ b/lamaria/utils/synchronization.py @@ -0,0 +1,55 @@ +from bisect import bisect_left + + +def find_closest_timestamp( + timestamps: list, + target_ts: int, + max_diff: float, +) -> int | None: + """Timestamps must be in nano seconds""" + index = bisect_left(timestamps, target_ts) + if index == 0: + return timestamps[0] + if index == len(timestamps): + return timestamps[-1] + before = timestamps[index - 1] + after = timestamps[index] + if abs(target_ts - before) < abs(target_ts - after): + closest = before + else: + closest = after + + if abs(target_ts - closest) > max_diff: + return None + + return closest + + +def get_matched_timestamps( + left_timestamps: list[int], + right_timestamps: list[int], + max_diff: float, +) -> list[tuple[int, int]]: + matched_timestamps = [] + + assert all(isinstance(ts, int) for ts in left_timestamps), ( + "Left timestamps must be integers" + ) + assert all(isinstance(ts, int) for ts in right_timestamps), ( + "Right timestamps must be integers" + ) + + if len(left_timestamps) < len(right_timestamps): + for lts in left_timestamps: + closest_rts = find_closest_timestamp( + right_timestamps, lts, max_diff + ) + if closest_rts is not None: + matched_timestamps.append((lts, closest_rts)) + else: + for rts in right_timestamps: + closest_lts = find_closest_timestamp(left_timestamps, rts, max_diff) + if closest_lts is not None: + matched_timestamps.append((closest_lts, rts)) + + return matched_timestamps From 1e807502d15531c34fccb7eef2ed8f926af767a6 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 15:41:19 +0200 Subject: [PATCH 438/665] importing sync --- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 2 +- lamaria/structs/estimate.py | 2 +- lamaria/utils/aria.py | 2 +- tools/vrs_to_asl_folder.py | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index ef5159d..f978af5 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -23,7 +23,7 @@ get_t_imu_camera, rigid3d_from_transform, ) -from ...utils.general import ( +from ...utils.synchronization import ( get_matched_timestamps, ) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 444a429..d0a2b82 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -18,7 +18,7 @@ LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL, ) -from ..utils.general import ( +from ..utils.synchronization import ( find_closest_timestamp, ) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index edce62f..feaf970 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -14,7 +14,7 @@ from .. import logger from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID -from .general import find_closest_timestamp +from .synchronization import find_closest_timestamp # ----- Camera functions ----- # diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index 532aa24..2d03779 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -14,7 +14,7 @@ RIGHT_CAMERA_STREAM_ID, RIGHT_IMU_STREAM_ID, ) -from lamaria.utils.general import ( +from lamaria.utils.synchronization import ( get_matched_timestamps, ) From 4e1d10bc92e9c15be1951e698b0b5ea0ac0f255a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 16:06:44 +0200 Subject: [PATCH 439/665] estimate loading --- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index f978af5..da59ab9 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -139,7 +139,9 @@ def _init_data( # Raises error if estimate file is invalid est = Estimate(invert_poses=True) est.load_from_file(estimate) - + if not est.is_loaded(): + raise RuntimeError("Failed to load estimate file") + timestamps = est.timestamps if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images( From 46c3abe29706d4ae4400c7f1d3c85e509505b4e6 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 16:07:55 +0200 Subject: [PATCH 440/665] estimate --- lamaria/structs/estimate.py | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index d0a2b82..1021038 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -8,6 +8,7 @@ import pycolmap from tqdm import tqdm +from .. import logger from ..utils.aria import ( add_cameras_to_reconstruction as _add_cams, ) @@ -58,7 +59,7 @@ def __init__(self, invert_poses: bool = True) -> None: self._poses: list[pycolmap.Rigid3d] = [] self._baseline_cfg: _BaselineCfg | None = None - def load_from_file(self, path: str | Path) -> "Estimate": + def load_from_file(self, path: str | Path) -> None: """Parse the file, validate format, populate timestamps & poses.""" self.clear() self.path = Path(path) @@ -69,8 +70,9 @@ def load_from_file(self, path: str | Path) -> "Estimate": with open(self.path) as f: lines = f.readlines() - self._parse(lines) # raises error if format is invalid - return self + state = self._parse(lines) + if not state: + raise RuntimeError("Failed to parse estimate file.") def setup_baseline_cfg( self, @@ -178,9 +180,8 @@ def _parse(self, lines: list[str]) -> None: exists_lines = True parts = line.split() if len(parts) != 8: - raise ValueError( - f"{lineno}: expected 8 values, got {len(parts)}" - ) + logger.error(f"Line {lineno}: expected 8 values, got {len(parts)}") + return False try: ts = _round_ns(parts[0]) @@ -197,9 +198,8 @@ def _parse(self, lines: list[str]) -> None: ) except ValueError as e: - raise ValueError( - f"{lineno}: non-numeric value in {parts!r}" - ) from e + logger.error(f"Line {lineno}: invalid number format: {e}") + return False world_from_rig = pycolmap.Rigid3d(pycolmap.Rotation3d(qvec), tvec) pose = ( @@ -212,7 +212,8 @@ def _parse(self, lines: list[str]) -> None: pose_list.append(pose) if not exists_lines: - raise ValueError("No valid lines found in estimate file.") + logger.error("No valid lines found in the estimate file.") + return False self._timestamps = ts_list self._poses = pose_list From f0341a19b0aa74a6c97a0822fe6078cdc2161312 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 16:18:20 +0200 Subject: [PATCH 441/665] revert --- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index da59ab9..65fe58d 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -136,11 +136,8 @@ def _init_data( images, timestamps, mps_poses ) else: - # Raises error if estimate file is invalid est = Estimate(invert_poses=True) est.load_from_file(estimate) - if not est.is_loaded(): - raise RuntimeError("Failed to load estimate file") timestamps = est.timestamps if len(images) != len(timestamps): From 4447fb5f0989d4558090d94947353860d4c94650 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:11:49 +0200 Subject: [PATCH 442/665] estimate class upd --- lamaria/structs/estimate.py | 77 ++++++++++++------------------------- 1 file changed, 25 insertions(+), 52 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 1021038..635bb60 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -32,16 +32,6 @@ def _round_ns(x: str | int | float) -> int: return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) -@dataclass(slots=True) -class _BaselineCfg: - """Configuration for creating a baseline reconstruction.""" - - cp_json_file: Path - device_calibration_json: Path - output_path: Path - uses_imu: bool = True # if False, uses monocular-cam0 poses - - class Estimate: """ Loads and stores an 'estimate' text file with rows: @@ -52,12 +42,16 @@ class Estimate: (i.e., inverse of world_from_rig) to satisfy COLMAP format. """ - def __init__(self, invert_poses: bool = True) -> None: + def __init__( + self, + invert_poses: bool = True, + reference_sensor: str = "imu" + ) -> None: self.invert_poses = invert_poses + self.reference_sensor = reference_sensor self.path: Path | None = None self._timestamps: list[int] = [] self._poses: list[pycolmap.Rigid3d] = [] - self._baseline_cfg: _BaselineCfg | None = None def load_from_file(self, path: str | Path) -> None: """Parse the file, validate format, populate timestamps & poses.""" @@ -74,52 +68,31 @@ def load_from_file(self, path: str | Path) -> None: if not state: raise RuntimeError("Failed to parse estimate file.") - def setup_baseline_cfg( + def create_baseline_reconstruction( self, - cp_json_file: str | Path, - device_calibration_json: str | Path, - output_path: str | Path, - uses_imu: bool, - ) -> None: + cp_json_file: Path, + device_calibration_json: Path, + output_path: Path, + ) -> pycolmap.Reconstruction: """ - Store config used by create_baseline_reconstruction(). - - uses_imu: - If True, the poses in the estimate file are IMU poses. - If False, the poses are left camera poses (monocular-cam0). + Adds estimate poses as frames to input reconstruction. """ - self._baseline_cfg = _BaselineCfg( - Path(cp_json_file), - Path(device_calibration_json), - Path(output_path), - uses_imu, - ) - - def create_baseline_reconstruction(self) -> pycolmap.Reconstruction: - """ - Build a COLMAP reconstruction from this Estimate and the - parameters given via setup_baseline_cfg(). Writes to: - output_path / "reconstruction" - Returns pycolmap.Reconstruction. - """ self._ensure_loaded() - if self._baseline_cfg is None: - raise RuntimeError( - "Baseline not configured. Call setup_baseline_cfg(...) first." - ) - cfg = self._baseline_cfg - recon_path = cfg.output_path / "reconstruction" + recon_path = output_path / "reconstruction" recon_path.mkdir(parents=True, exist_ok=True) shutil.rmtree(recon_path) reconstruction = pycolmap.Reconstruction() - # Adds cameras and rig to the reconstruction - _add_cams(reconstruction, cfg.device_calibration_json) + _add_cams( + reconstruction, + device_calibration_json + ) reconstruction = self._add_images_to_reconstruction( - cfg, reconstruction, + cp_json_file, + device_calibration_json ) reconstruction.write(str(recon_path)) @@ -220,22 +193,22 @@ def _parse(self, lines: list[str]) -> None: def _add_images_to_reconstruction( self, - cfg: _BaselineCfg, reconstruction: pycolmap.Reconstruction, + cp_json_file: Path, + device_calibration_json: Path, ) -> pycolmap.Reconstruction: - """Add images to an existing empty - reconstruction from this pose estimate.""" + pose_data = self.as_tuples() - with open(cfg.cp_json_file) as f: + with open(cp_json_file) as f: cp_data = json.load(f) image_id = 1 rig = reconstruction.rig(rig_id=1) - if cfg.uses_imu: + if self.reference_sensor == "imu": transform = get_t_imu_camera_from_json( - cfg.device_calibration_json, + device_calibration_json, camera_label="cam0", ) else: From a6340474d478f3926d3d3e624dbf25ac5a47d55f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:19:32 +0200 Subject: [PATCH 443/665] init recon from calib file --- lamaria/utils/aria.py | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index feaf970..470a65f 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -16,6 +16,26 @@ from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID from .synchronization import find_closest_timestamp +# ----- Reconstruction functions ----- # + + +def initialize_reconstruction_from_calibration_file( + calibration_file: Path, +) -> pycolmap.Reconstruction: + """Initialize a COLMAP reconstruction from Aria calibration + json file found on website: https://lamaria.ethz.ch/slam_datasets + + Args: + calibration_file (Path): + Path to the Aria calibration json file + Returns: + pycolmap.Reconstruction: The initialized COLMAP reconstruction + """ + reconstruction = pycolmap.Reconstruction() + add_cameras_to_reconstruction(reconstruction, calibration_file) + return reconstruction + + # ----- Camera functions ----- # From 590f68088ac19f21ac48b34d21566ac40fe3ad08 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:21:33 +0200 Subject: [PATCH 444/665] sparse eval --- lamaria/eval/sparse_evaluation.py | 24 +++++++++--------------- 1 file changed, 9 insertions(+), 15 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index bb195bc..ccf9b4b 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -157,7 +157,7 @@ def run( cp_json_file: Path, device_calibration_json: Path, output_path: Path, - uses_imu: bool, + reference_sensor: str = "imu", cp_reproj_std=1.0, ): """Run sparse evaluation for sequences that observe control points. @@ -169,8 +169,7 @@ def run( device_calibration_json (Path): Path to the device calibration JSON. output_path (Path): Directory where intermediate data and evaluation results will be saved. - uses_imu (bool): Whether poses are in IMU frame - or cam0 (left camera) frame. + reference_sensor (str): The reference sensor to use ("imu" or "cam0"). cp_reproj_std (float, optional): Control point reprojection standard deviation. Defaults to 1.0. @@ -183,18 +182,12 @@ def run( timestamp tx ty tz qx qy qz qw ``` """ - est = Estimate(invert_poses=False) + est = Estimate(invert_poses=False, reference_sensor=reference_sensor) est.load_from_file(estimate) if not est.is_loaded(): logger.error("Estimate could not be loaded") return False - est.setup_baseline_cfg( - cp_json_file, - device_calibration_json, - output_path, - uses_imu, - ) _ = est.create_baseline_reconstruction() reconstruction_path = est.reconstruction_path @@ -329,10 +322,11 @@ def run( "and evaluation results will be saved", ) parser.add_argument( - "--uses_imu", - action="store_true", - help="Set if the poses are in IMU frame. If not set, " - "poses are assumed to be in cam0 (left camera) frame.", + "--reference_sensor", + type=str, + default="imu", + choices=["imu", "cam0"], + help="The reference sensor in which the poses are expressed.", ) parser.add_argument( "--cp_reproj_std", @@ -347,6 +341,6 @@ def run( args.cp_json_file, args.device_calibration_json, args.output_path, - args.uses_imu, + args.reference_sensor, args.cp_reproj_std, ) From 9f3d8e094f5c9645be8fb70af0553dee5ea1de93 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:32:16 +0200 Subject: [PATCH 445/665] est upd --- lamaria/structs/estimate.py | 51 ++++++++++++++----------------------- 1 file changed, 19 insertions(+), 32 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 635bb60..b9bc621 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -1,6 +1,5 @@ import json import shutil -from dataclasses import dataclass from decimal import ROUND_HALF_UP, Decimal from pathlib import Path @@ -42,21 +41,24 @@ class Estimate: (i.e., inverse of world_from_rig) to satisfy COLMAP format. """ - def __init__( - self, - invert_poses: bool = True, - reference_sensor: str = "imu" - ) -> None: - self.invert_poses = invert_poses - self.reference_sensor = reference_sensor + def __init__(self) -> None: + self.invert_poses = None + self.reference_sensor = None self.path: Path | None = None self._timestamps: list[int] = [] self._poses: list[pycolmap.Rigid3d] = [] - def load_from_file(self, path: str | Path) -> None: + def load_from_file( + self, + path: str | Path, + invert_poses: bool = True, + reference_sensor: str = "imu" + ) -> None: """Parse the file, validate format, populate timestamps & poses.""" self.clear() self.path = Path(path) + self.invert_poses = invert_poses + self.reference_sensor = reference_sensor if not self.path.exists(): raise FileNotFoundError(f"Estimate file not found: {self.path}") @@ -64,14 +66,14 @@ def load_from_file(self, path: str | Path) -> None: with open(self.path) as f: lines = f.readlines() - state = self._parse(lines) + state = self._parse(lines) if not state: raise RuntimeError("Failed to parse estimate file.") def create_baseline_reconstruction( self, cp_json_file: Path, - device_calibration_json: Path, + sensor_from_rig: pycolmap.Rigid3d, output_path: Path, ) -> pycolmap.Reconstruction: """ @@ -84,15 +86,10 @@ def create_baseline_reconstruction( recon_path.mkdir(parents=True, exist_ok=True) shutil.rmtree(recon_path) - reconstruction = pycolmap.Reconstruction() - _add_cams( - reconstruction, - device_calibration_json - ) reconstruction = self._add_images_to_reconstruction( reconstruction, cp_json_file, - device_calibration_json + sensor_from_rig ) reconstruction.write(str(recon_path)) @@ -108,12 +105,6 @@ def poses(self) -> list[pycolmap.Rigid3d]: self._ensure_loaded() return self._poses - @property - def reconstruction_path(self) -> Path | None: - if self._baseline_cfg is None: - return None - return self._baseline_cfg.output_path / "reconstruction" - def as_tuples(self) -> list[tuple[int, pycolmap.Rigid3d]]: """Return a list of (timestamp, pose) tuples.""" self._ensure_loaded() @@ -153,7 +144,9 @@ def _parse(self, lines: list[str]) -> None: exists_lines = True parts = line.split() if len(parts) != 8: - logger.error(f"Line {lineno}: expected 8 values, got {len(parts)}") + logger.error( + f"Line {lineno}: expected 8 values, got {len(parts)}" + ) return False try: @@ -195,7 +188,7 @@ def _add_images_to_reconstruction( self, reconstruction: pycolmap.Reconstruction, cp_json_file: Path, - device_calibration_json: Path, + sensor_from_rig: pycolmap.Rigid3d, ) -> pycolmap.Reconstruction: pose_data = self.as_tuples() @@ -206,13 +199,7 @@ def _add_images_to_reconstruction( image_id = 1 rig = reconstruction.rig(rig_id=1) - if self.reference_sensor == "imu": - transform = get_t_imu_camera_from_json( - device_calibration_json, - camera_label="cam0", - ) - else: - transform = pycolmap.Rigid3d() + transform = sensor_from_rig.inverse() ts_data_processed = {} for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: From 4567c4fb3cd9c983135344c0457c52390f032dc2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:42:09 +0200 Subject: [PATCH 446/665] estimate --- lamaria/structs/estimate.py | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index b9bc621..6a17900 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -8,12 +8,6 @@ from tqdm import tqdm from .. import logger -from ..utils.aria import ( - add_cameras_to_reconstruction as _add_cams, -) -from ..utils.aria import ( - get_t_imu_camera_from_json, -) from ..utils.constants import ( LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL, @@ -75,7 +69,7 @@ def create_baseline_reconstruction( cp_json_file: Path, sensor_from_rig: pycolmap.Rigid3d, output_path: Path, - ) -> pycolmap.Reconstruction: + ) -> Path: """ Adds estimate poses as frames to input reconstruction. """ @@ -92,8 +86,9 @@ def create_baseline_reconstruction( sensor_from_rig ) - reconstruction.write(str(recon_path)) - return reconstruction + reconstruction.write(recon_path.as_posix()) + + return recon_path @property def timestamps(self) -> list[int]: From 010a108587cf1e3f7f597d5e859e4a72cc4375e8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:42:49 +0200 Subject: [PATCH 447/665] undistort asl add cameras rm --- tools/undistort_asl_folder.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index 342fae7..a82d16b 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -10,7 +10,7 @@ from tqdm import tqdm from lamaria.utils.aria import ( - add_cameras_to_reconstruction, + initialize_reconstruction_from_calibration_file, ) from lamaria.utils.constants import ( ARIA_CAMERAS, @@ -80,9 +80,7 @@ def undistort_asl( if not calibration_file.exists(): raise FileNotFoundError(f"{calibration_file=}") - recon = pycolmap.Reconstruction() - add_cameras_to_reconstruction( - reconstruction=recon, + recon = initialize_reconstruction_from_calibration_file( calibration_file=calibration_file, ) # Create a dummy COLMAP reconstruction. From fdb763be202dd890ce830f1c6140be13cd6f89aa Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:43:12 +0200 Subject: [PATCH 448/665] util fn init recon from claib --- lamaria/utils/aria.py | 28 ++++++---------------------- 1 file changed, 6 insertions(+), 22 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 470a65f..f586094 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -32,28 +32,7 @@ def initialize_reconstruction_from_calibration_file( pycolmap.Reconstruction: The initialized COLMAP reconstruction """ reconstruction = pycolmap.Reconstruction() - add_cameras_to_reconstruction(reconstruction, calibration_file) - return reconstruction - - -# ----- Camera functions ----- # - - -def add_cameras_to_reconstruction( - reconstruction: pycolmap.Reconstruction, - calibration_file: Path, -) -> None: - """Add Aria cameras to COLMAP reconstruction from calibration - json file found on website: https://lamaria.ethz.ch/slam_datasets - - Args: - reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction - to which cameras will be added - - calibration_file (Path): - Path to the Aria calibration json file - """ - + for i, (key, _) in enumerate(ARIA_CAMERAS): cam = camera_colmap_from_json( calibration_file=calibration_file, @@ -78,6 +57,11 @@ def add_cameras_to_reconstruction( rig.add_sensor(sensor1, sensor_from_rig) reconstruction.add_rig(rig) + + return reconstruction + + +# ----- Camera functions ----- # def get_camera_params_for_colmap( From 21dbae55a254dd689e8d24320311da5ab56ed22e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:43:31 +0200 Subject: [PATCH 449/665] sparse eval --- lamaria/eval/sparse_evaluation.py | 23 ++++++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index ccf9b4b..ac65e7f 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -15,6 +15,7 @@ get_cps_for_initial_alignment, run_control_point_triangulation_from_json, ) +from ..utils.aria import get_t_imu_camera_from_json, initialize_reconstruction_from_calibration_file def update_sim3d_scale(variables: dict) -> None: @@ -182,13 +183,29 @@ def run( timestamp tx ty tz qx qy qz qw ``` """ - est = Estimate(invert_poses=False, reference_sensor=reference_sensor) - est.load_from_file(estimate) + est = Estimate() + est.load_from_file(estimate, invert_poses=False, reference_sensor=reference_sensor) if not est.is_loaded(): logger.error("Estimate could not be loaded") return False - _ = est.create_baseline_reconstruction() + reconstruction = initialize_reconstruction_from_calibration_file( + device_calibration_json + ) + + if reference_sensor == "imu": + rig_from_sensor = get_t_imu_camera_from_json( + device_calibration_json, camera_label="cam0" + ) + sensor_from_rig = rig_from_sensor.inverse() + else: + sensor_from_rig = pycolmap.Rigid3d() + + reconstruction_path = est.create_baseline_reconstruction( + cp_json_file, + sensor_from_rig, + output_path, + ) reconstruction_path = est.reconstruction_path aligned_transformed_folder = output_path / "aligned_transformed" From 5817d5a55c42278145153c4a8748161aab6852ac Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:43:40 +0200 Subject: [PATCH 450/665] ruff --- lamaria/pipeline/keyframing/to_lamaria_reconstruction.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py index 65fe58d..36c5588 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py @@ -138,7 +138,7 @@ def _init_data( else: est = Estimate(invert_poses=True) est.load_from_file(estimate) - + timestamps = est.timestamps if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images( From 73f14b030c27fc819f6b55c8deb94b87a542c83d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:46:09 +0200 Subject: [PATCH 451/665] est upd --- lamaria/eval/sparse_evaluation.py | 15 ++++++++++----- lamaria/utils/aria.py | 4 ++-- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index ac65e7f..69f36de 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -10,12 +10,15 @@ from .. import logger from ..structs.estimate import Estimate +from ..utils.aria import ( + get_t_imu_camera_from_json, + initialize_reconstruction_from_calibration_file, +) from ..utils.control_point import ( construct_control_points_from_json, get_cps_for_initial_alignment, run_control_point_triangulation_from_json, ) -from ..utils.aria import get_t_imu_camera_from_json, initialize_reconstruction_from_calibration_file def update_sim3d_scale(variables: dict) -> None: @@ -184,7 +187,9 @@ def run( ``` """ est = Estimate() - est.load_from_file(estimate, invert_poses=False, reference_sensor=reference_sensor) + est.load_from_file( + estimate, invert_poses=False, reference_sensor=reference_sensor + ) if not est.is_loaded(): logger.error("Estimate could not be loaded") return False @@ -192,7 +197,7 @@ def run( reconstruction = initialize_reconstruction_from_calibration_file( device_calibration_json ) - + if reference_sensor == "imu": rig_from_sensor = get_t_imu_camera_from_json( device_calibration_json, camera_label="cam0" @@ -201,12 +206,12 @@ def run( else: sensor_from_rig = pycolmap.Rigid3d() - reconstruction_path = est.create_baseline_reconstruction( + reconstruction_path = est.add_estimate_poses_to_reconstruction( + reconstruction, cp_json_file, sensor_from_rig, output_path, ) - reconstruction_path = est.reconstruction_path aligned_transformed_folder = output_path / "aligned_transformed" aligned_transformed_folder.mkdir(parents=True, exist_ok=True) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index f586094..b703113 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -32,7 +32,7 @@ def initialize_reconstruction_from_calibration_file( pycolmap.Reconstruction: The initialized COLMAP reconstruction """ reconstruction = pycolmap.Reconstruction() - + for i, (key, _) in enumerate(ARIA_CAMERAS): cam = camera_colmap_from_json( calibration_file=calibration_file, @@ -57,7 +57,7 @@ def initialize_reconstruction_from_calibration_file( rig.add_sensor(sensor1, sensor_from_rig) reconstruction.add_rig(rig) - + return reconstruction From 04aeab9b0b9fee693730ae5c931fe39b3ea4199a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:46:44 +0200 Subject: [PATCH 452/665] ruff --- lamaria/structs/estimate.py | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 6a17900..2dfb26f 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -46,7 +46,7 @@ def load_from_file( self, path: str | Path, invert_poses: bool = True, - reference_sensor: str = "imu" + reference_sensor: str = "imu", ) -> None: """Parse the file, validate format, populate timestamps & poses.""" self.clear() @@ -64,8 +64,9 @@ def load_from_file( if not state: raise RuntimeError("Failed to parse estimate file.") - def create_baseline_reconstruction( + def add_estimate_poses_to_reconstruction( self, + reconstruction: pycolmap.Reconstruction, cp_json_file: Path, sensor_from_rig: pycolmap.Rigid3d, output_path: Path, @@ -81,13 +82,11 @@ def create_baseline_reconstruction( shutil.rmtree(recon_path) reconstruction = self._add_images_to_reconstruction( - reconstruction, - cp_json_file, - sensor_from_rig + reconstruction, cp_json_file, sensor_from_rig ) reconstruction.write(recon_path.as_posix()) - + return recon_path @property @@ -185,7 +184,6 @@ def _add_images_to_reconstruction( cp_json_file: Path, sensor_from_rig: pycolmap.Rigid3d, ) -> pycolmap.Reconstruction: - pose_data = self.as_tuples() with open(cp_json_file) as f: From d319d944b42c39274a860806630bd3c407d31e36 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:53:08 +0200 Subject: [PATCH 453/665] edits --- lamaria/eval/sparse_evaluation.py | 14 +++++++------- lamaria/structs/estimate.py | 6 +++--- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 69f36de..7a2c976 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -161,7 +161,7 @@ def run( cp_json_file: Path, device_calibration_json: Path, output_path: Path, - reference_sensor: str = "imu", + corresponding_sensor: str = "imu", cp_reproj_std=1.0, ): """Run sparse evaluation for sequences that observe control points. @@ -173,7 +173,7 @@ def run( device_calibration_json (Path): Path to the device calibration JSON. output_path (Path): Directory where intermediate data and evaluation results will be saved. - reference_sensor (str): The reference sensor to use ("imu" or "cam0"). + corresponding_sensor (str): The reference sensor to use ("imu" or "cam0"). cp_reproj_std (float, optional): Control point reprojection standard deviation. Defaults to 1.0. @@ -188,7 +188,7 @@ def run( """ est = Estimate() est.load_from_file( - estimate, invert_poses=False, reference_sensor=reference_sensor + estimate, invert_poses=False, corresponding_sensor=corresponding_sensor ) if not est.is_loaded(): logger.error("Estimate could not be loaded") @@ -198,7 +198,7 @@ def run( device_calibration_json ) - if reference_sensor == "imu": + if corresponding_sensor == "imu": rig_from_sensor = get_t_imu_camera_from_json( device_calibration_json, camera_label="cam0" ) @@ -344,11 +344,11 @@ def run( "and evaluation results will be saved", ) parser.add_argument( - "--reference_sensor", + "--corresponding_sensor", type=str, default="imu", choices=["imu", "cam0"], - help="The reference sensor in which the poses are expressed.", + help="The sensor in which the poses are expressed.", ) parser.add_argument( "--cp_reproj_std", @@ -363,6 +363,6 @@ def run( args.cp_json_file, args.device_calibration_json, args.output_path, - args.reference_sensor, + args.corresponding_sensor, args.cp_reproj_std, ) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 2dfb26f..f317266 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -37,7 +37,7 @@ class Estimate: def __init__(self) -> None: self.invert_poses = None - self.reference_sensor = None + self.corresponding_sensor = None self.path: Path | None = None self._timestamps: list[int] = [] self._poses: list[pycolmap.Rigid3d] = [] @@ -46,13 +46,13 @@ def load_from_file( self, path: str | Path, invert_poses: bool = True, - reference_sensor: str = "imu", + corresponding_sensor: str = "imu", ) -> None: """Parse the file, validate format, populate timestamps & poses.""" self.clear() self.path = Path(path) self.invert_poses = invert_poses - self.reference_sensor = reference_sensor + self.corresponding_sensor = corresponding_sensor if not self.path.exists(): raise FileNotFoundError(f"Estimate file not found: {self.path}") From 806d9dec8876d81d7877c3e38f8acdbcffa6ee47 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:56:05 +0200 Subject: [PATCH 454/665] lamaria recons --- lamaria/structs/lamaria_reconstruction.py | 87 ----------------------- 1 file changed, 87 deletions(-) delete mode 100644 lamaria/structs/lamaria_reconstruction.py diff --git a/lamaria/structs/lamaria_reconstruction.py b/lamaria/structs/lamaria_reconstruction.py deleted file mode 100644 index c8cf7a9..0000000 --- a/lamaria/structs/lamaria_reconstruction.py +++ /dev/null @@ -1,87 +0,0 @@ -from pathlib import Path - -import numpy as np -import pycolmap - - -class LamariaReconstruction: - """Custom class to hold COLMAP reconstruction data along with - timestamps and IMU measurements. - - Attributes: - reconstruction (pycolmap.Reconstruction): - The COLMAP reconstruction object. This object contains all the - 3D points, cameras (intrinsics, extrinsics), and images. - Additionally holds a dummy camera, with no associated images, - to serve as a placeholder for the IMU. - - timestamps (dict[int, int]): A dictionary mapping reconstruction - frame IDs to their corresponding timestamps in nanoseconds. - - imu_measurements (pycolmap.ImuMeasurements): The factory/online - rectified IMU measurements generated from input VRS file. - """ - - def __init__(self) -> None: - self.reconstruction = pycolmap.Reconstruction() - self.timestamps: dict[int, int] = {} - self.imu_measurements = None - - @staticmethod - def read( - input_folder: Path, - ) -> "LamariaReconstruction": - assert input_folder.exists(), ( - f"Input folder {input_folder} does not exist" - ) - instance = LamariaReconstruction() - instance.reconstruction = pycolmap.Reconstruction(input_folder) - - ts_path = input_folder / "timestamps.txt" - assert ts_path.exists(), ( - f"Timestamps file {ts_path} does not exist in {input_folder}" - ) - with open(ts_path) as f: - lines = f.readlines() - instance.timestamps = {} - for line in lines: - if line.startswith("#"): - continue - frame_id, ts = line.strip().split() - instance.timestamps[int(frame_id)] = int(ts) - - rectified_imu_data_npy = input_folder / "rectified_imu_data.npy" - assert rectified_imu_data_npy.exists(), ( - f"Rectified IMU data file {rectified_imu_data_npy} \ - does not exist in {input_folder}" - ) - rectified_imu_data = np.load(rectified_imu_data_npy, allow_pickle=True) - instance.imu_measurements = pycolmap.ImuMeasurements( - rectified_imu_data.tolist() - ) - - return instance - - def write( - self, - output_folder: Path, - ) -> None: - output_folder.mkdir(parents=True, exist_ok=True) - self.reconstruction.write(output_folder.as_posix()) - - ts_path = output_folder / "timestamps.txt" - frame_ids = sorted(self.timestamps.keys()) - - # sanity check of frame ids in reconstruction and timestamps - recon_frame_ids = np.array(sorted(self.reconstruction.frames.keys())) - assert np.array_equal(np.array(frame_ids), recon_frame_ids), ( - "Frame IDs in reconstruction and timestamps do not match" - ) - - with open(ts_path, "w") as f: - f.write("# FrameID Timestamp(ns)\n") - for frame_id in frame_ids: - f.write(f"{frame_id} {self.timestamps[frame_id]}\n") - - rectified_imu_data_npy = output_folder / "rectified_imu_data.npy" - np.save(rectified_imu_data_npy, self.imu_measurements.data) From 59da348749133ba37c7431a8c30a72b4860a894a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:56:13 +0200 Subject: [PATCH 455/665] vi recons --- lamaria/structs/vi_reconstruction.py | 87 ++++++++++++++++++++++++++++ 1 file changed, 87 insertions(+) create mode 100644 lamaria/structs/vi_reconstruction.py diff --git a/lamaria/structs/vi_reconstruction.py b/lamaria/structs/vi_reconstruction.py new file mode 100644 index 0000000..d2de4f6 --- /dev/null +++ b/lamaria/structs/vi_reconstruction.py @@ -0,0 +1,87 @@ +from pathlib import Path + +import numpy as np +import pycolmap + + +class VIReconstruction: + """Custom class to hold COLMAP reconstruction data along with + timestamps and IMU measurements. + + Attributes: + reconstruction (pycolmap.Reconstruction): + The COLMAP reconstruction object. This object contains all the + 3D points, cameras (intrinsics, extrinsics), and images. + Additionally holds a dummy camera, with no associated images, + to serve as a placeholder for the IMU. + + timestamps (dict[int, int]): A dictionary mapping reconstruction + frame IDs to their corresponding timestamps in nanoseconds. + + imu_measurements (pycolmap.ImuMeasurements): The factory/online + rectified IMU measurements generated from input VRS file. + """ + + def __init__(self) -> None: + self.reconstruction = pycolmap.Reconstruction() + self.timestamps: dict[int, int] = {} + self.imu_measurements = None + + @staticmethod + def read( + input_folder: Path, + ) -> "VIReconstruction": + assert input_folder.exists(), ( + f"Input folder {input_folder} does not exist" + ) + instance = VIReconstruction() + instance.reconstruction = pycolmap.Reconstruction(input_folder) + + ts_path = input_folder / "timestamps.txt" + assert ts_path.exists(), ( + f"Timestamps file {ts_path} does not exist in {input_folder}" + ) + with open(ts_path) as f: + lines = f.readlines() + instance.timestamps = {} + for line in lines: + if line.startswith("#"): + continue + frame_id, ts = line.strip().split() + instance.timestamps[int(frame_id)] = int(ts) + + rectified_imu_data_npy = input_folder / "rectified_imu_data.npy" + assert rectified_imu_data_npy.exists(), ( + f"Rectified IMU data file {rectified_imu_data_npy} \ + does not exist in {input_folder}" + ) + rectified_imu_data = np.load(rectified_imu_data_npy, allow_pickle=True) + instance.imu_measurements = pycolmap.ImuMeasurements( + rectified_imu_data.tolist() + ) + + return instance + + def write( + self, + output_folder: Path, + ) -> None: + output_folder.mkdir(parents=True, exist_ok=True) + self.reconstruction.write(output_folder.as_posix()) + + ts_path = output_folder / "timestamps.txt" + frame_ids = sorted(self.timestamps.keys()) + + # sanity check of frame ids in reconstruction and timestamps + recon_frame_ids = np.array(sorted(self.reconstruction.frames.keys())) + assert np.array_equal(np.array(frame_ids), recon_frame_ids), ( + "Frame IDs in reconstruction and timestamps do not match" + ) + + with open(ts_path, "w") as f: + f.write("# FrameID Timestamp(ns)\n") + for frame_id in frame_ids: + f.write(f"{frame_id} {self.timestamps[frame_id]}\n") + + rectified_imu_data_npy = output_folder / "rectified_imu_data.npy" + np.save(rectified_imu_data_npy, self.imu_measurements.data) From 2677fa1bbf0f2d89ba38db2d93fbbd509bb22938 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:56:39 +0200 Subject: [PATCH 456/665] vi recons --- ..._lamaria_reconstruction.py => to_vi_reconstruction.py} | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) rename lamaria/pipeline/keyframing/{to_lamaria_reconstruction.py => to_vi_reconstruction.py} (98%) diff --git a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py similarity index 98% rename from lamaria/pipeline/keyframing/to_lamaria_reconstruction.py rename to lamaria/pipeline/keyframing/to_vi_reconstruction.py index 36c5588..63a679c 100644 --- a/lamaria/pipeline/keyframing/to_lamaria_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -13,7 +13,7 @@ from ...structs.estimate import ( Estimate, ) -from ...structs.lamaria_reconstruction import LamariaReconstruction +from ...structs.vi_reconstruction import VIReconstruction from ...utils.aria import ( camera_colmap_from_calib, extract_images_from_vrs, @@ -42,7 +42,7 @@ class EstimateToLamaria: def __init__(self, options: EstimateToLamariaOptions): self.options = options - self.data: LamariaReconstruction = LamariaReconstruction() + self.data: VIReconstruction = VIReconstruction() self._vrs_provider = None self._mps_data_provider = None self._left_cam_sid: StreamId | None = None @@ -57,7 +57,7 @@ def convert( images_path: Path, estimate: Path | None = None, mps_folder: Path | None = None, - ) -> LamariaReconstruction: + ) -> VIReconstruction: """Entry point to run estimate/MPS to colmap conversion.""" to_colmap = EstimateToLamaria(options) return to_colmap.process(vrs, images_path, estimate, mps_folder) @@ -68,7 +68,7 @@ def process( images_path: Path, estimate: Path | None = None, mps_folder: Path | None = None, - ) -> LamariaReconstruction: + ) -> VIReconstruction: self._init_data(vrs, images_path, estimate, mps_folder) if self.options.mps.use_online_calibration: From 3aa615035ee4cb0813fe12bd16b780d131a93f0a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:59:24 +0200 Subject: [PATCH 457/665] renaming --- run_pipeline.py | 42 +++++++++++++++++++++--------------------- 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index 712e69e..b15d221 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -12,13 +12,13 @@ ) from lamaria.config.pipeline import PipelineOptions from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector -from lamaria.pipeline.keyframing.to_lamaria_reconstruction import ( +from lamaria.pipeline.keyframing.to_vi_reconstruction import ( EstimateToLamaria, ) from lamaria.pipeline.optim.session import SingleSeqSession from lamaria.pipeline.optim.triangulation import run as triangulate from lamaria.pipeline.optim.vi_optimization import VIOptimizer -from lamaria.structs.lamaria_reconstruction import LamariaReconstruction +from lamaria.structs.vi_reconstruction import VIReconstruction def run_estimate_to_lamaria( @@ -27,12 +27,12 @@ def run_estimate_to_lamaria( images_path: Path, estimate: Path, colmap_model_path: Path, -) -> LamariaReconstruction: +) -> VIReconstruction: """Function to convert a general input - estimate file to a LamariaReconstruction. + estimate file to a VIReconstruction. """ if colmap_model_path.exists(): - lamaria_recon = LamariaReconstruction.read(colmap_model_path) + lamaria_recon = VIReconstruction.read(colmap_model_path) return lamaria_recon colmap_model_path.mkdir(parents=True, exist_ok=True) @@ -54,10 +54,10 @@ def run_mps_to_lamaria( images_path: Path, mps_folder: Path, colmap_model_path: Path, -) -> LamariaReconstruction: - """Function to convert MPS estimate to a LamariaReconstruction.""" +) -> VIReconstruction: + """Function to convert MPS estimate to a VIReconstruction.""" if colmap_model_path.exists(): - lamaria_recon = LamariaReconstruction.read(colmap_model_path) + lamaria_recon = VIReconstruction.read(colmap_model_path) return lamaria_recon colmap_model_path.mkdir(parents=True, exist_ok=True) @@ -75,18 +75,18 @@ def run_mps_to_lamaria( def run_keyframe_selection( options: KeyframeSelectorOptions, - input: Path | LamariaReconstruction, + input: Path | VIReconstruction, images_path: Path, keyframes_path: Path, kf_model_path: Path, -) -> LamariaReconstruction: +) -> VIReconstruction: if isinstance(input, Path): - input_recon = LamariaReconstruction.read(input) + input_recon = VIReconstruction.read(input) else: input_recon = input if kf_model_path.exists(): - kf_lamaria_recon = LamariaReconstruction.read(kf_model_path) + kf_lamaria_recon = VIReconstruction.read(kf_model_path) return kf_lamaria_recon kf_model_path.mkdir(parents=True, exist_ok=True) @@ -105,19 +105,19 @@ def run_keyframe_selection( def run_triangulation( options: TriangulatorOptions, - input: Path, # path to LamariaReconstruction + input: Path, # path to VIReconstruction keyframes_path: Path, hloc_path: Path, pairs_file: Path, tri_model_path: Path, -) -> LamariaReconstruction: +) -> VIReconstruction: if not isinstance(input, Path): raise ValueError("Input must be a Path to the reconstruction") assert input.exists(), f"input reconstruction path {input} does not exist" if tri_model_path.exists(): - tri_lamaria_recon = LamariaReconstruction.read(tri_model_path) + tri_lamaria_recon = VIReconstruction.read(tri_model_path) return tri_lamaria_recon triangulated_model_path = triangulate( @@ -129,10 +129,10 @@ def run_triangulation( tri_model_path, ) - input_lamaria_recon = LamariaReconstruction.read(input) + input_lamaria_recon = VIReconstruction.read(input) tri_recon = pycolmap.Reconstruction(triangulated_model_path) - tri_lamaria_recon = LamariaReconstruction() + tri_lamaria_recon = VIReconstruction() tri_lamaria_recon.reconstruction = tri_recon tri_lamaria_recon.timestamps = input_lamaria_recon.timestamps tri_lamaria_recon.imu_measurements = input_lamaria_recon.imu_measurements @@ -144,9 +144,9 @@ def run_triangulation( def run_optimization( vi_options: VIOptimizerOptions, triangulator_options: TriangulatorOptions, - input: Path, # path to LamariaReconstruction + input: Path, # path to VIReconstruction optim_model_path: Path, -) -> LamariaReconstruction: +) -> VIReconstruction: if not isinstance(input, Path): raise ValueError("Input must be a Path to the reconstruction") @@ -162,7 +162,7 @@ def run_optimization( db_dst = optim_model_path / "database.db" shutil.copy(db_path, db_dst) - init_lamaria_recon = LamariaReconstruction.read(input) + init_lamaria_recon = VIReconstruction.read(input) session = SingleSeqSession( vi_options.imu, init_lamaria_recon, @@ -172,7 +172,7 @@ def run_optimization( vi_options, triangulator_options, session, db_dst ) - optim_lamaria_recon = LamariaReconstruction() + optim_lamaria_recon = VIReconstruction() optim_lamaria_recon.reconstruction = optimized_recon optim_lamaria_recon.timestamps = init_lamaria_recon.timestamps optim_lamaria_recon.imu_measurements = init_lamaria_recon.imu_measurements From df103b43b84ace6f54c1650dc48d319e9d36d595 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 17:59:55 +0200 Subject: [PATCH 458/665] virecons --- lamaria/pipeline/optim/session.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/pipeline/optim/session.py b/lamaria/pipeline/optim/session.py index 21cc7df..7a7b04b 100644 --- a/lamaria/pipeline/optim/session.py +++ b/lamaria/pipeline/optim/session.py @@ -4,7 +4,7 @@ import pycolmap from ...config.options import OptIMUOptions -from ...structs.lamaria_reconstruction import LamariaReconstruction +from ...structs.vi_reconstruction import VIReconstruction from .imu import ( initialize_imu_states, preintegrate_imu_measurements, @@ -15,7 +15,7 @@ class SingleSeqSession: def __init__( self, imu_options: OptIMUOptions, - data: LamariaReconstruction, + data: VIReconstruction, ): self.data = data self._init_imu_data(imu_options) From 720559bf84c04e4272cd74084666d30eedeecbe1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 18:00:10 +0200 Subject: [PATCH 459/665] vi reconstruction --- lamaria/pipeline/optim/imu.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index da40a8a..0d82cdd 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -4,13 +4,13 @@ from tqdm import tqdm from ...config.options import OptIMUOptions -from ...structs.lamaria_reconstruction import LamariaReconstruction +from ...structs.vi_reconstruction import VIReconstruction from .session import SingleSeqSession def preintegrate_imu_measurements( options: OptIMUOptions, - data: LamariaReconstruction, + data: VIReconstruction, ) -> dict[int, pycolmap.PreintegratedImuMeasurement]: preintegrated_measurements = {} @@ -52,7 +52,7 @@ def preintegrate_imu_measurements( def initialize_imu_states( - data: LamariaReconstruction, + data: VIReconstruction, ) -> dict[int, pycolmap.ImuState]: imu_states = {} From 475c5008173187d71179e8f13e406f854ceb22b2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 18:01:08 +0200 Subject: [PATCH 460/665] keyframe selection --- lamaria/pipeline/keyframing/keyframe_selection.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index d38ae8e..61915a8 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -8,33 +8,33 @@ import pycolmap from ...config.options import KeyframeSelectorOptions -from ...structs.lamaria_reconstruction import LamariaReconstruction +from ...structs.vi_reconstruction import VIReconstruction from ...utils.aria import get_magnitude_from_transform class KeyframeSelector: - """Class to perform keyframe selection on a LamariaReconstruction object.""" + """Class to perform keyframe selection on a VIReconstruction object.""" def __init__( self, options: KeyframeSelectorOptions, - data: LamariaReconstruction, + data: VIReconstruction, ): self.options = options self.init_data = data self.init_recons = data.reconstruction # pycolmap.Reconstruction self.timestamps = data.timestamps # frame id to timestamp mapping - self.keyframed_data = LamariaReconstruction() + self.keyframed_data = VIReconstruction() self.keyframe_frame_ids: dict[int, int] = {} @staticmethod def run( options: KeyframeSelectorOptions, - data: LamariaReconstruction, + data: VIReconstruction, images_path: Path, keyframes_path: Path, - ) -> LamariaReconstruction: + ) -> VIReconstruction: """Entry point to run keyframing and copy keyframes into keyframe directory. """ @@ -215,7 +215,7 @@ def _build_online_keyframed_reconstruction(self): for img in images_to_add: self.keyframed_data.reconstruction.add_image(img) - def run_keyframing(self) -> LamariaReconstruction: + def run_keyframing(self) -> VIReconstruction: """Function to run keyframing on lamaria reconstruction.""" self._select_keyframes() if len(self.init_recons.rigs.keys()) == 1: # device rig has been added From d36f20935ad36136a9a532cc138a660a448dcd8c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 18:12:40 +0200 Subject: [PATCH 461/665] vi recon naming upd --- run_pipeline.py | 62 ++++++++++++++++++++++++------------------------- 1 file changed, 31 insertions(+), 31 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index b15d221..158dbd8 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -32,20 +32,20 @@ def run_estimate_to_lamaria( estimate file to a VIReconstruction. """ if colmap_model_path.exists(): - lamaria_recon = VIReconstruction.read(colmap_model_path) - return lamaria_recon + vi_recon = VIReconstruction.read(colmap_model_path) + return vi_recon colmap_model_path.mkdir(parents=True, exist_ok=True) - lamaria_recon = EstimateToLamaria.convert( + vi_recon = EstimateToLamaria.convert( options, vrs, images_path, estimate, ) - lamaria_recon.write(colmap_model_path) + vi_recon.write(colmap_model_path) - return lamaria_recon + return vi_recon def run_mps_to_lamaria( @@ -57,20 +57,20 @@ def run_mps_to_lamaria( ) -> VIReconstruction: """Function to convert MPS estimate to a VIReconstruction.""" if colmap_model_path.exists(): - lamaria_recon = VIReconstruction.read(colmap_model_path) - return lamaria_recon + vi_recon = VIReconstruction.read(colmap_model_path) + return vi_recon colmap_model_path.mkdir(parents=True, exist_ok=True) - lamaria_recon = EstimateToLamaria.convert( + vi_recon = EstimateToLamaria.convert( options, vrs, images_path, mps_folder, ) - lamaria_recon.write(colmap_model_path) + vi_recon.write(colmap_model_path) - return lamaria_recon + return vi_recon def run_keyframe_selection( @@ -86,21 +86,21 @@ def run_keyframe_selection( input_recon = input if kf_model_path.exists(): - kf_lamaria_recon = VIReconstruction.read(kf_model_path) - return kf_lamaria_recon + kf_vi_recon = VIReconstruction.read(kf_model_path) + return kf_vi_recon kf_model_path.mkdir(parents=True, exist_ok=True) - kf_lamaria_recon = KeyframeSelector.run( + kf_vi_recon = KeyframeSelector.run( options, input_recon, images_path, keyframes_path, ) - kf_lamaria_recon.write(kf_model_path) + kf_vi_recon.write(kf_model_path) - return kf_lamaria_recon + return kf_vi_recon def run_triangulation( @@ -117,8 +117,8 @@ def run_triangulation( assert input.exists(), f"input reconstruction path {input} does not exist" if tri_model_path.exists(): - tri_lamaria_recon = VIReconstruction.read(tri_model_path) - return tri_lamaria_recon + tri_vi_recon = VIReconstruction.read(tri_model_path) + return tri_vi_recon triangulated_model_path = triangulate( options, @@ -129,16 +129,16 @@ def run_triangulation( tri_model_path, ) - input_lamaria_recon = VIReconstruction.read(input) + input_vi_recon = VIReconstruction.read(input) tri_recon = pycolmap.Reconstruction(triangulated_model_path) - tri_lamaria_recon = VIReconstruction() - tri_lamaria_recon.reconstruction = tri_recon - tri_lamaria_recon.timestamps = input_lamaria_recon.timestamps - tri_lamaria_recon.imu_measurements = input_lamaria_recon.imu_measurements - tri_lamaria_recon.write(triangulated_model_path) + tri_vi_recon = VIReconstruction() + tri_vi_recon.reconstruction = tri_recon + tri_vi_recon.timestamps = input_vi_recon.timestamps + tri_vi_recon.imu_measurements = input_vi_recon.imu_measurements + tri_vi_recon.write(triangulated_model_path) - return tri_lamaria_recon + return tri_vi_recon def run_optimization( @@ -162,21 +162,21 @@ def run_optimization( db_dst = optim_model_path / "database.db" shutil.copy(db_path, db_dst) - init_lamaria_recon = VIReconstruction.read(input) + init_vi_recon = VIReconstruction.read(input) session = SingleSeqSession( vi_options.imu, - init_lamaria_recon, + init_vi_recon, ) optimized_recon = VIOptimizer.optimize( vi_options, triangulator_options, session, db_dst ) - optim_lamaria_recon = VIReconstruction() - optim_lamaria_recon.reconstruction = optimized_recon - optim_lamaria_recon.timestamps = init_lamaria_recon.timestamps - optim_lamaria_recon.imu_measurements = init_lamaria_recon.imu_measurements - optim_lamaria_recon.write(optim_model_path) + optim_vi_recon = VIReconstruction() + optim_vi_recon.reconstruction = optimized_recon + optim_vi_recon.timestamps = init_vi_recon.timestamps + optim_vi_recon.imu_measurements = init_vi_recon.imu_measurements + optim_vi_recon.write(optim_model_path) def run_pipeline( From acb9932b9c0e40ff324f273e08a09d039958bc79 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 18:16:30 +0200 Subject: [PATCH 462/665] vi recon --- lamaria/config/options.py | 4 ++-- lamaria/config/pipeline.py | 10 +++++----- lamaria/pipeline/keyframing/to_vi_reconstruction.py | 10 +++++----- run_pipeline.py | 12 ++++++------ 4 files changed, 18 insertions(+), 18 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 31a0df6..43f7931 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -52,7 +52,7 @@ def load(cls, cfg: OmegaConf | None = None) -> SensorOptions: # Estimate to COLMAP options @dataclass(slots=True) -class EstimateToLamariaOptions: +class EstimateToVIReconOptions: mps: MPSOptions = field(default_factory=MPSOptions) sensor: SensorOptions = field(default_factory=SensorOptions) @@ -61,7 +61,7 @@ def load( cls, cfg_mps: OmegaConf | None = None, cfg_sensor: OmegaConf | None = None, - ) -> EstimateToLamariaOptions: + ) -> EstimateToVIReconOptions: if cfg_mps is None or cfg_sensor is None: return cls() diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 263e3ef..6f12323 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -4,7 +4,7 @@ from omegaconf import DictConfig, OmegaConf from .options import ( - EstimateToLamariaOptions, + EstimateToVIReconOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, @@ -14,8 +14,8 @@ class PipelineOptions: def __init__(self) -> None: self._output_path: Path = Path("output/") - self._estimate_to_colmap_options: EstimateToLamariaOptions = ( - EstimateToLamariaOptions() + self._estimate_to_colmap_options: EstimateToVIReconOptions = ( + EstimateToVIReconOptions() ) self._keyframing_options: KeyframeSelectorOptions = ( KeyframeSelectorOptions() @@ -40,7 +40,7 @@ def load( def _update_from_cfg(self, cfg: DictConfig) -> None: """Update object attributes from a config.""" - self._estimate_to_colmap_options = EstimateToLamariaOptions.load( + self._estimate_to_colmap_options = EstimateToVIReconOptions.load( cfg.mps, cfg.sensor, ) @@ -63,7 +63,7 @@ def output_path(self, path: Path) -> None: # Properties for estimate to COLMAP @property - def estimate_to_colmap_options(self) -> EstimateToLamariaOptions: + def estimate_to_colmap_options(self) -> EstimateToVIReconOptions: return self._estimate_to_colmap_options @property diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 63a679c..5eddbf4 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -9,7 +9,7 @@ from projectaria_tools.core.stream_id import StreamId from ... import logger -from ...config.options import EstimateToLamariaOptions +from ...config.options import EstimateToVIReconOptions from ...structs.estimate import ( Estimate, ) @@ -37,10 +37,10 @@ class PerFrameData: rig_from_world: pycolmap.Rigid3d -class EstimateToLamaria: +class EstimateToVIRecon: """Converts estimate or MPS data to COLMAP format.""" - def __init__(self, options: EstimateToLamariaOptions): + def __init__(self, options: EstimateToVIReconOptions): self.options = options self.data: VIReconstruction = VIReconstruction() self._vrs_provider = None @@ -52,14 +52,14 @@ def __init__(self, options: EstimateToLamariaOptions): @staticmethod def convert( - options: EstimateToLamariaOptions, + options: EstimateToVIReconOptions, vrs: Path, images_path: Path, estimate: Path | None = None, mps_folder: Path | None = None, ) -> VIReconstruction: """Entry point to run estimate/MPS to colmap conversion.""" - to_colmap = EstimateToLamaria(options) + to_colmap = EstimateToVIRecon(options) return to_colmap.process(vrs, images_path, estimate, mps_folder) def process( diff --git a/run_pipeline.py b/run_pipeline.py index 158dbd8..f5938bb 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -5,7 +5,7 @@ import pycolmap from lamaria.config.options import ( - EstimateToLamariaOptions, + EstimateToVIReconOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, @@ -13,7 +13,7 @@ from lamaria.config.pipeline import PipelineOptions from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector from lamaria.pipeline.keyframing.to_vi_reconstruction import ( - EstimateToLamaria, + EstimateToVIRecon, ) from lamaria.pipeline.optim.session import SingleSeqSession from lamaria.pipeline.optim.triangulation import run as triangulate @@ -22,7 +22,7 @@ def run_estimate_to_lamaria( - options: EstimateToLamariaOptions, + options: EstimateToVIReconOptions, vrs: Path, images_path: Path, estimate: Path, @@ -37,7 +37,7 @@ def run_estimate_to_lamaria( colmap_model_path.mkdir(parents=True, exist_ok=True) - vi_recon = EstimateToLamaria.convert( + vi_recon = EstimateToVIRecon.convert( options, vrs, images_path, @@ -49,7 +49,7 @@ def run_estimate_to_lamaria( def run_mps_to_lamaria( - options: EstimateToLamariaOptions, + options: EstimateToVIReconOptions, vrs: Path, images_path: Path, mps_folder: Path, @@ -62,7 +62,7 @@ def run_mps_to_lamaria( colmap_model_path.mkdir(parents=True, exist_ok=True) - vi_recon = EstimateToLamaria.convert( + vi_recon = EstimateToVIRecon.convert( options, vrs, images_path, From 6647ab033183e4c71b60a77a8b3d1cc4759ea4da Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 18:19:29 +0200 Subject: [PATCH 463/665] run pipeline --- run_pipeline.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/run_pipeline.py b/run_pipeline.py index f5938bb..3093df8 100644 --- a/run_pipeline.py +++ b/run_pipeline.py @@ -21,7 +21,7 @@ from lamaria.structs.vi_reconstruction import VIReconstruction -def run_estimate_to_lamaria( +def run_estimate_to_vi_recon( options: EstimateToVIReconOptions, vrs: Path, images_path: Path, @@ -48,7 +48,7 @@ def run_estimate_to_lamaria( return vi_recon -def run_mps_to_lamaria( +def run_mps_to_vi_recon( options: EstimateToVIReconOptions, vrs: Path, images_path: Path, @@ -200,7 +200,7 @@ def run_pipeline( "Estimate path must be provided if not using MPS" ) - _ = run_estimate_to_lamaria( + _ = run_estimate_to_vi_recon( est_options, vrs, options.images_path, @@ -212,7 +212,7 @@ def run_pipeline( "MPS folder path must be provided if using MPS" ) - _ = run_mps_to_lamaria( + _ = run_mps_to_vi_recon( est_options, vrs, options.images_path, From cdb9af05b5b74d2bd235d6c1d945b019d2b26950 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 21:10:00 +0200 Subject: [PATCH 464/665] mv control point --- lamaria/utils/control_point.py | 220 --------------------------------- 1 file changed, 220 deletions(-) delete mode 100644 lamaria/utils/control_point.py diff --git a/lamaria/utils/control_point.py b/lamaria/utils/control_point.py deleted file mode 100644 index 7285f93..0000000 --- a/lamaria/utils/control_point.py +++ /dev/null @@ -1,220 +0,0 @@ -import json -from pathlib import Path - -import numpy as np -import pycolmap -from tqdm import tqdm - -from .constants import ( - CUSTOM_ORIGIN_COORDINATES, -) - - -def construct_control_points_from_json( - cp_json_file: Path, -) -> dict[int, dict[str, object]]: - """ - Construct control points dict from a JSON file. - - Args: - cp_json_file (Path): Path to the sparse GT JSON file. - - Returns: - control_points (dict): Control points dictionary of the form - ``{ tag_id: {"control_point": str, "topo": ndarray(3,), - "covariance": ndarray(3,3)} }``. - """ - with open(cp_json_file) as file: - cp_data = json.load(file) - - control_points = {} - for geo_id, data in cp_data["control_points"].items(): - tag_ids = data["tag_id"] - measurement = data["measurement"] - unc = data["uncertainty"] - - if measurement[2] is None: - assert unc[2] is None, ( - "Uncertainty for z coordinate " - "should be None if measurement is None" - ) - measurement[2] = CUSTOM_ORIGIN_COORDINATES[2] - unc[2] = 1e9 # some large number - - translated_measurement = np.array(measurement) - np.array( - CUSTOM_ORIGIN_COORDINATES - ) - # those without height will have 0 height and large uncertainty in z - - for tag_id in tag_ids: - control_points[tag_id] = { - "control_point": geo_id, - "topo": translated_measurement, - "covariance": np.diag(np.square(unc)), - } - - return control_points - - -def check_3d_error_bet_triang_and_topo(triangulated: list, topo: list): - """Calculate L2 error between triangulated and topo points - Args: - triangulated (list): list of triangulated points - topo (list): list of topocentric points - - Returns: - errors (list): list of L2 errors per point""" - errors = [] - for i in range(len(triangulated)): - errors.append(np.linalg.norm(triangulated[i] - topo[i])) - - return errors - - -def check_2d_error_bet_triang_and_topo(triangulated: list, topo: list): - """Calculate L2 error between triangulated and topo points - Args: - triangulated (list): list of 3d triangulated points - topo (list): list of 3d topocentric points - - Returns: - errors (list): list of 2d L2 errors per point""" - - errors = [] - for i in range(len(triangulated)): - errors.append(np.linalg.norm(triangulated[i][:2] - topo[i][:2])) - - return errors - - -def transform_points(points, r, t, scale): - transformed_points = [] - for point in points: - transformed_point = scale * r.apply(point) + t - transformed_points.append(transformed_point) - - return transformed_points - - -def transform_triangulated_control_points(control_points: dict, r, t, scale): - for _, cp in control_points.items(): - triangulated_point = cp["triangulated"] - triangulated_point = scale * r.apply(triangulated_point) + t - cp["triangulated"] = triangulated_point - - return control_points - - -def run_control_point_triangulation_from_json( - reconstruction_path: Path, - cp_json_file: Path, - control_points: dict, # edits control_points in place -) -> None: - """ - Triangulate control points from JSON file and add to control_points dict. - Updates `control_points` in place to add: - - - ``triangulated``: np.ndarray(3,) or None if triangulation fails - - ``inlier_ratio``: float - - ``image_id_and_point2d``: list of (image_id, [x, y]) tuples - of observations used for triangulation - Args: - reconstruction_path (Path): Path to the reconstruction folder - cp_json_file (Path): Path to the sparse GT JSON file - control_points (dict): Control points dictionary to be updated - """ - rec = pycolmap.Reconstruction(reconstruction_path) - - image_names_to_ids = { - image.name: image_id for image_id, image in rec.images.items() - } - - with open(cp_json_file) as file: - data = json.load(file) - - image_data = data["images"] - control_point_data = data["control_points"] - - for tag_id, cp in tqdm( - control_points.items(), desc="Triangulating control points" - ): - geo_id = cp["control_point"] - images_observing_cp = control_point_data[geo_id]["image_names"] - - pixel_points = [] - cam_from_worlds = [] - cameras = [] - - image_ids_and_centers = [] - - for image_name in images_observing_cp: - if image_name not in image_names_to_ids: - continue - id = image_names_to_ids[image_name] - image = rec.images[id] - detection = image_data[image_name]["detection"] - pixel_points.append(detection) - cam_from_worlds.append(image.cam_from_world()) - cameras.append(rec.cameras[image.camera_id]) - image_ids_and_centers.append((id, detection)) - - # HANDLING THE CASE WHERE NO IMAGES OBSERVE THE CONTROL POINT - if pixel_points == []: - cp["triangulated"] = None - cp["inlier_ratio"] = 0 - cp["image_id_and_point2d"] = [] - continue - - pixel_points = np.array(pixel_points) - try: - output = pycolmap.estimate_triangulation( - pixel_points, - cam_from_worlds, - cameras, - options={ - "residual_type": "REPROJECTION_ERROR", - "ransac": {"max_error": 4.0}, - }, - ) - except Exception as e: - print(f"Error in triangulating control point {geo_id}: {e}") - output = None - - if output is None: - cp["triangulated"] = None - cp["inlier_ratio"] = 0 - cp["image_id_and_point2d"] = [] - continue - - control_points[tag_id]["triangulated"] = output["xyz"] - inliers = output["inliers"] - control_points[tag_id]["inlier_ratio"] = np.sum(inliers) / len(inliers) - image_ids_and_centers = [ - image_ids_and_centers[i] for i in range(len(inliers)) if inliers[i] - ] - control_points[tag_id]["image_id_and_point2d"] = image_ids_and_centers - - -def get_cps_for_initial_alignment(control_points: dict): - """Get control points with z != 0 for initial alignment""" - triangulated_cp_alignment = [] - topo_cp_alignment = [] - for tag_id, cp in control_points.items(): - if cp["triangulated"] is None: - continue - - if cp["topo"][2] != 0: - print( - "Control point %s, %s has z != 0", tag_id, cp["control_point"] - ) - triangulated_cp_alignment.append(cp["triangulated"]) - topo_cp_alignment.append(cp["topo"]) - - if len(topo_cp_alignment) < 3: - print("Not enough control points with z != 0") - return None, None - - triangulated_cp_alignment = np.array(triangulated_cp_alignment) - topo_cp_alignment = np.array(topo_cp_alignment) - - return triangulated_cp_alignment, topo_cp_alignment From 3111204a91cd31513ead2ccada7e92250d202454 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 21:10:23 +0200 Subject: [PATCH 465/665] structs cps --- lamaria/eval/sparse_evaluation.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 7a2c976..0dfffb5 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -14,7 +14,7 @@ get_t_imu_camera_from_json, initialize_reconstruction_from_calibration_file, ) -from ..utils.control_point import ( +from ..structs.control_point import ( construct_control_points_from_json, get_cps_for_initial_alignment, run_control_point_triangulation_from_json, From 9f3175b5dd312a2594aa1e5a809df905d032d404 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 21:11:40 +0200 Subject: [PATCH 466/665] mv --- lamaria/eval/sparse_evaluation.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 0dfffb5..473a90d 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -9,16 +9,16 @@ import pycolmap.cost_functions from .. import logger -from ..structs.estimate import Estimate -from ..utils.aria import ( - get_t_imu_camera_from_json, - initialize_reconstruction_from_calibration_file, -) from ..structs.control_point import ( construct_control_points_from_json, get_cps_for_initial_alignment, run_control_point_triangulation_from_json, ) +from ..structs.estimate import Estimate +from ..utils.aria import ( + get_t_imu_camera_from_json, + initialize_reconstruction_from_calibration_file, +) def update_sim3d_scale(variables: dict) -> None: @@ -173,7 +173,8 @@ def run( device_calibration_json (Path): Path to the device calibration JSON. output_path (Path): Directory where intermediate data and evaluation results will be saved. - corresponding_sensor (str): The reference sensor to use ("imu" or "cam0"). + corresponding_sensor (str): The reference sensor to use + ("imu" or "cam0"). cp_reproj_std (float, optional): Control point reprojection standard deviation. Defaults to 1.0. From 75791684425f9ee1d2ac8996a823d06aeefe2cba Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 21:18:35 +0200 Subject: [PATCH 467/665] fix circular import --- lamaria/pipeline/optim/imu.py | 80 ----------------- lamaria/pipeline/optim/iterative_global_ba.py | 2 +- lamaria/pipeline/optim/residual.py | 85 +++++++++++++++++++ 3 files changed, 86 insertions(+), 81 deletions(-) create mode 100644 lamaria/pipeline/optim/residual.py diff --git a/lamaria/pipeline/optim/imu.py b/lamaria/pipeline/optim/imu.py index 0d82cdd..d87c04f 100644 --- a/lamaria/pipeline/optim/imu.py +++ b/lamaria/pipeline/optim/imu.py @@ -1,11 +1,9 @@ import numpy as np -import pyceres import pycolmap from tqdm import tqdm from ...config.options import OptIMUOptions from ...structs.vi_reconstruction import VIReconstruction -from .session import SingleSeqSession def preintegrate_imu_measurements( @@ -109,81 +107,3 @@ def load_imu_calibration( imu_calib.imu_rate = 1000.0 return imu_calib - - -def add_imu_residuals_to_problem( - imu_options: OptIMUOptions, - session: SingleSeqSession, - problem, -): - loss = pyceres.TrivialLoss() - - frame_ids = sorted(session.data.reconstruction.frames.keys()) - - for k in tqdm( - range(len(session.preintegrated_imu_measurements)), - desc="Adding IMU residuals", - ): - i = frame_ids[k] - j = frame_ids[k + 1] - frame_i = session.data.reconstruction.frames[i] - frame_j = session.data.reconstruction.frames[j] - i_from_world = frame_i.rig_from_world - j_from_world = frame_j.rig_from_world - - integrated_m = session.preintegrated_imu_measurements[i] - - problem.add_residual_block( - pycolmap.PreintegratedImuMeasurementCost(integrated_m), - loss, - [ - session.imu_from_rig.rotation.quat, - session.imu_from_rig.translation, - session.log_scale, - session.gravity, - i_from_world.rotation.quat, - i_from_world.translation, - session.imu_states[i].data, - j_from_world.rotation.quat, - j_from_world.translation, - session.imu_states[j].data, - ], - ) - - problem = setup_manifolds_and_constraints( - imu_options, - session, - problem, - ) - - return problem - - -def setup_manifolds_and_constraints( - imu_options: OptIMUOptions, - session: SingleSeqSession, - problem, -): - """Setup manifolds and parameter constraints""" - problem.set_manifold(session.gravity, pyceres.SphereManifold(3)) - problem.set_manifold( - session.imu_from_rig.rotation.quat, pyceres.EigenQuaternionManifold() - ) - - # Apply optimization constraints based on configuration - if not imu_options.optimize_scale: - problem.set_parameter_block_constant(session.log_scale) - if not imu_options.optimize_gravity: - problem.set_parameter_block_constant(session.gravity) - if not imu_options.optimize_imu_from_rig: - problem.set_parameter_block_constant(session.imu_from_rig.rotation.quat) - problem.set_parameter_block_constant(session.imu_from_rig.translation) - if not imu_options.optimize_bias: - constant_idxs = np.arange(3, 9) - for frame_id in session.imu_states: - problem.set_manifold( - session.imu_states[frame_id].data, - pyceres.SubsetManifold(9, constant_idxs), - ) - - return problem diff --git a/lamaria/pipeline/optim/iterative_global_ba.py b/lamaria/pipeline/optim/iterative_global_ba.py index 9c9a8b2..d6523db 100644 --- a/lamaria/pipeline/optim/iterative_global_ba.py +++ b/lamaria/pipeline/optim/iterative_global_ba.py @@ -5,7 +5,7 @@ from ... import logger from ...config.options import VIOptimizerOptions from .callback import RefinementCallback -from .imu import add_imu_residuals_to_problem +from .residual import add_imu_residuals_to_problem from .session import SingleSeqSession diff --git a/lamaria/pipeline/optim/residual.py b/lamaria/pipeline/optim/residual.py new file mode 100644 index 0000000..8e429a3 --- /dev/null +++ b/lamaria/pipeline/optim/residual.py @@ -0,0 +1,85 @@ +import pyceres +from tqdm import tqdm +import numpy as np +import pycolmap + +from ...config.options import OptIMUOptions +from .session import SingleSeqSession + + +def add_imu_residuals_to_problem( + imu_options: OptIMUOptions, + session: SingleSeqSession, + problem, +): + loss = pyceres.TrivialLoss() + + frame_ids = sorted(session.data.reconstruction.frames.keys()) + + for k in tqdm( + range(len(session.preintegrated_imu_measurements)), + desc="Adding IMU residuals", + ): + i = frame_ids[k] + j = frame_ids[k + 1] + frame_i = session.data.reconstruction.frames[i] + frame_j = session.data.reconstruction.frames[j] + i_from_world = frame_i.rig_from_world + j_from_world = frame_j.rig_from_world + + integrated_m = session.preintegrated_imu_measurements[i] + + problem.add_residual_block( + pycolmap.PreintegratedImuMeasurementCost(integrated_m), + loss, + [ + session.imu_from_rig.rotation.quat, + session.imu_from_rig.translation, + session.log_scale, + session.gravity, + i_from_world.rotation.quat, + i_from_world.translation, + session.imu_states[i].data, + j_from_world.rotation.quat, + j_from_world.translation, + session.imu_states[j].data, + ], + ) + + problem = setup_manifolds_and_constraints( + imu_options, + session, + problem, + ) + + return problem + + +def setup_manifolds_and_constraints( + imu_options: OptIMUOptions, + session: SingleSeqSession, + problem, +): + """Setup manifolds and parameter constraints""" + problem.set_manifold(session.gravity, pyceres.SphereManifold(3)) + problem.set_manifold( + session.imu_from_rig.rotation.quat, pyceres.EigenQuaternionManifold() + ) + + # Apply optimization constraints based on configuration + if not imu_options.optimize_scale: + problem.set_parameter_block_constant(session.log_scale) + if not imu_options.optimize_gravity: + problem.set_parameter_block_constant(session.gravity) + if not imu_options.optimize_imu_from_rig: + problem.set_parameter_block_constant(session.imu_from_rig.rotation.quat) + problem.set_parameter_block_constant(session.imu_from_rig.translation) + if not imu_options.optimize_bias: + constant_idxs = np.arange(3, 9) + for frame_id in session.imu_states: + problem.set_manifold( + session.imu_states[frame_id].data, + pyceres.SubsetManifold(9, constant_idxs), + ) + + return problem \ No newline at end of file From 71ffb66d5547ae4a275c0791875eaeec25b9b8ab Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 21:19:23 +0200 Subject: [PATCH 468/665] to vi --- lamaria/pipeline/keyframing/to_vi_reconstruction.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 5eddbf4..c5f17b0 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -136,8 +136,8 @@ def _init_data( images, timestamps, mps_poses ) else: - est = Estimate(invert_poses=True) - est.load_from_file(estimate) + est = Estimate() + est.load_from_file(estimate, invert_poses=True) timestamps = est.timestamps if len(images) != len(timestamps): From a31a17b4f0e2a64bf118dc140ee0d0666c9a2182 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 21:27:10 +0200 Subject: [PATCH 469/665] fix --- lamaria/structs/estimate.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index f317266..c9122e5 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -178,6 +178,8 @@ def _parse(self, lines: list[str]) -> None: self._timestamps = ts_list self._poses = pose_list + return True + def _add_images_to_reconstruction( self, reconstruction: pycolmap.Reconstruction, From 533b10a5db2ba37814549b809fa44f2a2a54323d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 21:30:36 +0200 Subject: [PATCH 470/665] vi opt --- run_pipeline.py => example_vi_optimization.py | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename run_pipeline.py => example_vi_optimization.py (100%) diff --git a/run_pipeline.py b/example_vi_optimization.py similarity index 100% rename from run_pipeline.py rename to example_vi_optimization.py From f2b4756c1402702bb63d59fb390a6789642ec787 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Sun, 28 Sep 2025 21:33:12 +0200 Subject: [PATCH 471/665] ruff --- lamaria/pipeline/optim/residual.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/lamaria/pipeline/optim/residual.py b/lamaria/pipeline/optim/residual.py index 8e429a3..7b11c5e 100644 --- a/lamaria/pipeline/optim/residual.py +++ b/lamaria/pipeline/optim/residual.py @@ -1,7 +1,7 @@ -import pyceres -from tqdm import tqdm import numpy as np +import pyceres import pycolmap +from tqdm import tqdm from ...config.options import OptIMUOptions from .session import SingleSeqSession @@ -82,4 +82,4 @@ def setup_manifolds_and_constraints( pyceres.SubsetManifold(9, constant_idxs), ) - return problem \ No newline at end of file + return problem From aeba49d436b9f6c578b6e14ca7e8d72482e4595d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 00:19:25 +0200 Subject: [PATCH 472/665] timestamps --- .../{synchronization.py => timestamps.py} | 24 +++++++++++++++++++ 1 file changed, 24 insertions(+) rename lamaria/utils/{synchronization.py => timestamps.py} (71%) diff --git a/lamaria/utils/synchronization.py b/lamaria/utils/timestamps.py similarity index 71% rename from lamaria/utils/synchronization.py rename to lamaria/utils/timestamps.py index 6e9580c..3d6e181 100644 --- a/lamaria/utils/synchronization.py +++ b/lamaria/utils/timestamps.py @@ -1,4 +1,28 @@ from bisect import bisect_left +from pathlib import Path +import json + +from .constants import ( + LEFT_CAMERA_STREAM_LABEL, + RIGHT_CAMERA_STREAM_LABEL, +) + + +def get_timestamp_data_from_json( + json_file: str | Path, +): + with open(json_file, "r") as f: + data = json.load(f) + + processed_ts_data = {} + for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: + ts_data = data["timestamps"][label] + processed_ts_data[label] = {int(k): v for k, v in ts_data.items()} + processed_ts_data[label]["sorted_keys"] = sorted( + processed_ts_data[label].keys() + ) + + return processed_ts_data def find_closest_timestamp( From 61b5a6d61374060cfb489eb33c13bb808be9479f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 00:19:45 +0200 Subject: [PATCH 473/665] timestamps --- lamaria/utils/aria.py | 2 +- tools/vrs_to_asl_folder.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index b703113..0629d91 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -14,7 +14,7 @@ from .. import logger from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID -from .synchronization import find_closest_timestamp +from .timestamps import find_closest_timestamp # ----- Reconstruction functions ----- # diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index 2d03779..dc09cd9 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -14,7 +14,7 @@ RIGHT_CAMERA_STREAM_ID, RIGHT_IMU_STREAM_ID, ) -from lamaria.utils.synchronization import ( +from lamaria.utils.timestamps import ( get_matched_timestamps, ) From 6480840b9ae40ecdef69b3ae5e2332137e3ab1fb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 00:21:19 +0200 Subject: [PATCH 474/665] func --- lamaria/utils/timestamps.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/utils/timestamps.py b/lamaria/utils/timestamps.py index 3d6e181..9834aa1 100644 --- a/lamaria/utils/timestamps.py +++ b/lamaria/utils/timestamps.py @@ -8,7 +8,7 @@ ) -def get_timestamp_data_from_json( +def get_timestamp_to_images_from_json( json_file: str | Path, ): with open(json_file, "r") as f: From 67d052f21a9c3d336ae30d2a7b3c884f38d2ea58 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 00:22:47 +0200 Subject: [PATCH 475/665] estimate upd --- lamaria/structs/estimate.py | 29 +++++++++++------------------ 1 file changed, 11 insertions(+), 18 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index c9122e5..ce9902e 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -12,7 +12,7 @@ LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL, ) -from ..utils.synchronization import ( +from ..utils.timestamps import ( find_closest_timestamp, ) @@ -42,13 +42,15 @@ def __init__(self) -> None: self._timestamps: list[int] = [] self._poses: list[pycolmap.Rigid3d] = [] + @classmethod def load_from_file( - self, + cls, path: str | Path, invert_poses: bool = True, corresponding_sensor: str = "imu", ) -> None: """Parse the file, validate format, populate timestamps & poses.""" + self = cls() self.clear() self.path = Path(path) self.invert_poses = invert_poses @@ -67,7 +69,7 @@ def load_from_file( def add_estimate_poses_to_reconstruction( self, reconstruction: pycolmap.Reconstruction, - cp_json_file: Path, + timestamp_to_images: dict, sensor_from_rig: pycolmap.Rigid3d, output_path: Path, ) -> Path: @@ -82,7 +84,9 @@ def add_estimate_poses_to_reconstruction( shutil.rmtree(recon_path) reconstruction = self._add_images_to_reconstruction( - reconstruction, cp_json_file, sensor_from_rig + reconstruction, + timestamp_to_images, + sensor_from_rig ) reconstruction.write(recon_path.as_posix()) @@ -183,27 +187,16 @@ def _parse(self, lines: list[str]) -> None: def _add_images_to_reconstruction( self, reconstruction: pycolmap.Reconstruction, - cp_json_file: Path, + timestamp_to_images: dict, sensor_from_rig: pycolmap.Rigid3d, ) -> pycolmap.Reconstruction: pose_data = self.as_tuples() - with open(cp_json_file) as f: - cp_data = json.load(f) - image_id = 1 rig = reconstruction.rig(rig_id=1) transform = sensor_from_rig.inverse() - ts_data_processed = {} - for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: - ts_data = cp_data["timestamps"][label] - ts_data_processed[label] = {int(k): v for k, v in ts_data.items()} - ts_data_processed[label]["sorted_keys"] = sorted( - ts_data_processed[label].keys() - ) - for i, (timestamp, pose) in tqdm( enumerate(pose_data), total=len(pose_data), @@ -227,7 +220,7 @@ def _add_images_to_reconstruction( (LEFT_CAMERA_STREAM_LABEL, 1), (RIGHT_CAMERA_STREAM_LABEL, 2), ]: - source_timestamps = ts_data_processed[label]["sorted_keys"] + source_timestamps = timestamp_to_images[label]["sorted_keys"] # offsets upto 1 ms (1e6 ns) closest_timestamp = find_closest_timestamp( source_timestamps, timestamp, max_diff=1e6 @@ -235,7 +228,7 @@ def _add_images_to_reconstruction( if closest_timestamp is None: raise ValueError - image_name = ts_data_processed[label][closest_timestamp] + image_name = timestamp_to_images[label][closest_timestamp] im = pycolmap.Image( image_name, From 71e881bd49f597ca58cee8c39c35514f8644e46b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 00:23:04 +0200 Subject: [PATCH 476/665] timestamp naming --- lamaria/pipeline/keyframing/to_vi_reconstruction.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index c5f17b0..4a2d74e 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -23,7 +23,7 @@ get_t_imu_camera, rigid3d_from_transform, ) -from ...utils.synchronization import ( +from ...utils.timestamps import ( get_matched_timestamps, ) From ff08e4536a900aa2b17347d1f9b420f4caff02a7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 00:38:47 +0200 Subject: [PATCH 477/665] cps struct --- lamaria/structs/control_point.py | 216 +++++++++++++++++++++++++++++++ 1 file changed, 216 insertions(+) create mode 100644 lamaria/structs/control_point.py diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py new file mode 100644 index 0000000..ec572c6 --- /dev/null +++ b/lamaria/structs/control_point.py @@ -0,0 +1,216 @@ +import json +from pathlib import Path +from dataclasses import dataclass, field + +import numpy as np +import pycolmap +from tqdm import tqdm + +from .. import logger +from ..utils.constants import ( + CUSTOM_ORIGIN_COORDINATES, +) + +ControlPoints = dict[int, "ControlPoint"] + +@dataclass(slots=True) +class ControlPoint: + name: str # geo_id + topo: np.ndarray + covariance: np.ndarray + + triangulated: np.ndarray | None = None # None if triangulation fails + inlier_ratio: float = 0.0 + image_id_and_point2d: list[tuple[int, np.ndarray]] = field(default_factory=list) + + @staticmethod + def from_measurement( + name: str, + measurement_xyz: list[float | None], + unc_xyz: list[float | None], + origin_xyz: tuple[float, float, float], + ) -> "ControlPoint": + + m = list(measurement_xyz) + u = list(unc_xyz) + if m[2] is None: + assert u[2] is None, "If z is None, its uncertainty must be None." + m[2] = origin_xyz[2] + u[2] = 1e9 # very uncertain height + + # translated measurement to have smaller numerical values + topo = np.asarray(m, dtype=np.float64) - np.asarray(origin_xyz, dtype=np.float64) + cov = np.diag(np.square(np.asarray(u, dtype=np.float64))) + + return ControlPoint(name=name, topo=topo, covariance=cov) + + def has_height(self) -> bool: + return bool(self.topo[2] != 0) + + def is_triangulated(self) -> bool: + return self.triangulated is not None + + +def construct_control_points_from_json( + cp_json_file: Path, +) -> ControlPoints: + """ + Construct ControlPoints dict from a JSON file. + + Args: + cp_json_file (Path): Path to the sparse GT JSON file. + + Returns: + control_points (ControlPoints): Control points dictionary. + """ + with open(cp_json_file) as file: + cp_data = json.load(file) + + control_points: ControlPoints = {} + for geo_id, data in cp_data["control_points"].items(): + tag_ids = data["tag_id"] + measurement = data["measurement"] + unc = data["uncertainty"] + + for tag_id in tag_ids: + control_points[tag_id] = ControlPoint.from_measurement( + geo_id, + measurement, + unc, + CUSTOM_ORIGIN_COORDINATES, + ) + + return control_points + + +def transform_points(points, r, t, scale): + transformed_points = [] + for point in points: + transformed_point = scale * r.apply(point) + t + transformed_points.append(transformed_point) + + return transformed_points + + +def transform_triangulated_control_points(control_points: ControlPoints, r, t, scale) -> ControlPoints: + """Apply similarity transform to triangulated control points in place.""" + for cp in control_points.values(): + if cp.triangulated is None: + continue + cp.triangulated = scale * r.apply(cp.triangulated) + t + return control_points + + +def run_control_point_triangulation_from_json( + reconstruction_path: Path, + cp_json_file: Path, + control_points: ControlPoints, +) -> None: + """ + Triangulate control points from JSON file and add to control_points dict. + Updates `control_points` in place to add: + + - ``triangulated``: np.ndarray(3,) or None if triangulation fails + - ``inlier_ratio``: float + - ``image_id_and_point2d``: list of (image_id, [x, y]) tuples + of observations used for triangulation + Args: + reconstruction_path (Path): Path to the reconstruction folder + cp_json_file (Path): Path to the sparse GT JSON file + control_points (dict): Control points dictionary to be updated + """ + rec = pycolmap.Reconstruction(reconstruction_path) + + image_names_to_ids = { + image.name: image_id for image_id, image in rec.images.items() + } + + with open(cp_json_file) as file: + data = json.load(file) + + image_data = data["images"] + control_point_data = data["control_points"] + + for tag_id, cp in tqdm( + control_points.items(), desc="Triangulating control points" + ): + geo_id = cp.name + images_observing_cp = control_point_data[geo_id]["image_names"] + + pixel_points = [] + cam_from_worlds = [] + cameras = [] + + image_ids_and_centers = [] + + for image_name in images_observing_cp: + if image_name not in image_names_to_ids: + continue + id = image_names_to_ids[image_name] + image = rec.images[id] + detection = image_data[image_name]["detection"] + pixel_points.append(detection) + cam_from_worlds.append(image.cam_from_world()) + cameras.append(rec.cameras[image.camera_id]) + image_ids_and_centers.append((id, detection)) + + # HANDLING THE CASE WHERE NO IMAGES OBSERVE THE CONTROL POINT + if pixel_points == []: + cp.triangulated = None + cp.inlier_ratio = 0.0 + cp.image_id_and_point2d = [] + continue + + pixel_points = np.array(pixel_points) + try: + output = pycolmap.estimate_triangulation( + pixel_points, + cam_from_worlds, + cameras, + options={ + "residual_type": "REPROJECTION_ERROR", + "ransac": {"max_error": 4.0}, + }, + ) + except Exception as e: + print(f"Error in triangulating control point {geo_id}: {e}") + output = None + + if output is None: + cp.triangulated = None + cp.inlier_ratio = 0.0 + cp.image_id_and_point2d = [] + continue + + cp.triangulated = output["xyz"] + inliers = output["inliers"] + cp.inlier_ratio = np.sum(inliers) / len(inliers) + image_ids_and_centers = [ + image_ids_and_centers[i] for i in range(len(inliers)) if inliers[i] + ] + cp.image_id_and_point2d = image_ids_and_centers + + +def get_cps_for_initial_alignment(control_points: ControlPoints): + """Get control points with z != 0 for initial alignment""" + triangulated_cp_alignment = [] + topo_cp_alignment = [] + for _, cp in control_points.items(): + if not cp.is_triangulated(): + continue + + if cp.has_height(): + triangulated_cp_alignment.append(cp.triangulated) + topo_cp_alignment.append(cp.topo) + + if len(topo_cp_alignment) < 3: + logger.error( + "Not enough control points with height for initial alignment. " + "At least 3 control points with z != 0 are required." + ) + return None, None + + triangulated_cp_alignment = np.array(triangulated_cp_alignment) + topo_cp_alignment = np.array(topo_cp_alignment) + + return triangulated_cp_alignment, topo_cp_alignment From e11c88a618292ce39872ec045b3f7997db7d79af Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 00:41:07 +0200 Subject: [PATCH 478/665] ruff --- lamaria/structs/control_point.py | 30 ++++++++++++++++++------------ lamaria/structs/estimate.py | 5 +---- lamaria/utils/timestamps.py | 8 ++++---- 3 files changed, 23 insertions(+), 20 deletions(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index ec572c6..07408bd 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -1,6 +1,6 @@ import json -from pathlib import Path from dataclasses import dataclass, field +from pathlib import Path import numpy as np import pycolmap @@ -13,15 +13,18 @@ ControlPoints = dict[int, "ControlPoint"] + @dataclass(slots=True) class ControlPoint: - name: str # geo_id + name: str # geo_id topo: np.ndarray covariance: np.ndarray triangulated: np.ndarray | None = None # None if triangulation fails inlier_ratio: float = 0.0 - image_id_and_point2d: list[tuple[int, np.ndarray]] = field(default_factory=list) + image_id_and_point2d: list[tuple[int, np.ndarray]] = field( + default_factory=list + ) @staticmethod def from_measurement( @@ -30,7 +33,6 @@ def from_measurement( unc_xyz: list[float | None], origin_xyz: tuple[float, float, float], ) -> "ControlPoint": - m = list(measurement_xyz) u = list(unc_xyz) if m[2] is None: @@ -39,16 +41,18 @@ def from_measurement( u[2] = 1e9 # very uncertain height # translated measurement to have smaller numerical values - topo = np.asarray(m, dtype=np.float64) - np.asarray(origin_xyz, dtype=np.float64) + topo = np.asarray(m, dtype=np.float64) - np.asarray( + origin_xyz, dtype=np.float64 + ) cov = np.diag(np.square(np.asarray(u, dtype=np.float64))) - + return ControlPoint(name=name, topo=topo, covariance=cov) - + def has_height(self) -> bool: return bool(self.topo[2] != 0) - + def is_triangulated(self) -> bool: - return self.triangulated is not None + return self.triangulated is not None def construct_control_points_from_json( @@ -92,7 +96,9 @@ def transform_points(points, r, t, scale): return transformed_points -def transform_triangulated_control_points(control_points: ControlPoints, r, t, scale) -> ControlPoints: +def transform_triangulated_control_points( + control_points: ControlPoints, r, t, scale +) -> ControlPoints: """Apply similarity transform to triangulated control points in place.""" for cp in control_points.values(): if cp.triangulated is None: @@ -104,7 +110,7 @@ def transform_triangulated_control_points(control_points: ControlPoints, r, t, s def run_control_point_triangulation_from_json( reconstruction_path: Path, cp_json_file: Path, - control_points: ControlPoints, + control_points: ControlPoints, ) -> None: """ Triangulate control points from JSON file and add to control_points dict. @@ -131,7 +137,7 @@ def run_control_point_triangulation_from_json( image_data = data["images"] control_point_data = data["control_points"] - for tag_id, cp in tqdm( + for _, cp in tqdm( control_points.items(), desc="Triangulating control points" ): geo_id = cp.name diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index ce9902e..68dd433 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -1,4 +1,3 @@ -import json import shutil from decimal import ROUND_HALF_UP, Decimal from pathlib import Path @@ -84,9 +83,7 @@ def add_estimate_poses_to_reconstruction( shutil.rmtree(recon_path) reconstruction = self._add_images_to_reconstruction( - reconstruction, - timestamp_to_images, - sensor_from_rig + reconstruction, timestamp_to_images, sensor_from_rig ) reconstruction.write(recon_path.as_posix()) diff --git a/lamaria/utils/timestamps.py b/lamaria/utils/timestamps.py index 9834aa1..6503180 100644 --- a/lamaria/utils/timestamps.py +++ b/lamaria/utils/timestamps.py @@ -1,6 +1,6 @@ +import json from bisect import bisect_left from pathlib import Path -import json from .constants import ( LEFT_CAMERA_STREAM_LABEL, @@ -11,7 +11,7 @@ def get_timestamp_to_images_from_json( json_file: str | Path, ): - with open(json_file, "r") as f: + with open(json_file) as f: data = json.load(f) processed_ts_data = {} @@ -21,8 +21,8 @@ def get_timestamp_to_images_from_json( processed_ts_data[label]["sorted_keys"] = sorted( processed_ts_data[label].keys() ) - - return processed_ts_data + + return processed_ts_data def find_closest_timestamp( From 1fcd1fa764461747feb8033247136aede89c01db Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 01:06:49 +0200 Subject: [PATCH 479/665] sparse eval variables --- lamaria/structs/sparse_eval_variables.py | 143 +++++++++++++++++++++++ 1 file changed, 143 insertions(+) create mode 100644 lamaria/structs/sparse_eval_variables.py diff --git a/lamaria/structs/sparse_eval_variables.py b/lamaria/structs/sparse_eval_variables.py new file mode 100644 index 0000000..9c8f992 --- /dev/null +++ b/lamaria/structs/sparse_eval_variables.py @@ -0,0 +1,143 @@ +from dataclasses import dataclass, field +import copy +import pycolmap +import pyceres +import numpy as np + +from .. import logger +from .control_point import ControlPoint + + +@dataclass(slots=True) +class SparseEvalVariables: + """Container for sparse-eval optimization state.""" + control_points: dict[int, "ControlPoint"] # tag_id to ControlPoint + sim3d: pycolmap.Sim3d + cp_reproj_std: float = 1.0 + log_scale: np.ndarray = field(default_factory=lambda: np.array(0.0, dtype=np.float64)) + + @classmethod + def create_from_inputs( + cls, + control_points: dict, + sim3d: pycolmap.Sim3d, + cp_reproj_std: float = 1.0, + ) -> "SparseEvalVariables": + + scale = copy.deepcopy(sim3d.scale) + v = cls( + control_points=copy.deepcopy(control_points), + sim3d=copy.deepcopy(sim3d), + cp_reproj_std=float(cp_reproj_std), + log_scale=np.array(np.log(scale), dtype=np.float64), + ) + + return v + + def update_sim3d_scale_from_log(self) -> None: + """Propagate optimized log_scale back into sim3d.scale.""" + log_scale = copy.deepcopy(self.log_scale) + self.sim3d.scale = np.exp(log_scale) + + def reproj_cov(self) -> np.ndarray: + """2x2 covariance matrix for CP reprojection noise.""" + return np.eye(2) * pow(self.cp_reproj_std, 2) + + +def get_problem_for_sparse_alignment( + reconstruction: pycolmap.Reconstruction, + variables: SparseEvalVariables, +) -> tuple: + """Create a Ceres problem for sparse alignment. + Args: + reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. + variables (dict): The variables dictionary from + create_variables_for_sparse_evaluation. + + Returns: + problem (pyceres.Problem): The Ceres problem. + solver_options (pyceres.SolverOptions): The solver options. + summary (pyceres.SolverSummary): The solver summary. + """ + problem = pyceres.Problem() + problem = add_alignment_residuals( + problem, + reconstruction, + variables, + ) + solver_options = pyceres.SolverOptions() + solver_options.minimizer_progress_to_stdout = True + summary = pyceres.SolverSummary() + + return problem, solver_options, summary + + +def add_alignment_residuals( + problem, + reconstruction: pycolmap.Reconstruction, + variables: SparseEvalVariables, +) -> pyceres.Problem: + """Add alignment residuals to the Ceres problem. + + Variables consists of - + - ReprojErrorCost for each observation of each control point + - Point3DAlignmentCost for each control point + Args: + problem (pyceres.Problem): The Ceres problem. + reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. + variables (SparseEvalVariables): The sparse evaluation variables. + """ + if variables.control_points is None or variables.sim3d is None: + return problem + + loss = pyceres.TrivialLoss() + point2d_cov = variables.reproj_cov() + for tag_id, cp in variables.control_points.items(): + tri = cp.triangulated + if tri is None: + logger.info(f"Control point {tag_id} not triangulated") + continue + + obs = cp.image_id_and_point2d + for image_id, point2d in obs: + image = reconstruction.images[image_id] + pose = image.cam_from_world() + camera = reconstruction.cameras[image.camera_id] + + point2d = np.asarray(point2d, dtype=np.float64).reshape(2, 1) + + cost = pycolmap.cost_functions.ReprojErrorCost( + camera.model, + point2d_cov, + point2d, + pose, + ) + problem.add_residual_block( + cost, loss, [tri, camera.params] + ) + problem.set_parameter_block_constant(camera.params) + + cost = pycolmap.cost_functions.Point3DAlignmentCost( + cp.covariance, + cp.topo, + use_log_scale=True, + ) + problem.add_residual_block( + cost, + loss, + [ + cp.triangulated, + variables.sim3d.rotation.quat, + variables.sim3d.translation, + variables.log_scale, + ], + ) + + problem.set_manifold( + variables.sim3d.rotation.quat, + pyceres.EigenQuaternionManifold(), + ) + + logger.info("Added Point3dAlignmentCost and ReprojErrorCost costs") + + return problem \ No newline at end of file From 1370755fe51813e97602180283d1101a1c784594 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 01:34:39 +0200 Subject: [PATCH 480/665] cleaner sparse eval --- .../structs/{sparse_eval_variables.py => sparse_eval.py} | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) rename lamaria/structs/{sparse_eval_variables.py => sparse_eval.py} (96%) diff --git a/lamaria/structs/sparse_eval_variables.py b/lamaria/structs/sparse_eval.py similarity index 96% rename from lamaria/structs/sparse_eval_variables.py rename to lamaria/structs/sparse_eval.py index 9c8f992..0933a61 100644 --- a/lamaria/structs/sparse_eval_variables.py +++ b/lamaria/structs/sparse_eval.py @@ -10,7 +10,7 @@ @dataclass(slots=True) class SparseEvalVariables: - """Container for sparse-eval optimization state.""" + """Container for sparse evaluation optimization variables.""" control_points: dict[int, "ControlPoint"] # tag_id to ControlPoint sim3d: pycolmap.Sim3d cp_reproj_std: float = 1.0 @@ -60,7 +60,7 @@ def get_problem_for_sparse_alignment( summary (pyceres.SolverSummary): The solver summary. """ problem = pyceres.Problem() - problem = add_alignment_residuals( + problem = add_residuals_for_sparse_eval( problem, reconstruction, variables, @@ -72,7 +72,7 @@ def get_problem_for_sparse_alignment( return problem, solver_options, summary -def add_alignment_residuals( +def add_residuals_for_sparse_eval( problem, reconstruction: pycolmap.Reconstruction, variables: SparseEvalVariables, From 67524f655bfcefcadfe1568404f41009641b22e3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 02:23:25 +0200 Subject: [PATCH 481/665] init recon with cameras --- tools/undistort_asl_folder.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index a82d16b..fd1ecb5 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -10,7 +10,7 @@ from tqdm import tqdm from lamaria.utils.aria import ( - initialize_reconstruction_from_calibration_file, + initialize_reconstruction_with_cameras, ) from lamaria.utils.constants import ( ARIA_CAMERAS, @@ -80,7 +80,7 @@ def undistort_asl( if not calibration_file.exists(): raise FileNotFoundError(f"{calibration_file=}") - recon = initialize_reconstruction_from_calibration_file( + recon = initialize_reconstruction_with_cameras( calibration_file=calibration_file, ) # Create a dummy COLMAP reconstruction. From 7e05703409f343e9041fe9d40423aca3b623a91a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 02:34:07 +0200 Subject: [PATCH 482/665] aria --- lamaria/utils/aria.py | 67 +++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 64 insertions(+), 3 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 0629d91..6c483e1 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -24,6 +24,70 @@ def initialize_reconstruction_from_calibration_file( ) -> pycolmap.Reconstruction: """Initialize a COLMAP reconstruction from Aria calibration json file found on website: https://lamaria.ethz.ch/slam_datasets + Adds a dummy camera as an IMU along with two cameras. + + Args: + calibration_file (Path): + Path to the Aria calibration json file + Returns: + pycolmap.Reconstruction: The initialized COLMAP reconstruction + """ + reconstruction = pycolmap.Reconstruction() + + imu = pycolmap.Camera( + camera_id=1, + model="RAD_TAN_THIN_PRISM_FISHEYE", + width=640, + height=480, + params=[ + 241.604, + 241.604, + 322.895, + 240.444, + ] + + [0.0] * 12, + ) + reconstruction.add_camera(imu) + + rig = pycolmap.Rig(rig_id=1) + ref_sensor = pycolmap.sensor_t( + id=1, # imu is the rig + type=pycolmap.SensorType.CAMERA, + ) + rig.add_ref_sensor(ref_sensor) + + for i, (key, _) in enumerate(ARIA_CAMERAS): + cam = camera_colmap_from_json( + calibration_file=calibration_file, + camera_label=key, + ) + cam.camera_id = i + 2 # start from 2 since 1 is imu + reconstruction.add_camera(cam) + + sensor = pycolmap.sensor_t( + id=i + 2, type=pycolmap.SensorType.CAMERA + ) + rig_from_sensor = get_t_imu_camera_from_json( + calibration_file=calibration_file, + camera_label=key, + ) + sensor_from_rig = rig_from_sensor.inverse() + rig.add_sensor(sensor, sensor_from_rig) + + reconstruction.add_rig(rig) + + return reconstruction + + +# ----- Camera functions ----- # + + +def initialize_reconstruction_with_cameras( + calibration_file: Path, +) -> pycolmap.Reconstruction: + """Initialize a COLMAP reconstruction from Aria calibration + json file found on website: https://lamaria.ethz.ch/slam_datasets + Adds only the cameras without any dummy IMU. Args: calibration_file (Path): @@ -61,9 +125,6 @@ def initialize_reconstruction_from_calibration_file( return reconstruction -# ----- Camera functions ----- # - - def get_camera_params_for_colmap( camera_calibration: CameraCalibration, camera_model: str, From 0633595e5eddbecede2a215d05a4c9df1b930f92 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:07:54 +0200 Subject: [PATCH 483/665] updating est --- lamaria/structs/estimate.py | 25 ++++++++++++++++--------- 1 file changed, 16 insertions(+), 9 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index 68dd433..d2175f8 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -69,7 +69,6 @@ def add_estimate_poses_to_reconstruction( self, reconstruction: pycolmap.Reconstruction, timestamp_to_images: dict, - sensor_from_rig: pycolmap.Rigid3d, output_path: Path, ) -> Path: """ @@ -83,7 +82,7 @@ def add_estimate_poses_to_reconstruction( shutil.rmtree(recon_path) reconstruction = self._add_images_to_reconstruction( - reconstruction, timestamp_to_images, sensor_from_rig + reconstruction, timestamp_to_images ) reconstruction.write(recon_path.as_posix()) @@ -185,37 +184,45 @@ def _add_images_to_reconstruction( self, reconstruction: pycolmap.Reconstruction, timestamp_to_images: dict, - sensor_from_rig: pycolmap.Rigid3d, ) -> pycolmap.Reconstruction: pose_data = self.as_tuples() image_id = 1 + # imu is the rig in this reconstruction rig = reconstruction.rig(rig_id=1) - transform = sensor_from_rig.inverse() + if self.corresponding_sensor == "imu": + transform = pycolmap.Rigid3d() + else: + # left camera poses are provided + # sensor_from_rig == cam0_from_imu + transform = rig.sensor_from_rig(sensor_id=2) for i, (timestamp, pose) in tqdm( enumerate(pose_data), total=len(pose_data), desc="Adding images to reconstruction", ): + frame = pycolmap.Frame() + frame.rig_id = rig.rig_id + frame.frame_id = i + 1 + if self.invert_poses: # poses are in imu/cam_from_world format + # if imu: imu_from_world + # if cam0: cam0_from_world T_world_rig = pose.inverse() * transform else: # poses are in world_from_cam/imu format T_world_rig = pose * transform - frame = pycolmap.Frame() - frame.rig_id = rig.rig_id - frame.frame_id = i + 1 frame.rig_from_world = T_world_rig.inverse() images_to_add = [] for label, camera_id in [ - (LEFT_CAMERA_STREAM_LABEL, 1), - (RIGHT_CAMERA_STREAM_LABEL, 2), + (LEFT_CAMERA_STREAM_LABEL, 2), + (RIGHT_CAMERA_STREAM_LABEL, 3), ]: source_timestamps = timestamp_to_images[label]["sorted_keys"] # offsets upto 1 ms (1e6 ns) From 161cae2d421b1a7543d6b6739a49f104650d9288 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:08:36 +0200 Subject: [PATCH 484/665] naming --- lamaria/utils/aria.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 6c483e1..46a74e6 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -67,7 +67,7 @@ def initialize_reconstruction_from_calibration_file( sensor = pycolmap.sensor_t( id=i + 2, type=pycolmap.SensorType.CAMERA ) - rig_from_sensor = get_t_imu_camera_from_json( + rig_from_sensor = get_t_imu_camera_from_calibration_file( calibration_file=calibration_file, camera_label=key, ) @@ -360,7 +360,7 @@ def get_t_cam_a_cam_b_from_json( return t_camera_a_camera_b -def get_t_imu_camera_from_json( +def get_t_imu_camera_from_calibration_file( calibration_file: Path, camera_label: str, ) -> pycolmap.Rigid3d: From cc3de83404fcd37cd5c0f4548fcca1579d4cac62 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:09:16 +0200 Subject: [PATCH 485/665] naming --- lamaria/utils/aria.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 46a74e6..d567e22 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -113,7 +113,7 @@ def initialize_reconstruction_with_cameras( rig.add_ref_sensor(ref_sensor) sensor1 = pycolmap.sensor_t(id=2, type=pycolmap.SensorType.CAMERA) - sensor_from_rig = get_t_cam_a_cam_b_from_json( + sensor_from_rig = get_t_cam_a_cam_b_from_calibration_file( calibration_file=calibration_file, camera_a_label="cam1", # right camera_b_label="cam0", # left @@ -332,7 +332,7 @@ def get_magnitude_from_transform( return dr, dt -def get_t_cam_a_cam_b_from_json( +def get_t_cam_a_cam_b_from_calibration_file( calibration_file: Path, camera_a_label: str, camera_b_label: str, From 2a160f7508e3243d05b3d00877b9defc113a712b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:12:25 +0200 Subject: [PATCH 486/665] fixes --- lamaria/pipeline/keyframing/to_vi_reconstruction.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 4a2d74e..ed7140b 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -11,7 +11,7 @@ from ... import logger from ...config.options import EstimateToVIReconOptions from ...structs.estimate import ( - Estimate, + Trajectory, ) from ...structs.vi_reconstruction import VIReconstruction from ...utils.aria import ( @@ -136,16 +136,16 @@ def _init_data( images, timestamps, mps_poses ) else: - est = Estimate() - est.load_from_file(estimate, invert_poses=True) + traj = Trajectory() + traj.load_from_file(estimate, invert_poses=True) - timestamps = est.timestamps + timestamps = traj.timestamps if len(images) != len(timestamps): images, timestamps = self._match_estimate_ts_to_images( images, timestamps ) - rig_from_worlds = est.poses + rig_from_worlds = traj.poses self._per_frame_data = self._build_per_frame_data_from_estimate( images, timestamps, rig_from_worlds ) From fdb0515707e372da8bc6784f00ad3d01340f9f24 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:13:23 +0200 Subject: [PATCH 487/665] renmaing --- lamaria/structs/estimate.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/estimate.py index d2175f8..5485464 100644 --- a/lamaria/structs/estimate.py +++ b/lamaria/structs/estimate.py @@ -24,9 +24,9 @@ def _round_ns(x: str | int | float) -> int: return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) -class Estimate: +class Trajectory: """ - Loads and stores an 'estimate' text file with rows: + Loads and stores traj data from 'estimate' text file with rows: ts t_x t_y t_z q_x q_y q_z q_w Blank lines and lines starting with '#' are ignored. From 13af9cd58b78743d3cfab503a4409c5d2c54f89c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:13:40 +0200 Subject: [PATCH 488/665] fixes --- lamaria/structs/{estimate.py => trajectory.py} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename lamaria/structs/{estimate.py => trajectory.py} (100%) diff --git a/lamaria/structs/estimate.py b/lamaria/structs/trajectory.py similarity index 100% rename from lamaria/structs/estimate.py rename to lamaria/structs/trajectory.py From 164c0aed26e23451062f2fb8d73508d23617d938 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:13:56 +0200 Subject: [PATCH 489/665] fixes --- lamaria/pipeline/keyframing/to_vi_reconstruction.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index ed7140b..295f00a 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -10,7 +10,7 @@ from ... import logger from ...config.options import EstimateToVIReconOptions -from ...structs.estimate import ( +from ...structs.trajectory import ( Trajectory, ) from ...structs.vi_reconstruction import VIReconstruction From 4b374bbc7f0910fa3c5a9e9e5f7c2b5d2cf3ee59 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:30:41 +0200 Subject: [PATCH 490/665] cp --- lamaria/structs/control_point.py | 27 ++++++++++++++++++++++++++- 1 file changed, 26 insertions(+), 1 deletion(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index 07408bd..de938de 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -19,6 +19,7 @@ class ControlPoint: name: str # geo_id topo: np.ndarray covariance: np.ndarray + cp_reproj_std: float = 1.0 # pixels triangulated: np.ndarray | None = None # None if triangulation fails inlier_ratio: float = 0.0 @@ -32,7 +33,9 @@ def from_measurement( measurement_xyz: list[float | None], unc_xyz: list[float | None], origin_xyz: tuple[float, float, float], + cp_reproj_std: float = 1.0, ) -> "ControlPoint": + m = list(measurement_xyz) u = list(unc_xyz) if m[2] is None: @@ -46,17 +49,38 @@ def from_measurement( ) cov = np.diag(np.square(np.asarray(u, dtype=np.float64))) - return ControlPoint(name=name, topo=topo, covariance=cov) + return ControlPoint(name=name, topo=topo, covariance=cov, cp_reproj_std=cp_reproj_std) def has_height(self) -> bool: return bool(self.topo[2] != 0) def is_triangulated(self) -> bool: return self.triangulated is not None + + def summary(self) -> dict: + return { + "name": self.name, + "topo": self.topo.tolist(), + "covariance": self.covariance.tolist(), + } + + +def get_control_points_for_evaluation( + reconstruction_path: Path, + cp_json_file: Path, + cp_reproj_std: float = 1.0, +) -> ControlPoints: + """Load control points from JSON and run triangulation.""" + control_points = construct_control_points_from_json(cp_json_file, cp_reproj_std) + run_control_point_triangulation_from_json( + reconstruction_path, cp_json_file, control_points + ) + return control_points def construct_control_points_from_json( cp_json_file: Path, + cp_reproj_std: float = 1.0, ) -> ControlPoints: """ Construct ControlPoints dict from a JSON file. @@ -82,6 +106,7 @@ def construct_control_points_from_json( measurement, unc, CUSTOM_ORIGIN_COORDINATES, + cp_reproj_std, ) return control_points From 41858869b629b0c6ec738345f8dd80cb2a90dfea Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:31:26 +0200 Subject: [PATCH 491/665] structs for sparse eval --- lamaria/structs/sparse_eval.py | 95 ++++++++++++++++++++++++++++++---- 1 file changed, 85 insertions(+), 10 deletions(-) diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index 0933a61..0d11e7a 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -3,6 +3,7 @@ import pycolmap import pyceres import numpy as np +from pathlib import Path from .. import logger from .control_point import ControlPoint @@ -13,7 +14,6 @@ class SparseEvalVariables: """Container for sparse evaluation optimization variables.""" control_points: dict[int, "ControlPoint"] # tag_id to ControlPoint sim3d: pycolmap.Sim3d - cp_reproj_std: float = 1.0 log_scale: np.ndarray = field(default_factory=lambda: np.array(0.0, dtype=np.float64)) @classmethod @@ -21,27 +21,29 @@ def create_from_inputs( cls, control_points: dict, sim3d: pycolmap.Sim3d, - cp_reproj_std: float = 1.0, ) -> "SparseEvalVariables": scale = copy.deepcopy(sim3d.scale) v = cls( control_points=copy.deepcopy(control_points), sim3d=copy.deepcopy(sim3d), - cp_reproj_std=float(cp_reproj_std), log_scale=np.array(np.log(scale), dtype=np.float64), ) return v - def update_sim3d_scale_from_log(self) -> None: + def update_sim3d_scale(self) -> None: """Propagate optimized log_scale back into sim3d.scale.""" log_scale = copy.deepcopy(self.log_scale) self.sim3d.scale = np.exp(log_scale) - def reproj_cov(self) -> np.ndarray: - """2x2 covariance matrix for CP reprojection noise.""" - return np.eye(2) * pow(self.cp_reproj_std, 2) + def get_cp_summary(self) -> dict: + """Get a brief summary of control points.""" + summary = {} + for tag_id, cp in self.control_points.items(): + summary[tag_id] = cp.summary() + + return summary def get_problem_for_sparse_alignment( @@ -91,13 +93,15 @@ def add_residuals_for_sparse_eval( return problem loss = pyceres.TrivialLoss() - point2d_cov = variables.reproj_cov() + for tag_id, cp in variables.control_points.items(): tri = cp.triangulated if tri is None: logger.info(f"Control point {tag_id} not triangulated") continue + point2d_cov = np.eye(2) * pow(cp.cp_reproj_std, 2) + obs = cp.image_id_and_point2d for image_id, point2d in obs: image = reconstruction.images[image_id] @@ -105,7 +109,6 @@ def add_residuals_for_sparse_eval( camera = reconstruction.cameras[image.camera_id] point2d = np.asarray(point2d, dtype=np.float64).reshape(2, 1) - cost = pycolmap.cost_functions.ReprojErrorCost( camera.model, point2d_cov, @@ -140,4 +143,76 @@ def add_residuals_for_sparse_eval( logger.info("Added Point3dAlignmentCost and ReprojErrorCost costs") - return problem \ No newline at end of file + return problem + + +@dataclass(slots=True) +class AlignedPoint: + triangulated: np.ndarray | None + topo: np.ndarray + transformed: np.ndarray | None = None + error_3d: np.ndarray | None = None + + +@dataclass(slots=True) +class AlignmentResult: + optimized_sim3d: pycolmap.Sim3d + points: dict[int, AlignedPoint] + + @staticmethod + def calculate( + variables: SparseEvalVariables, + ) -> "AlignmentResult": + points = {} + sim3d = copy.deepcopy(variables.sim3d) + + for tag_id, cp in variables.control_points.items(): + tri = cp.triangulated + if tri is None: + points[tag_id] = AlignedPoint( + triangulated=None, + topo=cp.topo, + transformed=None, + error_3d=None, + ) + continue + + transformed = sim3d * tri + error_3d = transformed - cp.topo + points[tag_id] = AlignedPoint( + triangulated=tri, + topo=cp.topo, + transformed=transformed, + error_3d=error_3d, + ) + + return AlignmentResult( + optimized_sim3d=sim3d, + points=points, + ) + + +@dataclass(slots=True) +class SparseEvalResult: + robust_sim3d: pycolmap.Sim3d + alignment: AlignmentResult + cp_summary: dict | None = None + + @staticmethod + def from_variables( + robust_sim3d: pycolmap.Sim3d, + variables: SparseEvalVariables, + ) -> "SparseEvalResult": + alignment = AlignmentResult.calculate(variables) + cp_summary = variables.get_cp_summary() + + return SparseEvalResult( + robust_sim3d=copy.deepcopy(robust_sim3d), + alignment=alignment, + cp_summary=cp_summary, + ) + + def save_as_npy(self, path: Path) -> None: + np.save(path, self.__dict__) + + \ No newline at end of file From 35e207757a95f27d1d6ad4644f8e36651263ec26 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:34:46 +0200 Subject: [PATCH 492/665] result --- lamaria/eval/sparse_evaluation.py | 377 ++++++------------------------ lamaria/structs/sparse_eval.py | 3 - 2 files changed, 67 insertions(+), 313 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 473a90d..85743bc 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -6,254 +6,98 @@ import numpy as np import pyceres import pycolmap -import pycolmap.cost_functions from .. import logger from ..structs.control_point import ( - construct_control_points_from_json, get_cps_for_initial_alignment, - run_control_point_triangulation_from_json, ) -from ..structs.estimate import Estimate -from ..utils.aria import ( - get_t_imu_camera_from_json, - initialize_reconstruction_from_calibration_file, +from ..structs.sparse_eval import ( + SparseEvalVariables, + get_problem_for_sparse_alignment, + SparseEvalResult, ) -def update_sim3d_scale(variables: dict) -> None: - """Update the scale of the sim3d in the variables dictionary - from the log_scale variable. Occurs in place.""" - if "log_scale" not in variables: - raise ValueError("log_scale not found in variables") +def save_transformed_reconstruction( + reconstruction_path: Path, + sim3d: pycolmap.Sim3d, + output_folder: Path, +) -> None: + """Apply a Sim3d transformation to a reconstruction and save it. - log_scale = copy.deepcopy(variables["log_scale"]) - variables["sim3d"].scale = np.exp(log_scale) - - -def create_variables_for_sparse_evaluation( - control_points: dict, sim3d: pycolmap.Sim3d, cp_reproj_std: float = 1.0 -) -> dict: - """Create variables dictionary for sparse evaluation. - - Variables consists of - - - ```control_points```: Control points dictionary - - ```sim3d```: pycolmap.sim3d transformation - - ```cp_reproj_std```: Control point reprojection - - ```log scale``` (np.ndarray): Logarithm of the scale factor - (from sim3d.scale) + Args: + reconstruction_path (Path): Path to the input reconstruction. + sim3d (pycolmap.Sim3d): The similarity transformation to apply. + output_folder (Path): Directory where the transformed reconstruction + will be saved. """ + output_folder.mkdir(parents=True, exist_ok=True) + reconstruction = pycolmap.Reconstruction(reconstruction_path) + reconstruction.transform(sim3d) + reconstruction.write(output_folder) - variables = {} - variables["control_points"] = copy.deepcopy(control_points) - variables["sim3d"] = copy.deepcopy(sim3d) - variables["cp_reproj_std"] = cp_reproj_std - scale = copy.deepcopy(variables["sim3d"].scale) - variables["log_scale"] = np.array(np.log(scale), dtype=np.float64) + return output_folder - return variables +def estimate_robust_sim3d_from_control_points( + control_points: ControlPoints, +) -> pycolmap.Sim3d | None: + """Estimate a robust Sim3d from control points. -def get_problem_for_sparse_alignment( - reconstruction: pycolmap.Reconstruction, - variables: dict, -) -> tuple: - """Create a Ceres problem for sparse alignment. Args: - reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. - variables (dict): The variables dictionary from - create_variables_for_sparse_evaluation. - + control_points (ControlPoints): Control points dictionary. Returns: - problem (pyceres.Problem): The Ceres problem. - solver_options (pyceres.SolverOptions): The solver options. - summary (pyceres.SolverSummary): The solver summary. + sim3d (pycolmap.Sim3d | None): The estimated Sim3d or None if + estimation failed. """ - problem = pyceres.Problem() - problem = add_alignment_residuals( - problem, - reconstruction, - variables, + triangulated_cp_alignment, topo_cp_alignment = ( + get_cps_for_initial_alignment(control_points) ) - solver_options = pyceres.SolverOptions() - solver_options.minimizer_progress_to_stdout = True - summary = pyceres.SolverSummary() - - return problem, solver_options, summary + if triangulated_cp_alignment is None or topo_cp_alignment is None: + logger.error("Not enough control points for initial alignment") + return None -def add_alignment_residuals( - problem, - reconstruction: pycolmap.Reconstruction, - variables: dict, -) -> pyceres.Problem: - """Add alignment residuals to the Ceres problem. - - Variables consists of - - - ReprojErrorCost for each observation of each control point - - Point3DAlignmentCost for each control point - Args: - problem (pyceres.Problem): The Ceres problem. - reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. - variables (dict): The variables dictionary from - create_variables_for_sparse_evaluation. - """ - if ( - variables["control_points"] is not None - and variables["sim3d"] is not None - ): - loss = pyceres.TrivialLoss() - for tag_id, cp in variables["control_points"].items(): - if cp["triangulated"] is None: - logger.info(f"Control point {tag_id} not triangulated") - continue - for image_id_and_point2d in cp["image_id_and_point2d"]: - image_id, point2d = image_id_and_point2d - image = reconstruction.images[image_id] - pose = image.cam_from_world() - camera = reconstruction.cameras[image.camera_id] - - point2d = np.asarray(point2d, dtype=np.float64).reshape(2, 1) - point2d_cov = np.eye(2) * pow(variables["cp_reproj_std"], 2) - cost = pycolmap.cost_functions.ReprojErrorCost( - camera.model, - point2d_cov, - point2d, - pose, - ) - problem.add_residual_block( - cost, loss, [cp["triangulated"], camera.params] - ) - problem.set_parameter_block_constant(camera.params) + ret = pycolmap.estimate_sim3d_robust( + triangulated_cp_alignment, topo_cp_alignment, {"max_error": 5} + ) - for tag_id, cp in variables["control_points"].items(): - if cp["triangulated"] is None: - logger.info(f"Control point {tag_id} not triangulated") - continue - cost = pycolmap.cost_functions.Point3DAlignmentCost( - cp["covariance"], - cp["topo"], - use_log_scale=True, - ) - problem.add_residual_block( - cost, - loss, - [ - cp["triangulated"], - variables["sim3d"].rotation.quat, - variables["sim3d"].translation, - variables["log_scale"], - ], - ) + if ret is None: + return None - logger.info("Added Point3dAlignmentCost and ReprojErrorCost costs") + robust_sim3d = ret["tgt_from_src"] - problem.set_manifold( - variables["sim3d"].rotation.quat, - pyceres.EigenQuaternionManifold(), - ) + return robust_sim3d - return problem -def run( - estimate: Path, - cp_json_file: Path, - device_calibration_json: Path, +def evaluate_wrt_control_points( + reconstruction_path: Path, + control_points: ControlPoints, output_path: Path, - corresponding_sensor: str = "imu", - cp_reproj_std=1.0, -): - """Run sparse evaluation for sequences that observe control points. +) -> Path: + """ + Evaluate the trajectory with respect to control points. Args: - estimate (Path): Path to the pose estimate file. - cp_json_file (Path): Path to the sparse ground-truth JSON file - containing control point data. - device_calibration_json (Path): Path to the device calibration JSON. - output_path (Path): Directory where intermediate data and - evaluation results will be saved. - corresponding_sensor (str): The reference sensor to use - ("imu" or "cam0"). - cp_reproj_std (float, optional): Control point reprojection standard - deviation. Defaults to 1.0. + reconstruction_path (Path): Path to the input reconstruction, + which contains the estimated poses. + control_points (ControlPoints): Control points dictionary. + output_path (Path): Directory where results will be saved. Returns: - bool: True if the evaluation was successful, False otherwise. - - Notes: - Expected estimate file format (space-separated columns): - ``` - timestamp tx ty tz qx qy qz qw - ``` + sparse_npy_path (Path): Path to the saved SparseEvalResult .npy file. """ - est = Estimate() - est.load_from_file( - estimate, invert_poses=False, corresponding_sensor=corresponding_sensor - ) - if not est.is_loaded(): - logger.error("Estimate could not be loaded") - return False - - reconstruction = initialize_reconstruction_from_calibration_file( - device_calibration_json - ) - - if corresponding_sensor == "imu": - rig_from_sensor = get_t_imu_camera_from_json( - device_calibration_json, camera_label="cam0" - ) - sensor_from_rig = rig_from_sensor.inverse() - else: - sensor_from_rig = pycolmap.Rigid3d() - - reconstruction_path = est.add_estimate_poses_to_reconstruction( - reconstruction, - cp_json_file, - sensor_from_rig, - output_path, - ) - - aligned_transformed_folder = output_path / "aligned_transformed" - aligned_transformed_folder.mkdir(parents=True, exist_ok=True) - - control_points = construct_control_points_from_json(cp_json_file) - assert control_points is not None, ( - "Control points could not be constructed from JSON" - ) - - run_control_point_triangulation_from_json( - reconstruction_path, - cp_json_file, - control_points, - ) + + robust_sim3d = estimate_robust_sim3d_from_control_points(control_points) - triangulated_cp_alignment, topo_cp_alignment = ( - get_cps_for_initial_alignment(control_points) - ) - - if triangulated_cp_alignment is None or topo_cp_alignment is None: - logger.error("Not enough control points for initial alignment") - return False - - ret = pycolmap.estimate_sim3d_robust( - triangulated_cp_alignment, topo_cp_alignment, {"max_error": 5} - ) - - if ret is None: - logger.error("Failed to estimate robust sim3d") + if robust_sim3d is None: + logger.error("Robust Sim3d estimation failed") return False - robust_sim3d = ret["tgt_from_src"] - - ######################################################################### - output_data = {} - output_data["robust_sim3d"] = copy.deepcopy(robust_sim3d) - - variables = create_variables_for_sparse_evaluation( + variables = SparseEvalVariables.create_from_inputs( control_points, robust_sim3d, - cp_reproj_std, ) reconstruction = pycolmap.Reconstruction(reconstruction_path) @@ -263,107 +107,20 @@ def run( pyceres.solve(solver_options, problem, summary) print(summary.BriefReport()) - update_sim3d_scale(variables) - - output_data["full_alignment"] = {} - output_data["full_alignment"]["sim3"] = copy.deepcopy(variables["sim3d"]) - output_data["full_alignment"]["error_3d"] = {} - output_data["full_alignment"]["points"] = {} - - for tag_id, cp in control_points.items(): - output_data["full_alignment"]["points"][tag_id] = {} + variables.update_sim3d_scale() - if cp["triangulated"] is None: - output_data["full_alignment"]["points"][tag_id]["triangulated"] = ( - None - ) - output_data["full_alignment"]["error_3d"][tag_id] = [ - np.nan, - np.nan, - np.nan, - ] - continue - - original_triangulated_point = cp["triangulated"] - topo_cp = cp["topo"] - output_data["full_alignment"]["points"][tag_id]["triangulated"] = ( - original_triangulated_point - ) - output_data["full_alignment"]["points"][tag_id]["topo"] = topo_cp - output_data["full_alignment"]["points"][tag_id]["transformed"] = ( - variables["sim3d"] * original_triangulated_point - ) - error3d = variables["sim3d"] * original_triangulated_point - topo_cp - - output_data["full_alignment"]["error_3d"][tag_id] = error3d - - recon = pycolmap.Reconstruction(reconstruction) - recon.transform(output_data["full_alignment"]["sim3"]) - recon.write(aligned_transformed_folder) + result = SparseEvalResult.from_variables( + variables, + ) - output_data["control_points"] = {} - for tag_id, cp in control_points.items(): - output_data["control_points"][tag_id] = {} - output_data["control_points"][tag_id]["covariance"] = cp["covariance"] - output_data["control_points"][tag_id]["geo_id"] = cp["control_point"] - output_data["control_points"][tag_id]["topo"] = cp["topo"] + _ = save_transformed_reconstruction( + reconstruction_path, + result.alignment.optimized_sim3d, + output_path / "aligned" + ) - np.save(os.path.join(output_path, "sparse_evaluation.npy"), output_data) + result_path = output_path / "sparse_evaluation.npy" + result.save_as_npy(result_path) logger.info("Sparse evaluation completed successfully") - return True - - -if __name__ == "__main__": - parser = argparse.ArgumentParser( - description="Run baseline sparse evaluation" - ) - parser.add_argument( - "--estimate", - type=Path, - required=True, - help="Path to the pose estimate file produced by a specific method", - ) - parser.add_argument( - "--cp_json_file", - type=Path, - required=True, - help="Path to the sparse GT JSON file", - ) - parser.add_argument( - "--device_calibration_json", - type=Path, - required=True, - help="Path to the Aria device calibration JSON file, " - "found on the Lamaria website", - ) - parser.add_argument( - "--output_path", - type=Path, - required=True, - help="Path to the output folder where intermediate data " - "and evaluation results will be saved", - ) - parser.add_argument( - "--corresponding_sensor", - type=str, - default="imu", - choices=["imu", "cam0"], - help="The sensor in which the poses are expressed.", - ) - parser.add_argument( - "--cp_reproj_std", - type=float, - default=1.0, - help="Control point reprojection standard deviation", - ) - args = parser.parse_args() - - _ = run( - args.estimate, - args.cp_json_file, - args.device_calibration_json, - args.output_path, - args.corresponding_sensor, - args.cp_reproj_std, - ) + return True \ No newline at end of file diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index 0d11e7a..71f9cc4 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -194,20 +194,17 @@ def calculate( @dataclass(slots=True) class SparseEvalResult: - robust_sim3d: pycolmap.Sim3d alignment: AlignmentResult cp_summary: dict | None = None @staticmethod def from_variables( - robust_sim3d: pycolmap.Sim3d, variables: SparseEvalVariables, ) -> "SparseEvalResult": alignment = AlignmentResult.calculate(variables) cp_summary = variables.get_cp_summary() return SparseEvalResult( - robust_sim3d=copy.deepcopy(robust_sim3d), alignment=alignment, cp_summary=cp_summary, ) From 8ba62a312071dcf1d435589ecb33454a3192ca1a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:35:25 +0200 Subject: [PATCH 493/665] fix --- lamaria/eval/sparse_evaluation.py | 1 + 1 file changed, 1 insertion(+) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 85743bc..77bea41 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -10,6 +10,7 @@ from .. import logger from ..structs.control_point import ( get_cps_for_initial_alignment, + ControlPoints, ) from ..structs.sparse_eval import ( SparseEvalVariables, From f036160c4e25e3637e97bc8fc3ec092467ef4a90 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:36:18 +0200 Subject: [PATCH 494/665] fixes --- lamaria/eval/sparse_evaluation.py | 15 ++++------- lamaria/structs/control_point.py | 11 +++++--- lamaria/structs/sparse_eval.py | 43 +++++++++++++++---------------- lamaria/structs/trajectory.py | 2 +- lamaria/utils/aria.py | 6 ++--- 5 files changed, 36 insertions(+), 41 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 77bea41..e937889 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -1,21 +1,17 @@ -import argparse -import copy -import os from pathlib import Path -import numpy as np import pyceres import pycolmap from .. import logger from ..structs.control_point import ( - get_cps_for_initial_alignment, ControlPoints, + get_cps_for_initial_alignment, ) from ..structs.sparse_eval import ( + SparseEvalResult, SparseEvalVariables, get_problem_for_sparse_alignment, - SparseEvalResult, ) @@ -71,7 +67,6 @@ def estimate_robust_sim3d_from_control_points( return robust_sim3d - def evaluate_wrt_control_points( reconstruction_path: Path, control_points: ControlPoints, @@ -89,7 +84,7 @@ def evaluate_wrt_control_points( Returns: sparse_npy_path (Path): Path to the saved SparseEvalResult .npy file. """ - + robust_sim3d = estimate_robust_sim3d_from_control_points(control_points) if robust_sim3d is None: @@ -117,11 +112,11 @@ def evaluate_wrt_control_points( _ = save_transformed_reconstruction( reconstruction_path, result.alignment.optimized_sim3d, - output_path / "aligned" + output_path / "aligned", ) result_path = output_path / "sparse_evaluation.npy" result.save_as_npy(result_path) logger.info("Sparse evaluation completed successfully") - return True \ No newline at end of file + return True diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index de938de..40311da 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -35,7 +35,6 @@ def from_measurement( origin_xyz: tuple[float, float, float], cp_reproj_std: float = 1.0, ) -> "ControlPoint": - m = list(measurement_xyz) u = list(unc_xyz) if m[2] is None: @@ -49,14 +48,16 @@ def from_measurement( ) cov = np.diag(np.square(np.asarray(u, dtype=np.float64))) - return ControlPoint(name=name, topo=topo, covariance=cov, cp_reproj_std=cp_reproj_std) + return ControlPoint( + name=name, topo=topo, covariance=cov, cp_reproj_std=cp_reproj_std + ) def has_height(self) -> bool: return bool(self.topo[2] != 0) def is_triangulated(self) -> bool: return self.triangulated is not None - + def summary(self) -> dict: return { "name": self.name, @@ -71,7 +72,9 @@ def get_control_points_for_evaluation( cp_reproj_std: float = 1.0, ) -> ControlPoints: """Load control points from JSON and run triangulation.""" - control_points = construct_control_points_from_json(cp_json_file, cp_reproj_std) + control_points = construct_control_points_from_json( + cp_json_file, cp_reproj_std + ) run_control_point_triangulation_from_json( reconstruction_path, cp_json_file, control_points ) diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index 71f9cc4..be1d3a0 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -1,10 +1,11 @@ -from dataclasses import dataclass, field import copy -import pycolmap -import pyceres -import numpy as np +from dataclasses import dataclass, field from pathlib import Path +import numpy as np +import pyceres +import pycolmap + from .. import logger from .control_point import ControlPoint @@ -12,9 +13,12 @@ @dataclass(slots=True) class SparseEvalVariables: """Container for sparse evaluation optimization variables.""" - control_points: dict[int, "ControlPoint"] # tag_id to ControlPoint + + control_points: dict[int, "ControlPoint"] # tag_id to ControlPoint sim3d: pycolmap.Sim3d - log_scale: np.ndarray = field(default_factory=lambda: np.array(0.0, dtype=np.float64)) + log_scale: np.ndarray = field( + default_factory=lambda: np.array(0.0, dtype=np.float64) + ) @classmethod def create_from_inputs( @@ -22,29 +26,28 @@ def create_from_inputs( control_points: dict, sim3d: pycolmap.Sim3d, ) -> "SparseEvalVariables": - scale = copy.deepcopy(sim3d.scale) v = cls( control_points=copy.deepcopy(control_points), sim3d=copy.deepcopy(sim3d), log_scale=np.array(np.log(scale), dtype=np.float64), ) - + return v - + def update_sim3d_scale(self) -> None: """Propagate optimized log_scale back into sim3d.scale.""" log_scale = copy.deepcopy(self.log_scale) self.sim3d.scale = np.exp(log_scale) - + def get_cp_summary(self) -> dict: """Get a brief summary of control points.""" summary = {} for tag_id, cp in self.control_points.items(): summary[tag_id] = cp.summary() - + return summary - + def get_problem_for_sparse_alignment( reconstruction: pycolmap.Reconstruction, @@ -99,9 +102,9 @@ def add_residuals_for_sparse_eval( if tri is None: logger.info(f"Control point {tag_id} not triangulated") continue - + point2d_cov = np.eye(2) * pow(cp.cp_reproj_std, 2) - + obs = cp.image_id_and_point2d for image_id, point2d in obs: image = reconstruction.images[image_id] @@ -115,9 +118,7 @@ def add_residuals_for_sparse_eval( point2d, pose, ) - problem.add_residual_block( - cost, loss, [tri, camera.params] - ) + problem.add_residual_block(cost, loss, [tri, camera.params]) problem.set_parameter_block_constant(camera.params) cost = pycolmap.cost_functions.Point3DAlignmentCost( @@ -165,7 +166,7 @@ def calculate( ) -> "AlignmentResult": points = {} sim3d = copy.deepcopy(variables.sim3d) - + for tag_id, cp in variables.control_points.items(): tri = cp.triangulated if tri is None: @@ -176,7 +177,7 @@ def calculate( error_3d=None, ) continue - + transformed = sim3d * tri error_3d = transformed - cp.topo points[tag_id] = AlignedPoint( @@ -208,8 +209,6 @@ def from_variables( alignment=alignment, cp_summary=cp_summary, ) - + def save_as_npy(self, path: Path) -> None: np.save(path, self.__dict__) - - \ No newline at end of file diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 5485464..92f3b81 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -206,7 +206,7 @@ def _add_images_to_reconstruction( frame = pycolmap.Frame() frame.rig_id = rig.rig_id frame.frame_id = i + 1 - + if self.invert_poses: # poses are in imu/cam_from_world format # if imu: imu_from_world diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index d567e22..339015d 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -63,10 +63,8 @@ def initialize_reconstruction_from_calibration_file( ) cam.camera_id = i + 2 # start from 2 since 1 is imu reconstruction.add_camera(cam) - - sensor = pycolmap.sensor_t( - id=i + 2, type=pycolmap.SensorType.CAMERA - ) + + sensor = pycolmap.sensor_t(id=i + 2, type=pycolmap.SensorType.CAMERA) rig_from_sensor = get_t_imu_camera_from_calibration_file( calibration_file=calibration_file, camera_label=key, From a63f8ba256897c4fab0777079db62e790c65b17d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:39:52 +0200 Subject: [PATCH 495/665] fixes --- evaluate_wrt_control_points.py | 145 ++++++++++++++++++++++++++++++ lamaria/eval/sparse_evaluation.py | 6 +- 2 files changed, 148 insertions(+), 3 deletions(-) create mode 100644 evaluate_wrt_control_points.py diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py new file mode 100644 index 0000000..a86e0fc --- /dev/null +++ b/evaluate_wrt_control_points.py @@ -0,0 +1,145 @@ +import argparse +from pathlib import Path + +from lamaria import logger +from lamaria.eval.sparse_evaluation import ( + evaluate_wrt_control_points +) +from lamaria.structs.control_point import ( + get_control_points_for_evaluation +) +from lamaria.structs.trajectory import Trajectory +from lamaria.utils.aria import ( + initialize_reconstruction_from_calibration_file +) +from lamaria.utils.timestamps import ( + get_timestamp_to_images_from_json +) + +def run( + estimate: Path, + cp_json_file: Path, + device_calibration_json: Path, + output_path: Path, + corresponding_sensor: str = "imu", + cp_reproj_std=1.0, +): + """Run sparse evaluation for sequences that observe control points. + + Args: + estimate (Path): Path to the pose estimate file. + cp_json_file (Path): Path to the sparse ground-truth JSON file + containing control point data. + device_calibration_json (Path): Path to the device calibration JSON. + output_path (Path): Directory where intermediate data and + evaluation results will be saved. + corresponding_sensor (str): The reference sensor to use + ("imu" or "cam0"). + cp_reproj_std (float, optional): Control point reprojection standard + deviation. Defaults to 1.0. + + Returns: + bool: True if the evaluation was successful, False otherwise. + + Notes: + Expected estimate file format (space-separated columns): + ``` + timestamp tx ty tz qx qy qz qw + ``` + """ + traj = Trajectory() + traj.load_from_file( + estimate, + invert_poses=False, + corresponding_sensor=corresponding_sensor + ) + if not traj.is_loaded(): + logger.error("Estimate could not be loaded") + return False + + init_reconstruction = initialize_reconstruction_from_calibration_file( + device_calibration_json + ) + timestamp_to_images = get_timestamp_to_images_from_json( + cp_json_file + ) + + reconstruction_path = traj.add_estimate_poses_to_reconstruction( + init_reconstruction, + timestamp_to_images, + output_path, + ) + + control_points = get_control_points_for_evaluation( + reconstruction_path, + cp_json_file, + cp_reproj_std + ) + + sparse_npy_path = evaluate_wrt_control_points( + traj, + control_points, + reconstruction_path, + output_path, + ) + if not sparse_npy_path.exists(): + logger.error("Sparse evaluation failed") + return False + + logger.info(f"Results saved to {sparse_npy_path}") + return True + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description="Run baseline sparse evaluation" + ) + parser.add_argument( + "--estimate", + type=Path, + required=True, + help="Path to the pose estimate file produced by a specific method", + ) + parser.add_argument( + "--cp_json_file", + type=Path, + required=True, + help="Path to the sparse GT JSON file", + ) + parser.add_argument( + "--device_calibration_json", + type=Path, + required=True, + help="Path to the Aria device calibration JSON file, " + "found on the Lamaria website", + ) + parser.add_argument( + "--output_path", + type=Path, + required=True, + help="Path to the output folder where intermediate data " + "and evaluation results will be saved", + ) + parser.add_argument( + "--corresponding_sensor", + type=str, + default="imu", + choices=["imu", "cam0"], + help="The sensor in which the poses are expressed.", + ) + parser.add_argument( + "--cp_reproj_std", + type=float, + default=1.0, + help="Control point reprojection standard deviation", + ) + args = parser.parse_args() + + _ = run( + args.estimate, + args.cp_json_file, + args.device_calibration_json, + args.output_path, + args.corresponding_sensor, + args.cp_reproj_std, + ) \ No newline at end of file diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index e937889..e400e9c 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -89,7 +89,7 @@ def evaluate_wrt_control_points( if robust_sim3d is None: logger.error("Robust Sim3d estimation failed") - return False + return None variables = SparseEvalVariables.create_from_inputs( control_points, @@ -118,5 +118,5 @@ def evaluate_wrt_control_points( result_path = output_path / "sparse_evaluation.npy" result.save_as_npy(result_path) - logger.info("Sparse evaluation completed successfully") - return True + logger.info("Sparse evaluation completed successfully!") + return result_path From b49a0d3637b803a27dcd6dc19e7bb0b61990cf33 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:41:06 +0200 Subject: [PATCH 496/665] fix --- evaluate_wrt_control_points.py | 33 ++++++++++----------------------- 1 file changed, 10 insertions(+), 23 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index a86e0fc..774814e 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -2,19 +2,12 @@ from pathlib import Path from lamaria import logger -from lamaria.eval.sparse_evaluation import ( - evaluate_wrt_control_points -) -from lamaria.structs.control_point import ( - get_control_points_for_evaluation -) +from lamaria.eval.sparse_evaluation import evaluate_wrt_control_points +from lamaria.structs.control_point import get_control_points_for_evaluation from lamaria.structs.trajectory import Trajectory -from lamaria.utils.aria import ( - initialize_reconstruction_from_calibration_file -) -from lamaria.utils.timestamps import ( - get_timestamp_to_images_from_json -) +from lamaria.utils.aria import initialize_reconstruction_from_calibration_file +from lamaria.utils.timestamps import get_timestamp_to_images_from_json + def run( estimate: Path, @@ -49,9 +42,7 @@ def run( """ traj = Trajectory() traj.load_from_file( - estimate, - invert_poses=False, - corresponding_sensor=corresponding_sensor + estimate, invert_poses=False, corresponding_sensor=corresponding_sensor ) if not traj.is_loaded(): logger.error("Estimate could not be loaded") @@ -60,9 +51,7 @@ def run( init_reconstruction = initialize_reconstruction_from_calibration_file( device_calibration_json ) - timestamp_to_images = get_timestamp_to_images_from_json( - cp_json_file - ) + timestamp_to_images = get_timestamp_to_images_from_json(cp_json_file) reconstruction_path = traj.add_estimate_poses_to_reconstruction( init_reconstruction, @@ -71,9 +60,7 @@ def run( ) control_points = get_control_points_for_evaluation( - reconstruction_path, - cp_json_file, - cp_reproj_std + reconstruction_path, cp_json_file, cp_reproj_std ) sparse_npy_path = evaluate_wrt_control_points( @@ -85,7 +72,7 @@ def run( if not sparse_npy_path.exists(): logger.error("Sparse evaluation failed") return False - + logger.info(f"Results saved to {sparse_npy_path}") return True @@ -142,4 +129,4 @@ def run( args.output_path, args.corresponding_sensor, args.cp_reproj_std, - ) \ No newline at end of file + ) From 73b2989a95625661876113a4e5ccaa9585dfb6cd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 03:44:37 +0200 Subject: [PATCH 497/665] eval --- evaluate_wrt_control_points.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 774814e..a4b7158 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -64,9 +64,8 @@ def run( ) sparse_npy_path = evaluate_wrt_control_points( - traj, - control_points, reconstruction_path, + control_points, output_path, ) if not sparse_npy_path.exists(): From a07d713ff675fbf7086a5fe3196f47b597c05ff7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 04:01:59 +0200 Subject: [PATCH 498/665] add load fn for result --- lamaria/structs/sparse_eval.py | 44 ++++++++++++++++++++++++++++++++-- lamaria/structs/trajectory.py | 3 ++- 2 files changed, 44 insertions(+), 3 deletions(-) diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index be1d3a0..19a5307 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -1,10 +1,11 @@ import copy -from dataclasses import dataclass, field +from dataclasses import dataclass, field, asdict from pathlib import Path import numpy as np import pyceres import pycolmap +import pycolmap.cost_functions from .. import logger from .control_point import ControlPoint @@ -210,5 +211,44 @@ def from_variables( cp_summary=cp_summary, ) + @classmethod + def load_from_npy(cls, path: Path) -> "SparseEvalResult": + if not path.exists(): + logger.error(f"Result file not found: {path}") + return None + + data = np.load(path, allow_pickle=True).item() + alignment_data = data["alignment"] + + opt = alignment_data["optimized_sim3d"] + if isinstance(opt, pycolmap.Sim3d): + sim3d = opt + + alignment = AlignmentResult( + optimized_sim3d=sim3d, + points={ + int(tag_id): AlignedPoint( + triangulated=np.asarray(point["triangulated"]) + if point["triangulated"] is not None + else None, + topo=np.asarray(point["topo"]), + transformed=np.asarray(point["transformed"]) + if point["transformed"] is not None + else None, + error_3d=np.asarray(point["error_3d"]) + if point["error_3d"] is not None + else None, + ) + for tag_id, point in alignment_data["points"].items() + }, + ) + cp_summary = data.get("cp_summary", None) + + return cls( + alignment=alignment, + cp_summary=cp_summary, + ) + def save_as_npy(self, path: Path) -> None: - np.save(path, self.__dict__) + path.parent.mkdir(parents=True, exist_ok=True) # just in case + np.save(path, asdict(self)) diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 92f3b81..cd77e14 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -64,6 +64,8 @@ def load_from_file( state = self._parse(lines) if not state: raise RuntimeError("Failed to parse estimate file.") + + return self def add_estimate_poses_to_reconstruction( self, @@ -79,7 +81,6 @@ def add_estimate_poses_to_reconstruction( recon_path = output_path / "reconstruction" recon_path.mkdir(parents=True, exist_ok=True) - shutil.rmtree(recon_path) reconstruction = self._add_images_to_reconstruction( reconstruction, timestamp_to_images From 7b69dc9adbf1ba43536bf70bcf064cce0a61bc6b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 04:02:13 +0200 Subject: [PATCH 499/665] load from file --- evaluate_wrt_control_points.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index a4b7158..808e504 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -40,8 +40,7 @@ def run( timestamp tx ty tz qx qy qz qw ``` """ - traj = Trajectory() - traj.load_from_file( + traj = Trajectory.load_from_file( estimate, invert_poses=False, corresponding_sensor=corresponding_sensor ) if not traj.is_loaded(): From edbfbe0781cbd0863889f17db599cb5ab345fa8e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 04:02:41 +0200 Subject: [PATCH 500/665] fix loading --- lamaria/pipeline/keyframing/to_vi_reconstruction.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 295f00a..8f131ee 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -136,8 +136,7 @@ def _init_data( images, timestamps, mps_poses ) else: - traj = Trajectory() - traj.load_from_file(estimate, invert_poses=True) + traj = Trajectory.load_from_file(estimate, invert_poses=True) timestamps = traj.timestamps if len(images) != len(timestamps): From e87ff5f2deddb84e76ef14bbbe18db4946cf2b89 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 04:05:12 +0200 Subject: [PATCH 501/665] return type --- lamaria/structs/trajectory.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index cd77e14..58656d7 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -47,7 +47,7 @@ def load_from_file( path: str | Path, invert_poses: bool = True, corresponding_sensor: str = "imu", - ) -> None: + ) -> "Trajectory": """Parse the file, validate format, populate timestamps & poses.""" self = cls() self.clear() From 9f101e94fd0ebf44fab3a752741370285d065f8c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 04:13:23 +0200 Subject: [PATCH 502/665] return --- evaluate_wrt_control_points.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 808e504..7dba4f9 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -16,7 +16,7 @@ def run( output_path: Path, corresponding_sensor: str = "imu", cp_reproj_std=1.0, -): +) -> bool: """Run sparse evaluation for sequences that observe control points. Args: From 4846d6a01662cf4fb7f07adfad71453b9dcfdc63 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 04:21:58 +0200 Subject: [PATCH 503/665] todo --- evaluate_wrt_control_points.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 7dba4f9..4a8254b 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -73,6 +73,8 @@ def run( logger.info(f"Results saved to {sparse_npy_path}") return True + + # TODO: Add metrics here? if __name__ == "__main__": From 9e398f5f128d5c1c91c02c0cd4bf9ab43f2f486f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 09:37:04 +0200 Subject: [PATCH 504/665] readme init --- README.md | 37 +++++++++++++++++++++++++++++++++++-- 1 file changed, 35 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 72c178e..25cd36e 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,39 @@ # Benchmarking Egocentric Visual-Inertial SLAM at City Scale -### Downloading the dataset +# Table of Contents +- [General Introduction](#general-introduction) +- [Installation](#installation) +- [Downloading the Dataset](#downloading-the-dataset) +- [Evaluation](#evaluation) + - [Evaluation w.r.t. Control Points](#evaluation-wrt-control-points) + - [Evaluation Against Pseudo-GT](#evaluation-against-pseudo-gt) + - [EVO Evaluation Against MPS](#evo-evaluation-against-mps) +- [Data Conversion](#data-conversion) +- [Example Visual-Inertial Optimization](#example-visual-inertial-optimization) +# Introduction to LaMAria -### Additional tools \ No newline at end of file + +# Installation + + +# Downloading the dataset + + +# Evaluation + + +## Evaluation w.r.t. Control Points + + +## Evaluation w.r.t Pseudo-GT + + +## EVO Evaluation w.r.t MPS + + +# Data Conversion + + + +# Example Visual-Inertial Optimization \ No newline at end of file From 1d5e77d86a87b44bd262d6683938cbd29bde6722 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 09:37:58 +0200 Subject: [PATCH 505/665] ruff --- evaluate_wrt_control_points.py | 2 +- lamaria/structs/sparse_eval.py | 8 ++++---- lamaria/structs/trajectory.py | 3 +-- 3 files changed, 6 insertions(+), 7 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 4a8254b..8297a62 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -73,7 +73,7 @@ def run( logger.info(f"Results saved to {sparse_npy_path}") return True - + # TODO: Add metrics here? diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index 19a5307..0378e9b 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -1,5 +1,5 @@ import copy -from dataclasses import dataclass, field, asdict +from dataclasses import asdict, dataclass, field from pathlib import Path import numpy as np @@ -216,7 +216,7 @@ def load_from_npy(cls, path: Path) -> "SparseEvalResult": if not path.exists(): logger.error(f"Result file not found: {path}") return None - + data = np.load(path, allow_pickle=True).item() alignment_data = data["alignment"] @@ -248,7 +248,7 @@ def load_from_npy(cls, path: Path) -> "SparseEvalResult": alignment=alignment, cp_summary=cp_summary, ) - + def save_as_npy(self, path: Path) -> None: path.parent.mkdir(parents=True, exist_ok=True) # just in case - np.save(path, asdict(self)) + np.save(path, asdict(self)) diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 58656d7..8d98be5 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -1,4 +1,3 @@ -import shutil from decimal import ROUND_HALF_UP, Decimal from pathlib import Path @@ -64,7 +63,7 @@ def load_from_file( state = self._parse(lines) if not state: raise RuntimeError("Failed to parse estimate file.") - + return self def add_estimate_poses_to_reconstruction( From e3d7623c4ff44c56b3d41f110cfd13d9b024c570 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 09:40:03 +0200 Subject: [PATCH 506/665] readme --- README.md | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/README.md b/README.md index 25cd36e..0b8221a 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@ -# Benchmarking Egocentric Visual-Inertial SLAM at City Scale +

Benchmarking Egocentric Visual-Inertial SLAM at City Scale

-# Table of Contents +## Table of Contents - [General Introduction](#general-introduction) - [Installation](#installation) - [Downloading the Dataset](#downloading-the-dataset) @@ -11,29 +11,29 @@ - [Data Conversion](#data-conversion) - [Example Visual-Inertial Optimization](#example-visual-inertial-optimization) -# Introduction to LaMAria +## Introduction to LaMAria -# Installation +## Installation -# Downloading the dataset +## Downloading the dataset -# Evaluation +## Evaluation -## Evaluation w.r.t. Control Points +### Evaluation w.r.t. Control Points -## Evaluation w.r.t Pseudo-GT +### Evaluation w.r.t Pseudo-GT -## EVO Evaluation w.r.t MPS +### EVO Evaluation w.r.t MPS -# Data Conversion +## Data Conversion -# Example Visual-Inertial Optimization \ No newline at end of file +## Example Visual-Inertial Optimization \ No newline at end of file From 2dabcbd6a98898b7d9c973cc3fc4b0ffb1ddbb82 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 09:40:25 +0200 Subject: [PATCH 507/665] read --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 0b8221a..107bd16 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -

Benchmarking Egocentric Visual-Inertial SLAM at City Scale

+

Benchmarking Egocentric Visual-Inertial SLAM at City Scale

## Table of Contents - [General Introduction](#general-introduction) From 76b9d9bab798df3ac5fe521727e6251019075470 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 09:58:40 +0200 Subject: [PATCH 508/665] readme init, assets --- README.md | 15 ++++++++++++--- assets/teaser_final.png | Bin 0 -> 1534589 bytes 2 files changed, 12 insertions(+), 3 deletions(-) create mode 100644 assets/teaser_final.png diff --git a/README.md b/README.md index 107bd16..bbd5642 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,18 @@

Benchmarking Egocentric Visual-Inertial SLAM at City Scale

+We present **LaMAria**, a egocentric, city-scale benchmark for **visual-inertial SLAM**, featuring +~ **22 hours / 70 km** of trajectories with survey-grade control points providing **centimeter-accurate ground truth**. + +Using **LaMAria**, you can: +- Evaluate SLAM systems under real-world challenges: low light, moving platforms, exposure changes, extremely long trajectories. +- Benchmark against highly accurate sparse ground truths. + +

+ Overview of LaMAria +

+

Figure 1: Overview of the LaMAria dataset and benchmark.

+ ## Table of Contents -- [General Introduction](#general-introduction) - [Installation](#installation) - [Downloading the Dataset](#downloading-the-dataset) - [Evaluation](#evaluation) @@ -11,8 +22,6 @@ - [Data Conversion](#data-conversion) - [Example Visual-Inertial Optimization](#example-visual-inertial-optimization) -## Introduction to LaMAria - ## Installation diff --git a/assets/teaser_final.png b/assets/teaser_final.png new file mode 100644 index 0000000000000000000000000000000000000000..00ba238166a7f919eeff1551494d2ffe0b0ea1d1 GIT binary patch literal 1534589 zcmZ^~bx<5k@HU7A5`PXbOuMMw7i{r&vx5*-!w2)c!W^x@=i`~36>0UiMv1?>O| z+1=b=WMn|WB4c4?kCv=R7S=ol9EzK zr^k4B1n+MzBErI_(CwqstLrluFE6jse`AxC^>O}o1=~g=WP5&nJ%b%-YpN0v5qSeW zR8-Yo?#^#+Za?7C<1xyeJe*UBXkt+EP>_&bpIwu4YoVgy=zP^n%gC~^wZ&l++ub?3 z-rfGwHw0bVSl(P_6QWsKhWr~Gq!2Ur^7C`GH~zZ>O$hT}e%soEERZd#g~Kb{@l+(KGg!IRS? z(7m}Ip~27RSM-V|@v$*vOoFAQ<(r!u(5J2K<+LwJQkU2dqzUFx4=wN<+8iGl|CataC)6qUZ+S=M& zqoBgEeLZuveT=RgS65wwgvXs6880eZ221v%O6pM?(cDbvZMjR9Dh%`H5L9eOOw)*bWPM1-Wjb-gr} zr3?HRln>0Fzg~hpzsY_NpLlu3`9c&I9%a+MlgCVx65y1b{)5FOYI}ORF$eevoAUNC z3mv!|>y15KIsMyOId?r|=_L5Ke_7nrUf!6MPuJO8QryH`@L_@%)W5yAe?51(LvCyr zx$;7%;>aTvOXE^Tpx+9egUCs0PYhN%hhFRE%N`@{Y3yY08iq^tW}sjt7+de&(=$4G@Y@^lFz4VxC3 z@DeElsQ$oJ`~5>2KS|!&PJ5)M_=??UQNy{9s`~d+Eq(?_H~TQPqnYv4sk{wJ3~CWj z{nnD+qOz)5IcJmMkZ|I*7Ba2e?DJsFlnv-bBDj&gRrJ&{*3Bq7IMn+JMhE*UAe{9fj};N18!IkIEqtt zN^trANc>;T+V)X-`C1x_;>*jE%FD@X5nsv4$+Q1_QA$y&j?i)RJCb#MWgdDr$h z#yR$rUzXPa$Y-kYv)wF~c#uOow#5A296{N);hqTH+uzbRkv`_rGhBtk$T^%F1*2ut zw{8d4fu1j)-mMCb?q;0+rv-VL^7fTM@EAJ7WN@6B5mavtXbjla?Uqpw{OXq zPH!s;DtW$_tAG2vT;v?;^lmj1Fg8R+D)q8Nd{}z=Z({|^TBmXGl#*x};T!@*U?19C z13gtVZ*2ZgTjfJ)3NODA0i`)zTnq`x%E~HNv*ojW`rvB{+|hVK-mnk-oz4{3wwOWT zGE)8FttY11y4}NLxG@?ej66NT_thj;OxO$E8sXBoMV~2-o#PDh+JT5dvHAWG#F9Yy zuzt3If<=)#m4IK(hWLtT=$Jy`J2~?T^?~J z?8Ff)BjkT~qHH@AAIsRU1Gl;gpcMw6E~F&8h#=4_M{ULq3b0>QQ!FVSek<#nz!_#T zQpiSZi552G3DK`HWQn5?ZU>sbZ}?LzcO2IVpS2(7`=7O6FAAS`LDf*D+aROOCif?P z=2KzMSY#sU^*4XHTfgSjIgKnBtn;^Z{{LxrMi&B4KahAno z)-To{OQ2W_G=GPn+@Gv}NZ<55sBPQuJFfL!w-`V^^!{_`Z5N8~C-F?)2Ju}&^bb1z zGaEohF!JNM7BMTxV3idAXYVHNCgk~lR@xUmI3T{EbX~0~EiFa9_`NEkC#kSM=(`QF zt(Sa80t~@Kt*b?G7vi&`fH=1);rjm7tbW4&DYjTrz^n2>z0bFW8#$MwI9C|ZdrUF% z(rR@0ahj>vQ^1^ zAYKS@`wpwjjnJ9NyzgI61zyvkCIdE<8IKSi(OBtU2%g8Nprp&9{KL2<7%McSjn5oD zI=wIU+zDa(wd9DeA+D^{Q;#oKeUX?VJ%ncCCf*7H89+>*9OIxR6K_RsdHFW>IhW2` zej|zbo|ccRE$KIR{uDm0-y3wCMy-+IJU3mg$0^@7=LmwF9DFNSvfH_KF?z1^T5FD- zYg)gj#Vt4+j~Km}ocj$6L-x|VyP)Lf!M%Wczde(i&09>DPi*CBUHNT2s&3j&EY4Ty z-`4G&BfS4QTRSWXALSGzw^jE3Tbytd-HiL@Xm_plqJGn#l|m`_7_yZ1T-RFjWypWB zo(uqdf7P2R5MG-5is=m^J0cPHw12U?FO!*4QtqmzTTD;Wto~+BwU+K=G~WDohXo4N zi+5qti(mVhmX?;}?n}q3bp`;QjXgeNrH#|(XSY|`vF@d13gRjD{Ipdg8&tba~P(xLUW zwUgHQzP*omApoE^riYN_*UW>j_!IFpOTV~6*WnCy8iy?1H=;4kFN6pCcG@rtvSa4s z<->E#Cp$Siqd1{BQjJi0)B-Kys+NVV@S;$VTX!=?CS%H1&DgheRCFxPt!q1+#mUgj z=+lr@(_f(w9?1J6MCZqZfugq|F*8L)MGy$22r|0wBS>cdJ-V&A8TjF_83}={L7$NT zon9L^5BKl=#ZuMr;wGTse8fCNRHh_cs@srNx1fmB_M4_s;*VzBiL0$anqC{QfbtEN0%LSK)ldQ^M0i3uBkycPqsPyS+ z1xG%l&4rTk6h`}ehmiqoAW*BwW|3Jz4`vR~ohi})knQgbbH5JmgbiRLsn4vS$uPlmYmcvB}~@#(y-}(FbP4j1QaOO zBt7A;!4BRQlFiHpq$!hX(TPDr^&&&nzx^RP%*HvCdG+|!0H?YXvFCIZLCqT7YGbbW z6toTFD7lg%m5MttZME=Q6NfsrE6)RFJ^_F4Fw!%^-s#GXCrF9=xj*EZ{dje`zV~3M z_i&8itJu@1`i6ecxpu*m==yA#@W#m&7CcR)7^W?BeS90MvdHZKS?hf>+j1u{$u_#@0OHWj#>!8bhM8z z7vSj;{t^>g9F7B%PdH~vZ;fc|?*6_r#oW#N%4@_+gse6`<&?{?epjC5wqs_dIG(v8 zV{_(DxqF1gTWinK>XE1F*u(^WOb1_`YwKquhxpeA@#xGSmEO!i?8~r8e8mvqzsXqsvZ-y&&Iwc&yciKjwkNNszO{oE*x* zY}r+JRU11pkRrNxlhx1*ozec=J@NK(s{e-!Wx3XLdn{Kmzl)*`?mX#(`>2ldE{u`# zKhU6tQHuDOO?cpd&n?kRJ1Psns|{v%=56_-ujUj_}2$J(xcufgSVr*#w-@% zJ7>e}r>DLgp40NZ*1B7V^PN3>jGp5q$fd)%UnBs}^* zcuzQYypbJ=Me0_VKGV4awls@#UuZb(U`I4)S*fo`MdU#YL_<3cmuk>}TlDxuCEA^6v%2+^1R9+S3k!Q@$B3EZIIV_* zRWH>Sh|#D7Kb@47$PetfTffcJi$2XaC5T-fYX6tDR7@%IUj9NJH*Qd2P0u4{MB!CR za}r5{i-SLQpHp$Ltt57*ob_}{2$!-TY9-+KTAXIi{~>v3ILE)DynK1@dm3#9xN}Xr zkmDh1T+`%Askx&NOjt>&rmbvWO=dK?gp+q7NPv(sz!puGIVLZ@f>z#Ib4ji`T$zrC z93~BwhMvj~!us5KJlP=8BU1c=f=No+ly)6{6iNlJFALQ=iblWEZmq7<8un%iVsD#& zhMEI56EvEqjp2f|VL)YljT#Dn#kSHxm@_LG+AXjAFz7c1T}oJ$L~-tgb~sXaz`U6n zL)Zq$8mN_4GYWw)*}Ek{3_V!UZP(;xFJ(OVlA<&Tqdqj|>J<92npHKI(gLuK^q<6} zwu|njK{Hk*)nz0Vs$8z&>}{W-s#hDLrER-Fb95m zUhx#8>Zye(qR^!SwZ#~Q7>^~JsokTdPW4^A>&KNBW)0IR{DZTwxdYvU{mE$#1lZEm zeF&^+@OeKS%Z!D9CFX7Fc&(|PRMcE_x`Vomv`YLOvGdl<@B2?PvQLO$)KDOy7qe*v zQQI1jbdBqxx)6vJ(sAoNTO-8iEwS2Z9|m7~ZU5D^$H(;^>Q5=cD(Edo(7^A?F2*1+ zf1mR#^@yA#%--AJ(C%F0JnxKGKl9(SMD^{~#Q%;mw{8fbJ?x+30N-}h+wkLLJJ!A} z#S8}0@kT%I0>)~<`_R5zP3O!?Gb%3MVkU~H3tV&gui0%6O|a_=>W7oc^&yIR7RKHyS1e-CD{M8vR^L zgOo1~d5y|c2K(I|=2?!V94B72N&>z^*_bsO5gGyNXz6aiS0*@h9boF?{-r$)#jk;< z?ghiz)ma`B;+)9?+^mPKEh%rXu+S$^|AokHVm3v3`dJi#1lr&iz6vc|&{_Xr%riax zQ*sfzM0c-ed40VS7vHoi!r{yrA{ zciP9pqjEhuUWE5&J_Yfo!5oK)1v`&oUof``YNSJ&6o3>nZi(K%LhZa0_>-9^Q%t1G z<>S%f_rV8j(7!|G%kP?`N^XAJKt|4Kvk8uj_KBhXPk-$+{b~&BmHR2JCG)xA2-(L)ErWcxWu?Y8-7hZOF zzs@2lOx)=dNSE)2mAQstMO6(Rz`v2sGOkp@PA&3}WQP3xXfHK51@#$Ej+H;8CM&Ou z+kGf)`6Po?J{y+HmMs1Yj2VrFgC@NPBl^3E19A_n(iAInFHhO9uCgk*76lPS7HY?Q zDW>u&$|@Rbu!|f{wgN+KisrN1w{UPq?IYEB=7Z>N|onbB5{au$H(cN_%?JHKjFfp>~Zm96#TA4ovDnnjhC9b zt&YByfS-L=zeA_Ta?q^f7vy}>Jf8dg)Jd_}2~jEU&TrCWSr9UvHIjEKGD;D(&&jkW z8FC(Em|ylj13a8Q_|=SAV~&!Wh%Rv_j!xjSJO+Gsb_DwJr;qLd^%Fa=UzuC5j(wq) zH(=lmpXZGnUxhFOTmehfu)^D4%N}+W%Dm2q^!%wMTiY1h(t=GrGn2`w1wDhB9zV;} z(f=%|hsXHT?t$*LOE6z|iB&oNC9?F>zWV@UE@b2eA()@flaJ{uEl0iHnN)Gg-7v?~ zKgt?)+82t;MwJ?H{!vsPhWo#uoQcs?3;2jT7m_X z`yX?dAUii?(>arB!)a?8i{~p%_djZm5WlpL9qO6voXiLBoE zL(U`Q%)}3;=ik3~j50$ETlpEg75Dge7Llmd74pP>Vph$K&!x5c(X+Lhwy z1f2f#9%;?xoqlV|#Vj{dtx3g#KZ1*4Bv)|>UBKe=BsUZi!>phrKZg%)e;qgolC+4X zF2B#^Q4@Dg20xkvn2QUDHO}(Hv+O?Ez3pb3^0dF(#F1kX*tK5 zt*MEB%o-WZ`SK<%1T?6w+LQyBAR#lf-6?#qQVD@CUR4BGvcopakB?e-3xv+{GI4M| zMbjF1mtE^5(siQ;Yfo0U5ShyL?9m0dDkPCHO9hzZmsv>B?zFidb+!s2Ga=ewOj=Bu zbtzm}t9MByEw}U|=8& zNLCgI&qrFWQuZ`^3hU{+4G$j=I}T$#=6qFP3VsE+KhZKCTdyL_xxM9Pzn^HUi#{DT zCHU<%Rg8%h&Y`S~>tG_l^li#}jgjTY-L&W8K9!8>R5kJNiJ3aYd(>tT#0}(Hl|5<+ zwm)cyrD8N=sj8`NdkeYmHs_}rA3+50KY7=V4B|#)v?_IR?%F#78;&{ zXk+vS8hk`z3S)JRYxZ}oai%LC*<6aaaTG8SRsxct-6G*z((2!mqdY}uIVKXyo-64T zMxEiO)lFZQOq!b58XCgNLVCsmFus8u=<>Hh`NL+fBxG|y+u^gUY9SMY3w~U9LxnUr zYT=bxt{tX=WTO{KzXgv31*@9(iwg^~ob`W>3kSK#pTy(2=~^)|ZRl z+wv(Z6Y3u30S_*@8Mj^Bzi6&mn94QCG1+U;&8;?D3-n=1Ncnb##QoH=_j1_Mv9Pev zVX$S)lc9I{hci>WK_ntuY&>@5*#G)*Z%_99;P!Ooz#GW}p!HOpLu@iIRXwNhL?fDK zX2Kq--vNS6r?Ke8Zw7zpI1B2AktL^l@1cg8WY8JBe>LX7CU4sQ6OZYk|Dm5vNaeul z@o_LL^jZ|_1Shw|H6}064DE9P>Qi%L)@0m-%VXA0XY46U%&C<++aEKDMPMgM;nK{? zdnACq!%Z9KTdqwfFw@{5`hh<{qkvGP@aWLM|tuVEY}uv#8BU?w=D` z9SDMcI{X8&hC=(6Nd6;TK=;0)vqyfP;>UA!*O@WD`bB-{v46E=-eJOu%6qbl?%aEM z$Y7!p*3eCwv^ik!s7TtqTEF{#x+vf6goTzinnDmx67jRiH`PD@TSNYJ)SeXZ-Wi>8 zmB$Qb1{L=Y;5mS}-K3@|Qc!`*;x_=nd9$l1zfR$lBJ3u{+# z<&PbsbAG2!b{%yFZVDHU*cb_n%uwcNUJ#g^eQ zlAPpMRZ?l~riq#}`%E)Pj!MyV)eQ&34|1`a61#`7|TT@9ipJ3%6$!lGno z8Nve=ZchrK_Hqc8PVpY$OwewqJm{PX_Bb-j5Mny2ZZAg|!foO|6qYqcsPB-b1tRI??I>m!3 ztX-snVm>En&o2#Keq4hp?D#>jSjh9uCQ9d8b`cLPdin~RMvSQ2UM(yef%ve7A zrGR;e<8f0H7U^?9aK&X%s|vBj{+W`QYvT~?@OBNb;YX}ed2h<f&B;~=vtpq7Z%?3_i@>eS!+{r}>A)Y|{GK+_MXVWdsM(^@jehb? zqUn%^fnMpC;=sN`|LNJy+k9`oA7@k>RyQ0$pP62fl~6n{^O}VtbkE7|xaYM2LvjOiV-$9jU3w-oKM0dMI&<&x%sty^E&F2j zCt-pz6RqiJs(~fU2#pur2l{k&Zi_)`jUTp~slrNQ^XhhNH#cS|6Ytgsz{d1fHdL>9 zbge7437ve1+pp>f*6mPHQ-_gT2o4MADR?ebHlBUN;k^B@T6Zy#o?QiB10Ke{ds4T8k zhs>GEzlZfKv&BhcIi-WR(4g19_MasK?^f-C2toopePKu>zHVM_#7u!eyjQZ|@hYaH z+lAw$y3xAH80Q8bcT7pq;GIhcjpsG8xp0@pvQ4Ud=|fX+MuhBZnezJaO&NY!LazT_ z+EQyOOMSQ3Udw@LssEnO3Z2hQ-!2VTx;EmqgpxEiU^o*dI{X7rFY}U~`@qrs*`fngi7|XCj?khv_BnyZxyOJ~qfM(~sEaaLHB5l>^jPn*{6SRy zaA?G60a(NKVDuBV1Du-`f7!m*hS2E>DBSbjb`=C!|L<4;GmlyDPglyNxVb!)GpE%Y z%gzmv6H0k$?R&*nj0IqDT-$06CIwoeI2NwI&WrEO-)q6zVLdra6Fw#Nno?`(3Nk|> zl!%1bnlJWTXGuREv!T~~8!TLe#^mRUHJOQLfW>a934;&AXp7cVlxpI^-#$DIgD~IC z4jZYo?l{)QH`m(?)Vy0zWZrr7a5wVmKJUD}k!R@}mfwI(Um&yk4lTRp)IuU$lGD}% zl7tD;_cGoV?xI;I%Bm_iF^PbqrMlqbr?xtiDTap(A_aymu|j@kL~N{*IPF?7gl9~OZ(cM7~j)nDy>b+nLNj5#Xb+{&XDU)bJNrtsShTPdQ~O$7i=i!E;{yo*8sE3wwNgJWi93q6(j* zOsZ77IG!H4P&g<9HECu%3hg672=0RO-86zCqci=3F(N1a$yH7;*{o$RKw2d~V=%?!fSE31edlPp2?k3R}K!i+=-N*A$4JaCLfJfh~1CZT0Rk*X2DWO!`Vc9=TWg z{{r6tX>wFF-uL1-&b%83KszF%c&f)q<#VOvAX};>w!sEYg@o8iv_|g}G|`w!*ahGB z!`<21&-wXFSZU&e*b=md|%i#129Pvw-+MmF6vER_>pp8lHo>b zt_F`aP4rBC_c{)K!t`z$F%j##A86@KJKR5Z*y19)=dAPIjiX~C`CS!X zBl@5BJogP?QM}!34@BOdXr{;rGhvDRwoQ<`KjF4vAdmU8lGI|picdKrFas8M@aS#m z5}0{d=K`1el&rG)e^=3zfz>8HX|YL@9n<5!a(FEEPJ^QkYJVgh8i%uMS6W`O?o{AW zs&u~{FRzzB&nA%iLcj9wySDu-5@jVQ>6C;)(4kITN*Tv{Jd|%2wqjRF2?6_DB|yPE zU;4^99xfA~vpxY*w>6vsmkoQXB~tq*j26^$^Z!Wu7mRVBr=;w$oq_}Jy3*M#hV6T zU|Q&@lh~SG*FJiI-60#Fy%#QdOqq$g5*G4P+uR=%nav&SKTo9 z73}tOyHM2#j=)VLq56u^N}DC^oWiMGyU2nat8>}%1vQ$p-))Y7i z%ckL#pD4LBrfCXXl8v+8#S_MVW6DX2WlXG`KUG#Q-paLbu8l?EQ@}q?Q#%UPi zL5HiQUyvhr-e`FvtpAG^m>f|*LW0b`FHH@dnmt=kCE+_mJB5liVpf(Nd1j`*{zvvw zM9CEs-J>fLjl!Go)^Lf|Ji`wRKkUVMKki9Ix0_au<7FEqb_)X{?~^9NQ{u7rNoGB1 zDU#8JKt1zM{YbT9O=xaHOf7_^>4YB;yV%t*Mz@-%%KTzinp5{}h% znc)wU;gS3PGA4STIx1rZFm67<>ycXor>K%E+_VXFR8}y=pqzzYwPaF1dRdVu*zb}A z>{-rlsFb?T077;3#1%DeV6^w+!$FI*u7)qzlgXe&;dl1ngNJujxHuNfi{#*LylFUy z4k13tt<+dYGK$8w%Y&)A;W$ZF#qOd|l5HoM7w?TOf7K3ws<5{ssduj>qtO$sn%cMv23PZjUIycVTd_3AU^B4?a4b$2XGan_a}~8pNtin)vbxIs zfRBEDUNS87m!kt6un3`@{LSjIX?0E4`WzWE4;$vS!RbcwqPNQjkR`nnSXA2-X4n%0 z0C^~AS9F7=@wE9rjXPQ~)6EYI;$vAk5q$1vf05u%9$5Z69r-VaROxnQFASfmyBNwl z7vl!LctN-K6D|L!C6_pxW&R5wS#o%^9|}6)?B1=R) z+bN|s{oBmRMDBkPZKR3%%ba0}`4A!gGr8&&9O;qW^YnW>zVT?gQ0+7{8w~Sjs1jD( zpnlHdUn@_+v{{1U^BlZzA3Q79u!s!zyF~9mJD9Ob8-5xhbLAtxH}70lF0J*KsH{nq z=6t@f#So6?Pi=K#c1*3*Y&Qz0CZ3apDZmOIM~1ga%{Mud{w2|nsXC*A&&V(1kZmai@r%c2epU|b z%M1k%i)aJgNrp24j6ftla&G{8rpEy*J1=H=GyK6_4|=J`)TzByVDx{rZZK za>K6H=K`2#P1^-m*cc0lKO&Wc!J-bWR zK19aic}N1h%p{!2IwgN=RI{?HW!NVv*b3t?@5YBwBdOm;0C=Kj0`^wd!{d$B(MBn? z4lPV7 zyKA9wMahk_E#=!uLxqa09y*g;>fG~B*Z}QbQpqW`dkQ*}laj|Z_Jp(x^RlTH$cIJ^ z((67a5g{0IsnD^mNFkAYQRB?V6f(0T7SMnt27){ z83g9cj~df3V0R3)cW&Rl&g?+F>*_!`9D4w6@>q$UcUL%Y$kl`7hcvrJYR_;^&5$*za)I}={>%9!y1M5B-oJZp zS_jcq!tnXf-M=}O?p&gxj7qj&?W4lYSxx_=>*CW#kVvS8Z9?p+d?tm6%EpuMStmIT zV)}us933**wq5@b_4qUB2AtFUY{g-j7+%r7BVJPTAJ!POw&t16oiAdxIu>Wx5@r); zH^X3qC+uG=0unsB0(5LLY7=`t%@jd$q`~rQIj)9=VD%Z(_Xy1i=Pm&*U#r#fJ<>4# zE$?-mwRnL;=%bw3$l2bHm7hm{hf(Kck5K7u@jR!V`stp&32i(VYW&^vk|g5Vy(6do zU9;W9=wHIQq>vvzcvC~Y9}Xm!9Z#omw((b3M4m*y#<%=*yJcNbq?{Tttq2e0%$oR3 zkqquw8-#`eNhP)AwKjhMogj=GAC1UCS5<5mvomgv4l6;d?7z@zv13M4lvv0@WADi# ztcPfb?PN;8_2*v%TIXJ(fj%P3eTlcJNLj$A2d%XK-lsm|_Tcz`|Nz}+V9I%H;M zrdHbe(2+vci%w&yT=c5D#7GQq*b&P(ifzm;2@Irz0<=(z}uLID|q*YMX$>&R+?7) zaVCZ%fOrkZwawC(tuV6C`vy}+dfK4JaCDdR~eCh~64 zyZ`en(E4|9`c>u~mPk+Vxyxypebas0op=wgSwo&F9RM!~DWC?2X#pZNRnTh&>z$Fj(#k zT{vkY&M9|@6l0~Ydq#y5;@^FVlif5(1tsuoA%Ac5w+AG*6xi&EF)isS_Ei>R&tCrl zuKWdN&2d!=t1y&fLW|Kk5Pt(WoHN;2>|oI8_T}{uFouu&(CQ=dpI@LDEt&?qXn!xgR~*nakiKjqy2a zNmRia~8-3CXQho+4Vbbi(Yz1l<_xs1WK()wtHzN-> zpfBDzu~wt&ieS~;^|Fl;R@~5lTP1l5xe|wt#}>1Ji$2>tf-`Odr=pfzpaa}@bo$iv zbiW`lgArp|rgXC#Z)TS9uKxZtp>mn&)hdgaH(l;l10ubDGZ1wRcg2-ciCTJ7aAV(< z&sRj!OO{z-Y$eJrZ_F$7kSC8P59C_dWVWCJ!>vV(tU& z_g(d0kB6`p)y^w&bt#`@NRz7_G}}Wqwg?Aq%y>GL!)CXyy~i@x$h(V5T^45Oik}nN z#d?{_&=N&OmNdd9Wv9eX_nO@a++2D$Gq*5!_xX|a-N&V3+et!BCs1x&9Ja)(p_J`v zHnhSeO_lyaW)Nw%L1xyENB37a74KR_r4ST4KJwjtr@~{`j5-TeQ4FvpYUjL{k)#%Q zg4gDba}~ED`T~2HRM5!Y)1qC*$4SA|Q%W&SHxHfDN6Fm0ypfopFlM05wWGuxjC|Pd z?oV16GxK@&o63@bE6MDo=42nRve&eDjERmCmOok*efSCf%u^W0Q>TTKCFZJ`z*e){ zp~>otDK#Z61h-fof8iJ1#-T_na`io9-|kl*av3uowv7<5_FO}G!D!YvSxU?nSzbUZ zMWshVFRgOF?lEQZ1bs@3v*{==NF@JNzmqk*D9u|JPytnn z=FdTcv;TJ8EFk2Vc-Fu}nihNZWA!gkf}A>!aJ$6rKVbSWEcVuy5d6Zmd*e^Z;{ssh zxXsNd@#qtkCV?N{@DddYtd@C;um>F5@zsteJ;XSPn!T?>$nrbOUfFnqf&}RO@1Mzk zCT8=!UQgcdP!X>@*<39dwv3vO`r|Vru`+%nmE| zAA(>Mpqx5(JMo~i^%)PS{1g|`KeV}eFN;cI3waa5I)Ko|+~h=FkAZ3AoKTI1a+UHT zM%r7eA=_t~ImKKg&&#M9WbG6}b?=nGL6uCc3O5eFDRnFIwsD12!E%}}G zILC*vYF_H-_ZYJP4Qho>=~Vdwzg^tTM*($_=UrT2fzJ+1zCbL7x}dc%%2)@RsiQe3 zX8UHD=ImUHjocJ_8!_R7yVLVUR46GMedwq@FVP;EWwT%KQ1nD%@C(6rBN>CTsu!4o`!(tf}@5Qxz^t= z;rMvd-^D=tQV5$Wzfj0{EqK%OvT`}f7%G?8ex~FNls&>`UtX+}FRU<=Gc}|5C%+CQ z${=_Yb#EC95y93ZzpIRiEh}@YDsFVA%$(ib>G-FsJN>{t2+M&>LEH;^39>u-$(z!g zydEWj(%(JhfoLo-&zBSS-S=>!0rPSxl&KDl7*L(oZtuLn=$c=OY*U(la@s8@DsIL! zBK&WTWb(Jtv6q2X9G${=r9G0@&mUJLNw6O%h&pJcx46H?J&^O#Z*JVqou}K?yB^`W zz!@wXLZ%{mU@}S!B?0Qdl*~7P0^zMQo7Bw&C%cVvBAB$JXuQ(jVRXoUd~1lzMM1Rf z=dtfV@2itjVM8oN;99)hv1E4s83mG~=KMr4Cg>fv?gtuO_(F$>ZV;2?f5>!qKEhQN zwroO@%ASv37-O&MvG`F|gq5~aQ*ftccsjm%fiK&J>ycokRE05{QOCxq)KR-BjWlVW zUZ%Hw0VA@-K;LAoP=D$eyZQ7~egQ6FmbAth+VjxhK( zzQbc3L7zVI zh-&B36$72mR?lWo_euXx;vMDprh-bFH3wlhHuP-<}@O_=LOxHQo!MJlXvkP`fAx|y{uwGgij#AvS?r~j6i;JQ^h21Sba3nuoxVxyF z6y!f@s-m2cAO9!l3eh&T7vY~Y)o`~BguPtR6G_x~ z2=j1%+7ixe$;gX`qQT2HRf`f~XjzjKPzikrx{L;LuZXhpkptdIf^|*(u0T!tjh!Pz zp)Hv@abfKfIaaX04TD;MU$Ah_*-^#`($PO~k*N3m2(FI99p*HI|L8avN{;{V#{D9x zs0i!eW%d+?$rQ@(YI62wPnHv2C|hmm=F&|PDuORH7(0HuSXh{GZ>%UqTz`^MxW_>L zzLSicmfWmO@|R29Z)7_0Of5;5nxLI2-urudU;MIMhUs!GEjmGZ?QCTmH9xK0SxosB}3ausF%-W== zfe_eW0NY{;6}~kyJvY|&gblTMmx*S|ZkoI%7LzEA0boG{CmpvRZluxx6PsHE&`vRm zS@CSBou%72fu*iyCW9eA&Ct-!3*--1n;N$4WKaZyU|wIy@NhqE?FmM0=KX9yiA>Iw zOs+?~{VRd|r2-)pmA>c&{eCEDBR(s0FC||4v)$QtSpT_N;O8a0h-$^5$d8hH&)90} z9PDRe`k$ufozVY_M$$S;{1*1zW+@_(Z7i?0`wr6hp z7GU0>qnm^#b9#lbJvIWJ;*#&`?8~XR9!lO6uUMKFZ3PMWjhyMS1u)tA61pjJ(}2y)0hFa=V}Egf$^m1KZCJ`P zrrR1mn`=eAC81kaeRiZOf%b>R9s-x7p3T)}D@8Iu_Ol#&r-DG&Ec2?7pai+XLtOs% zd3cM}1gA?W&swa8yQQr@R%{{Gm4UhpI(TbAcB&PsRaiW!iRtL+gqLD_(aXX|QPbxL z1g+yTCvFtq3Ij^@LIX#u%e%>ho)W$G(sW#^`AyYyC#O3l{hO56zIkbcn_Yj`YtOy%+;?PqG1to>#I_wxSAg^v zUijPR{`SkJvEz=>eNlxWf6z_%g}XF`xVZl?a{8waf4bpKM>NOf;>2`AbW_wVh}2TA zAR_a+L*8-RDu%D>I7C;^h7iV;csAWI<@@TDdxYZX5zv%SMjQ)!oGDtU)eD z)N~dSrL$=;{r;vA0FT`1XRfmEhDF{ty>K{QQ50!Cmx!614yf-KNcU8th{=(JOan0K zsf$yCM^4i~&jeq>jtRIaozBtBrb1Kjbay7EOAAEr&#kS+0?JX^G}DjY0{=D*jp7it z9ME4-6(!D6qjs5E2DZl9+n_cj@euy5}wBE5$l`i1)P8~K#&sR zl0tsy$k9j+8WT)Yoxnx`a>3~{S)u^RY11AW>{Zo*HEGEyru;TwI$@Sro2z(uWYfT8 zJ=jgy=)$lf7zfgmIKKy}+7J+F8@5D{=@gAZA@~l=G=)i2W0a2Ro{k+ z$@CKHY*j!P@){4E>uIEWlE0+D@HiRp4bv?tW4wJO9PaE72L{3|%q*wMGfgv1!!*a5 zI@R1xTE^yHr1Tn@Y$D2U(;S`268crBOiv9T**DRBgglz4;1DEduNHlrKZOWSE(}1- zw~iG3ps@@nnDL{e);u_hd3$rZ%!#El)Ee0?IW%e3Dy^r7-0b)j;yy_|flcD5sgmW9hK4LcLQbG&jQ^pb z$trcY*jR}+YsZ?Y5N6T|8DZE74jC>^qS`Y@K2{EO0%kdRXHYj#ch|>2-A`2Z^Ivc8gF?eL8QO`_pzg*C2DbuS^Y&v( z&5$m}cDyZecH*}e%L#xhF*%&BEs4?<*D0Hc{?$>l9kIJjGl{kJ?~iOm zsbpepKsv1@T&ob=^2!CoG(y0Ab(;RNFTknnx}0e za;h(Dbd{BtK=*@hcQswk^qWJvOPvm-Z@AOXUgAOP$hq&lC^h{>GpzhK6M(>tef$-Z7GxmpTrUKF_MEG)pb@vgpIFt$dyLCP=1x4{)O7+p8Dc0jXmIZM$RR>h zt&vkTY|7RzwCN!J#&mrRy}ody{4m73q^2wRbVsI8=?UiGbh2d(C8D6;;J(3&M~*B^ zz(E9v5?7gyp=FZh1$})cJT_g4t&YxRF{)dn#z4mmvM!;7q%MTNvAZY(3fZm`@klxw ztkiH*AVDL{!tu<-vC<5sr?WEy%9<;W`^lF6&UV0@EP|-`*(CYf+lMbb_3YCora$Sa z>5o2rv3b0Ox(F}}*5Xc=nWdTtr(%&&%mB(w7J7SYQy)$yLeY@^l!4$M8ZmiFAyiPG#gAq0K0eR2CmLfO)1` zixn^cRVI&JoEe-_GpUnsXkvl-NidXDhDlke@s&tTH!Cjha&Re2;6m4I+Dq11kX6nTriIpCVBXgP4`(d*aH*E z!Qi0s!*HFbV{$*{D?C%iGEZ7YnOVpP&*v2-2)R&T1B&q_O?|2}O-o&Y4xBkOM;eYJ z*{hPl_f(c6Rw*4jHeIPwYoLbLq6qyQW*0r_C>E8gP#7b9P0YCabIpl?%i&Vp)H z&-tY=9q`0CDyYnv0&!YpVf9DPLUPmrpV1%14z(-L*<8 zIo&0Fk(zFT`p=K&{u(k7?dMgrhFs=@ws_t00TlN&X@&y^%S6&73c!d9h3{>t{f88oh(l)%0EdIv#TjjdS-AH+tgW z^0gBOmzG!2*RRvo(e>TCuan*7#L|h~yHCunUe8}Uv2=~LN0$!#HA}3{&0gPqVs!Lv z?@hm?=11Rv(=BznAl(CXdM}+ld-jzVkREiPVd6+0;y9Vb!Aj{<`%QQY#_Q6bx%^a z!A+cg%Wb#r??DDM@!Hx4(iw5jN0q5oaDeaMv+K^=T!g8U>S1-H?AvbJHO&G4YDk@f z(E+jf{!F@FI))7$my2oWvfkWbOzyEcgw92f`^P<1koV;tU7($x%LjCTTMyAurPGAD zQF-X;dH|@EEfe4L2z>socX}-C;k7uOf|zbC8!6Ar$3FJ4cmKg1fBcXB-M{-sfBd_W z(=CDey>2n%a$iW-h|lTTtg*kz>YEPfjn#D1ST;JF)_L9Fo5ORr+SV)PZAu&1s-_Fn z&1j;|$uCJwzkoCSJW~4AL;T5|ZjgSV>jISi6Y9d^aI&78o*rLW=~`Jy^z@v=eC_~! z3!fXcYaI%S*unJUU^@BNd#(chSMM*Qv3E&Mzv>~n<($Est~~B%cu`y$8tgc5dRG@A zEXtPA(Lw5Q9MVA|NQWYE@MvnNulvZpeG3Ak0el$*6ViAdx;x*ina-or)3riAKSzy_ zZyL7)DU2pA0xu|(&>Vj0Aq>K5XOcGCgBg4povp*sV4PM;X~0sUhl9z5%L4;4&wT6p zwfpL^{+ZpUKqT*rYy04L8NvdJS0gO?%LWG=bT7hA{zk_&+e zYBAhOvbnW^EN1q7mxlLUy0q`%W5*Oi3Z?h0U(PLHwCL?6`?|sc+Aj3-5L%A|+HuO1 z%h|9|dcgT!pmyFZDSnB`M^jF<@M$%5(wNWWP^uhi9>*j-BySOCN2MsjffgpK^V602 zW5)`e-N`;$YSqJq1X*gV@bO@!77#lvTdw8 z>Ow%j_>}N=gh{^+6E7r*#*HSiyrgC0uU2{5fFhp^5JXyAzj!L#M8HN*7T7BPIUR-^!h6ncBW%Gr+-wLfNXI|} z94oUr_7f+pYl>v-EiY}?HgC8s2v<{|XwxuqRjNAw6(Ftsoi0Z410mrlIxn>T75 zc|%D5CZVM-Z4@t#^qVie_8iF=0d+H|dvbc$G=%=67ycGh|FSgp*N$Uj*Ebw72_xohWs9$DW&={pQ8 zU#F()zU9r)kpJ>1bZhShw%1IjSuFN!qlN=p2T`e1ZmP@tY`e(uUqwVoug9#akNk~SfotdSg2H3if3|Hg7Miqji~ z>cp8dC+jVlGXKWBXF3AaxndN5G?cE~cfFHS!z41HkxtZdLgw@X5)bgTqUln!+}iZm zWF^14rUySlB+7u&7s@<9Dn%N-0e)Tb3sPC5L>7{l2{W8%MXw4BJ!!hzJbpE{+Tj1bxhMSz0&FR zXds*ASB{zs{y_w-x>Dd@u8!J- zi_6F`m5OYp93YvCr>B#JtBJ(vna+STTRoE~Qx_s*`A}$Nhy;Y~gj&Mr${B8&Fm;ep zzI5zhrBExRI#X#1YI;uT}}}B>hh`DV`-}7fnA9Zc}@&90JE<4GKZd^1z2fYJLgdI90mIi+b*2xj+TU zSrT57a)&P)kp}X;aNnGfp5BU+9^VUjC#knk<>2AL5Pv~!;?$|+gleL+Y(1T?>G=u{ z6%K)cL>(X}vu)30Y4q6QvH7AN9Hnu&S93Hhl_o(c-=rv&Kc&|J(|P_vb5KEP=|O#6 z@WJa@lUKaE!4@KX6C>Qv8VO$fTPP6MR! zqFWxCSdKQC+H%FYnkYR6odfDlMi%o__s)m?yKoLY0*f?u253X_#(L&SBI&_9;bWe7nxG-bUqkS`Bpi76R1mEm!Pu_?(naW0bE~!d zv8BiFe&8;9JYdZ@nX$*U!>U2Ua|3m8x>M7+8g_B)nFA)62M^YGPT=FC^|#=qKVm;0 zZbXCrepOg6rw&@Bhq4KJ@Wh?%KOJ-IHjZ|E=5J_wEmq z@5OPtBYL-?2AccCF4)&Zsq?mJZ{J(tyOGgl(~)^cw0X*}XxP8b@}@)SW(haR`txc> z2nk()4yB)07%4Jv6D=FzO?P5Cm~MKxJm}+=N8Pil`zpGV&Ly8~Nq?%wN%nFa+sru) z5_m|t|IkXDHcmUsnXZ_KoTK;~b!1d`YPuBlGhVjFlV{fOEsE0dy%5Z(5TRhacRZNH z!yTQR>Kon%s4ryoZ_?jFl+&7&a~}E+bT*^3R_065fy`P!n9ePsl^kHv=z>r%+B_5r zwWmN^f-=!WVX9;_n#^EoA0S9E85Ir(NsZSN?LE>rBTWC+x315fIoZ}9=ebF!7B#&sR*Fx!D*Zt;VcI}Gmz?DIC6SlU*F&n*j_UKc$L;)xhEhX zn>PfQvxax#G`PfO_gNcHO*EMrMyVd;a_MA{7*iS_*4<%PAj0QVanOJC?e!=8%RK)I`$q+^{a2P!qAKC?9UMR2nOAm9kJZf2hZ5*cE0? zkj5O-2dGW+t=u>n%9($ghYno8G>sXJ=7Xih#cDW1{VY4t7fc9-duR_HB*nY zXra~tId^EbNR&>UMV50?yHjX`H5x8g=JPf1gTu;FOMuYvL#c65IDj9J!U3Ub!wp0AC#+8kRFLp$IyoO%CvZQ1G`5k<} zH|}iM(#@B?+3?~KI=$C<(l<%z0&I$UHs}xBq|YSx-hgknmdDb^H!Gn`Z1+mnA9zE9m()!mtY)LGOa^$kwH_uhM{-TY#L zy7xf|((!`0hKe>=+N5(KEpK(u)h+1@!JE@M zcA;@?$r#&EU5KwlijZ=yUYf00R&^QDvh2+YiyNcMCYs|#&vZj18 z7AFd&J3=>B=h597qPyUpH{bcTwt9YfIakc{ttX1Kvc_>MQ6&6c&lme+Yz`qEGmgya zb#kgBuv!n~s*GTb#Fa6A#8D6fD6nz!J{QC0f>UBa!4?MH`@n`lgU6<=6 ze{GcXi;q7;x)-tsTthlPaU#FE^vvjqgXrkap^n_XclUDs{|1=;{2Nj_0RQT%uRizc z^Upp1{PW+}`}@!T=(*>9^x})Jyzt_8UU5koF}RF$oqt8S81?tu-~Q;!W?3H*0JhFp z<0#&D{g>()Pj=KECxp~_ULGK6$>F>AKYriDJ02IA+n+ir|5BY>Zol(D4#}KkTgWSmiw`aB{@elfw3jB9?mkQg_Xi)eeB_Mp z*+~)@w_%bv-g4)jQVVHOWlrIwQNy;zvF?=RZy8Wmm3jP3bMPsIZb#ArTg-- z>$_F;lhfG9CQ62{jnJ9o$>~PbmbyjO^mmw;E;ar3J;!>wI-B}Ki#u5(d0G$?rJogiD^^rp0z)Zc^80-#KYRQv%NV0GX#?9e={OrX zK2BiC2yKzxf3@XM*9ul<#Va+AL<45Q*_dLme&!50Z(A_iLV=L_K&oC`Pvo!z4@HuQ zy#+Olb9!H@&t;%%D;Cx=2*o^c>Q9wR^JBIAbS1MRkP8nq4FJ31-GHp$VC-NoL3<>V z4#C4vnJ`^R60?%7iPcO_VMmYz4%+o1Os{_H-+$|0{Pnl)J4sWdEx28XA>GIF$;-jQ zkzUmFr~liNk3K5T%d?+->fwiTrb9J2F)FuhJIy>Y2yb(IKLg z6fo?L20hW9t30HL2Z^(dl6)Lxx>Ql36y@w$KqAle^wfK>`VXp2AtDpTX@ZKnm?%9B zr>ok)CfkX1Red0$OfvXh3c>E+`s6y#UP9ps9{PyV2_qoEPm=SH@g+vHR=UyJ&6W(3 zaSFu1(;XVkW+Q`D8Rh1@QP=6k<# z`0(DxcQ5TeuzUCJXCB}G%;N_h-+SPMgmV(A=UHZ%+%L0p(|}?+4gN-{v8t zGiPD(n{zsd4wk?AeJkIj`~3I6|IO#0|Iv?RO1FHBQq<*op*eFBF~0C4K%KuY(>^JV zb-~k?Z@LF6vc<`Ymwd8a6 zVPti4yU6;Y4C*E+oBzWJ=^m)#gE2Xso)uyFrXpMig!e4vrx$mBZvWl~_n_9ZDS|W2 zI|Clu3w@rqbJJJ_fGPk@D&6_O?uQna=gC}A#o9$fc=~<7sbc^1M&)`4D{;qc<{r*_ zw*;@JiRQ5pN#lzTBuIz8^!Q$L*x2!z%|$paDsOZ(xVcC~_g)UtRg;nT<&IrDA20Ib zwW)ZwF%MCN=nUFKH;F+XUmFAd1b>OG<8DlB3<#@3PlPVf+aq;ld9fJM&wK<-|AW2f z`bqcPI#b(!>-*mQk;lmYB0b$~>^_fg>f4|rbyL&XhjySgPPMW!;IaXC z43OtLI)7}eG+(I(z#cG!n>O1=GtRvYA8tnA4?#hZ41(5STue48;Zo=@gvy0HhclBx8uw=cLY4 zbSWyc@)9cZHc4d`NL!hnF+`Dx7DxC&NA<0 zPfJ^UwYWw;g+QQO)-_TSn^<08bK?5R?MOwc45oKB4NwJ3k=C#`J~WQ|nt3D0=`_D7 z^_X1omKrgwlqkW;u_~=?7NOg0I)H_I5Sx5*a6x)HBDG<$Juhfe!#%NdPLz)4DN58O zz#lG0$##y9D3ayeviNW?i`NQZDOG_g&LxOi*AJjoNyp?7A>m^Tj3;+WI$0bY3#2QR z0(PguLYih>d6+@W1)z_QMLAfcgtImWrwl4R1_0I(OcHs_#!0>sP3jtRxM|{T zxdc#pa;O_EofDCq&L@`Td#T$nhC#lAEm&T9h$2XkOrDrru8NZD(_(EZ6V9Tik5*!t zjM_XUidLU0n66|SfC~UrFO4pbVPK+pQJnTw^2n!iiua|>ty&bz3!nNxI2mhC4^5I~ z2ty4K(Oh}9rLTy5K?(0}@H4P+D_2^&bQt}eyp(Pb_w^Uw^}5*6&2qZnd^4XL+cwy| z0op#Adthz&t>GKqj=>uXI|z3)&af3DZtK{#w#epCxl_o0``<$A63kURbl13BPkrIJ zn{T?h)??HT2Vwn&B2`_m?v+n|3O(J+`O*;7O-|=GXX^$18CTzCdmogvZ>OdkODjW* ztmHy>aj?41m2P4>V-CsbnRi?WZQ8U_ws_d=2>pVr>4@G)>Uvp18PT)-F^jEw(mXwi zR&P^FM=YQ(B-Kawm?waU*Tn>^&Tce0;|*v#_SSAO*)S_tA;OcmPfp2Yfn+C^Y*M?I zy`C+r8(72M!lt2P-L&!*d0p5ubyX!}RNbJej+oqhFM8CZeCaU#EXQJg7u6#0q&rMk z-!(!?^k|V}=(t{JU6dihPG_%;UOVx3XrOza!EL^@n|6%$?%jQ2>F@sPabY^ktj^_^ zmdNfqI=XsoSq&h8?z7kTF6Czz-|m=x>6pFT#g?FsgFeX;{c;QR$BO1d-+31Yim^uS9UYM2x$(JU^_z5c^12k9gdkl*dh2z^ zu6rI>E_?SO*Yj>%KA9S)yJ!#fIo+On2<;9OMm9e}|=G#F`GJ zfAHP6es@f&Yg0#j_pVz${@6eH@Q2^?VV+vb7qg+8J5D!~yQi{iineHY?kWV@z0=Os zb<_MQ-Vtu}8hG9q*qHa04Efjj!lA8dI=p`JysYVX&R0;+rKX=(KJ;@vS9-3TqirLJ z=>l+La1+xVr)$t>cQ@?DZCE0^Y3lGi4J6%Qgw3meSeVoQ{xM_cBlM~%+ zFB?if)K2@TnA5rMMkf#mu{$H-;%Z!v_KpwHHsfGnC^$8^?^5Y>ayV`FUw#}=o;lTy zmPBZ5x|BaQU5%#uTL*H%PK-19SX*ZTNzCTaK_CW9kGF?G;V>CCz%rF+ivNt(&SBb< zK?6tXjA8i=Ubq0F|KT70i$DBNSI=~Hq@z<<#HaAFfSgmLLz#lppLq0HQ2pUY9;PYJ zhf5b}a3|0Pr+0l-lAF!XU06F)%&%U~uFhRnzRGK>Yxg0aua+)XDwi|4Qf_^9y?<@>On)1V z^0BY(q)S;w=P!fk1F*U2>FSipzlfTP${r?9I+RY1_2y7hQ@l1g z-cAk`vaCo;XI0c*2BI{kxj3DUOjg4LJ}yvgfolo*B;J+>4as($kj_nVI;2ca8i9ft7ILQkQ}(-XBSR87Z9 z^XY8u;KAkELZK3*u1A0>dD|g;stM7_$y)O`v8NnFAN!Uwy)A4x9@DhoiYHyU$f0(u zQan~Ebh97F$W8k8Oc6G$YfdeUnUPqGr#!?=NG+i`>rA*dMldv$35@l^^kigeXlimY z8LCn5AUD8bEell()Nv}w5-%LWbh8$SwQ(~haXN>kqrg5ik?9^x7LF|Rb+0#vGP1m2 zb>eG7054+t5WaV+0#LfE(vc57_a-rY3r9*zx8gIpFnzP%WkX4aSiy7mdOfJayPIDQ ze>WK1W_lBijNPzS*;Kqyn`TS7O}ZuAk_~H%4K&vF_i(tG`s&i&XGo(?hIEjA`R|raEJ}D^z9w5c-j~@Ed&%0kd&&QKeS7wun*O{b^+tL1 z`5*r9hx~o@%l7)=SM4QmfBw~1UwZNtsp(4f;$ld_^eb0hdr@u|EH7Vv?gdo!D>A2x zId?$mlF;6&i#JnrnEvSp?zwf>{)74H{OJ7XC?P$|i^s^MiL8#UesK5a9^d=m13Lw% zPEeQF>_leko9qqby4X@Dr^D$gbPeI}xD(`c+PSS_h_0aqshf=Mv~(w^;N-~4+zvn@K{h`tPSTR8+3^kk%n>(W6XX7R*E13zUW4Wo87I*&^$sfrMsY(Ta zu0waG7T0?{sJlvub;aqTbJ03*?hswwoeDSI9oX{Gc=sxgOC65X7gH^u9U(+fHAkDhTrIBSI>DGra~_72i8qj>rBRQE91 z0S5+V_`-VLf=sMuetK+rlsG&k8lx#l=XpWWoQMq~KB`^EUQ91|7~=8N_#}BYaCDQn zBTOnm(qy!=ZDo2%L~;b*t$pdg{NW$|KmYLm^@soIOR=v0I7E*rLM(@yWoW2<>Zla- zM<0FazdiXBkpA#RGV=wT$gMU!jrdVj>>D; z!Su9ZL}`>#8NAE-k8PbGvJ*L74U)oz%tKA@>EYLk9g%s2Ku6wcx3X3U4jx&bj81^* zJQrwBVSz~wUM?h)*~^tVoSnJ+>>ByUR#z{J(dX*fw*0Kv9SMECQdt9h)eF?vb93ZTn=8_wCP0pZXFN>vq^XHad13@9eVFUkNyGuB7n)(hm4Z4< z^7-*o&6r+JA+3i}===!O5$YWvWOR~2V0CdUQOf5Fv=c=G2Q-{*FqqIvg$;s z$e4R(g2acF#YLVlqyvMwzART=4N{TsGeSfsVtOwcc{FHAVqoSrE^j){QH9cMflT_3ThGw~Xc6Ny@lhy}hE z)Z)~RY432lHb0s#%`eUu0<_gc<$ziWdq4zd_W~s@L9vvdpCi#DjUp-DAx-K>uGS#m zjEhPBQJQ!dlr5|EQKjsssyT$?1ximzmZ!d=G?(7p;0@UDrjx~)jyYX|7o_4hp!5c! zzfMWN!Q^7BZIJC@`AvIn0a)6R_$D4V^tO&q+6{5NF?B1Wdm_0O*AmjmMdkjV8~hV7 zxh5K@yPlTRTY|jiLF-Oc|IenSE1DGZiwhuz$P_LmU1B=67YXZZMQLCpY^%qX zwX}AjP4dSmgXC4=zf!6>E_GyYJ?(+r&Hqwo33m+kjn(?98QA7yv}c5)OJ^ca43NIY zqB8Kf9kHx++}wmMC88E!a z?vlHz6?`q-B1p;fq7YIHFJSq7b7zW@)oFb6OkF0H{1W!`Yjd=8nj_aDxfthGuan&` z54SV-#521|lfJro0?P}z)XAQ%#4p#D_wV+9Uf-VmnM*icHb;=Y`os@^O!;$OKmN^s z^qW8a&ENbTUjOlr{^NiA>X)B?^`%P_XJ7d)V*1yf!<#NzSGeeFuf3u+jlA;Wi(i(+ zJ|Y#}EUj-5rJG1s0nWJx9T;_Dv(&ilP(|2#1 zV%x*;V!QDabYD+@12tX8rQ#i%ZO%=3i@W~)!}F#)OUd8d2OP`uazCyY3TnFC>9j#~ zzUQ1_x-q(AbI99=^c5g|94@Da@5P_$0G=@{>u#7dFDh5mj_El-9&VTCotz(FNpmsf2trGr7s;p`%CJ+q=6-BQhjNzcf7DPV^!*Pn{*K zzGFuwF+Ex#M3JU!n$igxg#`2a5!3mKXVME0>tGOgj)vL+&2%IlI@){+eZE(jIl>@u zQ)jywk}!PWk^{y_#tv_xjWzVmgL~A$&7KN2jKyF6}#uj{fLppL*(% z$!;PE)f&*%mUv6134=KX4mnW!`D|(((PHoi|haX+Cvor96Uo z9RcchTJ5ibj>I-rDy5d%==5}j5K=fD+>|$nS_mpOo)t)#@K4FW*j~WQV2+DI z2&u(KmV?n$^Ymnt9EJHxb|ynMc#_kzY9g+-Qmd9L22okhDCGNBiG{G5&;}?~gh(PB zNl(s?RtK_?SRtCu(mYlcE|xo|nJY|XFfktCi3#5cP?>}lRD(haB87mP3j{N8_RMQf zg<<)Hbi1;7VoaYPTl{42RFrxoYa_MGsUzGbXP54oD3Cvri$ZFB zo)A&#;fq6VMefeZ^1@q?&Vzy$*$djT%6U;Cz?6qCqFgPN{q3gm(hguT1LP08>LCi=egcN%y)NdI-0htV}?gG^4gSvsbrBKKD@((;tmzFMf`p-}4@AN(>=vB1q zl<9uNXGX==#?M|#M(OJscZ6&*x)LR-olvXd!OU(OwlOcSiUGQ%dNG+^Y_7D7R08_V z2=DFIdV+L^|DLnO8C$G516gY1g2^cX47-&L#q+&rC1p()lGB0^ZgPdL8mWu_SyO~A z{x>z9U2)V*#bM5^lIDskb9HI}JOpCx|i61mi;b*&5(3n>wv9 zsnq3p;mr$juhX)T#;t>-4x`^UcM?p$4^~$u7szet`Z5uvv$NOW_1U?TvnLMhCAG`! z>b0e%<)!P&v`*d^W?v(TI$2+qmruO?F`eY-9;d(b>a$P$_;`bu^Qj+{qOQLsLM;{ADP|R?i?l_omg(d!3F8bZL5yWr z7kj(;TG%U^#+WJZT7beFLAv8~kJbg}jdF|3H15yzZ%N=1*41Mnh~1h9-MQ!RUKwKM z@qHAI?tX}F|Z1Qj!*}A=RH#WU;lFFtCMx! zABpKexvVbWy6a<3zh~D0|M9E)fHq^gDBPjArUI=tvjMMfUQIV4-LTqe>cVVfainn} zHtda?g(i;hpp)t4-M4(>yG!#wnO^?x;a#`>#e1cu3(@h#K=YoME=KoW)?+*Bvn_2_ zoA*j%z{WSG`}5T|KEDyxH!tuO4g3EAo;TeygBuTHdAWKXCrVjrI_`9GG1AnL-rfEQeI&)_NIW+9SXm6yqmjonXr6g$&NqGzsZWl>} z28aSIgXu$)_$R8>LD~|!`ma&b4b#6A=;{a~q9>=wo`O;-NFO@dKGi-oHTlS?sY}D1 zon%14VZgKB7FvR8>L3tQ7H1S+xwBgWT`jT7;zI{Y6En#qskZSusI?!Sa#^ZBl=O5Q zJs05_CEWzu6w$V7t!W}X(YJnaU-$aObv4dJdhbY2j~G^2V$yNIjjSXsE2O3gC65#a z+Xt}oqoxn{C4u{e!SzCVA`67?*uk$QAyFr1SBvoX0wJTN#Y(tZn#;}Q)=P8Qf%Qsu zojjIvsOfX4?fJC@8Dlg&Fi@#wcrrnD&F1l5p?WQXb#Azfmfn=2i>ZG&l^Uv%Mh6L< zg-+GR+smEtQ?;QG(X7fh01ST@5^rT3P;3UDLPF8$c@=+#n)qmuO zk&+y&V(Fi(k!F*?)l9LH%nSqqq|Z$a~YMw=DBijLtno-`I++GJa% zrvH5Ybnmt;N(Z4u%X&L+x-@l~^Mr7LbB6Jb@HR|`USlmvCB9~|v`D$3Y_kDmb8XER z(=opIYPwU=P55RpNZlMTlGxdSxZ5(must+B)7RNPhn11cy~aZLR05=3!6Htoavh4i z@!++DdKB+`z8)iV6w8a5V#vif;CwI6?c$D|<=JAaICd=;L*FJ|)G7yfSYq``E!R)7 zmuh{CFwVt1;i5|OqTRvk7+@r%6IaS~3m#QhZW*jD^)vJ^xX`#!oeuXiD7}t^K3hCf zT%D`Xm}nle3#}LtJ&I<&oL}9&OtVLje17Sf-J?W|K28HiNbsu!n_k27a-G~SODFO) zTDte`ucmvL{@gd8|KXp1^*{djhtEI%#Pfgo>a*W}mcPFQ*A3Lw|Dzv1Io#BAjw~<8 z=wCBXmzs{_i zr!OvIP^TP}^~LNjyZ7UM0m+56u&urDdpI~3g9~7VzY@u9u7K8C+y)&C3(yg=)wM-8 zQ@Y3MlH-lT#pt&Rt_9`Lxde6VkXikGXzNfnix{|TTld^WT1isY>_2eebDul#IpwWU z(wbcjwr6RYEOK=S9gWo*bckN@PRpH~-}O&c=in9bxe>Z~Uxe&;?K+V2@zMGorh7e6 zxMB~GY#n*WBz~>z(vt|(HB@7sRQ5lzC)>AKK$XwJ|a1N*Pie0|L)<# zJHPQ4G;oABU8WZ(9h!&d4a8ZMmxFc#bkVkt+S;QY5L4jxMzI5d+uZ^9J%e`gboiN}r6J-3S>U3$92b6H-@&%z-7 z7yg(6rPGxe{W!ocQw*3se*ApTmGkF_A(fm?Yez`+=;>Wl3UIx2tzE_S;xV~;v~YyP z?+3RMU-~5yr{mV{lbVhj1+hF^m^?alcJl1$$=*|wQ;$6I$N=F$9={Znj=ElM>epflXvR?0fWftlFNtM3>VNse|2LTaU;fjfenKSUxY~(R#H;|O4=JFP25x$%XeBh& zE`1*VFF$F(VLaY7kcy>)&CN)~mgyW%z8b1uuSBD%lnWsx?+6Mn{Murz*+^QKOpD#c za?n(R0ee(1Gc%FuORi5Y5bKIP9VI)FsMhMHq=TSRdC6%4xhouYvb(QO%_21o4;H4@ zFCJMKUPyLN%w#U-$fTIPyta0R)}%;wSzjaXOR2IxmFgqM%UmH>Sy!^Ng*E-uk$o}8 z6XEsjz{2|6Wzws!?Z~cS^)JWaZ{9Qvm5AV^&z6T%0DA9aduk|!=R;MTp`*>c!{s5& zM7Yz-BfYipNT{sLHR<-4@{VBmmlmH0PmdK#l_Xr5q)k^O|G|aGWONWq3sQPB+Bvlq zLsE>r^fy#{<2fo*^`Fi;sKac8L*2p0R2F_LkzYy3pLBxD4esn4+& zH3!S{3RoZ9jkwh9fO-fEJsuk#cccMf9@+5CDJO@bP&$UJUY=?U%H_je(uyAlTVgAI zlKKPXflQ)OBF3MjE``Zjv^&{6+1s5S&UW_m1)j;qB<$m2Vz=0zloux*!k>$ln+&P|=mT(EwfKZAcBZODh-DdJrs!iOJ`V zjOp^yTe$AOfbp%xAY8IJMIFf8d@mZ8c}37}Go`Xa?wVkWF!^5!-#w}a^U=_6z10q0 zS~|rebL%@$zd59f)~z@-U9}O0G$K;xjonA>ksk1WFx+RfktET^){(_m@6!<|KDk z{0xd8wfsbxVD0QF;xr$9YWk^T^exNEBkd!^FaoB|_p&xNnkO;QbbhQ3?LR;=?+m|j}IMddjE*#m{ zO?yr4@t#^WQA}hq;g+s2dHw=qC&|PX`mz%<6G^#V$eG?jYfD6mj-REms_~%^?h?|@ zq!G~D+j~oswNpc~z6^~|jdMXp0Cwsxsa&UbT@mg;1u+p`_+X8wS%VobuQ|1aGU$=*n*jjKA(H7KXCD;+1pHCxrr?~w1 zl(e47_FPfrPDhT0k;&4cPX$?<*|h2@GfFgRG#(0h}iSS=(CV@U}%=Qhdoi07n%<4cnRZdu61(M!~*joZsrA!y3 zCt@z^O)xdnsa*3E!*s-Sod0PB=&BJYo)9%p>cXq0U@uOi<>xfLSdJGVx|iU^Vn>~n zj*7k!I_eBBPDtO7(v=&<7<>zQ8#Zr(a37<$z&9gWX><8$W40Vrz6s17gi8E3M{wspd`a9Iv=>D#;*FO#a03=(TIhN(QrZ zef0W%7Js{kkaoU==Y`aZKm7AQ{_0o%{HuTbRfF^I%jSaH<<*y7g5baZ)vx~Gt3Uq1 z?>yZ(GtmL2%k83UFM7Rp<;CwgOjjW3E4((T=@2@%#kUUAckBo(?IA(>;X7`><-vn_ zTG6u@QYd|Kd31CdllmgY7s0vXbc1ywN^y^P;4KOlq{D&Gst{MiZN*W#7+nkLPiQPq zH!^2}IGG6&-ZzZtrkzVT_ls%jGO92^6b^?w9B=d`sZ;1VY?r)lMSA?^O(C`$r|T#i zH3hHg;DFswT?ea!_Q>1~>x^v*-CcL+t&M0ADk$cF*>%UxyLS7*OgF)Fp}8sLhUqua z(~aJpmi~H--%6?iWd49)cv&Ni@)l=fc;W9IE^|7$UOxU8e{kzJ?)-y4_=~^zIC;}Q z@)19TRFrONdV{Tv#kT;tc4DCIHm^}P$(!u$+F|_WIkru=>ed5)!!cbHimuVmI(geh z1JhmJbP4JDyYB;}O;SIxe(a#gFbAUl{nj)buUo zB)8OXFeH1nar!{^)TxJ`_{0-m`@~bnfOK-KJn@N7Jau;RXqikdSUM=#V*Xej-LVHa zN+7C_T|}P+w1`*XZqS+yB4ZQdNR(i&@{WW<*h`uxNz_f6#3=3L^^4OdQp&eY3-zht zk@l{Wpa1KB|JUET_JPbmxr-(wd%;Zducwi;ahwxN7?*Y{js&RWE+>I`f)!b;;yy~gK}MyQxfpR(@ipN3>#BNP}4~*+1iv+@{}Wk*dZu1Br(&6104r6zls;S z{&m;ML`%9GXZ@v1!y_x>=cdn%DLW0HSf4L5AlHsW4y**@E6g zO-6#Wo>bu%clzKWlKMnnx-Y0Km5?~+Eql3Y9&)ksL5ecDyim6qpHd8MJe1(_r!uK@ z=~yL;zZ|wjK6rO>QQf5NuS61roSVl2WFdtxQnOB!MW5#IqIZ7PK!#MSv@y zuP@)miZH!SEGSZXG#X1PYGWcw9!msuJ#iu-QWn8q4T%tnvJn*6n!Ok;T}sXMjU+qT8x31*0MsMhKxolxjFtJ0_9j>m` zDBTNjp#+kO-RJP2%L%xOg8s~bXTI{4!(Z9E_bZPB;=7+Ak@{aT@`YVrcxF`DUDQ-5 zIT=qJAkq4@)%=0SmzEB`m5}Lu=KllrW=7P4(epq4@qhd(fum6Rk45G$z4|=<^dCO| z{by;4^jR4GtCTf)>94)^zeOA$DeJIvu}~;3jCyHsEdMCI|nsC%w6=;D7%cnO=m#64O6mo)c&my&4-gETv<4EtqbdmX?bK`<_xE=Eg48Kwq%fsn@%<1`Y)d?so z=X(yJrb|vo-@humiw?=_sS4o=Ss4*Ws#UX|V`AIU(HT7Z^rKIb0r6Dr>^P>EPdxGH z6HiT^ZC+^tD@}0E5qmT?dT=a|>Fl3Ll|EYF$3$jCxeTF=gNQct#5scG=&2I774Etv1BfHIVU4aRZY#X ztn42MN%V19kbAK@P8!sB3sy`Lev@FGeCR+ru1oR;(^^@Hrrnh*5jh(7H4I3tK#5+e zXxg-tNd*8;14+IC%D!|8C(aBx-z{RWk7L!-0O*Z2i4(9rVmeLFH%EI5==;&hi-Y_6 zy79Ph!|Ws%%W$&W5DrN1%+g$@cvyb#t8FbkJ&~cQQ;$p?y>#j9@pC_U<=8O=C8!)f z)YLW7RW5fmk>q})sSCFfPNgQ&E>haz^rP{}xatbX;_1F*sZ=04&Z&#TO`RiC<3l6u z?V@zt)}dY&Eq8`6+ncXD*j%$_M4@zSJqejuqLpKdrP6#9XZSEwO(I63O);-jNwq`4 z;GF=Hxvnypb8!{BNn9i>E`&~}CiBNCMM6t8m)a7UA04HuhNEEIxWPHsmOfP|w1dl2O=6s5Tv9nWI)tMcc z;!(=R47xiRitxK|*3`aKG2oOavC1;(bxXxqu+G;>7bi*Uv3Q{RFu?P9x6WiH%2b6U z;#0xUQAAXu#P~z-E0E3?P2LypZeX|8pV|>sZiRGbO!qK-la%gfVRV*s&-AikN8f;J zhWuiKo5ua=e&1Mr%ls`Pw%F^Z*kora_XZtn`&;#q+ab7NxYN@cRIWMx3(t$u`Jes? zei*$xv%35)Q2M`Bok6tTC}w`~ax;F)1a;MGyxfesmOu4^-!Rkrppd#n&DOPiEW&O6 zq^Sex4C(EouDmE>bTC++7lU@=XL(cX1@Jc-HZl?i)s>SGQfH2vrJzr53Omti@}+Nm zG0J|}wm(^w0OdXJ&yi6|5_wG2o*O;9YuDWe@*SdX)epD}2G#-@WOfLhmc07wMGlt0 zQn0#`pNq9%Xvwt|F~hKJJN~vzi;|^7-qy%hZnjt_H*cj{oSm!8!S%VyEV8|WbGV%* zNab}gaXr^|rZ_u#%_Vc0J2SV2M_u-G$>`Ry5gv8y=_FW0Z++(QR}SNJSzf-r|F8Zo zKT9a--0JGwwd>bUEIqUH&vwD@&+I+?R|l5K)OdLJ^-7JVqB{Ng;K*Q2Mhkeg9Rd?XN!ngJb;4?C7}iiga`fA2l`oHD67COT=i_IM=8#V*anqsR7&?(B3sGh`d zItn8tE8}}_yW=iGMfdFa^d7R#+;JN?Zk`tp)fqKR|KJDT{oYNi-r#g?SexZ2-ND&G z__Thpi9oLJsL<)90AeW%7A+JLpo)>zHv{$g6(_v-M9TK;` z(K;M2V>V0!85y8laGatGwJeK>uKnl5Y3$&+#jph=agr=V3uxiF*~|_=ePAM6DCQ(BO$?r% z=;+7I{jJp;j)Z}Mcol+5^Bb^6jzFCA{2pbM=YXPScw#U%Xw{5b9~Y+cYl+YuO=mLY zK%lFw4Oem{H(6@#OQykef+gjcrkJ~$8VRwZ5_^LLSt?&&GY#>;lQSJO0iO(@ID?01 zI`#0`qi4@O{n|0IXnpsU-LHJ^70OSZmd6QmQWqbteXx8(x(w2rI**R`9z8mA zG=b$OAyAKAtV|BiOyGMV*-PihC6sh%9n1bua;kYeIz;xDA)-xzMdeZ9{9>>pXBex- zNO2P^Q5F{$Fujo05E`X{A}C!|fC#RQLG)x8)8Z*b;*yGc^|%2Z=Ryagm9a{i_C%`z z3CTiqih0P9oaOtEN=7D*6fqr2SAlua`hF zM=#+Dd2od|cRSkHg z!aLrQKGK1@d=Ll%y`I5dHw4&4prl(C!4^Ss)i4n0!r7c&85{t^$Nx5CZxv^35 z{-QO~9xKhMqU@(9I+dm-9So*u&PsV^(Du1{30)u#gQM@IlEFm{huic(Ld`_INle%6 zm;0xuqpSZOm*K^U>6_af_53a#t2P`jo;)s;_WuOSZn!apfyUdP?JcFzpSK9SwQY*W z;NFnowoUhE2)lW2ygX9Z1mkkeX9>sXe=4nA?sdKV4!Hhpfc@L<)c-RV0#2uvVnu?w z?|a!~dvVg!)?d4uk9oIkZbC}H;@%R{9d1kFmXdDfbb&fURv_Co09v@NzJatBvzKit z(|~R2$YFB&Sm!Fa_O+UH3J1$4qTK!*+z~ysfjfugUHZkn8)=zI7}LJ0&~O zwWY(m{%q&ogP2%Uq2Tb_)^e~st(LJ_Etrd8UvFDe_~&eC&J^)j&dfUYOn|(P^`d+< zZDM|0<%0<8Cx?6-I7AG45~XFvZmv80m!AB1KdP}qORjjhte^< zC?UEay$+k)1|Lm-g<(^zzIi zbIH=U|0{2EOmA(vgmNyi{Q2j<|Cg_-Z)!Rsx+{SC_n)0guU zrJ<(3_VWMwAHM#DFMQ!YeEqM!BXM1sUfybNI{!2Cd-jlz@s@YrwtpGLj!$+zZ<*7{ zo(`p(>7}8kBdA+h5~m+H46Q0}i&N8o$8)`G0JqrNaj&Cy!(I`u72hlKzyo_eefU9F z4nyA$(CVo+Wnrk|Y9nAX*YEbi|)F^^PoFScixxxz3<&%I-Kr6 zUH)}8p{4#s?o|`~!y(*tQ_+aW>YA$Kx0lsJkkXOQ_vGt&lo4m-f!Kv@vbeLAK3uyYTkIJiQrHeZalFy=z5V zR|5>%MvVLg{l8H8IWb+{bZ2-`S7Q3VrUBA(Qoqfbex8hs0GTv%%2qkuCV|*2e7pw+ zKU7|cAEhZIFz$XeHL3!*Yxem0@$nvU`U)0`t3bLEI0ETVy0$M+hX7UDFvsgSB%b@u zbWc-v#|fqr8-NEq4cSn}`RgwcD4BI7Pu9S8*bCS&V!xh#;M-GRT7AE@HoTK2-)T5kQ~ z#J~kwOXb#%#7?qBvIJt4B&d>>Dc8`U_%TF5LQG%d#|obU0%&h<O(s*>Cglf7rBf68 z){_gI4l;G3w;C;0dg55bu|}YuDzG#XN)DbrLTjb_K=U1nC9g~A8ix_HF&lB(DArhkAWg({9z^iGflN5qHMm&# zu1zaut}YYJl49L1EtZPOa2BvdImRk(ay)e<>E5(lDk+>*<$8hGSwzBn3@sfmh~(vZ ztdw7m_FdjbYI_I*_1vMJT$C_Fr&`XR$S^*dZU z^6d;U8Va|A=#taTOyk{fH{Wk>I&3mW1Jo^iw2>|y0No^}Z{&Ds$jY#CgT95$9y(jk z4SQ1@IeXn3r)m7gX#jC7MIrnk32=bDNGXYdVFVEo_jEhRy;q zz}OlhbobJl-peiS%r9H?^#8n(MBUmX{dFAbKBglOss8ikiuXYwb{jSeno-k{xxJV1 zvzcDd)El-J$W|?aaaWR>t^y7N!-m=da{e%$qnf+OQ2{!5&Q!f5qBB8pq&CKYThqsK zxzHt}yFXt@H+FXmBD}Ytl(YX#1`~KbKNna&{J}rlxrf{>c+8oTB`Op_#1NeW1KA<^ zHBv3ofCvP>_p-Sr#a{>sC33;Dvd-h8*;iLNyX_0ci%04wm2Pg zwr_gb@TNO89l90Z+H!PE%BF218Wa88(m}F5&gXeZT0%XlRK~^#k5lG$ss{%j+N}gF zpMGHHuDjH_souA|@3vhJ9CnlrrymCDcOs~po(`u2=^JADyFE^4y6=5)D!qB&EeRu> zuA;hxY7=hs&kVrQ+& zw_sP_bix zq#ypUGDrE6*U;TM{z3-oHq&2Gv-Q&ZO&0G`vGmW0>GGxv ziLH4fwe$IbtA|dWJAYp245uTfGhj$<9bZkCqRyWdlOTR*<=j=I@-oJj@pCJOz;JT8 zpqazxlFykiPV^`xuCWz!y$Ipqe^cYxj0*1P3tzg*;b2M^rc>^_k0Fp)gBC?9HNB^v zsI~yz{6Fv5G1GbW=_fFxKYBJq%9l%zJn@|;o_ccX?D$9%xnA(O4dlpKSEn_DS=t|M z?d+@^nM4U2&s|QZe)2*F2pV`EX-9d3)9zVL}_k4mo669vgAZr zrD;z3-@1<^UNl=xL+*hpp5nFv?%f0@Wiz?C*^-2Jh@P@ul${vU1Ga4ZEBrq4dq*5* zC$X7{dcCJuCxSGW4oyy`CfbQtL<(07X^&EbvjmtfAz5-Wt=mVjUo=M-5bPBZI*{ti z4qjaE>n`+?4Kfn#X)e-24t{CHG)AyRV{{00Cr=;Q*SGJ8j4lIB8FJjrm@~aK6F-_7 zX}?5{cQ`$?5+{b0##A4feE8{eSI)ii<(I$lM}PEal6-}v4iz5GY;y5Tzb{$;TJ zyRRvWPZO{55ac~HJ{}RMM^MzGgBL4g=$@YJR$|8Crje0L?d?Y=$$&H2+e=Qy=Gr)V zdOH#~QZEp$e1@XyNH8##B`;%TzLqV-W+uoDA8yA@J}DSZR3k(2P>9T#7&;U}s=OzN z!r3$w54dvrs>EP^iB%>O`D3;9gfw#Pf$Bg|=~!G-r+mV37+vwBbYskxNj^k6#+dl17roC!$g2NpDYnPF1G(z=&<7su%6Xgp>+~ zJE;wl0BC|(VLk>vc!}x3Ayolw$5b%@be^(MyCXoEl#GEyjV4qIWFz7^>^iye`*^hz zK|la$R_)L#;**Cg)k2PXN`%i*$;XSD##<2J>0 zTzx=Fyma)2mhRY`DaPuqZzCLq9Y}wFpubIS^4hg|j4A{5-5=Vs#GNxsmh%d37F3N` zt{-_^IbdR}lWSY6oF3X(cYSZQGemS=o+arqkVm8EMa=U85V^g5XpN!pSpCnG5rCAQPW_mbz|^7``Z z+$=4Uj$S`V;upbqarPSFrKDoKw)-o)mrg8STl$xOwS+MzKexR91e4z8n7*TFF~rlPz<)vZtFlT^)=s z&YLbme`txGk+$#KONRV!53*Cy_@7Z~H|8Aa(R;&ea{=4*?3d~S* zc0jK>dTN!?FF>_6mIv5(Kfd=KSFHS3t*FP}dq4ES zcO$0*>Kh()r>2{o202}aWoo(+x(Dl4m+)#7>iM9q*^JoBsvJ6{JND!)S+F_-#ofDZ zdEa|)L8QNHZ{nty?nt#EmWxQ=5MJMS&X!fgzb0Ob(H#&Q6^qgJ2dvW?sj@PDhO~?b z=^y&g#}qzF5vYsPWpXix`sUSbW5(F35P0H~Q9KhRq;DLBhv07ib_|>6+0krF(9qUX z+u-u8OKlmu=|Xn-JXvN34GNiVZ5#{`fBpkk?{B%9I6r=lC{n!XR?c6+n@p>so|Wq{NY=gY^Y?AUkZQ;v{_5J*md+V{ zduo98i}=?FKz%(lLccs##^utQsVzpcfliFi$?k9`awXfyz<@MNbaZG6#k3F{&L(pU zpmT1H+dq#+5xdvwBuI6&Hb8T27i!8+qQths(xz4$K z5m5-*F4AO;q+-&lqZf}?6Orr;$=aLxWy7F-_$r*9m>XT3uU1O2358Ues~mF%J{OXo z17O9f1XMvN3B2)K*9yp`ir*yqHIPb^(i?YrbEH>uX%JOSq5`h8OTUj(Brf$xVc)*K zh4thFH%tYdN@WG%$~4>BKCCwBX^v@Xia66FM=qW|eR2HZpPak$+IL_6#`nG_NdLz7 zc)e^dLHqxY*UL8g-76!@E|NeMRhMqy;q zmh+TBiZ`|wxx684+(gR1BhOMZi3bZbZ&Vu1MN6g0K0aqCyq#8wFptZaj)AC|r1a9! z!F1X=g7}ryJ`pPuen8TCTsP%Rb^f8n#KLFs-dvoVJVM@^!FE!>2hHstl)4Yz0-Q? zvBg>_GcZ98{l$DGnvSJ9QTKQ70Azr=NS5@Yr8K=BW6(wlB~GbQ^5 z(ckGTFJF9**P_uEKk7^AqER2zeLna58`8E=*~%MI_Qq_7^+36M-DD%)wqDm0S9=pZ zBHsk!3<}nHG0&DmS9dROGLWvhdYN{Pn?)m<CXhultdZyz(ZBciVQ+qj0oHdW)J4;L4ybA$^0?h38^h)1lQ9M@tfSoQ`1b zJJ4wfTDrQb0KCkM?)GIC7*+t*v71v9kmJP!bFZUK+S}{+!|X+i$JXHRI^<0&p9=Ab zjqW*EsdFeKYpLUAF_yN7Q&wa{YNH5HE@5|pw*%aZX>8Q?Kv!91%$Q!U;6yJNro+fZ zS|(j1R21LKDmm0Kt%Lmv9j$8X@O&(HQdrMD`r7h!Zq?UUS8=;o`t-|ZaH-#yA0>no zPYcNyahda0T683G6!U{8NV~ZF44OHqA5Sdjfp})zcYTTUF9%LsC%zPsopnxJ-+lMn zT}^M@(e%=jxL)LWfz!YGN3SBG>-B>_|MNfpff-;>(x3nHfBw~1pFIM1H;r6*MRK|& zdvT_hzjYy`uYLTVef=x{?9cw$*ZBZbG=6M0nmyOSb=o|L*CHd3o?0-Pq>g+4K(7i2Zy6-ag)O0Oi$V)S&JNND$9V^BH z{RkyMIrm|TI7BDnghd9dWjl>_2-w4kp8SJI>9^i~`<*)l>0)$zFK%$puG<`<8==dX ze*5isUgUZ)d%Ddu+lyQ?^3a$&-K9-80RJRy*4+@{Mn=aMZR!`hCMxZ34JL2>IJm%7VP7+JA{~S ztWK+;UNL97jme@6rjH!Lvn*GP;z!#Zr_1odDo$`mk$3hNmR1@@HcUZacV$HO7n{^| zzGtPYjO*pi?>wPwj88rL)DurU`skyN zOmz>>*a96bW7nFiV~b;BJ!X2z)JAjJ)I=&dNJEnueG5A-bi}GrFntPRHk>{f?n?*P z$R@r}$)lX-udiL`CwJE@e`m6=`DIXjb@e`+jb~Qp`m=LIa2}&0%>mIm=bSKoEz2CV z^lBa42A-ifxS5oG)kK^iKjlJ%(n&E`?deI>tN0yCW3}ng$V?d>9MUFxo&YeB3lTzE zEzp2dK@2*nW{je}&4pY#(2`LlB{LE3i>?p$C2{RAyElSuhcqF|#}`cQqgyzl;UoKw zBp1?|9r)SR;*Lru=}W+L8f^m5b>bJn^waC73sb%49{$NsUU~WD@5$-%0#27#zWd5| zRbF`c@XI?Pbd~?}doTaH7oR@F=Z#iAV(AzOewCvh^Y{Yx>RRR0U@E0NFccz4F~AQ_ z74{`32Peq^6YM1uIx=r0)J`Hw(zFo#n9Q*S0dSDC|V0r+7^cmk)7&ZPm~BNG$d$>A)16Xs&weuEnI!^*P zdYnFkX#{k8RzbdUbZkosqnRwhySav?Ua$>_I9t1p1D6eH8{@V7bPIIfF+ncL%0>K7 zG@(k{MtoqnwpNP?8bhPwMa=J;& zn*e(Yoo^Yrk+t2-O^etd9rYWN8w398LT|5lr0#>drusZ?j&sJ$_+kre;I^A8hW7#7 z7`y@K3^*+J5q%S+OIQE4<$V#RTVqGEz4(H<^z>h+=n7KbF;d^m=x>bd-fbJa=55|| zdZK4gn6OSGZ{uP*n@bEhcWSzc=|XEEx*|d4H@6^BX?`-kh{TnO-Co+dye_u5?Uc>h zj@X0|HN-5xi~o}U#kpX#f3v5vcmSPyj?Cxz<(PagQa~0-ah`~=E#+@-G52}BHd{gT zkXfZ(SJOw8YvkF2w)=C%xmr=a8CS5ftdZM=951Noq({f@axGsZ0VJ*#{Dy5g@~GFb zyVv1#Hb#N@)Mwd?5%Cnfb->um1S?m!ALO_hnEghx+q0P5S*;W2A0T^G4r!k@s`2JVEMo5;DH_!k51% z)5|M=@Gt+_SN_Al{9gzo_0@DTy@(9oLQL=IFFk6vBN=HY_eljuM`o3Fs?varGY3EHhVE^>t2kwE>&7p3d7ln|b zrf=nR&z$Zs-LkX8+gsFh8=(nOLv-0+bkyqkeH){ri9q^2ca4(c&O1OJ-3P`FJaEsQ zx9)sAztx()V-t!xW4cMon)6KQG+I^I~a07+4uUdh`-mO=5J{DKE_8H+6IICPD1U=fYDkhij0-$?tstl5R#$PjptXpRt-uaOLm1MJF%jprI~0v2Z# zXq?Bpc|69EOvn=J3G3i{^mGiHs6#pQaWUv5VW{$46yS6+JN9GfnaBi$kTg6=1Z*UZ zEkw=|T16F|t3(I)4fd{2Vqi~Cs71?G^DMW{(9RKy+2aG~ZEBFVq1KVpk048rpZkf# z^p{`wF2SQ1U{uaQ?*C;8Vi&IS_wvhM_~Vzq^BSCvoL(k&xOd7hJx(AfB0e#>g(P_y z+cCXR@TViGw|BR9Dl1KIjl3-2ZoGD?ndE?}6owJyGbB-pC>`fYnii<|boqFO33nXs z#`vwv7aO@7U8cYSU1xzoc=mZ%o$&y2!`Mz$9F{I8xJm-Oj z0(G@6oUS&V!1P|J=~!$?AVi}=<#aTJi9SLC8$9=Bl$k7&dq&lQ0Kt5*IDQ$PjF4qM zl$z)qXsJzy`D|J{()kj}h5&O~NK(M_Ody@j%Jd>{ItQAdHa3N$h=&3^SE<$b$*IK@ z^&BODHJD6wP9&?%YB?7%y_H8s98(`3wLqObFM8w!zk}cBOAndP74;1s7JUW5x9~$(!){USp01ygz^NhNT;e-Z0(KIRFk_JM#()NbYuT zn*>>l#zpBOcefyG*oevInyN&M!gcFv$gQCDgy`;No3UYk7aW*UH2zz=4*w_47cR|j zNKVK0^2sm$1CP^bfJ2y$X5-z_f2sk--L^YCn+meGlBUzxsP9g9wsc=nhmWnq)Ky1* z5mz8=!+FW$U^#3qJQt}mpskv24wq{xpl-Vm)bj@1S>5MyHzYc5;JVFYKU&20BV9gs z`0nKjUh%dJe67Gv%YjZTXiRaWOlS$r?Y-@uUHfsRl=5>VRv(?Cc_JEB1Leu+LW#-! z&YMby8a85USS%|P|q++0a*8@bhl>ct*>=xq8VxzLwaNsNAGb(B1c zQq%P!Eh7dP;2WhKDcyQ>h$ux}pBp`~ba?67>e7Lwz0X`Hqx$Ns7G)`{>VLQQahf%n zeSGf{PIs0hwDj%X3aK!9X5!iZ`24G;rvLBlp%aiVs{~UkmW^r*`ZJKdwO1_ucw{C#FkDR~RYG{@@$(*f zamC-l%|LzYsrhUCJbkP2_}>rIbVFi;U>xB}$Jm1}g}}}(yy>5Jq%PI;lGN{pH61sL zlyv!BFrf>>SB@V&e)MQNrWZIJJU_36$qREHIh_#|*d2$Akv(f`LCOl-9vL}Q?ixvq z((ezw-A$H*{_2@TVuEi!zFsKsESUbCCuo24(%I9GJn>JTed?)) z&myMJ@Ga};uaAxedZtTV0rY3|%1o>Zq_htz5ux-;D_x{M9~Z@#f4UttJ-5)7y*yXR zWe4W+@cG=@8PxRETz2*H8kl~0mHwHv3v<|C&dgng*kwbXTg~>LSryaU8dw$hA&se> zdaMuFBFJu%2=#SickUielMqCySs+H_^vd$VhmKX^j z(MhTDY$ud16mdlurgxA#om?b{#*>q*JCqoYtEEqZHKDR@WOSO`kqRf|y)6lKLB*L^j=SX#fRgo@qiD071CtUrju9j^)Pn1&=K#}!HnIAi}vXZj&) z;%#Xl7TBkWqH--?!}Amyo34<}vX8us7K{muljo&Y2)2-2KS3lbx!MUBkXL*#$rA#i zbEygvx`|r{;HO@o6g}!hCyV6ygtw6o(`#7m)wnFycAP4ya%;IZ-$K&Q9j$5hNgZV( z6(d&*TN+47OsC+*7pLb`Uz;L|f|Y5vbgW3eP96+U=_Bi+GB{>}v{S2t;FDIO7p|oe z^5gj#9BL172_slu)Up$TdZM`+Q@dN<-Pi}koAp6SYj)IUbkowEn(m}@Q_~I7os8~j z=|HykdIQY9fvz{G+Z)=LaKnpq1WiwnRT^NhaPyY1x|Ma*2tui$da4JUseQWIKKO?9A#;3&TA8l|t7xCWr zI8K*G-6wUw|N76tyKO6#3&0FQi=WkTFQs`w`KD_fN95|J$z^Duj+hRsGa`N5;2t}R zIbDS4($X=tuvvLq+ydH`w(be)Y?z{q=t6LDGvsU|jJvlJ*IkW3i}SbERvbOBG+QT$ zBDy*x4SsW9GeAcfr(IFukcsmnI@ZaZ*6!s?+~3Dfx<|&g;{(w$n~h+`Q__*R=S1?1E=ei;}7*6E#0gu z5c()jNG0xT(rSM6nd_@WkP=WzOQf`dG*`TDl^G}Sr9ZRx1h$tG2fnhDw`P&9op{@0 zdPfr)*i&Eq0do5P=lg#Nj9UPyf=EqPmpvVCx|JOFp{9}XSN`40fAsHO`0gv;dF8n$ zq^5t_sp-h+AOFJFcYgiOm(8k9rWf6|_|<+()$|?3y?gdP2&TX9@IhiYrKVd-MrCA_ zGaVHjMg7<{M0L;if;U~3mxq?n)Gdlsm`>t!r4CncC1w|E>r=E&F{&k@;vI(%jP+w^ z0l+s1d@GQ9|G{ozV08wF+u!>^$>|%e7o&7P(~CGA zQU}uw&g~EtM`~}lT@%FbI&eF92j@0sgIeIOI~N1}WZ>`*SUK~s2a`e=WcR09-@8p2 zgBqT?4wHWdmj2ZFB645KR$nM>WNm%M#NN*IB2Jem=+z>e8XaR&gxq*y~DNoDH@j5gg-nd zJ#mt@I5qwA_e1I+HJC0=cjQg?e$S8&bc@G@+sBWt992%lqX_2;KGkG(#O9)Q2wgqa zpjlHxd`SJ=@pB_1We{)#)Kd&9oZh0aR!8Kn3So$Dn)=`PYWfGR)~gFN(bxgZHFZAn z39RXlo))B&knwBi>W`crZgOgRfBjk|QyJ~)CyE?zdZtX{k+CFEmltUO#>e#jaDp@* zQ~QRxu}(yjsq})H*(4-1*Vcb|bqz&*4fAOzD=q zFqmFwUr6^wtAUQzt|kQ*qPPxHM;TrSVvWJyObBEwT1#9GE~FR8w7zouCx0!=%PYrT zdFrXNm(KEtq^XGjyFf(0YLvrml4erQ{bcud#p$nIImBI<&|%bULMszAl}ZgEjhvoL zhldGQEf2FAs7@24P&%!-4)JJU@>H){4ULOq+r#a+e_(4lUSQ240isG5m@dh2-b40Jf9j(m(mL!w)R+Y;hF#H{!Rr-?FsGqApX5 z#B{BWoLBTa=NKs$2mW`yLv(()6YXphH=mK{Jb}z3UyiS_NYrFBM%lJaL>1=+Hj4(_4pV<)gP zFO7Zf8-MZGAAJ3VS6+MNmFJX@@x||{OL^fNw|?R4U+0HJ9+*a^m$w$vJJP!!q@A8y zKlI)`2TQYrkkZ7FlhZvl-9VkxFFvJP0I7-T5AA;F;QpN^FK>j9DmD{Lr<+{n=+ehp+v8x9svnbkosYB&ig2-02R}mFESAxHG+25Ggqs zk=eI+UYwk+%7j2&9qW3aE?RfUZrtv3y3l+B+o^c$tPK!Q?wyLcUjQg-P@5!ncXs}d zgpsGur#A6tsOei#Ram_7VxFXI(X?Y`$JGYVfHh<9+{EeFUhe&{Invd2Lx8%e=wxm* zIo-D9w&D}H^&O|1j?TC(Aa1uE3(7Ze-6lI^XL@6Mwx|yCtt!?!3Hch{xsf;hOLcRA zn`(VkV*34uuAW~>NK8K@M7Odc00+~J(qVKc-BZP_XA~}7{OI^m*;vjan|q*ceM5E^ zR%)~k*{|Sn!RjKjI+3SGkFJ2~A#g7qr;VdVRI5??eIM9xr+X8~9C;NvMj>`kdQ%f> z`X`=v;_N=BrbFq^o;uqOp!B|dryn^Y;|nQW@K?k!T;xa*7|g~>$EJy(B&o>| zRE4mM!YyJIw8FAjK9q$Uaa^t!&`oSNGmvp59y$ufP2ts^8pIvZ zOGG4jN}@q>`Sla7($U}4k1c)jA{O~HfwJkoY?@h8n*iT*AQ#NF#Ll04<>g&3zw#3` z>v|eU2haxqb()K6B8jEq2fDhhp8M+;zK${G6{L3NkA$Xr2ch)1yy=Md?Y$S9BdN}E zxzpryk}?iWp|7h3W2~XOb%v62)3Dm8G#Eu7I+SH<30nl_XsW zEUbJboQoRfk=aCDoZ38qLxWm!2jNKx$gL@w+Z zER#(I%4(q(NLMX~_N>S*gM)@=03-~8()m7+UXn)=a{ttdB*uyVOf`K|n?@pZ3Xtwa zk2Xx{n?gq$u5^QRuk-V$<36DO9276U7GWEXYfx`D(amsN?q;x{8D1Qc+hXb%W*dF8 zm^Y>+ZA-R>M%>$$rPFw8dGGDFfdr^iJ+XF4QPk1XfA3Q$>eACc`pGZ)oZg^x-JO3% z@qYCkUdw`lc1}YK{>!3AUG8)Ndm|&G7@eXHs4it)rg5$1+8DLSQ6ai{(1;zfJ=5fwA#(KE;)#PNmPxw!|L5+1fZMw7GhbL-F4z)Y8P_H#T0&(Il9weMiP&-y zj71d$I6!%I#Wj{mNpM)1|HR=C0=TLb#;n*xykRtEn3s`a&1Hrnt-0&W?Iaa%Urlez zs1w=c&F!YtoyOtDL+7UUP4fDkJBjOUw@#GKdL}#dzMtp&I|rl``CsDByU77~aQ@){ z1W4d>p7VU4FEyY;#I&qqJ--2x?nUnN4np#*KZ(E#v*Le1exFKHy=q{K3{*V7o z6{HwnMCJl@1|QUYPT%OA9Jv0eZ+?Ujli&I8zxb(Fzw#y)b?E%NuZhbUULiE>mDjmt z8a3ULUfyRly|+0x)_LgheGlC8*kTSfohnjwI3oNF+Y7ObOXtPu^W3PEblkk@7RNX~ zt~V3ciw(xmA3?o$bi zsGFMZu-vru3af+XPEUX6@EGP6q;r3`Lqhi#bGsAMO#}Y9z3DrpY!8`r<1V_fDL@^O z92%EB-3=b1%k&~O{Sled)e1>sy6&T^aktwQWA^K=EcPhfak*{i>F9>$w$^sw;kds; zkI>yA#?OoDdI9Z4w2}WRH*cF>oS1&|k2WCmE3^~c_NIf=BO_*d0mxNE3Z+Y8fAT8L zDLqD)Vh*B96=%ZAM%mD~UX*TDbt82fkt1{J3aycl)2}oQ){S(WYaPt547QGp)CmFQ zPB%H-MszrG+PX8U8>-`bNrjz#8BU-0qSSOuFPAP~{wD2>p8ev)^(Ok1Vrc0}@PWON zPKT(vR5U$2>hL-7johSl_qpgCG)(vRaz{f)14Vp+ zn8b8pI!$xBVe%s8=17VTR ztb|7pOkZ1z;^OJT^AZf7Blqzlrv@91co{p_O2rygWN&rizu!a+u$hC`MN^e$I5U`)3mMIkb;CA>BP9i+hN z8hBC5;b2GMG|{-TC1ssNgE+G#D6@Z38m-|GkgCo^IECbR>8*<6IY()?lK~tOa9X3P zF3~tVKAfAK%_O@|Z1%Ndd_l2RV^K)APC=QALzq?*Y4g zQhztMw+ZTka$SIHF4DCH<67WGW-hlav`TPo8yltD_FCjFzwONDM(UM?{>pDW|Ap{d8!dQ`{!bJ;juhQH%VP6Ub*@v z7~NK(bEtH+F@e8?A*;5aJQc!NQ~@f5Ta$uxV44KR&~&=(4?5>@njnBkFh?vW=89X) z>KIm#)wKiTd~mu<7z{MNxHQFH!rBdaE*eW!pB`2`W%sEp~JqHf|j5)753TM+re(mIWdn315KooQQGxHgWAp5~){VPSERUh>>53=O5X zZk=3QT5P*^a_=*+{Q7uX+xRbeAY;8;)sx-d|G(vWK~Fa{cRISXbhS2OF`gI3tE-dO zFTeQe|L{Bi?%(|d+r9b~MZUcG=8r#bE*ArJH~Q9_&p9<6zYC=MGYHZ?)7*KB2pkzY zdFb(n?tkD&8{Twty__cN#bVPvNVo8GQM&I%>-7b&Qi_}HEkn{rk9)4)=5rv#P zG2K+?!w>D*{m_|{WAnvru)Xtnyv;nI@&tK|yB`G8!E-O;gjQf>z3F)F~ED?t5`|i7+efH z2ailE9v4TMJK?>ug|D^0Bg{ISHcD1QQWLp7q84%gGZ0<27Y2MUfI3_bqI)vBkX?!D zTB}VwTGu3?t~>ff?xVN%Z-Zc6Gkh5Hpf+QLLx$p-b*2}4KI}yM)74hL^)FTV0DtRE zcC6w1mIED)f7O4PSC=n1bGmcA;7mV7EFzJL*wfA3U}`$?=Qz)8cn(HaXHuu88=Sl4 zQqx80qIWJ*)18!VGk`jGvo);6&3@|Ca~(3ytURf#b<)*anLf2b*h}kb#OrQk690A= zQlHi3Q~$(;`+{ z9v}dN?DTE24N}EayvvVnP*iMp|1FjlCRTHsj8svl_&& z(DYPK525OGKME0>u#uIAnRH#U-U=+!iD50*<*EryGv=wTQqPsK3(!~n&OU=!gl zB=c3DrWlZ-!gxMb%K<|`ya}+E5lT^habWX|$n--p#yyVK%)L}ZO4VU+_h|dsQr}#( zq`<1?u0l$0Zf&gzbgiw?v}bfqzv9M?8CrC6l>)^9 zNUCajN^1HiUps$g`1D$i1B!u(>>OX%WWD!t!JXEVXzuB_aPy5tB457xlGTxt_tM_q z<*DgWUPLtCV1Tf}`g}~bm-_mqb9mFqXGB<^z@P%9Bd7O+>-|KMD=HC&E(YUOn6mML z2%&4#NV9n|QBxgP0(lsdwnyq5-<0I|4>_qAy&1tA#Fjh_!1L?I5{1*bOnhdO*Kf2b zC_fCLj9kRCvdOTa2An6HmPlawt_uZGwrh1V0LOlm1jKNJrdVZK#CGH5kDlo6?vCT< zM}FtMpr=v??MHc@6056CVAoL}?)y<95Q&$;`_JQ8Hzl5z4ifN?C!uuG=u%3>m&Hc< zKV~L74oL#nR5*tt&Ak*g!0dFsZAp@(52mxLU`m^7QvIG3137$t{CtiRHDz~nQx#1m zN0WiL{v#&q2RPQ`$zX4MWHXBC76*)(*M&b>JHN% zRWPIHd$GJ1XMEu+?(GKeV;hQA<)>N5z4B3Ev_EW5`AeKpT*SV?$s{0lXtqVyM6C%Z2ZsQ%@@_;>&2`J{HdOqWqS-1hk6hwpjd;KzrEZnIEER2++XkvpA?7iBVm$)sSL>@mrAY^roYx3&;)0O-c9UbbG?yw6;*Tx*I$`H!&T; zKa_%=Dm=cO!T8gvdgTMlP}6MH5`^8b13$HB=j>Zedulca4gTuq_KV|a<8+DX>P1>n z(*@`n{u$+?Tn*CA^rA9SqjRHbw^Iot@V1n8MsBU4IS*>{y7iud4j6bEjI^CHca(^1N~XfR4gImdb~l^lIs z@C{@G=qz=EUm^<153Zo5v!%)CZfuqpn@3VNEuH1k;?3TUy9Puzj|~rbm5H9#RpfLR z@?xOAV+5&tV)}g-rl*O*peH+2a{1Y3zo@wMZ$A6YZ$3-Xi@fQ97JOB!lyq{Ul27F- z9ick!DlPdD~*PFq7&{F3T8$nw}(MV{ViZMu3%6m$kJriZ_&g z>Fo8h*V}0`8E634s3pYhTo_(D9g3H+dO(~sB?8kiSYUIJy`2aW6-%-p$Wz3BEw@Z0 z)XF(2%0Y3aZ)TdhyGnh8O7{2Hp6fc-)L)GQJQ&3s(m|1`49wwBYY&+=`MLnYd$1`! zmz>+AI6lv-_E#&N%TAx%$_)W(J3V>jCX@bgzY*5LW>_R(xEwXp%rCN}h%aQ1*q z_^GK27ryhIAAs|J{f7D+4fYQ-1$E3pKDwR-LoL^QZ+#52i_v+#IGxm&mVvI)xrU1u z8|ri-1v#C38pK`oyN5wxUi=wd#jbOKSQXkdZDw(j%kv=zw(KUnn39uuG4!f5p%$}@ zLm04GcU8loKt7M-zqhw1n2jb$$k*|Wep2kHs!E)zt?_`s`ZeU%D)faHRVBIx>9BW% zgR@9SpN{B|uJKKGP#VYbQW{}fuf$Xh7xOfC+`wah5n z#u{mE2dSfyyA6EqHu&~Oy7hE)pVi%Vwt+PCFE~j5!t;*RwcP03U!Zvh=>m1LssFZ% zd~wznXM8bEcLsH@(-B`AmG8Hm??GkSd!r1|70BYWaHDA0*zkNOqciOUb@X!uq`=P5 zFQBVzL*ceSUs8HcuP3Q1@I`)i6!j$eEGjZ}h|aDYpWE0xFBMAXLELm>k^VwR781Q_ zKa}7;Ju~xT2-^_0{3piQJUXb(b%T;po(TL5WM|VusiE=onP+msdFkuyrbr`FHfp5% zkYZkFJ(Q(K1^+NsA&atccSadCl!n5py<2)}e| zX<__@&L50np;>t0$AA2H zpg8Keye|BB7pdvr{{BxWBK`hPMklYo`lAgp`Z~8w$3F-bs zbMJWPp(FP`u@SKu3O{wqle9! zu2dIYb{_!KDI%5U1u0z#FNWxTY5eI!h~;}>25IBi-U7> zx=2xn+JFs2aUbRmL{@PL;?mvna>!GxPdp@?(Cf!~Az1e>Ctlh8^ z(7i?eOLY6JH+Scaz5^h2J&^yWwEC38UZL;>tm*erFnU~FhE84WfW2r$BvsvrU0{6` zN;kvHshd~8Y~o&|kPF|rFknnqF{zW&o#%xG6qz1(>s4;bO0DP0ZrPZz0z@GHs~i^S zv0EFr{qnB!=zny9j67F+x@1SqssfXSdivmB!_be)<*qsbJbDQv{Z zpTH49Y878$cJimWr=TXljbJ*?gDj~mlyyp^LZDXYI^*u{%w~78JyRfQkerqV`VVFL zC?LIrqJ9ZAy(x;M+@a;gOoWqh@rKj6hCsBTL^)_b28D77qe9f^l)6_8##AqIC=u;y zAc-#=2~;KUK%(?w;AxK$OWxN{Y_2O34*S*wRJbcD-rbcVmL+JHfnlggqB97 zzJbx?DBc{NY3df=mD#Ba(>>Yra&mc!vkw=pwh{F5`qgkYmm@7Dk)>rH%G2t`wEXx~ z(oXT^ICbp88{b)c>AQ~8pX@3%4a7z|I%=DU=aw~|%pA21#hhMKldo5sqn5!Ygmo~z zWw5{N;>Gg0e0@uPkoKh`{Zxk5hKYIs$kq0TKo_h#bs%XEMY8*QM`2I~UI~6cUUCs@ z`#4m=*DixPHkb&;76!p{9le8U5b_gM;h9t>UBHP?<);SO{Ns&t7)XM6WQ6IUelP%5 zgy3h$8*ZioppV)FJrWW$5pQ8)Q^0S?ml911e_2N~jSdFFRJ?-wfIdeG)C$;EEu-zc zO?bzH@h0nm%7fT|5)N%+Jcy`@l!G%69YtN)J)~xGETdmkLK0FEVv-G`IA^-~QKO_x ziB_isQ(}DKppBo}!tD9;=VymY>>i6dS^6?7xWdzxc8V{$PP7o0)50Hj56x_)s9WN^ zJy|R-IuOKO)P?!Q`!w)BOm^NHrJI(n3`VKxE`$*!T~fN2mi|+ImmN}i1y4b1(yleq7O7NW2oDPst;YkqrKL;THmi%2arskl5vus745+6~1=qH^ zQd`OZb2m~iiYbOO0ny#|4;P zm_N4qfv!2?oiVO?63Za zpckj6=Uc8b|Ki_&`NbbW@n8Po=U>M4VqHjgs_97To;ST2OvktVeyZu_(wIHjx%b`& zcAq3dXjp2x%;`!_*8r${gHbx9KEE_H9Byn)NR;boE}Rj$9+s94E#Gs`LrZ*AR~0_K z7uaQB)x(Dm+;i{mc8(22bO7_72hNE%7an_%q?d;!qAQ5eZq6Kn)X$tD^Zl@S)9>BA z8!V@0bhp&>d&KF2bRgV<7@713mY8YYsp-DWMbs{0cY~OnDdTwIyQiZI(;qr`W*8cO zcfU;K>%w@`Q97;-H{8jf?`D1{4jWb*p1UcB)CTL0)a7_lv8WT#&HiF}>B#8@-e5N2 z>ioFDINd1QJ&FhETI~p4lx}LeMoifp&)VIGjf|h|*DySHcVja)(a0Yhtl$0g!P~ty zVssf^Y~=qXNlh2|%22}3C(Y-3JOBV707*naRBj&sqvJP^A6K;b)l&p`jNCkRT;`Wk z^-|bX@%fxVd+Q3Iy+ckHsB3tdhLlcsXNfB#Wkc5KYMC(1YRX{!$tOpyu87ciJdO*l z=z%ycSZ$4Pz#wajgLEB3FtC89D&b!%E?k%n$JOIUt!!fxYZpKDsf%lu*FJUmQ){0h zl5iq6DV-cO9Z09$oN|Q7%~1UuurooAowbRz(!fA3ln%%A?2ifL1nD%%>cTbS+KJg*KyAbJ0v} zbS_gU)0e0g*b0^}PRN^n8C1XCP7x_6UPe(zC&idj4CK4N{XnVTWpjI+K|%K~() z_tV6f5wMn?y6}mu@4WJZ*S`Al>sOw9^5VsF1F^b}hLJ$KwcnxPC2~4ukbFM20)t|E zQ7=;T^nn3VU%E;o{e#du#i!>+8p4ALwBe%k5e298*VWc`jf|vtgC~1;?N1;do21Tb zz{`V6qz_LGZAnqFDTbtzDEF6L9gP|zc3sU%-AJIOKwJcVRD#+qlM>rIdiWfs7cAp~ zbYVJ!PBla#@w#lOXy-4WbkMj8uMzKbRVY4+i$sS*lXIzH6l=KNM}&8(WqEVt!4F~= zr!ZMsI%0Y^HK-GtB@E{QTsq*sq56zzwf$%|0GQ322x*73* zS>bdV#_Fkb^Eayp#PXszdb0E(eR=e|$f22k_F^rLp&~WKagGpiB$=2Vi&CSEsVknx z`X%E_Yv?9=Iy9vgs7jG!e^%wdtI$#QJ`F0Lw>u`_Mq@~M(z%-9#doC((tS?9T}|I9 zq;JFc&t-dYa=A#HA9J=Cet&^!L+RgU;(2~F%WBy?+f=6AUFCM5RpBAXuw!r~TbACECTKE~*zyTiIx@tS(Mj zcVqd}6M(ux(*MrZfZCPe%$<+|wL0`UO<*PEqRk(A4luc?w=1+R9C- z9+iFRKmb2`&(JuB*wWEA2vb**Oe!pUdUj^9lOoS`!q6dfH6TSrUzT1jQlCmAvb&pg z{O4v%r{EM!ztyJxqm+zJk;KSW3Ugc_`GwEIDe_$wpBYP_b( zwRcxxtn;xw59~feaJtoyrcbK{Db-5^r&B;`y^XBT(fOg%r)h+vIegTHoufVXxiENE!XY$7tsw2e%mvzMXh(oG!o1 zBkD}*vKU3^64QN3H%1pxv)n{;ZD9Kse%lU(;U0NAGS{ZJsp)RE@^t)-#q-+)@Bg}Y z$8>+~U2k!`@D;#=^F83d>|pwR%K~4}mlQ-%x(&$M=-MkQ9anF*9>0mQPD(l^a%|A8XegZe~~}KR>w_7*PTFi8j@0jisJ<_edX#1j&&ZISVrvW ze^fEd^Td$S-5@x(ss9M4qoz-Xk}wUR-n+l0XX(xtvWDlbQ+#y68NwJQ3x8ZjL|bTS+YTbR=?$z(;^S%pr}=CnT!-n+B1x zOJ$mD>-%PXeJPdfk*gm5b^-D07jAy%&tCiF%YQ>_KlO70&N(G~jKhy*CJBk3=0Id- z{X*-7tvAe{4yT{HNOMf=6lxRIK55 zaKiB0qus;AxXQt81u{x`3}Iry+)mLg?|pTqD@wq5O^mNUBn%ldC8ran7>&*$-*d7c zQ!a%mO3+DxAP|Ee2PaH5iH!5J7wPE41H=9y-;V9C$;okzE&bT8t?6-hc7-HGP!hjeaq zZs0B4caZK)F(V0GBX{-J3&FL_QM(*2LUqvDjU9tCE0{L>i(A6jFA8Nja=EP)q*rEr zWS6@|<`;Ky6O5hdMW8Np_x9>Rx`DdAMlSJ1b)=@J%l0BgotN2$%D3KKCcKYr3}~z9 z-6CmjoXia<`&BF6LluzfO_wMlMO9xs*)~2uRitkzeisTyf%8b? z&^V7M54-#>49h01FK4%~k<+0R`-~u+d>52`-01o!8j3<2pV>GHj# z7seKcaKup4N@F9AC=lAA^Mz{*Gt=u!i}WRZVQedXYwVNHEH2&}`en!TdSSXEtzP_l z%;{!Nmtrm%-3CYLW=(&w{<5ImU4HUyJTEW5a$C|1u5_;3YWhDx(hCsWyergp=*+(R z?|*DOJv^o8^wS9H*562NNQY*b<=dRga7PE~OhReL3{FrEpFDh!fR`hO_hAaBuh4;$ z#r?=fJ)!xd7N{bKKXCuOk9A%fFaK<&7al6ohN0%bLq{QWhvjLH66l~ zXT#STJQ98Pb{Fp8(XP|64WPxq-j4%nhtdLTSy~?XD3ETPF1w54ZCfXhmzJ(8cjQN; zE=D&T*FGJW>ppIu?s1s6P0YM*_wnwc%^_&*$i~{M-O(287_rgMG#J>Urkn4@`@G*p z38^Dr;qQg}$Ya!n0TEpVo>y0>C_Uam&iSCV3muVFMG`oeE;xVk6hFH4TrXH&P6_92 zsIa?jp{@MoW_y9sC8f*pvhrjHb61a_x_X>mq}bE(;&Azo_x;DGc0#(IqNn}C>C4m? z8K$F!Pqx%vER&o)G0`;9KGD^LZ9>JNsOgC5e|by!=1}^m((`J&=vF_`*WNy{mg`D# zij9HV_1-7|jDMLPFqB^g<0LKWyC;+Z>))h0P9A?NhtX>P!KQcLrDJ3~D7p0w2xh7E)p134)`laiaQPT%vO?3^l z_#xgU6Ra7YEzFkj97C)Gi*vj{T#H;4we3<*1)_8C{-(@2BXuJq4IQYXxL#08>wf=6C}uVW4q5pgLvt~HzTc)m1&&^pdAut9hxUco0K zC8N#S?8naME|%6fBNMDj#IZHW1jhfuXwzI@7d^D1bS8}=((}FALq7r?VH&4n!-voN zxxne1oAEvk?!tw?0y+MRUolU*SRF|Bau|1Z9(AVlO6{nV((lITKbM>?q1+8N<;dIs z-YMs-wq?+GWdUF=m0U2+GUM%UXs~VA{u})4U~@<5;%~c?wuiah73yYFA-Ha}#g`1^ z#pAX>V^)8Oi&p7@HE2%;?Osn(%X~pm|0~OTA@BuEH{VNz)Za!<_ueS5Sr=n$V{1w0 z2?KG3FeZ#}y*NfVUEN1r5vd!q!~wN|I@TEjbO-Ae{L&+Dx;b7bG1bFJyw^iiF0!=n zFbM;7P3pqmwR;wcL~3ejY-nm|TE-XjdwE^tI?)f9&KPXgfIoem{zRmWV|rmzZO>*l zGE|Rj^n|k0=`A)*BqGz1^|ACuk9JVN$X*y)BxD_{F@Y~**GMnFHjcoqCQ36)^JF#} znk(-`6A?8&oo-v8Ws!~%u)NGD<;AjIP$`I4luAxUI+A;8xiGbU3)P*fCaWPGdSNk5 z$&nS5k~y=SMUH2CqGQ&1?8U`}&NBqR;ClJ51g!tEn_l>g(H|n8E0@3gZE-q;ZdV`3 z5z`IQS%EWMa=Nu9Wt*>n>ECju7r9(^4D!HOZaO=Ee@jSts=d1s^POi7-t)lWkDo3K z53keU==AIsoKApxZn#jMt_$(`*jm-ffv=Pj?&3I|59IyLscU8kdHCQSRBX`r$liJE zFp0$e$oyWQS7Q3%1NYyvxAWR!y6R`DedWP=W)JV7hE&1n@})~pR~@OF+WVkaLh9V< zI$BT-DWeZD-hIHzS%Gw4OjmL`(CrK8cgX3I)eYTmyMfLP*fl!R7E+n8olnqP{kB8p zYs0YADE%&&Zut4`!PO|&VAydpEGz+A>?|@iH0H(z82qDlfz<(W^SmIbi_mSbiER)U zRg2X9tJ|fi^KSoo1cA67+4H7r)hhu}_vQGh4)qGfLp&&R3X=NBO2n7a0dK=^L-MC_r?1G+Za7{ccaP)U zrml=srWfCqPP~f-c1*?U%1Ye|t{1t}5zjSjgF5DUr>7gb6P=!FTy0*ZE|P=ZmOyze zL!w6$o{OfgKv%FBn?y`^rkC}<1T8VLqlcEuT~t?6KH5Jqf$wEtk|glvR%0tVP7#+(BMS7vSFqwqGR4N)L zkfosuNxq80!&rB>lFHW_BKb&N*QFEJai#<6WT-U7YDUmCgZR;l@nY`uY?-(}WcO&- zMJOGHq!Lt#+~Uvx#fQ=A%q4VM3?*b(;!Y0n;xep<|vqi z$(BPmBR4}G9d*dV@fwU9&69LLZJ(Gp2S10D{l3A$$gR{3PW9qunJEza^0#zvI(G9r z&h#=>_}k>)PLT=^qOTug`(?Jgp+>C9&6$nW>8+c`Kk@oYuYL8;Ucd5m{{(1U(;Dbv z_o(S$I-Cv!QnlEc&({dkZNQQbr4K0aMe~Es_OhZpn@Fl$OaYGk-Z<9rwiHwJ?KC9e zFa<{pAdi+#t0IAVsjnYfI(aJ6!WC5*h0^f{t#GVRzS70p!Fh3l+)9PM7{@It0Yyts z%A2lkoLzk!ML?>Aorrp=J1`FnMswxIpps`5-pC6_ucjMwln(RqC2B0098gzMOtDCK zOdq0oO)SAT7oMtadcSfc1*a>0-D&7-jPb>6@l04oJ%2$pp*l5evJ)v8N=~t$!|D2t zFihvLk)EVg)l?vlHsR<|$0Z#UwD)DQQq$$~iJLi{XnY)14Vh3pg{?`Hjtwdn@8b{d z5`PhjfXDTYpkCk8+PEw~0WW2clo~wo`t5O8b-cAVU6AfP>6Y@cBjm;0E`Igs&VUyn z{ceQr0Q;@icm#gOjlkUTxTZAi=1f+%Nf9|$TcP#N>Y`a6#ciFqn?Y1=1a7yU9R}_; z_GT^g?QP)Qc#tk>oh5ENH=*fmKzD+=Av&u8^?z`1Zm9kZ953G>@#RnPsZ&X6#uq<8 z{n1B%-{*8sPUl1VEeG%G(yZfBx`Ana453k(eLy!#w~@5;4OPrYO{aEQbnZ#sHU(P? z(GB&rH{bC>QK^x-9zwFZ$>|=9`>YPB3)FRGByT!5a;Qge$`ohE+tx!V76Hj}*@)9c z-wt`-_4DcF2? zsBMgf7Bo4UnqM4i&7O|zTnP9^dtrva#-+9;RP@EgrE5R9 zM%v5CXZDU^j+uX3tog-X=}>e(=dimkfA9Npp_^PTR{tIW>X=-xrpxv6{Y!XW{EI04 zD?fb2yy-uFc}LQV$?4`zKgBmWNiXlWH=P=_=F^>zQ$zY7HKeHN!#Q;#Eew|l|Ii2ajh{SPwitpP2pG zl3tLlo6Bb&1jY}NlI~qVbXQ4w^ytF}?)AEmS_!F=Uc~7zx()Z-yNA%3ikL2Ax@3Og z`1aLj^PP+QX}k3xo$dA=8s<1er*_}X-~p;HnEQz7KEx_3-#w;Ft`-dob&ZsT&7iiM z5f=N(w{8u^p>*@6vj#jjM6UpPMNQWd?yY^h-5Zp%2U{X?*Y30h4`q0+Ew!nx{@vKZ zo|ofu-NkmQh1-Me!<+SAm+iH8oN3sxf=PS%MCuGXOGqnfIulp_=s3m~8!)BgQAbrr zRzI~;pKl`5{8YYvkp84A;g!~iNL=m}H*5>%qI6G9-hFtTBB^bt;h(LicNs*NoKCT%FugQf=nF*q`%m;uoaI7jT??H#Q5z>G6E`w*%6bu} z17YN5RHcd=i6o_mc3w9U$!3Fb3cnjWvixsX^+a%043`tlt#$as1LjY!q1{c0aF!%M z7AzshDy%OW8|aRn?K^>?xGvab^`nJ^@Cdnsb&4|I)w{nr7H`UwE~&lg*|TdnU*`JwPHb#! zU7o%fS_wCh1Q?Gdbpmg+8%n=ObD>O;fU>EXjbu-1i1W5H8=FY!GwRc{d<;xqBEhBY zO17|mV~(X-zs%42%;w*&->@dD+PG(V>#5b_pLhwR|C7@fQOScNb%Ra)4R~J8VR_+I z#A1%|JQAZDDbbA1veoO<97h%+nYP2B9{Fh+x$-L%r;?+F6N4G(yS zFy<5+Kyd}V#}fPj(eiUZM+0-5H`(Oxi1Q$DI&wejL3Kqr^7JuJmHFf0@#1y7@ibVX zoRz|0Y6(UI#HZ_Tc2%ej_D_yRgYC3Q;xIs*zLts7#A>YwX%hq;#)w}yeL5G7HTA1< zR@}pv5ur3Zk9d2-Su9->Q9^(+eaU)Gr0mB`*{VA#dy>DMfH)n;i#oy9c^}4ip+h*G zsB}})QG4%hdD$74?v!*x>YXE*RWxj4y1}(W?Ayj}yStAK)&0>I+#Y;Hmu_y{t{csG zD;(Gxq=VJy=c0D0qy^HPxsy^5ZYZ_bfPF)uq;f*mm;*)$Q#hkm6^^U zl;&!Kb5)d@vd*OAb_5GHxH}Za^+vC<}BhO)n0OpZpJh@X5}$#gp^83kfichUsCd2cDiGE|E_; zb)=KsMHQqd>XOv)^kso?4eL|4ww4>S3sbi`Nq0$8FyA;mHl*58yfC&Nl3&ik`R0aM z*djoE@rAwU=>ORH$xhN9f7vnJ{tSUQLc3nY^Fn_kPfmZ;;W>!@chb|p|KfGac@d~P zTK}@tbcp<0-?iLyqS8%JXIxR!E$-3j_3s7}-_15K^{(>R7M&ZdKp_h zUwn58^c~MycZw*I@xY!Vk2x`2db;Fveja=5AgPOfB%?*A%X{;o4}HkOUhd}xL0ww< zgUX0xFg0EBxG3FY@$D&FXaw(V;i>Ajsiu#NM>uSGmty)ZN0vTpf|&wLf7qV#m%N8t zkBCLePPUdSP`oTUwnbuOhDYoN8C}BpugUnG%S;m7l*J6s3U z&6v`M9=5*gOQb$nu-%>@QcIeDd76CsEe7*?k++A$x_Yvw(O;z#J}r z@`?%f2=*&_jMl*w`do%~x^YxEN{gdoCa^QflYL6y&If%DrgI(s?&^t@N|`A2cr=V> z2sVTu9!}W;nMP2T|1M`OW@7ikbAwe!RTK5qHLNkpe*V?F&EgIzQr>hBBEdZt+B zOGa|@>S}hYsop6cLxXk&V&W3`8N9Ibr5AM3bTl~_gJ43nb)q*KV(nDWYeHR-(kTN2yLNP4q{*plCH=x_s&Si4$ZPwhz$YlE9IMta{kz&OdQFHygx2 zZ?*{x)i{SiN9qcm}xCq3?nzwhN(YBPz~AX^)21)i0I0X!Bg|MBz(_x&xOOS zk()QewPe?vRWYH^Z*nvk@4GnB#WU&3w9jR-B&Kgn3C@XQK-$7ozmA@?yu9@TN=QF3 zo!i_Ty|fn1Od+--p`)b(>vnTv`o>0YszAv7acnQ2eC>%R&y7q>TxuW4$HE<5{dJs? zpbC@$19x8(SN=c@4c#Pk(q0DpC*X9Krw*udrbe8O+Ga6{x);{`269jkgR602=V50s zU44w8N;**WNBg_V4Rv*jg&_)@fqGif8d0PvJ!rscqo$jIns7}7XVP#nv{{Oh%&51g z3IhNOc&~Rt>yF^h(9SBWqHWBQN=02r{p#BfuR_M{wua zoz0N3LlC3H^yWP0P$=A$ft+m5K5AOI(DD>GSEeG*uqMRwrST_c1$5+9OHMo0pTQ_j za!PMKBRiJLcL>P6rBSg(>A*H@LfS{@5tfpuCtzZ8@xA4pKA!+M(bvP@l4|Y zra)Q0V&t8J0DZ%Hclw=2>F(fZ?_%`EDr_&Zw-CJuiAz>DH@ahWQM!%>^a$Ra1myCi z`yO?N=-YGLgX*F_Oe6pRAOJ~3K~#DnG_^b8b!%WGDP4JpzM3w_i-OK)((9y^gXlQG ztWR(epaD|s=vZ=*I?FNCIa#IL=YN>5LJyVu4N=ytjo)~Co zc*<0o;KX^#InmnLmE`nnN*~x;%hI9QJVWNuBS;# zhv?VaZh`YWSxkT8bwqYXTQov?;p7W#V`FV?*Pi)7+rrojozHaMDlFYWVZUUvPGsdf zcd}k;dL=m>8VASeYxMo^sqc|0NC$i=U2B;B^2^`ya?}5W&Z9d9vAepED(U5YH@!3? zr>ELFk3M++17|R&tB5q0&Jms{Obx`Xt`&+O#@ z;WkKD7g7fGH@g2GDf}OLV7IL4@Hv348&lJb#CHnjZoy9h`fb=w%;e#dWw1(CA$u9# z>347@4Tt6srarec@`%*bVMzWh1|xANSKqOPL9|d>SCO;?busa67Z1XX%q{Un%&r>8Gvj&GaToo%(Ap}V{P==L;(?%srZ_TKMll>S~& zz4E);%VkL~n(|-zRZCP+nWkdXh3R5-4Oh9?4Gb;&3)U?h=~Q^;Df(Pd(2JPdek!86 z7LW$Rk9w9q&8%CZr3@}#9e8&uP}9kDROX{O-AC#oDykbme+VI>o z^`|(fV9kZ)<>?J-Jvh_PKU+^DrIo?HTF_P+X|Nbg^j6Wg2XDs~AE+~p3haoXqDBL9 z53~d6*iR-9WFtLN)AzT;R8Q9j7I)#*AT1!#ICE?xxjM7Nmq%f0YPyjxpVeur{7*FE zQdHgvAt)F4GNji=HkAk!3Vev8C84+!NLMM#F&)f=qSd8~g|)Sd7dZ^*Q<*0`ef`7) zsW0>n8bE#JGyrmGuz`-3x!Lm=)Z@{!nJC)6T+}q{gg-H0*MPAZnP=$ri8p7W)ZgD! z(}O<(FUy=AbDSXWvHNd9K05JGKiWuWdVd242Hm598ZuLMHFpPzfdTOebtKRvDwBC~ znot{xLaoUWY4LM6QX4n7Ui&I)`h~*US?H05nu?d~N#01!rMLszT7G(OGDXJy@hdoF z_P%`n+zMS_Npi`r6h}tR_1B%lQ({9fQ{6Pma^rL-pSLvi4^$vsoGvf9{PQT(!Rk6F zof2B4ZOTOnJ`CkSXA;5jjKj}(iD;ih`9K+ac(H-A5COSf^zy*M*uXK%C<>ByvASk> zI80H{bP?lSFFaj?K`k6k3N>U!cksOVRI8LI< zfcW(0mKvfAm7b0-CRpNlkM>C|z5D_7=JOa=Fs}pvWFlbH`;@Hn+CZFBDu6me404xO zrWodlBB;~TDXj9(XpEM$-Dl5s^N#oIS~W-)rmG|sEnauUt%IfysYj)UL+Ye4&Nej3 zToo*oRLzVC>Ey)%#(>Vvjp9o@qw0m?E{0G!=*Td-y*q}PXlsku0jQPc@-l7XB z=iT(-B}{jD>Asj=sUG#>T`Ga;W_a0F%*EYz4BpC$mJTs{Y;G{Ft+iyw;ASc%mzr`YSpexv-bd_>?Y>k-g~D5V^s> zwK?x&+mKqSH_eGqzZGwelwOh0eOI~>dxTs=yy;F)2dH%?FArU$Zs1J-J6G+>eq6(& zimWb(_qOxORUMt*N$aX6Wjm!MW(iFv!4VHU6|3@wBaF)su8K}Ux+vZ3E--JJW}wrX z&YYsH(`2LztJzXxu|2jG_?c3Z;l+7{p-(ZXa?t{6{7^xW>u~v!Eb8eT8={*trt=XD zuU4hn5%`boC6y(`F%5R(yIH=mA%nWoUS>#UWD7E1mg#{6qFWj~uY5QeY(*>1cX*m75H5~P_Uc}*& z)nA0q<$3x3_b=BIn(j#5DE-wJ)rAz{{FRrVd+tq&Nx8Vuk9{@$pTzXS|4r5TLuU@} zzJKqSFx@(lcF5Q9F0ACui6@kT^6)`3x`gYBUO+`Z&e#YJ8JsAd+t5h zd2(rfSV;{=-9BQyn_D|f2+u#f=fMNJAA0QQQB{%t?$O7OqNV>XmKQ|!Jrz(_Qu?0V zANmk_I*g9YelK$R1NYqfAZ8U&x-Pn^D)i1lOB}0n^V1VfhTnHIO>)D#dD?Cp|8vS` zaY1?oJ2jyVZd>rKXGFRN(Xg;_vT)kC*rR2^JA--Bb%Wu>=Cn|Qt#y+X%C@_*#_iK~ z=cIGDW3A9fum&x$b#^piNbWXbmpnD?LRYtJ`?s>?+q3Ux>b93igsy|1U-jPv%T51; zqv227e5$q8v%HAVh3d!YIC>m|IwoffF!1?Jpc;cZHJ~DJkHQ^x+xWNv`Jlvf*18p1 zLv&dqkM{LOJhS?Q!*fmj}Zl&yyNZ0s6!wf*fUCN53%(?u2e0eb}1qp*4V zi6~=XdUB3PkO;2%uF@rr257d^!)I$R*^N47fKr?Zwv%}h+H6d6N`h>K#Ks0NDSJj$ zm^nbZ+g$b&^?HS^#xG9vM0w7pSL_bPVq8t&%`nVSEv% zV?&8|547+nI9Z<$)#NdSt6i)dGZYkn&e%~hFul4{RU!8ai}h0s$C2+<&zzC-r5(B- zXy+X~F&9^Nqh>@U=}MgbAY4eHJp{%iyE!A1>FdV&L(7dIUY>LVXBPs|F4Fkb!8P8) z@!DiB(dqG8HdM9^#~*#|)D&-?wI{!ee*o#})5z&O2lsT)^{c#31NV7b8M{v^%XmTR zMN9Y8^h))pOH02U(suy%_T;vFeiw#!9PT#urhO83vqt8Q&RJlv?(w=2xQFGHX^2>h zY#vCKaL!0VISYl`#@@!(CYx&+7m4F0rrR2*+AY>XHw9{I6FJXq%64TaZW#Urs~puv zKE4~SGt!-Ol|@~O`tvwnP}J4w2sIrs{nx$l^ndX$9{Cr)`iOD5yoo-b`?tI?-Ww$y zU23|dZYCY0TXH(6Zmt*1=*0T)pKYivT6QKERB^j2ch`1+x_m8`@?!e@D($tz=Qc7K zT{^lim;1NI_MW7!hhV{Q6C zYKBO2>PM#=vr9Nsrq$L6vIemUPtU4_sq)d$$+HOz>$#yJbs}XwkRNHB7N$=P;YBBd z6>8VrfcaEmekl#G69+Q|ealcjJ=Hcu7YHV?z3>6PY02rzPoGxki*SA!7+>eZeuHAw z^uj`#Mx-+vQ$vee99JC69wYUIFB5h^qI!CLYhB9vt+q4&p>5&XGiQisyw%ouW^vsA zdi~|Rg+e7euQu-=y<|Zz64ZS}*DaE|E2LGszhWLpQ*cON`?a(;dm;@}DKZ}je-mcJGEN@P#& z+q3V$p2K^OnxKB@@iR;ueQfVRoaq(M3rR0~_UySwwsh2VDE+~Gd+z_hhwi^uh8K_0 zH3g;{q`R@>bqD6QM5D@t5&OY?`!MkAdwAcG@oN1F?|MMZ;o>0OaQsdv*Eh;rq3YYI z=^h&!QF~O)jZF!J?ZW60fjOXV68f(K>c;9$LI>0Z+8(eofuOEgZ+C93c4~X$Nm{6) zw{Mo|9y|@VfqO)a{SACb=Z>QF+lQZCa{Kz*<|;3ddo|tb>3`nu@;uAkTGVbxSwa>8GLR0_0A z#t1lVZk(dAT&@vJuaDLBH#9(3G^Ui8-hSy~L##d_Z#o|ji2&Uo1JzN2t|{-!fayxp z-CV!5niQr_ZOlyZ;jL=QnGIBxV=z1!C>yG+L}MW}Wql^jB;P6<$?2gPT1^I$HE5gh ziv?2J%gE`&7aJ6q*sbLB2|VH_@VvCQlPyR!p&|my!^MW#T)a0g#{@)z@BmFrBm)Y%j>%oK%qC1;u)#e1D ziqdiCL-RrD!bst$#FS-*L2uF!yD}r(pIdi_IB{Z>H>@@S zp_?GX*A?P;Z!9TK530KT`ca-cq#f@#O^8^Tj2ZskITk3Dv(+j-pyMcAOR?jS^T;^| zIwx_scj83fW;IV9N6chzYlL>B1Q!)0rw3*J=e6@bk@a!9J@DD90VUlPkya@E(GNeW zloIgVCv?yBVq*F>obR0SLET}xkKtl(4VC%3Xz6Yf+rr@77@T`BBVy-bBD&by1u%MG zF3y(!oDnx%jNDnM31Heu=C;Pj9hlZu@U+3Z#B^!k%532x7mEq$T4)nub3)SnZF~vc z7Q1b^-KaZdra=#c!GDyM)mC z`OK7uT-)Rpm!>eiG>We2PRdB)ys{P5B{WB`By9|7U&@U^qju1Mj4w@fU6{IdM$guO^m-^2kUAzfCO8J-=2IaZlmLU;;GjpSc^^RHhw;rvwnH}R=|{#!r(;g5g#EpXi} z+_kH|o=?B`IX7K7~g--SfaPNc=Fo# zY$U-)boeBe7Zmk-?m77QN!lXSQICqm^3J=xeGA>CIsG`zMDN{m_{d|@(Iu!u=|}eM zF*5gUFCufm908qXM}Gj3KYaM!4}IW)-Fpnqotlm;e!H6P6FIkbz3tYYf%26CKUT!) zbNjP<+c~3jSk|$)@%kN9&ga){O!}^81nMGa@5d2(h0}ck7lnHR>bj$Jp}LD^^jC?l zw+Y*`()bYW>*vPb+Aj~RO-xL8dbx1j25qA?+GKl)Tj1us&34SZ^W^qRq}R%OP5sy1 z)O70@bRU)%Izrs6JJl#f{idXJH7IhLI(qs|gmka=LqJPVJYT4x?YNoOeK- z5>h_+YY4Fbl=z1k%@lAUWG=3uB?dEH4b>P~RIi<&uQZ8X(0orm5WH9b)WLM&%K%|7 z@M|+_I!$1DiAAgi1yQi^fTvQ)DpCiNJu_QSI-ke10zxTYpIN`Z6~+Ky=oj ztrHFazT+QZ8#&rHhGsT0S;(y=5$h{pc`4(0xp;ASm`YEH>1QVP?$?X&f$oV|oWIj{e`Dw9EwuQ|N2=&~k48-j4-tYKYy>dJkeAqgAmg?NzZb9A!}CkSX<1sSusR5<{0J`Cg`JNQ&o&V?JJ6_7%FTH{DS> z4h)r!GWe8Ual8QOm|o2HBD1vuUhblmI|w%zx6w~+;*q+o+=1kRYc34lgn_zD=UQT{ z?g(5AuBAIK($lq=i@01DlT^urmUNe?h(4JFk`voaZ|#bDcwzSEWj@H1V@}7L4yFs#d66IC>Rd0FjqZ~8;(cu6 zAQw!V>@7-Xa0rd8%@r?OMMih5ZiLRCew7*_IU1Kmg+Y*Rp^LVZDbcxy=sbcT-Z^8S zaue3Q1A;_imHla@Kk!Ikto$ym2IxwdftVRWd?ty&H4|oPy0Bg-$Tbd!b8k8jf#bQU zDL#xS5gi&TaJOj{eiDWbk|U*4b!|5H(9|%}c(ITL(ed(xbyR@Ar2{Bu_Y6QebwR>% z4bw~GLo<3r22}Dir#@+UCQ4TX48l36PEHJwFBFqb-*C{*hC=e?blcWcdTfF9Gc$`X za9?D4y1}W%1dy*@rRg-1Izs-!t%b3FY->9Mr!R~VIdkTh9Mh?s0n>M_?i#)P{qF}&Qh5d6S_eFyjAe6iukL8qf5r`v?Y^auao z0GNIc+`jMNk%RjVKfH%}(tAi{l-H#)DCwmlqWhC?ed|h3A@#9>w9UJ|5_ex{A_8P7 z6x|+egQ;QX_U!Fb9{c(TymO_;=7!5gqkqij3wogUiW%%3;&zbkdic1xyZfl+c;C=S?aNL16s~HBL9P|w6 z9+b0j6g8`MkiKp&n`Wl%gP|(XO_(QbY=S$eT1lyd~aR7X=}ru0Qm^daK* zxC}g)C>bWog|0S`I>n50qsf`gWbZDb3Ps-HZ(+LB^uOKMy0y`>k%Zoti43q6m_kt5 zHMz_-H`3F1C#s28#Ht`f=Q=D*A0{X71f`zmCQ54)Fgii!QIzyR9r|wrVs&!A>?FxJ z76*tE15O`Bpj~8nQ{PxOO}JusB&_&s)bz7wDMQ6`(ZlaQ+K%b{?1|Fa=1uI?)S6}h zc@6FDX94(uZuM)}uiZ*bhhh6s+RNoE$Q$YiX3KSrsd5QSe|qBFNXN<>Z~obL|NNCV zUVr^rO7)-q=H%6J%QLsOmOEYQi}xbMb0!?W z%ZB!bm%Roto6veoHLnhqgJA$WBH>ZCat;G%4#eSF9|Z;sA)3idgJpJ10P%UMo5n>-fcQy#% zXUESn(LK63o14#7Q)}T5koshzJKi40$-EESnA%?zM4m8l|)eIup}5v-L)K`ec-{svxOde$Uqc7LHAq6&$O-1U0ma$QEzmaLx~;T@ z+)MLD?`Z0Rbn8n>Pg3)}n4In~-S?+^?sPc)rw8wiG7Y__S9#}B$I-!^cN|8C((Ok~ zzEOqFEiK&u-ILSVg!|a`PD}^WMdvnhO1jh0-59r-E@TQp8mBL@a7rAC%{6`aZiFC#o#%}l4q(v6MT zYy{<8M#R*{*3#At`Zzy!xiQUW_{_`=0sAuAKB&$$jaojv-Zr$p)z-GfkwSLi+EjtF zsQ~@VG$Ak2+S3FR41wyn*Oi;TwY7NdnLp^Hmh{%rwOO@H&rdi?H?I;Xeqj)XtkQiIOK@U=6C?>+F)7?_UhC6_Bi zc#wC)qp0Z;%)xX8tn8WZ-5;9mT$~-EBuh!4;q$94nZx{~lg{eOaIdd$t$h<__+>o4Eeg!1_~bDkSV9 zwBT9{?JgBYx2$yIa%6O==vre7HQ_+rn{aonNaY6F4$RrWVK?{Cz>Rx2E!Dh6Huh(^ zbp-F8j=zc9%x!M>dD{`M-|g#d)==I516kdWhr|sxH(F~@n#uV;)e1OUBBRuFH{3iP zS-}*;@FYns3_I0w$LM6C(*udWM`)R$#@fy~j;&7OYj7<|5bVfmPAn|kaRpZL?ocwUsw>Hb~4Q4oDIGuKT^ z8UnSOkb0^4+uzgMQ|Q=Q;-8Xg%Y1qGBH7%SCX?zGQ{5g4Asy-Si2tkRP?osy)Lb>C zeATJB#2lEutM|rw5}S*pboJjPH(W8|TCmZ(u@1N&Q`9(G`bIB``^I{jv=pHJ*38C@ zR9`t0%?!))Ql|9tVi`=wrGA!d^Ai)L($fDG-fC*GQbfGs0EDIJM<+O;E+IiEsx9PU1OHh8a{5c3{PUMz=UwH)TMqOlx_|~y z#JjNhS68Dg2a9z*aC#))%$@272BGwRUrQfkVz6Ge7t_--MIv0B8c&62wjo=_L>-DH zdL*gS8I)v`5)@k9WrqML$0Vna^kSIa0d{kyq3_bgF1-7F0|S@ZM{^9Bc&1dO0aCRR z-a;g;pr!-ta-1Ng_p>M3UR4`qbEcj{HMH$p_R9N(VSKKdq+o86m%m zq;yd_LhrwFeT{y@`CXjnMV!84xI<3&>DzGHv9`v@={|#RPk7601stvIbhC4UX)Q40 zi%q#X#!fc(Zrn^|16GT{4cxi48Ac|j8=QL!#n(;o+V_TZHiRo~<+0?y6 zM$Y0v;VKN@(2b~_F~F`MM(?79@~_xZV{k|5+9&(!)u_VhCY>vCQ9B^-1w|dm=ibQZ z>{w|o8W7GQ=kyd3IMt?&RJ#xw3NOp;V%$6}$|kP`x}MI?;$_)_ge7}(U&M5dD6q7r zF`Of)XUpj2@HjYMlzI-3E2{+vC$puous8*E>vs|06ZV3D&x)e6#T2tMWqm6kpht9o zuu(7z4f6~$YIACCb7m+PWr-rvQO~I~BKQTW*W5DlygZIWv@33lhyBPuCJdwLHr_8x{VOke`4NqNL|)+;utR`CI>E?)x}Y|VEwO^$M~%` zEr!u$G44ovdGom^&GCZq<^6pD`8D``!sCbb;_L35A1+fxI-D*j4}9Q(`wv)d`tL|h{~e*aQ`6rG z&MV}O;pL${2M;Y4{q&o6{RgQJDvPGN9X5ZyIeq^a0^4pNUPu}yHkli0)>UY%ji75A z9`SVa9TAKy+A&mUT^1KxE;U>X?hXP}GV0Cg;TgQ&LBOpQ3^wu>-#M@SysN%m zcdmHTHRHbr&2pA_i7LyhiBVu7A4Ajz)lZpgU_ui9UU|wg42=4ec~2|L*d+< zdh#kd`l%D_#Kz6)xrQ_<&tDle; z{%VI5_333#H+P2-%sjQay0NkPlyN#@x<1I0h>ybbo?WA!;dka>;3gwt){ z5TT=#Lr$l$(K-4TO)$uw-cSlRsl7c$58C+6RhMcTyH$no}retv{vH4 z0dG(shG&E*Lc9-=5E}Kwx$Ea9YQuF`zVq^HfBwpMP}85qntoZP7cxnZuhGZ3&>p8w zxt!u`ZtHtaed2X-{p-(NAH43;(VObJXmnXuM>%e|TG=gpbhXyQ*%3vilNjHBaYA?A zf$D({etQOhIZ)eG7ibzOmr~UjnQE)zb)iVUr;0AFq3S>=sFx#9%_cA|`QbQ~5V5HM z4TZ~Do+4qJCrX#sNQXRo=~I{5yK^6VwlMs$@%g2A4d>kB^k0EftB|Gx^cdoFLRS=p zo>MF$)|whxHb#)syRgqxhclTJA^1>Eh(C)PeRHuT)2#DUsRnkKN#~ zf_7LOd(j$K-EkG8Im*jY6QlE}4n}zL*j~cJM7GDLP5WBDC~V2Y(t^@kb=^!s}Th0sp;E} zmu<641=I!CcN+}0?_43sw!!dwd(tg+Yc*|Cw~Z>|x#-)2b1>YIxd_`da^biAFw!Ix z&W&@Q+X5$!+Zv7Jd9fR#a$&jdVZIkr&!w7!>R-@>1qS?5)=|oB6%ei&HwNg<0K*bZ zdUCp>e97rMGSq+T!`6osR5x6gy+}t#-WzbIKizwyWE>~lTs#dnqjAfQB6wynIu}EW z(%o2$?GLt4jLkye8%{URi-9?UhAuWpVCNV>1Nu1|TJ5RTo9dx#*P?WGBTC=sn39FX zgmI9X2PUK6YDXoZOZgU}H#Q=bX9*$)uUSiI3um?(@x*}hEFz`_A)LBUyu_JQi(B(_# z=Ko>zlOMgv0Hvd(fA7T~UG8q4+-`1!md>g#fBxkkn(4)I(k1rU02heXp#%6|YI-xc z{yq-E@%_81W^uh7IBLMGb#9+2Bfgk?Un2d5om1Je=E=C?9%!=sc~A_|$Dq z3_XUNet6&g_a1qCY-xVJOcpcZpa0suyI;f1H=ue?=zQlx7}RBbIdI@!;$3jTJZQvj zLb^iJ;ql!Md}#NF9y~&}3)_+V0;b=?;_U`Uu=;k=i%|U?ah*FHIr{N59$-k}Jw188 zHttZJ>_dyEQGxi|R?e%MMCsl3m&YnA_cI zi5|h-`g`B0*Sm-Jo`arJ1;w@X_Mko7wsObJ_Ev7{?J(WWMacT1tQY@}$15QRS3SG$i}+Cy!p+qo-$4c&Vh7r zU1J-bKF1+B((T}26PQjz&8ytCH9r{caK88BH#@H8TUQ(TWc3aroH-p^`mw2FQ1R+h zoC8>1-q5FdJOMWKR)y&|P?ebmr;^!1CfS=z)&zs2I(ODf==p^Lr&JSiyw_zBY*HaM zN+zob$O|itps|Oq5TZiSgw!){E=BR;T&g=hhfiSF9A8tZhD@p^QH7>Ux1%8FMpDRT zYBWg@0V?_~qS8~@4a%~TDOv_KZ!B}(bS8Bp-nZF+icX{pLb`_G;j(0PyyA2Lx`;F5 z(nKGao+&rfB4R_qg2i5*^5p0oIWM%&0nsyk{Ui)ZOpk=7Nz&^mVtGM^zfLPt<+}`w z_R5DbO78aPKzrYuss{N%R<6a~Lb8lux(@Gq=b|xkP>31q>f(u&*UAm$a-m$tiW7{~ zWp$u{875e~+41^oe~y|ybRJBgh?X0uXvm;;?IvXbZ|By zP8K?ZKhgz&()B3|=u%sXAYDa9d=lUloHNwc21q<7*oB}M%R9taUWbbVzXxWfOKSw& z;4XsJyH8wNE6leMbs3^xRgn|zRAFNK5TORt36wI@KAL>Ota6n!@-icGa}pz1>+J08 z9;%%qIfeY4c0e6XX|#s8M|cLoyS_I@6)>d^nIi8^7$BFhAF<+2`Ej8C5Z)4e>xzJZ z{zKfTezQm_Xos@{*kgEB$r#;N zy-x!l(;Xwqd|}l1uPVOuM|~~*E|6~Kbcfp_a3Qu|H)?Z^ziopZlRNL=?j^9hs+^)@ikKwUyA^oIS1yzxm^Y6{7;wgwDJy*V!wM0NiUdQ6q^pF?=3g?q>mguzm%@x?&u!nPE_rO_uX^P!)H#;4vh~L zI!7oz%~k1Zd-v_xvky|ojxJ!|p{6@QecyxklJoL`0~|Rh0p{L&?;$uH zOqUM7jp}$_%x|ugMFx$W8OEP>3ki6Uqy3@7k9D@qhI;vx-sv^D^Vf2aE>eGg20r`* zz!e;Jur8r{hX(~lc2F%@T~z*vxZ7OmJHg#x+#79+=^(W>VgZjLCWq4^FEv>T*jUdgwv&;f~-qVyu=&LVYf@th~CYep*i z;L6h@=bHL~QxZKI6y!|DB$-|~F1UH>>I$8dcm_A8y&6&i8BI~AL!9a}m!Ep-DH;!f z$eexUtA+D4R7PRxPWJQ?5wM<;u0+#LDzO<_QCBWxr<`P-PdXd>R7$xvF^MFvVHvqn;T12im;dYwA&WV*V*&Fbmt zj=%Xc+8e!r>E%b)F{fW|891AY@+D}PjvXkKsjK05&7|;rtfhDL)YZRv`KzzJ{5tk@ zr>58E@vVr^v8SsdH>h5pBG^!!@)T7(TTgmAhjg4wHE%l7`bb#`DnzjG>vnZ8$`s0( zKqypa!golrUz{0K=?2;LF{-G~C)J$f%!9iaU+Tzxq4J=Q^9 z^h6=SxA}Ak36ZRDv}uIoYT_faftUu}K0NE|MaHcSu%Wck)p*TuNsQz|kQs2da0W_`WOJ*g86*^}X%enLC zbG(71xxni29{y-16IF8Zgs>W6s;7x9&N?ZG#>~h%P0a4^h;1*;~ME+DhPIQA47Q4XNCS-hjH#;3+ex6ZtAePt%_iwHvd$ z7HdbqHQw~b$P88Nxpb7lCTp&_%u3)%TewJnhcLo+2Z zShD7-k$F8^C<@B?SEn|$xIQ$l>=}VKTz;%=3rfe?qUd%eFq><@aIg<2A4i`^*0Nr+?xo9Wwvg*S_}mNB*a;|HHNKYY}KJO8*|!q%b{pU3)Q32m~x*W;0unvR=>LGILdQ``9-UtL@;oktGb zyYKO#VOK*sO}NTC?1S~q`y*|bS`Hqx?nd|De{_0(V*K#6^!ec)?#zo5`Zy-?BM*^y ze&*!-(D-Rps1~ctJMvDuzvIy@$URXWKl$)O(78wGa=n<6F5z4fJF@wK`)NUX&z^@Q zydSui{zeK;7t?Q(`a{BW@wYA>qzl)XW;kfezW4F5`C+U&@A!h;@r*U=iRn<~ zPx0uxT5ucbat{%+4T4~I5%d}?8%?tw(~50p^t_YBF{W>0I!%vm8wBbG>;Bz@^**Qb zP>#EKBqrU8?T5E#B&^@Q+;%9T#kS5pca6PYV|&57ozhFmi}|bm=l!l8yxz|9vb@~5 zTGbUDXaUp{#_2BB1=dDNM@+v-6w6B8%E}-YSzLT=T;z@41;k!a;5l|>{17XcmbD0n z41f-*@7NjzeQ;nfaE>N8$h!Rv!Ei^%m5z=P_Dj5P4~4b8kF<2?+^Ol@7KSNlyfn~MzKH3i z1im*7v;#^FN*Y(}2c~B};U*`O)tPu-0ni7W`|vT)hDJgvsx&5Q5?^f$M8!q z#7Y@@PL6g{GRotUUotX+-Mp^92~2N~%bSiy-&De~Odun68ay?zCZHHw2FD%A8o~?_ z+WV?gndzJ7F};{K{aJYTvM{~+Mz!R0)N!2sWZ0189y3mFi6vWj+ury%0{rW52-7DW zz6U5et;O%cV0h1&ix7uFka?_00qZjU(0w#-ly1zw(uGAEBTk^U$oT~dRVj~zI0tW(|$2m2$sjkI}(v_ zwmglJ-in}30Vvo@0cjVu7hZ^_coP+>#KuQ(y^yS^Uli#*PFzI@o-gVo#fi1Tn)GzO zUs@6^@}%s~#{qi9TeinJhC-YVbF6?+zoHyQ>HK)b0qJOHE=H_kT)$9?2t|&zinZ!m zrNBzsKUEh_r-!$4sqVSCIkL`?*G;OImM*ex(cWZJq0BZC56|EbI6phwS4&O|2LUls zTsXE%aG1fX!IB2frtp-iG4*uNWmFANlX2ed0o$84P0nF_k)Vzfr{sP1RxsUM7tWSW zQlMu`{|tHQ-mp_l7hvB;>4w!t<~#7)pVZd=;4O1-4oo{77l8X}WdtuNZj2wf8znAtHeAG(|>;&Y9lZ-aKb)kw}4ak~@A!Ed%>xubAM z+zIP!XOkMS)<|F53fEa>S1*{6P(~dBiPEK~EAPeHkvc*B?wD>^Ek?JP7mGJ{?sSp5 zlh>KoB6TL>B2H(>oi(_;rqxY&v2hBkP5bo~J9fjxmfzP?hZ_=0|$&rCG zk?7ReLXgro0B_9W@bhv6J|=s`D1D{YJJdzBl+gb=o1NPhw46I`sC3AyB|E#c6y34HiaCCjPJyy_D0r#>2Nxj zj-0;xP^dTc@rP$Q;UmEu(oYN>#q@G`&+Z2iq}$GC6Frm;6*;+yd*rTxz7o!`f zi`5O+b#rjl%9u2+s5IyJuf}Y+n(x9F5fwQ+r8dl z20)jXuAl8Lq|GT`um;n6Yia{6Ed!$l>N1CG5Ngxa2zbVqvI6%Fwqj{`TgRSaW}RTfWyu;6vBB(PI%m1Oj3k2TgpX@= z1LebZqmeD?7D@+E3WHK+B%evG5Ai9R4dIpKlbKDXR~x6%M^Y)eL*t5E&t>DyqwQjK zHPBR8qL@cUjG%G=J3#hCOE{Mso-M;j^@$awcdt=fQN`9i*KwK$X=^ zO}JYm6QigT6a!@El{YdPJzFB$r2PceY#M0Rj?fUE)Rx+QatYh9((th{8lNi#$sv~xI~jTGXT^LyJI=y-y&BlcGq3i6?0!G)^NF2GNs}Y#4s}s^a8NH&WJNgz@ zS7>`1+TBXG!h>-CMhlI`xvNV=_fyZcMTOoC&uyf|x_UEiTI8)|+c%mOh|B1r9}UdA ztIcVFAvw#m-e1eDC#{RVnG?7R%x&6jw~g|S(FNmzb`#Gv<;@DvzwjlG)O|tS>FJWw zq4dvu@PnqO>s7b&7y|XXW4iOEbLx-@cw50O+(78^ydZjO8FTQtIoCmKLASf%pTKRw ztc>ZNknV};IRBhEoyA%w8Q$l4b|DE~cn&ffXw$_Aj8-`)+IVOgbVf(#Y!q603ilX* zZmb@rpi?X@sT-f7_8Oz9K4_wkb-Pglu(m?g1-U*o-FFUQFu|Lp1U zYiAzYOVo?`Sj69Z?p1!e)79x{^uPljqNx#2=|dm*00pG?$h0m__k1rz#W*$Hkllg1 z;N335ccvc{qd$zHzFb8R+|P1cVK1CMqpTgz`=q9eV~u_tkUJQLzs1cSOYhXcjmizL zh2lFXojFs}Kgxtiy`rU4L2CPAId^b(6_)GjaXS8R;$kSFH&lc%mKn&s3Aju&eB>IMe-aayxv1wcniXXC3+URfciafBS0!KSAC zKpo9%=y8tJdLmjK4&%_k8NIS{RS`2IR|f~{R`NKRr(Fz<>%O%76zznL-5~gI9e+A` z<$tNf@)S*{LDYy!iMg zMHjhgU*3Q?&n!V8-Zg8tBGCzU_FSaPwjry2ACciC#?N$^4}PaSn=KXo+rTcVzC;xgWBh?+a|JNE?vj@f-`-fomTc(j^T9D1KYdL z_O-Y7_fOQG3!bYxHxgdy=2NwGAqr1%Unq(`iUgkBEXI>Hd3sFI*Hqy#b#=(;;&cObI30bRgEs0zaj2I!i`AKI z2GW#U246PKH(>`8sRR6#LEju_bfZQiR%cEKZP{o=lpGiU(q##{PSYSVbwc4nIg%ie z6L%74!>7ZdbT}GLkJU6aHASOfIqw3!lxiCzB&o1Gj!$I+k`T^EA~;mK`X(-w&Z^BT zn)IZ?KIKctj>4gWP&~+=G1hqASl+B6HKYt+wVodKr#_l1%_Vt`1axk)X+t^8JI#Y; z5X9%!a$N!be$we;4atcd-RZ!owWn2-J}Cn{;uMQGd{9UYF)!zH)D<+)5UY=re~Ibn zp?F^4Zu#An?xMGu!#|Gh?4Sf7kM_}fDG;HSfUgg_Qzdya1n2PdyiWs<39WL}^SdCX zyNH+1;7fOE`t4G>%Rv{TS2*3c8!~sKF5(tQv%nbL2ldLFTcAz2vK?@~BM0636B(mJ z$6D`GxzFcXqQT^HThENQ44n3-Y@44RiMbtC!`mj7JH{4gdlxp*R?LC<{J6!oK+`6e z3&*`_w;t@T%x|v&+0Cwwn$BQ7Nk9AP|AQ)09R_{ygO7gjgX(nTQ97O@hv_>E>fRg0 z{{f7yk>NMd=cbMe&C$$-=*+9DsFrw>B64ZsnwL|?SJS1;n=f6#v=|2ouP`y)wnu(f z6r+t9nSw4zM^cwtr7;;I<`97!xthGh#%UUF0KtN9v%R2MP#>z)a}4B`h=_fxCxpH) zR+k{pzJc^C!a4tyJ*f_H{P0rSRxUk0uS|5cHv-aG3j1T2fxX#0hj*@YLth)GIr2gWoUq(xR8AgBIDE+xNzxCbkqM!RUq}&SAPkAc30q*<$ z+TmUq@7xQ_o|zw(Ih`8PclQ{fF({oZ7nt~-2ksq9ByycYpJHP@;OGE0 z`3FAm0WtcoiPDK}#12#8bO`(*T<020I5!>LhxFee)rIT92Om6mbZkhmG)j8sxpHX4 z@AO^=GgAYWcjD$<(DdCdf|225e*n~lz~XgB(N633r$x+;&w*^h80C5~jQ(dI{b#yv zGrFnjj@E_Y{*;?`obDb%^zD|il^rtdgl^+;Jtccy{z&4 z5{CdC9j9(yz0$F=LW;I^B9+_4g)$xk)8TL!TV>i&a8Dm=^m>WjVmmsMhE^3JHZ_xMoJy}=SWc|cZ*FKNiJX$G;=E@V zlW(vVo}`$M=AEeAG=E13l^3Eql*tw|$;m2VdakO4+`N1p2K$ciG$o$&v#cZ7TaAm( zPV@og3Rgi+pMcU&f9zwkYnRq?f%u4WUP>w9mjkGkgKE( zDTXYaT??e=NAum5PLA}izZmKZ zI2C}NE==dxN0d&hDUIVXIDHN-#!1h47rG+~DLkwmgP&XIr) zOIlld;O}M*uowV!^nMN|(CD+Lm(Hg6sY zo`yXW-04B}gbLJ!620~f%u$;-T@81=59SJ{%av{!FA$?*UTkob?zbNGvlx-gZ|_(H z7z@e8=8n*vGH%kkN9vBph19k{x5nyj!j0)I>foFkUAfq14#6vo&ce#QdnI#SoIiR;{0 zS5m7bHFx?4#p#be`oUlS{o8FXPFC^Wm|yX|isEmXZ9&*%kWx}|+QvzbhVMhVS2_{r04H1-<%_Su* zU4Ra~%k<(5FGRo)j3|>~{(EJzbbxS{fT`TVhXHIb~4L1^I-=jE@u3B@Rz* z%xn#PzEi&b0k9)Z~`s9gMNlJ&&S^4V8*Is-1PhNlhuV4A$E3ZpT|MBO) zYofZQpL_FFN$I{d-8oTy23~w8zHIJ2eew)J2#t4!i|L$Nk=T$p{}>gf4;S`K_~Q@lK~R@yPFmxEJ-czFe@K-60UR$hBo(Fmm=2tyrkiALq<;HI{7!t#zJ~~Q zDXP088c*e^Rwmy4Q`e^x0+;o2_x7^Pg ziPqT-b8M%jZqS~Y5}5B;XfrGT`rXlh3Gi-DwjCo~w}%tUz_i z=~pqcbUewjo1p5*NKm*(Y3SRR^>T}$ zxM8GbghdyD`mrhX7+OAd>)0xjt5bzUGCQ-e zv4wAaW?k|*H^)d~Nv&sldzV?VzPgG7ar&70Km+V-ySkokTuq^-uV;0qrO;6Cg z=)|SciT19N=S+vxOXp91_APA*I0t~fFi*~>9}4d`e;Il2#)|y`ebZibYP-He0oj z3jDj-e<{;d!re~xV+LQh`pQS6n|;E&aL^(myJ~|S9pe;){`H&ZzxeE@P}5(%I5?nI zm+WqWz2cY&HpF8I4(T}D5~?Gt_vTwikkh~V@*9I3;!#G5^JRaYgRia$`QZDab9%2u zl{NMCvHt$pATXBbU76(ne-Ivhe0CKo&uEN9EbD*ht% zsl{s%t)-~9y|!yYryN534maAXVuZa!VjRAly(}&LL^sLuYFCQ4sy58Wrd4HD(F6%M zicz#W58+A2wvEBP7EzvvAGkamtcz8};;4lbn(}}gC506N-ybclwRiUgyGcwTk)P9q zsN1mwjf%)V?BYmDLy+hg%;B{T(*x|2SAdrQI>(-_9!(?#0q}tubaS#6anbk9ek?be z9xi4G#>C3b*&2{sj+{Klh{AO0NtsB*)aj@@zD5>fu4HL3zGH|+5~dys-EMl(fxN366{!1djUN4QCFI4oyQp;Z zEe4VEwwmtA$rnCwShs7O=duqA|>fSO((B5sVdQwz$e{8VM7M7rnr2g5@ep=b- zA4E?7&EF)Qkw&DCJfgRNiwzY>uVA_%xCot~7bm3SazP%KP%Z&on9Z&AJ~AfP9VD*1 zTW!Y%rl`Z?GNud7nXs#2I)otI9jd03gRzA#3bHLg5enZRrIbFQWVTTM6XFLUT|JC8 z;B_0p>~so6Ux%905c4oCM*)7=yehGgNJw&LJrED^qk4C7&ON-;VG;;dT zjOpumS2#x*;7TxSy`}r|kDQuL>`VT+=iYekxu>tZ z^76}6k-qZE%b)))mmh!Y$1nfzhd=qrPr&)7pFD0RKXIbZzwhsh!^d^@_2cii_+KekkD-Hkn4Rt(fGaMw$+^e`s%2ZiYecHgrbWnCfeT!Hj^cHgU^g6Wp` zQt`a}j#0W3)lFQNHRkZ%L$l?C-eLXFo!U9me}<>LOKS742-NR_oNu?tsnk2Sa9nNz zwl87}mAN=5HURbrdK;OMy&oayh0A~U$Rq#kS0C{iT#K0gs3UU5f^_yIV~h=2;eOmw zjc*^cL~6R-)!kXsTCCmOK4_!cme^fyTVgYMt=@8QjBYO`o9V65ushR9MVL4<)5oWsVVbzIUzuI(mphKmbx)_6@uz zrG|z+RW9Oysjlfw;BT8vhjhBAxhH~@o)V{#Z9)a(2{7@5JS`I{AJxwq5s2px{mUl` zYlY3V%;*3)i!|fBc(LnT)8L?t(o#WD>>DCIJ$zy%XuiZN6GX+wL=g-Dp|NCaE)I$l zHAwr?6KBtM^#S3*TA&$jr0z5nNVZ>^;BL5D`f7E)q94SBjj_dWP9W5T`vQb)(6yl! z(=y2;(Z01z`v6Tc`Q5tEo-@=5{Ec$c&wu4SRr{D;o*o?NEAkshh3Mk+VncOoAjU}p zl?tP%uUOdr6%6gKeUn7Sb1^^eWd-u@YmY{Qlr!Q0$06;VeLh1WCH;LFm9Vn`NkTgb4r11XpQc=PnzCi{l z5*aC5zc?L#dKH`w?WmCx9a0sdIk%SKxNWU4dzzy^x+rZ@I6J56PT_Wb4YXQ{kMkcK@ zs?fGuyS;(GN_x5OBi!fyLxl}hVZjixobrVe_J#+)ONgG*-mJ_WAJC(Vwubh z-i^rx>K>fC8?E#&{2nUx-5QPE6%8I*cclL5&wkdzUVi=8AN>t3pZWdY zf8-I*obHkOHm7@U6aZ~*7W20V&}BSd6?rqb5l}8B7pZGGTkylx@El5q(167-g)GcN5|VeymK zwr-^QBBV$(#Vj zAEo(Ec}?4Z>7Y9iVLvi!I$HXr(Uwzx1TtKI^7YSu7e4>PoSQ{sBPQ;h9)u?oK6&`yLx&$aaL>II zZay?iCF*#hn8wv2mx!J&SucAZI&zQ(M@O#}dJ@8PeJE-780p2wc9$d?`xS1_+|1|Cm~E;wN1d!g6S6&x*Qd=ZKVgxD)r%N-+i0T2j?ij*g~ssotbM zoTq48u|AD*j+)-M!Kd$X@)%4%O)m>hcrrB3q>|ILw@AaTP2XRS0lpo!Bh^uq4x^)` zvjwd%2Z(gx7yws8p8%92h88frWip>>s2S)(PM1-pA2Yc~oef-(X)k1mKN$-OzYK>R za!=O=LHe_O$h6qKiQVCSQ}7Pnbaf&9*t4Iy>;f74gCPRbVRZC#<+}$G`2cA*UQ!Du zU6T2pQ*XTX)z@BMsc*kH;&FQGU=us!eda+Zv!q#5VXYxtgDpmFN^1jfdR;YBbxuh~ zx2ezfUu3W4j+!LBilB70F(r$I%t$;i>XF2W_!yi%2YS*4i6foIGyGnemmV$`j2Rn+T2&Xd1rOA(6$fgsHkDu(K3a z^mqdenyLeJ`1vKKE9-^tFgq(uwxM=GU?*Xjlo8jdSu1x4Mk5eS4QY}Y<OiH$ zp#+dl_jW8s@i@(>&UTMx=#pBB#~DM+M8QxvE1pkcwNJwT3KiuGjK4w-#71MGXm?-k z*<0slXA41|VO=U*)vHtmg)yqBsN6anf(X<>^%`!OZ_-&4P6ptF(kTHBvEtn=Br)u& zlDoGm?|m8=qJ!y})BnY<*T#=Ono=-X#-ZOF8{8hQJ9i_AEd_UU`) zt?{Ull!xXlHbvdj(!cclKj58_L;d;BKL6RjQrOF{V^04K0Xvuu zsO#eC>AWxA;Jr~Yx*&;*)wz{84vE9mvcYT*9<&>vn~rXqIbhe=Lv*R>RE}!SK%X_hZxv4sn9eZ(0bSXpd13%^Q{sBE z&3PP5Eh$)iDu-)kX{c?UF9aEC*kFuo09!r1KD32*U3)=K2gH}N5IWxo>sv#hcQy-y zV?7_*g8WG!7<%TJwy|3r6{xWhLwXArI+dljKy-{b3vG*S|NAv&fOb8V^w#*;V&~z# zWB%9cFYK*&4QO0#CNFp3@?9uhYWnB?@Qbg04Nm`wxn9!$*XN#p#Z%K+$N;=6>4io| zxZGRGhI{%=)O6|TjHIb6_2pYHf9v(HeDT>6Ryj%xxsU1Z|4S!m&Ye8;*kL&K!G{mE zEph(Rj47hjw*XWnuk6Z#>4y*FmbvHtdmcEFPCRjDxN3MdBx8yVy*=r@2lpO)2s_Qu zL*t~e1KB;j+2N|51nw1oD{teU`DS=8TDq~gg!KEx<@fG(GCI?{=~oKHTiA<8T&5S@ z{thDzzXPG;N$2+PV<+beVYHo}`I+2tNAQ!6r}w0$3t{gvI5pi?8lpQToee!X-I1?P z(}HBatGEHC-LM1FrLGIqE2X2_+{19&*ydULQBANa77e(soko)* z5YwG#=>XG*ibSizQN2~6=`eySzYQWOwWF8GE5|&J)c_QS(@&qCJ^!&o|F$hRJD=ky zq6tDL?1dG=bVObGt)-^JdaXoKO^){QBH`)aan<5Sl5a30<$JVyfS5s^3xLW&f#h@! zrzU&%x73y!2u|;6Z*m7eaHp*Y(_K|+lU{RWuMpB+6C*^DBHp?7csnlTx?*Oezlj=A zyy;i}=B2NG{-yJ;<4sr4%V2#|v=|NsvFS)n2h=<8L&rugmN_c3;PZS{OTM}Fjh8?9 z`IkP0!MuUE7t|3^cYsRK>ONjOWt~(vtd+_Q{jruorK;2CCncy2chwT5&&GqYy4R0f z97brbiebi(EhgAshk9Rb2$H%oT`ty8*bI`+H6o`&!yH*~zJLPNP%wQ=>yYsKB!b1uZeQZ znc$PUu#{7SFz?eqIOr(dH>Nw!3+PxWAKej`4yV6`?L|xuLOXA|0lM#I5nAi2)&8Wz zcE-weGt+W?6ye*=C;R~PhHq*@xJh!Egv~I14)OdS)3$1dO z$^^3p>;8%zw_Ni$rwO(YY~5XT+x$gsuD+C#u^-uYtKK>XO}^u&%sy57Ys4Al-y? zQ9rP*kp@y;q`7P0&xz0%{V-B3KJ=U=+7vr^co}e>MnESZ5l8xRD!feT2U9F0XQePb zZ8l7Wt+s`Q|N6p~ z`PlKTFWp)k>%4aIvHvjUf4%;~-oloAxHYe?@~M3N#oH_|o~Ztv&wcK5fBGl5UtVPa zqgTK3hb)je-F)oA^dG5qlDs?K9Ff`h;O>VWJ2XbrOAp;idqag{kH|m=9`DCcc+9iB$n=8I#dErV=o;X457S-L zi-+kVbn8v(5@Tp$baFh6vZHU5_v1-vA3&vtmT%9WJJxzS`Hm&GO=`7cT#emag^`)C zX=8J?vj}xb=Yn!m)O{HL=p(Lz)TrD;bFFj4?Uq96_E2K|9T@MB-B;7~DE63a$}{pd zv9S?CROrIsK_41jxk&XT1gQ}|6l*|BZvOw?>_dshYlV3$j1t$_6cGd zyRfG}O+n>#T-87)W)&(TNoiMyhx&L|6k@|1L|q_CI>m*Xr3@$<)$7}UO&*F3)XA(7 zkL9tw>_<*7w72(d;!fvP)maK$=(t0+#n*Q>eG$BQmCg^1lgHD*5P3KLgLuk1xRv)WV>r@3QQooQ#&~1HAMWo2-t>@}o zhf<`N!S=2Utj$v;FkE0ABm-!$DR2(@t^gkybpR;!EXOR47TJjE z-8~S^tZj}?7S{T5^B>D)sz;M?JTIi^P!(#tEsY-8Kd&z@-rF7>FH&GI7d^X~JO8oS z5;mwvIFcj?hNqJxuaR7wj6x*Q(3QX_OF9p)zD)sT!v{FOr5H;crSYd+mFUgPx1FwO z4&}U010gyk_EOWu>4bQ@>d|dqIy$=VdASYIL2;vT5w{RpSJZQxw6V?mBah47X0Z9E z0rclTt$NDmvAQ^Gxnp$Q*C%%m(#7RIn!8&ztxOnp-+koZ{BuHZ4K^#pw(AZleOn>- zS8gxaf#j?deOGS0*@{~3N%8{o&l#wDw9ZXs8IXp56$H1<6CSm*o(7IfC4h)c_F z%+60&0qzQMNvDZyTpC-#a)Y9RLmo|Cdm%89G#LCZsrAD2Od6l~NhEj5QisO3gyku; z^QBuTo0vpo49&Y)s?;|IsI}spO(Fo^{4(C{ai^eek$X0svfoBxl{GnFQ9WyB8$>N z$jSGKZg;!|l<*{GI}aTK)Cna&a&nw{pll6~^)|$c2GUzN&p$v%@>A z=e?09jvPGl@V?y-?mcw!i4Kl>;q#u3Tn)!M@0*%lIBGdBqHzU7-mkjR9RsNDsp;Z! z)O1WQUQbeWK?2tg9yxRJiF8qo4tXU+LhsKY@%L98s=ozyzT3qDa$OubyD5Lp;j#AQ zC>_c+UUoozJBizzS<^+{3?6m68AEQ!+gog#@U`cF+h6ML!gFzox+d7(ZRDU`M-bbC zx4ri)Z(p~))w`QAEu9y28`GOn(@n3wxsl|YI%o3{&~=sNM1s1?NI5~z%w)d4hiGdR zhSD=sj`QQEj$fs}=%B(G2f=Vao1#H7L5R2`xvvX`q^=G$KUc@fAkA!w9V6(AvF=Ps z?aa;Y0vl=I&P2hiTwS?(^(wHAg$CwtZRIcmMt=&|%Q4jS`&P+IS11iG^{1W^tv_`E zjXjl0a@IdG9KlMLOr>ZLGY3qOYgfIw$r`K5NYdJ_Fvt1b-saIb-y{sE>B-PBia zS%T9ED;*kIPws-*!F0MqV(bpo_BG)@>FsU7HlWJDu3ECjo3JZKYvQ5&WHFr{K3~w^ zz3Hkc<*JjR*iKxxrJ9enPh2A6MGAE3Qy=-a3`c+WvAzHHcOU;)VU6IB(wagUOXQLd z#;{Znkwcn1I`c@K)ea8KHO+C-0nQp7#gvXGDGH>Ib~mA_Q=`a11QG5M;c>kXj|jv~ z#>>&}=mb`9y|&2Mys|-zO4(EYskmvheuWoLw)P<)3{zfeuXKZ zyTzpO`j&xez_35qMe;l$>UdZv6^6aff#=BJ{1QmKBMtrMJWfYX9}Huhsw4A;$C1Hi zH+`X_$jJ-2(&bApm4bm_38zVv1EF?8 z3kfO@;zO@W5S_BWCm}ZqmjKnMb-b-53^P0t)gRDfif2lt1PXjjCKuW)lv6@=C_BR` zfnZda&c8}L6X$OWgzlwwgESRPOLcT*QhQMhMMU=KPfWh`NL;}$3akO)p=jW}G1Si6 zI7hl8HNElb+1&Y|42g@AQH~}u#b^qvll)dXXQPug2aqSHZLoHA7oKY(rovNJ^Gu!`QZ;g`oZ5fPM4yNnC|LGZ^v{R zjgpRt^i9iAh}~y#hvm}2;d2w#MeCw+alN)OFSIWKUB_ zic4iyiaVlr2L&v^dNvKc&*a!}Dm{KOoysmQ@Qj7$Q%iJ2!r!mKg z(=lUtdWulq>GiFpwuR}bw!LJ$prcc6N+WA3L?yaQHD6d*SSRU)a;IC@mgJgAuWu>1 z@#HhloE%#mTYP``=l_p;0ZyfEulBSm=H=Uh?>mM!U;5nhuL;xr;ptbt@ce)AOfS;c zjnc8a{OEduP{-cUmciF0q|@N&ho-9gh;B(QPvT6MPg;V+`$x8SynqmMb8+m@na2;E z!TGZ9=*Q=2DVMc6$~(5)G0RbF?x-+*52hCiHm`NG9ZL5O4}~SeyMf;>eH1zUp?eQJ ze5mu=u8^pXavYD2a?NH{IMfaJpDsvN}nTzM78f#pH9;bSdcq zcI+-t`@?6hogWVCD@#Wn+h+oPo~PvQ>nQy_nO@!jSB2(Ii1w#Ehz6RC&5h7aPWQ3e z2XR|%CoTGMelr^J-H3IDvi(a`J?ob)& zspI@$C4aJvsH!Z+kvbe3{SbIRS=6|rA;o@rtpK3>6wz*JqZ=kB1Yf$G=_aNlVG4`t zI1kIrN{^pj#rXwkG@9v4&Q;H43Y*=9ctbWZJ{%V9`r0RSeP=jviF2vJCTBr6g(M&8;VZLC;%zOm&)YKwLlc5Nw zV~rlTK8jCzLZ+6c_Wp^rk3I3k6CZ#4cgLO>f8vSU+VEQY081GzMR~GKgRoS8ps8P7 zF>C8wc6y$yMywDq#O^*BE;#bQe9aL8-i2VGjuxLm3RWA+r7(Isril6$V!#J@bUZWh@rPqU#b)m95wh~;Pi7R`ek}~{Uv$RKXv-q%V^V= zpKc%MDi=%TE)FX&@HBLd6ayr=2+*Nw4b45VNTUAK8!zwu>Pv5|wASYb%=Lm6Q!g8O zxK0OR{6OkDTcM0vIlFQ?DXpZ7khp>#f!sFj!3f|M5*neOMMo89Ftv~+`R zbDxXUHK&VX^U8$3*yDN4>T0zA>F2-x>A(7|um9CIp7-v>T0y-C9Ws~1z5~{|8_R9* zm-_Q}+ecQ&KI_^!|a(~3FuJ+^n=yJvQ ztnMwZ(7NF}=5=i&d-|6Yp#FdShB_RfrhoW1e&bP)-GRE^2F0h}siuq2L2lQ32vC=n zUKvE-2I_XJkrBBz!sue4uEs|ox6kMTbb!1^&<@a(z>g2cI+vR1MfIbAwl)x_%kV;W zB809^MkbTGwBAN>D8~bs;OUN3zzBm>&O;BUDHzSk$iix(5ZlHS-iVzMK&M!h5%s9tQByp? z%+SfD_2Gqi3X@XGSsdCT@>~N*&f4ts1}#VBPG=?lN6hO}gf!A#bYc3|$serGxXz@y z3;uVS9>MerGNsdZRCio@;TD?uI<1XB_l34=C-JVgEx!Ls@Xt?E?`aRvoU+d$_4@1I z`#Yb+E4QyQ^{rR_@Z~o(!H;gP{Ljxn|B{F4-$P=5RXHzE`sGp1dN)tj4?g+&O9<(v zraRAziRsV1DpCDZE5`-z=^6e^8^hf5oo60D^Z3!d`wkrGTpY@!hePT``ql#<@9CrJ zLb?YSe&B(7+J;YF3snux?re>;zd1x0%wZZJJ#@75UP(^(#dI+Jp@$wmIyRmwazLU3A^Xl!_2~OFz@$H$mhMP= z2hut%eH+c;VS{9GF;@d(MmA;aZ3Hd|_b%R~EjC8?S5@v}tK8;lfj^Jyt7%m1z>BcEfOiR9o)|MmTD;-zhX`^(Inh?gC!MgGlSSd`&9~Fbu(f(RNIKA#E zCXGU#;-GLxxd2xJi@Ktw-w+z1r^~o-rQ<5xk3w&h&gdo%o7J25aU5Zhk;j}(-4VKx z`%}jt_hUDgH#So;AmFc*2#|?)gUM%45QuWNtFN0(3mrvI26MCLbMaA<=q8iI?o~%? z=Td!Dgj8orbMe~1Y`SN7zJsG=`CpRZ+L1t09mZ#%hBFCz8IV~^v?S{4M|@={1;fRf z$>Ql;VW}Xwp0Eu#9ah2?(@qrQ+3N!&?Ok8HeDTu6iKZs<$TJr=FBVQ8Iy!!_M6L&E z>IzmrAx@uYzdjIXQd?HS1Bp8vA^tE=L;A@{*=q>G9_@~@eYCrYJ9omKmh&x)}W|V}n$Rg6Q>} zW!ayIAfjJ+o%=1)>MCD1alHjZXZ2v9SXLjSaBX;mOI_{Axu*P}>P8`Sf?oPLMuQ_q zEbe7cJH$Z6d6znYIxqCa5n7WDYKk1gzvGIVKHvdlJ~b!Diet{9-s>I0!=o4`=x8!n_0LICN+z z#v7<KD06z3MznN$?XBZB7-VqM6Ean|#=gR9 zyD*(K8sgn^WW038HlIyb?=OuH<&g6!S;kz$0br(fPNz$XlGEj(uM0UxlX+hh1vy&1 zRw!g*RlI^VvceEV6pizIsHBy@21X}m(jEy&uW3?zJ(S+ng__P;jR1cFJ-9J6$cL7=Gi?56W+Z>1EsY;`Jl- zKDN=)O-*-Iq>{=#`mPwx0d5RgRi8!;4OEa^v3B6(`etw-c!YyVcI+c`cQd@U`FZaHZo8b z%ts8Y;qa*f{&VDaI)n?m8G5rj-mp$t3 z!vS9h?v=MhY5gNqop);b?%nr4@Sy|qL!E75QbX~KY~QQ5=lo;H>HBCzdWeuAveSDB zPwy!dtjE#&^IK()($vTXB3|xsX^i4@qjWQ>`!6#1MTluv{fa5 zch~BML~5+*t%)8$92kewDI)dKULaHo?BGP#^N8k)v3^`ETsrWO-(0y$ays!WD}=aU zze=7A^`xt-jrS4BXx?ID0yfn~(Gqa>(rjyA&JxvFeNg>@;n{S@5-v4&4hau?ysNxM8&Dk5XVoLL`_jd=rza*Z%iD4` zQzCWmBme!!%4L#Y)-L8QHNokI=@&0GHMw*_Se-tcT^BR5R^T~LX85-?=Iz?riT;Um6X&`b z0?6nzH_8vXPNdYkHj@WLEkE}=^U5bqwbrlDXjGJ*9}HmPIaiC3rxsH>e%+=S{JI)S>inI7{H!<7)lvR)p2^5k|U#M!9cArXH5uVfe$7ZGlH7#JTHFtQJK;`EnT+sO7W-%)hZViVB6p= zGZc4qq&BJbqIX>xDkM&%3$tJU?XLssSk)b=1Mc5=-YDJkw`}X_cPQq!&%)(SFLx8- z@(PnX(6)KNT8g=?m7;E!+xh%+wuK{b@w5%vP=mL?yMf0m1B?8Pd_vc)O;>Kb1=7@? z|A%ip{|{gPtg_P|CF+IY(MSKy8g76903ZNKL_t)?U#F{-Rgp?i*B8=l-gHsAkvh&7 zPbC*jJ560k&6J?q-DXMK_7 zMQS?uosmv0p9*72N3Sgr^isgoE*lIqjwvBMRYtN0(-i?JgSZSWg~EIrWujQw+b9)< zw%9Z`RZzwYYIr#lU|I(-(+@NhRqLs`(W0@Z$3sdRrr%+mpDph|W%o;|sT#l@|s~FKjKe zVSM=|FukC=$|XLztEZlJMPl!}4j!T#s=x94=l=9HdDF3`E0NK4JtFhvy7B&Geaqmv zn}72Ie>n34U4HPtpE>i=b5HWozxw{kyKh0B@}}pL=?}U#8WL@9eu#?!G ziY___f3?EVxU-rFjeRlO(Xqx3nLTjU0uQYXq;1xz>CWt82(HmbwV4hE>@JLq(j|^p z7HKnYt@h)Vo2;+N?MKv;)><3cJ>2u&@iOfE9d|5#7n8qYucsdwunSX(hGQ2RvAhVz z0d#>nZWl2Km|hcaim_^vtJVjKT~aVR8g6!6KvGw|=io}+AO;BB)g8kZiE~z;7~^!j z7kww9;1jkAm>mo%mr(`-Yip?K!KfOjGpG=h@T7U*GU-`gA(d6G=&sZ>b4)ji77y*OHM~7gICHUge4dbaL+q`bx!WLO5ve zULG2*(*L3^2%Yg#d5wmZ#Jm9MqXU;NuTj%@@lxN}%tUalaPj=1Gs5)J8Y$`*&kl4? ztgUrTTw1$0L5CxWo`}mdhbpZ#bkpdvp54*Mr#jk1chT-xyRx^d+vB9dfY)?9YRKS3 zVT9MbNHlsLvY%|Blu+IWd=q6}XVlYjDdvJ+YNAzrv^C|}2%|Js7|JvWEhl1djzC7d z>7@qijM|mGa^dxtzWUlrub)5v;^oUm_oE}S3z)3hwor-pg#J!X*Q3}AZ8JLcE zQ&02|r-_EIbinv^;f4{8Xe=C^7p6$iqFGgXs-$$wnF19<W7wOPeR=3g>gta(cES9}!h!Dd&_%96|@T1?$eYBGQi4)Ku}n%>s2s)RESt zsv{)zaH5BXd+FB~QC!|Y&zw6+Xa=_azJ0$gOPqbht&+9h95=Y)f-xUgX+ej$adfi8`zJtb%-L;NkC&$}@3b|{icwdmyWlsN% z5C0aN{+l2Cj3=jy(VaWpK;3(zd`ve~$7$XOXPfcGRBs92P6QW~Zx06PUJi_HjmJe7 z4aq9JGO5B)Tjyg({@@SxK6B=oGiN$GPkx-(71U&+TF7bXfy;~8Y1}VV?Zem@UqEbF zUFj}f{U|(+gpE5yLb;slfV^TG!FQQm0CqPaWql(AcuPo!x~B+kEX)rLjpJXTjVNAo zmXXg`n3;jv3)4mLTqgAbB%Vf7&rXfEtryZHt1Py)Eh;u$jzu;C(`k5=o*CYnpC4bE zUt)9kd8q9S-9nMh*E4$Ji0hu;h|sD2~I)t!Nzx5>vdNU z`c{4ju%OaIAVEFp8EICka?divfy2aX(VJB{ll{B}-lB>qs_k;5qE z$|--~14nYFDREwunC=hocu#X;Txl@-cJDjd`H``uA{4>P*V~a!psI@u{EdIcTd=xt z6l=P9(}_(-O(z@@NcTbAJTJoZ1E!^8Mn_0Ld~|H75Ux_lz@1qB^FE;+zXx9%6_>_4 z5a`=;tB=9j%6^2!0%NT}Rp;BuG7gx3i$QqJrjE^>H(daK$6&i-nO1$&Q`5IMb5s7F z?5@Zp%h28?JNuQ2oxEUdviE=e0Dmxeney@c_m<4i|PKYsisB0al3b@S@Y)zzEJM(IQ` z`trFy;oV-ikg6JuCaDo$1!Ab#h($AK)bzN4(%E}A|7p|>w$z@Uoz2AnS+)q7nyzC9 zMS<8be0sPT9xlsG#s*>h)92tCEH1UUuIcef{vQ^KK8QyLA%SA1HkFtRolbWQ<$N`r z{{{R98QH%}B{d)#7(G$C^z_BcYZFZ;x;FdPE*75s$e)d)5aaM>X053m`I@Rs#$b9s z#fxA%FI88mFV2C{evX--Edor4Vj-`)iV`~BQ-Yll^kNQo9iHHN0o5XP(0)`Np>B2x?)IOXm>}PMUwrXXsOf_(15(pLYUFgRIb8urx&=@ljMb2}iH8xrq$d#>9C?C-nE&NFSHW}! z{OJSdx+c(YrA~9f?v0m-HF?SGcDRGSt_wF(%w?isoyIHu5OypcKy}x>yE+=GQ*=$` z00lP;5%S5=(Hg4)?I@FKNwUicYF#g1I(xQzpk4=ft*tk&yunfAl@U(xbksqsmUvk# zPN(V;_2|+Zhq5;~Um-HJ3QgyjN8vfdvW-)kajXN1hIC(*>osaTA_^zPiphH8`H zq1jL}RwG2`R0)Gfo3xi&stwFx4r=p17$>7frOX@;$>q|UPjZM6uOdGI)eH5!Hpl@O z|8pGvg6q6a+(j9Y93=3VIsoK&2;&hiG!lO;#k1o7P>l4YVs6~~%$6FUR&KxcYrkfW z3)xl=`6tX(pUs(k)z>_G4=E8JaXXv z-+y5Do`ZzU&8N$u#srDvDYCK}L!>GS%q54beiR(HpGasmWNm=(s#E=0McpUTJCIEe zBM6;#0XSU%bOzJX316Q|&#Gf+dX@mh+*aEn9YeG98A?+XIy^PMgxv*aOJQiHFqTfy z@)SIunjLSW@lm>M49Ckjj6RP81saF%)43UCrb|Pgo|+$9DDY$m^-5ub8Cn?olRt)bSzrHRzJ0{H1o`vg|;QOoR-agh9eJ5F39GF z=>YoJB2>S1ZDE~I7{HxrJnNm$Tw7{;!vA{xMZUEl!BsktzO|UHAVvn4_41wPpZ`Ct zy^-W}BGaX&|3vGN(ZZ~x@mfA^nt;ri`w{~eeA{O!O0-@g6r7wJR#>eGXR z|KzWh_@Fs?z7tG;{OG=WAKKd{b9xG*e#?huP59$JrsGY2EIXYW8XHnLdSw6@ns?2r zh!oe$W1XF2Pvojd7U07=QV74zzAHO;#|f~ed3f)hdmnU|z8gvxr$gzwvBBi@J$v@; zV-ppQKJ@To9~n;<^EyP}KtZE_qT!vPv$Dkwh}|(M!Zi*C$c@Rp8J0WoTkB2lX5O|i za5rdn=q#8vy!J*ObUy;Gf7F}yw{Uy3t=WNXU|SfwYnQg6O=#p3xgM5z{n$nG76oZf zO$QL{jMcXdcg(U5{QgxAYTj{RI}QFjrV`ByH!s|56{U;DrKYzeTdaB%Exigf%3J-Y zp?aR|I&w%fgu^R!gt4H36SuL_qz*mxlLLsN;zle1;&iGN1?ka=ey)8@!BT7#hUhBL zC8j!K+Ayc-fn;hLN9xR*j+TC$8q$>&957_PTy0%#`ut?#v_=;|<9eArUENE(I2{{+!u@yB1ExP0m96ST(cYg!vF&!VQ2p{^wLwZg^rCKY9N5%w|>9q4XC<|M^37@Qz| zr9Fn%obHpD6RP6_-7yYlI6gqpM~pRlML0-WM*{)dyw+riz?yL#UQO-~6|p%73*}5y zwTNJPkfSIxVB}{oJs71+lQ11~hdeJ0DtK*=#{wh~${#Y(Umcph@*OKx}YF7p$ zBlt}QMoDWyppJw~rL)&hT*qZ}`9C4057f6(-S9^^aISW|ar(-YH--__$pjUpSJTUs z7D?fn1RuoZch}UaCHAvB+a2Yew<=VQN4Ko2(PPTZm*8hiBo_v)-oxp9^?iKKjTbzxII- z{J($g1Nbg}|1-)=w*kkCd0u39sW@IL5N^(NN92y*D{}c=F2j|>~)HSjnO==3T*8G=jmCc$st_6nP+hbGDZ41ZbhTcAZ zdo#MxJv`}rCynpeeCOhw)5hx0KmS*l(?9d*hkr|Q`lFA6=^QFKPIq#;INf`rg6k*G z96fUQ$dSEAJI5A>3e$>C2h*)~RLzVenLAKd?;-pvG!nH$@+zVl@vb9_V_A{mMaCEG zFGlO&x{_j8Nf0BbgwLEuo1ZTXN&g-ipHCNXw2Tko3(u_&Pc4n(bfHG15lc*ZiD(zP z7j@#1Sy~*UpXAW|IL(P@E=1zX!dTn<6n+=VN~eg8r0NvBMqa1~bf#Z>{_aCb3iF7P=$P~1_5z_gt;>Qmket6&ikGsEtZtFhJ zd{JWP1b3{90 zP3u@fh7xP7pn*QPdYO)vZ7Cg|Hlfw!#8Hz~NAmKAY+t%@?d7^z>)KJ>$<(z@R&=Vl zN$>CZ?+t$F!*P-(jk`et8+&hTd=mWqpZ&bgyWzT<@r;cWvZ&|??u0Tb`0$q|WWhza zi58?QYPx~+OReds>DO(>D9V5 zq^lpxJ0j{ekZj0Uybcy?wa%|1r;D)-XN$FqK`(1TUCS*Wi`kG>_K&$IYpwQR@5r9x zp;!-syVuEF(Hyrb4ls((sd)L`UXQD8^})+99nZ^|+7n&n4Y;~N^`e+g-DEuA!*S~i zV1iKu3m+GG= ztMMT#NGD#J>LC4f&*b&!sW)UIN-QNDPjW>_DqiTXfdCYj6z`ID-~!Gh<7pC0wx>2Xn? z+3AeU>o`vYZ8*ty5p+l-`WOs}U_I4+e zXfMyL*HxxGMm+&qT#mAn8vG??v<^Z|_qKtCI^s|Vu32dyJ>(LeNx%Bmx4*w*{)KP8 z^v6#*m13yx_fcs)~gBrXe$QPfEeQrRbfE+__~U8uuE_B%baRdV+8 zL5<_}W^#@7F&M(`qRyk#I5#%_N#lvzk6+mH+S_mE-!ANVZO{A}0#8VliSU+l44zC! zx=uFFyS;d@o8hNB@S|L1gD>)DN?ftr zp2BEpB;qeEIhz=bGU(#1Qypo{&g^waY2{g>sD4iVVE4_ z;usGPQU|eWTpfH!G1h?R0)0@QF+ds3Y&$%Io?Xl`hHg}tw^Z2boImWb}pKJutKl0G6iT_wA?UT(eP^Ol@mTD!VfBWnE_C57CLUz&jJ0|8u zVmf_FUw-G{fA2i>@(+LbPyh7#KmF4W|A`rqxtT7W6Q}<_ufN&%D+o%r{#w?Y8$fU* zhsJ4g)O7uI8%GGFb$7jsB}I9=2~u3Zbh;ZMUXM5e?rb)wfA}ll%lC2jHC^HDTaeRn zy=>)=BkMJ;IrrS4=OKnvRfeJTKDIX+kP<`t>(SZ@+2V zP&%cjB{Ax~-_I|)HCA+EY+%7U3q|T0F6hjj%;R47q^xIg z`HS#gmRyeMsMQZOqNa<{hY{07>M)Q_`acebF$=1z)u+$ZhQk7=8U$cz?1)QUq)sn) zI$}aIz8*h8G5!!lYrGXOAU{?pUeDNEs&1m+Uq>o5B&yOyNq;4{*V&?MFe{%sS~_7b zcj0(3?sRHMF{dA<#?=tI1?l!IxDKR$;lM}mNA6vUK%&-xoo*^bA*3-CkWzE$BHP1I z^hAb8#+YBnfQV!S*m^=nO{Zh$!KKl?*<><7Rbfbfb6pL-GHM>3H6@{%Z+Kk>)3r#t zFENu8Q=)m7h2qtYm@qwL{uV4b-OM6#;^g<&>?M}a>WbOd*GX5=xzwJml#rsP!|4g+ z^d4H8%39qq)>((5T1IRO4UAy=&b~-VoRLR)fR^z!hSEv%Mi1?vmnLQn{1E>By*OKV z0eQ0Au7cced@ppt=@Oik@hbBc)O6s7iA(Uc)O3zvlu->JHJzlFDheoh56<>*-|%n; zx#?r-LOS?b``>))m7mU!9eUt}2jKMna+mR@yCkODYC16Oi#v}{ln^f^H62bbA4t9Z zzuo`+@4tqej_akNj|7`OgXwh&WEbG`L@6M(rnrXybva&mQ9Y_{B(R0RczZ1*?; zacn4c+)cG?iR>=G`+Rn8&^OGz(m=@V^^@?T#-qaY{)U0Z+fUpMr{6wrAieqfBJ~R% ztTMRpAz46yEEW!saF`#5lIlCbcT{v2NsLs<@`{BRV)|>cv8A(#*x9{gr{E@`exatv zhY!4(uA_r4jUtBTmNO>5gPM{K3Rs)1I`Z)6cOFBZrr|H5S7<@5MU9;DYaL-b?Uu>$Sy+Y+HoW35*fp7!sIyca6 zZp}4osWr1wCn`LDc0ZIZAIw*DDtgm(Yq;C|t}~!pq%I=2eu{i<5xLG0(ao=g>ypTg zunudl5z(cz7ctz-S=U9@)>U(9K)cA^=CXK2Yi!et+2~!*9yQw>LV!u&BbTtWDb279pRozn5EdXC3b^B@&%*|EcoNZ}g3Z^>}h2~^5 zKpUX^2teMlX%p(IL(kE2bptDMQK4Ie2fB8z#7P( z$+IM!#RRiFbga3M%oE)Rg@=iB(ZFC?+I>#L0T_Q4vX3Tkx+9m9Iy2Os4|x^RPU<77 zIztovP;4rbI@PG;ywBzr7e03sHT~SV zi!Y&=3(+6{tG{~e)u&L?|4=Zm0#YNUzhqSQi?6@=`kODEJ0v(?JryY(zsp66R9}Cy zvzj=VU-`t-s;_TrmYiO>>H3XB1qHnrb?wS`%|G?-)VMHx!zM8OhE3^!!|f%E5pFiG zk#5Ee6`J0~joWVCg5!OBh{6U{k#=8G6^?d0Oh2J3@BTe4)nn$A(rj3;&$xJ}+UwxOQ_-p=GIK3C_d{5gH)pSd*772sSvW1&jo6=dR#9)Kd zt7nqVIjvuOi$QMwr(H5>w@e1V(bFZj>%NN93ZZK&YfFgRYyy%O*GkscBPo)))PJT+ zK;2rn?)*JiUW_?LH!8ksCmtf_<-nP$#>TjX=>l~lr~~KpRV)L+1nm5ndeRITcd{tB zI$YF*lCwwOBCP6z*#hBr001BWNkl)!yg36+JRD@BlueqB6zW?0j*S+UQ*JF6s-xaD}0WrQfjo?YWQ%WJvUOYlsDP)2e_f(>2Oagri~vOx&i z{0Q)6zG0zV0}RPQ27ErEI2WduQq=S^Ke;%jgcQ$*yy+cy)6Xb3{nfX3%pH2^&Bws> z-Tj!IU`|o`7~XUr3GKpZF*<_=J|K-GLX^j)roZx@8G)`*mm|J3| zV^HRFrh$RoX5i7Q0TG~HLQ;JuJ4k?xNm~ckLp6-2+XnHwII#~YjD{>vZz)Fy>~8~o1IhG)Hyttk zhHHQKx;NhVJZ|Z=<)fBZ4qHo2H`2M`>lH@VwIZjRH8zIp!k#sonA_UmZgaZfZ=I=D z)VR`#K*94aPUkkZN1b(I^viT}qnNK*DrmRWb7qC)64UJqu8PJ*`COP;&8(i7wXa!o z<_f@Vv$$Dn_`5h~udtYW#r(2v>D74Mp!%~vGTG_4Uha76j!%6ad;0HxOa%f(d%9&# zx8Epr^0d_SqNq;Z3yp_X)bt{y|Ex<|7Ik$adq;E42`{*f#BF>i?Umcr9c7CWE-IS{ znae}4CeJ)cYtPE(w{5E&A0lqifjlnsuI=K67-C@b45|tC79*Ae??j$YnF`cUh&9@p za%y91=K_}s^{M2`z_}_V6*DJ=-Lq21!};cs5oB~k>H;!-igH$RU|3rqF)^K%Vvc|w z&fk|iU&t>KO_Q4)Y9C2X<7@}ob9~$9Aa@WScYAc2qXq2?LwH)I*%zHmqx41M?h0vH zXz<9e@9Eg`Bwb61jLAl)rkB$TLz9y+R^&wK93$X49uA$R9g-!UQ*?@lf4dqQ5eYeY zs<|17A2~k%Zy+~aAulH9<*IRvPeSQf%86aP_}In2x_I%Gr=H#S)ToTBQ9If2|$ZPsP^KHG(jk+czs-ta-vKPif7vtIs0CT)MLO+N-_M zfdi)-VR1|?NWcM3B6S%n&@vtIAa$d0bvBai1>*+?@{LRgI-uXupN61xggfLqx(UVT z!P5`rqX8B!atx0(H%dBm#lQu^t;Z0>8R<) zACv`#$PUU!C8vMEa;F35B6Xc?c2|d^h@ZR>)K2~&>K$GzxCr5Hlu@bxtw_fD?y5v` zCYjO4x4H|{hx`q6U#fv1BhDU7)1%aUXXx~+VM#ZwS20FIv-o2C4N~A8rtTCORk)5p z!sRWk52R+Y%V96WY1qjGzpgfEU|GXNf9pYP@&{=~y41%D*!Ru<@W1@t19M|w`dnfT zRO`XVj-h3AF0wRQ(?5&?U(-pq(AG{`4w;vzI_M7)ea?u2N7~a{Qr0FlU8ZH)OqRIL z3e*|@L=c0Weotwj;Y5mlA8w*R0QkKae^6-s^#EqI_N_P&-Z&@7=HmG|*{G(b71bZ} zMlUw`QRohnNy>QBUwPqyZ$5VD;m402CFh*t76Hbn8M`cW2LI#z(^^67m4bn0K1#61q@KI zNWtx;K8MrvVj?EKG;V(z=sWHMLT>vd(qVoOMlTZg5+Rnd}R*&@3>^zHC9by@hpU z%_7bIk^S>W%rU=iLQjA6SyM#%*;{YjhdrI}^m{*no^B?&UViJp@$T4fl%aI7x_AQKna^rQ^ZXjr` zrE>csCh$CtagtYZq?ypiabYWDT$rqqkEO~XLppFvg|^gnnb0#+ZIqD841-AqCI{h- zll`G;3Bofm}aOc4+j}J{E-xC;=9Z)xzZXkWt@}ia2^yW#UbQQVeS9Pg>)YbLg^wzt#w%m06bz5_>)D$He zK!YVbUv|Is)sA~A@uqLtU`#LD6PAW<8&Os^*Uj5L$EcQ0q}#W)rweKJj1Cj7%4Ujf zDONWA1!nkHm6le%;!OwAIozoVQj9OC>DOMr>86`o+V2UM(g9)Jb6I!g7r5)6d6P@n z65zIeZ1lEeW<#-;Yh{Qim7L5}e75#eD}s9Q@{(t~?&@Wj{#&bR zy4oAL8yi7WBJ?o40O}2a;b5EsHaeulgIt5uk=mKMQIwGgh3N*>NwUMKExJLyh7Qgy zE%miR4X~Sof=dK-guUKgr?U>V4@&Q;>uK#D9rbHp>3XKZW)nF2~+l#9O^r82WMwizF zvV3J{)f<>TM35F_sH(`CK9pWxjWav5X9qR}H~GOt+~}ABPdnZa?&GslU;4(D9{A=1OQwR9 zl=1|rj0mee2jT22A(cT&3lUQ(uVw0?D?PT1?qQq@qZ!=$#yUg?Nusz}r2K7n$fSbo zqS-3$p-~sST;A1~Duj0=N*y(k(VksU_*tqE$&*x8WKRjPCM9IVlz1zmWelz8#?*tw zW-q0#K7YsDp$d8zMG%%#Z{tmWJ4(Ui#*t(Sd&TpTbD4N&a>}y+ftSmNGP; z$Bt@9yMn|0bL6JK_5J?~b2^PkQOtS9eRaEgcN3ces&@dpu8zSD+8YraLt+q>xMqiD zx6}%N=^YiG0cq{Jb@@Qu?us&il}MY2I`Wiy1_ucQ0Mp@j55aK5GfDFDSgF&JY%f&-zWPXnu628y9=W#U zB&SB013%81vx(_%ba$TR)xurQ@e9wOGv2LgoB+7XtB8vom$#=C>lQEZUJic@1L{f{ zk_ZlBb54ndj>j!fVdSJO#rA{R;Qv22L2#~m(4ITU$RM9wm(-HTa_CQ3+@ z)PC~k$5^b223CwuI2OPMj!P;@yG(q#G<7(AqPyR}*Xi%~Q~he}SUNyN$py6;WBius zv0&@Lg+tDUkiSGB?ivK(CgNpf^n>%?V}BD%z2L|pYWm0T{rHVHT=xbkyvH_feEv(H z`qXDWW4T_$=#aXp>s&+U7KyJc&{iu~E9Pnu$N}$_Sp(u9-U^8SOVpR&N960SnZP2PQyg(IC)mGR`4%F}gX)+QP}4X~w=n{{W?;2i&!pgg3l{ zXk`!B4yJciWy0Z%I}nI9w;bD2xwv(Fv2x3{jmNIvSlQm3BM$v6wW7(9?bltm>H3y5 z2;SwTH)z5gnoN3esRz2qYUF{Dv5pDmbRZBSOA&t0PDc^aQS3o>(|eR;^u**;Dvg_* z{iefo5XHzcnN^lc(hWr~r-v3QThQ)N)hQOG0yGB-Io_5$BK-O0 z_95WCc@aG4XR&>JF@GMZoOLqD(0^#_^G#HQ(mDx4OyYb#N5v>IIBpl*H2E~zdJY$U zdy)YKcAik8eQ1(>&*o6?rKGboqy$GGolWzLi0I8jEtSp7%OgK%Z*E@5pD#>LlIobw z-($Z|@8=6}ln8@0ag2ZU@_J6c__{bXA=7cV~c{Qjr*y`_FfEHB0}!t5B>Z4ftv zF5`=>r>}+e*I$2`|8~Fnm&-6V;Q`^r@$r_8H{8&|o1P$*#r)sC;@x-Ehej%!!0%09 z`i(aX5wZ?Sh{~=1_|}b>M@~#ui=8 z64MQ*OFF;y+8Y)3V%#npZrY-wTg`>6+cX(n8FH9o`@i&^|EveMo;Ag?A6xTNKVHEQ&y2ZQ$@(j?Z*N2fksR($C(bCInj6+OgA{L z^N)Pwp~Hu7W04g010NBnqpQ0cgT79{jz4uBega4UBTOwW7m3$rF{e+kxGSSWs<>YG z%$EY4MjDpkrne_X9C>yo6-(hmh*x(t1iH%6Mlt^K#1Z|;zw7G4DC5QUTf?}7lFdjq z;w|kCB$l%~P}AjA9UMC;VSS0lq=wV8>O@K~ zA23bcOF|+m3GPD4C6Z^Hq^}H51cqH|HyJ^=r82OWSF{2_RKeVc={TTyj)XK~Q12m# zkJj`VZ`=_}xf3aGoa7eV61X>d{58fO;dA%MK0!$V;xzz@%Id_sgqYq(Zi>%WGKzT| za4RdDpD(0kH)#+AExKRQqL`LM9pQT0hXBhn^GL1(77m#(5Z7{kX#Qo24!yj!@ah4jYPIwvDW3K~MY z@IYZfqFk7oOObt?kCu+8xcza5r>(*)r8yVcd!&b#k8B@(U>XA0OMDKWo6N{km41?% z$w!5{>j<14?4)v|CbG9R7Tc3s@>lRq`2s#Dy-c3~IpSgWh{;{&FHkg14h=&JTDNk^ zxKKfgfo?oiN*LvY?L|Ht>b6}G0&^Ha>qS&$G#_ia{}Ss+;tMVu%rAUeu+6YjhXVzl zTk+0mWTFyX``bX6uI@&bn0~|WUPlYNEnBwTzwIyX|I(-Sq4L_OE-iiKWM+ihD@$0n z%IP+mo8a>`sV-)71M1BE?8#{9pt|lxlL2&_(!p(u(Cr!PD(5n|6elB|Be7d*Idm;% zH`g?0W`Jx-=|H%_cmVt>qHqK20&uap2wdl8Mpx{K>uVrg)c!|?=e3$y!|1v&zeY?q z()t>9fAo<@pZ&U#)9<+BXX*3GO>wClFAmbs0TohN$VF$;?HG)DqY0FCcV;?~TO8kZtZ95C94ibB zjaP1YzNu+@d(w3}JVN&L*7l+HrZff-*gcvERaFH@a8V9SEx$Mm$#98LU7AQ_rlx5O z>YgH1Jrp8zUG5qZVJ1_^+)0&+=5zT}ZQCUFm+3?@9Bpov^(9$AuE+MBY+e|b!6lh) zU&Jl1=$B;sViF&FVR7sEn{O3$}9 zg)zJ&b5kV5qqpahGx?kxFfzcf|8R0>f#yWH#4;#9H9g)A|D)tjwxO=8;FWfzaQZ1_ zvrnFyZEq%BW)>&#Y+*S(GK7V_d08rbezDnppWeq8d^PeGpEZ2Aow(zF%5+N11NttoQ) zhRXKO<)*TX<+5#wa26vw(&5!^^xl@E_m>XcbUkvqIvlB7^xErgBtHFE<=ySry*SvE z4G~Fg?&zwI@4emC&%f1LFlC;=L8#jno&~S=B#M3a$%b_ceRVDr7es5$zG@b5&HAwc zd*#AHW!*+MTQfo2)(^L|S1GFzN;hY>7$oObJGF z-PD}cJj)`e7cbYWx@>kmrgKjpD1P5xQ-7H5K-7M=^l>z3@JDqa5O)Lr_I`c zuSBtKOrVu<%t{NFrY_=jLWIK;oisy2h7MFW#EB3YLs0K^RY*%m9Y(I_2f?0jc1}T9 z9e=gU>sIj_YI=ofLwXn8jc7m`m+j^FnJU$gg6WuEZj7%-R=|}j@op9s~ZD16^kke9qZvVHy5d^h$UjV z^bU8RzPwA4C1L4wPUAtt=>bPqz@eyemmJ4D{frAt_ji>iW+sK{97_Y6bT?))_7|N2 zZo||yVn3&y*yLOasHM89wF?Qzs}+w>xfd4C_xhG<9HJ6Ew=1-RUV zUYH&H7+*Sdj`}p&aLKU`+DG9#w<#SUr}r!79C@_KEg{a_385<`ro0yyjz1WuCFn4r zmP=zNcRvWI!|7-4qKobAU%2qo*S`NY{iuKX+S}jHUm!sJ%wQXq^S&O2mlpcEk^RK! z^?_2SN9|F8R-PV((5|yfXIVv(?kOWdU0=k8(m8_5_==-DCL~B7XO5LHlB(e-5l64a zBD5Rj!5B)nNL{^BA$1;!YGe811n<^I;7XIQp zXuMB9wU0apbs#EYy5V!3X~C*EzKZGAhSn;3y}h-$ux>B%zS3k&=*1OM)#XwzPV&1j z>FiQK*K(-ZK3kdjgFpE4b1ajNE)5+#7kfWq3Fpjf#uC@1ov)SCxhf17sT<{7*Xa@U^G1{J<|BnuSs^;VSkq}=%5$RsC}#KOyrLo( zn!`zoUz?jxEzge3GHA&EBVyvy!>Y8 z&(DXy;4LWY>B=^5ZP^CtHjU(xDL*3;4o{E{tK zZs(<4>CKxrT)%m|y*Z};zXT=4+-UE=G^X>A-R(E23#nW$*E3{5Ouz2h>nf8GZ;1LM zjtt`?u%5y%eP=7r=RMA><4x?Mk+SYxS`&sHXlhky?bg;-F8%!6v@^BolOQ{dO zo@l7E#dOFDIs+;=`Y+=PVj-e>1Y`OHO^^`eak_U8`|3ai{K&l>5PA)k7x_mJ`?grBK>kpGwy`E5WXQvHL59bMk>A`jhnwM2R$DP^bf<^8+Rj(vqi5X7=QAsj6x+%h-`Q@pABZ8M|P53F471p*F9VhwCgW8CCvveResO47Zsg6rRl9 z(9~Jn#Rx_S_?%RRGg02(N@eEU=oo7Hp@V3@v>+9xr!nx*iy zbyuXP4qo>U*F|Rb#7F~)k;zx#B3&I%N<|s%Zlt6$VF`uPBWK}zJ){b+CmW_RF~O@F z^bq6H);3iVIZIL_!F>$BI{ka0MKjpoeZ%wO=Qaqh7+*SRTuH|sIkzFVj`=;We47%| z`J)e#89-A)~-!d^51)eXDn zM$3Awh;$_NjzQg*v4Ts_XU@$@u6bp?R1EI6Ih|V)2O}XJO_&^Ymwf9$IzMs3Z9Gas zY^WZt=@=awokvXw zOE;b?^#qmW1&Nz+5TH(UIyCNzx`;$CDe?Jm;8RjCv-EpA_SQve>im91fA&TQ!Qo-? z+sFOZ001BWNklISC?^zlZJ?$Pr(_CvuZvtE*m7!_WFm~P6v0t~;nLp~w2 zFyil$@v{a~y)H&?>`-1I?U499v~&#bCM1YU{#@CPCji{r-v*KjB&L7#UJ6JN)8Dvm z(+0{2o9DxsG9}Gbk5nA5zz(b2GK3WT!1bNhrC7N zQo!}2ZFSKQAuf247wQaa%XHq1}k-7O1Zi)NNJWlGKgy<*RonI~~`{ zzNd}tAz*aQP8kO>ejijrmvv7p>4_Pnk20AYm6|G)^*Y%&J3~x=Z<6o zFt3Hu9p*;#DGM3A4?5gYId`ewNH(`rHa$N+l5gL><@saBo!?mY_wV|Pw zbksYUC3KOLMxtFpQ(!tkP6`Ypo|+1wD?;N`0M0-$zhKs~g?ujxP?zDtl7f6(n;Ck*E0moNUqxBirKBiFzF#b3FVC_um~z!`@AsZ@PZdbvInw5~T#~s+iuDXutVp z$?3E>N>gf)NW~QQXe=^U*!6o|B+9R^j{YYaj21DSYF2)(z5a6{p*hC_G|W(0>wDej zzvOl{Wfm`rfG$)Qs9N-@%i>&d%S$iK=3u_zXuw&xY>?TU38hzlG|QFZgjLg?weH8h z-I`5UZ*Nk(nPl{xCgz2kvQ8Mj^8;%F9E&$7?#yh#wotwvX_3>-RV_5nP#dp#qQzlK z@$%BAy!Lt#)3tN+QmlH@>(5M`uBCufG>S7FOb;Tzf#pFQFEW3irVsm^&@SQITq3{; z)hYOtw^>nk$~+NfyK!X@3O#|mhx!cTcQ+6d-P1!RhZ8`@v|;3Qb00UVM4yq z3B?OFID`l38i~^dI#(A`@)_?s(RiluA)C|D(h=1ky6w9MkklVK{E@@-C$$n^4jh;Y zwJniGC^?Msj27sN1m@|(-0ck~_r$6++f~ZFGU4LIm($aVfL#-brC?{W zjLP{(*3i&Jl_ZoY5+rGzol+i1p)8IMTrY0i>1FPCb=ypAc}KJxS8|ubl}*eLFEB%6 zz1VbUZ_pTD0OYs=RE|RFbw>}49U3D%d@jK~G0i0&z|G&+H{5?PM*c@DI{GLVeRchH zC6S(zY-}dNztKbzFFak4gz2MXiCctTb;h7N=`E2_VY)2SUTa5?BAmR_JPOxF%AzXs_fD=7cOX(;R{8>f{OmT`Eot;F&?umxDb8yba zbgCKV>4AFt6R)A7|J`dB(94CImA%o z^L3(ipB;sKF|D9A!^K`N#&mrK93h$`p{~m%kH$@yC89MZAbjP3GA11Pq$VcfaI?=r zk%4M-8G``MB{T_T3%ASfip6l#BxYhWOPwV>zF~TPVOOF16Ynsb&R>DIxeeiKIi1a(weAI8H$)1&JF3DV}riks7X|OS}I_Fg91iI@f3k`9Ns+_7&G#eh- zw$P4%y_lW}Q}Oxyw(-iv5+w&maPTC8n0k7#{k$qn7qKBP96Q#0 z9(Yf3Z8~-y3(ahJCS7PAA~czLP=N1JLjjdrfU+a z>nH$at_$t6i9#NIeR8&WF^`l^+ROXDgmgjzM!B)3zfOxH09&SW$=`qar@H=+-+B5! zK4zj`2v0X5=`X$W=8ykR)O5+~N>n$I>PH94hdUGRyr~*e;rWw)_@^*B)u=C1Jo=A+ z`R#wujQIV@bJgX=N_P9(=vQ`uPS;iMFJR%?wuuVqp=LP!a`cucjmlo{9lBWwE&%d% zH(bByCL#T56ZwlqPQU5;ZCkevB`Z`?U1c%$<-5PyPOh+AmK@WBR8qPf^>PDR`i<9a zNjoesFM4)~Pel2ghwzsyh9+s}#H?r^CejsLXQ9jorF!OrM zdf3{Q9kA`n^j_e6W#dcLbgd}9&Ryz5L1Ko1bW!@SFUY@fCWj*~HN6YZi%5X(qt-|$EOk>2F{*mR|POFBLzD7n(mpdIyk0$CG zNFLGPvYys2GUt>y2YWG9cewV7YXCBLYEL1YVS{VROTFZb;6{dKYFfu!ONr5vQddPR zmfVwxchh~H`bhi&zEV6dLUsNcx)pwd#{p^tzWmvWkf*devmDzI&Om#9Qnqno(!DRH zA7-aRR%HqYA$E@qb{vJ&mHM)DXbBj%DP7)lO$S*z+BbG^6k|+l9sN_)RnnD8j^ae_ z&Ln-MIM68yBn+{_Q_BB2O@wjdeQ^ZgbQjhk4s9gbobGHw|Dp^uOjk)!THPcPy)gkMJERk_mZfOK?pTTU;J^S%;>gL)l^56%rD zr9Yvwd4%)hw;w0s<+Tf6ctSO#GQC`wKXc>=^_gHg;fp0exSPBlul(uV1kJ~35T!Op zF6`mMXJe_ekr46n1nFRr$wWMk@@_JO0uEj}IZv=1mAajHXDU$BWk-V3TX}VB{0tj( z+ybu*CLIn?psO<)!dk?wh+FZyqTcA9Tr3!feRF2%tPXGZS}R7&O31kE$j)WyK}%Jx zQt!cY{sQr)bIllE7%OBmS^Tr9GKf3aB~CYC?VNW9f<9#QFn5t{Yy(%Dk=}Ymqb$g+u)X41nRdSrr)bH#@~J87zLzTn6_0ew12Msb3;_+ zE!@9<|D9hi68P%ns&cMny0(JpTm`DN*kW|8H;c5ii0>A4+e|J6y{M>Lw9Zw$Engu= zk;&w!uW))1%hz45z`9u~^5%y(4&2-*TsaXW!FLKdoM*vb}tQ zGE!Sj|B(Ggf#(hsb-}sC>Xwuatrr;`RF?%Nh?1^f7~K-knJfC$<$uAN&UHsE2M{51 zYr;a)jR%GXqttIWl=7&_;XbAAMr;~iPNp%YW0S{r-X7+TZA>>8(P?Zi1ig^R$Z>#E#Lnc$ zn@Lqy>PrE?%WOW6d>_sg|GmC{FZo)zrhY)ybfzC#7tH)Ap#CzN`72L-XZ*JxGtP8^ zT`W2M+)MxPk66>ebd{B!J4ENBlSnn!bbsR=TrU?z_pkrs%c67)>#sj~@$ttWzxc8x z&V%U_^^L!-SF4K*iLT5&?fiYgI((jOC&5%G*O zE3AO5ZTvRrWR|rU!B;0ACrDI&6(~C{T~MHo?&b)fD>rn- z5z)&i0+rELgs#cuqGgTAZHH`*DTdw73nH>u+~>cYtn{(Pe11ZbbIQ? zm@Yk?pNWY87HTin3Bm>m)M!(=pEzBRe&)#SjcqA%T+qxd*<2;0Na_;P;dERt2R`xz zlHWga;B?hggf6HmuR{jthW#Oxvfca+;_N6J=5LF?7P@$Z_oVcPqbJ4FfKqxfeUoK9 z+T-&jX7(hqJ8+ZvkU(8dOE0bi)=h(?`hX&>JD@67@>)P^L0Ts9uON$aEWu2K>_G1n zj!QaSCUzuaQ>OuS^iJg7!Lh-)Ir@3xdr|+<(TZ#$m00S4es?MNn_5!(lG0AIzpk~f z7nUE@0~npj1`)RWS%0u*6!DWLK|*PCsj9|W#PmjHpg+mAKsv2pvl+k79o~V!kjmmm0E4paiI(2YRrVewoK2k@Ha#-LyUh(oNJ$LwR}K zVAkvF3N)%OXxqGHdU^1{+n=~_;fdRyxcv)nzkT6$rsEghrj&I4Lfi4GBYenc#z|cz zkt=*?QP155th>A8q@j?Z@1m{I@Lon)1g|IoQf_cw(+NINRyl(y=@h2}(g^Am9UO`v z^c*qW*BSIjGNqR71=ko&L^Xlg_;ol4MFy#_DjVJrNfq{FN;9#gU3=+AiZh0T5z^6l z`+Ak+!cCki_Jq)3bsDdd=!2jhjbz#)ZFDV7P&Y#RQF+t(hBoKdOc05$K^Iln2=`?i zBrWiY_5k&V+VTg&QqE%CHI$4WQHxhl0 zNX7Q{0)gpB;K@7|bP7)igaMI52v`&7@3|l4hTQS54?1%ojd2#!O=f~Us`R-g2)jdt1B(9Z0zAzo0jPN)n`QlDs zxXH&R!S#HheS{XIj1)xZ{Bm|`dipRPon@AD9AR=9DZhO-)m&J{ACGP3JQf+A&8a=b zf3NS`OUVGJ>E{ffuTVO){-==oKmOyz_OI{z>UjIs|M1&y;!an&C~ow3-jQ)#)^wc? z4V*l8lJ9SVV<$Qfy>ro+T_`m*qWa5H(9aDFoHNwUJXfmAe_gK@?A$%kmB?>x+1_;1 zrt7z0d?9Px;O;7>0}Pz1-OZIZH#KeEh$Z}n>sk_oeHE4K%O5R8ak&<%NN>7s^Z3wx zu>jCqjdU+WU)}HJH~X1OG%^U>vk^oWrK^PW+8eGT=w;JT#_acB1( z%i}_E!>X48>k6i?V|8=Iu&_aE==j5ikc-!VWPvhBEGXwkdipJ}HNWPXz?eP<_0!+v)t@Zk8G#e-d?K*Y28{ISU<%JvoCvxvgNR$jp*hUT(K^-Q|(4iMUUpv zY2EX^bfu0(tec82a+ez)VzAqSXz?2V!fTA3l{Chx(jei~4M7S=l^%iai9jt*7vXXf z!q2-K;(o46`z20$7!LRM>?IPWYa$q@?Iwow{(fICnmW~(Oxl1uF*oG4sv->@k?TbV z-%CjS8^l}8)M!p{`dw$*&YYkfDKI^m$Ezlo~E;U_M@}~F7w}719u@q_bwbqnnN~;p7%tW`p zw1y;?HL@nV&Ys zm+ErgZjuBCkIJ78k00z9UCPd-Qdw7P&92ddoqY$F4pKr2rq==K2=0V*petASOA<4s zc%o}#ds4)vGn~N2pf048YSoIyT z_0kXW>JRqTVPD~z88hik^Jv|mx3`Ylkle!!;{#av%Ld9Dw43sQlel;0uBeJGzA}}3Jrwi$8U^-$tt`~wCF~c0GQXeClyy6Gns}vTH7J7~oL0(PJ zqWY2gIVKVb`p+(r^McK$0$)p%+*`eT-ElXqy__LNGQ6g44mSCb)2S!!!Ov1cC^|S^ z7AchrNA`3QP4T?2P!4r2og~@^1HQzbnMgLghjGAJ!stz_3On4oRl2B3n(VsCN`3Zs`c}Lw0Elhq-#b^hAO&!!I zyKoor5nzY%N-?;wGTBknqvn&Xf!2yQU6B6KkA6sbj2u*@x6vCLH#gnPe<`NQ?f=Wx z|L`9uCj7~Z-y@S`pW+eCRBTIXz}>KWk-fEqNt(Gi>B?o(I!-r$&L*p%ZsYlCm8jOi zt-@DoXMUp$BWL4`9*8Z)mjynqJvv!3MXX+y-5RI zp-hy6b)tTpF~B;vbU3<0$;E}OBeOBAFpzjOHhpS@fJS#!G&Vaj%}$|o<7=6Uwwfc6c_vAt zp(w@|d@qIO#aXt?4=s*24W&;hz@09ji(4sdU0A@i(mb?ve5;B{hd4Ep#E2PvVI()h zd3*czg{J#Q7zY&c1im+Ie!iXM6rHBe=aRD{xfnx@gb8k!QGOEM*Kvc~B+Zp5B?Z)@ zXy-H@l`S1mCsLg<(qsYseHJx6J*m)`!l`h9Yv-p3nTZvO|6bp>mr6{luRdvNKZ{bj zxy1GI@;|=(kFV~#^Qotv`p$RuKl+pNFgf0I(|J_LE=cD}AC{T&@)KY>^;!KV&l&5? z>n~q4YP#{cJbtqLs0iI$xp=btmqOW}_#>%ZU9q9@yIYzzZ@6yLwwC+C4)dLQ z>0{_h-AxD5rY(daUVrVzA-5vjuBwc)*X&T!wx-S3Z>k(`PkR+$u41`g7NfDZUsE-- z;U>)Kj4C!=r_32J{nHzhtGP4gftvuvpW~JIm)UeJp|69?qF!Fa-!&^mt5+gcYq{8% zN$2A9;v|N)V3;Ka!Xa=b!|7I7OA)ipavRjGdHY=M7+X%4cD~axrkV|pv3aPtv!S1+@p~!fD}~Q7m&^R( zkYJ8w)=6YIECrxp`9O_z;yw2TVRcGH{X!Z9JZ$XU6TpYmbTFmCht60-oA|*JC1s1y zO>hdC>D-rw2B`Sm4UO(LLN*X*aXhrOJ&1^IfjZTri0UdLg~%nDn+bFJVfv<0LOOYy zfp^322M%yl)fb9P8nF7km3VK1Z8>V{H)kiMGo@bH`ieBG@$4G7=>gOrNNBhi9nfrhQ%t z$MIQWS#}`c?8qf|#4=uz#inbK)4S_I%6Xg|bB6{I(~;AcQn97PSYM}t)P?D1J3B|0 z#(L^nTS?LDP;v_fBUIm#grhW*V6UToUk|TkFGG$tm&YL)T^>*V7s|qbiW(*MFXQwu zcsQ_ppwT@O>l{9~tFv!cjaP{#sOi;fr#zG&otqL>{9qICJ(64kDg2v=ghx z2T|*Zi!lYH40s4_B()KNevqC&foeUyt||_{95;~u;1lydoqqxq{lYx4j2GZ@u>Cl4 zdfTAKPwEPOaGWnBRT@k;wsT_%@}s49hL$KE9S%mae8Ald$4F|-_|4aHKvdpF?zr34 zhGU52dJx*Q`|OC+a7?1r-$?|cLqk`vpMyjksi?tJ#2*K&9`}`$dELX^exm!!Tr-U6 zNL%-p=tzx=zE9kbH8kcAjyK3mRZbB#=YsVR-Aopq5wQqq&z5@Ui4!wg8X6f zmWs!nPK7LXsKXJXX9C_Sdo{aZPsr&;P3I5*fX+M0@VKVN{x&d_{?U(r{NDfe>EFK= zNGIpzesW$ax3{#k!09b_e-5v~i~sd|-+PocN1D|0$n-t3k{YevN5!~CvH2yI7I6BK zCAPKQLUZff=;-E5J{OC;Ej8Vmw-&N3xc!w!o`ZC)UqkA`YD<7OqPciosBK*cp(UeB zeP=rs>Z-Yku3E~w*0W3^yXK&DgW+1O8T-s!th-`XS(L6>>!j<}FCZ=!x322K+El1+ zRv2P`|aN_P4eKY6Q_olYpDo%V8zC8yhO6vh!tO}A_=MpZA0>RKdZ2gI3SBA>B% zGR!VyHqo>m@2{?Bf1zMJsTp?N;$|~fAymWr>ySQ1Km{fV_WDFW7^pK<%6mU8QEiBU1 zXnY|}`y#$snG!TA#nYG@M*vsHBMlX1&_a^Q^ALIa;?Tn9aGdA2wv)R!w3RMQXz@aI z0vd;ib6IR3T4;KH`y#DEb2*c$KD4l9=zLn)>X>9mtC?i{z+izaNYoX4@F?sfl|zN- z>_|K1qYNe52&#e3qtm!url$`?IitT(a#_(d7;V~VZWLa|^@0SSWW}jm@fhQbbpQY$ z07*naRNw3S_LBdiI73gq{JPT3*Q)8#(@9W&i`KyV6#I1N{vTmZ2hx$#EwhUO^>+@U zut-V=QAtq%*@ffu92JurdpZL8$%%epx;35qwPAYkP3cMvwFuNVqEc_WJDtEZvO?*i z2>s`-T5M{<^m5adn{L>2-OXXZVP%uzZdNb3d0=MyX0-R~ZW`Y@G^5H?jdoVIcyDvu z%utMdX>ODqXQW_zUMOZoOTYHo?b)uY4jJCtJ^hPpb*WVY)Lx}{dUUUX-^JC4hekFa;rgC#5 zv%#vmZUMU4QE_)>4_dB=X&GJYdF#-Dxo7*CT2I%cHx{3qeYy7eUb5;6SBvjY{ggM} z?T906!_ZhCPzBZ2kbm}Z@VzU*MI2WJ4v=0U6a{gL0wF-cAD=)px4bOzps$qU`lVEk zN|0AvOx%+x!KdC@=cBa^b_bY16`tG)lYw+gS?|XBUWHRy2-sVe9n2g7($8=rj1gKt za-1CO+A|o`C8p~KNBT!@`|hdlPJVZitQQumzmeqh+Aa(>mYPnCQk9}lRI9kV7yPTB z!;wDu-Bqb%VJ3lPthyejv4UQDYkDZ!?CELk>G1cLrBXAwWOjJMkH#sXv8Kk^N~EL9 z!5F$5HQn#D4=R+FIbB{yb#(?4I!qo*>~$}J)2TLpAnqrUBL%)^rKdB(uJ5Yu8W@}( z9Gjo(Ku(VxT6$n^>0l3Lm%g)02Y0pZS~}R;Ust1FnUuNTnmWcpkqVC^*cO|~6%xT= zUr$Yk8t*{lI7UrsM{Oe)SkvhzpP`qe*Cn@f#(R8nep2;`oeGfYtV1Mjq{DpoL@5V5 z_R=<%0hfkfh`dPXZi)(O{PZ?5l!)BQ0fheE-Xq8J)Plb9(-&TN;qez9f8Z!dFJL-6 z4wTE9zIIaV{n4@A9o)71uK8E)|C>j@|JsE!`i{1uUVNUpj)4YvJMP>qM>Y@c!2)}_3_kl>d3&6 zL3$h^rz4@CIdkMVpCmceS@7U-QNgUqZKuYJv-3x{iA1VI!i`Ju^~msZ*d(djUS<)muPs^cLLJF zZF8nJN0g&t_4O+QqX6L}`pbnSKrc?H{lL4^x*4F(U#RMh2Q?hRpq0s>r&l@g(Xekl zPQL=$=}(J)tB1b!bHTZFLIby{dqo>xnGv6JlAw;H&h5DX zye;bsaysN)oUCh-$Z@J@_v;zm264mQB6_YHP`74*>f#Se%~}iCSC<#p1LBq!T}ZA| zkHoaos*y zkPdlE8Mn@*rkjaHa=kEFlrBWKiCwe0CSBbT$}lEeL3nLzR%27|9zK0X z;J7~6Ksnt!XC~9z7RDFa$G3yqv?XG55*rf~n@%Nh+>q%qvb{w)Eu@^o^jj6dNS`5Y zPP?JcEo}Ygb_zJ!r%&KWQt}d<=>fHJ~a)ZL+jB~xY1_|le0q$i_P1yxKA#R zoDVP0=9|f6Oy-Jzm+#w4bXiJB!Su_gAA;#Gze<-gWwSne=f3^_$D8k%Tt@M^OzAJ3 zBdC!h+faJ-36hGh>826JQB#B}&kNJ**2T%;@^coWQ=fWnVC@&$uj7U5c88nCTgF=| zH*dLV<3>O|yDCnD3m~veEI@kGwk?V)ziG(Jivl}eeX6gIE;ik~nOvBrty`P3*u|s{ zGQI1qF56$X#tRfpDY>OvmY4djaHVN(v_WZ%*I%c`qc?15CX)R(V7e634Q{T*Q9-N7 zcFnYc>1&pmS++75EGYi)&X0b4rv>Q-)U^{qvQXKabe(H5y$IEf8g7DFBBc(hVaH_pr>%61ataK?5ss--2};0&U1u?-kLsv{Wyw&HCJ$YQEGjak*>o-y zjn|i!Mk?q@Pv$sjGHnRt{76j4d*RzlHDd;LCtABquIa`D`R03KyOv_RI#r%ZFk>Ti zFZC0pHNjy_FTBBq(M#}dFwxJbtOt~&wveDfoD;3Boqb^XYj1t~{1$&YxNiI-R(ir$mGy%}%Fb7TkIOW%6!@0LB{a^&=WKzpFKH*Rp-XIxX} zcBQNdP4R&-g!Ennby_4jS$G873!qV7 znwm-PAN_bhjD!HcsiVQ z4!#bd-fBMv*u9~%u~TRF2KBt4boiFzD5xskU4FOE!3&-7ViWg5=%!$HS4-dQO4eQFD#Yjev(h5Oz zX=$TIPu3rxaGJ?oN`0(4&N{S)3er8fLO9F2zS0ib`qxJDu6kTKZVr#QJsb=3QFoi2 z8y)S%%Y@Y*GgQVyA*oK5?}h4E+Ai^@45w3dVt*Tu@I&ZT-B+ z*;l$0o=Z>1`@&?*FPs5twjO#dvLZe=pAb*JBQi~ZkT z$>jLci*Rn+UQBl*N$CK${fnk<7Fe6ITpGFYzF4Sk1?;xIzBUS_%aU#g-YmB$ zo!jEH35ACi#)r~aKQ2-Wr!qct zs#ycZb`sLVrwC>oqIC3BVRo82(V?LcLRPj8<#NdFi0CwZ!R?;^32Eu1q>mHx!X-u+ zH8Umb{rM*HV${zx5q0w=t^CDA7{NTm10r=MG`lH39iAN;Kc#-D3^jPVlT?`!myVuJ z8`8-_9_DA%F!cOFds9BVoS3AP^gNb#=s)-VPkP}$Mt6C?Wlg_~)L+K*!g%~Cbx{D* zpZ<%VkoBU;K)N^`F`bX973IzU#Ky*fqcXkVjzLXFQ#THnizgdaG5yIWPyV_w9sMkI zUrWn>!UlEomYcS0yqRpx3=!l~^i;mq)tyL><9MMq2VeM2*H(rF-S(eg5unyx;zW1s zz@2{c=Ib}K@LBZABJ-}dSa226jhGIms~xJ;^c$N}eC@B? z=3j5-a@w@9R4Vg2d3kk9tuR~Jo0>Jn?O|X|AO0}^j6VJ8j|$XnL0ufo4{*${&dmf` z?-ULxT^@M_DJlQ8S3do#^U*6_hsg*HnyBI9Sq4Q6`|S?btFN=NCku zAOeIdNYtp=J!Ktj-Xo~#XU@p>a=h)XD&+LWyXf2$@YuN>YoTorUHIGw4N#|);s`Pg$%tIMsx#47&SMA8*ybsX_0Km|E{G?t2# zVEz~mB#_%Dh6zLz%E{?bMx=JIn`6Q_fLj4|BYBpVc=5c{`-$3(r3p4y-C?JZQPmrA zqMKey^dZj9%tX~hrz?JBux&6qxVx@*bcyhELR}6X>}&1p1d5lI)L@8%7%~p=pe<1u zD>B}SKwBakt!hiCtrC71LK$U2$9Vy!Q|9GH#`VLFn94C#=qC84gKg&0hb(VA#1WMLT=&lJ?dWi{R@TE1engG=1}EvqFzwO z8|nt}awGI|3m~`*^UCgixzE9L-X`-#dCC}U2$4bc-56W6)-bxx2I?@pbnN!vWs>g& z4@}(CM&eMQDn&233#q{)gY)x84W>VF;Q*f_C>ZDi8hgM)F?rn zH@AZirXT%VZEAy&v!Nhy>8BD?gqc$WKt5$fMu!!Cl^LUl# zh`?N&9z+;7g~Hg=iAD8sSAaT}^k{6RuqQ@ljN0ll?lhu{RCN_L;jgFm)PsG7dsMx` zC?jL1iPs_W2YV3rp}JJmdfkhxT)Ypw+I$M^ZvzwaA}#&8>)*Kk4dYFJ{(fobKR})Q z!NOmB^*dj>^-H%tjU$6TN1R#HJ}K*8 zP3_joBA1(MB5ojEoL+=<>x#WXC~tYwA@nc*(U-;PhSzxxww$il_~|=7uO3JL-d58& z)^UsdMp36JgNd1nj1G@00LH>{!`*AnR&iYXZfok0d6DQ1jdMoBUnM8X;G&z@LcDzu z;A7t%44q%Rdtos@lb9kYJ%Se{UqFKo;6ev=GYUr!Vnp{6nm!ec;VKU&aFJkN!QP^T zIzke0sJm&>m;%yMBrPIE7qFSr(gF)iVlqjf%n-&E6!G?Uz?}dVeiKxqCYsxuN463R ziIHVd@#i_Z8xilvXa5agdi{xOu8QfX;eYtlzNelx$IkXWz3-W4{`tHFbpbkOg7r>{xzN#R zlEh&@YEcIyo4+fmO2_pA#NV`G<47q^^LK-8B@NWOn`v6QdE@n4#_t{q!~DMhN%P3KRlTEahEMK& z_fd3l_jn~8NHuMeH62U`)Q8-%KK|=Z1~fmozWQ;6Mh&bASPiy{%?*re{mM3LNtK0y zUXWK=1~*=}Y16ege*B|+^%?4>v4<{MZ8ox0aovSD-Awj{bw!MB_N7aM=A2n-x|V3w zn(Yl)o5l9dZn4&{-9)Q3Jg{VRJqUhTpnKB8=2V>Y^sMbnJ!x_A&vjXRbL-=c5IQmE z<(OLliaI|jEHpZYyaS~G4Efs)GQFrD4gb}ZMF>U;^YFN!rlXhBrwC6vXPCn=oey{R z^>q$UbfKz4@U%7R031Ls6*`vrEE!!Ze02l90RkJ#3G{YK-|Q6_9XUfM(m@bQqI#nN zbs+uBVbzY>1{dbki1fRY%eTq1F3*e9^uz9sQC|b&T|TlA!*&>1TZQDW_N^Bsb%#j?LtmJGI+dg9zA>v zLLWPM@X$eCrapx+qF=-QXrK&-uo1h;+@LH%u3RKOcOslhc*CQNb~-wiATOn8hZKU% zq>R5#KVE4>Uir$sE}}l%{?5ej{p8{QA>&JbtDiU+jT6clh7lRa8;7eNB^CW$cjloL zD~B@bkYPREv!e7KLL)17TzKu(x1M_I=C{7}m*4uWV*z1ngkb>JytaB% zJ^0C8Wi)Q;b@Bgw&{ETnzm@{d1=c6~(9hKkQ~!f6>xZSxTPq*=qes6-izCVDPn&}lpTwR1#ee@HrM>W<>O)0L zw-{Xm#T8B6(7GTU!j_nRwG-4FMdcphSP=l?Z;%Y=N8-{@Ls@| zPUlh64)t^)pIFYfFHgB^a|^(Fbm}xi4u%R?(Zdqbr=fLx^^?f?%|k!nr6}N12iXg= zN{J+f``?0^&VS4Dlj=Qmh3UyBUw)O6lw0rEcdLf$`}h`EKu|aKbdfqe@%V4cKOJE6 z1bQ$35aDuk^rHhZrayVK+<4N@ohz?iF}*zbhPdGNShZbAgS*FF9Vm56aN$A173#PM*{wm$6t=wSSO{yXtNja2U z@e52mwrq}GVjDMZq;mB7O&f2*nr^)5*V~l->1|2uFu%~we}TvIZa1;Ob3LZB%+khx zE-JOL7ZQfYKYYtAH(vYv_}xv%Zv5y+KP=&WCE zik`mHy438-2^F68W;NpgCcB-fcBUPzOyX~Afi-7VXx4s2fVu_w*3&htZZLh7+TZI7 zvF>%WUv{a=T|l~|aA+dv-x~ze0d*1+8-k^d@&GlY0K5}5SBkpK7=W3&{194A;VEz~ zK^pSIk6RNpB6Bo(cFs--GjglG4lj2X@cRJuuhNJD_mw)}FBl zS~}Bl(CEk+8PrulN)0LY^fPogDprdM*X2&9UC53S?Ayb(K_q zNwns`ekdZQ=5MTvJiM8NgV}51Xrnwj)sT{}a#k52HLeua6;cp~QPYK^On9>CVQ(Z? z60v1B)}*eLaagRDR(Z)7l)fW^!l`d22wfA$qa1CNqb8Dx6JUCM3ud zUC`3|b{*Wci-Oz!&N>1DK__=48gYft%KahbbGKzmssdH)J)FoT{D9@sQb!LjKDjvJ zLF&8=s?)|5c%)g6m$E?IGrM*jeDlwK{AOq0o*7#8)a>=eyZE}S5BP?CdwVhwE2Sn{ zQ9;y+EGAy!$ID<%<%UN>?wS(JID_-y*S`PCD{qaz`sZ)`;kUl^mv4P-es0hUweo5z z=?Bop3C|U7&+RhqqjYk0g{rEKT=*KMm+v1BkMeooo$cSXt8dssZN^Q5+>X+; z?n&()oX4Dw75zbKMpM*~&YzKvE^|6+IxVyCy$n`)c!GejQRMacXeo@$kX-nqik*=nnQrznKUPM`k^%(9NeLgs&b*m!`renl`B%0>jut_a!>L5^==nhj2^RAnz3) z5)ZWua=q|)A%C*d%~N9ZwSwuld=%5mjRf*uPsqy_PRHJO<4gDd1&nT5kly+k?9!S( zdBhtgO-KhY*J)&i_cfNe0A=MIL?jvx%?#DMjjW8 zTPx*nF^an2Tx@QxT2bmOFiWiq3)LU_-m_0zu9yAKFdVw$4i%C9{=HTzef1=qO*X@;>NXI^#PESWvi54l+n!&_^5T)<3e#v=bE=t z#+gfm9KkNf^w1)zJ`^AFPKQIM)nXKn`V=I7nrc)O_o;9q6^D;Et<@Po3?FlWRvFX7>3kwI1-PGDTo_8uumJ+N*d3oue*3Ye zrmg8@zC{b0*#QQbJnck@Opg@`WW12hI5kxmr!-d9blfh)M~0V)aXCLJ1I#IqoxJoH z@!(XBla`*EZLfT>xp_8^&wN9VEPF(^!oDZ6VinzR6&Z2epDB)Upz|EqpqK;t~SdJyFYoZ-*~ZqZI}+@ z^3b|UW6kaVsb%~4c8YH*D>1kz)e8B#rKQqH>3Ci?!^)e75^@^88>XX{=uf08H-7V$ z&098XY1!J|oao|v`P~@zit9M=-<2Jy+^Ad^%j?$CZL`}xaM?Zb--3-`An(jqUhm5sUcLM;kl}`FmO{lpPJ8N(Nn)6ef*g{-x ztmeA7U!iKL6sU z1DO?~LK7eE_t!xfbh!`WFDHgY4N0*^sg@MaIc1dm*SAhwcwj82_*}m9BCZFz8UySO z)wWZ8j4-!|cA*hJ+k3d}AcDGrvVC=gp1knQhaY?Rn=c&d80&B7$55lrM%dA-8sm*s za=zSk*X;^=!K_}@c!EBp_9RL_Ok<;m&d{86^0tQ#+=l0ci5&G%h<2OkjQablZ=?fh zuO2W{32J(cI?sSy8Fi4Zs>VLtK%;tM>yXoX)wpL@PY>xT3BtJ&6~T#WXSRkOKEz=3 zLY9cg!%Eug4mz;z*U_3?qBJ>&<&NoOI+uvV!lQJ`sc-CR@^x^TSIPQ}9*V{)$(-ZHcpXyVR3W!#blBIa z+?GB#c94QVV9@EQx=Wo%ORG58OimzeZ91UhzP>|mzKDJ`C;$K;07*naRQcl{KO7^{ zrZKonoXp^)zPxm=ud{^KKI%hCvi2y}WX2y<1ans;u~SY;{=F!R*2Al?zAPj-&aiK@pV+i15@J&^Z$lEGa|g8asKi?`+7?c-Q>fZ~bNa z-?hzq`}8QhNu1Ud@97X7$G(o8&JRqz}MWwzBP%rA~ zLUlIw=y(pFqq1JwRuN$shtuN~dy;M5@SbqC%`-Q@n+8X!B7G1hPf1Icz)3L<#bYjU>N3*C*TQ-vcJ_!At7}P?Kvbuo{l+{m~Y@+V)~`#7fI^RipVdY z1nT1PuiR-5vhK3vXI?4&{ym%;&djVHTt`ubfLI~FSpB6+g_>Od90$S}ILSe;n+44I6d zAnfI76Uz8`g}r?7V@gk7V|p=e7siR^WVl?!ZACNMU~U#z7`|@SQrdxemZHTQN~f+g z=)hk-<*qV7ZiIA$=xZpS>m;JPLQ~T*eBt?)aitXo@tKDy9>wQU>!4!#@l!3lY}6`1Ml_F3rkj)PL(`JcDKX3&NTv1+J8{*;|mn0@r8DIvV^t{0}BWK%_1ho)DJ5{^a8WCnctz8>qK2-2}i0*v)iO ze)eDE1afog4ouCA+}(nn-m=}Gx}~5uRqE25-K_p@%~q$ohsqc+-~g zt?lUyi+=72`pz^r-Gqd$X@i{cvb>nz>#q~0-}vb*F@WQJhv{JIyO63Sz=O%+?hoAZ z(Vh3Uf1|s5dT7%}KMi5qQo4b3=FMg-Tytq%6Q?tAZf&J2+?*c)ISK0)wi`OvnMLXP zdSwfA`JKA=%ckO@;w77!2V|qVc~;zRmC3Ea#tMbo8?0Qv^2}8*eIh{BCnVAU2iDaE zgSEk+1GNtRrU=gA@pYAYO0ftB$YeB$*ASBAOyqGFJx7hz#hfdG5rcapln$I5zl&sc ztRdoLZox^0;|l!A-oZH-{o%(R``TlVJ^b)D9~kTJ?-=!Z+Olnu(UIlv^5Rav{jTFE zpsFEdqLoT13Y3~ufgYm^y%ORl%T>kxEs{Q zv%=L?K2h(O-jhz#PAK75pjji~D@PjP^m6obM(VYx84i|C)^c>JJWe1W(dkQvcAZ2^ zKZKILYuDboI`Tt2e){c{#!E>6%t)NpM2)EY=kC%e(jC(&UhGbS&|7uia>F>u6{$LM z`Yw4Tf&`ang1b2^uaK7ybdU`KeiO{MS{|BR> zj*4EK9$t6olDC5~hOS zc_@~&&7i1;`!|?Q38@0_dp#E9vjdc}<8Zq0K_oPHVwga7#PLiO z3kTNDDH<>3rn%&j42!J0Q)6M=Va~&BXSlLtvRm2@gcp8nk(=HGXbS z*gE}Kne6`~!t{@e(wW}){KjqfH&y<{{r7+AOTTmLr#@*Dy6~JNZ>BGP)>6~=!|6{w zV{^K(y$ID;{V)6OF!||4HQj)@;Cw|i7r+}(H+ZgDCY#i)71pN3WfrC5cacOcN@voA z4e5XI{}YaD60d6;YeN7W@D@dD5d>~6E|Plj(yV74m-<}=crCEt++GE8GiM}mU7C3= z%_4JITxgbQL#;B5Zf2~j0(a{qIsK0wdG^_7Y}bp1K)2rUc`zMLH{t0kYI+r)KXW_> zPM6z-?`;F?MKRro_m;>R90F(Keq$y}pJtff8+bAeS zqRvdBn=nA01lCokndLf-hei;=F~s0~$&ZhZB%`(7Pzqy9x@kN!)uzOB$~PAwb8VGK zEN*Xyj#1Ou02bY^z39f z%afZ-Hj})br$!cHFEou11v#l+sH!BLq6g_TAumw+bQsZ}{KxIvelWB^{l>z=_7|If z(mu{zwJ(hP++g+_cLQOz-Gg*3p=%zdKKD~P0n_D7u};*I^859tzWuV&(=X~q7pWjc zjn_W-FLLm=@-xOulv{gI`EwdDpUuug^{g>(&2O? zs#h97udHnP&nh6@*3^E_l)4nXmxo6kSgM`ArJHZM>E@QZhjM;s`sY1Dz~CX-Vlz6J zj^D-B(m{0!NU8C^;l^gKEH=Nu7~o(0CB8Cn{-R64UdiPs)VJ)s<GAmZrt}I?Za}`Xl=Ab+{JxmiKUtOmtJy2U3m_SeI z9`1@u%Jb5grNQT+38|4Wbs(Js>KIzdUzBEU3@?V)F}Zie8yhC@TeDPxI*IFQFj?XS zNxZ~&Fb||xq;^P27o#(M^P3O!&|Nd@&ER=CbHwY2#~ZP|P)LflPRO3@F9_#FPDfT( z3sMuEzC3x`pBUGR)b!g96Te{v)oGL*_keK>40;h~sn&Bvg2sz7(JhxsLLF;p4qDcs zE~Nalw$}93`TQvyY53B@Sxh@+5k;H8>GCi~Tz)m;g^kF{R%=h0dK>r}>WWgzL?WY$ z!&Las&rG$QscO{slm33{yE6Qz2`8h$>aOxG&-`wuai&A*2M>wUJ3ISn2ML=~35pc~ z;|g?$-vwJT_5=(J4!76A5FnLGWc>b~(OroC^ne1aOKK2JEu#dO9y*KLn*Kwrt$l|c zke2?pKYsbo-i%@3Ik>m8GoWvxhMGt#YC28}N=;GIX~xOEfI(h$rS(yHs2p*PTM%K7 zf8he0p5AlefhV4L;jh2-ZK>&l9*Eb4vKIz!dZgsKX$UOFB0;%&F^{T z58wLBS1z<==f>*#PuA7d(c)BLFRk*S^Zu9gmeHrFq>cd)uRAARNmU3ahFvEU_bEx= z{3y_6U`34Q*3>w_@x7cte#%M9oM3v~LwwJUSR$4h%#f0JH@=>YqYBSvHQ z9>EXJfQ5VI#rBdt@AmqGc)ia~pY;bhPQhDW#yeo57$+K_cKL(om0B@4T2X?q&3LdD zOsb_Wjy1vQ zJ~tVnU^<}g>DB%4vhkty5at7_0 zf5sBg4Wdiw{SYU_^jn{ydJITsdU`*$7n{-Lidi@Dzx+-Va|_3d=Rmj3+(_r}I@b)NJ8D%bs?D`+Z8jRB zZcd;sMmH-g&x_(1gM21%M=F=Uh1;uN-stA5jM!eV-|kfY^iSUrmX_T_L}EK!Tcgjhtx4D@WZGMYws&jZ?YJDnmL zF_9liE><>E$r*~K0sir=_+q9osS^Z~Mz+R%F7pid4W2irsU=+`ig9RRVQXGhNC~_% zif zF%Hpl37w9H4xcvD6#kj~&=2s>w>R;3vVF@Nl|-k{HZL4|{{H6|n(aTR_wfb)!uqd{ z=}&(D>v!Jy^=J1zOMLp*zit9we&<^+(_8f1lg7_}2v2%Bz8Bgg)8gpFHMZwPP)?^( z3d1ZqACPB#Wx@kf{1*FlzHroQb~~~hx49cNU7RjZ2h*jb(}A>dThrZSL||xnj}MOT z=5UJ%alEOirKLTY>82N{x$S%0ft)o}L$;JIHJ!SR6iom0wcDaZJ@e3iov+kY z?rS}0{xa8WHQgYufcm4iT-UU9sPfo#AGefl2)wv^z}Z6e4e^p%m(1;Co8l6)SZ4xsi_ta91G6taV7to=#jiYG zZJHaFCvD?{!LDE_Z5>g@^?mKBYN&Gix=_WbBGo^907*yVnOsgv zNEP&g@@_op$mv~;@lw1peFt{|XA38wDu%od-k{j zrLkCWq8^)%q+LueT(}}MA_da}7ywavNSuD~Bqn}d9#mLwO{Y)oCM_i$;FFN9f2E}X0efm$ zS?-;1^)Aw9dR-iLPL$euC*GUd%aT2T%5)*0x=E`&IH`UR|DVt3XBv<@ zAfcrf;4ZcwE$QfR0sFAF`Qg=da*O~X6{Ry-2|aw+SWTH}FJioUB*Dn4K*jQ6j}{p( z;(IBLlXdCANKRN`IF{m(4@y6O@WG=GLhH7e4yqei#{+Xj{YWwG3}%T5b%iJn_6Oso z6dCi$=?;{fjqFtz4kYfO8i7wsJ^AMuYAU!_4h8YCR}&$u;(o_zD9O}o(tLej_ zbQO{-2lDknI1|EWCG1pHg{b`u&!n@%{?>{98Xtc`gR-LVR?;yEce?FN$D1xS-JOZF zaX-99e0bTjo09HQZz9p=D(!OkOX*2R?FE(>{4_OCJj03Nmo@yZ1b94Iu8uNZJpIY> zs7={0f3Ofbq|OITXs(F^1LlhT{d>!YKKf~^|EMz4-}wCJ-}us(zVs=%F6>Ee7cn}_ zs1`ibknZ1yH-j@{dx6u1>PAanmD7dnfcmqLw-M0=;AS#VE)+LKq-z%z0el^ybHym< z*1{ED7l0f3mY^st=>ryPOjjS^+EFfQ1%guTT=te{58b9W2<NKqG)+h^9!wBUP>Af`WOcOw0)tVB=iIL2o` z``M3u@!k*J3#Z#}R8dNo>t#*SOHnhIv~Jkj@V7vZt+bP|X92$)y42~D3$z?p~3A!5Pm6JluOCs7vw<9opHb0b3Qnbk})9I0g=Z7fv zTuz4zLrv}6(R3Sg==?}i<@llo1kii)V&x*ONt-o` z7shyB@*^WdTQ_e*vR7RD`MfD7m7szxJxtruZFv&ZWpqj0Kfat&x+KE{dDN#4hfaqM z(>itf6god@eEa?5Eeq``%zJH%M zec#vVNzBDlfB5pthPWlT6RyZV9rJBe-q?7e-oo^gHm!4b)u`!o9<_PhLiK+g=#-zF z@A=X;4x^0ApKd_?KUP-$XLUAes@!@{j1&g8c(3ms9>?@{s!_>@+1#{!DCt$7miKyN zZO1)DE3YTZ-4fI-IbESyrnE8}836n|`~4Md`!mS%=UgpR7tM;EcYgHK z*B#rk>Bf(L+ypXOD_Ex)PR1N=&6=%s2AJ!nT&$hIbIIqdu~c+LqFX;}x6=GhZL@C1 z+QKZeR~6?qPB5fyJs#_cS|rZ7c@qC}YPt#{v9tO?Dy**X1@3Ab*7&R)RI63td5On~ zg&SrSguTrYq*9ap10jBS+@jh-f@u(CojI94)^H96BC zdsUcDMW3SjJPwgJU558$B3|m^8HFz9a#PmfS8r)K{bZ}+Z8NE<((s-(ijLKe^e&7pM@8%4xn)&1$c~K)J^jL5+Yt{sHscfy z%-04>C24a+1MgRm;PV>!T1Z*ZH*@`j&&gnhp&mm7jO@I8so?azwKNRkP4bA+ zU2bCEy)>VK@tp)^mip<)tM5hXI=iX^nN%#@JhL~#fUMJ%^|s;a;iwdYBo1Y)PTDiS z(QL-$B&3o*ok*rFTEV?|vxzK^DNyR+qr~G1G9sPu(J$$h!vxQ zI#|)BQMH%HjfI>FDY9KU$P@<4b2G zZ&_IEb6s2GO}DNZ$=sT?tT8sD^X;K(QDk|w2Mt+%mn&epfFAayCSoc==OahpbTs1* zx*egJk#S%+mxv~(0wIiBQ4ro3*tw{U(s(pFRfYUcc}@Wz3u%gy(lw=~Q}{@t38G%m z#uKzPnh7V>1~eR_#x%yp;R3x*v5T`kPW9%N@gXA0sq$=pe#jAuBESzNv9u_UQLghL zIvo83mE52>^M#Rxty>l3g2iPqkH1_JI_?$>FGD0VvdfWtI^VRVC68kfm>1fQG_xX& zh98?98Q<2t9HZ9}rJ_yaNtzuA&~;{~rkeuNwe7HiZr|GLrB1?zZUHm}9>Luk)MOo!9UO=|k%U^)YrTsJ#3IUmhN)F{X66v&nmg?%r;6bVKNsm3I&21?l{AU(rH- z*1ZtyHsNl*dGpOTgV`Hz-aeGeuzO8E>z2j!fJ355;V#xBEqzr@m*?fiYq!#AiKD9T z`9T$T{j0eAIXV1YHn$L6Xv;5n{98maGAQ}zEmmy01?FO6ek~riAYFNkJ1x2vNgGDz zO#T-$&#r8=7IR~!(Ybxn5_?+N#^k5(EH2iiwaT2^XKM*vysoEZUs%sjPlFp4Cwqh9 z)vH`yO-)yo8&Qn(DDTHqPQ;0P<$(qu{RHh+h>j@rRS{_@pDfs5SVhE5$4`mqhS2SE zSzh=dk#Se6Wm_jbh71u@OHq~Gxd!4H9DCrm|I1^Ki_;&+`tsWk^wxp@UN0Suyl0M- zk`38-mj~Fr>#jJIPH#!9FeIlN(VR1KUBu}p{^SJKm*wJ8QW_7Co8_i#&oZYs_>7be z^~sK1mMMd?DIz5*H8-=IRZ2^B1ByB5$&ZkR!Jf2}nP9mKei|15=qu zPsqk}KO+N=8YKbgFGJ^o^#A@2a{8O^>^it3b*B6T(K9&PJ3D(U5@yn=g}a(7tq=Tq}Ns;Y`P?l;K72QsJ7xybhtOM$;WsTw=YB?R3G>-617?c2c=n zl6Cnj2souofMFAcBLy+amu{7&YKKv&=@dBg$ASrp!yRruMkxe)J{{x@bk|oif=1;G zMR@sXOXaZC8U}{^E6`|?p^t283dV=^E839KOPx9q8t;PbeTeo!`CW)E;@AH2zU4z7 z|2Ta!$V`9Z*rzrg1JjA^HbOcjqsEXfR+O6l31fL7jZtd45!3fSW75-$Ty9%nRye#|cyGQ(&)vw-E7 zkvK~%FgF*P)dDVYq+jJnfR1;?MsLyj%FoJdajm^(WdqH856jCVoN&FUL>Je~e&RI9 z)%h%GFJD}%rVG-UZ0Z)HTX~F@oNm%zSg8$GHv-hH1-cBr4&9A- zova+k{St<@<#!L0uGoB@cyv-4QP0D0AOJ~3K~zm(I<+nnCtrWvE*`z4 zhE!@ghsU0h;|1#rzkvF;|IzL(YN_d9zP^phPw;IuV8x}M8<2+nSC8}m$j0=e*O-}$ zw)5p^oPVP5y$D^w#=i=tynLUAo~y4RE&%d%WMYMTIM(tx>KhjCyC=N^g{`YgZ7Foa z_XOJY*93yqZ9`3)w{6>a6KPqM?MV}GjsfWMJHN`3`fSq%QXp42eZ}>HHT_2V&(Ueg zsQd4Ik5{>)e~HCcAM;j9oD8gj;8HcOsPGj1M#uYXP z&Rc#LOH6MdSv=tDpBU~0^)aTio^7P4oANu1;-EU{v3qO|5&h7immYiR&K2oG~Ini&s?Y8eCq;tCMw&m|iRLAxrHT{75 zK%1Mgasx;8)js;}fP7>JQs;+KjHY9ElrM)%@vA@X(Caxdt|^>#2y$)eO(& zelLazIOC494s7jl)s^wIon`(8y;K1wZWExr%o)i#_`10!gqofX%eh`(e;1g3`|UJP z#ZFJ;%>=%Ozy#nQOQswXT~+ikf~Mj0|9-NwlS0zIUD%Jy+$g4A`46ZUWnx@pCM*;Z zX)_r|BF15cY{KJv{Uw<;xn2l@$8FyuS(xxZx+FE061YvUql@~?UWmJ+?F%x!T$n$~ z^f;y$yy+e4J&Lcqu6L}r&JZ}MnsZ=!Nhsv$9Xr`ET1Fqu`Bw;JeC6#6%PGPV%lkQN zr~}FeO(rK)P2bPn{&+v2UQ^@jRY9xJ8OC0Guplc28pQBzYYPM6Bg?-Tf5+KxDJ zx?pt)o_6!_%0{zgE=HaWP<2BgIG5rF3jB1in1`6%(W`@!XzliT%zi+FUIDHh^v@ zd1;o3%vSHRrRxmi%$+!T*mH#L41 zA-R#(SFQ=Wwa}b&MOwOC={jAG?=1V{@1dnXA~pTdXFg+IbX+g{)rwSdIz^-!BH3@$ zdMRBY=+;Tl&9C)ST!>_@h1Mz|JTf|@4oah?cLCHPFZt%0D1w*O(fHHBZmtHA(jjye z$xLOU#P|EBqO=*{SW+P1PN0L29*d3)3LyDP^(cQ>KccaIll(`fOznItY3 zC>ry+tS@;;os{} zdAU=Vz7I@aHN9LsNd>794G3hs28)YHO+SYC-vZ|)zdAa_EPv5w)*`YoCW{Bz6T%rJ9nZ4I6y)vm2mA+=1 z)mTM(kWxR&S|-Wp#YtpskvbR+Pwy;(v{_-VG3;!3d}S@yB&6#{c66!mx~;tj8^Fy? z)||0^bywVhxeqbA@!yykU9l&#u^c)2wWgJI#cjB}^6S9z)fcq*C#=Ti_@=42tZ8VV z-3}Trg^i?nH#EQ+aRl`$7wAz&#)pWCBEAZ0N3orY(N$ZjGZm0>U1~Z>j#QPJwPv9* zW8#>9RVk-1MyC^%boZfeKK9blLl5ihw;y|e)a_ohN|lg$;q+1;(Jobdv1o#4EznErr&@wIB3n%NW(e*sac46gFZfBLYwvKRr;l`&o{q8uXZWXC;t$bY-o01x zE`szQ{+NK5H{X2c;L?&}+28pw)c($)>={No^?GM%Zsg`|@bKVkYWCKUd#_Xy^^P}| z)gocaYXSFl4?R! z#*TJ?nRgv;2Gd_%zOZ9nBu|^rc-?NW&`k6zqQQ|vc@{RF(Puk2sN0FYW8xN zf(*hEye&p7S2LrExjEb$N@k4LsVo?!U6b-^*b3AwW0jAxh&e zWiD!E8ESA$i8qK>&5ezhiSYCE~>SJ>QIWUh+b#p{1;t^8vX z^71HR`XkRiy6Spak<&4!e}Xbn`z>Bo((OJ)p!qsjH(0*H>0GlH7(9p5<(iQqUt2{+ z3*tA7PHR%h=*14Dsv_kVtGPGiono*^35J`S_%rzNY6HQ{l$U760*Gs*ZOSVhr>7DG zFrE%g$?IP0PSHS_Tv;_^j$uj=}w3E3f{d?)$ zJ&VovH17%TX<3YnMoGF2V?9|;gxkmA-yNxzt)Xmz1ay*9r^!qt>4jcJ=|XOZ!9r{n z^UBty|4h-}_9h}4TehcjduU!%NbV`j=120)FOt#-il@UVJn7+?=FLs*U^}*U6!`X` z7l-mcX{MhNqWT*-o`@0|r`s2?-o!w1!d;Y4gM=O;0tRl!S|3hsd*j#-u*E+3vVn;_!-)EF`>@RmdB{lu8v`S##$CnUar64+u z*Q$*Z{dFi@s`+0XWtmk|`s5+Y{X$i#ZipQQLf5y~uT@Rw(U6=~WauvZu4~>l>)53s z?6r&6Y;pN)0BQc3K;iCf#J$L$zUAh-^P}`5l}+XHt*@{I(~DzqV7i{nd!34y z&Mk`XkrZbANz$9hSEtrEAl|M%FnyS?H~Jr4N+;hL3jl(;$L%FK zy$S){BQ4#dp73#O>Sv}Tr2qX#zI)quEi!*d0y-1Yx)Ia4O1Dzd>QFE_?$2mEfYUi7 z3Ra+rNIgDL4x3k3g;8z1awAmx$e9G?fm2M^#Ez8I`TV1?8OoB9Gr$qg8=55Tg-e$g z?=oFkeI=MhM2VRS*&?dJ^gX$m06IP1^tR(?{^WKh>R*LkX2=l8?uhZvCL0WPo?SY7 zb{8RuG&VXo*4M|#Kw}6DIWi&uO~&^i=P*^Fc;AUJFDdam-4!zzcC@7u6~4~ap3xcv z)-y+@z{i?ae`iULc81;M$3Lc}5s-f9&@M(h9S0Bo54as^{r7T(R8_o8LxaxNQjS+J zz#vkkrsu4yPQ2+fJ(4h5l=!_gf$i-WBb~DBj4{1@|DG2ffBfyg{`0?l>(vXpd&q28 z&J1r=N72yIuT;h|7!?hEZp=AQ)p#cT>RWHU`r3umV4Mol^0)?C@TNFd+}%;(K@}Hp zD=JfmD^$9`dbN^*(|goBNd&G62Da~2`XiujD4pFAzD{|A=v*%irWtlJsJNFnl?|y> zCPlqhs;~opI&dy;y5w|CXz5lN>2bmt0d?u=o+Gd{F>_Iz^QJts!b5FrH)=ZlcO7)8 znuz;wo8#Zt6Tt2z(~VQEbLFNx{HH^*q!aQ2ZIgA6{RGR4S8pPvpy-XI!4g+c4iye| zQvKgaBxa|tl?qh~N4*~XHNemSHhvfVakx5YKTFe5QZldt^Rjews0u=5#V%?T2q7wj zE9AW5`Pc-) z9kaT~+@kX$jSJF?zh?CclUpmS+h`3ieg(gaD0}5+je>44++uJzUQDi&^|N+POSHis zKl0UQp8e4yk3RA!VK2{oQYNEMKC}N$?CE!4J)#w>m5RIN=CP8!# zN}z88$hb;S+H2wQui{m47dkcAE1$u+ZDc-UTAm7n+cU3IE zn3~Fx-_9ML3ZGJRdUO6%dpqIh>Gtuh|3~G`|NG|ud~?gz#qBp^aml4p1;CshMru@= zp9SZU?9(&hJ&Ex4o43-mw1CGQDSV-60a1Pd2Yq;CLwYKdp;u~RlE@hb5qRja=uDrQ zj4}v0tY)c%w-W_ZXxg}$_;qg1vw_q{@~>=pLg)rCsi@v<)I1vUNJ8?J8(vw`(kijVAPJfvUgYJ;C2yqY%rUg31z zc96FPzrXccALhjLK~cHTcXhJx+yJn#r)bV>qZQVyeQxmDoLQt@yly1)ow~7rUlSJw z)vYsY*=6V2$ZTsrM*DtOK-`*Pqg6G1^-*i?-CrvU)7i})W&7fuJ4IbyMEtfy7_ zJ+LVoir3{5N11N%Morh_l8YR-IJRO}n|o@@I&M zyUU@2ecmH&#|LG55xT$m@Jwt+Hr~(HeXaexl_>Ot#GuKes2Vk0R9WSAV1J;ms+Z?V zt0!Ac&y$w<@Z%~WePzBEddJc(bgmc^for1U5EgQ|vU^d}cl(ZX9eHgWIsNSiF6@Yx z*EPfk1}Qy7h}JO2$j2R)Uk0qEIi`uy5pa{(ewG%nRPma3ip`O(ai=4tL+Ks6=LR(} zFnB+RfNvPx*x3Pf2;1WH4sQi@Xj3V2-n?0Z=EnG9NZq8Tn_^P>lNxB3p6Es?3LqaCc;LP9(AS z*1+l5?IUFh^wgc}17LrP-+(Xuy6c7MK)NX1;&kJAvAyZ{%Jf3Yiy$3Sh84#s%L|7CE*yVJ^bF~*lwG+!0d4T)QDF5oWGxDZ@dt&7$3^$W~$&g>r;TR+b| zXGr}kKYH#fKeF)Lz_%@!uZ47*(XV!4NPW%9KmPKU`9Turq;v7NVR18KEfcC+IWJ!p zk8{!z=JX?O=aOak(x2TAr9b<~SAO)YEvG-dA2-3%w|-u>7qvM0#3$@G$_U{|-8PRS zq_5G^%|dHUF;0CY4+eD{U;1e`2p+0EjhzLv3g%nwO1|=-0sbH%iw+d?ZmKnvQk0^7 zXssL1Im{k%)Yp15j;;V@9d0@-Cv)LhntY;flk5_j;(Ly-P5>Iw90z)WJjNsy`;xR1 z-sDJ(>(qsU#A4iCjpQYwtP|CuZldXt?d`c}C=w;4JbHkf#@zN-Sae_E z=J9O%Vqzvd9g0p$*QUu)E_oieIbki$g=G8o7J5i--M;x|v{w~N*lKVCB5ybS38}wr)8XVoU z;rdNCU3cRR+j9Ja`VD#|41)e5nEr0Giem)G)$c9l5=)G*S7$czTJr{pHOr5+L>uYH zo-Cj?R9#%O{?gpmN_g36Zf4!WApGi$+>Ot8@GhKE+1k&w>gxZ?C~Py8yT zm+opHy^D@K-QYDLExTlGKDY~idH+P9O4$-<;7}H}6xa#2^2_pqTxTeKSPX7J-Ecbg zcJy=f?532~$q_cPK;lFPS_nu{&Pch_V?+NGElh%f>3>dHKlS!|7JdC{ZsmynOf6cMnTWM@s+5ZD$VLe!}gR zn$BN3F7#kc2svGXx*k28jpYSSug~mACQ}MY!W!Vg7=wEP!?l##4w796rmW3Gy;6@b zmVjuK@~OE^#@Rj5)kQXCjnj=zDbovktFMjC(7~MmM@vn&G5z-AUOLHm=}N>f$gh81 zGBwhJ^3<-q42F7excAny8cs(@FCj5cz62o?XDTK1xOiaP4+Eq!zcb~Qp?<6t#d*|K zMja^qMt2>gmC^rr=ixWs{2_i9g!FfomaZDAxS?QBpMW^yJ20KJeWwBZc-^4# z5E+Q*opDtxrIr$BrSbDYqdJ#W26Cm{8^9-N;~kpz!>+l);(Mo=-x(F7+sr0$Gc z->0woD-3t)Sq}+1M zOPWWo50<)Je7a>yXp5qn^CqeYitm5L>6!*ebS`D*yun01`Wi9dk9JTIzyOIm&(QAH zi0nLsVhJgU>61QpZSbo71ge z##LsgzH}e9>#scb+?~%^ZkHmWBcn@6zg$f(qPih<5xPy}>%n~WS`pD#Ae|Xh@JGJP zoj&)-bI&~U+>ajp>YYD&p@vyVOktv|}l)4cc}qKNcas}<=T6p@-1NA^Ew zqoz}}sh@R$jB9oC;tIA}g?5?EPgB&wD07N@MRg;RDIG=q1f zXOqogFg+0_n}xPQBdFWC91=KCPPJx^W#78H&PEAW$C=yMcHFAi<1O!LsVJ(BvV@OknS7q@TEC-Y5|n5HJPka~0b0;|O6K)Sj$ z(TsFDN?j|RR3}qO94;g6EekD`_fxU@gK_fw#@kW!3FucMbzoavNWZ=h zIbD(I|C8oM`|c;`WmQe@zow|Bqo4YgW_$MX?viAekeSu0&1O1gdY@K9ckj7z4jsjib54tFw0ZHC;2?jnm~ON=Xsa z^|J|3zwU->H#d81C*{BBWB$c=W=Qmd?~b0A(CW|JSTJl1E4Ta>)^ve7{AiSgu4)4|*=bN+JG4)hm~P#TSyX&% z=8_G0-0K#-w<}jr(~+L}!)RpeOF$u769b@{iuhsA4YS7|$owJHwrtwnB6ul+Ab1yvn*Dt;BI7u%ry!5rl z9)5sIL}<@TL(aA-{uPvVHPW-j**MTBHWR0#rmJN1@ZrDbT;3O4>TcH1fP(r+XA zg)-6uUpVtn<5XxEOc#tRu{wkfDoE7HRpCJ@<%n8!Rg4sCcXt;9c6C<;i=i|gLPyW& z+>)=ME)k}biMHA9NC+_%^8p#uyZ}UWlS5cdU?00HDa&T#T&oX~Dz+yaG~V>PZY!$k z$7#*f*jN&Y;0(cSQQA^Te41I~#2qW?rMF*X$mpilDL4{hDe>@4GPX!Q0})vNX7RcW=lP z2=ET55vk;KD1DH_DvUu~Q9X>Z(Ztfy+)|{b$9&8HW914VUyo*GtHC+mYvDaf>`tYD zGqM5E@!%LM3MHT%aTyr!s26!^I*XlUZvMdmDe9UmR5vrqX1tx>2MOgzPjBP($Y#p) z>67WIBSY>=oN76h4ox0Ba6$k8AOJ~3K~yw2NGbCBkhSS9TG7iOgS;BWqF~^XnvM>S z^$3Eo;_f3tbv!H#wH$ytCz4)hV~Uz?qz{_;wXXg z7s*$I+!ehfy`3R~?C+kCH#L)sW&HT8u)G8~>_V8eMxixE#%E7vu*Kunzd0#2SZ%ty zYgr3Vc>r=>sfQp;stfcQ>*$aSH&W82r`uoAH(a~vjSa_+y>ZMqUW}M-LAog-l@Ej7 zMud>uLH($K^nLqDBiWCR{_Ot!{Fqjxt7yJ{Zr^_J^I04yCgnv~zK+aw#farPH@_B^ z8w|JB*eeWpBMJ2 zr$2SaCy~?t{m1TIqo!M+zCz%(tX`DY*R#7-K&o~8bfKpQ5Wd}^EJ=g4^0u62DP|Y> z(}8r8qaN()@<$Wdkb}=7$PTDGx`G)pVX7S6T@DglyecZqCiq%|yH5>ORxak#u~4vz zdX34H`!sZo!kxpNP9S3#cS|yt59gY}aBc#o-!WcRG1$GC4U-2`Ql~r{HvWdZ-;}Zbpn> z97*SK25+TN(bl2+3T@$(w@q7916mlN!)PwuLOE*gzLw3Kw-e|XPG|?=FNKdQ@I`ex|4>6{b&4CYNV7wlx2M5Se_wy>iR_+nUCI0HSO3 z@ryIhZ^$j-!~r`t-3aJw&%kQD>38mXifR)XUPS4um@e1L#ZE*kOHIdAd%{TP7ga&} zGGyItRqlIPe)O2xi6e?U|h!s z$pKG&M_+~0#q!rw<+qvS^bG*EKuNz=-ixuO-?Zu48*Uo$)>HD@{TuQ@;bDC6XF~U7 zcxv6^-EIe9-(sxgoFk|MynrZVhV-yv?*zTbsOe zL*WL-SBTu+M(fS2*`&BXE(Pk=Bjbu0Eog7niHBhxGxz)RO;_@!568_APiY_&e^NYp z63Yviez0|T0?!NSi1AV?qy8i6RjI8v}7iDQbE=e#F<` z&jmH555eaT{r!Lcdq~|(RFfV)efac42Gh0jfV}BvrZRq2Zpz$3dZGm~hSL=WNF*a< zT^Hf)phSRKHBPR5PX;`EY=)Lh;0(w;(cIX2Zj;mAZ7RTx*b$61HG->tpIX(p7R zV@x*T=*AimnB=H#EJ$g5xxDGNntuE^m|j&CNsN~Gf^i>}P^V%Xng!Iqu{RWNlY)LI*FJD&IxE@++s2@9{OE5Ym;d0|eavHkkhX3mv;CJB73dh28^Vbf*46-ncRk^#moo zM@M%L__`V|G{5yX1jEeFIm?Gp@4(Yb6%5F?Sx zHM&G6)f%@c1ArqtDi{xB(b5NdWl8DStr}7$B0e={M<`&t zcPTI4^Lg>PWk@%)Zq6(<9d|kb>hp8+X#JFZVt3-h!9dY~Hq~_j61W1i6LtFgsj@YK zI#zKP(U7Heey73=@dQwMC%Z`r9vB83nYIX@T)lt1iOPYYN2#BWJn9gBVVvuBe=A%?g`e4(7!rHkcPxbn6m!X2zTe#UFWuz{p#_bnC7A2|fIt zt(O}{*GBI)iNXzv7dJ8s>?HuU5znn{jG8Wi9sV}rc@fU7>lVywnW1{KQ1ZIb(tiY| z^UxkaOMm1?k3RdQ&+<}#k)aL7qThkj!SsK>YI-q{ZsJ~~r`vIiD~x_Av)k9Lix9kx zKYfaJqI|O0ktMo!1*E2T(S+Ja={U19RkRn4GGs(`?jvTM<;i6?I_#3m`zCu~t} z7p0cxm&42FmrpIv&PE|~1nc&8=Ft16(76dyoSs612#?&{w0KWJC7|KhDLKXqN!U9X zjV24}MS3FT)6I8(E`2_|NQn8?aRt9rk}jjYOfGY0lSDC6@tIy6Z)qWmJ-z+;ZF!vQ zg~Ivd^7-U>X#G^W{rQ&mtxe;285x3v(hJ)PB+4M%!{_`mgn;OmlRC$^v#n_XJ|D>! zW*H{5w3F?=Tu7&v-~X7-ztEExC8b}%oG!rrzNMxs;)MdzeRuBvKk>Y*RFGaQs_E6` zYSm2+GG{hW-x^QzQ%OPgh<}*+&H!uOHM})-@JWf zPn%l@SM`N^6-H-(!UlkNs{JM*I-0tX(^1nm+;rWwTZXa>t(8CX8#95GKOcw6*P&Zn z{bq)=0b@B{$YsI&BH|Sk+xG;0Yqq$DBBcM;2RWIPm^Gre1>KzQ6sKFHZJ>M2nU-n; zHqq=Q8|^fSj=H(ETdmiIJOqCAsLWOSvDp{)+Vu<9UMoKMwaYZW=JhPT$HOI=BRF25 zbc#tQ${P^WPeSSkV@ox|)d9rx?s5X^B&PGf-86_a{+H5WS_6?yCq|csZX|UAU=;EK zrw4p!h7#N5Vu#T&y#(;D_%IGYg3cgxtyxKuaVI(pLqZ z50Hh}Z{+k7Cmv!t{r5=fa5}I~a5~}Xr}3r}qK-eE9GEZA1SuNbYs7R7Rwu}n4jJK< z5e6LQb(YJtTi@L_Gm}g(tR=Vw!t@QtmE=vf;Mgdci8TovD#+=GktKAN36?nFrMfyF zy(x_ueYggZceEms%~Df}nvNR*(+huE>Oy*aMNU6+SK|?PNkueULBdS%?9BP|;R2u@ zo7#JJ^lS+ZVelW?L{*m~L|Uvz{$X28ud1VCJ)9oNa%YqY?g*zMqluoSR0+P7?1~>< zW*60s?%LJrcOD@CyrW|jf6EvZqlcunBd24A`DU!5)X7l-XB|mX8DbUtXlKga6-h!) zA0CS;8fk_i^I7g~6u!^4-DXTLdtP|y@fRNZ^S9o5CDqaM4XNqW58yVp4d&$oM?1iD zl3u)opd6K&exmKQx4!*1uUyQ5-G?+Sgj28H*uIV#uqfDe(2q636vto<Ivk_eGJ%xH)uB^^k2L})<7SW$6a zd^6K_Ya-ZlmgiYoMMoo^C$#}?C|LkRt|XE^@QlK)3=Zr_&Qk7;`}0;2<-2Dl!QYLy zly80>nxiyCth+6yhg?%+;hUbdZW8btE#r&%AJ9$CjOYsOoeGmS#&5kf20g(k4o>cWmcE2*0DTRr zV|jVz(fyC&ye=|1#uuZeE9b>pwj!rrRZX|#^>q?@k(`kTUWq!L*!bfwUX2=S$$>R z@Vr(%@|9=N&@I0Uq)sg3)1ReOSFV?5_kZV8xYLE{xYO-7ib0?zQWcG!ZjrkDFU6Bh z?kfmytn1X72INgA{Tz0tWvJU^z6jsB9ZEV??`CJ2$>#8anEEl(nM7bd4}OHLk+zSxeOPW4fAnKZ@xa@!Okc{|eE zZyw*;oC+&;9k5P<>KYRyrny}q7Ngdaa?tzoLkr_0*kH!n2{Iqa$*Y1#C3=7{d>)HB z?Ms{Q9&e@_(&w5s5}mFGbsp>v%dRt77^>W!zJELJ^-1>I+_I2N2-BJ1^yqEaY?hPS z2S);$hmLJ)8E?9ueZuJkr}H4_q1s${|6@A;M6cG}$nvH?g_@3{E=I@va_7FA|G_rB z7&U!ZYC2y+)#U@%)LTCE$1Q6*&5igMOz$L!{YkKV!1BBF8+HBM(Q@1Mf@#mNY>`vm zf0z6h>Fz2`a#Y7SUnHn+*s!^BD4n9dL(k1R>bdTT=|2y@JoWlOwIkOA+S^*XY%i)G zy=gIvh6Kj{2E96$V&>}gHNa^vEMm4r>NcpZ;Z=j*a<~Awg7ekM-htUx(0+x9oqy1f zyMbmgwKWN^Es);Ht(f1bYilMj+`dLwjMiDiZs`02J9pB<^cE<7CmR*FGn;E?+K(uG zWzwwq<;)sOtgK=N?S1Xlb@OXphT`(#r-Sx83AZi58Bm{SP$!&Shn8BwYTs}TQVC9=a*-f&!0No{SDOg9v9$=BcI`kSe=Z%2$_t~pV7A! zVqaHMkzK0DcHmJj>FC?LE5bjb1C2p{pGjZ*Gc__Yi2lwYYCdafR1WH-q)-!(zN;gf zovS(c=8ymO&)$s9J#eV6ztwld8}O+Q4=jp{nqva~VJyzvB`yvE!8tsT%4SCoEgf7M zOYfMZ z9&k3O?_~!j8sJdJN=%|l&sf=@lyp_jy0UZGQ7>I?%Nv|!H4P2U$S7TmHdK{0t5G=n>Xfl})CTDUXBt*6s!l0EzS6!MGpN=c7a22yT8iL~ridSsFKv zFGdDBU4xStg95%6nk1=>m$QaJAt9Pno$^qbFw++U8LzqFcW*G=M?WKz#Y!4u5z#;P zF~E`ORyoswbimx0)45!o0CFZ7)Ynh@_Q`TBP+ui=8`;+?>b7_esarIz>sR4&qm{44 zYkPsk=~`hHaP|nl-}~}&dT2be&)oXVkH}OZ{Y41BR!}d_3%FOO_19Q#EimWBSuPEr zTNlRPVgWn)x*>F3TiM7^yL|)D{g3|$Te{%<(MO&^PB*iU$n`>?&i=1I%TVZdZdIwk z8Z})d$}*VSKNN%t$X9=CGmIsauZrs|4w|DtQ>eon52|&acDqkotS?)-F{ZN-eik4d zLEX{qmrWfBoq~;8cQzKrpB|`EtI)|zRf7JV>9CjW{h>rVJ=U9=7L%dr*r`y43>fNh zfb~R`lGAhfWNri_di#C38Olb9mu*JqZjLSEURlN)jvbvM&D%~9dU$FXSTEc*b(koa z<7x!sj8g^!>;M~j`sMeWjFRIIxB>*{Bi&!oU zx2)>LMZo#aPw%{CCySX@Z>JrIxOJ)fw}00>6jomf<$7wDJk~W=S6&T`HLNSe_iZAZ zOvc(8`Fv1D#9tMJi=a*z2~jV@H3-2I@qRU^0b-p-`bGYw(T!*jit^*Uo=~470KNEY zDoTfm?dWF@P&+@6JM+HbRu^^;Fuiy8*vX?~M^BzSIVLM~Pb#C1E&uwDP1%UsjFu6@JFa0z3mj{bbRW6FHXnya@hTiT@!G+KI`-% zBG*oi7s?Tt@wiIj`Xi{Wccfssj1p428{EXe6TC<5C|;4J)Yvebj#|?eV6;n~hR@du zF4edy$j^59iDaB$DcLLt<&mm#{+pj_V zke;j)6Q`$7onQX$`S3J(FC|n;VgTV~;Flp#4{G{oBqY2us3pu}WY7Vq^17pcR&?${ zw>r>xxGK;;+>hG@v&)bF_T_if$mnDz2$`YIRA{KkG%u+xyT(RSXXZPwrvvi`TbB;@ zwe}H2@91}-qP9^s3A4E(b<%`|>A_L}zfAR|gS|Zm5B3#HNcTMa!qFEVH%TvJI8tg5 zu}S=PjTubGr|-*P=|&_k!GX?4B-jvWJaXZc```M*S9Z*&Mth_`x8kAEbHo?o^_Icb zJ-BjUdopz3MRHs`9Cx9(xXkGrt{a`3BNztNoa#;5@Kor-!so4*)N%xPvK-CeU|@hd z(>~dQA{h;*cMR@^)18RuZP|1>5zbaoB1#eIQ87A`(iyGE26b`zpu921=Xu^vUu)!G zghWV}i@X#>Xz@5jy&5yh6;egDsYloj8bRe~=0;Z6j5d^e1!Q+~#HEyez6^XI_EOU! zX(B)#y#wPHpGiJGL3NaZs7sGX#->gWA`g+SsbU2N31wD3CUQE118t@zv57so9c^gh zKKf=%fa&tCQ{XJ)Pl&%LV&*l{;tshHle}5VfV8ZSU3^@*lTe0Snhv!m)K>)c)tRE-MM650Ve{g}RVn>aeixTpr{aZ8>cVjp^*i-2K8a)J);pekX5X_v z`ttW+Zmqczk_*6#zglk?+demhy|P|gY2wmyvzXNuwOb1;VqfvW7-TovI*2ZbouqUF z>GU`Hku~?|BV@gR>7RZ2nXf*(&-6I@?7#p0-~YtN?5}MI+iHVr^mGI0HmXZbx8(6v zI#D{sMvPBJ!{?Dl z#OJ8#*x$K=>Yd7*%H`-yn#}!kbL`aOcy6RQ+}xa7M%PaQ+T0KKG)YM-osJmIkEDk- zJ-;>2ox|STCyF_Ni=m;Wk>^_y)7j}%VdVMoq@;8bWq43blc$!$r%=+9%M3keS9*VY zZJ2QuPK|N4rWF4K$h7*{a;;xJ!6@}`67_4P(L z$CG{zh`;!N;@0X<*b@7>Vn5Q8MRWQ!;`H~sl5YM?MH*e*T_KDwRwd~cf%-A1dvhh9 z;#kxju-q?27K7F;P)9%nKH3T`Y-_Q-V$*NhbbV8vDpU^5$_cP~tAFjeHKcjz?7MLK zl`&mA_%Mu$(*-sCmJjG;q57qOYoWHb7aFetVA*5%F_>;3S{!YDY@pUPi_Fbxu8Gpk zJZH=m5nY!%KYio>``&AJYK5hy+Z&pF=+2o|Jum;x&W+?DaW9u)I!k{xrt2v&8BQ<0 zwcXj|9`bFy94zlbKPKZ8P#-4RyOTslKZ1C9e}5fSd+2uPgGNmkQj>gws80N{N=3<+ z_W39#H7D|21nlOv!<}_|;q&2sBeDbZ}G#+Dcr%&=%||L0DfX^qQfCRr_b2~rIU)o1M8^S8;#!9w!9qG zaSlQHpS}6!OYbO;2jP4dz3$1^5i2She3 zUj;o!WY%zc{iWz&qI1ZIF685v3?7&e%~N^+QBN!Vs(9rAK(s%ebL-t41d zT$3(cpHxmt-G$z=loqWKw|9n-sAs&{3m z=JPwR^Lu`S8wQEuF(srjt!HT81hMy3HIOt8!<5pJ5X8-(#lrL&y4li)^zYAH_v*$C z{d6Ttt%TDVi4|sHm(i=nJ5fo(q9Q19UGwS5O3Wk=hQS_VGor)8!Tvh2cy=cCm?)+j z_jwZLl)5@fip{0uqLfq>GXAR4pS>!9D${TmYI|v7m^hRm(afH5yXAUOD^g247p0r! zDQl3^`%%-w_8NAjRP$MMW}$)LE0J#-NC#tgh|Z%t%gYOwb2Q!@YC%z>mC!@zJzFsh zLDg0xAy~XL6G~S@P-l`Ce+vz14X3x~WX3Tp!uPHlWgJL5qfoe6ejh$%4l-WSX%ab4 z12tSPswS}8X%6EHlhr8fr#6DemKawW$BqqNPX>=k8cfQeQ6#|Un!gGPs z@t@Nq3EiE+DBCBPu16%p7)WOx>q2_PT}*f0V6=40^D^OlF?JV2>1gQ|q#H_?KRxPA zKX7czfdgAiC?lkPF|4De@8bxGS|}dl@yT;?!B~LJNsPEJT$})LOES0StTa>fWP;6g z6V~)?b3z&E7{i6JV`F#RzIhCnyh=%*c;d7GTT_g;t#jtAS!Hza=t`}fvT|b4Y-4R` zv~n&0#Mx9Hb#u_nP`lQ%pk*;Sl>Usw^wUO9KZcl2+{+XD_ThSARCN2XW4x@&PQO{4 zK7r{d*hWydd@o{i1Lu~gZqAtVF;q8NJ4lZrPIwB5C7`(&UA`Alx-O@&QIyj8b|`RQ zj?o0BtEiL-u;-e1UHm?;qnlb#zt<7!>FJ;Yud6da;K>QP3N2Yoc=>?3hz<;3d%^nB z>o4&5XeHF!gDX71RS8bd$B6&a)K{%3?B#U@rX4vkLl(TIhPZc=;XLdmEjM{*FmDe%gGBzI?$Zm%*VE`f>CU1KTpR7@9>_=MbCNWCC$n z5CucXTCo1iO_&>qUS0rYk7^fo;YKcbP1yZp*jaP(F$vM&Ga=_=MCk5{HWH6 z)46H>m~>lukl1f@ZtBB`J}K)_Ogv=s@P4P+q?SI}-Uw@TkGqvGF$dZ*pf2MJQ$tNz zc7qe*&c+~41)ni22n!&r=!A)c4m{9hqLbhLcnmTCJJNZn2~P*kS3 zadVWMz8`D){?Y9(eSzMjD@{`4*6pLNO=S&or%O$r8;1cKl0%S{Io*+(Bmo^KKuAwH z5lo-k9v7cLIc$dNE-OnIEo2myWu#J~6bZ{;K;0v-jG$eF6+bDVLZ+8or*zB&GOH!d z=XfJMmYTkQ(SE7vnx6a<+K}#Wl=Kg_)YMcD53l2Sct+Yqe?!v1iwLK|sao0wTnp>ljt zd}h{$ethpW*`-ya*`y|ysOc)h6lJ4>>0x_mR8ME%NW~>eIuni;EtQmX;d^P{;Sbx& zLruZ*@*O+G>9tbLIT|(HDC_9!oR3b@(}|f6d*TZ#w-xe=wl^?X#r=({jgF4n#RBz2 zdpcsefLxI7q)Vu$nPG-d8#&$V1wo=NBDIDr7?C;yT$q|2I<%J6?h2J^AgJ@N#Tv#% zI}!=(KY*!IbFsseD=83$=?fAs;w#I;8dzQ(s@jJ@azUij0Q5!z3Ym* zUc2iq8D4I~wlaa}4?g(Cn5>Q%Eiv7I`u8F9$?2F`Ja#~m^`)k<1LQHHr|)}W0?ehI zM}>2hM+z+_QdIjpHMo*7%7cF@#!Zd zt6PK}+ivPPL*hc}C~e0U**3b;I%RGseBzw7{p8x%`6;KS&Qz{+3(~0_RU{)Ob!K!p z0@H68voL+d?FQ5TJo|r^hqv!jDXq(C^|%4=5_6PXnV3=C1{L*-|FfWXEuKJ{Ki zZ`N>=0e;X(ZSMo{dprDr#&ZE|Ev&~DgH^}h%K}!NNCcC4FC4yPxh^CM5~;j^#==yI z`a3%F?nmMu0OU{96IIiJn$Bo~sC0$GU`@vr&%HjWr$b%L91- zq^8F(eQvETCF8|x^(GXLfAkMRO&3lJ)Z632O^X*SL{XnjGb~7*)}->X%$k4A!X;_T z$qDKuUsV5bgaeQQ9rpL;uUehQ=1A!h;AdMMNEZzGD^Oj^{~ty2OWpbJ1fQSS=(0;- zx)H^vQ#1+z1HeX2H>}P%!{bwKMWk#1*}A|0y2Z;{ZE>_ku%F-EHh4>aj`KkDdQNJvFo+ zd$}u$==Ia1zMP(P`dsAZrY9k%Lb{N3qEqSTnNc26pG6V6bz);DJ@Pcp7fq=}A@;l{ zN?C{0*~1@2_6CeEWy!-uS>p7XqG5kCG>jTw6rWMZw63yn)22GDRvCxk_p8aK=$8@85K2at|9iNU@!E4hT;oUl?+GY*`h9(v}v-33zPEk=hG zdA`XG9!7h4skBrQ)k6h}$IB@S^aNVx$@C)E%iSpHq`W-oaO|+}$gHYs5lF-771Xni zjE|rT9e0sf$;c-a@XeyF=x{S?dPxh?G776Cf12+lI}k`sQa6vD>dQ|1k&d^<({mcC zjg95?v+o`(t4Y|=MTKT1t|445bWMW#j--Dp*Irq<4&mEz#8DTIj{g3~@4vo*&~!BI zh74C(W|@-Gk!)qL2GucMfQ?zGvKjIA9Uk%zLH{}{H~sPVNKL1`kpdaJXm^^CQ50X~ zNG?gT#Pqo-nGPCXfqf40TuM^O9M37w{gV%#JCpXKS3hXoJB;CFxTG+P&PNF4$q9De zhsunEuCAmmI%fHTMK-!#<&@4X#hqS(%_+&*klnnii$c*Fo>+4o*J1$2j*u!kjY8^x zx_Vt{QY>Q$)NdiW%;|Mf)M+A`U2acL3?d(J`@h7}WlF}7f$m?ZhaJ76cy#ESm%&#iAlSy{B9PBv6?32ctrmxWip^MmWyZPoD?!5C(>MxfqTS50x4yJY#F5irhEEvjfKW z0;FForQ>_qyiZ~}YC0flJT3zA*c63x)s=$SmXsbt@u{b}Fv{Q)bZ%B?rTL4I_9aj8 ze&4ZA9v7tRAKWo^#~8C8oIij1^b@Biwm0m}xyK&&QuTLs9qCWAwbG zrB6X}wzwy5inQ`~INE0X? z3FNmed2QkD#=bxwtbVGokBO`rF8Ko}Azd_q>7Pta7goPV7$b>{sOd~n(}_+0>7<(8 zZq#&P`hMx=KYj6^u%;^@{l$ao_r|3broWgH#q_9}{^FozmqBHqnCCM-@%1YzV4rG^ zyD@FyY!l9iO&wxiBK#&}asK@IhSsl3TYgV*JyY>L%hU3f7<-Hr@xo^F0rmN_S4ZsZ z8U1~%ti3dVUKUf8FMY8Idx>r`v8C~)&z!ULdem(III5*fQ#VTbRB1X2z}CqG3tL-& z%~~($HcN)SS+Pc|csSO2tzEoOV_X(w>)d3Hz^_) zqa&#c)3vNErao5_$2j#NPrdNdmwDZcGyMWgCz3Ek@^>p=aY0Xd?tTZ~YrQ?gxHQ_! zQT-ITl0;}UgjIl|4v~q~`KgyEhvyr1Es>@UTuRBy#Aa+jU6c>%^GA$FGHHO|eqr+P zaC35HDz^6H8OW9mxLwNVqSRh8Oz_{~4Lc7GZaDe;-i;etsGXyHHBrv@3TJYBLqq1K zLo#>2)Qt&U?iOQEhtNk>Vo!gG)O0ZYTS{u&%2)ky9=vREOyy1$J*p{Br3knv8GgaH zyC}y`rD2$T2aD!rlPj57DbGCCn952XVkHiOoSaY~Jgp+pLDDq7bxLM=1&TsW1=rw+ zU`GO&9xr*54N>OhP2az$JpG6r6@3RGA|9GtX43r=@BKOqK9!pqXm`+IYNfoH?R33Q z#pqC2nT+41xrMFJf@>41>>5fyf5@^tf2urrr5RtOdTig?74al)vdrd0yOfpH*mvw& ziLE-6T3uGiUJ2xMuy6G4bZ5qK{3-MzJz}ri_U>NUUe0dV(A-SZQfJ~OXBmKK8K8+9 zk$6k=Ut%IXS~G}oA&`-AMRjP`lj?5t^IP{myZ2djA^rIW#`MAqL9?i&D(ofLn6ReA zqoy-tNv^7+Jx>OfmqpZ&zM6)d-dfkX0Xx(1a8*{7EGj$?eQ;oI0v)T8Qp5ftCzM`M znuEN|ZuLY4WPD(1yIN|qYawp3TNtfXa!q_c82L@3P)D7;*2KNA2~DRM>lh)O7l{Ye zl~k35JfC1s3^w`P>>>}_?Zl@?r=66ILgW`9x^tmn*>Gj{n>?p_)S_0w2P$9P>1~m}vsVL~cka*-L^sV?;ikTu;6w22T>xNor>oOS;3J9v=z^J^0(XuFIsV<9R`)hts)^ z+%C>|^8onZ&?uG3Sz1nDyYVk7qL&Il#ug!OY6(=I5Fa)vl8nx{4WdBF=a2p#VtKh4 zE&T>*>5|i#Znyyx%*}V*b{9+5bo&aWrc*o`%VV@a{eU1HTt5&CPrnG&x8O~eHC?kO zEJa<&9X;wqe?MRrU2QE~Fz3vKdTuT-E39?QW0SVh6g#!fF(;G!2L!J$LCjBl`;I$q zXUK7MZ0tOu`eRQ-Iow=spj;bjrI}4$$_9dTi{cHn$M|~!#ACX8?1D?30`iZ^mo6!N zpJ-ixP9&qjbut;%;poBJR`8*jylLqF!8l@*N@LShp2m79;>vf#SU+gnAi1 zQugoeExu;Y{25oCSUo>)C;|xg_70II9`OY+odD=fO$b45Kb~}ScnUf5i`!_21T~MK zYE#IGJDg6={vs+ZlqN&Z(Xg|Crb&&xKFogI#CLVzG$HM3Jb!s{U}K+p65%CB_6DHk zS;-#=clyQev;q}Pqnf+>+Ik6bCtbaljG4B9fg!RWxwl9o?MfL$5IEEAB`2mnZ^=Lh z?Mw+@)F4Hfi=^NzUs%rr_qzx37Ngm#_YnoBedIRw^GVU6z;4$CR9YZ1exTKuv$M0lN!~%FB>qH5|24 z(_j3j4JoMUDY?{;lG4c3FgGTv*O>EfmSvZ6>7sUG*go?wqH03rGe=fWbgxg7kZwZM z5!KBi78tcCHDdWS*GOh(4eP*i`XL#T#~~wI`s}=Vx4H#eNxQ#iFU+Np^OGqrliLYi zFM~rrf$3zVPoFb;`8`XnmZGje7sJ9aN(Y0jtB8sxpxD51jE8l345bZrGmEO}7JzHc zWKJjzjiEOtcq8LSFExw~y05u<{)q)M=78~BWepdK)CJ@`I361(oY%5eMjw*(5VeAb zX&xMxOr4@nd+MsmUdxQN^w z#9L6htRy5%nBC~00c$X5Bp?%(5|NIoPTi;|T@f!eWf)>==yRWh+ocjN^)@HN?`7+X z3Tf2X-rn!q01dvpVen0|)Supaa)Ymm-bkfb1ITl9#%FR}QUegv-+f6{qXyHZsH?9L zGpy-gIz5m68Au85`L)k?&M@UK}I;hU~8T*@+O#FO0{aL zR9j^JqUPpdUu8{Brp@N-^@H=OxFc!W$`wgYwdK&IQjZCnJHj#@Ca2{j_n^#2)%3gV zJJNUTAX`iVr6F?21g6J}IuOuC9K}>#22CPCD)& z6Um60&XG1-CDANM(j~Rd$m|Byu@P~aP?{MIhXZRPzHoP-C(KK@!JjV{G$eV5m-O?>>z>GQwLFCfXLyS=oufqk>(d8b2WGK%~ zEpmYN!~&ISusXLr6LsC0+|0-;!Rg8*7sk0qTp zr~u?rK3+*lp=P2udE*%e^Dn`mFgZE;ZGbV|i0Q_I{^0G9Iqny70M(|RY0~*Z8L4S( zwB;Eqju9<=3^ARfnEg_om(3KA!sur9#6Hr~4VW7>-C}i}e^?ofG5)p|Cg)QDJ&NFP zcy#kmBDwJT;z@3F1-w|(V`Qo0RbTNCpg#6(tu{<<_}iQjh)2&wA>BfAOFoCmb>tEu zJ4cJfAO0J&5IuJ(KDX9A@;84YU-~|)-I5X0WlzVZ9_92c43!uxZISC`LQapqQ5K3D z1}E|b-x5V8@|asx4s{!hM;{k|V{tQ>4uFE9;&aL9*1-v?o0P_R=|C#PEtE$#k4sm} z(V#nMl7~R_kk=D}*==ax)Qr-k2qQ^Ey_JKc==S8dQR6n_>TA+wEhvV&dkHdJyu59I z%1toc=Wc8&z~d5h50G&Ygnf&57Zb0d3eo_+m?mP=2gpzl7bFviSj0|$Ur&)OIe+o0 z?oDC(Bk6H>;0GTMh69V2*Q;2RDH8B^QheI&r^Bef3AH|`ex~@}Nl_%=yxSjGJm4?z z`inX!@62CZKSbFok7l50DDA{@&LENd>73Nr+qS3PJ&J;YF`j-;oyRe~_-)0r^CI1t zZ1VHkc#s(9JKT&WkkM(C8tEIrpH7hE(21+=&+ouL-$dqn(|{X9r+x}l|Ll9y=aw&O zR})gEORMQWw*na{9z{zB*Z-c_^j8dM>pExop2O~<3Q4O*^h4s(-!!S|wBTfS=>Ayg zXw9NU7M>q$k7BxtPT3R4Z}y^aV1$%odRg#Al1#EhGom zL3SOD(ry)x(t>pM>{+whnnDWWl|29Z_hL*z%nKMZw*C{ODi!+Erpu?_v^r4Kv~bN$ zQvm%^8^>P6Z66)Qq5dx`V`@5bx}Qd*e43#eEG;(TMtESA zvX1a9k~AJ=i0eRtX-zMewqA;@rzA;44Tgg0!<98odSGLEDKDo1D>|*ErpKd~#uGqE zbAd#5EyRPXr5Y{UsFQN1n-Ws0^>*;Ui6W`1>sKdDic;~U;5Vr*>95MJC=c2+b6b0*Mfs7Qumr-S_zsOzC*!aCC3fsOaR{xdNBEV_6Z z#f3p?A3b;$;9nKLW?*N5^5UG8MdY%l%XJf~EPQ(qvVZDqiH`zFFdaqRxLyS5lqxEZ z53HoRfLhn;EFiu5AnmPMJiERDrGMZXd=uBptN(E3=es;$I??IuR)F>3Y=XvdhpV($ z6X!~j6SA`jPDf5(f94Q@P`lVYIuWm)nwpgu4)Q?` z+7}h@4u(T@VPIVSNKw;w8cY|R|H%UnJV|mo+3AMXf%(*`!Wwyp)@`fi72)L;F`ENf zI0)&+F0SMYbrF)g#XRvOwepmoMV1)3P?|&WeEgy29Qj+=gXB!ez#gOhO$uUU|Bwnv zxs1UfFMFJ89yu?R^zxsR+8jziBIlO4x5Rl8)8(t7+Sl%Pw}umSy+t^#*cCznDLIXT zaUh)=mB%KLvQQpW23OLa7+zn=I8jB4ulI@^CrLXB`XPs3$uPPmRwV5f2o*)Y4eq+x zsOb{ZZ-4Lxi^|34pa0V5qZ5l(cKQuRL34xZ&!~j-7-G7Vbcpi6GnYzxIf{%fA>G*1 zKPjgRw{^5A-8vIR@Cg<-3sYhJ6KZ*szd!W^yUqC@Ou6*2N4`C_<^0$RA|}UvAl7F3 z4(J_)a|7QNf-{doyLFj$R&z^Mx6m9!7o<-hy3SbCE;PUR+#`QuwDf&XJVL|^n))LW z)UDJP3GDk;7&%?87mL%C$ryd3pm3*9+|1G?j+=5&Wi%R6kDkzO)atZFtP9R^Dn|{X zM@vT)=`yc;5go9&AsQJeutmOgZwT89p^Wo#{J6#Aa#%&k3nDkYx6-}7h(CnHZi^7N z62^7z?sWJA^?CEJxcd4l7Uu0)K!ye1t-&xxl%Bv)TcfwP3A9fSxtqu-M;}M>u5W9r z&(E*lorYd6{kv(PadBe+F}=v=3m0`W1|U|kU}&f(Y}?d%eEW9fbRrSMe6tTM$-9Rd z&~EB{n)(7g%5#)O#S5nQ!pW^oz2kncUP0&B*XtW)ct^}%yt{2r9_>N%Wyslm|H3?~ zJ(1@X?&9dkKe4)Lbe?wv%M02&YC6M$j^forG+?4k^h7bD{RrYbfx0{|RR4j#rhJri zh8B6Ry;cvzvpXO%J}@A|i?ZL{FO9f+V?VE-+0&H$pXN;m+X3qLqH4M{^*iA7?+eo> zOfPS?V|THTa-zABDHZ+jyQMf%MdDF4eO-IZ{nGxXIQ_$e?J4^gp}0@0NcqgZcvBv@ zp=yOgvwuI)-&+r<3(aGIt_G!Ibqm>bDmfi8=TyjUoH5s=HM$9ZMiZ>Swg3Ca=~2uC z(J#~ARO-Co%#;f*#Mg-nj6gko&romuo;d=g?&P_K7(@mthxvJ69rJr5Pm&C@>X;G=jw7k7oIZkTK(TzmJo@#_ZHJ!{?D{dse8EnA z33kT!VmGahSj$lytW(L>lG&YDUqt9)bmm4_Z>Y&gF3Bhpaw~SPswTSzM@SY~h^5)S zdpD>j>9a3u_SD|Pdp8hA2t5*;!S6l)=FoHAv zUsPO*>&50xjuW2nxu)VXfg)GYA#$!BAO>HJ@hfbtR3dq^`P8@5PBosvMTQK*g63@* zWeH(ltJl%#50liFRE3;wdWG81&ol9+r&N>@^jMHl6mn^-Y|{WI8aP#wtqN@5|NOvHRx+?4bes_bSo?+)tIMwd7=M=d^ynUYV4ogp$c#d$c6CnM8CoTVrQPUrI zz|+5>j;3Cwrn#D(4TK;PCoV;uaStq{+)8tzagB;-H6~Te4Dl((PcC;lja);k8-W%8 z03ZNKL_t)kDA}1gd~Bid6rPUK?+NiyOny<4Hj&D0IK8x#`cpJ;?hP|lD9I5DhfJ@j zL;@dC)3KwJ2-E2+8x51Zhz8Mx|nkXNI$|o58rqAo3^~ip?v2V5#ZWMVf1ismF;kF%dmR=&@4+;xSEK zydJ~y*l7&Z|3(XsJi;Hsxx{oUA7E z%Ht^GF={(aNxO&Dl3y801YSn72=s3>; zz;jdnP%pOf9=tG3L-j)ul2?is7w6}bH!g*nN>6m5-9t1=LYxnf(l}IKKjbSYYHU2$ zU0^Fh;NH#wdA!3^ z7~8t=T)8sm0v#g}^MD5;r`pn9TT%@BOJS$ODlv>kP9GoHRKte(Q>JQHby2z-v#fuT0c=f?XYB!|*vb`h(yWR7N0c`%6TaQc$f^}QjYco9x1 zG(tT6y?Y^|?0E@H|1?TRSN=3*8D0AF8MEgvoe3Hn&IZ!8@h7&AL9unJi!ZT>Mb*M^ zb7K}s8%AfvoO}GeCxqrKgXh>@))<1nfTeYrFrSqynn%Q~=*A)y~;dBBd9Klvd9g(34M<8FABL(F-8rG(?mnITFB3zUniiH+M z9Z6j#7hEsuO-iP^mgI)v^3-G^4xwvJLUmzwRt7OI!_5ip?U_Z*pjHhz>orhZEijf1 zLjbctOuxP^LVx+$AHKrL$-^74Y2z3-*^UrDblI@!&~aQZqcj`^#wjAzwEbIKJH+YR zU*hjyz6Gd%Ve8iI^wT73oxN?EvYl8oFd^W#LG!mKhcfk1pSCDnKQX~vMQ>Cv%E;jH zp_!wnR~MF%%2&jGSH9|lA+BP_oGut8Hax^LLnm0|a>DJlP*Ei8Ag43#fVy$Vfa%JrsiJd~lJu*U^a7^m-knP((#*gNp{ZWp(M+r+Drn%pDm#(ACUJ2tak_j?o>YfX<+(fEQ9ATo0!9aY z*aQfJPb8ZZNn8&u(Ups4Rbd)HSF~rmLzm3p-jId&G=0QvdAyizo8Y zVl`JK@rO?rJ4W!OYiu3;Hn=N>>9G=0l=BHrze&=8W}m+tP{%gCOaeL+bk0#)`T=rD z_NI-b#5!I;>*8pxt+{5u*(I=(!i&gZPMO~-X-`_lJ2%VWZwHQ4%pI~=J2#-Am zk)M7& zoSTKw0wT{5#!2ay4;^ZkLar+a&_(7TIvj5dFznqS(ZyI__;VsrAYgvt}>ITV3Dd_4s=DPGl!zAnXqmH#MfAr!ygCgXT?? zc+vorc$B^-dI2HI6S|m>^34KPmZ9Rdwzl0=bz(AU@^=<^JG=3sAaMITg1)BWCHLe< z2AU*p!^ZiMAbu1a@_w9}jcYpyV(oDUajo}qliX8&BjLzJa_w^#nu)5Ye0ZaJxi0+~@L7 zj z-tAumVNFMJ|IEI6 z7d-IjXhQ*W>|dzJark?h>KQj)XUs2_fG!V=mdsyNOxMZmh1a#MkAyJS%0Fa=FP#3q zO;O^!1g4uyERMbqOM%=AS6JsDUBGwxO$gXCjnBl=sH4n#@in*!b1PzJrYV#zsuqk# zXDk@fHk+AsBJMSF_N@Lh649Y_E(O!Y4>v~E& z1Rc$ZVR@sbbN0VF#olVvWlT>H0J-TlzV(oXW&4BEd)yr^)~j$WI|m`K01qvtYfj0x zMGgl{l3>e7PymV?vNS&urDKQTw?7_JIZC>m?zgd_6OpcJ zQ34qe(>uO3x?ep=mGhz!Qq_>oBf^o-G&ID+&$Oi0sw8Ng{Q;@zGNam-RP5??6~0Za*#?Z<2bLgGp<~bA+Ah>@n7Lg-&T`#B>nDrSqgXoD|y-FeM!g6 zVjz8!a}#o}CtT#AuP8dZ@34wUUq3s%u529@yDqp>JIf(;#M{gS)Oc(a2{kok)!SOC zNsl}Trmss48gKf&C(rIYsS?us59-vDh}82#FlUAeI%~UdnOBuS$FO=!HM=1S8;Dm- zwCAQAS$pQpnKxej@dvH_Sv8qS{rz=pm8?id+Dz3UrY9%FwO1(75r+^VirEC}&^b?6b$Lo$xWOLnmS$<4GE~_El~j~wwM^f(~cC&x`b_wqIeC-eN0WtM6F3o?eX>W zgy>T4%XI{I*`f2v$+%q%q?{E#+Rg%>Gq>Low^ky1=B7W0WfVf06 z_~p|DXPk&v}V9GKTmpgj)k-FflxoFA=MZ9!VVkj`AvLc%>V}WyAlV z6np7iK8x7u(Y}Z;2`ClGF)&Q7)rEeB!7x zW<~VWoQuskjRLtv<=RG!R=PYi+J4FUN|+Nt^(WB*kDedK4x4mH*7&( z7pC7XIX(JD8PQy=wm3%ro6X)H!Fg=Lmo8f8@^suR(0IYToC<3Vgf53VosMidap>fo za>UqN<>~leIFERYVojq&wDcT@S7N>TV-f69K(DM2&4g%f6!epA=tBb^&GD_K4f+*V zUvb^?)$`|H*F#$)e>kw7HbfC$(?D-;{gOx+Qzhn*fuW(sdjs;h$!FbO>GPENsoy@&Lbo~Qo9LfBaDyt z46JU#vl;2Zld_szNLq^yiF@@MU-C)J&w#dE3@?dv5KU2U08)$iVO<%~9H zJrWtGrnIqbH^vtzof6V>e+VU{2;M0&nKOOTn;td2SZcbmO~Lhx)O4^?EY3GiO0B{3 zohj1bX+=t1JD4st-BQuXXE&D|WJ67F9t7c0)92>?{>jGC|Gxj)350;ECr&UXrb(i$$j=`tSP^qFfcE|1L( zzHFEa2^+d$;{{=PuQn~5Ma)#0svA?K%o&yzKDhL`y5cNXs zd*}d^Lbe?Bq)ztly8tVj9g3u>iqI8Q2N9qoP)UMyhAAeEcM8%Wb#p=uDW2~lyy>P; zGrlnEU`-9~iW(&Kg9LY!Za6$BG5y2mfpn$~FP~JWn$l9;M0>mI(6Dd#P+7wvyy-Yy z=tYWft_kDIH(vS{&h&1?^r*tVb!%s54pHk$PB*G$CJz&TLUI*JG|Es($T5|5Igqk1 z;(+AaE9}jwIMa*bnPGb&HoY>#*W(Yl+(GiGGm}Dqk1$=slB6U$L2{)yEHX}SYNGym z45r)JrX#^KfA{Ig13j#1nmnlNqHOdZQr{w~<&8=V_&%N2@!P5lluif_F2e zm5g)>ioAF~upl_l(^FGD$qE9&dr_(ifdZ0H4Z$c_P9+MSgCP~CqwBT zTc*pIMT`qa49mbHN3HSaSO7XAk=_*R69oH-U!aJ|LyX0f@=aJZ(vn3TxN_ z0Q4U$!}GGO%hMrm`j1;ToZS1orKXqE$=YmeLDgV+S4&qH5$j!$dKdm4s#w=mW(l%$ z6LQPbTfdoh=FF@A@j+{A3j%rSuGG3JUfg72yOZlm?6d(Qa0iyf#jhZA+9ct_E}`SC z@?$Epd6DVBnwpSpJm@L4UCk2iNtj1ehtuooj6IzO8F=}*S`{BW28z(IMi6`$$wJId zXl`xw1p}?E!Sq}TN$Yl4lrA;hn&eA=@&OF$qV&3*b%TS0>jo7?Uz3@hU{?XD64EKp zgPJFN>gnt|lC6t+1*CL(Q}LS6Ql0+`3+f@@WSZJy%Oo2=v5*f{bCI5RWl2#6NiN|c z^mJFL%Z2fUK?-iGxJ_{`7d%ZDBSiV=$N>F5E=~gu?j^YKUi8ZNbOni$@h>)yD8)G`3Z|pecMdCs7p<;D{>4u>JBwyBiZc7uLb{ek2^*qfC%VE#|ZhQ>W zC+bH5^)JOJ9Xb8;219b!B7IjM{7ma`7Bu3-9P?wtqMVM90)uMCjqEDHVla9GXs=0;ZoO}mW z8#{VT71x?e9VS*Hn#Wu&6YF$s>n6nF*2QK?n+n+{4;HvT#@3I(-R^K{U;$nC?co({u1JHuQV=ZlI+3%tQl0nzInM5Ys_67YKh0e`x` zX~~jnuDari8O4pzbyHwtuiNXvJ6S)_N(`|Q_kwgQO-|I zpbw_ronQP$@xaK|l|cFU%1Ga--S?ju-@cWg7u@Hx0j0-KXa4GiO=JnEaupp#wVl3> zV25vfE#%zl&aWruu^1FjYs>Eq^z;r4-LnKQ4Q)vSjmsA-$Xk%Ncp$$XTfDUQzDQ$$ z5Joql>45<`*KyU1bZ}2(uw!EH8=BF`Xk}=|Yl{t}MwCqKtQPYbB>yvZKoBksl>9VIA>kDG~{fOzW2(!(# z-el)pR88M6Px?<^tOde<`r(V;<*QM$FnghEEle+us_6%#E0oxnf|@?}4@FInak5Yw zPM1ra{(1O}9btD*)7r-Rd)k(-PP^_pk{YQmHCZs%<)y9WbGng6r2;dqr(^7fe(z4B z^m++Q|J)^*Tp)ab^c}srSqa%1=taQ(ohGx{C$@#3Mag1vbFjp8tO6|Lv!GFF*;dlx`peq)pH|JjorHH z?=~kQN0Zrj^1Wts$9PQ|GmTy1NN4PoqP{WG6I2~3Kkg~zDca>yQO+)RdtzKpcA{P4 zAGK$&dV-T*c`XWGR9b34hC~mXDm8_L#84xNmldT_K1w!pQM2FI?{BV2fd%Pc4;vz< zrx;9s&V}a2^fK}i z_zt$Sa^=>o1@j6rHj!^`s;pCTGD(rdh(hwAk}#5NU^>qx#~%p#BgqKkbK9NCsm_d~ zl1isKK{AyTmHB7bFyga zD=3oo9xB0<90t?zHP{kNk!w!kp#q>WV*|YX`pesD93cir&NzpcLV=>=!yfF*hP@Pn zPIDa8S=#R;S5xnqVYlx{UWcXqo!1Zd^i&QXFLNS|Q4}dkcea%MI zw{(`Kl-4!<=->X=zy18J_gZ1^iiEoU=B}(l>ETu3aGi_BRdGgeF3nO5I>(gKtZ;K3 z^10q`XE-%8F*Vp49}r*t9DeD7tVb5Pnhkj+u4HEXOMQWPAXOO#jjszx-u5eTDRNAl*t#XAYyAV8#^_ zgl-l#KSRh1gpQ03rE_9H-JrD~`;!M&MUOE!*I6brH(;*h^J71t_|lrprO}P7<%zik z=HGev+duerG>~xu)Xf5D&1BHsVsAt0pID*G%q5e6t|dr3dWnJkD44Sf7}uo+;-`?h z*??}W2<8HHMl7gz;sme%6)e6Jmgr(=C7Z8xhHyC2N z2QN&>AE3U}hL{5;V=en(MEazc9aPeZ=n|E4|0>@dtaCHwGNO$lAt% z;1Izs`So;b9$KEJz(i~!zHSczE);sAhj*il*Ehb@cPjs_k(DbuI$j#5;3)r%hfchO z0MotFyWP8;p#)pkr{(o^`@M7oMNJRjKw*K17ZPOZF^ShN{`&H^ueXuJ-V_-pw7n;i zzkKFEVKu<5)t|#xqwE%zEl&U3(iuyyC@!9H^^)1z%uL$uCOsJ4p0(2O zx4@i-%LBfNnf}aK3F_9wwvalwudBu;i{PiOiCr?~)S~nYF}=NlHs+)s89ANyU*)#2 zZyZkNa})6SlU+IG3~tL!Q^R&~LV9MVvN=egFkmh%PTeH|b<16%lyV3I;|tVOlnksZ zz&G0%-vr}ro^qtRJYPziHFK>AHa0@ak-ApMUrSA>NjXwAB zL;K%-Y325}5z{fJ|BIE%_^mH|jq74qr<6=b(=PU z?e?wwbkcIPs05D##Fm(7)rCp}M!T)vRL%4C9H}c@Cr|s?;h<+-172teZ|U6AyfW9O ziAv-J6Y0s=EE!~xW=HJeo`T38ZY;HZ?URz7G>^kgD@vWUd7aGPBxqHhc@4LJ>&MM?Yx$z{xf#@V8#R7UtpVk>D?+tq@cUI*Uu zJ0M34nd*G-3fNU)-a|f*RT$rKQ)SooZwx19}6xO;-geC7QqqdmSuDCq0p4Iu>vR9c36CR%NjqV4)E2lsY0|Kd~jaNcm(C0*%+e z=|!o{fO8Vz`|+Wo<}jZ@$Qtj93&)T4V;M*%b0t@|uQ351BSuk-vyypYCBfF-UNAk; z)Sc38i`J;hy4RhO(9XTe^`cB5Y*NI@Fd)Sm#9L_D&YhV=a_Aq}s5sJcQb>xyT9w6! zk%m^33&_gO?uh6Y|6O-M>DXB~Vt9#qUaXWC{OD5DElQVP{Yzi`^DmRwxMB-vj+zdh zTSB@;>iaILB0VZ+IyyRs(+1K_ndHSj^r^HSg>(bt7P3$9dKACEy<#&lkc271>ePmQ z`!B%thaXlc=!KI7=~`#x_ZVqUGPku9TW>-4Me`|Vrz{#gkDWJqx}}zXN8~O#pP=;b zSS}a~))CVmd4g`J^0`=yPRa`h&LOKC(~H#fCl1{H;GbhoA3H{z`Y~lP#xQ-ZkFNa?5zw43bB^P%`pOPY-|8TL zx1$5oI7x{-lg^>t#dIBY_YD~ho*ts~2}LW9`0JOiPg_liYE#qt;#VV`yWATG@UBqU zxjOHjd%kwv*N1w)zGUI71$bb(n*tp@eUa|*$ar@L?iY1D>W=JwZFi)bt`hH^=0JVPBiRHy~GZm3{cl73;8rr?Pt?iV%Z=i9{Zt@ni+j$&FZ_Hm$cshk$=gvt` z|Lg}cPHR|H7FE-&ve77_>&!bcz5K}3j^cR1oPNjmH-G<3Oiec%qNbzmnVoos#y>m> zgVTca&034SrKVe${^mi;{em4PVKu zPX|&>jHa0oOm(4wGGugv_EYHIx{2SL`6Oaqb}25m;5N2VOec<=fxm~F001BWNkllHY7sfmyX45ZYS*p60Z<=$((wod40$ps5)+6SQn4-i#<&pgkix*;g zMVwO~3&oUbl651_j(?h-J#?JtD8kB$LBagXETU@=wpfHig^M`t@DU*q#@%W$I$F9Q zMwl+wHN}xd@xt`1cJh3PLVtC zu^%U5dLbi*siNZ0ao_Pnhepo5yZxmRq;mne1uFPupWW>epqifkeoGeXV8Z!Dt27%x>=9&#`pZOZ8^@)bE7T((h{i`W5dodgj3 zT@{-~E49{^lauc8cOEL}w&&pV$L$c$-e_CFrqNN?CVVJKp_01fDqiI{wZkdLVnjEc zdFe+wJqgu=ufOxN_wV(E$!ytVJ96a6R*&a+(K`GT09S%?LUPlO;5mmdQQ4Jq?zDTJ z^zWtVJnVNb>u1Ewcu6=HO+W(1cZpt`>nyyx{WWbypq#f1aTW{UFVFPLFH1Q<7ho}}>K-E6^!O!9J zS6d%w_BFdo31sZ=Z^_CiX%21(*DfOCB?s?ELQs=fq*~ag}DrV+QI^ z)~*&fJteEFrMbVkvV_E(5*jJh^%HxkYeDfOo8ZIdC7?hRYm!Q8ld7EADYaQ${jCW} z!Jgh=kXBEgC#f4nJvVN28D5Be`K~fw{sdM1U>8krRY7a4=~;Ff3SmGo-gIK+)5Yg< zo3KOysYLDsJ`oIOs*u(#U`7dd61eCprN0*+DF!MSOR_R+vMOmd3(jZ6moyg%(z$-T z$vFqp_3_Mc7EmF~;KpvZ%r)s0`0@sFv)oa0>&B*yf!2^>UQ{7M>ruv;rRk24hut6| zehbqjt5Xw#smrM8C2HoS&~?Bcs^?>A6d5R;ontwP?Apn6Rvs?`&xQ4Tc&eh`_$2;) z5k|-F^7#jEiaFCcBSioFWoB-~by50#=;<^lySZ#f38Tdb}d)nQ^XLOJI|)8;N! zLTXfT&CQZI7o+XpdK$fulZhj@z!@W)PhM&u-56e2XIWxmesx?n-%(eiedkTp=sr|) zBc>Z+U6T5~W2Y_q%V|Y2vdiKqPf@K%SKN5R&CxeX?i3EzoKsV7qBXAQ0p(nm(^j+- zIJffC%~fOUpVPtqgM;EG(YBiUms8bz^wzm;)I(v4I`Y0Ur(%Z;4AbX1&Pdb00 zWKi4f@9FT+JgBMdn)&muyy}Y85fae-x(bjV_7ne7oF8!a(&UKd=RkUWWMFaIYB0S6 zF&z&Jafj?B#k4}kBN^=Z1CI~nKR&?xt+(Fld+DXO&I#J#^==(7zO3|jG!~PJ-hj@$@VO;^YFVN%j;(t%8?+tEzb$vd2pJar02U{a+^Y3j-8(Q3U&+65yuUjyiSz9Bq zkWGslC63ctX<)pAhl4pTf6s{_{O6HCgg_VU>TZA2!nFEGWbtdWPUH=#^0l5k8hWb^ zAp7_6%b1_`&|;`OFb=^FIqdR^-fBMr42z^3JH-U^& z(~UX(j%U741?ka$_}8Dl@~;N7wcQ|JI8xJPO}FCGqsH?Tv}DWmf{JeB^eCpk2&PB3 z$({yoU{L?ezlNXoO6!Rk=vJ1VcJA~2tOdY?%v~1S1?omX|9!TkPdvRz=)4HiO*hTh zr7>9j6izq%E2oIq*syaHu4C7qJiX{%CNG#=;?8t`+?4*zG-U;gTyPWjW$wseJDbn^ zv-;WB=Pj87bjPl=hDuZL9CysptCy_avj+X$JVM>Jxk26KsjCda z8Y64iPPB~zl2N)NY=QJvud-+V=SZNBkpvHNhu*6 z-0=L%FC(eH{QQQ&llPvitD`4+X-)-VI!Q64F}^+0O(yM2?~Ge) z9O2OM?n9%a1%%{~p3pryx_xBSHQL?1eWZKTb$q)nqaSrBHOY3U`=xVzBd&RbK8Aw{ zE=RYw(|?F+Ldp;m?D16k;Z|TUL9HND0Y9bj+mOcxU;o)V?+Ro^Y7r z&1!%VyNBAg@)VKg6&aXHX>Sp3a7-fo)!VSWync3DkI$2C+awk>d&yl5SXfBfF40?3 zc(9sqcO-AUM|CSrZu-Ez8{Rzm@(=&&%yaMU@^GV=>nn-Esjk{^xc_zDtFv#u%*hYI z^j6;bZfARW`i@<}U{Uo0wYI=LU;T%_dNr_p)Z0l&eAliG{SVaE1;dW?(Q>97{39h3 z*^1)rtR%GN1Yvr41#L-5v}{goNr2JKu}h+T3we=QT_s5ldtIvi?kJ~c+WC+bLF-7*R!#AV~xj9Zb z)hJokGm%w|WAxhqAB#yvC&$G=dX&@+s9UTKt}}h<^FaE2U;K0Q^xJMToUWV~jxhRp zg2>N*O*V^6;Xr;E{}0=ikSWb`PUTl~$LC+=8r6e*uEf>G&@ zjh+9&`5%n&#}QpRO5@QML>8=r>Hls4`vj;9twq|CC)Sxy%voX9S*NjcQp}^a7cOV5 z(b3I@(F>5#DHxrAbkZ0fqpy;Z(jPG;qqx$I_eIir)Sa%2C9LloqaQ4lx(DzG(d4J17aXZ_S$Vg~7 z+{{-$d{2&}k9b3$yC8%p?(=p~I;!0C5GYS+GfRGg5A!H`n{mZ8tGpYVA_(*824;1$vn^Xr@FER?pGhNJYkhR%aV$?m|UPUFsjQ%vX0@wBGC$AR^?UNV!k zb&2X79eo3lkq#ajay*9iCUkbrC{~dOnBshNb;?5{LH~GbWTPm(aedGFRjY;?*MI%b zp!7doo%g3F?rBs*b}Tr74ljawN2kXdrbIQ6w{Z8lao{~bp=ba~_eOT-(Wt3-{`_n5 zPBqr={`ge=M~$cQ`}zo{>F9{`74N}}9)Q;eh^T3dVme7MXz6Y|>b=qT>9c#%-d+>) zrhgLFaiITeOifqf3u=1WD?hco=~LD8{XBnDAo{#KFR1A|`RO(4FcdynI%;qoOt8678+>DZc3-{U`p9`^xNc!8zKj7X0lFqu%MQc~WU1%u@&_rH%uEZvuTzXEt=#m< zb1WH6Sh%W*Q;wg+^w{O-($lBUoQ@ZTnE_=>leXs8ZT!x2b7$5)3aE{MK4k`^N7uz5 z9U$M6_vlSaujj6zcjjxX!}V*HGR=9k{@mA=lA?|UM$^pbqt?=#>x%OxG2I$)SWnn` z0RPE@zT_?l>pHQwyn=2!WOGxbMl>h(botad$;m}h$3JbXe?eOgB0I62`Ur{D**B9D zhhSKm86T!yys{YMac`id<9Pv;kTqq3q5BKekeTHOCzYUhRzZMOKos8L6xm+L|Ax~M z&HE2)dj9a?lP6DNvw+BUmDExwSAhirNN?Cw;Bp-wdG{RcjX?F4|6)2E8H>vo{@Ns` z^ELi~950$EA_XVQ1khq|EHm*LB2zd>0x9IJ9Zxy_9&cx_H;(_5x!E->)rEzHI0cd_ zF<%dppHf)XkC7!5ww0$ifie2{sCuzQI|>q9v__?E5^`rz27NT=mJ&Y}NOdVwqhe9_ zNO!?;X7D%~(CDF&?W3IQc8@^phqjNrt#kgM-?_c-;}v5ck8JNANe#C0tA}26uA84u z2;GK>Au+DJoZVnRqJBf|4o{~kz#Ud-%h?Sjpmsw;qCK5{J_=B8jV;Pt4B#l2)_)}@9L;`QK!=saou zNNUf{nOmBa6b$YtO^oyS9Y@rUl-Ts00(2v*qo#isNUz&bS9K6qdJBwB9zAKCAy252 z-soU6m7yvjRm_XQbvw2nKJ9!?pj&ztQIU-MOEHUy#9U^Uk>a8cM0<8AMig2MSraOE z32#)mgtAk{ImyWxn+RG#de7ER7N#>C=cYDP=63Fm{B`!~l#qLxoE-Ln=|MZql2reR z#2<3dotOWyWaM_XO5M8!(A-b$Da(5u7PgT<`K4*>5(=9p&%Pl~+_)dyuxQ=jcmduRH{|2Q0o5zd=omWFJ4y((HE?AF+G9F_9!+GfafFc=hBa)FcbzaaF zcTQls8X1As7Iurs1?gB|Tv6ei|Dt(hrIUls!aRfRQNf(`Br(d9j@jG`q@%gxi~-Vf zayW5e$D>auc9w2xJUff%B@`HF!n|iwC<@}YJ2)>6NgY;hiUd0a$g>x$zGlW%c?169 z#?E9cHl1Fdhp_cvv-37nml;P=Xv=l2~r zz(?b}j)v1uKX&@DzQ46V{cm4->!p9u0bdN(b+Nh6$4>#}rX6qfMMhS37vJ9)G0~22 zI(_Sc%`Yq5#&g?dtaZME~JrhQfkJBzW3Tdq_3|x z($u(k)vD)Kt4k9-O3xwDtI1KM_cM=}4T~l)-GKLG-pgbODQfyNn~!alH~ss67gN*C z)`P@4xXev~LZ{^d<(8UmdD6MGcG`Z!>n|!fJ&LX|O8Emi z6aW6asWnm(+Cg1#P~oSz}%F8F=cG6ne4F9R*NBv{9_R$eS+WoxHx5WKWm# zMcxr})|^btCe|AGo>+a+!iBeq_1vllHTR|~MvuB6dWMULeu24XS|bGTd+C~)Xz5GW zTu&d;IZNlS{@R|UYnINLIcMf&)33U6&E!2!zv+5bPaRBfn@m$4p|xW2Di?EZqjMkf9z#??7LSBis#8*Qbn`7&0@n!Ic23pvI}N4thdu zG`1JjTRP+t!DbyID!U(WFqEEANik{k^7;*L_1@LLb4FaW-rRf5~gE(ru)1M6TIX&sH?D#*LBq( zr~mBz*EjSO<%U9%)8ppl5}IDNX&u=+gum7mI;*;0G=_O&4n;tnlcy{pQ-XER$ z(XAVH5o!VoXJC1$ZaKMk=iVPa{X>H8e?{L|gXvEm*>!|8#wY*!$o6;Ne)rw((bBCvQ0gI*$bKoIe^N?z zW@#6(GT~4t*vcrPf0xAcs5{-*U)1Ml$BqP5kK%Y?;8<8#mXM4P81i^R3fhs9ZXg|Y zrlk0kcyFMkmi`-2bOumbU19(A$uzAe(z_mM_E$?3P>zL{=F zpr)ZPDe6LX8L^+3O6it#9#hRP4d+ua{dPEA1*&urJ&Hvg;|mevz&{O(j-jZJNms|T ze%?ea0_XG~h1?BJfBHNI+EbxhNN%oXU1(r@%6XF$qiw|G+9Y;a>|Ua!rGj)kFN{vq zaTITh#paf(Zit;lE>d#37L4l!PG2E4ec!RoM{kUlkj{n3!Rx4mE><_Zjv3vE=$7|f z+Bh2_smQX|0S*y&o~^6pxjyHEg~e{t$sp& ze}NnIJ4jG^N0>5FZ!kc+BHEBPwauPCyX~5*W-RXY?QXe$#q+Jaj*8BB=$bKhj%&|DNIqZXESA!t73y(c-+_O>5ic z&nKxJ(@R@1aqKJUDKbFe>c|K&G+;XC*5bF0{ zl>NeV!TBVh8v@rXrl#Y2F`_zZ`d4FWy3ybVVFX}Xupsotlg?fJ?Vod+sB!LBZ%Tt}HM(a9`Wh^`@sb&Oqjsnf|9>4Ho3lEnT8a+;~> z35O}%@4(%X8{I!%4sinI6yRY&BtsobV$g3ZN8uH!6X1v@SL$Ndegc(oXtzM24Sul; z(&?Xxms>bvkB72SVcS$%1Q9b`SxwWQl7!5Znp)NB9YhlrXXTdGI_hva?>+o7g8Bw} zl&T{qC8VV}lG7X7T^TObk{<6q{x*gGP&!}GVsuO{GN;R-&az2q#0{gY7bjjDzA0d! zx$Tt8Im@y((WC~fiObP0rD@aBeQs|!;?31I*;ys{DXOY?5?B%{w;iWn=P-j8zOX%| z6*ZIz5+leawB4*r^(3K~R?N*Q#g$wXkIcEKG#J>}p`QqVoJ z{ZL1D1-_S2)N-lm*kCIB?t<=*PAnTcasH!`{S~9y3@gaFj(J50T*(d$5#=dl7So3w z3yVoCPO@cCuPAf+`>#Ls`rdm<4y-Aw%E~I_aIlcQ7e&o9QYC7UKZI859MMS?GG5Zs z+-2{oDKvb)?d@&Ynv>OtRQj9Lbi&Me&Lu^n^qSO8&3n_(zZ|?ok z-#_>CAZj}At??~owH)5N^S!6ZfKlP^D**J#lRI}k`Hd%2GCjeq-x_`U-Cz9T-FJsK zzIx{VGsWxA4xaTVlx8M$)paE#=Hi$tpEr-H+9U^wHYHtIg6-O@68erdqfm!2(k`mV zE+@-AE4!+HL%6xQzw2P_!NU|SoE&_fCQa?^G)%60x}8B3H?QDBWqVRiill8wn3o+vJ>JG=V=m!B7+%n;?c#LCQasfV**(d? zGcq`EoWW=cGKcTk*+bT8Hua|Q7=5IDb3-&~5~kCO$PuQ5G)UC{+;WOPZHWn?P+~db zGh8v;v&{2Y*(Il2e_WZekyPG&C|xn2>RZL*XK01n`OH7x%J!V2)m;vcJ z;!cs-g$A3F(_vB7PsSAVsAw)Yx6s`ze43R0@WT{gg8oMZ>R>u^$?DMhX0&zgIBFlgzrvLL0?z=#H)xLlN>&Vhg|kewnK|2P>b=+)BOJG-%f zke*1&3hj(w*no7Kj!;2o5WF2~a{C(7X3bu5-TW&T<_DVUn^4l}59B3Rz11J;Y^uM9 zd~%}F2i78P4=vAIl6GBMevdEMG!UR}G{P-zl&n7f*5l{5yuc^O?2}=yh*8xM)lZ%N z=<&xtdh0P6U@T>QC3HSMB1OG})0ak8G6&WB`c{tg73cSzYs?p6(B?r!CU%v{QY3Lw$5w>g`>->MPgQH?qJ>HKMFZHFC1vrqAx2 z_C}>IPGI>2sz?1VkoOOtxkFuz5Yti9H$U^jC)9LQbCdM);)iU#()G&x!Dy&2fZk{Y~5H>UL(8cK)9mdpQ^^^-nrZiS8b*2U9ZY41V0g+NqX_XZXWUkQq2Q`#>I(Gl-|G&a99_;LhY&9gGf|{;+Ks$DkB--?# ztQM~G^{}7T?ZDw8$4dzbBV>gmPFKa#WReFK=Li)f*&1-wknOlJ5O&EzR^fujUGoY^ zp6NhTAL-og9v#K|B1OG>WJK0%ioI`vP<jPGqNXFKgXt~RSydFl&28Pbv2A84hF6r-)fv18W*T~NC5y%QQJN@+l3hnQ#w6s z4X9(o2kd1I)1#wcK-xEdInMY5xmhH@yBGlxy3YD6F0z?X03U@g4%=3Sin7L(BDdqk z!SjNejy$g@AUs?~e+Sdegm!L{g7|M#_z&2hAb}oGXY>=@!zxT?7ZVqe4P(Xw2=mcz z12H-J_QuG13yM@7rwZNHybcGkUtQ zri(c(-wP$H>^>q4&qNX2x=;%WaEgM_$kWiiJ=+P}l$F`h5aO@f7 z9m49TiGr~(9W|ZqM&~c)a-BC&ZNa#8#@fh2ZfgVUQlYsfi^a8VbiLWgT5BolX4$%# zhZXZ8WJgQ?4qCe5@h46jbGqnU;}wh8brENe!Rey+NA_*GU2nndW_)w(88AKiMoB-P zm{80OjhjkQ7sVa)Z|GEd3tJf#-2}iyQ(#=>1cYO8p@x%hmeC`lw)E|e?KTQZT@sFd%w|mf5u`U7hpf!<-wyK7J~{@f2x| zSZUZ-Fwet2fPjB|pm_D-wQHMthrYIC;iEIIT%GT0%EvN4&#QM4YwQ9i@fPr($(9DKTI!Qxj;>qZ-pL4($0nHAMUhT zkpkd^!s13Xd5zKjMo~5W#e;MAn-)meU+~J%h*UWL$LTZh3dFeb)4b{C@+dM}NcvmA zREQg$CYNGs{<8}vka*&%qGW3%AT$?S#}3xQ#5vUT>3Cb#TsD2?)w8agbJO(e_gr_S z4C?6Vf4LA=U%hHRY%Xr+HUV^VQ|9#gg$u5h#4a4y9di-)N)C)rT@&-@BfsRyZ+SIh z?|y|1qhX*2^}#*9k+|8dJLXAJM@`4T9Y!GVINXu7L7H2jvGlmZjyTvE)RkKVSx!Dz zd0RL@UUI!a?NGW=^o+_*g<_T6xN@t=9wGQ5GdruUxd7}y6Td}4-B>r;vvbQWOz$db zK^=wy72I7?l0^6Ta&*S_vYhq?Cu(|w>rhd_@k853#pEdH+ktb#=myv^zDQjssqtU7 zZe<^C$VL%06BI;cUl|8smJO2&!whx>czQgY?ud;6Njah2b_NE(6rm?ny2|#lt}w%g zo?d`0Av;q!fQ1KJ4pyVNqo`+~&XbZDBD~z$K$2xjSZX@aiD0^z+_isn#M_D7(=mdZ z1zmllqubrFy%P-x8VA!y{T-vD=RO)cf$arOU-{D8+i}WtpX(S+?&MW8C0&qg0(cI# z6Oe67KE94H$B-vkayp%g@MmmWS5qddM&ZFiQgw=oj>GBBGSqYzEiLIAkMAQD#kuQX zO?GW*X-$o;__No~`od0iw^7<7$&vD=>)1?FCoJi-GYzHEGilwr@K%$Xju+|h$@gd} zdg}%g+^7*4v53Z-j=uf8FrDVHXWu+~aOab|b`alFhLry6U;jIYU;pCVN3WjwUqAWL zTjM@&$hjyxp_CVk${E7sRc{xwLIO{>FK0ALAxhtE()ew@hiybfVv`BlG%Bb%Iizt zT|sbEONWwOWtr54^4mhwCS-9t-By{9v=b6>O~uo&N?oi(=|tQ+h4h)2T;*h8Mobr=A9&^f@hb=R9TlG&NH?H<6x%i4bOpWW0Io|;H*_AexJ04- zQ~c;rL^mhLR^0xO@cbd>4~=mgdjU25s5Ob$v2>q5cKZAs$K*NDQJDU1tCJC+t%Hsh zXh+Y*R#~f~mq$^2VoP1f6eaN~HxpeeP&a?piR5%0q@`o?IsM3EPn_m>?7XF*KY}^k z$mi12xzuzem7ET%Z^4{?+k-c3HY1y3TUM-y?hIGGrR*(ihI5Xmo%jkIZLDz3+c z?p|BJdI=tw^$>f+O=Jpga-nn6K;Nk?FTB9Jrwo2ge1dSQA2<)FYsx=$s_*eWj&Jon z)(5G-1*q%DAAoKk9s3L3mzPG~Iv06s9J~5kM6QgF^QF7hJMwBHV}jncp`HLv7Xs90 z&DzuG^XJ#Qdz*S_lteM>IBu1``dNFH*Y|aJydB}KVFg9*&Kn}=ea|&%O-*z=+D-4$ z@xVFk=p*9;yZ3yLTGGY=%r$|vjf=nXm7%q3H}!#BQ}Q`q#}rxa0f(w)qZ9Q10Mx|6jfG)1SVg%?!$`R5WG({{2)H$?Wo`F#W|3 zpWi8gZyFV%Oz`@f+MbL?4G2)&Q}$bHUOZR<PU5d-Rrrd8NTdI|b{v^pxV z`RPB;W)U}e-zamE)Qwm@SA~ugE%J*m^pecT0gtSj_Hf3I??s$0HC;I(YBpJ$&{b1| zo29zCA-kLoLL5pnv$9&K^0+OOUx_bp&?BsWW}UxL!Iv1-VL}6Om-QV4uV?VmlC*^fdvd$A!l`cZ^3y7wyl< z<*u>fq*f(4K+&X(GUvMC;o-813|e;t?G%C~o) z`}Z+O{rum)O_}K^Wl-)86?S1mr;E3gbetC+Fe)C`f&@OQZvaG$uxYK=_4Pty z-PzLBpVd&-@b=s9N=w)D@4xs({h6Qq&oI$U$ zz3@2$)ax|IH^l&D$Btlcz~ktMFyOR@gS&R9AL*Z{sS$^r51`Z^JXpQ0kX<(MsM8Me zJSlWOp0PsQlN_Ni0YZN6D0eQVmmC@v zxQKblahU;5GC`@P*n)QMIGuD*j*%V_vG2)zZn)p*#L&XQjsY8aP5QUhq<>w)itHi% z-?D?n7X3{z7%mWp&^g|A!)>=&qB>f-F~V3Ifa@w9z3t1l-F)-Sciw#4U7UIFhKGQ3 zNF7(Y0$&i;IX+`3-GKULK>g^LVj0EfXx$=pj>erXDxa{rL|NR@)~AB`1mI>M6_AO)QPs7MMp2nztIttg;8jGKGnKkJ=Q*^aC zV{K?Ij%{YPvd%=WU~b-AF*?(w)~%Q={^mP>W1Q;`KLMMQLSva;9uuCkXqcQc*7-+H z%N6s;V*>R9L^86kVvJOEyfV06tT&3>bk&Pm2jfUL^`TUX3e`u|&qxq&d@kC`GQ4P& ztw2?y>@?B_>DzIoGwVc7XBBvjVI|}x(HseyiW$s~Ap~ONVM;y8HwSDnr1$#0;U4nE zX)D^eJa6{=YZhK}^)-uqf&9fISYF%#-3Us2&`)@I@et*gO@YS7-d1-HiH1vx>Dajn zUC{;A%L1Nm#oIqVxa^}-8`uCyOS2bDR%>ZeW(h|IaP@zg0q^^Z=Ue*7)8^*%UV zux^xf%|z@5*WE95fa)tp#$UomGd@mjsZ{Y(-;=_gwz_eselfxAdzR!as1JbYJguG% z%sl=M63=OowD7fstD8Kexbr(84`wk#poQE1)^t-oiuD{!Pf_C|CRU2!U;OEt*wxLN z7vF53mb(c1`hRnO`e)`dbP<9IFPW^hlL#v2{xt437<-vOU3kvvWs;?}^<|eC-I|ng zT^)Uz8@z1hjBDo8IEa-O+{@&xb7dWQ5V}d>zPXI+vkpI-VUFA9alpGK%aC9F_MGxkmy^#)b zxqbV$wtj2-%9W#VI+g!|baA?&bhSO&x{@CrZzqq>8b{2f>m>ztv`;nv_QchcSJ-?V z>01LGSkrTDjyiin)^IZ>9pP6-M)mNp4{o#3Zo1czx6Pok+_3+ zT;#krA1`76L;hj`9pv#Uqs3C)nAFt;qtn+D^LK7()w;8(358PlqGi{h3oK-GF-IPvG=3<6DDnM|nGqVHwNB#itS$nMBMbY3C^4 zDCP-SSyjymH6{H;4doRHp7@GV)fSY-XJuEw=?7a*iqetpO}Xm9E0}-(q61E7W8ZLL66saB6_E7tXwBbdEryhpe{ry2}zl1 z3W};txhVAul#wPTp;=Q>jlBeX&LkTjMc#`YT~-whU$C`ke~}77xg}ig37K}4JkUZl zonNcD6|`K!^OBsHnXV_9T%@;9O277t=rM@d&1nMtQ`x(a#P&2bo)cNNqO)Rj>P{k)K`fU)!bd+@9_pTf6x=)l2uUnoM0i%Fi6GA$f>3806^PM-` z$%c2`_9ZGEo+`fg0m03@X!mpF~aB~(2r^Cj;Y@C2{By^Zo#y*WC3?{1tHUW}N|-h;BfZqSX558*5HB>xl3_B zYRu_JkMUaVJGN!Z(dZi`Q@Uk*fxs=HT=k@UYmbgn8w!M%GisB>9%FRAc#zLE5yWUb z=r*!q=thjWZhNPL4E0cF5tX9e?ywg-3LcI~D=rsrC(*o3`2zv0-aaD2aj-!c zo?fi!$m4rvEtz%Y{Jh3aWOl`-_(?MF_W0d+B`F@I<#}V%M%ouO`P>kGM(j#Ss$0M9(fA`45=|P!Wa*`IwVC_7T^ES{r5k#=e0e1W}isQJ8?}~ab8}rdtlWN zKXv@}c{)7#L_0F%Soqp&jUBSJ(6R^%Xry>XK1Q9{dA%FSc|kijrWfq!kyBT^QT)B# zjU#5;o}OD5FZk+Hx7>Q~y|;ezmZ#U=yZ)9{tMX$%ubpr=FE*1{{+iPkaw z5KPCFPG_TMC?iEprwgf(-G%7{FG>(cO+RQ-)89P!rf%d-&>WpCMTsVStHreQsG2TJ zf56-}4UX6s4yJ!*U%mfc5Bws)v?$#I=t)YyXrtI!3$4Z8kSz=?poP~(uR!n2>*3(b zE}wJt%*!uh%b8bSjW7IjpSyZ_{;De=c5ps=2Zn>qOqUxeotY?|m9nGD?_zFJXLP6h z875WL~pESK#8!^8Grce0vd3F;Yq|Ttb71hM!BOmMDx88fpl){iW z5=yLy3&(kSn}Yt{aMFplfADVtc!g##JzH|B>xqko>&;Tlilr5uF-RRh3FtH)=YyQK59p^#cE37N%B@ z;#XvJCSnuI!){M{7;F0eMQHX=VoiT42_nepgh_(w+m2Tb_eA{jyuMI&JKhrbd>wyG zNZ5dF1z$3_g>lZqJ2|1AjqYG6ORiE|fqDxmH6dp|m`=A%Wo(c#2)gqt8ONT7k12TtP~|5ipQQ_gtr@kmcZ}2uMQ8l_dN_S)xZoBuDpS^Q-+qQKi z*W`Y(PlBuszn z$*n;T#R3)6+Dn~wCoO6*fH0OLWJY~|N~$tahnur9n}-XtOXpU^rzXk%-%eqqtG%YO zzh!U(&h+OsFnH?OXAe_HK#c&YkS$fjn(#~wr0dfr+l$UnL5h^lUL3VgqQPmV-Q)H5 zc9z=`b9V&EPp^}ZZo(N4?%c`vYg?f(9lr?Ba>S&BZfxu0(%PN$lWEe;+DyGw{${cu{ zpg9lCj_1WZLO7gSSBx#XO%p`J%_;h8?xJ#6VgW!8t2?c4gGGi3f$;loShi=+4SVjo zL7Xl<-B{Csb1?>EiN-9^$`f*$wyIwM>(>W(6*o7c`B% zKvk&;T2a!=6F9>SZ(CqJb#9P)g12J}hTS=H0i^4^rYY;K6|t?N=X6##U~#%EFUEuZ zusA)cqMHSl1?85m<)|*1+oL$8MMP|Mq8O=YQgvu^6Tk&!X|ZH6aQZWOu>qhQ(3J zp>yL`m(_)qM^Xp)0)oZ~Qn#dbj4rHW#~tE3E^Y*H)EZLEfmGBQl|hn}PEfimFiq4i zdA+_S@&||N>v4MU6F_BXV{zWXS+f?*y5j1^O#%9gc6a+m0?0fFJ57-ux(f|mx4fPl z^1#|&bxdliU*5L-9=tE)sKdRuxCffnBBu|WdgFTxr?wnDx><_)3pijNI&hv2M@Zvn z>2DOD`uKZ!yWhb60;8XLTt;==FOL~fU8F7>3`Yc%O}s>-w_UXU_q~+vAc0#$({w` zd5q};1L#=V<2=x|=Z(fjm6S5AUB7nit+zaP%dNLQeamxCt$OacZ$ACaTULGc)%5-Q z??&2=`dy;#7o9}^J~V3j<~xpIP>0i>`JWeH`cE;vEHc(~3FSZiP^sx$^CajU!*n=3 z7MwoU((MKDQM)?U_Hxwp2}b$j!teDfAOL2H;(6>Oy3#rk7F&26JAdIRKy6X3?A+MH z;a$$pylVbZ(fXXLDeZ)-=Uh4eda?YR)%o@F#kd#VNbKD7n8?lwV|$5hX)s!k!%Sc{ zjuj>}_2^-#345WCbk3YPB6VE~rE6}@gzQ&KLzm};gRaNXT+Q65#t3E-r1KQ4v(a_2 z2N*lOG^WQc)e9MW-xsB$n6rnHw&W^Srx1p(XBry?y$-TbDhecvxV?dZts)%oA*Kgy z{-A=wTm3d9bM3mm)Je2M+>_nMBaN#hK9;!dwF{{!HhLERV}ob0n@4FYboj9MML=9(zpU&k?pwG+wXgI}H8&ldpVG4vR6>fN?j(pnkg4#8QkRhP z-v-jjh3dE6_1d0gd+xgHKBn7bf5DCZ#V?D}zbrK!O8@e0H{7}G#v4$vm)&_M$JZXD z@sVXvm)`~3i^5(wJ-x^VqQIDIT{%WeuvP1Xv)3?QFZYfy`yFPfXR2EM0ac#ODp8eMPT+d6Z} zEzQcyM=Ou2=@9y)n$G3QRTs8%@#!r$7);-yjQM@IUZQW5k;RR< zTq!LAZc{(1fENc+xs~|BT3x__Ng5rSdn%-S>Snk%ooCO^=) zqz&_WHy#;HO~~ffV%@ zUf6P~Pj#Z>k^JJk6M4Ju-*e-QH{Sof18=;cs#5AoEwB1%%dn2h-G^uWEyQyjR9s39 zj1Fk*%-%Z3<&j7qgM(9a3oTB&f6x3GdG-1181P|RAIHl>lcGL%q!EWp(>Sgd@S9M^ zp%Y6M4=k9!uzo<#c!W3^wv9x_8+Y%i|L9b}($bsO1L)s;?zyLb2&Dh;n@>H*@wrvE z#(rKuv!{y|)jkhf8@!&Jn-ymE!_8LG%jWOH>33|t7}NK&(|XZ%_oH6UF>6fuSZD{pXus6%*ZZ5m%ZdeNeN7>j=Iagl8rXp!( z#;yWnL)cf$P$>GEnKHmIo36R~E3ry2&UE$v)*OpE6{b?wuee%xZprBu-RqHS(i4b{ z2=utP0iMhStIWe?W<9n`V)~?*KB=b9EzhM{45oAHU+%s4-i_k)NKeocmboxgKwNs9 zBj~Yh4CLgvdpvY}qq4~B@UkbA&@BwdCQF_Ew)|64PAXBc6za|tN>FQuH9Y|>y)L;V zNnJ>Bre|c8gp;uc@2Jf_xQ+fsmEllUJB(gai}9hVl9Z8kWPfz+BxJjGha<5d;CJQt z{mur`2^dWjb^Gyo(+)$qDe82zo!z3w?eYa|h}&0g-)b#_J(W#7B~k_d2DF?>oUq3 zbjv1z8ortarfRO#_-4HbgvWrKvh&{34~ zTOhpwOg}D@5p}JYNr=j3+L4H>$S^vyn!>8oaGkw2t9qRQ{Ih3=tD3`E4Ke07joc_y?in;okfz}U#VHYhoGn%VtB$UOQU0sDSzOu5g zkhYwR;4&&}YA7U~ORx?lp?r!;U3`uTGAf(<2T$Irh?hYcDWRtC?5e`m0*QA?Hwf6b~VMkbU`jhz5zq@l64U@Eogol%r zAkz!not`fH5WN5xabaq)qF#V;p)UX|3P!@_l(0rg+;+&Ak9`786`IoWxu{5tmlr*i zLqWXBY+>BRI|(iu0~1QSCpDSy7v9=rXCiJaLSMKd0~A7uz`E*qaMGF{Wk2d zah1lA|IWAoTIZutWak!n06Zov%IQuJouPvkr2A{U!Ehj*L{FszA*3f4HB-UL04^~u zyIr@a-w^%J=ICi~jQ*wo=%RGE{5F7h&!dmd*aNCRNJjdXzW5~r=eGgt9NA8ozU+qE zA!0Cn*_}#N{}O>Oq^!vKLe`2Db)7{0=}}T&LB{$-5h<`PYqq)^O+fkN(r*oWdF&Ca z>C3RZaOXP3^kPB!Lwj^i>&yi5MZ;YbvchBl+d}QB41Uq_BxX-8U9`y*Y`^%D*m+%7 z<)oT{g&tXZs^3;(OSVw7h(TNmRw~gX>*{&i|^mMP1zJ#X)xD@9T znb@>`ZD6C@-_+QMy1r3KUw=z`0QxA^F|CLsXI$=QXYe;hQ34AP$f^zLvO^fyOr;qWV{p<}Vz5 zVapqj%dkQKdHwyb-F4@l8yPVwSLntAZ=8BuRi)~Hq*II9S%-H$|D(qT-a0pK;W{Oy z)RVpyd8uP7iz_=I?6=Uv2gp;5iYtb5fW{B*RK8Ms#Rb4>QmQ# zWz`RFz4wRTeEPZPzVZiPdXYCB`^toT4x3w^7K_yXNtnJFZ~FJq(oxgDk2ifv7t$`% zVP(-Y%bIRd(_j4X!`k+CvKH~&@!dm>=taTl1iVCn-9$37+xw5xXX6!!vFD{uCjt7B zxH|PJrrJ^~W?nY)%K3A+=FIum&6;@`UYGe-UH>^u>X%=S9R*CEe$93B=g9pnOgHy% zagnBVXJT@w-1uBrV|*$WHXG$zy#DC?tCy~s!-4*yl#N~vqEBBlXX%{jH)+f;bIt!Y zTDmx0f5LSB48I#O9Zn}>ea*}@*RPQPj|4A!x|z&FF!wqY-L1=_^Gjm-1zW^E0Oh%= z4ebwN$UY3HV|?k|7;raxz48|Z-C@Oc$EEWX9qtXg0sSbkVwLK#i+mA71w<{4z0%Jb$h!zfO9atn+~2aOplt=J5kcNZe8ha z^@Y97wro=`7ps|rs*SDPlz|Ujn8(64=>*$(l~A zWP4<{XVdvHIkmrkS4(pIp@M>psyY${=eqhnUN-jexwl7M#3^PVua?LV0<0mw(xwLL zg!U*xEZYR8+qrN2=yIpOzU^I1FY4Nal8#A(XcD|EsdZId_8ruXLZ@cRu2r~YYO@FT zeGPt@_Z1T}SXNb1nB7oFin*-KQj0S;)il8TEd=NX!g^ESOI7tG&-29&Vv=s!Z)FPX_5pb=VKi3wTiM#SWdHw~hMG)$OCXbfxESFnzx zuBJk)=Y%~ZBr>9F!|AB$!v@pw_28r8ZL32p$3^ay&xO`U+$dUkB7L2}bZP+DUy@28 zsEf!IW;rP864bL*3+l?m%j7={rl-oLGB-OhF~=DSOH8*Zw4JuAj0CJV4{aY%M@|>3 zr^f;2dYFtRc{X<l$(De40CFDlptIUP-1e>dNG>p z7&|fc(3nYjK@6w0(dma3iYR*KPx`qz5lCyY&ctMOYu%^JbrX}*h36*MN0$WYWV}2~ zV@>0Gd6*WPri@fbZYk-qy+j3cQM@syOJv_?%;{=y#9`mDvFICx<;8NnFh?vW`&{uY zethKy+&jhI+Ctv+c~Ci!4$l{;>V;5sfxAGRnF`jizJU4;FNKr1UII-+_4z%GjqrIs z&XxSe^?|hlYXo)m9&KtYZX{cAePiRm!14uq7OqZvZN@dr8|xPi1t>l3K->wqJ9;S4 zY+7GDkUzT~ws-sT5#}QU#rb5g=TkO{dM(2Xm~IZJ>C_RZh*T3|`a=i$Kx`@C1B++f zb=PZm(MOBV-<=Pkrc+INYTs_&+V6euh41Y?uzUCScE_dzyT8YoH*{dbMv~2S8!wHF zbfDw?>-ZPsgTJX`YN(aOhrPb^rx zXZ`}JTsed6PJ2?O$nLz|L{W~D`p8b@o_p_I`_1RBeGbRV)3^L^@6)&Lefp_YPkrXS z>2tHERZmS~L=2bRMcTNTKK$WPV$+Ywn@$tbJ2t=YSCo)i78&DB-(N8;Wk2Hio4VSd zX#GR1=@rKGVpIa0=aZO@C&m)nQ)PiA5VVYUx5q2^1?GP^aQ9!k@dn2 zqAQV*wJDRN^vkZ#Te6hxW?q4Mj`U1FP)Y3I?ivEh!RPC*w>bMUV^tRht4#D0_hd=g z7N@T<_si9EDtI?1GttrkbopM;(OIcW@Tjva;uf4QMNOY6)63E|xYO4xeUt|S-y2Hj z;+w#C+LvArr5jQ=m~JfbhR)61nY+GVW}*D0F?~`_pESMX-tE{0mo-;n$v)e2_T0ve z8+&|YOwfZi1+I$YBb&;P`#TQ>x(g0cl?0B*YDc$XcGCg;xI5U5 z2gGTd1V&Gff(c;Fp&}>b?(tKc8jgch$f-%71rWupEp$#zK=22J31qC?`!7wS`JO%s~Nf-=r+7s!kiH@0M z%gnBz8*QiknNK|)vm&YiUtuD6XneFRKL!L0-pNqj_J-sEI|g!FRY<5fEPV8R|RCo#gR$3q_VQga4HUXPq?xq+}z(98SgneczEx7Kl;g; zuRhBig67fb{a2nMzMVgsEvem-na;9F&sjPf{rVp@{qmR5$d_LZz44R3|H-Q#&|Rn~ zGdnx0ifGGilx-Fks`qPQ<#179=BDQ1V0;4)D+8Xy(SaYoln+yRMZ;)DMord%nOu9%lZdy$8dWt+V~RSQX6gBt_S(e@>p8b&v`PJCw~tgd_F5rzm3 zA}5u8r1BM2;m=8A$jEq=Z+@dz&CO9U#iW`}whI%X=(t@T-7|j=pe{~_lD>%1#ZWqO zJ0XmB-i{Ap*$Rv&w?pbT-bI_z&m+P=NWjX0E$8vP7)Aa30UYXEu%}y_ZpN{3ROH8mLGidvXqhR{j3zlX+293)|f15P*+dy@#-aWSa1%Pgh zE~FNMOH4m47&m{DG;LixdH(-~CGh+)6^}kF07p9)oMUYFwNJaD?lzmA>u$9X)-h-ucBtO+&@S^zOmH-7~PhX{|8b9|#b`*tobj zzmWi!`nJ4lW-nizH-G-Zd+LkR1~5uu2?+qQJ-vk-X+22K={K;REXh!UsdbRa;Y zcoTVy5IUY04r|xSrGDxFm_CLx-I`uF`UV!3KKgn_npRzTH6KR}5%0S5q3=QIBr{?Y zKTUYcN2dlp%I8$KpdLk9;N0UZ7~On;dH$)PQ*l~0R6Ah@%R{5vemhjoWE^o<_ zyu7@Hug%(%w?05zy3ak(He&(95E9RL9wYAM3-V^oU%=jh0N0nAK2G5)?Mb=G$T^y* zGHvX=_tsl(x#g)_Ry}p=(@#JB!>9K?{mrKqf96duG$CquS=FFS?~t`PIa$E|Pd_}W zxb!<@Ojil%3v?ls_6~1r+9^9JlDWxnF{$Z@>2EHopjOJbS)``VZI3$9Yh(S5_<6Q$ z>SU0D94x33S%_PhnPFWWW|k=M*o?<y^8dP^Kht5HF?wbby zg8%RT0h_OxNkdX}bc5+vFP(6vgY1UV0e!k2NlZ6tIyY-^cngV z`vl}-2=D-tE!EqGi5v8t6`}jppu+9U!hS_G z5|CSvhy|OWGUj8MiW3QbrU_{xV9LJzI;cb~F*7o%Dw_fGn#{}xzWXE?j?;x0z6M3{ zW!D1b57g~=05LeL3rMF04cJb6ZGp3*+gA|hA1Np}N1EY?`*??YC7ez^`F10w<3`8m z@`deNSFR+fyn`>|t?7w`ZZxRV3=?hEjqYvqLrLm64qqTx5O%w5<)BJMTzqoLaQ`;! z@P&Ge@l;c;b+}#-#fLYQ#oM5CCyFy-bO|}>C0z*$ z(ZP=`Qm?IHyr5#rEJ9E0*(o&*+g?|Xqr-zrHepKK0i+Am(@83kpQaj>m)J#y1KWmu zd-Dfwg};CJ+&|p^_g{s{tpj-e4u9{z^Rsuf@Xq_M|K=ax`A5!a_7sQLIs5D1{PH(H z`^VQ+OsZVQSI_+9f1P>ty$(2CJ5I=_QM^ixc1>X8X)em3kaf6!I6kYWvWC4dSn}-& zjBMyeT2bL@aA6$Z0H$-5g9l$eyt5`t@r$N7*}=fXA-@aN4^+GizYBs_TKa8w-gqN&I?X?6{|T|*{@Q(1wj-t!@_lsQ`7M^; zMV6QI`wom9BkyJ6uwwIy%_#0D=`y@9I~-JoY-Szg8<^|1q|qdGZ|jJ+lb=}|PlkkEDE#SCv&T{N?{yJ+R7o~3wH2`^AO zY>uF=Q{gyI-MWTH0e2lVauKtij+xUpGr*9X9&P!ecicG-%^Ypq2;}on%Q2-J zW;b#<9*s>QT8w(O;=}e}ol#Fx#NDROV)mG@z? zqG0*XWe5?IsbVy9fjR}BQ2IGz zQK#u>W83Z}^Y_f2wQ%7zvpAW(;QmI{j*hoB?U}IzsT@I_odWKmyczRnE$LM~X<$Tp ze59|p@x+q0@jfgs=lTfZr3Mz$%hTWd=Bit6`R3kRzxmWti0V&0w?6js`dK}ldv|%t zhlaSB(a`9^>BSeH|B)#jJ$47Meg}so%1sxg8%+Ojr)iRiH65rYF5RN_gNw=+k*!Ak zI^R7Mh{h6L4#s5lDVUBB_D4$ptbBOjN&s7PLzvU&D4*pbLKQ4eY@zLAOl_{G&=%uc z5#8b%fy2!b5N%Dd%_%fBs67Ws8zuefw6D!lU!lt`zx*Z(jJ3J0WUi>Y6n+EUXyi9t ze$!1xeP5%bmNn5$bOp|_0W)*kpM%hi*L>zo+0q|f`acYev$*u131*xzgC$E%7q+j_ zFCW+7@fcJ$Pm=^jbJv{F1F`11Cv&M5{`2WVOy9L}JQ%J^t!nWp$3&n`W1pgCe2B2R z3Q7YQ(*2HkIk{-+y@7C3Z!pl?6U3x$3wC)cbn0Cz0$b^Xvq+b)W zQGyqP@I933mP%yY(%LMt@WAxi6k$4nfkMXGt}Z#&cRZk2YfY%@yIOf<-J{7P{%*Jb zP|?UC*P(7EceG2;c8TeVPv5!{r^`z9wQ~nON78d~qZ63OgJIIxT_<{AK>D=yoX%j6 z+Z%GXdQC%8`aiZ*whUKhVVloLmVt!S>|sG;h6L4ckGH%%E{TAe>dJK`EtQ2?Y*my& zOB!swAqk`Ohj#^u6?Reqh+e4}@G83beJ|8_-1e}73Kl4pN^bANNjCRY~22V`Xuz>`yxGF|BoPl%|*>UH#Q zJq&IC?CiRR^v*aJ8aM!l5xN8+zse}-mY9x@L-$pM8;0D&kR97icJ;kdz{Tk@wrAPx zcON-&g#F-Z&cid$s3VZE1dW>k$>3RjaGrYqS5N)wAHMo`fAirjVP9VlHa{~HU`fBCcBXU_cFt0$W`1~Wn8>{_*S#Xv;MC_p`< znmm0(_5PNc%9g^U;b1dnk@!%No#JFD9lv&A;qc+ThsifTxN}24;>& z$y!@w)?iRCsq4zD?J@@S(%QP9uhqA)DbVUmPcI7hx3mmy1Jn|lJcd-9Rsh_Cf?IhHI(6k_RWXR-> zmYyI^*ELb*mHL@P!(M82L)uLuSA0BKKIsY0IKn+O5xibhR9IF?LVp7{H@98=N7E^9 z#`!|)TNW4@P_T`e2hkifXV3uVXD|!^-u2)(m}y?R3Ysb7=CedN4t^|kTZ*^mFd*P3 zK=;KTfiE#khlfCMjKFX?(J6nq=P&m>dWBKbg-W;GKp&$oqijM=%h1xJlPLX0yy>6+ z(tS9@+3fZg;7JIb1E7vqoxm66y-bk$?MFA0_Yw_z0al?=tBiC4!#}wY)6o&aIXsM- zzL`;iyy?r9VR=D3x9sV90I2K_kpja?yf0%1o`|aHkA3?*O-M~W>8B#~{~Z_n?PHG+ z6aUx~P&a?Z++v`dCvI4r^{f=An+2AkdKQhczHh}1s_Q*UA`T+^vFI9?qyq$8S%f}U+@WFUHy|T$*Q}+_3=%a{q#0O;8 z7uPROTRqUYdU1Y)FqB>#Filt?TlEF2Bo~b71Nn`+NqJe=w&b;?S1w$#U^Tv$ZWF5> zLE~}vHZCv5DKe0jRy@GoP4_r_E=;#bT}$R5IbCY{_hR9h#+?4p(F1*t4?K>V-h1!* zKc!fi;LjWGyz!ykZ{!a^+bg?Qc6W5I>`**=w-+-!u>vf0awa;_{9rr7k(J$Kz3akm zDw!guiphJ40PCQ3q^~j3yZo9H`GE*t`#>6XuxX9GSax~_(q>$-oL{)Wc*jVvqj&f9 zv#!~LS4SByP(KBz`Sp9!>H{*l_u;zV*jRtds%ux>+IR~m*WS8!@6!nD-@N78&%Eh{ z;PPy|>A$%U&vj1B{^ED>ZUrYMgC z!V}BFbn8MRqH{&KHWn_9h#s3P+K%3mZjQ??zYOTU`Y&f+xdy!c)AegtuOV6;#J46k z(v@TPty2LyS7rWrYk_40+G1@Bn>ouFsp+z@b2;mg#hHQTkFI%?i}eSwL*Nrk9sz`5$ooyr>5K0E$bMYrYy!*O`ZzVKNtH5EZX`(>j$mDT_r93 z2$sqQAKu{G;32wIMgRaH07*naR0}p2vDaOxT$&`Z}4H5(DOqs6IhSG!*b)b<>jW?sR3g>j!chz0yfm*l=KyS}h zcTZ8e;q)C3+#Tig9S;OQ2=D5Qi|eHOXhGa28?8tWbsrk-rk5w;iBV0uf%NW`o!uRH z3Ac8J?CI3B5)6%5zG7}U34l-te9oL{8cJmxm7_Rb@bF-HF`$y2QCVHM4wpi6Mh0cB zm4xwCO3{wb%uGsj_yeJeMd|SZqhy>x)Zx)eGC96NZkcqiC^3udcd6-4_^bqVxUdRM zKB*ZEH4a@Ap5#bEWrh=+&jteH<3&teCH-Bhnayfr-wZFl}XaU?*ec} zrF7FXwMAu`3KVxZ64|@Z&NUI@d)^&XqE1cCjw5#;Nl(umwQX{hZQ4X^da%E%lDPbe zUjyn~;~!ZEs{ia~yZ?>2mxHZ84${j)I9!9-q?)!u!?Zsw;|+k*x3w@YB!JP^oR9#F z7Q~g)^&B;QQ&GmI;ln+HLr?ZIsH-Q&DlTpsr$y7 zfWL$u0_dV}C#G-4Xa%^s)RRqNjvYyyO*3uYs+^-@iv>Z_t?bMs5#y0_285NY76{yxsx8=J5ap1v3PafDx57t zYa=xAZ5)D_q2>S{#|Ur=rIL-3w(y!Ic}o_~pRsWDsk=1C~IOLeigF_03xvZyj2->ejutK6T5}Pd&Bj+Rwb{Wm?L#_OqW* z(G9e}1Ev4ddj~du|Jbo_fBOKoKuN#Yv15P1-{$-O?!w&k{nJpxExG)|Xa(t;?Q`#@ z<&hD|+4-I_Eym=i>2JQs^k)113BNj-$A8517^D5ZpIT^1MW==2)0a}`sda`z4Q=X- zMa0&&F?Q!1?MKZyvATu&m*X5U?vWVM3cJmjG?D*IX@nWtPR$=A7sF$St_RJn>sdt~n04#cgZ$m*v9~_g;pq%+ z><#ue51alyDC#&KfzvJV|1alC+?o9x*f-R|AKy>qL4F76I*=jc4r54nH7 z9`q9N!lakO9JFlIi z1S*BQ9G-CVao(J5g&97XSI+vvxuuBd**GEWcDc>7MVqy?2eVb9$Qhc-hxv^$s{d^9zx}VDJazcVV9zj=o(&OaZ5upTL-J*1VNDq^FV!Tz zP#(*Zs3{p9M*d}Bl%Adgrn6%vV^e$C@xful?-uQX$)vB3wL)jA~_kF`rxVg$kOBplLWgF3FY?=Lp$|Pc*5XoeZsPJBZyR zP>A+RgzFhMJ^rdx0+o_vOIHmkVk?Fir;XL|83_yxY4%!|>S4!MqAiZZe+$x4wn$Mo zKb@>trk+N30_yNOtj-?)Ju{@HV-A*>E=(tHwIkDol0JV~^|`Q}WJjw;$6EhbLl~9t&{+yKQLZ1)V0r#i;0p z(Lr(IUUY#wzis*Qw)*@ITaK+@wA_U=#!}sB<%PJ84$b88;(Vcelvr>a9|QNat*`%j z-sTAYTb>siM z|BX{<;W*zr*v+d{8ss6qcUv*z@axmV3Fpkk#ING=A@SYoJ&wYD{CFo{zXkka%o|-9 zIaPm(s2a@jk;v{nd1-C+ygIAvX~eW};ld@f77f%dxq8-OH=&HgGIr!IyyhBVI#wTo zU~tbwnu=c=I>)aazlXSc*5)@FPQRtG_tqh@({a5#{nWKj{Q;=ys5*l`m6_49yy#?t z+VQcxy5*TWj{QY+I`$WLeEBDgb;}pvC;!}|i*KdR(M(w1Os0_3f^$RZ z29$BLOgB)?%~@y;UqAZPQv|k1PUm14n?>$eBDi4MS_On#l>X0VTKdoTJ-YOYEB?2M zQx~N(O`dMjc5e-PWqtx8TeYPxQm$&4S&lFm&m=*)jM#oqEoo}i~=W7Edg z)(ykW+Xmm|pp5Wgz6)E8=OwZ+LQG@C7YvT~5Mtgy9ceJ#5eVkcF~;ADDna0j!$Z+& ztJ@bY5Dg2G`OSya(G@Wf*OB#-K#)mgMon`+C87_|Tt=oBFdgcwmQ%WgP!0||b|mh| zy*oFzHWz_&M{aIzX)X=~HT%S~foxq^bV$CJ&h6ffYO_!Dqr&odLRB+*1FGy@~#^C_! zJT6XO#2x{c(?+5^&h?}sFZS~W$>}GS;Z6_LHK!ggLig-yDLH<8R6SQyOX{eDRBsx4 zVy=y>#BlRE9-=+0Qqb2Ax2D^XpKB6!pyY~unQ*=A=*p_8#cGd5UisoA9b$UX(1LXO zvf-ECfB#yt(^2Kgd&G#Hm~IT}XzBDyGS+od5BmD+7|+ephO@U^`|-ygL))JM+lp6s=ZaATu>RQ z&B|`K1IdeWT#WV_81$7@u4Cj;*9CB=_LHHakaWZ2Q7E@yJqqkGZm+U;VOq~BB|DuD zS0ar)dx8#|gYjBJ!Z6)Ucea4=Q>JV^w5-e>iT1=Dkopc90q`dxCpr;Rx;h96fhDGg zL&*hnYQlaFsN-5;z{VdPMdwyD$cfHQ7fI=6B0Ld|n`Yh$%-btfXzQ~#)9<;Rv%lz1e0qv_Rvu(SxpAx7*(Y_ z1eQT`S<|=ddo1d6K}vs^<^PMPzt!!TnRTkg*jX(;_An)^DCCB_rKw9LHw-S%i{*RK zSqs}GrJGGGkcZtjo4&8NZ_!J%?}_L;1%?|ZI_-*?9Fo#8yTIxu-$nh=s2@cmFCY^g z<2kCbYf(8{f$sWT=<2%IhCPJpQg}36z)8SI%wk{u(CXzw#mld|r?@z6sJAh{cK{O% zxDAr_0>Y6dUu1pnz|iX1v+~-O&$wz~etp_(d>}&Pk%G={H(-w=z3m>f=?JVHK`zH; z-Up=X$e+CFlavmpV|uXw-OTZ(f6pom&2QRx@9Gomt-15Y6_k&f3QkfBTEX;IWTe2_ z#>VxuTZ$fs77uZLJ;Myz5z&tcX+11`ovGVfgtERBX{VrID+NsX#r2KUvktVKn1AIJ zS6#WJjdIsW{WVLkS&-J$R6lFR!bXI5*nFIhM>A$OMmoTB{OEYx-2?Z`$0~zSePsMx zM<9O)hYPm!#l-`StG>SYn|q(V<*BcH<=SgM^WOAn)CCQHygP0A-~H;^ul(wrU%m1x z@)ixLzarv(b{|d`1LMaVbtGUsB z@jL1R%adw)yVZ~M&4&Gp=31Ek;kI^)Osy}aKhA&OUjf6K7h*c@5qK1!o`6zd`4dda z<%Z_X%n-6!!&w0{*VR?{V?of4ePzayS;*<1n||eWd)BaO&7ZCM8V!&P7h_Ln4I66G z#@5~G%o+i?4yKWjE_(FiTcoG!LFq#AIE(N!LjhfvON=`Hs4Oq&=)ZaWm(tT8U3&FZ zSEHD7Av1H;HA`;-)34VWwly&@mYg1Y)I1Tx>3TRkKI>8auJhPizo?^^>U9a`8(V!F z@H-3w>h$3(O6_-VM0MZ-O@ZJ_PnfU9pf@oT7q=+R=k{;xW$tl|BTNLz@%8w7B5r^t z5kgkKN$pe5CT=c^m=_sE zG%>d{A)!Wf= zF)@VrvJn?OMwWn|keBkDT&`7W4>5WuOCaf878ZG(dWmw0BPgD> zk@2?XV7PfWHPw-g=><%8^7Jw>CTNFm0VvsASyfnFDboubCT*BDLjF*kYhF<|S;j8c zsH=isOYA^71%7W_g^Z)%(zI!=kN$nx*!j`Y%%tN5n+Va)N}y5cCUj(bSn_BUOqc2) zJdp^NW|DFe>O4s#pud0iY=34Ic$;O14ay`ugC8*H`6z{P8b; zHv#=ZW~Y`E_scJF#5}d?%$dLc%B#J>){P$C&Dxq2N=d7?wbYcYv!wJaMmXF0m5o?a zlic4=YasAAy%awNA0|}$q8~g3N|6?c$kdE0Otx(D(RTS zv4}f(5%K*O8BE9cl9ZIGZba>_L}wgfNAXkwXVSlj3`M!f6~SUecw!PmVPX&yGkH?f zGw^X?|A4Myi_b8LFM#^oY!}Kpz+RC_w^NE)<0ys**^)hUdROssqMiI6iRn0vVX}Bn zQbIhbN@}Czz@Q^a7p!B{p$HjU4MVmn`T;vUIAz#FQE*6{&VT9!zlC4C?X_il?!=sa zmvN}ych`)&WO|{ektL>o`9V`bY9iAuQkSAGR#(!?gQ)5FPHw#Y_S@0ZO&X(SW9L!R zv7#$LeKWRnW-24ythg5`=?Z&6OuvLZJ*uJ`Ej^~D3)6LY>=;Rq*j$X|Wy>4q53FEx zaN7;bh-6f3x@mf}%y`pH(2FE=v~*e1|IemL;+|YG9L`zm7^CvPjnTQ;&|JnU5S{!* z1-)Qlu>^9XlEdOKcnrpc?&c6X;iAV`=4COZu@Bz9Wgjy8>3z|!ZCTUhZ;7S0q?@Lr z4A^9S;h>&H3R$GCl#hpU(ns0rG8#vlHI<&~AbywO#pa-p)Qy!yv`+5gK;zKzw)HT1 z{i?;w7gH;`z9)ZG+dcL8Q`GQiqns^~o`E*R^tRy9({&%aNN z=-8Is_wQc)@%z7e|CM)MdF8_o|LK+G-~Yj+nEn_4_7~s&_8nWcjJCzKnh9nF*}4`dToD(#G--|^ZS(iJ&t1Rgikm(M zNMC=2Sb6&NE8yrgx(+0KlTqRElq9EB#D>8AS>y(qlqdWN#2sLiEZjT@24 z++1JRk*8(pqmLq`zyFJ~|0qgFOuy=CSzMwLyxHcaIdg>RP`a+5$1g7DL=Rfe%{)sj z{U1-UH@>2qFIG^TZ%lHU&&pL{1og@yECL_2>YEl)5A+0jf?gYqKz;sTQ9)ds$GtJ& zON{i`9FgFW;CMLQ7ALvaM{#KgvjY3nIUouWaDum@iil`fq_Tz>LW)C;=LORXm|jh{ zoHBY(B4Y~7b17vSO-L~6z7Q?7rLwuDaGg@ue|C1mup_s$w5G5yi`^GTa&yzGEjK#(EpYn# z6oBG>Cxh|uVR{Sw=>G2&pNsV?ngH=%{#rJ5`WRhuvU1b0rlZ0G>hC}GqaU65`!^a9 z!ggh8NWmbjuw)o9eOqNU6{Iyaj5i7?<)s&GRaUbvSmLl_xu@6>lyp_NNQbZN_XnGK zYS~$8KFYfUA?rPhO-Sen>=Q?l)syQ=97=pCu{87C(v;j>M>=o&{tA~1e~U%uDW!KO zmJ;I2hfEVMA~O08EbXPlpA(s)MnX)2bn@?TuRzUCntRG-&fVdAL7+xWCw(Qs;cO75 z=TJ~e{V?J>0z1AKHQQ2gCz&sf5IO3?bfR4nvociWTggDyq`qWgUq@6&Nhg_+F{c@0 zR^(7Yih7<{$_KzJ6+RtI=emgL&_53j03(y8hR zMXRx7df5`z&ORL%BSd~mt^b|qx4{>`c;8(&s+o+`bP4HJ%!{;iSzf4Rq=wWu)0Y`I z*9@2X|GaU<&0qZdIK8BG4K#wZw zbmt^md~y<_gX7W3P&P2S6KlyJ`{{kRtK$?kq!QC(m~LoXinziRm4*(T1LxKWP_7ttle)+Td_I_T-dxVI zP@Qkla7RZNMIBY$3#hv>z4$3c%5ThXTbxg==-NgCU)qZAsc+rb2&U(+&yVm!K)a$= zx8I$gM%Z|9+N>F~R=e|;UzfL7%|?wqoetFje}u+G5_qJd<4W)4kE1}{OfmP16`L+K zeZ?4z9s_kHFN)IhxrO@sf%F^y=l4zl{e8H>aksRJ(g|ZvTcGK>1q+s3cioZ&3l`3w zz2G`cge;mVEp7Sodlp0NLpXVG$ZP7r2?MTsJADxaH{#`Nyl45W1;u*!Jxyt|XU$sj z^~UAbEX`|VdlG8$7hHKw8(EXYypZGg)_7CfYTWj{fpY=O>2C7l*MIZrTW`H~)zC-l z*AHF$wQH~a3Y7lbXJ1X9Te@if7xpO;ol4Oy`k&ph`I#+SwmhS0pL!Zi!SuiQi*K_5 z>%RZYEN-ZrRpU*6I?doD_X&X6J_ZfPAS2^?LGWL!BGD;tKj9P3JQGF+Ff>dC=B)!#th;GN)e_d*2D{_WC0D3DwxBm*DHccj5GH>k8vNyU3_=x61Oe(H(3h z(1k2@ub(siP&xuL4vik{FA;yaKR{Dyl3Yp^-tkcZ>w11Yb8_@Q!jeD@V0w zW_Kjv#%UhTOlVHE)LF^2sN$LN{l2ijC+KtJRG`F%6s=fPq!@VYF{XWK4ozkf6EeUm zVR{Ig!Z4n8m7mg!l*~X(FP-E@&KvD^kGcpO=+<1WdU6N0yS9&XcNaJd!rtzYb03W% zr@Omd^9m@43U+giZU8?$kpe~PNb$&|t}D#KeNmTMS=C%+ud5tJ_fAT$o(|_{DO9sZR(ow65bSj;%dwbj4>)w8w;T99p_uFOG zrB;t4gXvHI=**cjZB60e2bj{u!wlKBRg-lo!wdT$TB@)X4KZUN4H6Rt<7q(BFhqxk5als~SVSU9pu&hu zM5&xi_Q3~sa*{D0CfgQiVWXonVIywT=s089t}~OS<23y=C+Eye`F~&Edo8r4nZ5V< zpYwW6^V;79_qx};?)50H_5NP>^|?M?@d@#E>Qyb@i)GRAP^GJkFB||sOh?9N%F#r* z2me{DgHO&+19cm{8&Llc$BRL9vou;dF)#N&d6&fWdq~}&0jcG9!S6C@`h$}mG-~<- zcwQ(fC8qHK!pn~kpN^2eS}t_V>D$oLw><%#ACX0!vnP6w9yKyLq%PT*)0a5if^;#t zWlOi{+_`-2Sz)@dri;{JbX@6@(1CUQE*R4f^hWir>!7>kWfz%)#s6V7U7+oR?EzlD zw#g8hY+=%b$QL0<^jKL{1T_t>ap zVqS(}7@2m5|Fp_o1gytpCSIbDlx(nOeQOYhf{=~?RB{ephtXwxStZj8!%6DOV~kEd zh;d13I^)QZbrg|0&FOq8E$g`Ffd?jaAY`B8UM)=LJEkG7Vb{o8!E%IjGyMId#@&Ik z?vJjH$j+&<5?6l5{0?oK-!XrFWikSPBPPkrxWrnDndp$0u6{a}KzqRBN@#&YMDa&f!wQO!_>$(cC(K~{M|+%md^EZ$Jz~$>DpdW& zp8raE8F;V$-d9}IeLbQZ$BRH6RT-`Zd~udgE&7$g6%1jwVQ))2XI*NvWjJ?UtGm(t ze0!>)f3rS#umNS-4s9N~8GHuSM~oOT6w(%?>)aX>=k(5*_~g>TqaL8&-IF)yuDC+K z*AMkG`u0uZziZ@li_#b2cj3-4y}bJ`|MD*D>TWcAsBWcO57r8gf}XW>(Na~J!s$*q z-9+8!bu%n&-K_p+7p{N$jK2CLYGF*BXi0NJ*GhU#cHv!)C&4;@jRQ%Y2z8NpLJ~*$ zk}{J@h-1XGU20D&3hlGo^7~6|aTSjIHsaOk#u;Fv>k;1XL>s7)K^+LkwnqDAq|>y; z-8~Ehs>@Z7%YE{ullOr|dF^^!(R97XMIB1mF9#-jLSvfJiUOOm;z0?F$&p3SdPWdA za2_F*b+cjJrG^bMOH>t6+!5EnnSqJF%>`$ z*buQJ!e)pk9!w7Z$C$AjKTE%`-vRb-`|tIL7cv$dWLDt1g0zX zeLq&td}coTFI_&?+k0t$4?8Jul6d&)`u(KE+q}!5Q6CR`0)gpGbTKW88=!3%<@1i-Rf;NhDZ?4!a`FPcyqIi1YOEn=8Cb7p-_K!80Z zC(Xk%n9Pu@qE6V_I5}M@EH)nnIpTjo5$Cy6=bObegZoJIwgsWUL)xL9>0zp;&;g+gwDi<~ zNLW2pNsOhX@lZK`wLzXVomGhgNiV7(O(a-`ISaD}w0kvE<%yE?u69gNIlXX|Qsl)w zsHLhV18_P8;d~01X|D6rfF?$F-L>@YhvZP_qvtzHOh<@7OTT{(V)}QUr2VME7zy4m zLb_00u9pWV-Lq6dFO~sjx;9c~YPBJyniLm0O-Z43I9+X9~DIF(8NAH1yJ3(O~Gk1EK`*AV5 z*>r7T5w=-c>}{@c(zao47kOX1&A^)TW)|50+_{(-Z#9(8)tZKm(2#B@xUl$FiuAcksZ@ z0jA&S4~>)BqF)A>URgPzGP#m2rSm(m$4sl7Fd;d4*D{p#em-`qtBHR>Q!i;Q_8&X0 zlGn=Af<*Nw)cHGa`EW(FViVf#{BYcSieXhjy6QyRxxzdBNk2nMZ!3VeB~FLl z6{5a#KaGhv6bPkP?Ro7N|AL(zpNy8T#PW%D?d{O&=tvVC^Kbw5M=PTJk7^p|YcT!a z)?-w^w)cOn{XM?}E2%|+k<*FCDlGOCRDIOY&iK&li>WS};Z;Efq%4DpQg37=_K8jTdh z9T5Q$V>a3Y0#fNq6JHjbR#ukfodsdTGhXFoU1fppT@7*GZly7LkqDsfUXB(=ig&gL zC8YQTLI%0f+%eQE-m_}7yy>NskOsSFiHAJ`?S81I>FMdUadGuC600xuME3N|*gvDE zzPhItQYZ19HmZo~wJ}N6;oON`r%92AJKPu(l=9<-)4xDXfA52K`X1R1lW)dMDkdgi zOt+$8)S5LdN2Q7O+U*JU!jgJ0eBuAOGstzx@Nx_SC8K=cC^F<&~Ak zTd=(Nrq)5`2>RqOF32wHO2PD!o#md5^E^0pK}v!2?XV!qA>ni)bKGrVVV(soWx-*= zl#mj$7%WW35tPlD*0S9Lu`JQ|(;Z12WgSb5hB&^!FGaH%gX$aY$c$t?hH!{RZ=A0O z?Y9VP;ZO}1%oa3vqoph4m*YU5(w^aSQ96A-m49wPmm@WbB!McW=<#uz9FWPIuB)LOr|?`uX?a_>G6|1a~_Dip0RMZ>ss9quio! zH&S5SQp0IN6dFpn4BUtu8@14iU2uIN-X*>KE?SU^(!aCxE=(}@E1MA`$;A8bzUwZvHo9k` z6m-G4lyiyca=qMr*9~_);_YkWN(TnAA#K80cGQB9x#27&mu!3X?SubHt$Iuhn}Cv z=_u(MNzv2pjGBgE&Tj`l)BIQXcTA(`(SQE=0Zva&KEczjtn8?)e016)IM}12{HG=F z+Qn?6Kd-ueP5u7HlErO#yY9Sk+yo8>>u38>I27IFC4iR}ZC zFa~2S(OF65+{F5o7;iQY2<oUO@1pXEnK0@mDUVKE5ymT_|lTk~-bLe}- zGvM>Q&dq}-AG_N7y?_1JC+4iX=dS6OFCV<;21Iz~3~1xdVKANb!InI3%oWsiQW#HUoaZ6$h0-|#pg5? zQ4pC?n$K}lN1h`QRlSt-+Qd@3A^J?xx>2sB36jv5fz>=HXro*&*`BN>TV+0g|0>{GWd<@>+X*4f)i`gchuS<1dTD$rMy`eUSCGwjc%!tv@FU= zqrpx}S-i2H`}q;SflWHJC9{n8#un}gkf|Lgk&G#@P`p>TK!1!e8o0CW;JX7%$J`^| z3Gpv9p79LFWnT+$_w>}GlVfq&zkf${HHvx94wUqsH^B7jn3!ru_?YVYOILe)uddnv zzDMo=)9YvSM1tw*p`m5o6o9HPC~7(m=oY#U)64PK|0kG!>dNcw+Y8zYUN2~GZ-1Q=LHp(GqV)6fEKJV@UaDV&MwM`4 zPiXfmDDaEt-|GTD7k-VNzH7?^>2vsv+6%v-`a*q(M^mMa_k<%?&*A2pQgVZeu`59$eYC3?e z!6utGHgg*l7g$)_LsNsWfU8B3;!~*q#HPZH0!i~>>OiWw^mNZqDcMlIOzHsvKHl*u zOuFFoEP3s*j1%rdJEWNS%zTF}oRAkFox{Mq2ePR!4+wG##1f<0P#T@mkAMlKkB@2t zV@kbI^@&H<{ivWdNC}WirQrc(+RF>HfJvnLWbUH%&a(x&`FTab0aQ!Yb zzVjU!qb+AT8!So}qdO`6K`}ZDOfQJ((0=boZ;=jt_FH>~cw!K*)1>8NW+H@Bp7 z*Af6{YN7$4JH>VrPOO}lznQ=m4GvSK;C3lu^h_Wr3`qAQD9V)NH^*w*w+;RSGne;Cuz;_j2Blt&} zDczKSZjfAjUV;Ng2K50wUAT_oE>1^H7p8M~M5Y%wefm1%O;-(RLo!;r(pzM8M@{GO zs2ThFOOm7fI~IcI8mQ$RRFL9uIUq6ptT|Plm70Dw`Kn~~g$pYeJ_^;d(|rFG$ENLC z)vvNrf(4ja>>4{_?1U1IyXKWN#x*ku`Eb}nBP-F+OQLQW*`a7j%s#75tZJR+Ux}xu zxOElzH`XJzh@+L>FQ6= zZuAMbUFWjAT(71p?geyzV)d3W06L+_$mun|fY8y=Md`o&?LJgBUEv&B8C~S!bLV+e z1|PX;lGYXVGO(}fHve`0_xTPO@^mT2Mn;!01*?a_bZ8qe9!$y#wsMQT2a*{Lyy{xB zj{w(&<<|L4ie32@S3}miN^<&C1Hg;s%^M0W3ydF|b@6tD?#-y_i;qSizd^V zZ{D#xkiT!c+B@fo-Z{Nf?!Mv4-rnB3Z{q&GHTlq7fLcPjQPoX2qq$_!yJUC)I=e_h zM^4A`f~7?dw;8+osL6QTm)^i~>E@`b$39%z**OL0`n!kTHP&|gI(lV#x||J6R?PeK zpIf;8!877BYr1RJCN=Eaw|H@LL;saFJc@qt@HiI4{OU{~z1~rl*rghNGOj9w>1Z5$ ze#X~y2c{JfT|%NjVp4tupY!=+^4s!~RH#ViG`EkR3#V_vP-@Si-A9?9<`x$&0^u;9B zjtNg(6H}cjgs;zph5PDz()Y)86RXQlCQ?67hUf1{bWr65rFLl z^%pU{C@7W|I}3<9DeH<)p%YQOUs+dqPD<8-z!o(4lD5o98}?!Lrh_P{HO3O} z7UPA_AqZzrVncsJ0!exb8dRiUs#_{n4IZMlx;8R>M`GND#QiZF#NX9DYiQ0iV}Jby zP`sySOiXoRdK*X3UDc1tjoc$Vn$ARPR-%%jsp5Lt>0AVQ@UnDTAChXck`7~@BH|^fBNN><5!M9 zo(lsnh%KkHRgThKf@6cT2t((!;w;Jv^9>5lZYfve)Km|59Ys+;TTeevwzi<9=Xw+n z0Zz^*a(Xrfb)%_s)PZ*ZGIv^DEImENv^gU5Py#;qooe%mFb%w zy>YclOle3fO2?Z{1w>hCyj{pui}#($2`y){v1HM#fTVUkMJOHTO91))+){x-q|xiS z>!IA~z$GI*^HxaR8c@15gy(y0NC8+_`%7k)6h%uJClHoQ^)c?b$6VB9)qcl3#MgUBl41 z3(W=W&ULLl_x$uZ>((7S0Exrm2QPOVoI=tIQv+mm@@9_p9z1a1V8_l5@+U68YN7e{ zYPu87#o{j57Pnhye%;pVS$%-dQOh|A&b8#nTGd7Chs&=b-V4IbE8<)i_^}vWXNJ(t zMd7%U;08GOqkFh)F#RrkFVnX@XZ<^kHgY+~v^3P;3Xz=b7b)r3)s2*nj2>XD z=|H;q6Cs?DJ+!Y3Go+^DN6*8kjgv%>PAiG(IP_#pE0xj9CbX6`Mi*8VE^BRVY$&FT zbm5~!zEDG&46e2nPrGyEovVuPyrt8>6+8F*`3tAb<)&!p`r+3sI6vn+iO8)XU;2{8 zW_^hUkiM$5!}W(_vR;^3ts~gwBv*jxdBq*F%j*_=??_GWcY=Cb@tt=(vha3>lFA=> zWPTLN`T_hd#`40t06v)^j0e-ToF-kpvco?L<(@6SONf~MLZNomCAB`8i4R3r~YckQ3yi%%9iwh@o%uSv*|Sm7fBM*uzxm#D@*hHW%%GM;j&oB-ZI=+T!?-i$9@Ekt*O zto_ArN#o@Nr~mf1D|hVhz3UG4%bO&4o2&WMR2^qUOE&_)%xJ! zkIWWCOF4h{kwveyQ8pf>v z^2zh$T$hk8PIp;fxF{euL@x2%+>uFS6sYrntn0pSd}vswLeMsMzB_UAv5u(DW5W=H{*?+08FRrhfO?{ac0Q3uSAII#k zzYrN&zyAWdba&tWzL?CI@G&ND~uUBhf#Fo|Ir}48$r?optOy*(Agr zzj)^2ncY|EE~+Dw@8fqdJ&(%SsrInFpuJ_&CdvlnRlm6Y6N*2V<)=ty#|)EGlTG%0 zU4eb0eY-uuct~Qpv!L{x>>QF?SY~H$*kCUxM~`2>XVa$kjiG55&b;;8_h+>?o_goa zpPc{Yl`CK5Kc35U22NM&(VRV4UyQHX-8;}dzRSBPh%m#J79wHfItlbFVlEU;JKG>y ziMIHqh7tBs=J4Yff$T02yE&tz022udIbA?sy#btgeReGKy_YGf_G`voP8+&^sspeeKm12 zoSp^@OHS7e5B`SHrD6-xSs@7>H5@|{0iM}qpTg+12J+j^P7O0lh%qR3jVZa8WvXx@%B0O3=$asvo`U``62Jfid$#L+o4Bi*)|xEJElw{4p~9Zr{?e)46>=#1%@UXFmjrw0H4AOJ~3 zK~y}k8s7`)gND=v>dzWIT|_Q2zb37lOBShXc^T7-%hNe8$=?f{eI zVudquoRJ7dvRjN7MnG;DT`P#}MniW}dQU)4Ol<;zwsCPKZCC>168brg8izzfC}VPK zG=6kk>7+0=qSjOt&OcS@KMm75cnVjyCLgRglhB>P%a)rgO4pc(T1vPpYUF3)4+eD|fht3T?AWp8h-E{U^To;LNB@V~ zjyn4q{l(e;IJ)gON_mkEmQiy?I=bX^Q2mu4zP8P{tMIp>Oaok*%eMqH%N+jEXRv6zF_^3&-^CA>LO9La}Ul;c;gT`Lv$S& zZmt#BVtsKAOX@b)4i>H(?&bb;FM~%sa#ffva0bT@@k^%pxALi zd(q_kCqD7#-eYL*OXW>5T+YH8x--_q>}I_CFTed4DeCW0R|*iG7Z~%reSNQPTC18RzKhBT6wc zQU}-Z&z5?+5%^+j%ySzQ9z(fl0!5T0t;&PuB) z>Wk|xLQ=0U>P8pezrUxiA+xWcyXeCHzP?Kz*W-YJaeFT8uLsq;i@K4{t0S?K#E_fP z9ocs&j>Ht07rvM59SlqZoc{2k{>;{1^A)~`>cBTo|XQ!4S>gdQ<9KaQn##|u> zIUT2US65P3SymQ443gXfyOJ_P-Qv9?M`zdpUKpwrTSvCLm!FrLFg-*#X7tVk95$ul z8Gxk7k^Yc0{q(WX7%8+i#*IqQ#PFEJ`ua@Vp|*&a%<9DY+A-9W=4X1l(Ni_tt+Xd& z|NAN;B?@N7g*W!ogrj~&H3pb5k%6$3NPEqi<<_{e{K}Qn{ijd&FFr$R;^O`*ha*ta z7X%{*W0m(%XbtQpFb6&re8P?GK5~JWIz})(C2g%@*Oe6mrJL+UAiaiQ%$hyfWP#v8 zKV0CqeiIQq>(?jYh}qZtPSp8R`52IzE)-ElYEDgf)S&|A4iwVHbYsd742<<45HOon zuMLM|ytzG`zIM~5y40e~S?_2EObmbb zHcuiHOQCf9_&n7Vj*!G-O!3B6hT(;Pp(KYlFCbKnoy?sPp6;H7k`CoZ>gJyANb%X& z&;YzZL%*p;l`x9^M$<=#-<$rq$p40t_5AvA{bkAJ)&Rtfd~RfOEv~!#EQcAi*Gcsu#ezht*b~qG(D@IA zDlSSV7@y1*H#aWP&ZyQX=?Z^whA@ib5!w0JVFyKq+crS(lpHg)3t)eHZCpivNq>F* z8VoSa(amkqt!&g8duS}jPP^HEi2-RrxnwbbXjY1GWHXaSt@UR$iHM&<%dHn zOY-7Y6-Gm?PBJ%yZXjI?iRr7%uc36~aVc3WKG!H&+}x-F($-Zgm{LtKmKUWm9+8^9 z^F*u6=^V7>&goUEI~J%nqNYRX*i+*AOYXRB_SN0HpL$7{zWesuNqjjl?Eoq|C;cF& zcO(PlhS0(Fg|fVKR8HV>N7S_WoyS&?0n-u97f4)mM`6jX+eQq-(Za-qIGB!MLxqXd_Yzgx^vH8&cFKqI{W*42Q2VZSh^W< zyJ(<$i%-R>23O6(ct8xk0_3`Zp=Rrh{S4Z&qmk92yqV-g#^A{#mh$=XE)}8g{`swAcvEyEQwnOqIS+2F zsE^UR@BY@w<3e>!0hHkKuCb^8%jRz_dKa(prO)SHsz34hj1!&5F4cb?)fwH|(a||& z?zGLFR}U@Hi}==%!C&>JoB4?K{`_Z_u7B{<_WYETuJz=4sQoAfhSZNb@~f}3oohbF zZ%JDl4d43Wg6EgE0DC<~78WXY2v?bJ* zVr9&0qYF}miq)W7=SauY9u6$I(PpwfsVK6lDYHww-cw)O9Rr^yT}bQ7ywJBFNN8mav}b;aJ(jq|7*QrGE1 zT2qsUZKFLQ!CpY7d3Q`;lPw0uW@6wILzW_D4qWavBrc`|=cXn!&%FBCE^IaJADln% z9(UGWkq@U=h2?r>?HJfou6N}N1X^8I_Fmb>GU$)}(RMfJjelJXnp8#JvPurIdqsd+Q*AcS@E=kRA(hosb&-!X@D=vK=8_ zEt=$mv3WcEcx%wpy91j-)542f8W%QnP8tNh7);0Yq86lx=}*3Zn10Vhm5c)FfVk9j zWOD=R_tV^HBGv^kU8IFQ9fSIu>6DQ6zO2I0ZI^LaPn?M6jd;H8SvnnQ^va%Yd@m=_ z)1@v$=@zH|1)#f--CV)qvVvZOcSb{>ct4L$RQlPSXD=T>SYLhcpyYJMk>2M8+aS4^ z*95&>gK#IJ4^X&EA=e)GR$M1GU*mJFncr8%=C18lO{v+UO)e2#k7)){x|7Xah|XrG zH~l%`xTU0PC&TP)Ad?X}oldPJGE&Za*OPN_+4Cu?fyre+D+kg8Xhy04bWNRIkZux0 zouIBAYVEcSJ~1-9h|_HwY!nn#V|2;P?{AAE_XK%5FRs6#x;dJ*p2>|3Qo4zHDK3uA zYmQEyf9IW*h3Z+YN(Oz#AA*V$rL zMDQhxrL1d*)>T`GO?PSOCXo?2{lJOV&kd%_Ic_i=B^^pvB%?T8quGDlA^7~vE3?kL z!ug}KWjr@Ur4rN`cwDXxnO{1h{O3zeubdXuK>;ducK>M$lXsP%pSQ)~$nPBIKdsP; zhhI2s=+eozE{q;I^j4Z05%j{iboN+hG)auD(ZtIq?<$^)d4Dcupjoq)J+*iD?O0xZ z`a2F(&b@bbvGvdN4PNSdI%C7mH)VK%(-o6$h}`m|56I~joL{G^AAN2^6}|rmiU}DV zw*DhA_}hfX?I}{BIuQQlx1_2FDd%mO(LW+uERDvc_+qL)`XfD*_HY;C^sn6F%eVip zOMegV!1df|VhsmRy=m%A#I8(L0;AEt5zK*YT-p|a--NHZPhwn5n^3YC9o&f?6c7i@zr? z8rpemA_zYD-K%e1{R~-L$%%@AF~bUU(duSh_b#E-pIHudTrPtbZJxLJ(CzPYvopW` znC)okS7%*KKJod1j?X*p$LVrx=&)l4R&*STnsBv~XEAhu z<@)DM&2L0PH-v6bz3bvi?A&~G^C{aV1*5G&W|z#&KD;juG<86|qOG|xDPEAC7MkWs zVgxZ1B=h1@Pq5q4Gn*^onwuS}-7GD2B-WOqs8`VblN@pW+okUa*&*9Do)G@yGVzX# zOiGIPZt6?Q#Fvg2q$jd3sjsi0s~dIv!u|`0xb-+);O}m-Bhi~LM6yr!rFsfWQP}Ir zN2#yfzrViv(tZfHJ_cPqqds$tIJ%0(=+WsI6wuB+^)bPa`zBqn8B)_dDa;E_Lr!07 zIGvT6*dp4AmX~*RWd+A~aqJ*3$qhB#k2a*79Na(TxRHDoK=;#hdqTjNjlr~-Vc6uprigUP{?#)V(#D)V|0ncx%1HOEr4wnG@5X|h zwJqz*@up+Jcei=O#D_NZIj|lDE?7X@ROlQD+*?Sma?aEsKSzN_9aW^hqjQ60dtpN0 z1Dt2m{R(GG0U_xr1!(I9l#+_lHD!_w1Wqqs52ly5q!gj`3_|G+OD$-r3(ijIQgtnZ z^3=MG*KxXJb$+Xip6=mcNF7gksUO*gb|0Bw7)a@$v%KFPh~w@aF=eG5ZpQUODkDiR zkMU94X2YpO2Q+5 zYDI4Da=_zIALEu9ikKc492oECWgA0DU}*x-&)p%+`_V&}sRL>5rKS9n%Up(tFK0cR z?xq7*_vmW*T{Kodv6>=NOfO<| z^mK8$k<+gObyktk1?omg*ZFh*%ENTvO?M7C(`m1SE!`FLB4>KX&egr!PQua>&i^~D zKrd^BA8QL|&Z5t2d~VhZhCB0GKySn10&(-p^5;TybD6s`=K^$dQx*go>Wlg#3RqX_(SJElyVm3IXAv@=4nE7#B}3@ z;qVIE(aX^U%n9)v&E1CU#kPSXh#RalM{ZP`nNS^9TbtA$mzYV`OI&|-Lx0?==t5L; z1Kp%EF4KD3l1l$O?)0A!eWI{6x;WW?+=u>^$+Z8hZ0#3uuWIIJ71g0oI;$3;TQIH* z2G~J!2wjk_UtOtlL+P!p%(Sj?y2Nz;5zn@6QQ>HF9!GDH@O2x$b=t^!(YHx{1y8zd z;cd6g-MxF(nXPA@!oYX?BapdqwJ0#%P`VaWkzz~d98RAfb*(zE4=32=ecUmhUyuhfppr#>(w zr@w)_H67e$k^7PSD|^y2!WJmF1ASQ2L;2Y;!htnVp!C!V*+fF7|C87dgE=6ja_sT zgCIqc6m_4ImyR7u;>)6`0QqBAJEJ-mEv3X0^NJvy`!@Hh{WfD-H&5Z+GZ#Pm7kK>R zGs1Lh>Ok1byYK$0;qz7dFI-r=TMip?8HaUtPMUP~#Qe_AW4GSAxigB2m5yVTk3G|Q z+sF}`PYBC3wa}bH!&;iv|K!5;uO3lR(%4Xuv=%*m?OG}ZSwg2Oe@7tU)K(z@o!l2l zow|4y68kDJhk)rarlZs#?ez2@)dA|*z)LA2ZRoE}%qw+^$ItGFcf{xC%cWi$s&+*D zPvuv~)c71gPY<;bB$HXnuC&{TNlc7%i|Om>+n3EuwoiV8XDw)r_>UkCQJ4l1sp9!UJ=t*zNT3cSQ@$li_|NQieQqx~u zZXkX8;ll*B{PweGE=4d|TJZ4U!`?M(yJ*prlT)yE3VNYk0zyv8U(3@C6MGJZaQY*2b z2n#yxo2cUS_1Wm-iS%Ao6dD*?6H5^RZH`hSayOPyPMS?AYYMDhmt9^^ho^;iQyreN zpZ zvjakzC)w!`s#}t9kNl1H&A-1N3OE@u>=TpO(43c4YQq7f)}dKYdJ|>ZYUe9iy(lu& zI|es-P^cb_za17dg2%h1j2l{S(QB3h(nth;I9_%enXhoV1R$eJSS8ER7;k8ehwabch^GzWls$84s$w)9OehPA5TK9gYmDL+a0q(haMd^g?mE6VuJvbqfpB zfB0PQ5vMnu7DtLlUq_LvsdQBdDaEW2ma7Ogmkk|C7nXzIEP!(^eR*&VKM3e7^yR{itIn<3a^j$-SBxk42sOKN;@zpU%eGvKP!tFo%2<6>6IX|4f*=GU8L&tsHD;S-3+qdms zcf~ho+jSU9f1nXBj2iXA_#1Ab5fL_Z$;pc>U^Po4w2vA;YSg0PnE>8Z|=6NG5NdK;!=!3t#NHwHWrxLq}&0Kmo=9On|9R9+hp+mWLFkMKwR-xyk zrY@r8(NeD0ICe~W`a|y?gSp=Y){U)Q@H~|rmJ-;aGEp2aR}Uem{|lPB^U0vZFXcv8 z=gy73lyvE;+00d=mVP*LMRN323P*4495?dVNUBJAh#NPL&W)|zb%pD%U}OI$C5syyE+zr!g7o!R)E$lr42mjyr{P0eQbJ5AMMkiDri12~ zka}NN7sm9aw8*qblI4`eiztli5ny+7OAqIhzAYg@5zD)bNamm^cSa9_g7DOtE8dAPipMpskE&WD#;{ z>;eSes*L!Cwubu1(M8^6S!G0#lo7CA>f_^%kl!H|9<%!`)B+HCH=m` zhiz$VF{jTwcY67ch&fN)aX7)7sRsC%)6_1@2|Y`3nY%aT1Oj|sKE%DZ*!8O z@1i}&UwWzVz=}5yYMZ7q)tceU%Yev zy?0(~$5n#G{cyo{dKndv#UAgDUA?=hsVR#@#sWJhVLF5ve1VPbHlM=@3ELAK1&0r( zt^M`?{`FgDKF-;3^OY0le|kRolTGWl?%VjV@52ig)DibW4R20hcc6Dntxt>{A5wW2 z4N9rvO`%{EbGWaEk7ufHMiHEKRr$+itlhJK`lbxhQ*sLmHWk!myXSP1E1%*Hrpsnxae6MoyXf2yI}7~j zxpf{GU;Iph4w)$lUKEj%y8>(z_k*tBqCEBp*Fw+9l(}J3qWw@L#RT*jYJ@v8$xrH)o zBw{fT!WMxu39$3G#+{jI0#Cplah)S5^2GBV;Jpf^ZzYfxI!5Mnb#w~!fYNanc@tP4 z>-;nj4O+u+y3!d<8ly0MDV~>yI@hgJ&FF(i#NiUpr>}buJiq6LyU2NAZJjm>vp7wk zgTcjE(@$!RdL*TDZmY`UeLBXQ$-0lb|jarm`gODT71_;I#<9N+Fr^403ZNKL_t)GYXIp^ z>x=YsQqxZ!h0~vX?$uXMJ|Rq>IQ{t-2h?;J93bxr55lRNMjl!)Sqr!B=^i|F0%$k98;rTf&TtoZ0*c_TCoe{J@ z2j5dCdcsvcdM%NW=2Vzoz;vEYh;D2zOgaE~g}tDho9?9O>eDzHFu&4&esXe0RB~ZqTSJ^2J0-2jQ6G*g zEa{JHD7oXtTZRoEdh4yX6|;R+Tid1RV^L?BrWDh9iKG`WeF?S~qSI$CTLPb>>%TOM z*}`s9LhAZ@{l=d2#pxS1XvfJTL@*u|r4MN411q9)v~&@?i`unm8(A;u3X@IG&Hd2j#!`p&;@$gn%xf zhK&5nR}rvl1of7se|g0>YKx00bv_t98(X?cNTGDBgnb`_iNA@0sHu0#3abfqjZQF!;=$3FWE#oauXW(j)C$%yZr z$NW34&L`^8Y?wM~Sm%lrQI&Vh8#nKnXGT6VmdX5$6tmC>RV|#9>uyd0b@Pg>rSF=HY*tSU%nP_CI+N|z&i>a--yMDmMkOmaBjd_o@c6Qwezb36-AH+^g9 zNQ8qNzRt+NsvbT%+;k3t#zovn^Xgqx1)9qp!#)~=21Q~~-%qMb-2O|K$ablw1-40B z6q9o!GqA@YrSllL(Zg#UHhmt@6E)n^C&2+qdAfTkK_oU%1*F3CwbYTuQi194vwK6@ zh~kdWAgWL!YGYtJZ$#3j;Ly-4tS<$Q0wO#RIg7H$hRIq`6&8;-#t}I>EYJ_)E0>t= z@b-!EB=Qk)ll(@BtoRW8h=!EU2KAHdG&rk?0KM!w`V|FcWORRi>{##T-LPLbqo~_c zzHd)zTXXtqH_VXL<;CUIDC|%F=)UcU>4$SDlK0_Tlej2*;CN6^7z|tA7B4T>jy9Y>CHdAyyeOo8;{|g zu%_M7lJ7`3OjJavcR4`&(MQK$`{hf&+Cyn6rSkz&RFLt`sW)U1y6T5)oQo6ws$dbA-*TXX`BP=`vETx1Xr_4|7 zNY$E1Mi-yDf-=8?lsbdhIL`f2f<3bF{8(x_CT!&N9L+&_ReNHYS5e0tnYyu#82C-u zyhT}AB(Cu2sLS5W7{K#Arrz{AP|x+5!7u&B5h*}r#=>A3QiPnyD}LA2tJ3?`CIYJ$_fq&7V~@B5!0I+ z8!}5VPH|ls^%1d6?%jbwSkw{J`3)}$jiHNDDpnfr_&zY+GZZ11Iq3JnZ&ei}F#oii{U&xeT{I0w3hOfiwVi7tG-w)zVUwwI7@5^$gpWL={`b4n$$ecM7 z;dIhp@V(IKh@2Nr`q{S4Br;l@P7$e7Pahz2C#Vb84YWVkD{DGgjFQgvi+oNeXwqI- zrlyvoKqozaM2AwTLcWUQS$PHavin&&SZnIUYxVet2tX&M2TTHGkP9}f# z=jK{2OJnD17nc9`>(z9G^{-dcU5qX(j1$>`^k*rkRZT5hB<4TYs|Hi|Psj7}Lnr1K z)trA$U>sLEh|YgoVY$I@$>`?SsOfAHr`IMXfazw3!>T2bT|5NMRG}AL)-jY$KHD5h_SbhLtW=pUWz{3Nt>nO6U5z|h~9Mq zOvm%G3q8GX=CYTFdf9#NQ!l+V^Otk6sQ&|)UPwRp4XfJm#+z0N>6g@W7naMd4#Gq5 z&MoHb=o>poR{+Z+eE0n9k3ajLA4TZC)bQv_1*H1Oq4P8PI+zZX?-@NPgCLkHzPEih z3DXz+!>H*YV<#(q@KzUd4V*`hze%wu{{WaSsFZO2E%CVk-LyD@(lMtSSOwM@*i(iN z|Nih7MtnGw)bm9KSy?U`@ksP%!g08Gu!X`_RVSsMLrpp8ci;WNJhd7fI(g{`8W;ik zAC9{P{|VmoLx!ulE6{kvEw_x2l0J2mnvf2&+~=AZ$O^Oh*sfnKRtB}f^q~TD?qTRq zn0@I(q{SS1_t4cdOWxmg6oa5(%9tH}{Z^Hz6HH7oUsJ zWmV`#W^QUiy6?+u$h*{hDKGC*UQ%tSTMu4zIu~(A&^VQ<66^U;U}S{%(3jL+Z%?O( zaVj-{q*Xh-5z>QDTwyctP$4fAJ8~9V)`ianF}$lBGlZXqqpcyI(yP&cPlNU0gjhfe5n^U zX1~ltkjO14GA$IiMY<)#MW*Pw*wCh;s;1BX{O+-<^-XA~HE?=bZe4r3U$&(F_{16K z@VmVD!HLf=UFgAsN@J5+d(GOn$!dwlr+#>CO{_nkt4mjB5ITR!;HpZ@gb`7QmmSjhPjca*iXqxNHO zb`ivew2fSeswA5jRR|E-E^Ju9io2!A|X) zyd7#wJ;dGQOf9+K>NhF$Y$j&!8|xkpl*T_={*omh71!L z-X9jY}FqBSjBT@R&hv4*e9cNdpTXA5;v319UQn*~!p{uWZfD9Nw`9ZK5PCs}A zMrUoxbYfl5$$|9CC&6@zPGRdgVt|bAr-^=L^kwvh;MbK??hX!a@Zw!tDIel9b3se;$iS8M==4uPTlj_F-~y zbJE<~ZuGxx@^^0>Sy+`%KK{!4;hRgTn#A)ze)KqMdM;iWJ?I0O`|4{!V!a%J__t4V9SK3+WQ%p;QKxf}V+M;K67Ow7CU<{dgjh09}T?S}8otl?Xj(~os-UOM8# zvD}ThnV!H1nkkv~N@mYR*y8yyFA*TWUQRc({hxw#C(Y~KyjDV*9=8OMLZIG=`#gz6 z!fvVQi3up``IJz$Ra6rar(Qw*`nW`EQ8_8Lml|lfo9_Thm3pwIL+VX@ci1As?J<$G zHg`+N&#XB(LuhF}wLj`jk;iX-W&+LA>C*|UYw9g#R{;qtbY6tt({1kI z8E&PeV=@MHCr07~A5@f)Q6CrMEu*}{hq##ro^)JNVr>t%_0F^*qmRZ$gW41l(i4+t zb4!=QC7mkH`r1faA`M9C4QZoAqdToe<6}cZ={*`qUn7aLs)g0c+OA9*kKz_656+4W ziw(^$q4YH_lOuRuByZsNrfsBGiX*?p7+whcCQC3Su&Bz5z97Q%z^p)VHz6B@s_+av zOYyqkJ-`X!K}e1t<$9c~M~khAS8XA&B!R)PSxrSn7p_j}J@%`fZm;aRl$XxcdI33w=Ep!kcXNz?zG{6{f@Kv1@C{K1r#`$+mBY)7#t0Y`n64 zdqRP`;#0gl0#nM@@7uTUm07R6jX?g(S6+GL`0-CppZ@e&F#XK~(f#|8>uYQA-=y%g zW9YZ)g+qkG&`p~@YF|&4e%+N1&i~{mKRNYyDxH)33Jea1f!DdpSuvEp$%`ICDGE%q zhQbz8BT^&WBHU6*F^ssc<&|H2w)?Y>;q(h>CCM}koc-hT|8y$4|MkZo_6@^UPD|4) z3F=vD1{9bU%6nV3mRV42a5({tzP=k193JW66!S&~#ikX7<+O;?8FVrQ(P^~ggW-jt zMXL04BaegWgvTJxXDMzJ!^~;^kcS1ZibBbEkHb_lRJ;+{E15l)Fl3bWyYSxKc3P@)I5bvNe z)TRV=@*FjS*_VHxKqx&}Nh}{R zjc__x&v70dTDpem#sw|2i^24}ObgP9P&%oMi0LcNo{d@;)p20OoyW$lTd{5uvO3{; z>mIo4JNHaNyhd3+as)u9<I`k z_pBe|Pe)BRoGxh@N_RP3jEHVsaIT)j$Bbq#0i8t$cA6;^s9J+{W)VDzW03kz1Zhd= zmds5#sU>^MrsCAiMcH3IY42;Btm_8cF4sZ1*~cZLbAiVZj5`NBZq~JU)oA4|LVwY< z3$OCI=gcKjIBG2jcyU3xd6qwa^(g-;6Y-{_rn@j*4s=zHDuYou|M_*F(@Ev=1e$xo+(6w^z7HIg+S@p;LG&CRlQBqvXszpJ%m zf{HII!R9=nGum=%n|v=&v~i@%x&ZG7tQ$@*_7D?!=0_&X7=?4Qii6>k?^(LY73*UcX_zM)7N+vfYq0*Wy zMhDj!lB}&03@u{|8^r3IQ4%WGi+12HxZ>SKhX4zwm)y`Wo)^LVO@pzW!`R2@3kr54 z%5NT<+*d@^Tus-RLx<>Gq@js`aJ^G^ZXRRkGrHt5p__;9oHy^8VZ%s%+C0Jt@aC3= z|MiRp^CL(fyy&Jyv@Vs+#pvl~USdoy|2atKy^|d89Iik22wFUw&%fpd_?wbX7WIkM ziIj`tLdUCul_VuKR)mMH@8H)XO%A=gsgbnzNU0DFg7%8K@oj*WOqTdCOwe8MqOoPLaxBr?5rU7;I78Z z{`~&@^wHt*4(}{FN>U!0Qr42+g|ZtP4_9)d_}Ho{Z(+JyRS~8ag8#rg?=ocJ)DSnq z`{)XZuIcGTNK9yCWRqJ{WSRx)O%(W{d1iY6r+wW;ksCh$^OW9`^^u+%3lb7G#MB^+ z7PQ31?pd&L`;`wU9)0zV&)>iL{>KRIX%}*A_8e+R-~a3>boS-3HRaiUDCRlY1$e;| zfb`ScVEcCYo4ruGW6QJG?|bbcc>c=UpS<$BU;g5i*N%U3<@Af6eu|#{;LhYNZ_Jp{ z(;bLSo>xz#qI)1}I+%{@<+ZJEzrC{H$|oP3KmU_c?erS*@QIKwTmwwUtzL)yg+WqE z3Pu#e%FuEZc5YANE{&92yW_r!izLgu^@ooy;4fq)mo~26}{Y94gW?J|ACLQXJB&VP<5jm%#r7Y1a^lPB?(0c~t8Xy1DZi zxENjMhSRUxpxRN>*XTt(O)~>v<$0CI-aqH%Yu!NH2!Wbu12#OG34y9M(MK!cbe?TxGH2kq2wmd(T;clM<8xav=q? zB`4-TG%dQVdG4*x+!l4?cW=2vR{ZGBV;v={qR&RRX-?9LK^@yZpgwouBU01%KDB!; zsD3+Lj`q%-urS*7_4+y~LmkDe9(%2H= zYf{qp2-EXZ5zchL{Og8FORFqQXB7u~RmLCye}M0O@%ouVV^M6n6B2MCVP+`oCZ~gSQl@?5i(U6i^RQj@(UvX^%sVN;Gix(b|;iBvcOc>I~C^D z0Fsx|ugJo5YDifbG2DXW5yP>!3$QV&&{7?&=H~no$w&byYC5w5gZ@_+A3_Az^kC_T z`HRUcT;FwJ<>yyTc)Gfb@-VQvF`XNOx`B131e1wx#O(sKD;Q=ol#aM>95_4+^OW=q z7cF{0pw4lE!QYaYu1-$o1u5#q3}bg;>wkP$>GRgx@@>~2cQ|Cg2P>LI9-Lm^*O$3J zj-#H2(lMeZkb7Q%eof_QT;n;_^T<7$g!h=E?Ql8)5)_Vx0}Bk*l%{2fREjVXhs*WB z5!uYVz8FV*xEtn~1`xf0E^iH5)q=`Y6Co3Ck0F1~hRN2=EhrV?+cT~)Av}NCveIzR ziUxaVJjJV}-X%+tcs3RN`T5b!^j%7b2n+YLJG{cHGMkfRB_EyYX6gEoZgvL~0Bq=q zwV8QwZjp{s&(Y*160Jh~BCc}G(C%5mY1p6pxTA2QFrs(`s*Pnfn4VP@TGou| zygxI1bh@7-%R3%b7N0pNpAuUX%i#pEWKDTs7?|EDOb^Q{lN3t~cZ$Q?+a8{gigxOq zXqUwR_p%3vshiwF$*>H6Xw^ zho<}ZcDVb+-@mc{SMR??sA1%VG+@{6lcT7YnI%+~Zm-K;P*;XYq}&U{Z~x@<2OoU; z!Rh6%7w}ZPJmBB*J!`kVeO#EX@yAzw@%G!VwO={?!Ly$p{nMK(4jeeK<&FBDCVVTz zP{v~Yz;a?R{k5&HUEFuEOS|GuKlS>$mtRCS*53X<^~4?^mulV^YMWPdS}V^;?3KJaf!&7+yV3# zsq1;x*-H!XySQU}QIjEz=a|6N=1BREszE@TmO4!wOBggw?^Kia0?R7`k%>bL%|PSr zwop&OzGxl0N~}sqBN5aCVkjY{&YC}%Qg4&>LIuQv&@AuZAk0giq2a=GykVd^ok=sQ z!a~)a$cX8Hx26X?FvBC%%g;Sjd6b%`$Y(>?I&5x}<3*tEq37U7Ze)KZ_^erb%fI8^v zlG0sdZt3WT)}N!S(z2r~HNCg@?B$ML?i50wNa75eI@E#GNb0@MKPNQj=fBHgV$^i; zuOQffunXCBZvD8n82C1u4T!U_E;ymw?Co0DZAIyt4On%fhR)@4F?jx}=|<|j!1H*~ zTycE~sg<0rq;%ee7md^}GmdcGih7yz^0PmD)%gzvqzl32TA}8euq{4@;da^6tt(`W z;};@VUsAgbOy^TQ0fV|>^Mp(;RXcP#n1(U{03ZNKL_t&`pUjlRHEggaR&&6#nZBH@ zC2?)7g?Wi~g!MR39jJ{)J(nsDunM``I5W&nsyQp?*vPktwTt$%ez=AecIVo2GO)w9 zTcS_wB$tPOEEBnJvOTXEUZ8aTOx7KgI6eOgwNg*b zMop)3^WxU6TT!#;&VA%jT7v@Qd#M*q2Gn&zS)Z_%be9Q|)gPU9@4{rcUJB<5%yPd7+vr&D3y+-qkT6C=l8Ia46vg|lM5r) z%SU@uPG-W>|Juz5?&t4+<;K6FrWb?h-}IyxIj}7z1xA(1=o(-<()!e)H{uTg(Xnse zG-~_}#Ib^`c z_4DqJjrwiwgxev}-$cFYU@)EJ^<9T}G?6vS&9@yobm)=Kt{#HYr|MdH+nv;nk`IpS zSA!-R!r?@#WCJ|eT%;?DJ3CeZB{DStKL~GLKPq5B5H(qK; z>O&EBs_9h8xkZNKUZJEEsW{%zm6X(y5=dJ{S=8lHC)Lm$n@DI(K75Y-wzZiuAPAj% z6|MJc!2sDc@@d0Z>SNE3&iAQU7MrlGkp->W$~-@!LYV_ZUOG`dQhE!~G} z8XQ6Sgi4Ysnd%vr7njN7CAvBC8uA@FfSXyL7Z>TMaM(PO8Y&vPa`2+#F)xaxU1wP= zsUdPjD>l8HG{!8|9U_fl&IS^*(z5h4GXp3?#SDR?MKV0$9DzA0vE@neDLJt<=)UNt z@kx0NnVwZeO@3LyIe>b$dl{YsN@5W*OMN_T_5`a{JS_vM_j5yQT|h)2;T+f`ym4E^ z*3dO*N6+UR!9RH^vF`Eq8N&2#TS9xn#)t2_Z~5sjUOe~Q8_)gf&u_i;{{C(#y(WjO z#kChd`)v0t+%U@%Hl~IJ5^R{2o#IoFaQcI7pMLu3>C>-oXN$XgaCY{d*!8dNd;67N zz~_Jb|Ng&UAgaIpcG>pjpT79%vmb0bfAGyWUp}#FKjGWuYvFWhxLDaSr>}qQHD&*- z1=CN{J@lO`xpZBnS{yB29^Ubx zZd4zKXN1L;^_2&v1!BKR<=H^q*0=`MskzzMUI>7(7Zi}H&Ha8UVJM!R6ukI z>Rvci+(pSaPl_TV#pzYZ=|QQUny=wrk6}mbFGM$n#&b75!B}E2tKcOMaC1*Ajq&Dx zNTyvj8Kx`tct7{xNGLr8|F|ksLxU)XHe$L}cfq}LaKTezIzuwPKwW1{1vG0=Yf?Jm zI_#b{ALMilFzz-RO^+1OsD`K#+KC?W3~;LHAx=scsNeM+Q2lN={h^6Vp9ItIf9M{8 z)uhf99ike9%lUV%7`NihaSyI|Xz2|@j|tB4z=+U|n*QLFDYB-ko00VN>2oHolW5vY z2;&i2PENs~PNX?{Izk;vdM~m%db%kgb=lJaUSoW*)O1n0OI-iqbC)qQQzv>*PV{5S zd^u<}AT=eV9lbkyxpK9<={rvv;x!Bn9=j0SLh@@^4sKi6eI1Kia4!CK%H?J!7oA)C zJFn5*S&(j7TqK;!nQr}ZK|?!OYtEGyuS-eS6_{QKczO0&Al+%DF{P=mK0BQW)01=F zd~P7=1t&TM2X^A3Cd(y` z#Mgw{%xZoz5o4$mBHo21O-ci*8{+zDR#ehf3>7b%0HRZsl!VO%P2DiML2gkuLlQbZ z7wP0iJ~tcn^#HCfRw_CRGlcM>bcFP1yy&I`Su}3C*qVj$r7Mk5TDqwWK6^qvglMH? z9c0dIR;(BsMeXXcJ8r#W`0($}n_nDV z+1WX_B>MAR9Vd|a0d=0;vSJ?U(S>s-%zq4<3o<%EjI(DyTKLqmB{Tm4Fde!El6^yV zykQ;i8Zf=U;#*EXjny2AR$jx78JJ(LAv|kG&(Wp`P8WUutjUy%{T1g5IA1l$QqyxW z^r5B$>rPYq&*($SGZ3iYesS^2H}!n%Us2PA>80P)7v+53E=)IgY4l_hcLIK^&*+WQ zDsLGzo?sO!EJsn@Iezkp@giFW94a9F5~;)2#^gO1ke<4;j-akX>SKqqS z-ILaxljCmBS$~mcqQ$B%-F{!XuSZ##(i`!JUpWn>!|9UKc{bSPQPcOm_O_AIU;E?l z!1cF3+Pdk!w32`egf+^B0bkzJ7fT(C>?fJ%Th%oEJ^*}EF_QqoXP{>)Lv5j@^vXh2Czl1*_W++0lj0l{h2$sVf06X9;Bpc zpt>hnGjKW~O+GgIA2FQYqDmAoYPylrrKZE_OP~A>i~A=&U@(1M=Q?aJ^7&SF_^(*; zlNBre`GxUI#|qL9K1lJX;dB-cPMNcl=0-bB&dbT2bEZt3P8y?8(^Vq~r<>M8aQacw zUcN^eDT4ay=eIofIkdXUDy>A8{<4(rMD^#MyR3+9oHhD^)X`?4bov=ttloQ|V<$zV z9VqG@^1Mhof0e4v%Tm^z96oSnVBC4hb>(&E=4uzg>w>`ix`h+nc?jx3Eh@KME-p^D zh@EOt*JgNJcJx<~%oP%U{dktvqg-Ps-6C}f>aRYx?*1p2K6(EW@VgUNP|=m5Nb5Ap zL($Q#;W{@eI=02c#L`3uwWAKCb%zk0QJtVz7wDX|#Dq9wMhD+zI&fswgXRm0E)*UyVQ#>$V4gI($<$8&$XkIq%vD@*4&pb2p zDXHlbZhv&zG&FLY=@S;RFi!Q#y%Uo6RwmCyO$W{QPMfwDyrz5TT%mknF^(5p>K(gQ z@!g}>+n=}UM5X_Sw@!<0EV=WaZ@cxoLvNW@yzsVXkkl3KQb_4&bTQ9O>l5ZqAUJ)( zqg0UI%g^lDkKK01y^l_qJFVFD_4tK0OZlS7<43s^X|tDtVT7d`i>xyj)FO&6 zTH4vkq1qA8%sT{_&wJ+9TW%rz@RnzuVf~rT%~1NW6PM_m^SQh$=GIcOH9e3KMGcHJ zB&37e(6;t5n~?G4hu1J?MrxOb#=>-?vX9t|n65P`?&dyt=FYY8qh7e_1;XENdO`U$ z2GXaR6@j_4g4DbvdQ!Xz8qQZ~U2rbH4$}>yL+E;E2GsP7wOx`LlP)%Nb;Spw3zO!O zcgaW>4RN?$jGj(GDQ**vK7OKNo(4J&U7)fJP9GDA!<)qM9E>EyS{Kzc%zA0rQ!mZh zT9K6LNbn)hg*HRDXHD`m)AMj!W&>XYjinI*wBz7D8}gbLOD177=Fz|c=OJPV>CySc z$T1Za(G`uw`4j>=nu{A9jY|^a)QDonnC6ni9SO~G2}_nFY|Jakr`9tdJ+34vp_M)q z)f}^pNvvo~Xe*&;Dj=qzbxDJ}yQ6q!CFUz=g`F#FCzP&)4XvhuPza?|&$rv>*bXU?o_e_d+&Pu}_BVbhe;g~U}s9(aV@F?DMSlY=Pj z!gTh4pNU-Y=3VQqsXYv)@BZv9!|7sm#;^DT>Z!j}y!WT)r@hopwPsz)rt-Bln1L27 z2oA=s&tZ?I*x0q@Yg_1Xv>?o*EGsmtG$2*^ohC<HFa0Cn;n zoez+!d(|R0)zi|`?edM#+7sV7CT|=n*i_W7h@&Ga;>5+`5$Ks}q;EsfHsIVF7zfm4 zQx6UDDRpF)BAi3?xKX@g+#L;VNj8qK*dpCL>An?U?$&cbD04@0_x(!Uv6P2r@QuZH z7gY?BZKOZ%nCe%B8!R;(}U?|>gQL+6Y=6uhaI<2AQ;c{gwgqvi>HMu2fz%S ztKAX9$7X#`gkW$HrCX*K%kuKjLzwVs`T5U(W0tOMW_R7!ZhjGSAXdILeH!v?3~4zbek<42Mok+>@5T}SvHs2 zQsi1DDUNKS)&l>v3K5a>+tVBQh4j;+jd14UrjDPS6oQ9r{ohbdLeo`w*6hpif0x+wfpwH zJd4{O`@y^)jJ)lRasMcoj_GB`jx7p%aiyc9r5}AU0+tR5Nlo{K(|t#$pB^B1r>MT| z4P9?J%=I~o9RBqrie4@?U9$V8Fw}Ikb&?yM`uaz*s~d9v`Wt_vwu0$j>rG$wkD#VI zvDi|PjXn-*3RkC!IY*5cf74W0DV3*FrvmAn!#YZu7e9u6 zehZX7cGxgWPTx!~p^2THS1(< z(+#6LLH$dF{x>e@9R$-w>aM@>qAnUuf-!58)+Yh#4w6*z@~A15Ou}bk99^UV?ou|# zB~_qwBa}4s_4P?jSGpQ^r(kCr&zgNq<6PYku4+ zj@ph1FX<0RuWyShEm@Wi>E|P?N9@RtZmW)NOPo>NwyN4z-PWJqTB7=@#J0lXxCNd` z#niq+>0R_O%2`mfATTi79g|3z_&hrp;0C!3s2eps8}D;$T1!J&OkP{QJ!Et!=40Aq z#s_-PW;8YoYkGE0HtrYIm6{ULhW$2dJ+M2NE7AqYK=c5&@Bk7%h<&jEMwkmYDoqno z+hJaILMeBJ1kU5erq$G>Wi_{ce)ZiyU;Vh~0?Cjx*nIu;$*L^--j{GwDcd~qzpT?Rl*9&Pc<>lT!UUhW^>-TN7 zyy<@g(tknH%WL_xO#1X$)b!tDsyXrUgKwTVy}YlirOPiKr*_%;mQ8#1Y&!lLtwZ*$ zOj!QK=?~sRO|QES({Ws&rXxRh2LiWrJ0+cw$nk-Jnoi@>EE00!YY%U~^2zSccK_NU zbh9M!1y=6KEPlj)_W4=u5BuhBY6&LS21-xkAO&iAAd?Q*zpOks)i>BTwxz44NjaXr z>ET7HBOP6pM#Cl(12gcL*RL=+q4kmC8iNF4mT7ae9PKY)oDz_{_90N?J4 zdm+tJ2puY`3yqc}rF)Z_7>Q#+t!e>i4@jK+ml(>o?QWrCfOO!WmZj{b8q;j|Ko42l zy?tyRZe$q=(=&WC()Aw-*Ngg{YAu}CB)^LSAOo>e@o=d7JRxsCx^bb}W1=bLNyeKa z0sJk}_tc;|(?**U(+3Tx>3})|X1{;pL*IGw?z``%73q{I4@`XE0buI^mPnpRk!rvG z&v%i6Yi!_TsZ&FW`TPiHQzjDhvJ(!+^+NRGl!*^eF5efrwi$7(A+d1ovuFfa}=F!tm&jP z_MU{lm9=PPBs$6bnk4R2#s%Mo*0u8U-@I!5h|LXzo2_gVt80_lg>_a8-a89a4TL+r zEx@_Kb;|`aK5rqHvv82bx$bA#wIn45#ChL^dZ_(itpBU_8b$Tutm>s)4VD+L!iQx};s z$uOlsCGlSj=-jFxojz&Oy0f1f54+Rz!u_;0aF?H$`{rv&M_W}wikwc*z2=eQW{OM)?PRA@PFe}Mt5xZ}s{bqm;R|(Sh|CxIs-mRR zg(HtMQW^cf|IgE+@BC+B`p{=?9WihI?Q>_+uC!!=zy9nO((@^LNo(=UB}Ue}Zkqw`wen9cM^)F>^UPd~3D>w>k+XrADI=ltY`YcDEk+Ok1|!i%FO z*sVPhm(9N;s&bj@bCr#lUKGe^FZA~>EVXtr%dePT((@KZ-8pTEp2k;4`jTmP&R>=} zsG;?`YreX_+p;@#+x!W4Oe?we^ac&eOpc10(B>90&H1X>Cv%to9n%Ukue-BBgTDGY zzI5eZy#R3z18^Y<@uyEF3yAj2w zehW~4=%LC>nU@|LIut-3cH@Wqs@o?&W5;%OPGM4iBKerrcZj<*(2S*qlt*%8=rXGC z7;s;xZlYq$Gnl+|)Kp4JhXUZ=m4H5M^RS`AzdLkjr_=4it^#s(K$4a&Lg!>yoeSgf zyqL$i0TVpKObbACRmr+2-GKTcE=f$cUe>jj`M1}sH$*u({5aq9(P20O)~*E8Kkfpp zD_Y9BDmb=yi35OwW<2QxFjBv1gzt)qq>6^d=A_K7`fdtHh3Pn5_JHZ~Mj$aSSkR^D zzpeX@w{#Ifoq29&#hwg=sd;L*4jqqF|Z)q=tsP z1||t5ZTYC~C2>j7d<-V!mo!u8nrUy2#wi(B8<5`9+~5}OXv?&hEK9Ds8y@-&k{ zKt&h#mYR-uiRT4Iq$zz;19xBT@Wh)g&kORoM@nW_Q&m`Sk_qvHLA%PTs?>$lsOe={ zDQi*FyVP_v5H_=U+IU@5>DfH#{%E*}a<7OnQ2Lr$yAj^;+{ET&(I#_aW89_pj~%;; z&YV`>(!Txm<;qojL*vCQmoKlHQNRCv)b#f+bYr-tGBCDg?Zq>@KbyH2=lJr&e%^lh zneouF4>$ZkMWlfGmF+&U+4RlK4sPG~+RA-KM}Os&Uy`4GeDRgn|JUy&r+;wzNB7-) zWy^s#U*7VDcPZVSym&{-%aNYf6ZfL|Tg~If^zz<2U*!54bGIQ@$Z$bmJWLyp+$%Lb zOU1O;Kp9N;NGVs@ZB_!9zIFHSK0AY){%8IC8ShI`pMA`Zkfx+!bs=B&IC6R&jLtlR zLQ>{V?pYXwh z3&O(EjFi4Wvxro(UFw4IX}J-bf`23|C^&de9R~FjUIkN*n5-BxWusyM-wX1%k9oDO zd*u#-JZbC7%(;jAdvcBt{s^4jd$6|`MIGadIvpuNT_vQw-&@^#lv+zH>Z{PxKL=>P z94kt)QCBdTVhpD-~+p@ z6-x(@jpfA2+olNAc+hdXVv%3q001BWNkl zi|Y)aE7gU<(Jw<_548Ow3>Z8-WXEr4apa16k(hq;=jJmp-SnRjr~hb+)AeE? zU5jlqcI+^g^FQw4eZa&1S0I~gTm_{YHC^`v`3vc-Egx<2t>W{}!gMFB|KEI9D=o{x z@RC7;Do0rBH=3e?DAE&$jL+9&*`tPx8b$}vAtOr%9=c@IkP%VZXMCR779I_Q&mUB( z2=wuSWZRwW?~i^yBr4o>E2E}|B&*HQkRg@VV7VBKy>{2FoasSTJ$AEcd@Go zUv;I3@kq+3-Zw0L=vc>{G#b0*7P-+G^G41iBk@))e%N_z#et}GA1cut!#O;z2ZE6e zof|!#1&v89jt9wAJBmww)D2T*aUpqqGUcd9^j1mghf4+Jx-*N(b+3BT+Q?S@Vz8IX z1yBdiwcr6MA2lbvNMlX61a)1q5dA*|>bPC_cQHTTcD?nv72%*Ys%*C(wc=upl= z8TBZ@%%_(q<)r!fs4}=w8Y+~7Sl?G4PdwrdnbXx7NacBJ>5R0tJO|Zw)+;Z)^2*kg zEfkVwlH(Xx9YY3;am3)P9aKdq3|&a!a{!%#_aSs5(ouXRr_;K{4OT(7muo#gy0AGj zv#q!|uQb0T&L?h3TxoN3VrFYztu4~lmS+pkZ_f9uXs#v0VoY^(Yk&2**6Q}w{xutB z^snmQkl%VPp}&M#LQEon-`L=n(%jbWmcu~+1*F&DOM$bqDSw303xF9Ao$x}J?Ik-a zSWPf%y7HP)o9y8sp2~T_77-YTQ6(rWENf*Mw+HFLbdp{gn&UD<2UW?NPT6L8igy>T z2VuIZyl^1P2uyOd)XvZVpuKiYVy%r9_kcQy;j}IdUXZo@N?i4-W5ACQ0YDh0!u(kUfMor&SvtF*3Sq)(N_V_GYf+N0$q{hRq zzYe9Fu$M2E7X*9Q6E^zPwd`BG^7w1}UfH_!l~?v1KfeC>))rhZr!l9?GL!!Fxov-X zaNB8z-R^Ms@V;PXhiqRvejIQ5+O-Khj}QLz&+jynaW2$#jRhX$qwu!mV6Jbep|H)8GG<^3xky9*)?tqbcdsv>&hFuCad;DY>9V zosP-_g9DY8Nv&@-F)u0Qxuy!VCNw-f)lEHX!)SBm9#4*WofqF2*Cq!pq)z1tA;g{OTE;Z(KBF>bh z#6u{C)R(z{(bRccQj1a}>6^q8lfF+cT|YlsF3E=@dELtk-M`c?kswrRnGL7A;l^@( zo?Dg|nO^Rnv`z}=J@*(&$Mf<4nH)+*XRNk<51c(qaP+QmBW|Ip6yveRfz_O}&x4cZ z9K5`ZE=HuL^Sf^1J(Gm#z&T0jN1iy?dyv!@6_RozIQ{vZcwR*6M~_~{nqu^H1FvAY zL3IP@&IRU`ZM}1(qbt!xLjD1)E?Cr$AfzLuTPF1*SkvXIu^=7zH6peJ;1+g6!xnmr z)-?=yYend709?mqRz=EuVSwQcqnmkyA$8+-k&>?G zAWFA9FS=-{>6a%`A)rLYSDhc*l!j*FdWo*|PX^ShA$IJE7!(sT>y6WePisDTxtN$q zB0BjlF|`nQ{uqcTx6(N z)PVRoV|W4Ak(hgyh#_y6BuSk@iMl zx}@|IlG4@Q)Ns0a8lbazT>LjiOEb9`m2=|Cm23QFq=E73I$< zDvA{ie}=H#UqR`ZU8J<5r~6Oat0YEYIsB-=lXdzb29S3RM;d+8F^2m(a z%q}cO4&eLsYI?~0A^x^OgB&B-W18!R&hw;ik4R)So##2hb=6n)Z`R8J(;bt|Ig&#OKzq>PopSk~Ne~f1=Kj&=F(Yv5~jkHgDb!45v@} za7yPxIAdUM?T2I!-4Dj>BEJj1mQgGSi(z4Sd-CL^H+*~1REk(f-7s`1nmiTacwL4) zBuXbjW*EB}?ObQ-kfd9&?mR7>dczGjjKaVpn?2IGnSAI)FVX^BCy-G`6STCpnAdj= z(#?T_ue|2JxF}P)L3OTiz4y5-D;Z$+$}WDoT9Q_hs$vF3_04&-e9z1Wwv$*^H0&c+ zB`GPslr%7sO$N||QJ(#Xo$Q@(QF)>me|^vc$K>$_T7xXBFheSLj5T@>XrpwJW? zH}m5v=HgP*`6$pv{IbX5~@y;o#scA~ev<28BGDb(br_eN1eKP%8`mp1B zuPiIeCc2S)#`v(REOOJ6FukOC$Kr({{X46S){Zo+;fNZPP9(O8({Q7mWH8QmRpr*& zH+YrrfzsEODY!efyan<6%KocU*8Ta7o}TvCU;oW=;P~|Eb0;rfzI@`u{{1sCCydoQd1qs zm8u{;|K5*3Y0oukx_C7NI9|YNUXi(g!AfIOTrs zl^Y(RWc0}D-qi=i>FdzFrKdl?6D|Gd>Z7Z_cl2Meyol5#sDGWDE^*p4A(b7S3`P}@ zPFcr;U*1VBBiS!IS)&gr-t=|HR;z^6;ID2b1B^jovlNOO8VA9RwFT^U(z)5q$?c%H zb%llHhRn4v+a;yzp3ReD@udqErE8Pna&{86n_XG*BOP6gZY=5Yq#H;#a=P^lEMfiC z6H`<)a2=+@=t@Ke8=j%EcowRgT z@EJyzkUzc(i*<2pb89ihk*&@B{j9RmW?)%dZt*$z4UwC07g006B6N$j=h&f* z58_t5=sM`4-bIv*8VOxpjGS0**xW3vq;x2qe?l3lqAkOVlhQ3U9SObB2>W_Wv~;SM z=y4=DJ)c;Eg(Gk4e1_9JPRB+b8_5{w9IV`S+c@XN+itt_&O27zA!L`%4zm}ctxto{ z{r$0~cTDS`H`6MWkX|ARydRso|FEIS)97vf-Qk;maPRH6KZ5J!kwdrLJ7Mq4x%2V4 zYZNajSyH?ZRyQ$>Gs$?7U42<=^b*(C>o@ycHKOS|o;Ee4G#gd>B2Ldg$ETqIcyYS0 z`spo}*+o0(hb)+zO>@zoeH8Xrbad;DL93JN#R7VTt;6Zu-yq8evk56aWCzbdwWZ?B z|Jx%GNR<_Z5h5+zP>3!J9${7!2ahT>*EVqF2#au&STzXm2A!JSgby&Cg z4=i06Y8hSxsPcYKy2v%^l_Z#ap6|H>SKpa9yK0M%~X6YlD9{}&dBPEzBP67qM<{V z!sL?)c3d=Bcd>}r_EB7+SjWjjWpz;w`*1xiGX}Wap!s+pUxV01GeG#Mi$-zZc+!D% z^JscR1LRCXm@2T!%Qu+LITx)}mj9Vy7~NRYuVMPi#fvLw(a0%jWmk4^3Nm;D&K8ss zoaq(DoL-N0T%Y>+cwY9!b-Bk&AU74Ha*)&*%L_$%^y1lroQ{^hZ{;T9HPF&=j3i=y z>5Es-^B^>J;+{?CQT`Tg;1n+d;fCQh&(0I}#tJkclo^d6vf6d_y)ic&?xEVdYdIoEUXJ9t0wI#-f2A26P z@Np3JNWCj2pV%Cn=|p~0Ux)KRX(bH!1xo;f8d5@F%4^bUVzc5)t8u`GXW%^$aT3Rf znhwro<(Cy$nBM1Iq}+78=^0_6-odd1y=1c&ReLa3d}6$}%@h4x3Mm2EM6p1eWe!K} znhj6ei5<+sdrixF$olx{FL1A%?VZy5`G%*LpZ@vjpT9~i=&2J|KmUBy{`&6P!|jK` z^gq1yhhOb)dVG5Vm|lbBnyx{+&&c#LCLlb*&6d^YUJIswftW5(r^yjnF$s3B?Cku; z#m$Y4TN_ta9IvQotkA^FFQFYh9oNh9T+iAoTmJOs%h6Y267mbY=?aQ^y=VQ(;}yqO zUfjCxlk?~Q^y&GZy!Xy0E9+!3v5+;4_Ms_6q%hMF`w>~`o@yvP)t6G!R7INC5L%uS zo0YKqe_grwK5F{vM}Jy81k znmuV82UrkH(tCC=2Rul@=Z~0)A`S9VJ%iPriE>xG<5*r)N6PTdqLdhc-0r>6d4JZU zj807r(7elvHIz3!)SJUG?zq#{lL*P0;!Xb8({QW=QAG+t^PH9Z!VwuBfmjyaE6X7s z;DLT_FQXe*egps895J5mF{(-h)wzPq^}rN-Hz{^$;0l41Yuyu27o_t`EW4Yg47?>_ z=``x4tkl?F!jRc{@Tv^I(9}>LTTrTvhbQp`*iT_Pfql8O)~=SMfI8+KUW@ay*rldF z`6PTb{ooPk`a5@h|ND0%h(hQG-$Y60Z1ur6EmW7aeGpM%jgw0!k?L0uQHy}WpG zHP#k`={lS86T({ki1#ubY0ep#CAjJko}fotS+)ZJ&3)<^0-WrhCas_TVV5RsBW#znKb=@Ik5bs z105$&v-KlNx774#lyynyOU$!DyjOoC+Ame~>kEmgNPY><6%EBL7Vg@m#-OM4<67{# z#N+7Yk52PPV!y*5q5ZZyqWtG8S$%?}b${8}{X6I{N(<6U=b-gf$m!=QKOFAw|6NS0 zi@tm4kqNsWnf=J_NAB1>d-f0Z?j?HhUYziAmn~Twt!|`qZ{Mvhq)#oIwM;>cOfUW> zoc;&M=kH(_eIx6GCgew3j#z5Clf{od??bVt0DT9oMKyMu-ZtP)cgpFfosRRr`9|nl zU#1r;CY?Lwq#Iy=u{HtjTx}@b_y5IPf+9Znn!fB((+4$J5IcJ8kXGlTVq+Py%dErX zqpXeN@VJ<@0InQzZuI5mn;Sr(K~5a-t=#eNMiTVHdY6O`$5;#^wDiYM(F)u zWU|93=kv0*I0kOv_HCz{{+0c2(*FM3aJ&Kh(Iu=}&v?)sL&jP6GH8N@>7{sGoLfS4 z5WtD^Uw$3V9sUDn7J?cX+XB+Tlzw&|8@6=maFS346N&=ZqE4fUPe%D(dhGMdQ#kty zrW=%{=+wAf%w5Xj&M%u_dUDKfod>1g<{a|9%zH-Ri6aPBhs<$|6UYvKL+k*xwk#E) zV?-Yevg30%&*Fw}4W2x7#CT#MM+}A08B~OhA2nW%bHm@z{37#!%qt|Mn=#qQ@mw!Z z=S*3Qu7RlToEjkJi_0xI7ri^*j{gj!n|+nhXbv^F-u97P^ry$TVIYy3{xNcT4Sof(wpYHk&zL3D z&$CR~yxb~3Kfa0B4&wC|klYv^Nn-^0+GsaQ*HBs{goJ?Z))UfZYoxo4q4fqwWlQ6d z2zO4m<*Qjz^<-7o(d5tUS2+Swh>xK=CwNv1HovWk)4g-zNRKC-jP7`4Q)t0 zv8~Go;fGdQ>h4{hv$iaouJLTcM-$?Xp+4URamL%wfdPK+vKTPkJ&}${2&uFmfv?g+ zW9il@!}q2ZKl_HBr%7xf?7XGracV_BL9hPc1MvFD6VrFL&4AJ0kR|ZuZzi;{SGiToV?U{?mue7gOPR?Y-%1wkDdTjIzFA7iJUh`jGqm9!K6ejm6rT3L1u5oc*KAo`Wd1S*NCHqTJP;h84f2b*?_81@1 zJ4t2q4E6~0;BD4_5e%OSd?8E72W8$Z71tOWBt2<_7kQ?JR+RF;EdaZF0Pd^O7%yHG z@$PoJjiy`1^Ad{VMK8np&o|&rS3l2*lOB9<&cyrg`p(kt--E3fOn>v>YJs{=7N);^ z;J|@nOP5BeV|3Mw8!d@&^7pOaHNP%7;ou4hebLeVBnJBr7{8B*5F!AXJ z$(VuM53att^D5qSOfTr&63da&)z3)lu&-GPxvjM~%$aq;xfHFtezlvqU{;(rvaU6% zxPf!6UE^}GxP|CWQ0MY>CkjYK^;@1ND_)*-gX1h%5u#r|xb)m~)sQ}U#D(dj6CL$f zTuKw``D_-NOI#;XQAMK)chO~d-S}U)Nbe#XC8~33-6A*oPO>;Pl-y!L zxg>J~>HJ%pP4M{~W%XEBPvVbb(z+uZE-Brp_)bs<*w0~3&r_cx2DTTZbrf|v?vcw2 zsn?rack9Yk&GM>n2vu!V&0w`nsz0wl4T(+(%Q3t}-FYYO7(DD;_Mg__52c^=pT?A+ z|5DqzORHL=alW*zDqQiu~Mx@1I*5vanQW32qM_HL5fDl0Q+3qh27okOf$*exlGWpuX<& z%bimm`YNXDmM+yP*9Rk$j~X?ec1woM4WA3ut&4`r@vk7I8$=(^295+U zxG8QIlzC2=d9DqM)7dsc9gk zjh{drQU}cIQN%H)>jL%?Itb;nQx=dO*&{VQAUGCD*H~U^OdTohBm>DY{7F| zs#>P}mX=uZV1$+BScTQ}Xa@^OTT(hzB0xKnc6?~g|Mcd+K39Y0aTSF7(()xd+!4oQ zA=6DRc1-Me!vfsKly&vhXUeD39?LI25j!ns0CS0;@nlNF?ohgyFnw)JN<2pqGUJlM2Zg(r1$qQ# zd#A*E*=(rlv1R2R?CGAB(;Zt?)y-~>fQ%4ZsSQf!&f*i?-9RCSx2Q~VC2UCzpMuca zp-yTfyPLYZn{YHd-hSnEiQnf1!k>P+<>(W0dUu^W{o?8VRiB^y{6uSG{)P)ZJ%ls9 z-u`;%g^&O6=eK_Sag!Y}-91om=*3x|z5m-*9b`$k-`pW4qKG-5X zy&!fEhdOEsO8r_^CS6QQ;+3ToY%gdpSi2{7yD2qY?wi^(1KZ2aEz4&lI{Y@3uPuUzTB0$S%TfYSqVX)79%>S(Qu zy7yE?U07IHa2-=9Y8+s6=5(<*xP5$h!&>N4x^{iq0%}ylf;Rd@q^5?a>dzq513BHH zE<`R$zXs|6HJkV3;I1cJvWPohum|MjA3nQ0z8gV1Mrkja9cC=ZB|klz7NRn)xW{09 z(F%VC;0*Yr001BWNkl3q>Bcq#L1T@|q;R`|ghpk*C>03v3oUj-gQyAR zZSD9w(*{Geb`9RmU)QZr2N57e%7_M;q?KQruN^4JiluEpq#(ENtdkZ`*rAf1dy z(hCxJeySqHp#!tyb&)w8Nasa3KMll!X590@oCnZ9AGqi4?<~Fl`wzfeN6^s?q&qns zw%&OVPRAH{tm8y9G1rvb<9*q=?d&#eFA&+b%d6=_YVsJt^arMV_~cy^d-1j$rEYY! zx*MUU<596V{W4{v xBc^|E8<*hRlh0i;a4Rx5gY%yQ>Gb71GG`qSP7$dJMK7Q2 z?bI`us-`BX|rY(*2D6gMdjuS^O9J7gV*=$$>){8Xof5=u3@xvb5XXJpRejQ89dWZzUcgi z3b!H{YZH^|9TbMrY?-1`$efr)OHD6DY1fH97}cdcwF#M`SK3L?$0&}-T{@3qn2A1x z$gEDB#D_})mVynVTds8UbXF0|VO-R5!EUnwb zvA;qu&H#By>k?I)lJ~yrgpLVJFefG+$m`@L>Xq@bxEncTDhT^6iC%VUq5mCs;)21u z4z`=*^s|N0i0J25;d)7v-0Wt3fv$xKD?9lAlKYi>6n}3R;K99v? z^B-0IBZ)D^6Yjlt@9rgyi+K{u^jJ<*a(&5uQ_uBjLYvVyR=@egn*-)_K)hey(0o}N zCyG{nG~jx%OfUcK=(F369v=L+;hJmt=C=|Vh3Rx4)nks{G1{a#ZW5+bd^AXQnEw}V zVhA?wkRfxCExV9tg1>Y2B$yUQ^SP1_bj#5Ic3I1NX>E9)MF`RnSsHq=z zT0~+%mh>&@92*X-j=VluS&deAB>6e6Am-oKDt@2%Q(D35V13!Yla7t8~4l zzjE$^bUD<&<$CkO8?d)DBz5)mWs=aPOqa}hhdLV3Qix-U5@s?X^)^0`8I2W5W$|U9 zG#mxfdwSfkdK)~4Y1ghreBJuWFDW1us_$!9nc0#_7NOnIl3$RsKl^4Z2&? zycGLFcz6UeWgNWnpM7a?O+c-ZT#!xdF>wtj+X)=-mqR9lI7fQ`CJ$y5*j&JI1L`vX z^rtu6JmZZS0`{Aiueo`{nhk4gr3oHYVIdK<0gAPv-X|Ka z+K}WGrQsKE3$(>M5@k~GaK_%*aKN-D)NW7M4yij(hA%XEd2iqT`W1>jA#_0ay-(rv zZBO)0Ij{x0%jci}>Q^7vA6|a==?xn;*a{qvzuq2tff~|3zxDBjK>8NpCZWsyO62tS zm$mg@`B8*DhisIDgzfjeeudz4nvlxe&II7fm4fm;dx8rd-(JwNw%ne=ze9O}9=N@I zPww{Lqo#jK?)sPwZ=5*z;LCXX9gdduI`OYXXwTcnUwQ4*7v6jCJ*0m8>F@pNotLiM z_ptB7xeq6_gZhr`1&##20y`6%>=vpO2^ZlvVLM&1)+DevY!Bo)-M9S8nfE_Cb8&5M zdp>c;GfD#h^3+td0ZsKyPk%V+)NKEIXIA8<(iLQO!w!#BRj_pHfW>u)nKd0y$l;!}>I!3#l1*nTDex zbv7);nLg=3Jn2W?1g?#ceqi;>2f*}~cY^8PM;xJo^u&p1R7in3j1H$CnGT|x9;E2$ z+m1{G(@86tc(9kwq(^tEqtWWsv?Ud>_flA@z?Uu0UKXQMMcQlp>8k|k2GoV=6p~ty z4yeES;G$3fI|2prY?4UFMbaat<+SHK)C zU8k>Mb=P)tt=WgCgpEeQFcR3G1GWu+gXF9YAiF_w%_j_+i`5OdTXH&=5YyRk62FU6 zNOuxCP|n&lT(_|ORT3GQfjl{V+pErxZ9)~5x>#C^gM~`yqE{hING&D`MN*%Mm~r5nQw55I(`!ZRZ9 zg&9I~L%%V-u-4ot3rsUJ44(Z2au)HcC?Oqdc?V66=XdyXnoqrG$9%R;!*s3|qk5Hv zrv&ZGmVwc{(j~lB5I$Mby8jAmud~r@tJ*H*3DKD@;IVHloVH@*(C^Y$S{2WtBA zoie>#*WZW&Q4Jh1dVL|j89RO>*SdyrrtAFlM~LYk?fKhp0HiOYtBC%!P4KuLZ*&!{ zPpuZFAMxq70|`dWNmKv!J^deEEBV=OZksWlRpS>K)Hn?j&gCrW*r>zv+@(TPr` zEtM5L-RSRF!UxRexYgq@{J(C0LBGv;{jhm>g#zm97+_;=RKv!-woy2Vk> zFHZ5P4;`c6QizO{z7$elI^K9*7RmI|ah9${Q%A`o@}+^_MJMw%m{3P^t)Lsk9!e79 zFtW^*%xKOGmk%956QW_b&PNQLjG8{2I#4~10$ohi=v4JS1;j_)gpiM(PZZ=PZvqnKNKfR5e1j1($j5CY zjj<~*(&*_=_kk5RS7vQpspxcCEtV>916ta|ZY#TD!xnf( zfFS9SkWOTHWDzOPxNXzTfqI^k{`Z?{ItqJwL`F!u9fNyfeqK^iUVd#wo~LoNGp8Mt zPRV3IXp=1wXS!i>&SuP5E>6Gs4aw;^UqE*VzP6{<;T;x+uIP!zi0vf{hdK^&f&>kv z)Aa=>i?_So1lYMtP4||Xj_)FrNsBF@XY` zylplIJ^~^n;Mat?$bEefA+Ll1-Tn@7oc@_m1j|qO5dk!FVysGvT*iL2O1kpmm^tMd?V2A z!!sx(jr4T)3i1v1YmuJrw7cMo=ZC?*=;!O#bL$+cM}2X;(^fPP_9u!Q4-@UDu!i7r z*LOo$YOs%oH@+8a;LNmQ@TEJE8?r69UQW-A@IZnl-@M6*N`Lb1C&}gjs3y(1hs5-yPfAP& zr&q6*CEe7IzI@}_x?17yE^(|Xkx189v&1AlS>Etoeht$NTPZy?l zK6%&uM5Q0y*2_tFJ{{wVIDIt+nVtA!PCkdj^=R*9Q2jFb>2Rz8bpyW^rc0hSA?TMa zYfI;pP8=>|y{tQ+{KeHK@1^(PWqj%~zR0G2;yDY#b#IrSvv~Y3mrf)4fG1s8ZXvqs z8tXQ{dG+MKlEiN9rx+J;xEaFkH_RoM$%V~4YmvEz7@jrPEeJ|iH2gKUiv{FgT{?l? z1gGEsB*E#@2%tyZM9rizpgF7g;_W00JYofB#k^854D4#`$) z!|YN*qfyyhDwFA{S$txbVPX-wQPPpmEo(Z7EuwW<&!KeTy4YM`ew~QUVU$zbs2ElE zBE|rL&wb-@0?112loN_gRs>5+tx52%~LGr;4*MjqXaR&^Ds zoECMg^TUyyofL?UJhme0&J}k=t?*w#x2-!(yo(}Uv@+ix3|Bg%vR)YTJK%bb9Y|bf zHXzuSH@$;2n99oNewotAkrbt`qJwH{YjV`BW1qp{BGb#v-S-~)!R?P6qJz;7<{i4@ z2ai2Ef42YZxzQNn3zt20`(v|bK2`h_y-lehjsAzgbV=PZq3@XSrKlGe{Dd%F0g7NW zJB5Yp_+Kv9i%?zT=qZEg|Bh9KTk`;eoJ~i=WO@;+V|h0rjUQ?4VP7iRxW+{+|2NM= zgulDYJuVpnqz=>S=vzl<`Y{@Z_$_2+#96<24Gpf3Nv_N&xs^gcXECWfD${gJYgm|^ zxNsDhKM>0@b^w~$No3q??JTgi<_Xx}qpv+2-C(R8oJ*PGhuoAbLI2to_IExzf~@n| zZZO?>{fz?+mGX7lA-4{Ix{_q{3aueOk8=j`<=5fb;om)XQl`Ol3rfLsoF^LN?;3@u zKK=%wGyF`$AkL?BKCqO?6lmD&Zh%*$>%1cv_S=I2VllD&<=kQfWDcQQxrsxE-Y7)h zJVN0t+Bj_J)XBpw*UMydd)kT0paR(&`5Z(?QkOY?sb>nVX zbQAj^rGw_WtoTLi*|6oBn!ZTIqtelZ>&WPMUNpF=u$+@Fn^$BluV-;A_Zru4y0(sr zZaH4qgV(C9!JrUL#%EZkV=g~PDjBYzt-sPEtz1t@x1gjskIS| zZjCO)bhWyC?KNd{uO#cG%fZ)0emk~=^<66ETT3e50?Ovb5Xy*gW>8V6cOQrhz(7kX zfzz`xoE|coCd1*RTBHYL=21n;;Y~+kUXnF=WuJ`EApvxAjK`4)iW^R6F#{d_H(1l( zc!NUHT{1+Il}*5EYi5H!iu&uXu%Fb;c zoSOUouYN_bC35=V+U}<8^2ax|x1?S8nCSHPX;fO16YEh>@OS~;V+ngX({^R~k32D8 zr*4PH(a=w$rej#AgOMKMgD*gGvHJ&Kknu=w(<`(q(qpM=RS$X^Opn~qf8tGSFEcjS z1MAjqTDxh}%8UCbGg!Iuiw|B9r@wce=opFq=g+_N#TU#l8n0aWm1$^0Kux7dSf5-Pac%Uyx9co0^;J z>FFDi@X53v`zw_ZFHJf1yM!@Pd-cS34RV>yPzP5`!nNV&yAiw64N8y(jwE4(iI!ekR_5iyACWG&Wj@{(UE}Xg-jV*L+`rKW|;_ zBy<;ti^L6(TU_qsakI%78(Th(O9pgK+$WiMh!H}#^XV003RE-vN#2rF>9>jbV_<`?$QC{10g@o_6QRC{TS@8-9F+G8*qq9K6n3 zv&?_;&|7~x``*1z&3)vyd3W4C;r7SoZJu|>9jre}{LB2A(OA=WEm`u^?F*lpHEY)1 zy?b}hoIBH1IOzJ8{pOv^(4xa~@c53WqvcH}F4ZD%V$pv@{));wwa*|FHQ$ia=1QZf zv&PRm|I;YsPH)Fwc>^TL;dpg2Ip6Lwrwag_HKdz#u+TgS4xs-(86fL$bH_t(k+3bL zJkbg67)|6;5ztcIA10VfV#E+mv_HjO}}nppv{c2dFFwP^W9q067!7nEzlKT zc^%hw`x|Rc!h~2Q5(~X4wM0t4Vd}S~rX!{=9brzwbTRi(Bz1s!suIrmRXocm^(Zyr zE`obuwWRM6+<=>o7(pltjuv^(tzQY}NatK0VYGFiTbH?a>OuwT_{4FO>)}RWb0I?U zCM7IVBr3-`TQ#t^n3HRTOXCsK$1lRg1LX_T5#Bk&Bf}3*(45R-Fw4QDw7VpA5xO}# zASPdAY3YX24WpaIH4q;V)4v|nQPbgcbDis5PmgPBYp8GP&LnEW*!}RJ$0g~QsmebS zaWyJ3T_4Vr?=&_f(PT5;cwR8QjEOADsgaa!v~;QIzx?IyS6=%_w0=gJjAat#X^K=3 zyayo_i*#&JRT`bqdtmf2kyRlXY4Mp|WiWJ5S`kxbNS*(T=D(?#rGx2wOxW zynRz3t`{1S{`x{1X7f7oUbd&G#nJn_OB8-yvv$Eoyeu-h$dms2)5~9n)0NA3{V+1R z>3#&K!}IX^i@J3>?)05+zIpca(-F4da@2H$==I0fuiW&}7w;HKfA772mNf_C%X{bl z>794pInU3%=YR6k^FQ7DQv2g|o7&skH$7hWxEYwieYS6Z{PFGEx9`cVtJ}W(%91m; zqo(Ij_*&D$(Se@srYt{4!NbHG26(2APR&0>m!o$oKn12wUj!MfczWTlp(zq#w@fb>SWFB$TY^%pd-l!E-3X^6WVUV4t)K>v7aaGub4Dm0*! zP|=D^j<)beQmQ`~%1CJ`={9Bzi%4a@@E|t3j?j3xlQUFi$3}%)#lyxtFf_>WxR@`q z(N$t`MfGEQcgt`~$}6=y;woyBFbc%^WTXdhsDKC<^!xZyl{GVk#BYPo#$|dLWFY-+ zEe)rG>87vIq&G3R$jb6EPL~5LII)44^cBeM1R$DWK>frvK%Fa&Ooz^UsM)f^oC_{Q41nLv?@VeM9w)E ztVoyZ&desW5U5|bB0>GtlTXY!$u{G4*Bx4HE>=fPX9nRUaqC<&3jMNRmY@|~gwdUl zu1UdvWW0J=ZKv+P|K%5*2egS^G%bx1`N&qVi^Oy_BqbGH3$9c`Ix>27UR&lG9jxIa zyn&B%ThEyOXpAnE$!DqgJrVsmg_GAP-3jS{vK%jn=Ae2rva%KRVqhJ+h_)lNn^J@W z3SL}yEd+NGx<%~h=T1!bkBVA>#P09E z;?CQ~-L`^#SFDIaS*OVn2B7F<1oc9qUR1xTE=R)kW{ADHb^iDf-=$!5?n`s$&m$6! zB)H9+pLuNd?0fHhOy+-iSL2mhQ_!3MzZ&4G<7~Yv5%9hIOADMM7L}&Ebqn0^3fiA<$r4chU?o{#?cv!89s4dDY$D39;u|HTL?0aC^0Z9|&JuqsNO;FPzyYUtNJW_aP? zZ;6(#VLCeem+&^}mLWHS#39_F3)8QIW)fkz!g;_&1Z`nD9R4>B!i;vC&z_8%TswW; z{@1JN*F9oL-gxWAciQxVv>rb2$`ZIV-n#VF*Dx>Hcs_2x%uk8`BFuZMKKn--|E;(FuL{mL+>WM+2tWfH__B{4R( z;Zk=v6eWQD#gR!aBP}Kv4GnldvI2`t1!)hkT|^8yIHwZD^(`&3roZwwmY3hX^2)5^ z>sz|YS{(W0AXenF2Zjhl;IyKqn7+QIo-y4$#Hd$gq{%E0R1_4LmZrEyQ!HYV8Ap@B z!3srw;r6(S%>3rO{J6%#g~#-CpFzm_Kmcf1)&^M%Fl~) zlQ%sjE1POQ91EdASt&@wUPetfrk9MQ=D5bVym(u!y(|SS9dCid4sp2!dD3JCH!?%< zFXYWP5n;)V+rRkagHz)3>&CMNo=@#0xnk$34?ZZqDj@GkczjRJ1?2NOavQTEFZ?HU z8vpw<7W`Duz!(bL802Kygmm-xr%&HZJ@5?Ei}c)#HMLoEAzjbWkChjXAK$d+ibd%!{PUk)5U0QQ zCZ(i5VVwWTkKbDXrvK#p`Al@_3UjvpGCOiQi!Ldr_M-lgZIATFv znIFXsVN`MY_(Y^Xt>+xyj>CK~P7e50X25P*oVmVInCYMNcP52FAAg(RS3w(a_jN z#;C+~cY7+$x;$-OxD%lC9vyZX6VL-tgXq%Yz0^9_hu)?1R`LvRXI^O!bh**_!emsX zqr%H!72sLgpA?c#(_aVm%}H?ybPn_O42vYFh=V=MASK6pk?Ta9dZ5#rKIr>*f1h#J z-SjfD)b#H>x%B=ArX!{U*CKNR=UQXs06&wyfA>8HjmyO>cAnjasE+Lg>{cG58jzx< zuT}-=|BtWtGiT0RfSKoco!9&I4kzhlDl`X=L+LM)_wrz*#B}`}JSaikG$h5K z{?=tI>aG7js!HX0vE+0ssOA4sS_$f&I=F0cZ*Ol)RWH7Ws;Z`uohJzRGL2JB0=Mm2 zM{lQuR9KGh1#dbh5xU^p;JKl2vG)LqTeoVFHD^}7?sl%Xg6S+7;BoCjxQCh5#A0#x zVm)P1yg_%(7`F?6ZZWzwqsO!t{4Th6oqEs&r*D1E{@50Z^Fz8KmOx0Iu|ds7`Jt55 zp2TB^i9NZLc$e7NYVeZ=6EQK)qq`0xV56fSHadE1hqunK6J#y8G{Rl4&}E$YCLi}U5g-fJn3dcMV>W1G^oRLBF)>m6nFa0oisQC(}{bLRXuv-j2UyD zeBh<0?!WipJ0}0biQAqX{Pd`=KXm7vcRq6G!;22DU3)(}606rnKU%aF75zK+-+Sl3 zJoUm~l$w4Z_`u1nmYQxD9UOo0+<|fqLRxA%7>{%1K(iauZIXWnO#l0AWhwr_q1wBGVY-$n{RQ4VfHe09H}hY$Jurys+#O>DM{m-k=!SMThJ>4;^Fv-3f+V?dzU0Ysi?Qvhj^ugCww(s+W z3mS)-VVQIWvHl}pSYwd1dABzmOuzPsVR;}pV}y&lXvW$#(ESx4X&q4bud3<7O~4Wh z2y=!#Wloo8<(9jt%{)|TIn!~!R0^PHz~Vz_5~QF;>?n6zo)l#ws+Locibg<}G;VC> ziZv(3#X21tc4)+*8F<}UCYG1i1vE!2M@An;3F$DoUVv!%RgNZ&*oiL`6!3tO|Vx^Y_+OL zAFXZ+NDd(r+JmH*18{n3K6<)kdm(upHC^SSYD)hC-gI0qhSPIPSD0>==PRTocfbDn zhM0(s7-s|xkCMFt0+KzmLh}RSD!P+#q`>L?S8A^sfsj&B6RTc~MIL9s(xvgi^l&k9 zdupmz+=jNeHoliWhv^FpqIWIWvj;tW-L2;Ub?Qr1#z|?4zq6cO_pFk%He4BHnT`O; zMv2>ie`HAT3L)>sKsv?+vrjR*ySntT*j)*()KFU35S*UjQ{s(&n%-7cHXF&*o4A$k z?(*_vAH=H7v0lZLjta*q)WcKkALGQTUeZS2Nh{3}+Y8Z%nHAnS3Sbm8o0G)vGvEHG z|6S}VRFQr%?|9@qIKBBWK>oAyftWrr&*Nmz$ldGHk$U0%-@g6+&*Ao<+(z8r-W3%W zC?b8~;+5sog7zCFoy~#fW^`RKz85tyvQCE7MeUN?)!Imuu1=)y9y@Sg+qVAJWu1gF zZgYX@`v}*>_44C=n?61BjI8sffRs6NhS51yy>|BOJ7-B$Kl{;HBek1bG1|ZP-VY4X ze2EI=txyTd}(y)W*d=oK*h|6_SRA5}KcsR2~`@nxB;s6q?bteZ5iB2OKZMLuV__ z-|9U|E=^zt=5DlZ&mbE9_&ChoK`1*2RILUjq16QA=LY`4^j!550;HV*F}R^hOZNp5g81P35akZfPQrPK08yD^x`h zsfhRNx8aK7nILDw<;C8vxhv?ZxFXHh%NNIsGlC3slym>Fh~3Vyv>>9=8cm(0?C?3_ z*oE**3<>j6-a3V=K5?ZbbG>n+r`WMCSiy9#DaB~;PCvSq7RQ#(t&R^XraqNo?9u>7 zby~TS{87_A!f2VKgdfeNBC{*ph3lFC>IcbVlr^0mq$ZH@h_R*%(;MDAj+}n5wG~PJ$b<7NYdWr% zg9o=tPbWT|ByoYd&f@e-N@ctR;$HqP{43xEb1%QScw=wj&|YAzcT{*)Rd`fYOJO02 zjCKX7YDlB#QF^@Lc;Bfm!{Mmk+!JYiV8Gg416RIk#zJ-BIcoZMVSb(k6SGn4;<_cD zUu<9F*$d!}kj~6CHn&*ajppvK2ov3ug{^3;_IMkmokQu;MD9RNp1zbJIJ>qpH6 z!Hf*kq_e1hSO2b^&GSX*RmkY-VYF-+`(8#im*JcNwcFzQHFvs%b|76p4a!GX?4kRi z3!3Hw=9?jOp}Lu>%u}#Vo#)!5c`HZhp!XqKrijwjGkp9Bf)x#@BbiGnM?q(a zHMrC)3rAW5>$>E0H1)|cutWCaTj+ljwPdDNn_m7Z^it~%*DxIjAAD^iUpluGzd6G) znX~@TFRpdHn$EiN?6`;jBy(Sp`wZrGxtAMEpKM+G{OcH4ziF)DlL4Au9{Wuy&ilKCE>e>L$MbL)REif0KbGxS20ytf!dAFL58)ucg=U_Sa zGith-<*NKH_+B)%Io(pzEe&1sMp(Dr5&J#*+=U?B*o3Yv9l&%g;+?eL`Y~B_W5*n@ z`-y7A@3s}FCg#{C<@LDIk!m=4ib2FI$4T$);{=qlEN3 zDm;`y{X4G^7qT5$nUPbSaN)xXAD*wLNBo8hmtKE8=4cEZl2Rj_2zic>puqgBfQq;Z z^mHleYJ3Esb1+S$uBm@1O&STq-BoJ-E6h%Oc|<@-cXxM5@fv~`QPCx(n|zl&21^z>ZH8-3C<)4TKYYdt)XEOWvld}4w^JWJ9DV)Tk2 zH{FG3-`!S{KD(AMZASg>k_=b8%;N%Nsm;yNJq67@r<4cL0&dxKZ32HQCE;_fyp--Oq#C>*$ec|8-$ zC{mWaJZbneU^#2HB0be;)3?~ygWqN-&J{{agA&_?{0vJ@&!S+oO`ex5jOkjOH2hx+WpzowWj}#IN$$Uwoj?~vLSBd(l=>ainX65IXksX?pg=t>u5?8Y4-d@86feW-W3iAEy^qNS%L{vYCH%o+U{|~hwHa{~ zK*v*f8paE-^mOgUrlzQyZy2WZv>ex(>f)3HJh(N~IeX^R4(JxND;*eaft52j7?_Ouq{?Ju-aR8#vPeX>%f%=<^r!HRHuz1T|kw@@H9A{1B^sR43&V$dlzQqss-+J&(-08%pKlhyNd%66# zMo$OQU*_lkn0BIY`v1Lr@JM)J;h|x@hYE-FJ`+A_{B6A$)WciwyhyEu(UsJAkZDuX z*30e`7gTS~UxnjedHc()-lYP_dY(q{=mxCmvAg6|q|GSWI@P1`0K0T`dQO}~N2kD)fbr=0Gpoi= zMtP>|rdr%X$k#j4-Mnl|>B4jvxk#;rh)&1zqLRv@IuIRKJKm;FLR}hQ^oBPZKy=IK zVoE}7PB*YFs|(j7&4g}QbQwiK@55W7Oi)_nhwnfK;>_IT9ek1Trl@Y<)= zK6US+haWn;=#j(V`NIz%j$VELz4w0q`!8T)f9WqkO_x@t4-~$D4-BG))Ogd~aV{@D zr{18F(Tz7VgYyHrd!^him|nCob&W%4^sBS^KfpbAR7IhpiI$8QT zfNc$1OaJ|#evQxVxzAxb%iM2&C?)Em9`~b3Xf)yK zf%!qn9v)*crUU8`aJ402j6`0%$c3{zWp(BI{JG+Kn0bj&Y0pg zM>{V3mQ2QH9UdLJxaiA=gFYN*BET>V3BLg&S;M2g=vM z`1|FEu`nG@zi(Pt^3kroBa+ki6wCC2n!e(d>h+uCO$XB(<2R`d6Z-i(@0>n;=KKG0 z`kj@hiBW$SvHY25jBL(xw?uSJH9s(U=7%5u@}EDf$jseKjN_(#q@ZV(t@q3IH}H%9 zBse7{e&@{B&d#sdPmoJeC@v^i){zlcQlFXCULi4EYP!lov*?ips0Z$i_afZ8MaPX^TFAPFQa*r_lT=?ImyYpA35(uTO$lp?&v$UqDCN>^Z3(<}QxHw#%{-nG35N+;s%A}6( zg~Cuzr^5$hI#Dfn)4_eE%MedQN$6bClw4jO6vJZa(tierpm1}l{MzZ^T;oAsur+iz z-JIaz6`1pAwWp^tUMNlta}}3p1KJs}KMfSfIAzQ9S#NYUJUDCC!Yv!`s-*Kw!x1Rj zWW3m*Zq)M^`wn*YPTx2S?~5UHCX&;Eb#AcKbSy8T^i~t}65dN#BHMcNh&Y`sQf5f5 zIrDE}Vn2@WW$Wc;#PnuRT~RNs-);RaoPJ3GMZ|NFA!^FLlf|1xHOx%I&ZziXs) z8_%yZy<7+EpQCr1cnwdv6qvps zO~U!yoRhm^X)mhs(7Bjj6vFse&W8B8ieLoZa~_lOk~i{>af64B18pZqt<38Y8$-n? z*4G9?vJtZlB3qQM2u5SqCia9C$w%zzIap;E0Irw3s%|_3hZ)9{!OSf@dk7wdtcrKfZ3MP#l$Cvf!(IW~6qn#BF z-AWG{nE~;n{S>o=gB)>T3vJRLz4;$9-eeB`HPc)^!uM$H0hp)?p-u# z5iL+3dT7$x`;pUMxc8;UAAjhcMXPO8a(~PI@4FPL8cOH;_kgq2sOhGLRD$_itvvJz+ckM^0Pdw=M~^Kqr5bgLB-lAMMfnh#ss^@5D94>j7V z{5K7_`;NIcnKne=^Nma0T|NhyQcJfJoYtVX==H|3N`m!F7BMThA2bLR`kFT#mHQ6s z*Z&1fzouPC`oU3J|I5|%+g;X1 zg36)-H7Q7GtrEyIFZvae#7C4 zfYBnU?VM2G&7~F%;fF-UN+!B0Y-iZ%=9HF7Sf6nST4!K$8G+_)@wh;p>oaB`fZK5H zzJW{exalxzfw^RL@wpA@JTddsM&ClXq$nM~3++a&IdS?8W({*;NZt5dLEvKrGVpmsc%C(Z+ilB%M%*3H_~-+dPy6e_k;@x z7wkb-O|*2?pW^HFqmNQfB6jcDvup9KCwsvugwV$4X8|I)}?8r$gyG_AEFzAhEM(+p#@s;$gZlPj5?3PtTyuW%}#@ z(#;9pfO(9X9^!4(bPx(m=OuM#`b31Kj7?DsroeO`-0T4ukZBW{oSBuLo=63$)btMa zD@tQamoBX?jc^9iiPGDPev?jeW9G(Slu@%APZg0KbE&=)o32gpOFXsBifF>`YI59-?9DM*70!bNQ$9?6Ch`R?yxx$`+nbmii(Wf z{jWmm>O-oqm;2c7IbTN=Y4f^U*Cg)#h1B%wniXI=RikI$J+?P{`6j~K8_9UNVlGx( zthv&-|GrO8S8+S`^edm%T=|p`nTzidD09(Rj;Mx zBhW-~FAndZK+-j5Bd5D5o$y5|>9jR6i$arp{W!iMz=qPjRpSe#Q!}becI0x0hew!^ zqEnKR6!(IhZh9QW#9;)-zK)n4YA9U_JZK+?=Yh1D# z-5|D`W59E7!IDEv{bS!d6)OMDxSXxt^Q)~|EpmB#dT~0cPdKXi) zfrT86eJmCi_}zi$1^asmb8q`dGHvxZUFTF>w99*poI&kQ#HC}diarL3QbpU zqn3tnwKZB6IqSix;qbbKL2-Fr3O8;HKWn+tTT#)i8@R;5qM(@Vo%(u1eh`_zu=miM z-Z_QC4)qq!!TB=2_x4e}0(1>KqLHgjl#m)U7oDS~tAh0Z&ml~|dAj?7Dp%jyDX6Q1 zgUzEdg^N+@qcOcmJQtv=WECx4>tcH$%;5Dj4&~aIZ=hKPGtItnJ2KlG%08uB_8Wb zY@M7oJ2AY_=SaOsM~=Jswy!^V&;5@+GGWo$)vK$kiymF8deVm$egCONiynFSp~oMZ zG->7%eCki#NoUdro_zeCm+oEt)okuy4OdO7j9JWm#@n}l?seG9{)h`VTi#@2I)N|J(&gU9CvwXzLrfr|a2pnU6a*HuI~HsWYVObE@C7$x38=+pF_6sD807!nc25qz3Va-hjGtN;KY07*naRHkwy zIE?u4>bTQ|>D$)CZ}80@6YBI# zkx?Sh(?NVlCMtDITyYHQsFw`tUS6K)phiwl6sA|8go__Rp48O9fQ)pq*3;wSy#49m zPJbk=>KPEwP3|IHYWL{)`j(iXY;y$z*RQ^#Ih2u-&}%!EYQ<1?GHiCe|gOcyDf^4^Ni1K}S2TlJ)ZT z`xiPoK(mgHj{1b}yzs)moIdl8EHse#eT>G&ZN4rG(~UdbK)PY{`zS8lhFixo9gloj zz3=i@*NN>7rys~a-_b=VW9z%;)_9|)|6=!#U#VGMXK9sUFRgmaeNoiEX8R4m|K)D94lu zL+LWG(9kF`qhx!Dw?8T6sf3ErGAYSl{&aqAF)c%(Vfxa| zHF#b~b0LY*%gYxC4+{Q;0i0PNsFtlE)DbWNYWk#JDqVp{9y%n+MfpQ z_C^YOiInH1lBS;0L}$&KK7}Tt#-IKod=9UprdLhbSXgzi??r4bmgB`-N=<*09;7dB zwF*dE4?Z{xNj0+Yu7#Lhjv&Jl>O#`XJlYybO&6#`>IaV>RPWI`>*o|pC8t|?FP5SX z9Mk#-Oy4s7&@;VY`o@igb2j$&J_DvdLrr0Li##t4QzK6t={(U84zV9Oez{*#Iug3E zo&0f1`cKb&*~#Mjmk-YS2BsIcF&z}YHfweS+=On^IW8S*@Ur@?T?Qkh1K+<9fE!-7 zIQ{xr-NGOSg%tBHe6ZF2MX7=m=^Uergmm>3J&E&$Gg><7xm;%nrk9+h(M#y~ z6E%`HKQj%Z8yXfS%UI$b7M2@Fx`B0r>uBlyAUe5(AbL|LZ>KS{FkwgQO@=J#2Fa~3 zbhoI^rKuPVFYF!P*}1ZhYEy&gCc@EhKa-xrc?x+kPhjm#FdanKzJaM()zZ~FX&d_b zV;Fka8`-cXCU)lSBh+<#O64#?`pqpyO>dCx1@`77Exk&RuBlDw%yM&-SY0=0saU-w zd=#aoBRfYnNny7%b%N97e9<%2Uc|1Y*k9P6h~Bw!)Xh)d{^UbXt$t|&#+IT-H`hG+ z=%WRT?tJR0!;2Oznsn!qk(glaoJ5l(L^cG<0N~@_Gx&e<4a2 z_Ub-khMSbeAGI4Xon^xJ|CXT=N_Wdo*+H)PT#9we4bkRNo#SsZ_`aG&mfze7dDECQ zxY(%aBL|+_4DMrDRJ86&0v>e}7L)-s9nyAN)`OXMmvc(%zHtt%3)W+sPNw!txqX-${&{^mJfNcncWAR3;|E$T>8QZxAJ$sqtEO(I9Kdv` z=@fDD19DR;YGb+u<8qJ)e=QJa*)2nedEsZY+97>$R1TDu8ZQg1Zt*xIE*lI}OFU;O znT+PDXno>Dsp;1Z>x$HK3@rk5!|3b)7&^D6nnmX)99^atgXRX(&3=WE&$WhTI19ts z1(A^MR?{JMv!i0fbaw^mfbqrsF8#qv3)9(v4fgh1KPGhhiUc^ltvjSPt{WK7A=U+l z2?tCC=tvo=9yOAB8pqt@+R_PSfl?TzbB{{hiqYGtKozKSF17evkiNa7l&jqdu^&D$ zpr*%O*l@lh=BPN|>7=nsPEG>tE8|My(gOl!hoBC6dU=qkPTLtMoz^Y+acwCH*<%Pzb=jd=`4f)f_WL)Dy^$rY3!hBGk6`&GP z^z;BvdZ=4!I+!lg3t%l!r)-l{nhGCD_xy}0&kw-#lI|%R1j?zxz)cBhdS)B#jR<61 zn&V0+^>C*71mI4`cZr$1DGasD>(~;8ya?3X5CI*n;x4&^sgo;Ri%iTJBYCB@izrH#8DJ&>} zHlp>#D{%CEDgMXebJwHx1LiLq72Tx1prNy`;3U69U738WfXu!33E|D&!@B#*^UuFt z_u?BbHg|1v$(z3W6)>F=()SL%cX|NRKrFxAw4~*G_iiGe+?K4D?}N8Bp164SwRdVt zGjhp-rz(^szPbC?mnkwGy&fC-ruhBuzVs{7-9N0Tpk%QzJ~zFLQrfb_l18>hUZW#0 zj3X9dV@r3w^gz`+JL9KKOOmI<$2W9%e!lY3+d=TGp!J#Ar0#Q1-mYY@8KOo|pO#7} zd8i`*&E3+|d45^RV0uNn$#?;;gEEORFZE6uQ=Y`Hn4lHBHt6O!QxbiH2;cOH0ei#P zBLmdo{`KoKGJN7ldWrD~F0IZ~lM-pvC&?-QI<9us9XmFR?qTfqus6$rs4;_5@!sQ7 zD~(O_Tagfww4%C{6h@5i9)WaABAZfMwLT4k7fQ1wDV@CZS@gY}a#v+#Vd1PTESSD< z3YK*lTyV4;QBRr|`#Kj_RxWNj3zj3O3)HQjzSb9yU}u5EjpgN3>()s6n39>erBdX) zwSg*9!2I~U$cC*_({aVf1k<_|iwoBDtIzeHLU+daB1&)l?y0NPkiLxV#i-$6@$oko z&l=X-OAq(LVYps!yxd*|rO#2~#~8^OQq(k-IfkdEWU#LQR@9Kidh;`HBWla~8s z0M%_;|J=pPUACIuYJY4S_qiPCl(?Jmx-qz@oHX|2t|H2K@Ky6uRM2!Axq~B{@?@|x zRBTvSP>iL-y};12Fd0Ox1J0RM@u>7}!{}9nT(S#ftL3Ih^!U8v7NawDFLz(!R$s>c zSXF1=`~gHa4Cr{I5YuBHgVfXJrp4z( zPd;?_#1YtDFud?r8QD9Ia)j}tU~(}yrgKzvX5n^2?uN)gb8{;&wU{dYMM8v|BwHrJvV-b!T1l%yDy`e&&HiYag0$m~z(W)isZzr{8<; z+O<#NPG9uMLk~PMX~`p#9=>xCZuOU5SVUCg!+#0hbn};HQFHL1uD8DN27!z(x_vEg zy-Nckz8j%w1KL{ez(2kSpW8zfr2p|xxhV&}imoXc<&mu5bZy0`(<}kgO$})~H%poO z@5A&#Vsi_QiDkU;#+~;67#G4>(ot5fEg1PVo2(PGB$mRtqS0v2H&&-a!M&){w+-A& z%}FPteY>Kx!tH~q$LS`Reum3hr}XX{CkMM%pU*lu))gl@JY#ZR^!%G|yu~ewTeqEb z*R2jB&E01F&#iBjwQ6he_FFh~z}a%UBy=-wztJ2v2&TOB#?{s$UeJI~{d2FwzRMqR zLCy;^eMsd^CK1NsbEB;rlgtqG_aV0^ zc-?|_A-ECLA$8^z|Dre-nbo;w#Pks$`l=DbSW(oDfgMaAEe2-^Kcu}FFF0$}=`_&V*q|U23|Tk19|SJpZDa&a1yh+ctDtgl@6? zm(#jiO}FlF!`IyJ{%}7)IU%7NDv6uBL7k02^^;3iB;ZM>E|M10_)Qf25}P&`sT(m} zK`*2_j~%-gP@m>8O_)xds92v-0;L1%f^;UOZE4-zZK&uUUT71kr(sP`*sx*4(XlB< zJ;uhw>#?`z(D$+=t|YyrI~@Q*OV3yLMR1z`S#><(eD0yXuD!nTjq&>zTshgV1V(_k`ON9VpHUsE@$(B8&Y$n-@Qf#N9LS`Z8`Qku z=%vpdJYI#ueYyus{~1B+?fX!81H4`2kRLsN;pf<1-oKPk-~IZfx~m0iEEATpfn45*!*>6z#kzdi_CNCj<6Wlu43`ZS(P zSL+*a`eVK&*Qx2>q6cZ?0pJ-CU98Fv(@l*fxqhCB8Bcuwp4Z-4vEMgd2Msisy8O!g z;&aO~Gjd(@BaPqo?rGHY4^Y!Lbk}c>FX@&eg+G*Bx`(zmZufK0ag&BuW8QQOw?G%-^=a+{D^E%^Q{=<{Tj3Jkij-vy%7u@W6 zg!WJ)uxBTh)pyes)H{S|7_Y=)Z?Dj#6grvaBCLA{InpygX6ege#H9p}p^kKYMj~Q% zOm|FeSUHfN#H$U>g3yuFv)coZ)1{^>f<-&3mg$8!awwgh3pm|RQaOibu)7594WcaB z+bb!c*fWKAV9Zm2A%PJNPpVLzzCNW1E7T^G1QugA$8wG{-RTkLpbWwh;2B3?Bc&7S zcSP4w_969$m6*W;kRgh7CdMH9jJZt)_ zDO1ALcl6*J%fgo}oU-_cJTFrUdtvmx7i~a?wRLJe_=c$KI=vJ)KMy#i{`6qT{ZYFCT26fbNzEDo3H<>2Kmw}6g!=G1e#a;wnTj2*DK7~Nb5 z)GZRXE`{o#xuvUHH|WYg9-Q~!TLURCX4m1%Af08`bGq(eo`{k5wKV|UfcS3=q+9cv z4xB$Xd+z1q3o9|FKlqmYi`u|(P6lea#B>^srp=Y`j72ea=}GE7%@NU}T}AV&ZXZ<@ z)iiQG=!?T-vp897UQ~3|m|tusin!b$x-gwnf4__=)VKGvb~cc>7&$LIGW@y@MN-sl zNI(AOajw}4y3Og~c+n{qH6i2%&-<~oL`Sb(3!|T&kFLL@sfoz)!_n+5$l)?_zG5G- z*yw_1f|4G6cz$%`q% zZX(ByE*0In4!+;P6|wyImT=0B;qxXqeZ1jx4mq4aR&P2?h&r90cB1v;;g62StR8*) z;5kpcLlhaP_D;YS{N=wY<=d+uFy&*P-5 zyIltEZ`uFdm%+gchUt+E-@W7 z-NN)xH=~>TSmyM7Mwk2VRMW-gQP#5@GiKtAH(W~;A2cQkoVCYzi>!m8U!>@fBfhp) zLikO$Oc*pMhncSpSY%64V~ur#)btw%8&!VHs2hj5@BO>$voqk9-Q|h-n!mX}Zh4E-*@}H^V1#?cw23!H zx%U}9|2o_c{neL-IECn7tCATRKq@rLR2VBvM^=|yZh}!vNhScSGZVPoT+xL!aK6au zvI@M`pi8LWSX51hi?SG@@req0G46EB?ErQOt`&82f4oSv3L&Q}_$TUy!*=vXG08dBp>yvhB}PsW;lbnMaP zW0(6+BZwk~aCO>^Vs#Oiw}Ivqj*?9-Qs;VGcSjoaqm+*tbNZ#&3u&((J$it^LND5Q zvXhY0wq3QUC2eTyaRk341^Rot9Iz0nFR1BeS2}oF8c*ZV1n-iJBrQl8#BIqkrc|`W zc`A~TRF`!F(TwytvgGsyZcyKI)GG`*y(2D_18e0$CGtdM!Y5D)&iG`bPLgl#V>0!8 zeb$C(V~z4`JZ-EE}4|# zwZ#khce=NS(MT<>(WFjNGc=8$PW%c!bv@JE2q>%c%>&o-5wA z#wVu}>f0$HZLGP7n!fK-;#y8O(q+PQhc=APBx!F(E>`J`_{O!boqeY!*Vm^cj&@OW zM$L7(q_SuDbnER6@bpQ{y>j|asp%a1$c>LzihNvscYVordDHi9-`==>Z(yK5^6%Kk z^3J~Y+Q01M&;m~M(5x~US28oP1VQ2X3T>&c#~p+d26H;?HB!7>xehK7s`JaUvMMaw zOZM=5S!39TQI(vBpyM##|Ar7w)R~iO0DnRIKq*PE!m~mdYJOe{<&<8jI=w+Hn zZo7{MQR=kd(w`r>=|05IXfA|H{uUz1ov%_t{D6y8mMw3IlQG`lG3b zrEpw|;pIpP%c(B)*_Du!79STM7)lO}C)E>)arUPH6{K=NFQy%h#PrH3LqzFd`a24%`?i6wD znA0()55t&_`(;kyGowZ=8_&kgAmpW?klTm$HZ+~O>N!W&4p09|-)ozc^+r=lC|AA{_+ zjDC&W1?(>$G;K&{b=touqS6)gVoWb2qZ9bTFZ-nQ=aaimn$|#|_^y+6d6QeB2zRk{ zba}pIbup!xt2J*t;fAD*c5WcuB6Sd*-(!OyJv{PSm8kKzJjk11FkOUxZ9F(HeBL|` zVj#fxM4z&@YSP%v&OyQH)23tSe7X@W898BcRMUJgU27G{^ukjyoNoN^hnpt1oPg7b zF~`4S?T6%y3cJzGwP7;lUlCjaE` zX8A<7o~@9@nb$vw;7M+HigL4Ynly5tImfi`ym3Ox=EG*m=)7I!)>E5l-DiIAAPMU? z*ucGdhVHd;(c~L%I_!Qa&dp1-?%jEtEuJQl-5R%ifznM@1pz57wcVgU5?IVEcHx7+Xh@F4KP44|ir=Hrl`G=#vW);t}*6+NIfrt63 z8F13(QMlCBgN3cot{Gx)qoxm0S*gKxmT<{gpf2N!Jq)tTp-!c#F{G%!kZC)FO$AJs znr;+z3E>*}&&|Zf^MQ+162J|go2e#l-JJeLvZMp$khswN&;Y92pw6pdv3_h;XO@@4 z68A}*ZoN9Aq??z?D)!r;x8sJp?^ZxMCv$eQH@5xjNnMNW-?@%Rd~S&8-EVyo&4-H7 z^<3)2PaDj)SLPD4!JRYRj_Ks_O?J3!Jg)^s@iz|mu3g0V5(q&1ep=Av{Y z(l&*=V0Ixh-Hf!fZZI7|UH0_XFFbl-L)(T9LSpc>mlpea`g(f8=dY}Q)YWCF1XHgs zaTiWchfhF0XrV)Ej00;>RyJ4rl_UnTL;+2pSw%N-h4uAuCOTchxdC-tFU)pb=XxRP zWzSK658NrWP73SB(4exdURf_0M)(d02myWIAeX?6M7<0b=5%Z?WhK78NntrTF=JB0 zLU8fo5%4LY%RHo*p6CsY3e!8-EFDNsZr(*h#}vvujbj+UZ}Hst4$>6&?fdbk2-ZZq zDBPv_Dn=GG@_(bn=AOQBy4*UxdtLFMa#=|+C7l$mDw*-jncrmR=O29+PJgkeZTIed`x-BEZ92l6rH`^;akV#Nr5CEu7uRdk# zubh_YWj8xj>>uz(vwu{UN#r6aizZqnmq7Aq{Fc|$z4n9G-uba@GtX+PFUxG#{z+!O zk<~+qSya+XC^i(pUHb~&djWQKyvp;FGwaJT*6Z2XV!G87Dcjet*pnIrzhb{QWNoTI z(Qk0P_!VdHt5%&V#*aitQtCAN7V)PwJUBJqBZN4_xERFu>>#Z3#_Cd**p>;Wx0jWy zCmqs(mt34~YDlTZ^boHjiPJMwLs2Yy{R0C72x(9Bq^dX~ImR=r9Oq@ZvAu+Z;3qF7 zzKA47{_IQ}Qz)IYXGoZ&_W;iT{x&mk(z`r}_H_8V;{05m>|uF25=H4==Fksr6>skt zTmtM&kh{QPH)U9)ua$)!bb8y&$0nFm&M`RUOT^O=6s9M;b7zBkX~&--MGOmmS&0z-Aqh*r;IKK zmFdDUkjQY8t7zHH?Ww3;rgY;@w=q3@UISS!{4prbg=iQCn}v0YcCI}=e?DhyE=!^& zz~@ZHf4$|l+b2bDHh3Q0siYS@0aHC%Fn{Lc+lCGsx-y!Nd@%i_;wE{mD+eFqyZ%t6 zN=SRz4{ISbf7z&pJE|Ba&ZX)^!+7R_a}D{`ajcs;$Xup$CM*NWPeAvhP~$r(B8@t6 z8=Q}_PWbxDsHlPh9R;Aw)!JpjiW41m`_rTDh>CjP;hB@}Em)Ly|JuAqp!7-e`C(?# zgb7iT9(v&6Nq0_o;GstzxhHB--lTihx>ni{!(X zUPP*eA?#(H`_^x^-U+5({O-4JHI|k?@Zyb{4(+R4^cU^oeKT}9Cfm4PLb0WD^{Zrg z`;Pymi%Fvf?pExMad9t6n~4?WYj^B&U&qX{a`22%Yg1UTcIa(I!GrP!21owQC>k|m z=#m^}U3Uy#vc_7*E7%+*SIf9O3(2*(bl|Q=DaYR%Euy$nF|OOgCye))IlbCKjo)LoOxU?3x=% z9HJfob&Jr=ZKkMHxNZ&ZqVq%xymiGo*>fUw<2x6gTYW}F>Gm*?E->e1sMRRL>OKmb zbB!M>?uDDVRSPxrV)Sy%OX4jsZwA+`*)KA=~nD*GANa$Xo93e+(oz8q=MY#{K*x zrCS3(I;d`6E!p1I-Myj0cwR1DxbU+}3Eku|Mxe&~6z7x@Z%72IG&ne>dRNWnno^9+u#|i+kXdH8jLH=;F_yb!-K_(1y1J3V=?hFB zQhC$&>~Y0J3`)(92*Ivfj!r8zy)4}kfYut9p6-X{S?ujFz22epTv0mdHEEcBoi#;i z!R28gh_6tRPn)M#AieBoE6&3kMY@)Q3#p_n?8=FC#grENuK|!@bb|6+#cL{RGjsPN zr32go>Z|V?M#u1CS<;cnp=R>`0NRTE(sF~3kyF)8cl9t|hGstK>BnTtKXwckHz|{e ziHT)pi8xVwT`pd5eOyI4KAKmFhOr{ok4;NCu;bkq-*_Xhx}N?T(WtjK$;T`$4tT>LsorRTS?h^0G>Obq-&t1??v+`oj;%$e>$Ef4mCjc zWSP4#rch0th4dCw`&&!|{X%KrBSmp!CfG=SIe`lVk>a!iQ z)j7#m&t~k{X*AYy#m@DQNjphix<_hoQYw$kF$Z=N!d(1=b#9z;=oyRBiPFZL z4wZxJ2SmK!S(@g9}w8Ni$&+s)ZLKY_3|mY8sJSAq=WqyorB|? ztt+R40v zqLVp~Efo+)7f=JaGHQGkzKy*3c^FHK`&=*%o{P`jGlq|K)mUKAym7j44LDWm;*n+Z zAat~G^l@WkQBCNBDCuTc7fh)s<;;pYih&Wm+3>l=+Xm7}l)>mSAE7#m5=~U}s8Iw% zKKt~uZv+QA3LGHUh7c zIGx`(eQ3qyvX)n2UolXQN!=`<8hzwQk{EHFbE{-?A$k;7v>xu46Zl>zBjs8PUiI6m zaHiAGwu+dSr5t70yjf9{6p_-0Y33bI-~NLMKYV!6l85si@aP!yiczn^l59K|z=#HnKob*(|Ot+1}{Vn^y`!aZpiF(1E?pD*k`PRBrQM#?B z8%!S_{8L4z8&rSs|NZDkKiT=+@19#O#QpZ^u__5i+o1pD(oeDS8wudkbbXBBf7 z4+NXfk5vCJF8T6%e*Rv+d(GC;p~_W;QpJ~Ws^-nv%-fi5i|JZKJ0x38*QM%BCA#xt z1-@W;Q6ErLbxZR$kglW`Q$;GXI-G8%GMO71w;)}h4yPMmi-C3s-rQoXL-8j9z1v75 z78j@+lZ(yix7=;ibS<*ToN`o)%XyMF2+wuRfH+f|(z(1=L29Y$dLJ}CZ*{SjnJK$Y z*IgT!z44|SxeK@5c%%ExPI95@0pO|>g_NygQKP71PFF(XE-WvrYp5!v{}J6aalGJp zG2V0|rhCM!fz#7+N{ts?VmgSvJ1zDV?huchj-b8`WbW$kJ05ww zPii`0FIO*g+{#`J;SSE??z9gt{p{-d?|*jh;T|P0;&dlWg%+ZZeRkrvZ~xoBzx~U9 z{y?0b<&zkYk%8b3qPvbkc|I9scXefuubpXdzLo-Wi@5G8~nmZcp=#k8dm`BPM$<@hd5NYu@?c58nB7AFdZX>Fw>j z(HzxaR}33{1xfd_!F2rMS;O09Rp)`S=@5#dL%nfwJv(1zi9rB7F)#J)=6t7MA2Jo=eMHbn;vuKW5Lq2-lV)i1hbBJuuI~BMjS1TC6iAZ0;^+!U}&6FOQU@Py!*xB&p!T zKdriYb52^#(gbfGYFmRs=vm-re;V8cr_Unr@Ij(owg}U2lIMk=Ayc*xkY2TTBXgXF zOzCav3#X49Re~Cw%fd-~=>fNa^u8CDEk-5>(}8r(V7gJ$drvfVMjbJjuGo;ssi^5> zzG$VMt+PH}AW>=M6_ z=U!cgz=i3jEFu@98&ub}Ehcvh=r3zsbDOoBAQ7F7aiN>8gr+aW9I`YPB^}^B+*dWSscQVF$um*Z@w)V^6^Yw? zZb)7FwV7d|!FJ%>Ksr|Ry5^lday79J1$$F48j1M{FgLj^^DMiIWl+~r4u)tga)7i` zP|y>tICjA~nm89&NAlQD0M4bOFPVJD_)+7>j~aE`xSOr^-h6dV!hM7PM&5Ki74ph= z&L7!w^Uz^4Zn=d@Ffbj@3*&XnTaV?$ubnWA%!osk!!}YuS}1dR1L`=npCe5tD<<}p zkxd*};mi&8tS+E-Yeg;PU24Jkf`~5J9cph;zoU`xd|r<{LMAEFIv`M2R4{VRxTl}K zW8^)H@(O4Ub$>zLd`vHE3+Cso5+%$PkQ9eB@@0r;ejRhjQsk9dkPl)C7E8t z%tXE5dLimX5U%l7zlmEzwLw%jwiM=`|DJBqPal~6qvrqf&Hhcp-JtR1mtgvE+~=kZ z=`Y&lc4s~LD>bni9F0jK`!N;C{;%WD^c^rX4*haz`jEn#(woJxl9V-p$z=nf>k&BX z7Sk;`{cf?jP3e}JZmj9>xou6yoG!|i=fxf~Oj9JeUo1>Fln$x8X&i#*itTdIQcgCb zyVZ2yTxz;d+)~rsR&;YIHJvybZnV#EIizlZyFqko!mBZ_$6P9rQJxmPdh?o@8*riz z%nZP|Zu~Mz7ovX+Qa3;D-*{j#0(wpY=`J-UhjA$dZKd(3>N3Dk9GbA=BsXj>dbB2? zWNx>?bcn+cIulg&%tF;IzJNB?Li0(VT?G_DItCR!%GQm-Lypl(@Pb` zhznk@j_D*$5$Yg%> z%d>prX-f2NfAeR@8#5oY~ z+_q<0aD>TeeEZ+YJ^Y|vT{-*jn zCZKS+PmW5nYpU_4V@-#yX;9>JMI?pMrql<2j_$}_ke3%7jzD-!GF+$8DZ5$fdFttc z;hFgO%#A@~C$!zcVrl6Ft@Gog_?w^%{O|q>R3{TMjHj>mAz@UU zw=Am)M`Wj_6in}HJ>7SySFbgjdzb;STWv&IHv zU$D%m>C>mrvwu;WPsZ*l+PRrTm)JVYAxllzcQjHo5$Ti11DgfFvB2FRx|`FD??oUD zPFp8tC8A?_K}7Fif6H`oRcFx$!!6O=>Rv=Hx&`cp+QsIPi_y?KI~$t%tgc0D4>*Uk z!S1yMd51ZKJ|7vKnoSAXlUr^ZH+1OWp)~X!VSQ%`)5YivYBuF|DT)Tt3yna=H}r@R zO^319U&3v#g9fPSMfVJwF_BD0x|v{k=?%w|PIat%tZZ6o&Cb-tk|z1gn}}RoVxZh& zc?;0ZY9q0#8_&Af9z|VkNzu|LH<4P&E=K_`WwVSsjG~=O1`nPyX969JFr_cbi_V+B zh?b?RIZ&{+U~S&~!-VLped_R?k55?g!1#ynnfzqbq`wqQx5QOGG!AsBhV&cP>*cMpRFM9p^_$=P_9hNax>4gxFOfwM$}Khh7ZQT`^cAMV z>BF;O{r}jlZxaNz|C-SIrH}d7g@4+2Kun5~Ehtrjd$j5-<)s08j(c6=xlHVwCBL(-v~l6N z;dE_5g9U^w63NH_!Y4A}LZp6+*@Q0dmYS~2cgy1EirpqXkvz>dQpJNiiX-Qha(rO0&o9>YG?l^2O+F9o_A*LEkuijmjk)<7YMZKh^ zM#RKb#C3PCv3ibfvn?*S?ts}br!z5Q0rzN4jPuFdwPZWRoLqiVa~Xa5W2VH11|==YilbSU!||;M`xOM(#S|MI-LIVpPfISPxN8T8Zz5yQH0pd z`o#Yg$7dkZmgQVI`EJ)w*PWtEOAm5-Po9cMNrUO=*l^*|_dovZh4)`L933qi4Xuo> zH0JKxy?)Q0ZPUhH_^tfv|Ne88Y9cmcrGeAYtQFZOFF39drKW)Cxqj@2`Q`G$l{%R@ z+dtFe>`ib`TPf22NaF;^S3t>X#ju zjix<3;`P3>@6jtMt&Pgr*_hBtV9ZR;OqMt^U$z_a?hHhJ4WPCA{9zuXQr@an>&)E;q z*>nT&2=R>I8>l=KV5duMDFvi8n^)wJ2Sf!aB#sX6ObSz~qKm^j9AM$?A*d1dXN$DR z^;E|rpLB2K{1ZzAp+oJ&zW6vp=)~%s=t*w6k0aZQtGcGT#50JuI4jWp*uHBzUY7@HABi=6;q;9brDGqdyo+w5RkNl* z?PlCPq_U-O2$(+cZmH{24ox{Ueep8G>C_$0+PH-*MgaUWQg|ytFH^Bav=mnMo`9VC z`k*JGSi%d1>06H+!JgjQ(~0TDV0ts^yOsE2Se?>QK;6jcLUi!>(sQS-ZY{j4a@dGr zgL^rTQiA%hIe5rd)(n;;Qd1}kSQwxk8eMc99d>!SaP`HKT)}@W(&kM#y z=(^x`L+19pS#gK-aA5yA)bx3>rrU&m&dmIyrL-GhhtMtAoprben!Hix-JX}vqq?;r@tQtLec_1(CG*OuGy5#kd z?qVzETo@h}67ypuZ!Q_iGAGf6Q=WF65XU(!wpDb?;Ua7L8^-jaKMW0ax|W5vgrBHt z>dWiv8R%DJ9t;;tLEa-XA0qzbkx2x$k8f$Y4MHDx+fZCCe8-OFn|c+h6JMUg=G$tz zN=W5;>1!Es(@nR~Bb+Z&`hSniW4FS{>7w+U(we+EBlyOii0NfI`($voBPlwikW~Xx?~D?qV~HuS-=6*=%k{FE zNX9wChCThjOL?p3KfGj7!P-TS%wJ224!H`^^VuEY`$6Y>Cq4YsBXgEKGIGL%C6D|i zsp;mkVaLHYfb_rl8)HsKFaPehpT|8oe9!^1T=-g0O4)%iq4zbz=^t^knj3xE`pv(^ z_3{TP9g$q0wGg>6rvvQ#f%75B0NE|adbYlH6f5)B@n`xDSXe3?1zQKG6o?hB+Q_O) zL+OHAPKMM`(U}vdTb37z=`yEVoNm-~cw702d?X0GalE({bWu7B#pldemj<-O=ZCb^ z{8%zN(}BS=0nCAam8oj*kbt^brfXXIHA-C-?#_gl#7T&*3v=ZL(K#igie$8gUJ`U~ z4i=dAK{x3A7PNso}oi&Y(E(X}QXl}@NGF@1p4nIok!A??HJ3mZsgOt|o2LRtr6 z`q7A(oD~w_)97rvojazLu5rb<)}$q1zS&i?l&3&rBtpsMLNLQ4p@zm1E5zwzFktXs z8=M*vL%1JNG6vJPLE|!~n+no%w=U?iAl<0x*j~2Lu!gXWFn@nM66IL}R14G5SF2xKe)ho!pDnug@Y>VO7n{$}1qtnYT`o3{4DX|R_Ad|H z^S+JW@m$+vukTJJJP{%p73lSUC^0 z06wsxS~K#=_112XXGP}j4_^4}z$mza)cJDyNP4qy1>COXI+$;Z30 zpy%ul-aC8x@YM_F0pd{9^or!H^T}dxlK{5x;$ej)$Gxfq^B1ZT3lKo$-%^#E^ zS>ocHA)YQr7~emspU@j;q(tn32~Lim6l+4=b3mrJ$yYp zw6U~Umv8K&D^}zrQtKNS6l8z?W2?ZLzIZW-jMK?;xd~1Ocq@DF+SnV8mdqeLq|L_Reu}Vkyy-wXin<^jjr}>v;iBWZQw>u$ZrnJ6)O6z0 zO$Dhsk+z)ZM5c$*k3>c4N#lCCIr7LQV{^guatcpPmyp{C=9-%MYs`M#4crE!8zJ4A zWvv}Q-Er$V;%AOOsGt`q=LXi*j`W;4S>%4s^1JZ7McA^;{1oWtB=~2zHFa@0KQ^@s z%B7}T!^%_tjYaG>sDtTn`j&9(7ZprxTUN3IK^M{!G$Yk|eNx`Zd5L0$miZ94_F#&3^|XcmE;!W73?(GmId>rsB_@pp@*KD^w5N;kxTB0dUDCg zJEGiy8h@r-^`CxP!3SEmD(FQuq?YeReMtE_2tGg+=>af%%mL=6^@HddN=@%aO@Hg< zRAu=_RHM)0d0gf0T_m{i`Zbzv4mudh>tlJ0MiW^CED)j?+O@o6)(@ zFxG9&$b@bYIfQKH`ApEqg03j$#rV_tEFgZ7Qc~&aqHY7>*w9%rv2qnj=qenA<=wO{ zwcVh+S@DqW!H+oIqI6?!(L~QdXbzL#a>%f_xgu!iM{2rEFLwj!JXh^g@Y1-$wcQK0 z!2XDKL(EQxUYKR+k;%nEa~Ax5GI!r1d&`#$OHMZqb@%VB9Pf#Y>6p&}bue9WIwHD^ zCy422+e=rh0NaU7?2d_%TLmzekRGG3mxzdD$UUMK`|MbMfqGi0+%MZpOw3CT-gN9Q zjBfp0=#B}43!HdvFUOT8BzovN2Tta6^z^G10<4$R9$*CNv2h&r6 zQ|DH1e)Q1~+f+rEszvO2N5q;q&m{l=AOJ~3K~$ubww3&jntm&}>9;Pp&YO-q{nl+f zXO5kP#W=|pBqgRTJ(>PSnE~kmkSxh|ad44eBCd#xL`q2MZAP`zY|4%I1k*D!J>lhhG0oEmz#~juj;5(>i2~IO1bbc-sp%x-lqF`O)|c@Z1h~_8i9Sam zKsj)3yf299%rL>yj-Om9wPNLKF+1P zV0+=g5yaI@RBg0M$vmR46c3BkbT71cKg?l{Afg<(>hH;454q|tR}5i}L7qgt`w`eq z%Tg~7^mq?fY*8#xLtY-f#dE#cTAW`A#}bHNH*Ju-@aZSi zqy_1$SrXG_O~+qQ8ChA_5MD^}sKN9bZz5{SoF+~rTuPj7;$WuCT8s-~S>ddWQ>G%3 zzbV(bDoB^jni@{Sp~4|kS{hD7_07k{Jil{1YI=A>Cu%x+dQZ=hEe*#HUOhz-DN?#p z8k?Kzj5%GXZgINGNI_u?C#Q}~tt^~UIds@Cg!J3S%^6HXQZSv4MjGlvT39)_aKz}! z!V^7Rw*t#McATp_9)9Ft^Q}89I2U{i)W3Wftkz9nHuu(=Mr21QuQO_Tm!637U5ut~ z1-%%%3+5LC@Xt{;x!y zQ`}XD?M3_=yR!ffH{mW=!1MA7@>C*e+%9=5QPT%(FSf4k_PW$HGlv&l(TVhoJ<V@b#AVv=6)z(DBX%c@MAOHW?394<)lE7>DJ$_HHWxy)aQe9#eM{hQ5wDjh-=Lu-$t!x`3y;dFTA_VXQV9RZ8EhjIZ;;Ht!;C z(#G_h)z3bwFV+$4o)z-jR&2{iDd~c9w~mgMj+!okU1~aHt`lOq&FQ+P6}Ya$4kt#9 zs=^tw60o1y3A=M^OH+Zo`}B9JV;_dGGdgeOWI7y8_`yhobCCS>>YaJ?PgR~}-b!XL zsn37pPQqRuczonNOQOavnefc`g1<2BH#n?WNiTl`rdyQ$)_2e8(5jAekKv;-o17P{ zD+ktr=&aEC6Y#pZ6{K%I;0BE^y)1XD>6UPAi{=EW8>@^lr~jyZcre2KAUo~wOE>e^ zh5wW9z!;0dE%_LHwTBpe0Mv~)UFf=siI7)F&WvcCy>tPvr)L zaV~F=imr)uAzIhz2J>UT7;YTEbhqb4FWY(_zRY~?euI9`rNMJEVFmm5I;OlNA&olD z*lJ2e#pojS6?0uE<2uy%Sc24TGSgQifR?o}9mwYzF-H$5I^7_8ZGHrONjcW;PgXdj zj)_G!bybq$XyFIiCheuWo>Ee3NYespx!=){Qo5hAj$&cVV5cB0Eq-qC8oAU}PO7`L z)l&PWs_)c6gF+HEKU(w3_WJZd-03WX)DMiEOPA9)IlU#F!{TV?R!bv0I9-e7SwDuJ z&R#|8pwt*&gX!sQCAFCd-t>C};(V|X#}T0I=a&Jd=eiO_l=6enx{@~QIF&t$y<=co zGX(dZn5^S!P z^6X7z*sk}L0F1tlTx3odG9dF94+@qh#xF3O{_W%cdc04TnVx&!fB*eE?|k8f7Ygu? zf1B-ndgaQi_uY5jw4}h=^ffVicDQo)ZOR^d9!!VRk<jm0M;q(+_VW!fA`&6kETW(eXPH)lRDBDUu2xkY9KhAI2FMT$@T0cBL zx$9LL%Kfq(8Q$4iPk}J}*611Q@ZhV5zc@~*UKxIgY@YRk%81Pj@GSG0ts2rG{hpG8 zl0%aN$VrFH(Za`~hAZ)f6H>amk@_iZRK*UySX1JBVq&}kW4yi81efr10N;fQC1*}-4aW2|XNXHacMcSxwsSLbyDT%TLpqb!@IbGOoCH4tDeX@K#Pq4lmXY)V zrB4@?55We!u&}pqS=C}F-Kge5bs!y7AAM-m4K}488bTV(^y#w}_f9{Akv+1tbt_(T zQy$t!4^m|Fs>Q^^;0La1YC?#uYUnkXj{ilij)dt)E+d>jhf%%xR1ctjO8#`JNMEk& zvh{Qnc7w-VU6&iSOfNjN5nRLVG6z^6H&n47k%dzk3nLZtQdv2Xrw*o{gVAxT92ACL zmcA|i-f<1m2Q+gnw+G8Keu{0Ks#8;83asytHU8A`smGD^-GF}G3|jxos#KLZhes5o z^C&`f3;WIGHDqX6H)oxUcn;`U=V7G~62e#4C1?V%8)OC$4bj;~QEgA&Zl%JWF8wTw>s<-#{&Y84m z6{oW$tn5`)EAyn{_tS4lFY#)0PjueQapRu30slu0zRlhB(f)P)ufL#%^i3GunA441j!r&}`q4oLl%0;6&POKp zmoYn(_43Vc9)!{_p4MFJj<0y_e3R<~*TQr<)oFEkUX1Cb-B@8TyvX(P*YW524gju3 zOc$14!*q+$h45llb7tNiHmDm&=kq~K46VC4-Jm*0-1xAthg5P4zuilOuewF*qJC>=Ga_;^xji+?I@h&`Pb<`PUWfVMLPwW7hxHf+&aJ5h>Z^EF z^dYsHkh0p{WTcDEt=$ug(|-?(|DnZ*>E>nyuDgHbyI{SS6$XK&h6ye6iW-ZvPUU4HQ{;iv}Pesa;3Nn7C{0xtp+ zz4k~d%KRD|!SvtUdVn~>Jtuq4euDGmjW_zv^uPNNoPH&H`R5RwEhR}!FJ8X_)63~A z`}WG4ZXUs&lqXROiJ%@(TmRt)AHV;rhrVCxOVMhXcWFr}$1UPA$W71ibYu|Ok~upw zF+DjsJz@3Xdwzg)ukqSH{OXDJ`eIPj35B}+_9B6YCItmT$U(`3z$gc%J$v6ig)Rnp zg++J-qP5E%Q@N=-&}JZ#lsQ;#{>H% z+TRM&s(KK}9w{A=_xIwDh_VUn>VSI;z8fe!XK4=qzc}6bB~W(3J54QsZ1Cvq+}DfU zi=@(}D=13wqxjVRG(b&{d~?}@vlh;h=S9}^>0tW8g@p~h8)ZUAHW#4ZEsr`gRL#3N z9fSJx>0736oT60qEs>YObTn~!UJiyEmA#>G%0{Y9tBzDv;Z&#!@0~?iX(#ohTaRpQ zI@qwV;dmb$eiiwh<^rdB;B-}zqNR6nVGHWdA*BPxUHz9M?<(9lW!SKdhlb5z+%7ep zB2wUdVdd1qsdBuGphan6%R!=ENJ{Uzdb|)VxQF6$gXoCrV)frYMAl}!e6ZhuJ#jGS z^zfIDPkqzcTaf96a#4Z0WOWE#C!Q>1&t2VYZh^XCbR=~nuH%4_xUQ)t11DzO!`9TT zt3O3lf9`~mUZ%S-eJ9;HN%vMEX@Rm-6u(GPdOI#DmcyXAAK>LkuZfPVb|S}~BLHm`(y?`XLlLWj|D zq0@2%K@3HlmfbfXoug5qXVEsCYm6a$)$$uM=6Uud3RZ&Y^D(C1&37(el-42Y8P7hx zwg?YC_ItjLR^&Xfz2@;JpXD~0(+T$+PjM;`4xdBeOO_a)%aSF6bB3M~&q+K!6Li)P zqU$OGJn+um41b3sdx!Pvb?q!rwJD3aGsh!V=3y$@)xR^k=PJg1V153ao9}pX)RVV8 zQgC{0-pD2F0jXYAM-+HVc-!aa-FxrhdueerVdhIwPYydY;x7)38}57Bba}; z`2ZjH^d1GWE&B_Z4#CsDCpLde*7S>r>0o-78#KQ3QjNytO&?>`kP^5h54tE_SZ?(p z{e^@R;$XgX1AkrkKmQJlK_VB8Gq_;h8eB1?K5&b5yLDBjbe$~A3!uJ=&k38-jq624 zq^mH=X)q63<2RT4g&%9!lDa-!gx*@mAh_Xq-C+RHxrYf-$KZm1F53$zA9p1j1<9}jv4LxO^tGQ%mm4S4o)?nx2Za&!fXhXi@rCYC`_rg7EzaM|>g&3Vg z#v3uv+;mM%_i6Jhj>E1j+sO(7Urv@5=PWJStPCuo+lY(66ochuJ8Jlb*jVg(m%30m z7T`=jDoh8_={b227!88H(Tls38_VeFGVkx-d#`^-Tm(cID9!O6}sGxHsL;uR<>5|hwOejgu;sc`GSYZx~4RHi?+hV%ZbgAdR zGu9CRvu($*J!_6eU`~&5qLhw_h>Odl$P+~!H634wk0UuK04s(M6zA>hz-m#^*5>JC z|2`xqHkE2sDUxnA-FVZ<@)OP1lCQm{bXt5)tkWw7R0|0Sp!-aS1AOv7dFFc`eY^P* zgkCGFej*jH>YN50*IpX!V-$qUU+0Wnq`2YPFk$G>- znl)=k*Pcs@9O6{SB}W#pDh05>=n7dhc5@#uZ?R23W#nnLuP;*_X^^)!rWd)>F|sq{!Y50eCy|t0#?uj}CziDN5fYPyHwWm} z0R_wK!aAHCiS$k-S{@J%$V%mJOZkPN4o9F~4EA>HGVD@t&?CJ*s~kutBM9^-BL&k7 zzh`$YBgQXFPG`ReAjY2V!#nI3?`L-3JVU&as2&YdpP?}9=Kcz~iT6R-RC<(zW1^;c8lHX8t|r9Zm}^vIJyW~polY0f7#LxlTZ#Y z;vXUXd;U(YU;`oj8y(#=9z{+!1F+m_B3(sRTpCE{Qn!US=-0Kf zZ$9xSQqegL40QVFnfT%JRz^*pJo&cX!9(#OjTk|lm%dsl_EdZ^UvLanifP#m`dX%E z_>dX=fvOZpdT`YU(-(8%c{29ulKfH^%1 z@RkOyf#n=Yp8=K|;|s`*IL;LV=r*LA6(qG|PFD|7lGo=GBuO?p7MRYcKJop?s;HT# zqm7nszu@Rc#?86?$=h$gebQP?E*!MrR&E!otBVw%zG%_frxwwXbmpX$Gbi_sI5hu% z9-jWB&mj1~j)Tf$v>O}=#hafGCMXeaI%>MNc$DG&f@In{Rb}1zsD~ z95vm9F9sR2i^+P?aw|EVu1CShQh$}x|D?asKjp@xDg&=ztUN7-&Bdf zYqwso^$z@3SY3=xEaUZRdT2=+-UPrpEk6D+j4nnU@zmwibapv|d^Q zn+F6E7ZY(5U>Bnkv~KE6)exyv*?f%c+p*!K&*lLMMRWkl+O=>Z`~&wj*>(_mDXo|(D3&C}N-Ww=L9HFp5hVO!{y=*aZ$3iMziN)pTJ zyVL2wRGj9&#@9c^!zYAhr~Z!QEF$up{>PkGn&I?jsv*xOzq$$W7f#=|yL}UwjvOp| zNH&HFJQ+A`}FCyC7db2oGsBc0=McI7t4XA4OA$u7y&0RzY_okpeJ z2)=T?5MVfa_+Iu7ezWfR)co^D7p!Y;{phVv1nQq?Trt2(>WRU1HpJMAHQlv$#XDyo z_?IiWzKP_fvry}4l9c2HrVDN3cK_2a|NZ?3UW&d_npj_7uL^+TM3;ABh9?D~Na{fu z+qdVg|MA6lUi-l_uf6vzPG)@TwQv2nqQf&L&YOTsFg{#_f@+5#!q3NDMpu0fbIN`0w_Vw{2C!fF0fEa8o2<2X3E+ST!rlok% zZB=5rX9n*ya=T?`M^JYMuoUyieQ>XgXim#-qEU&iy&%*?4%JxY9$o(`Hn=Qh5$_4MZBh0`|{jyN=I zC}R4!XNDdc*4whUC9;=*cDfru=@W+)%JkCI&nJQEM?v<&seN7GIj9b-ANa$dKEUtI zkzLk2YIz;b_{+y1G-|pL&|z`|=3SD~sekQf!L0+3ZutC~sLq_!bP+m?ZY=BO(r~#2 z>o%(s{Mg*u^>XVQ2ft_JbXfh|a}Bg1#hh;cqVR?<-CTE)`q7mn2uAm))2Plph{2ZW zrHQx~Q!~n9Af4>PB89pX2+})I(Wipo5W1Y`mK)uob0A%mE=ZrZ45vT8xjwXcs8o%J zt{X+Gq4c8YM-H!!KD^|%p+mLe$FBqHt?O=PkKy-0e@^Hs=nx{^eWW#T!BAqs?_Y3E0uQylB$>hZjAvC{N8+ zM@}9$;x7%;!SU8N{)QsbPu$-0Z+?463a)fm+H@j9SC^U|yiRa_5NrB>yel#Nn}7S< zAI5ZJZXqFgc>CXj_E_9mowJ4O7QFwco#rWj#q>WVSO00ZHO9cJC>>5+waTXR0ZO-c zmaBsF>xUcBxkSPK9Hc9h(FXD%hqQxlNSx`laJu_97238UAq~wno)E_PZSgu%9-B~#<0S_r9Y`m3 z3LlK>IqN$%yngA@>s^<+>MnIXCWrdiqaGpP4B3U`g(TB@9Lp_dWI=)`N)+Zu)}!Hc zQMw2`A)$n|!1Nf!rJIgOLUoy6kkvV{M^M6YM%#9}K4xxD4CG%{%6a*ithQGkC3l^s z^x`l;40HN4x;@5hkTczI`sao8&sC8wxOGp=8Yh@OEoLlE_tcP%^x9;Zx8+U8&{Kjf z0$N8>m%1w>NL!qDv2Rj}SK89B@|1k1k4u>D<5Pl>qz&T+FNYbzX!29imd3A%nU)e$ z?3^|Y8!^!&A-*pEW5;q(!JB(76T;}&w5fd`l#W+};zyauVf1W(Hj64l9?>_KHk-L3 z=!}xKxQ_0}PS$~Y#XkUMH&s^W^ ztV>eU|Lx}=zW?zH6p;>(=-99!o)Sq15s1a{xyzGyI50ghw?zGg6xHaNUIwUp%ekY? zWCg7w?1dgjsS(?*{6@x`=GL=sJhS+dS*YnkZ?x!=^;R$no5J*sB)+NU^lRTb-I%*R zy*rt@O!o-QqItb19w2Ne)gQe7?;k&Ox`qQRU^=R`ydb=l848M2-i@m<=i=#a{QxCh znC>1wxaY$Tl4?2vJbjCE{dmc~NZ_Qgr*rtGc6KsRF66Dy>1cSU!#hL~DjZ-?%1edF zT#<{`bCFFwD6u3xu`MwJpGqLTSjolD%}r#NC`qd%1>$vr#J&A!Docej9{ErrGXwL@ z{j;HTz@8j@(p1t+aV07M03ZNKL_t*3+ZFY)o!+rQK}lnV2f@}VAw}RG8#2}l+1se; z($OhTAZU|a3}O|rnGmNBFein17L)b@sFx>U5%+S&aGUOJFkNbThzUMNDHo=Dc})xB zpcVT71nm3F^`vF4pCgF6Raw}LSBCqd!-MIG$}3VKH1(*SbV;JsXsK6{Z-|L_@kysJ zIwK>%;aeO>whlfU3GPW@@v)nWmd52!%4&ZaD31|Fmzqu^BZTse;SI~)c%$=;#pW6k zx;fdLUP)yFFmbq&YIdnqD#Z{DUtLih12n=cQ&*D z?+qkw&nNA=v#Dy~l&MF0kj$G8ww{VUB|)8^gFQ-oK}n}E(Q|~XSc1AqSn0aj8D2Pj z*odLMgmDwdII&VuFDFhkv_wuN`q4C$=c3_Y*Pe5G&YhyE@6>UTCz=6tL+OI_13L~p ze_#N|zkKGv^F8w{O#kVEm+PK;x$FO4o;UTlEvDmhA>+kX(-HhxOx-9LZk+|_oXtsy zuCuP`%nwtUU^rRSZqvHCXl{M;&F0ow4=!spV!HJ7{^L_I^h}>_|Ds4=jE*J{5U-15 zZVBC*Mi)To<5x;pH>r%q=OV6@=Y=)$R`Sl1rD*b8NOZ9P-6|5bYDNd_F7p~1Xjs*J z)gp85zxsMi2h!Q->eXu}9WGj(7d7mbyJu@u|Mjk=)hA;qje27H6F%K6G$go9b>w#7vOoh z_wZAT=HD|DP@g&KFU|ANOF(<2i2agSh{rS?hiC zty2+Tw{qFOd>Blp6m^W$^dD8QMIG5=b4E=sH%oVy2dD7u^W_`(>(c-EcfdH)Es8Zg zjx0@CU~b^t;JF*tVO$Vb`m^~s5UNX1XNj?=bH!5AMax4h6dwYc8$BGL7O}elUW?65 z)~#k0!{;!$DLNH+GZ5tgb3TR)kVENWa#rM1$!2wZL|MyjPys8{4W>&?=L1W4?mn%u z;M}|fO&B^T;8xQG+1J15n^aOtDVG8A-vi~k&lkpxsvpJrqWijkx#c9TFa*>@eB}V8&T=rfgz5FqqRJ$5z-B$gXES;U7mJToiY-hNT{DZJ7{;QQ6KrY zMdHNuatU*Kx5+IjCs*;nfoU#6G-ORbXDUUF>4pAA2G`Fmu%gqE*md5vZBI;0{-7}_ zPG<@|Oe2ufQPY)mB2M=!=}yGd;7Rk&bZ^y$Y6Qf)oJoPg^wiW4vaAu)y@7O6AQ9dv z6fG$skTJi!JPoT*{F-TA9$_)Z))bTRl2}q2ziq*~AAc$poS>Hv>$5lQ`vrnFB6Ctu z87*^`!|aCBv!PG=g638b5XoEyl5j;uZFfyw-SLKhJ&v6I-X|Y@``vX{O2`|`%JSc~ zZClLITzUZ|O`}S5uZmI2jveLoZpyAVa{A9NNKVJ~l3&}=U7YK3gm^Q}&Gi+NX5&T4 z^+U+E)bw-$Ofp=;^yCV1#*^dMz5Bg)e{)}O$~Kj;Lh8+Ddd?a-y=Hl~+JcsBFT-U* zx6b9fl)YfOD|f{^QD-k+Y4r7p!~SE)*1}t)W)F|Ri1MuTS3dsbzkhJ&+AEFmrMxs> zkWrYhu zXz3VOpmfF0m@N4+wp}hcoehv|$#doCgZ3-fvB@gio*7ie9%N8P(C{R01K9wzDI8^r z(2Y$6sHO{mpUcPPlgoRrQc%|#0`=p(BSL&)LdY&slOva}T8u*JtW6K2Fq(%_mW}BJ z`Ft!kc7F$dP_z`~DqBWPXM=um4hLo`tTx6bVn^2n;soJY&W!H;tZB38n+|^eF|?5z{wrnKJb_JxI68^1`{Hu(098k*FgJ z7dG^nR1s2NP}6CmbfQzPYWf`=shYZF;qg;f74%|EFG#*(bpq8@Nh(QQ4s|e{rbm`P zy}75aYVpv*p|_FqGK~E85rveH_M)X**7S*$!=_hOPHkzZgVLY7+;{v$%hZ-gjOvK% zW*9XcsJ1{|z|P#~sa*?pxH0`)SO0SaF-lEukT)I0o8T9LI(qucdV)qs7wuo8b3yp$ zPXkvK(8viYm-mHBx1KI0C+6wRgUcRV{6_1`UAq2{|9GyeK}j!_18O=(7r8Bv(Z%FC znQ@pR&he92R4`sTv4+eUIMV4|M5N1`4a*Fj+XDIkno~ZiEEk<{r&BY~L?X}O9=2kmlQ^r4nF zo!+TUl<}|6{KF5w{=mJ4(@$1cpIm{7GH1o3kI&&-_ZE(nU~;M& z-!i^slq7J16gd&K2&GdmDmXVLbC}(d&^6`UX|uX!70B2*vkxg9zdpwqPSd=#N~Ne6 z)AM!~M2#O+HL|Zjl6l?cqJo(>kGo^Slg|!&V6Cajt=lEI-zALSr8k0izu+l_r|0EO zTKUq-Nh|L-?EZTF3%NulGf^)ue&a=3PXFe2yQmzs)O0A^cv84_^n0-Rw;=9Mtzy#e zes`=bxPR$8!S_0MLR1-JszuAN(HN>1rHj_B%F<9{PXE#k{B_~~{5w!i{ipy|;4K<= zqpJH-G;4+}rUSjetxonwg5^w?`vpekbHW^STLmby$8S*FSYXIt(WT^W5ZaWxu%fPu zw{?p-Nl`b-xKsjZ>KfeFER>jTX6a=lFxN@9aAF(02Iai4b>*hZsCR7`RM(5t2b#Gw z^KMSJNgd#ppsrWW`(W>`Xu%&3=|)XgZo0XP`?p(8aUFGJcwOcyDIHQLE?rUTvBZ~K z=`Tf(Zmw?YuCJ|q-I!ivd+EZPz5{!@Kf*R$9}!9G12Cuu)<)nvKk9MxXoyFIM@YXZ zd*#wAv@tEo1fjrmdMZpSPAfHCNDZgU+hPqTK8tNpjgS7Eajy#IlMw z1v17{&9yYP*clRWET%XyuB;+GJwAS0F<4XX5F!4#~O1>w6E0B zada*LCP~ASyc)s!_51eiKeprCt=nGR6k?YHI z&ETOll9Xr&AETxR;ND2j@b;1EB~u}W_r3cY+Jn;f zp+WD>&gRTshQkm1-&8YS-gHba-L?6l^6{7?#4NlV)536Pm8JcCS{P7t19N?x zP&UX6M_Z6?)O6e`aJoy$=80He9Dz=9(@8j=>lYFj;^|4;3uVV3x(6z`zr!S;`x{F4 z7o_uJ%Kns zIvw2zjo)PCbb%If!wA}uj;{+%8wy+6_VommhlB!37L(`PsbZx z*L=AFTI*GFqhTWsRSq^Kq{^jXY@`V(O_>VkU9Mx@%MHirOxn_mQ~i=n=|c4bIu8_* zTBOeO8nR1o?^$-M(0fN$GkQ7Bmdg)DN=?V+!Wk)@jz<#wxh5suFgo;Y&4|Mdj1R#1 z7p}>lZd7$kP?x-}EShuu2MM-Zym;1wNBUj{(qDeLxvRfn;g-tE=^O1|6fHh+NNb4G zMe5eL_mKy_e)}WL7qmpdpmkD&qoZ|X;@}bEWnp6299PRg;-Z$AT2cH>RXWzuH2<&+ zGpnOl%P(VbDAS^%t3|7?Lg`n{Qhe%lJBcsciJC4i6lNE`dT-LV?cKBzlvG6&5GV6} z#@8)>HiqT7ee{SKm0&v9&q*buMI)i~IUxEfPR~9&=gEI~{K?1fJiPkRq8fVL@%03! zuc)5D_b$l}m4o@kSDjcq3WGXP{7r-^Lfxq62`IlNng?^`F-^23+CTG?(1Ys4tqS0y3(DS z`)PaxrIU)u4@-Fa*V2g;PA`DdA9-X_RDt{J^)KZT*ZJ0ONKZGEEDwDm5K4Ww_xSP&H?p&CNAKuNI-Rrh#+|gvlu96T{+S;W%4_lf~V_bVKigaZx;% zS}I}}Tno+RchN+*nsQR^FIqRlGQx1(ieEGv*Y=@vF3j0Lx*nYup@%gmo~F=TpJRGV z>)DxCcx|%E%(8c4hQV?h%?+fB&lv{Xt=T_nYIh-J-GLI)L1Cpd{3MN$o<>xSV&p&q z2h)FrgQ;b=I)A+&mQXUA&Zj}58hiq& zDXE^ZkG}FKGCW13W(0%W@pBQFjStez zOiVA}l((lZ^^_8Mt>Nn+CUABTG2PhUvHG&pPd7&s-9c4mVp*BDi~7wqzVtVW%O6x8 zV?yR#9>rc>u6TG%ZEYl5HiGGAPSf1z=jX9dWN%7J!Z|{@qVL}2id5Wm-}2?i(x4#z z2&w5Av@Z=L?=QJNbN`k8p5w=lU+xFf-}~s*WASO-aWq`z_b@wte_L4~so?qEiR+>C zeXgUm9Tjl_Ueh*QRXY36ai@RqVSCbn{PPtZ+j7g=b!31v87e5*y9p(MMQwh}0AG=c z>2st^#}%iM zUQrUiZE4Z>UwZ9_V)Scv7q^`L8JM2QE)9m7irW07Y>q{Qg(fBC({ePfdRKMziUcK< zY+g}X;vFF~dMKfc{6*p{Px1{SL}xt*4^ui5D(-Ru@o)!^qD7!sJAS{_S9WvjmmhC%|a}IK9#Ml?Q`T?+OWXrll2EC#2XP_juCfTrnL;1?A#z z(fT1}sO$PosOT^{KPVqFW-wQYnl41w;F3bqAyyvaTc!u;se|DQ3tOl{YcVtH+o*;p7>mI3!YPqkji;rrr`0gJSp5{vmsZ=JE>6D$5hJ-9Dn51T<({p* zgt`wc9EX~Y4Pt1oDn|wOF3*b$ z>h59Ke1Ord87UOM4JU@5p2nm)ARQy$+1CSh*A-k9r32}zKs9Q; zWOVamAbqtk-9$3d-e~9Q`BjDdSs-!=(Dj8Tce=#%L*%mDpsz!|SSwfQkA~%Dwb7L` zq^8@L-efQxEqw+hqN`Sk)}MUxAD({lfv0f2)GVdf9V!z2jaEdFvPQrIHKap_R-I@W zA3naSDr&yk5^)x!ciQ!%a=ma>3lPo?qU#FF@Uffrq19w@8V!sr3p%7uQhHjNB=xzN)#+w#k$QCkqGm^aguLlp^1NK?QV<{! z6r%L@`g#&JGL!PdP}0w*o)@L7L8-@4jJ6(LNa|^iQB0af7o~(WAK(HGp_X)eoXJc# zWuzs$ON8icyUp2PJ64(PX@2=3>7L2d^r5BWPaotDlxz$Nar0LJadfnu_ZsxuT?k=S|)T_~`8d)L}K^ zTyPWn_&8?Mb#it_S)hrO(I<@;-eO42+b7Y&bQgVvhQ>-R2S4&c6eAK{G4<*UH`45sr`d^7MfC(?|xY=7g) zlfQ-2d(Mc{-@QUUe62I41N}b(2TLM_j`@M<>`MUZzA?^@iuA;3(~e#;?M{FG{`(*Q z)4uE!S+$SlwwJXlm?RxXzerZmGFD)@j2!ZF7^k|z%M*_w@dN4x)vti*C+RYk*;YUq z=^OnE%Fd+u88Z7D_*m0 zL40u=V)`#X{`fn)*YCx&;_V}VckU&8vaGE>w{h2*(`V7q<#!nv-!coh`r2ndJ71fb zyD4{lMn!ire4dmP8X6WFni?7ylD7GNbhd=FgcX}>NFVnJEax{0S5wMNbuGqk<=-b} z=xBv;uCNXBauXAAx+GC6s=iA2UNW+IM-+L(fdN-(d^Qp3?7UU%-mU0$C_Ro2t~7$e z>;&R_I~~--k_R-K#{tum<+>pvGSDkXWR5qTJyZNI46;-l+EMck2@KSM8Xdf#u)(i5 zoduy_dg_=^Clu}FL}M@Z^~(3ao&u(aDBwksJY}N_PI9V9RdPLh0je-n@FPu>EHxcS z$4|q9dHT>BSM7~T<2{|eA>e;P(dwmX&Qx{^s6N$SHT{)Hg7J2GI^lHWbcA@iAbI%5 zCnW63v8|)Q#+yD6nvR}sQ97bJfNpvl8BA9ZsoFtKgu0}rZ@FtD^`mI;cWs=)^(_sT zFK@NG8}%HVx^Qtrl!_MT9qC-wM^v{ug*LR{E=IO(IMNi=c_Q*e<&?tw@2#9dAR{HDnA4Hd zv8ERuIr!P}%U!QGH$*NhJQ3M)q>o0VXz27ivIa8)sD3@9%LAkHfgODY({JtXH;t80 z)91}Q4yGGYH-)1J7Y5`97~N>;)-@xh8#W&RbZbT$y5=-t3Zu(}u9QYDx_XX8F6<3o ztad^il4x$-x@>VctzD;7-c@;*{mo26q3bc-SYOb2QFBM$Y3chW!>M(>H{O-DgCt`>2+sXx_)8Fg2o_0>gYId&KjbtQWQ z^P?&`4t=*Jq1zJKXgumVq%q{~%Db7Ys$bhby8BP8Y1zE>pqbyuQD7F#?WN6^&4-z z^^NPIUcOD#i%rvtJ|{z+X-e0(|F%yRq_U<%>2G~=#UH|S$ezAM^f9$VU9vcEE+@N% z=>WVjrz?^%_^+7$r}}07$+sgh-SjOoR62m_Ur^I6DP4eW7~RmicI&loe}hre-PjH) zTNsY4Z2;NmV~z=jfc1^&_0mz!c_&VvrNVq3(p1cx~I-OvM$V) zR@q^TtAKQ#15+EnZ!k9t$PKFx93WW5b#osJ(rv$s-USQN1>OHyEnS>0&x@?-*K*TS zigOZ98Vfofh>BkXr%Th~v8W@dlcf%+KY9r}csKQydld9?L4x}0uiI*RzMSdx?G^RO zp{b@LsoLYDny5x79p?*>;f#sL@Xm($K?`(-1p1KkLibRUs7@PEsp;G6x9^rw-Tbg% zJ4L7417#N5EUO9d~}4& zMRUjX;w?2jBi$7fgPQJ{Sr(UH9#_5j^|Z%U%nkE)k+LVP8g7EqeH*W!roVgj?SFg! zJSK`w+3E;E2l}M!<;!2)4-@a-gm(mIg2|rJDk(@TvdxBgXw3k zO)O$zT(*tb94`TXEEsk%pHxR{E-9}*Zy5+M=k-=!CNHx+DzV2?fh_s;?Q_kMuk$- zKYroE5*;$2TD7*eBgVOhtVmbsl@%Ayd@?}i*Ji%uX7-1!UdXIS#K`a6osOes8v1sM zKs|!YacH5Yy0k4JVa1BJxDqg(5BN~}m9qb)@>K_}mPEhx875ChMY|~H*w5tvabSgU z_?5_alj~QqK9B%w~?mF7CKz1IhYvfoLQBsjgDov?IDGbOfrdphu%`+5chp^cN9 z&aTgFRST%`lA(0y+>OvuxIt))FWxBMj&!=fW@hrYLtS;LPf&ikPco*LF)8FTg4wRp zx!xXONmLNTu{Jxgl$L_!lFdE*i(UT0bZjm{bL#BFw#f(!&(1fd^ zjCKl9TITfT=;o_5;Hhgq)mmqq zF7lOFg1Q{)mtH2M@$#ulJx$@gv^kRHg+Ru|*j;d-kCUoCqH;7{juu89IZmUbQx(YRX3f~CLwWlj6YhGGEQ8-NDG~ z)6RX{q^AG9v8IdDPmT#r{k>0K_g9V!t&!BpXg5(WsRQP8eCoq3b9y$pkAKDV-}^59 z58og)-EcZcN?U3(HLPyw=L1k{IQ=G2*R7@t(nY`wgX1^A%Q~wg8dR+d-DFGX%vy80 zFlR&WQp}A{#-KYBuv?47;^u-_SluM3H~Kr<(JGvIJV@MJFylE_IlsOKOdmUzGCnDfior`R&kw=tat$d&Eu*yjxbs`y$t#LU5$Bc<^jaAHc zayRKJ0IW1}baYfkKObauS~>doP;y7=M`tIKSuim$R zKP-%#K723iXrVGr@m!vS!`C}KDXgRDx5wwbXx!;%FYeE%$PB=&faad-4W^Uqfkx|- zft-#Dx&wHp0=VP+&qe8Pzx~3;AGT+QCRd~%1Jl=MQa*^H8-&M&W|X{G&kRdO*9!;J z$xs)kr~73j4d1)Jaa&`&Z%}qnZVqmz58K_XocM(|50Dx5cDuQsK;-!i20LK%LEa5|Ya3e|zrx3A~;N){0+xw)l#@u_DFFV|l* z>Fe!f^=)9fD4mcO({MoZdipwCJaU+qSA>7s3XVHD1C2KZ?)RQs3Z}Ck${#u+KRu8n z%&Wm-4(ucF)1b=CHub&=HN%H|X2W$mGvH`L93tyKnvKhjTDY4H+?G#5k$x0(FvJ zP}4a=ZS^(M9d6`%f7PlH>~L(}RYTUx3i@DksCWMDGbZw-JGye%U>Y1%wTucMbt0;B zNfQX(35^>;U6G8Y$&oR^aDyRpm>pKf0i%nizSDK4ff2Q%{r0Ol-4ul~9~Cu|jQIHl z+-lY^viUCBkdA-)jwf$>`s*X3`-?V1=|$Mt#p;{;>(J!EeADSwtPZ9hK3uTV{q_16 zatVna=toL_5k*~yuF-lcAGyYxqGqI0)4}v4F#R-Y`ro&*hFPEb^ zIbeAFpR$LS+iJSCzJ=*O%0{C5E2e+>TlilmI}yqHUkj1XGGD4xdrEDklx4=7+r*Jo%mGIJ%#AjB`XNc zxrZ=aC~n^4We|0c`|0!OjyfalM9wuEAi^xXYG+lN;kt==)U$xT&ls* z7jn~6iW5#Q-CP5rLq2phDovyHD4Mz)>hUC*V+kZ&rL8S4Kfkv7_1E#dps3S}^eFc8 zh=^qT8F+bjUuaJ*&+>>6oilX7N$0UgYsp_6i?rxNmU?NiK@g{U8!4huS?VCVA$0M& z)but&U$(Ot<5)yq#OgF+h@QUMQds`Xabo$2guMq4- zFG;D9@}|RSn5<)5F#(9G*iX_D=FXkVfr4U%Zs3gp(%~VO@3AZIlE{df{`Q4I`PrNH zdO?h2tsthu=TJIwI%TB8vmsGJyD9b*E92aDEq8V#&#u07^~CYWR>|p~Ag8xiU^{`| z)8%!cUr%=&wUx|+>4dceB<41P>F56qPXAZ*^bdBUozF(m)-i#M+33YIg{M!CI*?vB zGRR|;oQ|GO9ARRH(#{o9PJYh-=s*|0`X_2?UU{Ovy|EeBOY0S%be|Yh@Zya1i8AIF z(^=Cekw%?0XMcG1Vq>v5J+q^h-m56;*x@rMh;_I!g4&<>;Duj3^uiO~E@Rn&e=EAX zW7x^t(Rk+UH3fZO?kDg4qta!&g~~s+`q1h}VvBg-TJDsh=rkwr_WY zvg_o?E#2;$?O4wh6{PFceiilidQ! zHvRX)(ENET@*MYyhDh48xTM4fN~hzi)0@Vl2_+$kX>qgR^srP%PMTMQlen0$B&WCb z4mr>Sq&qxKai~CCqPoIkMCncxbe4G;ZR6)4K#B3xavyqFY7)^~-a#>eK^pY;;c709SG#v5-Maw9};oaeOs6tIKo zhSY~3nU6j+Vg#_hvGOjQF_m{=mzlbF>cZ)FL6cJtUMA=TG5r*kp!1M|!L=<5AH-Wh zpPbIydc%8JLS1QRXLv)^iG~xAg)QocB%4d0@kg7qm#gUMSHblDI{4jiy7~uQdKq#2 z6zKl)rQ@gI=DNP{$|02-DHpx1cPdi)RJqep)hi1}3}d$UL}bI%sg;qPErlirrr~n` zt?)QI@74g+f%HA+&Rfh*(I}?@NgW;i$mOF4y09V((vj0uLVB4G6&@KO{Z_XE@7CeJ zoYk$RMqW3>ejTN2;ko9{HDQR=SISLJlE zL7k03<6kzKt>swLi;Ui07hN!^VDiU&eY~DD2 z2Rh1toX)Y0g1uNyG27^43oQ*sLf54zpos9p9JEzw3p)qYg2mtU~>uO*~keDD5ju3Kt4;UEJWul3L{V#qVvPF_Gm;%tydDE7MLW+ zg%0s>#-Xc|{h|mMbCP~;8D8LYLAt^9(zX!ttIK^#LfFODKRN%?9>pqb<=#$;K;dTw zRitUS)3;fwxygFD#_3%g(3ZH4+Rnml+wfYDvytNA^q?6-d2&F-Y^XN?R`v7+(}DCr z%m>UMljC}6lbTK!R6d5r$n>HTQWVi{YBHfNINcM|i!j}1ZcIY;V=fO*UZZdb-PBXw z^lewpe01gvhVl0=Bm?J;X~R>Ew!41QUikdJO`>!#J!vmC6oul9fPjZa$N^({+ObR=UvHL$)elExA0b8|1w6sGS-()aO#L8k!`qZ@xUF*pNkJ}~o>Z~f#aKY4Xi;~BH$wFj;y)T$mg zpgS%A77oOn9zo(uM3PT6!El@(&GFfu;1l6+L?orsy9nibc2=?jV+TEyct6q1-FmvX zoH9_-AQKfELpN4t){D+da5fDe9^{)FFK1l=eK7n6*4psGrT{2MTt8{z80uEy!MLIG0OO1H{snyPA~RLsIIBW z32@L@%8?ot>Yor>sj9-XW;(($JNN&h}`+3T2Dd!E#pB6$$FvHc~o_ zj?tW`Q1%3PZR{)n<^0xNX*s3*0kV?qX!qBjW3epk#r%EBr;0Fe%4xeL1mym9j8eRRsfdvgcI~LfKF1ugd@yN)_=g=yE zblrhrL%k)$TjKif(z;=E%k5%M2Uz`Ff6p6>J6k)+r|)Sd*roYR(kZ7Cud{J_cvV%e z-v5n@JFD=#@Ls#U>Cv{14pIx!8Q^9#ElK;Tdc&7BRE00Tt5A};9gS|_T+B{C*#>+r zlmy^J?-81dyv;`JOSV@4xz=$uOPE|YB)bzG&cj;^3no1UrjMF|md^K*RVA? zd@~M-x92?h+PC2IpZw%Me)7*h`pK`qHD?uHz?CzG-Av)At)|nD6inyKRfD@&ls=%io@c8gdGC_^|{)*{ec;o)8 zu0o`%++fPbfLld3)GkuLHgv@lk1`dW8_>08t^Iog?UK<~@o{2-x;{y)&l3x#%}0wq zWNaUcl=A^e+yui&H&SZHqTv0S6}uR!%1t>IovoNk-b-M{Bx*W9^qIf^Pbx)AdNPj2(h> zt%v4bi%Q5)>m%ANIx#BXTR}_5*kY490WTJvTT`;h$z==-O)3wKYfI0U=fz-pSaB?# z!PwHdM4zYf4-RXGIw^LIjWrqR*wNjF7h00S=UtSP?lFcJRg!K)4UX}kuY6dHKgluq z`JN@o7)M}OA5?TdABPvbg@3pN*NQN`Y`q#+@=?Oa$QX~}I4IrQJ8mwfmon1Uh3V-5 zC1s&m0qoFV>rca@fHmERDm|HKz@lSdx~-<4588yi#TuKoH||{yqZ>*$aynACuTLU0 zmpQw{JIR0fF=uT>*`vEVt~MN>CprC-_s*=?*Pgil*fC!pe9nM3;UUBscCbf~?sB1q z)2Jvux8nTy3$ndfa(a8#@WxVKFdRHLh7a2GcsqzpM^YXb8K9^7ks_uCsM+VVY4MG& zY1!@T+xP8$rRJ4a_U+r$kDC7C%X=Nd^u3!%c*)&+%y<1>#i!tmzxdh@&R#rrZ2ua< zzny!IjXmb%C}^gZT#%;_q5;*}SE_4u7@OYyVE#Kn=W0{w2^M<>=#Eo+O3OaGP` zAo{1DetPl8%l8|C|JHl2z3>Xh44iQRaos+ixw+I0P&_~qxOd!&)zOm(WF1Ntyw=htN1RLtUhh=8X>qIX!1PULTbD z;SPdch+!va$NWuKWX+cACBQq;&nGY`(B+rt;zaF00L@daxEDNM*wb-lB?U@MmqKkI z9f+3N?ZBNLhh;ntP^Z&xeAoQ_Y%F=3T~`{#L6=dg+T?hz$l#uUy<) zHFM?JnJa%#c!)^z=@`dxT`x97U3oWA>&EnQByuY4F_k!?ag~mlm+MZUYSNgrr@7A5 zkaDTgRY!f2=+6OYlrsArp_bu;)anKzNN2g!5(9A*>mpo zuJh-t`J-UFL2ga3qst1z5+kg?-q5q4iy~GNaK(dNJ>C%6*VTnop>=_BcYve0rim7s zi{E8+_YxziTfP^x^sb&a7S38m0%Pa0Wy=os^!NAR6PnIm&Bl$r;Tty|+IVQnq3K-H z-q4UK_Ag3A2wt0uIsjexT+oA^sG)apZ*O?`;=(OdhBnZnXdcD8lGBmUWp`-+{X16z z=tdYf8_bJA1yuYR}%f!h+6%vYFL zU0;cZh(KdJ^V+X|{U5*n$$$KZIQ`du_d^!pO`lOY4hLbPAxLlS{*I64Nkh#3iVG*?S=op09B*+|A>B)hhf2HQoGJ^qy@U z(*Ck7{B_y?^gA$y-DwGrdptH%B z)C?a(Isxe#yb7MxbwgLoleU)WJ-AVp72ES7S~tVKu&(^!sl4ebA~o%e2E6HmTq5zg zIRr4`dr3&kS%J;EG=76FXcStS=9f0tGbAD;KRG1C@VOWr5Fgti7O#bA2>PzT{6f>2 zh=^$()51cWq%uZmh~zsW=<3K-dXFk8TKRG@bHVhv-Dx>(rbDTM8L_?y)JwMSMocG+ zQJQ*bdLZzXpT0dV$?~BC>cJj4OA$1X3a9bUjjs*b_VSq<%LnRXj}iE?jV?w4a-?&( zU6Prushm^_I}MIV*9a>Q4s(X2^0|>kZJ+!Ii84d@Q2XhHd%@u?(ssbT1TqF?I6|%d z#bYA8UB1f7@GhZKC9aMTjN-KMRJZ!1gw4Csieq!a@c$ak5=E4db(d?~x--omNlkzI zLb7RQltNda;lpzq=})vN7fRp1DR&bg-3cM~-W@$u5s*OPRZdvPUd`junH5YL@4zI%?jm~$P&5JZWs)0tk8fa&F)2PSRa zc5KZW_WK$e_ci|b;>C*~xm_u0F2M9(|K#G|zxwK{jX$pOfBx7zCj8~KJ6BV^+)-Og zj0u1aVygEm^UgF7U3xl^{t1rI5HB1rq2=V7Qd7Q zou3_ALC%p9VG=o9M81jxi-{~JAi5kcPX4Bfy}gS|0CjH{N3E6;0$u7Em=uu}=p5s$ zUQrwxHrF>S$wPv8TwDxdy8d#wwua+QMogb;Y~*YY!5viBvXHT|r)&FOz8ngRFE&9g zr6s8SEcEaVNp+SM=MXlX;GG&AhE(tGQW2`ZlSZg|8$HQ}kt84C<(kWV=lXgi*)?9l zCRY(7G-A3q9a4u4$yh|tojx7s3%o85h8dNIq^1{2P1kjLk1pJ@1%u0$Erh&meG^D; zh13sDEu2o;I?;|p3Oi?>echtrQ5SzVlda%$71Q&;O$j$^#(bz39D zF}+ypatCvtfeS&qHgetRcahx^)4kg*DNG-nb8I5LUayZV24@R zL)RiA*9l!WdbqU>H>F2I=@>T*qg(K9ZZXDduAe?Vf91#tNCq+BgE-J7v z-TETrn+!Bp2S6QZriGC}{h5D#?OVV4)vvzw+TT6-uh0A|HKY@%3Y$?mtQQ6!P}7S> zPQ1GkL0y<`d0q%tt2{CPsw^a=#7|oJ@XVPnExBXxh!I4tPnD;sgWH;C@GB;AXV7?P{r`4$Ot{62PAjfdtzq5zrMXE?ic8MZ7U2^$J zEH5fG)p_OZqehLIuySn?^`ltR^#@smjE3^YWI-Gtj>E)YJ z)A>eLlOryT=>-9N$8#@WQ@JQ>Izwu@GHliYPwZJ+Roj- z6!ZV55%sT+&pQB&t`d7frIw5=r;DyxCv)LuTPR&gj7%63)-5vERm5|yOF}n@F8&p& z+YE1u=%DvCIbE{`%5BiL8J=}4RM)4H?(q3>$lNL&-P~wRwSOQG*V#JhV~9ETRhi}W zB<-_#Vq7yTu$-Yc!2LGZZ-jl_T>SA9qo#iz(^HE}=@yD@oTPNBbV@f6X?q~B001BW zNklN(pJN<1Y~ zmIrlHaA!;}!t@l=;5@c;O_=t=wU1t&6jGcP%O@(NPNz`>b!qC1b-FO5zQD|i)7Kmu z>mL?8DAnId6gpWiTk>-ieQouMg_P& zaU~UH?e%4|17bn~0%o_B5eAc1ld#4kZEgfyiaFhn#;AT+jf>-rn*Qy>!u0%na4{GH z-NfP5bed zDC~uF!NiidxLQx*4FhVyQ8{;VbGMfvr_1&7_GfSZ@_pRt*_%ozip6;ku!_hndga=6 zgPWwMBgiAm$J4A-v60#PcDJ{K>92t4>#wwaLe$G++hU3dU4hc~?~mWR-{qTIN>s}F z#-ex5E;&=`8^jYzBoZ*U*e@|R9(^~iqML{ls*69k^MMC`_`vC+E04X}c;(8c7tdUL z=hxQ-Fhc1<^q+is@zcgv_r*6Ru2`|>=&ffghJWq;gtm^j+7Ktt9ET6CBnS4SVjr)# zYB4$~&RABxQv>-6k*FPrdp(e%O?v&9@J!{qnCx_O6e9~`6TevBTy*t}Kwf1aGr1Vp zx98+$)2|5K9pEl$PsW$tPGEZ`ZwdPbP`cXWB?aQ-@udNlKwa+_`$k#7{Oq#KP=}v4 zm`=f{(_|z{N*77XNX4HL5ufz;Dvr;o#!O#L#Vh{|5#`Q=r3vw+X$h_{53k}w{k8cIi-NAg$93;P5^-kNaQ3x1 zhc=ScS9sS#Fn!tLLTzTql&K~*y=UGm^(R_rKwYisjp^l5R~^No3@E(|F}>^3%U4@3 zZ=H8pDz`@6!4p$yK&lg^sZ*bwN_)~mMw;50`j5>jsUfDtbWZwdS+=%7Ikq)h! z!4jZ+fVZtVKIbk?J#w`U!;Kr$PaThJ*m=~x*?nPAIdJ~Fh;9`3>&0~g>9(9MOn<(s zwX<{Hl*K*GoxB~??;h!++;wr`U4;|~NI)+{Oy5XPSiQ%*)#leUXpn?-*<6};Lfjm4 zIH)N4$lmalWps`TU)-{I;gngXRFp_`x{8LMApBB^i$+Elqs!+4UYd*O)ig5FX{TK0 zy3I)K2IF@|Uqs6$7<>{G8#Q_SGjoRVWrmaG>zLXx$LAHSUj6WGGOS3YA}U=s9-2YA z0#WIeg)>CRoDmSpX(L-jm zH1!-7qR*U3hfzrUj%NlB8!>U>#LCf?H&^y5>Sg?>2COPLT4T;(el(U5>yfBzv=ELCV6J}0Puwwid~a_Q8`yc0FO>dE{rn&S?dqRD z>h{}5MLm2P37z|FmXK~h9b{K{rDb}_>!CR;ji;jj($sX!e|v%W8}T~@11Y8# zt^w9Nntx?5-B@EZ*{K`MSGE1Od;JBUPTX5}wliHoeyQokn~p-yCQT$``(M@c>)*CN zulX@TRGm13=f;%MJT$O8E5L#2#ejr93jA|+71f+fTN9yuaD(Zoq5j3R zOyvM3puPZ?x|}Z(&n1*uYP!U9Bd71#6B84XGAK37=_SJV@@w;kjp?(loH}d+i0NMc zAAA2E73F=e{o^5QXh4w!MmcyugpGm%A_@Wy2SG|pB_5?pwnz~~SO;$pPsZG-mSKQyHHU3`L=bllU9(MPB z{&}9P?`PninS1UzGR(X_*L}UOcQF1JXs#frH%#Vadb{&sG<8-qA~6M$uAccPYxkk1 zlhl{$np|+Q7Nym5P5NYSib#2eSPZx!h}hHD=G*WCjOFjE>CmSYl-H;+rf&gMUXpVN zOvgQ9I9=}af@)9r4@zIYJiE*`d7jIFM{!Bh;qF`iIPkW>CQ@g3SdeZVvkv?f zq~o{IQ>NvQ`uc$A2YdH@j5q!Bj^3tsj*-ZC>{{AG+dE!7fB5j>^Ve9GmL9G-T$c9Q z;Y&%M6kR&Mmk7gs8;De|&feESZ_rvi=(3?7Jox!DU;ggLufF`!CzsxT2S$JEb`4#G z&JTw4&%WBi-hwb&gFWbEO5fv;Uwg}t{Jq~>cZsUVp_0_yHJg5+3=f&g)o0W>qH^4*5%$O~z{WyvQ4%YI-O4-*+?o#W z-CKZ#A2B_wiHcC1Ec^B?r)q&z7fdl_j>6xt?3$WvrU|@eVaA=FO-s^)wZ-gD2`ivU zDla&xBUVyp3$za85?cP{q~miORrCJ;ns!}U6rYAP(+n>Dj$xB6x z0rSSn`8#oP2-6$KPZ6ef8#O(CsiE|xlGKg$g*e6QN5?KBXH&)bFS`g%Hv#6C!SwsC zDw)x6I>whuiRg*|jA@MNqJk9va$_TXj?Cba8Q5M%+PW?Z)3LP}u>orf=gg0FEP|Iq z-3(#(SS6T#^(ve`HukT0)32Y2Y3sKx{tHWom@Z%!x|@aMbnArE^Wr!*z)pYDqh}sm zGQO`o;@V&cWbqY7Oa9wv5i zMNG^JoagZ?u(Y(q;(8J1$Etpm+a&M>KsW4d$Q*gvDCzL{_c#d8S%}V+hYqH%GJtNZ z=~}(G1giAl-*_b1$8#5p>H8}LPSX9wvY+q=r}vO zkw&EcUX>$}ZCzbZI&yj@cuwFsgwBwbo>@mix}#)`_+mQ>?-m>kQZAB2!`NxEANwOut%> z4sN*Iab0sq;&R79xNeZ$T7m1u@vt@q+CBXcon$l6LgmkYT zp&L=OoFuw~o{iQnFaF?Ih$<8gJi4c_^AtNx-Auvax%Gi-r-^1ZuEhlJXzlKW5aOs2Upgirq7!= zujCN1=@V&;S<)m%KfHZ=6Z-nZ5-Jn%orF>3=vR|Q1iHJcN7(kmH7PfSXmNBDclsA! z(eslaav;4anFjaSICjM8n9~cmDq=k5?G0Bdu6&A|{^5IH{`Qw2?dzrB({3o8kZ}Ai z%Kz3VFiXcm(*xs8H_b@*fvKYOk6FC&!q)Q#d&@3MP5;AZ*S5d-@mJ6P>MQ)?pMCYK zHP;TWxpwXRwa?!AB;uva&(5F!{9{P{pn8;Qaj;__g8aT-;uwGT((hh+>E$QiefQ6T zU6ks=`0Dv<9c3L&7;jpG22KT?+dS6(c>9~Ci1f$LJyN^jTx+;`gyNw0Aa2FYHMPbw zE~h$!D$>=D@UuDJRk4{=@)VTYP*D_u#N(i%TtnaK3g9jg_nRE5pl z+dT(_4tH?_=!p}e*;0cEV^I=gRk{uFTvRPOSI~=&!pTmW?8fcaP_fK4g2I^>x~g=Q z&Z6$Vk90TSmKGht;TY7xBd_>g*%s2xX0dFuJ5I2?=N=P;E zsME%1{1k)fEQw8oNw}`Ys~V z|8?x*Mbva;Zagq%TtCBAWkg>pepMNOv;&?V7qp>IT#wzuZRl zBITmP!w*8~M~6q-JYm4?I(|HJ5s;x{vG>e#(s4F_h;a6;oGm?XWL`1ZhPX1#q<(Y3YuQ` z+bNyIMa`WWv8JP@`^>3r->B96orz{vZTVJ7kgOa;A#eXEQB{G!WLK7DI_$>CC zwAkNg+&H3M7B>2T>3XuT`00Sra+Gih=}75P(ix+50m5@#Y&cz6i*ULz#&mXKdeIk# z2prIs^`7TDD$~nQK&aP9(l8xd4_sh&C`w07AG?s*GGkI`WB_IvAYGCWjY^4SR52+w z7%1IjRr1=M$edID&GV*{ihjKR7eD-`+q~%p(=mh|pM{lN3@(nIIC1-aS<{bNVT?vi z|68UPxzgpB0nVKX>3Cl7;L$k=84iQ`)QM34zkOWs|6%(7p^VPo-Y~irmN(tdy6Q;( z^0>>fdLi5^Jzc{>VBxQ|O6yI~i19O2s zs;rKqx~jRZwYknXed&&4ZJ~KZ{hi3^`do4x*z{}Tc1jnYTfcfy{yq`ixs~NjmrN#2 z-T6n)E2VoxDVz?aOXE&2T@Q1X66dC3(!TZi%{bB3RTL;U64dnLvp7jWy84a6?Z>AN zcpFR?qnm+vPT%;r3IzB8oav{~RXxw8;#Y?*ri1A$XnO>xSDiCyFAmpB4Uk@g??u)Z zfC!CGz2S?2FNx`9w>)T`XVVNKCEbO8Wi)Q`UdZU1jOzv4i;D6uT)1Wl>QK4VbW2bF z!5)d}U^;Cy8>Z*oF%>7V`XhyV%4eLs90##!ZUkcmlc9$kzPup0cJJQoYIjOV`5d`p zYP4IGUo}5WD~LdOFUIN&_yL!`o;7}MVQ#_6skKdqw{H34+k-=3`WNqh z^8U5MPnSXI$ptny9yCRy**NQQ>|~>bLu%;6e$}lMk>Z8_kWQqM(>o4Vx!PfKCLN>? zvbl$60S5uPlyn%C1)d41=|R-5CKuLj=&gX#5B73U)XUzm(*2Z>#{S{0_l=*NEEd%7 z-~axt-@o;%w-}$ij8OiPai3y9{rxk)|K0E3_rLq`|NPyLfBe$B z@51Rf$B*B&2p!}0Be`Zwomwx=clN-*Ra-~HmaVelE z&0^W@;TG=AJ7@EbM{tp_Q^qemhZy{du<$75NfK@@OgHI+*;rdNm>bIOlOfr8!=dOzVxpBNQJG9^|O;}F6LWm?Cw8-$GYvTDrTddO` zZGp03YH11^R-GNDj-Vzo-GFqsJMWk@Pe9oQuKT*X*a)I0>BXj2qrq{$`8CW8Q`Y1M z=Y@O65qs`V+zWmwZ}M`mr`y$jR1J=*Y>GJ7ekcx5I_0BawoEU;HbtO#)7izq+c=de zjQcznCJNEfX&Ly~Z0FXN3Dwv_C~~~^uj$%(+JsUm{59>7Fi>=jN{V)6ohYy zTQsTZ5W0kLfx1C;Se+qGmtoz6z>qy6*EB>aPN&9{4dT0xy}m@A7btx+cD{w_GdESX zBqe>4^vQEYBf|9gGk3<4Z33pxoiYWFd;Bq}>D@7S;3+SK)GbgKy^o@1A4RzwlbWu0 zMsS&v-AjfEYNR8nHFjO4bQC2W(~HStlq((PM?xRr#7L!AV`JA0JTa#)WYfvn>A3=iD1Vy67j@hA4;@t zj>Y)QU;dvuyt?gy#Sib;pIDACzq;rMXsw)<1xF&bJ#Yj{2hzD7%KFW#S|<#pH!3%M z0UfEzO$jOY7m&GnR{%Xo?grESXV>=_Ob6S?_ssV9n&9O_yom=hE9z)&=?pxCxxFv)$)xWwZW4g&>l$tJrcUa56rio)FRgsy# z$Zxt^__8In0eqiI02hl6VY-sj|C=K)FeG43W)&(;rOq(`=E3#>1 z!ko-i8&?s=#Cw5VS2U$foRhS6RVIl8~w;X9?q=_um+|Af3-4L-cGe zRKHWw1E6jVb6Pj%l+snnE=PJjq|T9sHLdtlHC^k?Q@n-hdI|okfbIl!V|h^{Qb^tT zo{vsh4PU0nDV|QW3raf4=@}{Lek(K5*Jps~=?&m^`ar`eqofZ^KR(dhFi-)7GX}Eg zbJRY0Iyo?f`#wcvmd`p68N(069J1h5u~xxiB>^XP$2jn65#K=K~1p zLUJkUkKaR`7-wHIYsh76-(zoRz?Y7N#e1r0h(nV}Fdd;B{`0GnmhNVw&@J1Y;10F5G%VNY&(>W%L`3!ZOY^TL{^zW2Q~*%@R+rZC+}F_vLBH?&-c(%0rz z`q>v>{EuO{`TCXOUXfz17GPspM}bLYd=XAJa(Xe8Uch6p`4;$PCoc;tNiN*bbojH3 z#2bS{gJAj}{_y@gKX^J#ig!~PJ{7#t+0|0udHks1c0irBn||j`ox1V?0gxXcr~mfz zeH~?fc3c$rS+L3IiHgiEKIhmP=Ek@UZUwx}mg@sb@BO&<;O8%_+`OeQWBBL4_`?ds z@E^Z~KSf>?V^lGx1l~V>_vM#fX1x09OE2-G@v>R6y{=(~lhDnz6}$M=SJ$W)h0h6< zp+^)Qky=|@H=GJe#`mAn*M5BO?_bhwzx16gJf+mCw6dzyQ>f#95~y9nJ@QE)-^+fW z(vu#ZHPwV{uA3Sa6qXZ=|JsIgd^tIlfOc7S7?valq)%K2r?abskVZG~o7@+uThlWr z9gN56!&6sYJQb#*bhV}}^DtUEv#Uc;dNy54nZXtC3i7%u?K zQr#=W>FnfDhf`cH+y)9g4Rr~Xp?9f=o8!|!dad}-;&hAA4XB$1=efj!bxw#Q0dxi@ z<d)%-SP7k2y+)5kQO}{F#22_SuZ0!3o*USohvb&TE`xlUg&N_ z9^=t7OXoIjn%Ri&20=Y$>C*W4!Rv%HwzYNc2G+Z;((wqtI87a zcsLz@x{6SN^pW|%d1cp7=McJUOk)==^_Zcq`0IU--_w7Ooao>ZE5LJ%7N>|)sJF#QK+Nf-3;qU!ZOzN{i`=BF~&g^p|3pgZ44_wNaE@uuLatdEK3ZA7YXSM!qA+UzSyiV3(4uSpo8Q7 zlN@Tg!SvMujpmDUb`RC3clYq!+jHlX9&9k=FCwc?na!m={@kKWFJL-qdZia?dJBP! zEokJNN@xKz>cr@mGD)U{IA9I|x)wu7>zuUI^nlZKyVz0e9aY?zUjF>$Fp9Y` zy;uq9`i@sjqttX2kxrdxFunJ`ucpK0No!%;$Pi#Wa2o8IR9BZ&H-~*L)DfJJqs!2E zAV-`Kn41$EPXoJElweLk>00H$^+}?1FD8*3Phtb8ozpX>CBWUlIo7fA^2G8JtGEj$ zeH)n#B+?}doK6av6p~5Bg?9YZm2a#ID4LTLft{+Hate@{!4wmtSJM5NYm@3oE#h1f znF<52&!0G_6S?YvgbOXT7RbqKZEh(3NecbZASg>6WZJX*CApE*;N0x-GwwVK&bdd?J)F)RaGUk;xS*XQlQgA;9+lK|Zc~pL$A%|+(e zS{OvXjn>WF#UgdX>^C9&KRY2gUCoV5VvO@2CVGwW{;82Z001BWNkl4>-ih2iXdd3#N;v6{Lm|nty zMPYit`ZS0(u9tk&bQ8MDKeUUREiJ>iUXVI=?82blZXlfnbz)FD#&n~mqp$C2Xt#Su zGr_RgXxDy6RJdpA@}NTLv^3-K^Yq1-P7NqQ)N~=ORUgvei3()AW9qs*7h@my}lG>_ivntIM)`Y%5~!T<83^BsrFlck$|W%U4^MvbiACqabI6-toe-t-gPabT z3&;(c3$XuWI4NDnVswgU554&GVNC~0YHQUBmfoeOmh(`1vCCv!$U46Ld9&?H&u!U2 zo~N(xA-C{WEJ?gN9_Y?Bn^&Wwqlo*tx_Q>5lG{lQX)^jXZg8yHp4fZ9bVixsbiL$i zEQLN3?3?YE?Mh;d$wIHGE^rH{o|nHsN#O>>^y1zbMx zsMy`zjYLK7{LQ74r)Ok9=`OOPFb!nahuxzpHC={unPH+`@Tn_BT}7itP1lW!)VVru zHheX_(UkZ|LJWzFU^r{@>1|Z1>(y8nqFaPA<;h3fYl9qo=Ks(xlAspxa#M~@C)9wvEl?j|M}ye6}G zRZS(prZ#3ZQrK^*>88IZcpkF?NS7Rm1<+opb6+maa`n!8y zS$wZ-GsCO)ukQ51PcB_b-&cImY4j}6)o+r%wNhV}^)UA>HC^{i7gDu1n$0($5@IMr zrP8aX$H%9~fA+$=tf7!E9 zaj9VJDc8Moh91ZA`p>?ZXdmbbh^lLyo1UAGN&c|K#+h zAH9dJM4G9pesrR~Bq400iT`T9lyt}MQC91#+hDp*{ppbZ{0=4o#~o_AOfZ(3&NaaF zS?f#N<<2oC_BqdU6IoKW$5E&Smv=&59 zl6D>mj|Z3qY%f_|z^)f8LiZM;S;`DAxLl-e#yBbJtZ@8A?);Y2WQTeTV2ae?^;-gu z`2sNrZ$xWb`eJo1)W?%P!T9B1hIPbtW_Q5X9-p;|S(=OWydCE(KG$9agX0c*z`CT~h<9yHO5=6d3z0?lieL+&MscEhu1rAWpPfsV0eC60!bKF3Cy86V& zNl!oJGCjR{AP?6IhxV}x4P1~LJpfh8nr;c|mO-7^Mz+HMv#)U9xz>v4IP5bZJxA6c zo)Jae-kK`24gHSNtGW05{JncI0hjKj)exYbN6cPon9S)sU`@2A=DDH&??~}xBCmaI zI7xEIuvnjx!ahs{4n9M(@V3aJjz=BSOMljHoEeRrXJFyUTNgFiH-{N}l)IlAN)}Q` z=?j&q;IGOrT`78yE$ur!Ji|3X&_@sscv5T_o+n>;>Wycg`Mj67m)_p<&wlTPrqZqW zgx1^hQ(z>lE|?u)C-|&(3u^k&qr&uk#l0nm9x{w>n2`=bB~4}9$z_CC#p%67al0v& zB`64SIr&gQPEd7I*vWI(hvEmjrKZ38#kH)mWHeu_D;9NEJDOyY^kSftxEN^d)Ti(L zzrXzOgAafE-fusu?VuVKu@$LY4VzGjL3Xa~(FCD8NLDl}T<2hpYr{%#yr8CkeDH;_ z&3(-m5=TGz#fm?~exj;Q$>cBp7`0pw{a+ud7X8&%9n1lE=o^@hY$z-~c#>LOBz3|a z(|oz8qvLQ&Uu)DB_@D9nN3IZ(lM`Km11j1j+9V1UFV7(4C6Sc>l_^2Izm`=*(VH|l zEV;n5j25nRYAtM)X&+TRRjw4LoNiD(xQX0!q;ySjWO(saL?)Z`HZ|d2Vbah<9j$pS zJj(ohxr{fMZyA42)i2bF`;ZR5I_DdHvBYtCf@#Y3(dU5fs zO0SaXMW{}Rvio#*CIC{`xf6vyx)R^QVYq*>G-8FLqo#!q4=Sp%>IGC;nP>MFtz~ahR<)> z(WR^#t2&=@f_2pOi(P{^Zs2>t^3s2GIIF#Xu(A_1-2!z)LUB3+gpg)vv~_FY;B?2) zO>Q^*e_W>Y?~2whKWJ>{0&wk)pfPK#<~>^JZ@u#RYheCxl<`h+s_B%BNU0ryepg(-O*!O775$ox1s)RVo@)?I=Z{=zS=A(xWGh_;|G-E3YEL z?YJk^*DST5~DKGUs z2=5CPkMpU&a{>MoZspc6Uz0rx7cx&n7N1nU%i&EA$lSHMNOIO<0|9_Kl)iYz3@_|2 zJ*?OFtg*i%w3G7!rq5n5PAz6zLfa-0ir<1So#IcSIPUaO2y8Sn=`@s%Txb@;^Z<4= zKp;j>M@<)hJLL4l;Y-G>KU|d15;7DxX`EMAU1lOm`i1@!e)?1TF05ab0LFzzWE!^T zs>*+nZ(Z2VcMht$8keq4+_>@46LTIe`i5b;)b!)WB&LJv@V6oLqXSbXsy8^_$+D=J zuV+j9{>l-@DBsJE_8T?bSzPAC4#%+-j;&5bIMli+-b=*s%nF=Ni!y0zsS;r7TG{u9u^Ve-uTGc$$aa5i<%(!rBX zteR7onN&2VZY};59yP-J91JbIX?gdCB&@AV%3KR^<4ch)UY8Jpkw^X%?iqa?&W;QK z|MAOc6;zL|9>JA)`snQ3L`1?IFg%bN3oJmmVj|cwFp`^Q1@jo)4L>4&=sYr%eqP)K zNROn>?gHw!<#wTn8$BHZ+D%MHP5+hv71&g3Ba`-WEAWL&taVb-%^8l(I+jMNzRSVt z(yRGjH|un)v=?i|&4@;Q7Vv3s+t9}bXSLG0NH}htvo0~)%1~#vyLHVwO}(kMgvqrq zWX^W1(oHy4@DMFH*ReH^aGt+;0o&-=>-jhqI{queVESLV%&Z2^O~{Kx^_!-b+zYF* zieT$reIO+xL!_RjtY&+|IeY7=Q|He0txRbjXvT#w(APY0s=2Q(rP-d}H;~)Der#pm zKm&{Q$nA07B)uqX8cat#Ke%C8#j@$G#`Cg_Mvd5xm*rJZZc6hbIbqC^aj8>N8Xj&> zt!}28G(W%jq)^=iz3i=lhuqzBD%K^_jTB7RL|h*U6N5`1d1UowyKLzMG{V|y50jRa zwZ3m9c0oQz*SGJ<>f>V+RL6PBE^dW08gDv~zK5@3C;6{Iv3rMePC z$MQpJI(`S4(_O=Y3p|1~LEyfp&T_GN0AXR_+55IU_0+S^p091%*U`K0g`YjOrC{&o ztt;{2*wgdC9~w!@Pyd3fmrvgM@$Y|(DgDjgYhY2wU(UfXeg(rjRyfu<&V6xn1Fj)T zHzZzLxIrct7+Xmxy&bh3P!d?d< zdbWC~?#1yE#gwU-Sar6GVl@D7rZhsnv=`1=Xh#w4FU8Nbb8Or-<+S8u{q5xWk-JS zIv4ue61FeTOKO!YFXjg}_x7GXPv=Z8Qr)(3y`a9+sg(N)rf!v;LF^53N0cYI-DQ>y zHJ!{R&r}j}JnY%sKh-B-_^l{Nh*$A-@=^-(H1R#w(_`^7aDybl%&%NTL)4g7B!rkRqmE92gjDi|?kh5mz%hIvU{dd7K8)L3V4UjOzmSuMf+i z&f1^;;L;Baq(A>2EbuM21i9NE-EstP3o zca5KcJpsw1Y$)I06TY1@u$d-;`ZZ*Nmz3*%n-Wn_>E@baH>H<&JG zOi#~Z|Hb35r;n?z*Wch4qa%j%&Bz8))2ASZccG!1s27Kt&V4=c#F52|7x(!0%DRR3PPo)8%|fCI+dmd zausu{r*a2^OY<>wvo)>YSez3M~iJ z0pq$+Wpc8dQ%8Kh&TzzAGPAA-qe@*Q4wArxwdmyh)}1J4-P!=iT8em45&C-oDmnHQ z%_;m^o2agPR7=KGdD7rg%5BW<- zFUrKk4#XpvM`FW|)N~Un=SJCe6cQpVkATau#-N?En)SR|x(4a9zK=C>{sYu_3=<6!aIR_Y4+t=DnALH=vj%*#n|R4 z>ZIem^Y}Js|CTYc{4GxBG9#w5yoKp#)2k0`B_(}LX&PC}^fYQtgAC|SL%PeUzLb^C zant)QoQoUi>uYZxL%(cJUwOek&^Ja_Ksh=ODo29k$SoX>Z!QXIn>mY?xnd>RaJ3Ca&-_Krg=M< z&i`#r&DO1}w^m_RlaOVMak=yC4G8G#`Ou_oTvmEkiqaVc>h1URJDlpj0n~B5AgE84 zoSx(BONX1hob2lAK1CSo;yi2^*WFxCo_yhr zXPCbLqUg2jWk3G(Aht0y3z)^)i!)B}9tEd-w(?2-aYcTz0C(@`eGRQ4T z7p5}`s{GiOBUTBFt0Ex_<#TS09v zVJ8{~*QBtYe{9#VI+_3C=kH(p>Z^|r*X-T$@%fIu9nXJto|d6sef6vNfAt0M%}@r6 zSz{gDS~}Lh`24S)ee<)!su=B1!RUq!t)v6t?;%@;cy=(Irb$g@hqsrNZa!H!@vxE8 zU;4*S^P);h2n-6I7tQo)UBx=(#Nq##8yX0JI;EqZz)@*~@bjyh*R}nwT=qHXjP+ge(cu{ER0J({E!R|5AvF})a@i^@gux!`?aF^_ZVPec%m z-J5Q&COKX60R(b!x|^>XmCIl|IFDhb6i?9R=AhJ8tUL6>r7o4UNA3VG4n-kkHX2O# zr0;D3-JX_vW;;G_g^TjKSi(3$u7=7*xj@utU0`YJPF8n-x>*Tgk6)^w7fdfdxr*tf zZNB{KT%G#TMGt<`Ir>RpPY<_Gn&T$=`7ByQf#einx>3_dR~Ss^MzE+ajgN)7yDyF| zp)$3xQQ~p;@EKwiD=TA%!Snd;U4w1A)w}d+w?MtWzyIRVT~~)NrxVC{r1D5iSHkHb z=)Q6&enxy_*NCYo9cmjLu4^0W?B_$s3F$^w|2kDmOMkq5@W_oDLqj*l2$<;~zW(^* z|1#LsdCx$5)_{C3mM@)8A@oA7ZfWcA`_~a2E!|;JHz$62bo8?H^y5Fp;xgX^>*$r8 z+q3BO>B^DO78zcc_008xp6AXUKYL0ee(j!~#!dd48l7K^Brq<5(HV>AEP5I@kRs8C zI|BnJg+Sl?%acN6dT|UVu8Y>?!lqYd;{A2_Q@e1E_%tq%KJ6G@bl@DuT)o&~Sy{Z` ziEVsKhlY;CPJ2>`ii-_+3)JsbNQ-6w3FAO%zS1zKJACPUjV}PjHCd`(;IEZZ$R(1? z(84a5DYN}adT|CaQbH;<9ZX*g{&+3u@d5a~My3VM@Ynw8DYw3K$yb}QfJaLR4B0&+ zZIQ8EBZ0WnlagTcA?)dOnU_XYM0yD|9X%Z~hszynvU7w+t0g$Q##vyb|O`kSRE*R^qU>&jC{OE+y(B*rfb`(sP#Lnj2=o}O9!)>0x@-9i8 z^Q8W)HMSSQ`Wy`MnMKpQW=xALnv;pR4h~~b2h)>OR*DUMEoaI_$#wJ)3#fZoGPqpy zYv&|oJ}mbMDz`=NtVUIb!1>jC8s$6*SXTikRu{bXVsI#(YZirs$osAx2GonfDdk1>KdHxUpLDi=C_7`b2Ag!Ta;$nyydvAS7C@B&Vop*m7ka;u!%$7yG<5^%vZ%`hHf94YMa+)#*wn36aI*nz=X&d$ zW3BVdlzJ|{C8gKv8ui?iwc5FrxkX*XdM>ekB%^ar|G?7RA!{`p_iml}YfFo~^`!Lk zSI6Il>D1v`r0#s9=cXW}%k;7}WlbsB&VYJKeuI7b^l)k6r~1bF24+p~8*4^QA8T*d z*|_$xvG%O~3w*ofHXj&k;DYtJxfZ7vLYPGQ(etQ+pmY}~9fjS(_GP!kbaP7X7ncDS zQeV`Y6i~OHGv=3k>FAV{;(s9?vNX9Od^z59lllah=kl*>qv!hObTB<{R&E~M71*Jc zJH4Tyeb1gO?1u8D>xkYJ2j~sXj%o*|BdTMDVXMa*?9o$m-F@dxy<=jYYqhE}r8lc; z5GhtX#z`Zn5~70P#;ED^H}b@l3<_6EP5=5l!5SSre5^c_NgKqFuOr-|~l^ zJ~Y`aD0#!?=H~Z?;vW>Izx)0*zgl(ODJ=8AX2NwG4sJtgI)hqM5jwve2Qw(4BC+~9 zQE_nkQEEP4JQQ5AeS1gPGTb-Xq~q|5hrc>cDJa9FF?MX}cySBi>W2^N^(iQzBJ(ib zZ0~t_^h|o;sTa;Sb!_h_Yob8*6o}6Ir8la$B&v6BHnHjCxg-abmD#HDGcuM>e34G1 zSls`y?-Xh}y|bjI=j2Ak(T!&v34_s7sYwp6sR_cCzHVaPyva0ZWxojCp)z0FA>2by zI$4FpGJ@h3gKG&(9}0ukqY7&GVsJ51dvPHac>tb^bA0!n%nnykD4gzB*2KE7GKw?l zQ|ryULKUaVh#|St!$#ZBAfg+gbVWHLr_&tCje?3e6)3>Yq_;>=ckxTvO8e0@`OAZn zN!oGs1@vvm?cO=j;q1Q2$48#OCLi3caB;1{pu)i>HC@%BSY6zy9-R*Od(+@HUAA?F zHcC_1D);EbDMe=^;FVfQ+KvgvFXQ-juN7Nw@`n|+_^IwSHvz_ z8c#@L%+8tEU>X}^mW&Q}wkg16$?(ymSBXu>4g;tkJ$kWwaFBGyf89l2(u+6Rl=UJe z2iSLl>`S}A_8GXCk2F>emG8Qs-BYK>1nGv)RZVK0G1zYD>t^}*@#Y)xVET>g*J(t0 z<>IdP_Ummi-R+OlkwJ>N5!7LF9n1ORIAuWHVSxEl__qZ0dqz(mecWJr|LBVOJ8|^$ zvg@a3q|*QN{?jdymCT6lZX6l$@EUaaJG)DC{3V=m8k12*erO51^ z`*E#kk1GQ?oyyr=yAJHn)P}hGCrzlV8y-G@*#+U;5c&F50YJ*Oi2K=BtAjY*$mthW zTD^`4$-(f#&&G}aT>jkmzjt`EO%7UT&tDDjy~41W3mh z;-GYFBi03iaS7-am1{qavAF0+m(1YDDC(BYMK*O#@jFRen~;PiZc<&!GwDDp6B)9& zI?_sC2gB>;AgQmSvUE-ovuNIk;4@{SMG0%+bEXY*5Y|ba$)vDU2{crWioKz4MECnK z!B8byUL<}F3D91FkO;(ej4Vj%nt-5n1K3G(iZHMvrzb?SFbfkZBUs zy;Mia?@dg%oGy1Es*BMrEJrGr16?d`*j&;%hz^h&JQvDx#(99yO+_hqEL7*09}P=d z7ff3p0_KxI+^iqN&yLH?0NdB+EawHwZSfS7d_k2^n295={Wje3jL>m9et8gmy$ zO*bpG*onEtoD=}s-3V<)EP<*y`&T+JLeKeD;B8c;7yxsXAY zi+vz3cc6JJh04+6eY@K82FCib+Nl_gJ8m$2te=3!S?yze?bG{qt&cmdhDV6z2Vq+u6|@|4b4Pn1H ztS{npV|&50&R6Vf_J(M})_vXiNSGK56@%#{cfh(Dn0Z-(X@v!~n7`eEE12JFpIw~I z4|f4cetTbd<9Xr+U(leK^m|)6UU+0pMyVxplFFfM57MkX%WV5Pq^2Le@ylO+z7G(5 z=%I&R-0qZi!}cDA(zn0Z!5aBsdhuJxr$Jj$MCRpBAF>?^4hsuD**8Y(!~2fC52k-{ ztqii|(F&?j(+T0Lwc2f3kGwz+&+o8@I+6az2cN$8<&BR%-lqs~ZEqdmaMX14^a3hX zrKY=zWEpbASOay~!t~yQ8HnlqpI*F*FZdTf|HaRh&C=_;93oF{U3P`p*M{2aCiW6c zEFsIV5DU--lF|zbH^AUL%GSbVR|*SHEo zwii+*i=%p@aJ|qll>HBOLIz(W8FXwz)I(p%F7xB(5>MuoaBVn!UQRRz^ktXmICu5U znp{<5!$m{^Y2M_?hip|4b0NQFO;u$D*%W}<=r-hmx8qiiBkBSCnhK~UjS3@gv$~1b zzNDmgUv+O3)j{ryB6sYN%(ollRuod{~MPqBdOGN3# zVUp8>i-{(R!yGjka8?R`xSM;;=B?uNjMN~)TzJ7z%Y7&Nsz5Y4D%!SrM}F0g#Lcc; zNfp(!1WxyZ&M}dzQ7BJUi7yT@Jylta>FHIT{JVJD5Z=N0oM2>o95$K}u&`Arx@mJp zdR#QDj)lgSnp$P7SnTH^eP%j_`vn}I22M5oE=x`qtBcM-bD<>g zD44wMU@l}K1>S%TDV}vwX7&~)*%;@l$HstjAZNnEYU%l_x^|LYYOK`7W z{uiPg0rjgF!St;DtMS5gC8Zl$r^gQGR6$zl)zx)l`1)`QCYa$1eOb+Y&CSf)vv`j) znoZdX8oL=*+Dq0@7nBaCU%ieuo$SYpOX9o7viir+D1_x^82Q|Sbce+LXL>r@f#?oN z{qmX9N3(S1rx)na3Z;`aPYPzw%(=5SZ3@U7nKU%6aWx;$c=Gs!ziFI=(y(F%ZnhvHz z_9{*DpADr$;a<#B{GHWf%0K3Nk}=zV!Ibe}`Zz`5(}y&$tE(+CpcAlZfh9W8GN~ZN z`XX;S11vFsZfWaUgIgU;M@Ki9jz9eZk&HWVmhWGs%or2);uDaWd4S91dJ&edPn0)( zS|n=v1x%hob#v_tV|>q0+JzdgXpi!LF2Db|pZ%=-xs89O8auyl|F1koO+ViMbE~`2 zKRML&*Z-9-V~j4!O*h{3bx|BE<($-Xi_zKgb-IwUpUFY#f8oh1>4gIZ7t4c=nyy%x zSqSyqI1v9QnC`H+|ApK6>#HD5q;wQ=!UvP&OE(!W_)?N0Lcw%pG#ZDCSY2N9K+EK! zr6rhy;|`CD(A-GqoX4y^BM=oEJ2{izjftydcrjM=6RR>Q`ApK?@GBB$T7VC|To|3i z0U;Z23bquabKK{}VUai&tVQq-NZ?W9bxFehUZnS-j4z-(4t50e zIT-ITxPa$#aIfh74p-w!Z+z63G}67=Qy^I~=Gh zrDl|gK&X&BQfx1N*MAT*9q^siU7DdtNoP8JvxHP$7vZ>+bW=fUxZMHl7Q=T^FddOZfSxz?KDJa(KV4n~x2e#PcGc@xqtR{v9C|Iabq!SF^;cfPG> zRh5>mS+nwy9czH%&70R`&}AH_T?$TgbaScac}7U5TC~6YO8;2ESriaktRMvN#99&Ya!%sajDMR$y##pKQG8*j?m&kx^Y{S)_EKI>2r~ zJ+*mnK3!jGXuN`+zPB_vIciyO6#uzc)%5R-pWOX01+V#WcifS8yzhF-fade_+SAg3 z^n2j+^;uxL9D^J#U{24<>USnI;(3vpPIkIW-qaj#-yEXTD}o6NM^Kj^*`rLoZ;+GG zm(}U>B<*Y{6-2jJrFyidA2}$VetWmP@a$91zWKf9pL*f>r=EZ6XV0GByXMg~Yf@_9 zFHp(d+g4-B21y3oSN$R~`1_qVe)&P~#9lCc`$HuUp`inZlpFR^K)M}y9Z)RkC9He7 zhlkzQZVyTZ)BVz(K7?%|tT-rt?D~ztw(dU|Oiz;nP0=EhPSVKo<<*dw;F=X2_>r2v zZ-eP@^yzyyzWnV+2LVZQnYEeJbPt(c%Fxc?bT!lA7R+^7=#(&>)vUE$E$8qRdY*Lz+LoSM9RLn^II8QwunO^E(t^$i;^hi@pn zQUPW!>pl3?vrj#L9&-z|t{${c4JT6ErrOKik}$M)a=g7y*{9nZs#4Ew&hW^g6Di}l z``3{7!zhlXrg&b?tlW7n^IYQaQw7gE^z_pY%_HM-U0#lR^fJ=beao84I`%PLFtZtM zomQ|OO*|oHLS_UvRr_T(<*3yv9Y=c!vnR8@wxiZ~UZQ~XGB^2t3J7y4XyT_Vy9qBk zIqT@oyi%CcC8MWNg6g5v8Kv&a^wL|*Uxj@KVRTS(bBCPO=?EC+P0!AiQj!=6ra75P z6IHBLddYlkF8qrGM|+p9Nt;aUe!hDY0gjkaC;|qq*BkvBEM zsj1#H9`Ht0uS%s8mkn1s_s2a!_1@H7r0m#yV8>=sUZ|2V>5i!Bpga`MKb%8Nr`9w$ z%)^f+ta{hqhUu0v4lP5>DBDI?7gGz=4KH)rj2^mVTBmfGMd>V+$4KX)V^ok{Jk}k* zbLr9;D1B+n()(g*z@x!j0IQ2`21=KhzHnhC>CQKBqB1 z7d7t0h(1$03pO>5pGn)%5uZw*1(awRA>FXLKMhqEG~#%H&y|F>|Dm*^yLfqKOGJn~nZ0 zs$Ss##Qoocy)(V|1~V3x*(0GXp|N24lN71OF2cG3ahv`{0n85+oBn8m*OV!D-9=!c z(aWW#`(tk5%Wd{-zUp){mKVk_dcFDrLfJ&Mpr+rJ^s+z?!{3YWH(mkS7maYDaW+J6 zk-DS7AoTBpHy!$?gtRiWr7ds-+lw+8ji8=TH%e-YenyiBPVYoXmnR)Vj25_FXikbV z9ZX*dXUo-M>FKM1?E|}30r5ovk<`+TYf}fLK59qJB83vtNi&|9v287oE^HU1_Zw2@ ziiD;o4#VhJ9yV_L*>}G4o#(!BNiP$p5}PhD{dEPsNGE^&SU&`fc^viZI517)(22Rn zjpya7OCotArgL5sKegl`%k}bc zFV|)opoDfVHPV@rVgB|p3Ne_j^mH_A#B1s{^|vBNJg`fYu7PAOO6ON+q@1%xlDeQ= zKLENG*j}WwPs07eCXlTX(91U_o{))#Q{r+-=?LU_StuJNlpUsKZh%e>HcLo1D_9Br zN)}%`2lbl^=TK%^RKyJs-w(9Q6r=YngsiX^HpY!oL`f+S%?x0z@L3t?su5*>0i~dz zJ3@NV+Js2%3D*qXbxKOP3(iP&w={8(9%&rhPaqTB#K?zGQ>uHSAaz;i!C@8R&&-I949Rn*EXy*>*}o&)&=$AZ~-|N!r>OE>x_mu;v&Q1x|AG7 zb6U6NxF_o}YZGnC1?K2a7kbVbdd@sCy#^Y8isxn(3xny-Gk@`zEjU<9=UY3E4vG0S zrJJ{AWM`k;yJqv|%_(aRtlm%i(Y^sJFVtfajRLJV^LqvH{M5j}l?#2K`dC&owWX-( zxy@ti=}b!L)j)I{b{BfKlVSlBxZ_t>Oe1xrGOj}gK!OWi8YTb(YHBKXI)F~EBNse2 zs&I3eZg;J!&fiP!3$~Y&)zyB4eFu5sdQk-m|C_j8Cg%F>cw|SZcOGK;*wyRnN67*;ubz~s96*`T%Tg6#7oy*&E@{_MR}Sw8#JmXfBu8KpH< zIo?${)cN^(5|Rg_gS`8Cf1oy`Kfm$IPd7k{B{*Jy^6lG8qELWyB&Op_XKe2!GK3cQ z9yYtp-s*}>U41z1knf>GZhK*?_UlXH2Tu#rzk1sB$}%1-kB{m|*C5)UlH@MBwgzoF z{b~-=iq4Bx&@GKDi$+H`hY-P&VN)pFR88XNOq{^HTd@_qH|Ie6!1n>H3MayEfT7)y|u!p}}T9m$CWe zyzPm&)5&$*T9QKvDQbE}RB>=l?!IO9#Hszd_9nw zvzahDcQa^D1Z&w5!K;j(?uO3JSWZM|Ev$Z$hFAqrQOmP~Kw_X6QYROP$*EhF`Wj`F zR#!8pQk)PiMfnGbR-~ef&D$k|H?zB|4bF~cACwyrE|^`wX-Vi9({rL(PGX7DR)HsrT9Voo~|~#XLY*39|xK{b7ITXj+l;| z9!zVeY>zVSfpL5q0MC%NklWC+gVIsdElMBX=-_hBa!Z+#m@K`Ivd4% z5yZ$r7HOK{RFc;?PRcsW@8yHM4!jM)ZJmRiyLWeY4oZ+G^8M=Y#o^(rqvrVPxXK%E z%bY%R<8@ZQpS`>q6q`fW$1z34;wrn0`xczs2c@>OXBC zZaFhLI(!dnA0MXml5_CD8Z~hdqQmGMv1hrF1*zpgZRMuQMP$i4{!lP_IgoyWeDKju zzEeX3p9pz4aaB@RWnh2=?#!VCCB1B7mPddokzcuc&V<--&^UYc zcs4hd7fL|KEhd6`90j8o(eJ#|DCmaN4Xm?J3F&PAaU{K{f^_x%6DH|}JoWl1{xc?d zReFuv4ip^`t;l!fE@Iu)opzFSe#X)Mbwmq!1}aj5B`1pjn(wM3$v!xH>4sn&zi z%kjLNmU&leTZYJZk#Qa9(E#W>_bY0^QA3JDa<%F}ao;3xVL~L9{gIYT+>_QwK|fCn zfZLu3Su3h%NN8V41u1<>31eiwg3|#&EC1(z{^$Fjd+r~<{|)n|!_wq2%JTBVe{%5m z>p!`N&Y{9|>|RLUdFn;v$YV4Wqz+8~QKAE>t^Gh>=X9kmQYNZu(cTVqMgr5P(g=_* zTreH>=d_7r{J0ltH;EBg*$oOf{uTbyBNS6O0dL0-84RbzLT5i`*Qg*ot6ZMa&{^z$BuR=D_Ip^OiUP zmm5pVoV8fLjisfoZY??Pz&mxONc-hUq`IuFyI*1M3Uetp$~YO4PMsGOm@#NfGGm0SVKl ziPb}hkdF*y<50XUY@-V{PDARuw0Tmy^#7z_)Ihsg+}hM6Haf2Ae0N8A(o!gubd?Mm##CpY%viIA?D5qHc0uOt1RRWk z=k0y{V|_X%=;c&g+_}E7Qv+ESxTwATLf^o^`U@!UP&xtXSXWRv!3z>mbkefHkk7ad z0MV{{Inu3zEHH3`_QSV|&kdzxQ=jf_x0z^0$?2)CwdY)ySJPuiNiY06)01dcu8oS< z6#J~axUB1=!@HWJXU&_OmbT|LLHcW;xZ!jl{qlvBtUZ1G{e4;M`?D0vXykTK{k8VV zF2t?-y0d?6T}2QjqzLM@lGBB>h^aIWs%^sbg2EdX#`K;SYbr^QMC(z!S+8R;noCed?-blJRKTU*ry?lO>TuE02fwLV~S`L6J7#ua7bH?*xsp=!Za7A!3^C{p}+b!`cHI$tuRVwS+?MrfZH zrbeU4<+MjKuc_V(W!Zai!62Q>n2tN$Om=)}fK}s%pT;kn_Md3z_+AQX_tjEz92S;c z?GZ-pXc&Y}QD->(>|K+x^}w1MWO5I0Qy=P!Ob(>mTy5^b-tIL!N?oFZ(=%$qgLz{7 z+we~yH655|{)&zs&6F2R2k<>iY@xNSs{p#zxcb~Ored$haj}|_2 z6+772!&Sg^Y%Jt4J~&hNd$)1d$P7Ps(}Nd>&n}wpv&qYcb1R0smvYCAF`ZP9cHcLA zHC~+FeYF!(A3cN3rhADz>KAt%y*e5nvvf!X86XK3)rKvqw@%nrH> zgdw$zUVhvHatEh#MZtsaZ~Z#) zxv_FZWsFH*wEj@D5Xzx+ViXgG0t0cG({^Oq_cxvh@bMq%l$u^QgvVUjB?*&EdmuyQ zCd+UWfsLyYlfH#(#7Ai^))?o1WWf<8RM_DA(%M@h&g$ulBdgvujzK_oo4Ncpe--r5k#%Zbx7T&Fyiy|2n z&^a;`C?^Z{bP$Fa%&K99z)LqLH(jlbh9ZaXt(#3F%++rmIfW;`p0t`np*YOUxIpV14Su zhi1((=JZ|@&kg}-ueubwzjwgh5NL=3RiJb$;^l<2bYf0K=|)61GP-p}OOZL$F5O%% z4>{2t5<4ZJ=+Nqtw00Gx2<&+}QGSA&ZCPBnaf9AP_|b*t{372w0?^lHLdnWq#Pg!8 z##j?fRbv+oh>+x)5C} zS(qc||F({~wix(sPH-$ioi)Y=qe~sb0&P*YK-=*PVykVDbs1|Nr*3X*wyeLoo||V2 zgWzUqwlh3lUvKV4EA&7dN;?<*4Lo-|FrJ#(mB6#qQ@=HCfw~m(uZ_Qk>CVlZZ}L34 zj@Ho6r#gFY#tRv1N^9~7k0VN*-@bFr&FhKNWZG+^J=XX|$grn~^R@ z?YKJ!8ld!Cak`RRBm#Q7O?D4YhEnjoEK6Pnq~R}@LI{3939a(GOqZN4rwdD2)M-zu z3uK z*TM*#9v;25Qq#Zq!;SYoMFf|*g`}5~?Kq-EiSngy=Lc}FU0z5WI#={&YO=gF)S?%-7Ddq%RAU{_Ynq+BV?#ZYsp^0%bE5fR-hL!`>+AM0fD`fanTKPXF+| zFaQ0cEgSan%uv&PU1cM;GXMY}07*naR6WeKn2nVAHgPR+x=7vV=|)Y5LV?<{+Jjq+ z>7{qeW@7Vo?}LLwKm6hDpCA1J-uf_<_H`Atn$hqI;R`7!Mv)GqezL47n|Q*qCNn1h z5KVI(a6C9F_xQYdB_%ID|Fh4Yf3c~6%1-tg*li66@4mj-1;yEWdy}!1<5maKy&G({ zg1s-S**ou{&ty)2_pLQK71-O^O~W%o5~oVDn2>b8_dj90|IUlw%{fHRTjD@%zK0KW zY>4*)R`cJmDvt4@jxW!m3ON~NiUG;rWSh&G3mXvWu}N!#9mBbx<`SnOq#h~ zR1OTJW_F>NVb)uh+3;j#`)V`xyAY4VRERwS6N{6R^`7C68|)UWiE6NijOH{2-CEj! z5YGIq%9YAbI6XI5-ILV7sB}#_osCjUQ)=QWP~k~$37+f{M=&~!PB6On>3DH{9~#ORo(9C!R6+^ zQ|5F?9nBw1_q1jEl~vus^t;9j(#>HZlrCv|{P@P9E>q{|+YP#!GI>}+WZr8UrHN@Fgsce1*PXf$V>z&`7E z%BY+gL?Axd(n8AlNG0`Hjb8p_%g=1Yr7l~`xXMj89wBq+&zVtvuAGOltx_NJ~J{C zH-6`_`uZcUymCZ-6bao6Fq^X=$YtCUC$O%sO7fa=H>I9a@F!IUJ~)CeJr>i;2s<^X z043C%aCD!fM;+eu7Jp=V6ml-v6d=dR=;)=y(<2Le@VfK$Cfc@aFAh1KFF+jT%1sB- zh3UqdK1F3*3&>jcpX8-SZ3gc_6_+sw&@jdqt>^TV*_&|3bhQj&dYRNEt=#D4oyPRS z494=H10XPZWaLl?q>gtTEgfzT2pHWDo%dh3+<)2NIh&JJ0cR??y)r zf%9AT|MFup8h(1rQq!Fx`Rf-SM*>F*x70I*oX@lT<`>R&M%V_of5lhP(N6 zwn{~zbShK1S=Evf7%>lX`oA$gHi3@-fTgDY{jaE+kA_0&_)uVGkyem_za^rqM4u`)XzoyzE%Ds= zKn%XJ8hQo14b58{-6UM`y*Y!NEV=!y)v^F*?ZZ53HtFw;hV&)|}Z9%$lopC#u z|DBj_UC~-P-{yIK7{RM+s{LHEtC7+(N=sJ~&PbH{7@5>@19luLq>r&U9;c$cQ>`1$ zk&6Prr=P+NgZ60#$51-tZE#zTmoUuepf|;EIY1R>O#4Jca|CpSr|Xwf_|oIpOhfeU z0_Q{UNa{i9`6n|nT%#%oWb_QiL@vjR#p$zr*KA!))XN=tS)`C)o}YC*clx~7WO>mr zpq>S&zeA^^tiH=*7qawej2VU=q|(~=y!QBX%;~cx*SND^Eo#}hlUUQibO)MYdV$nH zP{r&ON0anoX6{q-!Vy$GJ;Iu*&p-S8vv0o8(FCRUzVOud&hOnqcgeKUD&HFSd6Pjf zZx77N*kiKyZU4dl1Ezm+(*WQ z;D#lqzxT}NMDO6>0Em&&sgzyr3Zy&LbOc=oeCpYYJ0Z{7?2aw!LfX->cg@PNzUzOC ze;YyZ?AagweE0`1zSx9&rFddgGUjtLNTrd}o0qD#Rt<}!^dsWBdY(GBoalW_t<@ed#mz z;_NC{v~;X9s(gsb2`&k1+WyY_pU|82(pL{n4CA6@%hIaKviBW)vv) z6MCk5NJ(#vi?$IZPZf4bzMq>LruwSt^eQ$|NDYvWvCNzHzYsmby6#6A?vy)w+8mz- zcZs+ioDO(9Io+qNi&({5SWYK!W947Tp&^8sk!8V7Q998yPh{mW&q!d|LZ3B-w9jxp+)o_9=Hs({H(rVU@uK zGvAOpmKT3K@jeq`)xi?aI@#*z=x5Ii?mmNDerES+a2#=+L+9Ym7)j}lLtE#WCHKX| zgXu6c7MR_;JI|ax-O|3E4bv`^4&7KklY5N0FXk4eU)l($ zXO5t{Q>baWYWGa5OT3g&>C<(Z%*7p@fdMBdA6*N=OB7eJuFs~~v*mI3TKm0?_k-yV zeEG^Nmd{*_t^=lX|8di(FHI~D@VR@T$tMTXry-?3iQ(nR*pW$IvgIruS-fr96N{6` zHZk2z6E;cphUn+^R1RM{%7LDq0hJ3E_^US&R88km)6KhHUzNbPAiL40OM#3WC?Q=- zAfvgg9#!A}3ECn7_~LP-^zk}Ef9LBPhmM{OH>%|I#!BW|3H%W!jNo5_zXR~IB;f`k z_$Je2D+6fp;=~km6$>QSlMEMVj0z-!;c#VYC?Kice z^v%Qdk^ss;HNQwm2bf-mn65x|8j#8=ql2{cRpoQ;U;B^$_}u-^-T%yUsOgV=(@ZZD zb04R>k>qrTm@dz`)O2}KjX#CcG!GC^|LT%Kc?ZwGei>5?+n5clZ&D|E=vWqXDdQ?3 zbzr(UU6gKl)9F4sD+-PNe|=27DmSIQ>c;hQ`>p)V)3UsPtSH?{4@>h#%7&OF6+776 z_**Q?3u_#~E=EJwf~0d{I%XH;ywK7V_Qu?viIxtfL*|T3g`-2xb4YX{umxI%v$4Q~ z%ec&O*Vj8GLbo=AZ&~XcI&~9#@4DNZTzIGDceBzMHD5$>~!klgLQaOI{xRMlRa(fOjZxx)aka zQs*0T{k8RbC?~zpPi6jP)sgN=-;)l_Q$sr7jX8aC+T^M0^42Y@)x<+}qsDiPkj@ED zB{BkXM9i4IYF4E^N8usJWu0EVDE+Rf$14*HkYQX@%By&p6m^WO{R#{ zuZli7`#PLz`Ujt0xq>3RtkpzR$~RIh!-WzV50{WHQoB5iT16Va*JPAdtXr0`hCoWh z^rr2Hn@Urf$8N;O#Qx#kKfL?Z)4o{K4W>&>_sqtAfu0Ux>n9s;gPYsF;)&7IKP9XE z!%vaZ-y@T;w~+p()KXfUj!0~R(;b0~mYA;V<5y=OAUo9bk9#}LZ%rAydgJZ;*yoQs zeK+Rx!yU=^S0+xZpzb!gu$6Mx)S%W1yhA)UQY~9m*t*=+TN z6dxoY=lPB@8%_(@(r&Xg_%@)XXD8EMh(N>T%TEPS1xkITCvKmuTMy+N{=JdY-^>S= ztGtOU%d9!7e-GfaFJIt_#xZjGEus;^fx|7PXFzPZ|J%6WO;Ik#H_uz2-J&{vuQd@*i0D{7c+U0P!6YiX7k5XlPICPs~Q^t>G;#7 zrz=JuClR||v|oYuOK);ha*0Lhny0#AcUhTVWhZyhhBj`uRoU(CYFOkFP5CU;E z#dIZsh`fo_7~g0b@K``@(Yj8{u%gs+OH0?bNYRtM2Jb@3;| zyJOCFcke!P_UwcA#VlQ_92jgX$0!!iPgKfLI8<#RVyW^L{bhlxGr)2eCE?*>PW)K4naq4F%UY)7DL&C{%zM#Wb8ea)` z*E4047g2sQFgCZHK67U949%0;+IF95Yg^KWntsLt_1!}|<1IuVykW$2VR~EJ(xpT_ zBBx`FIg3vns-845GELblEdgyKrx9TvM?{~sC$TLs7U>+_JR$USX5Dak=aA|iA$5*O z{U)l!N1SeKFT}#f(@Hd6hxqt$DA|pa)`IAbpt{s_L3;dsq9TULRjl(zWhOL56npoA zuDVsj2|lR6sOh_s0+UF3*_cFoP~djgQ)N8WzscdwA;vRHh6 zL`9*HIwzk1(l>(Xc-I@J&}L{nYC5JDRglI$*)`HL-e*Ma5_XI~tPV*)>i!l??*eCL z10$C%C&KC2!&`jDE0g8UJB8IEYnJ9469DH7vi^wFbP4LK5;9jm8X#*7WPilp=ZFud zh3U*On6>dZFhX%k&xBiJ=!<%`Pi3PQdqgJ9sO+M|zzn+FX0mgm91n^rO3gq<51|TH zVmgo^?|DMP>7@Pi!Rx>9PQQX)MBI|oFYllR7up#L4eVl{e!wa&!Qz5=o^m0vQzeF> zb=nr7S4_GddLln^=w|}y-{$Ar-+u1fufDSFm4CMWOy8L0tXcguHWH^h==&$HUxv~( z%yR_SXMyP^;@r`L^mRvaBc>NNkut8MKYK+CjI)~0U=#JyQE>;E0HSyKTxF-BP!&x7 zw||Q=CiYo^^gq9uKfB#qD=@LBdK4WUUKUoPZA(Yz$5>sou*@$K)g6v>U|nUS#+J^p zL3MRBLWjo5f{sqMi^OyRx&d_+izXDA-1HN;Ymmn=o`c(RY!y!pPXrdhT2+awzTDj_zo3}o)V>6~0#U`F4J&{ArxztlC51kHc z$F)KN17P`a4wLP#p{h$b*G_kd=|)W#tV>LHX%(mo-VLv_M489@f;gC3jmshEWWFa! zFAmcS|L?OV&QnQVDW#)Cy_{&zwGxcMbb1#VJ>6QMV`c4WM@~mmXAdX3*7}rEa$qpA zH?-R)&zc%VEQZYKYHx(h41nRbhQicj$Qx5S6^5D~X#UQay3V~yL@Z1vhVj{_&TrXr ze#_@i{p_iXlY4nQ2TE-cLCx@xM7i8^dB^r2s14~SH-7ovdmnx<2CCEfo|z8yjgqA0 zf;qJPPzn1Rg0gFoZOIHzD=jTvzTqG(lW=!qiRswBw=ZSv`cO|)h5VX=eZ{9;?`}Tco{4T%#c%S8b;kgG<*(x!e)}uL8iBhuK#6*NL+2UkM zR~?p@D9Qum;;}*C>|xN$NrL=xsp%dCWz{umZ)8^bnm0)SEsI3&$lHKAa{z6~9+AS@ zeT6h6EiR@vRz-509ZDy}MeY^z)(9s89pjgh7+v^#kc3YDDd|AoX%vR+$f#MfH6uSb z&XWL`XcL$2&J}HRB$dCNdR2fLRh*`xL3A{7HDT^V`6I7ak^K@b{0>iL9#FalU7nnG zH@C8E&-@zpYq;65#ghu-P0)*Be~I>P)T)NtnJK{TF4pJmEQj62VS5p!!`{aCf+^h^ zQ$*%dXuD$u=gj32)9(^X?_AQ2*X4DipkE!0-8sKa61t_PACugTt`2SQKGwb4tUrcl zo$^u>o8G->E?79%e-n!HCVVj*Mu%BBzUMAFmyX|ghK8gXE7a5I?AfDd5LChR-ED36 zb%N=1CB2H><>E!)c{e1FvL4SQ08EF~sa%~ubG`y*HW4HuarAs1j zqrx>_VdQ5J(mRpW@7wwI;0@mWy#K-Vp)+UVjp?P4_Ne&N*{m&os7>HK4pyfvPHY=# z=53v$#EI|PUpF$phr&-r*GT0gtQjJ63({ANU^drf4qG}$@k?Tt#KtZWtTR|46`da- zy|I3&^m`0G_c=;P@upu&yp%K>ks0&`fbSgN6Ihp6-ZHK-uoFz*kue2RJ{%^tTl@q2T?^v9lg<}oN;h%Q1GuP}12DR`0Nt>9 zJztph)TL@}F}u>Krek`UV*(kq=V08CasG?hk)W?u1LO-Kdh*;w>En&LUW&TrC8{B{ z0(@pn7y>vt>nPr%esr{M7*dxv-EcbEUnqbc*@E{4TZ|-kIQ^4EnbT3z!Spe8B3(`V z`PR$C$qxk-DHCWy&s{B-Rv%cIg1==YDU7Rarj8ba++bi4(*ys@LQ{ zKK$)_zyIxT-}~yT_kR182exhdrm5+(W?lZ_5C6%brmKkb^<)2f6Vm}{Wc7(mO$|?f z_LJMY8%a%@vM}s52FCCV2Tb*59>+ z(lL7j&AdDAC&3&{Mn48XWkNTCI_Ko|(0N*ls&Z7mbSI`8b2^9)s!t+MMH%P?NoQ2bi!Q9214Ls< z!L;%)u+G+MUc?(UfoOBpl@_UoDM2loY*09X@{JY_*#rNq#?T_mJ7J1U4rDdge1t10 zP*Guwl&%8T+DkqcOgd)?^l2I^vjb6m|Q z_bqG1RqhfEV#g`_x?){%MHq#qn^&&PXg-&kN+8Q#x`tNoEhU}BCdiCQ;~e~WOBt# zOy@s7Z&pqkT^&oOvkNS*Z@4cmH&<%ER8oE}oOsFVbx?^yU`imfYL)(|3-_oBm72mp9&f?^8qS8%U@mVVtf!?uSYa zm8f5RPTkC)dkY-?gQcrEMr|4GQw` z^!2m(`t3#P@dOoG?oHpZ)Cl!-p}jllm^V1_pKe za#{od{;27-%a?mJHDxb9@TGg@k_J02BU;p;k#8B>gg35<3^2tdh0BX+m0F!~V8_aoeD7%WA~J}MJkBu`?puXP-4)|cx*xob>b|2i zE<7UxsxIAJ9jEG1<)-t?-WhTh-FeR<>t&aB{e7wI^?ZRF5E=of1(`X0>(~ z7dvf)GaAy@q*UbuyOq#O)tmolF60RjpYAC!UHi2J^ho`anH+oD%__&Ifl<>fJ)M)c z7#$jytj-ZbOZ{3y9B=(D7HOm`<5 zcsEXzGpOlwRl0~d9p?**I`aYOTVRh~A78n2{!;A}kO5?TPmi&dKXwGj6`?>BE7~D4KfW}Z;Qo~6SJag z1=2b<$r_DHsqM(;6Nvg=5zjwzZ2XcXv28I({BXK*Xt90KVj7%@a>r(GHv0#DEwDOIa#Hve87u8R}^b#0L0qK*mPp+Wf(x#B4 zOP4MM%vkI-;o;RdauJg+xAe@`G;Io|mlc;T??3w4(ZtJ%r@chgQx-bZbYZ%_MyJf~ zsTY5vrdvrb@{Ev5v-;jCi0OAOKuX6gU$0HIncOao7N%o*VdkLQv^X8x45h$bm|j?* zk|%Z6p{Uc=Xf%Lyc!C#Ycu|@UE@be$B~%`D`O-Pv60qvB2wlHqaDwSHI9h#qb>b*& z-$~CTCANRln@IowAOJ~3K~&=+N?eU_eqiN=F@os3KsUwc2+?phjCLv*yOXF(D)b)y z{`c>F>|QYavBzG$_tkB$eB&_vj^js-n*Iw_keYFb zT+SAtSO|`OZMZvgZBZzgj!hiACUJ%iq$lbS**TuWmase0JDrylr2=U47^Rn!ue%Eg<<{m9lpX+mbGt0LrqhPdEj_(n=Wic8g`307GqlhX z)pNexl717_|87jz4Ozp9>9ZQr)6<(v>2TN}=Sxj#ezjY0aBap5TS&^-ce1cJIV{}U zov7+)mj=5_T+X^+H;=R$`h%vN%RlEDlntfRCWhaWd;Pc#GwZuHR#CxBEut&RS=) z(S05#MQdsh?ge2w!#CU|IyaY30*veW95S4)j|~?kXnVK@74{ya#!`uY4213EplU40 z4KCjH$#!3<>Ao`O6L`0*cl%G@p@#Gm94L$%64l@P;0kiOvgCW0MIr7Uns=zI#ug5AXlrA&lFF8(Qgcgyw9^MokCP zJpobAY@}AoNQ27eJyfwwMWnxc@55idN7xJQbj;~h9`>M9;_w1nlMPZflzuZey#Sik z8Ubf-?ZJ-^TJH2MV=w&Ci0L;XV+RL!4`16(wPtb0;lm1XDJTfaUhWEU`sU>2@|bQmYf`bLS7g*kI3*wJAEst?aY6ek^={_vIgp*57>Q&1YZOTUOmf z6=?5Aj1NEh{NTaQ-!Qs5aymApi4M7;2b3JB4} z!jBtAdOt4(HMe?Qh*I&R%G&I9KyQcA%c`<{gF#_WPmdtC<=KRIN{lbu$BcvL(OZZ= zec7_0{LMSmX~?EJP=s;EKueD!^jt1{5^tCp)>L_Wr>44Ac$aRj39nhbIzO5zkb!yL zPj;@#OG`+*#CwnBsOihYg2Tf+swoV`s1@X@`cd!jI9mS3*;DdYu1-nkJ7Ke*^ke(*CJSP6Wvppu3wvup#k{|``| z3njFl-Za-AOs8a3V*30|D~MpcczXU^v~<+;xiQ_tOBM;a!Sst4@9Q3pmrfot+6MSy z3X3_7n!bC<;BH!=a*IpOQV80O(vCzP3tP9v(_m@7oHVl2Gar!U1dnjK1CD6MJd@JHYS$%a;Qx$8&EyK&PSHXzEzgak2pF{bVo+Iu3=0s(7yR{W|CoHI$zQYXY+FUS9a0esB1;m) z!^^au86kyrT14ihRhJ;MI#MvX&(46P?-wQ9`~84>AA9u`g!JFt%MqTJZ6};xuiud4 zS>!SPlhkzMWHD;`JxWZpz8z^t1gC@PvZnv9qYjd{j$VH!*KG8cO)p|`h?}oiFx^;Y ztbBBtUbuiSc5{)z^p7zovW8bw-_3vj3mbu91b;Y`j+S1I04*k$zr}F6j?8(3>qbWx zri;oa+{WshRC^=A?m2< za<_0TsGZjcvkUVYm5`#(GdfIZG#uJF#5QD$}}gX1_V9t%rXz5ZxSo>I+!}WZL0vk#fE*XPm|aVkfn~(I zh}$hdHdETm%1yU0oqto*bYGcXCX?_oYyJL}lldH&*WSJ- z>z?-Z-`o__X*)_asoEQ@Cy|j<#ywdnQq!pxB2B%)UgeULH`UuU4oXK(PhB2_#aF|7 za$FQQn46a;NY_V*`DEa8;|_u~$VyNOZpRb|;aK z(cARhcW}LY^2~pH`soKB-uUGo$&7gKqkUK4{EvwXTo&wB<~DI&Sy~C1-X$erhurYL zeuJ zmxC{SdSdYHKfZF~Mo8@7?jMfse+cK(x~8(Hn>uI;1kfWPqf-axM3ofhgw-}R705@ zc&foW?NI5~jP$fi!toz}`}xD$y{AXzUczKN zl02Vg>Pibx#vN)p9v5rZf)sYDF_liP{6oD^hSZshP?AbCIj>%}t8y6i!qF-V%L}0| z>w=fZc?;8b?AV;nz8U=HBp{g)og3|4mF~fg8}c`SXD}TQUuVnkOkKGqFLlReKi6F2 zbs>q-X7{Cr)YpA7)e=k?x^x$78xGiibJgxN_Uy=_%wjfZ}X;$)17<{qg!Xh z^-1Hz_dLK&hk|nstNm04lEleNWZPawLkeZI2 z{1-s7FkMcNO_dZ>&W|4+J~JP7R`3g$eiakTOziGgmB-k9afLs=m_?&!W0o%Ij;SQ3 zu^ZQW{F(dE>ACr{koq8Z)(ubNI7f0ngV-%bm#H4>OQqK)Eb64U!^%GR;Q?7PWr$i~ zjjqG?F^yea@k4KO(2y@C26;Ya5#qK|W^~p#%|U&LJT{j5VLs3mLr*0&$<*XPH$)gD zPiesd|Hg5#JeDPA&$4KvS1RsmCA({IV_45A6Xk$I2S(Q`&M%No4Ob>msC3Morj0s7PV)}q>FGpZQ9}m|1 zZ}ORT>GI_R?_m5skTil04wA#_8f38J9OW!A>e9)bNiU`XQ{MCB)bs#E@)k&3m@d(r=0<4gj1aomkk=^N zizTK@P0wU60QxzUeiTmMwg0FfofP_jt`^jEN(a1VObAsDM^fF1{g19HFA9BP+5=Ba z+ZIV_AZP{`4Fx7V#v$O|kjL&7rEh!XUQ91=`nGM`9{8qt)9-lv7?J5e|EFL4(9+VW zAborm(JKyhn{Fm|pr%{a^#9@9#4@KJ;0si&ZNOTPefuylt`&UMTA2QCCB|l|uU zotuQ!1kF0Ld?PleRX{nnMB!+ruv|Bd+hrBF3?>JV-ePRvCXf+mr<^k>b5$l$iXpPD z0PvXG*-j9hpdO?NG&L#*krV1ptU@+dz9PE1QWQ-cXh3FNgyi%91bPBpxH<3|Ocyr? zJWQie?H|w@5M4`zZv*v2%8(0_fbX4(X^K#>$#6+zAX$z)#yLpnCSZ}$(P``@!0^Jh zrrMTDRNU#N52^S(kb6Q&=LRClhLKqvn3riC@^}0REEYFqq>_PwblChRri$HJ>2SFS zWG$(kQ$|jAVy}q(F4$NbTA0qKfN`T+TZp0!Pdm?Y4wmNAL_6yERB>ExK09=YDGAjU zx&ogqDqq(SiyJ^^jZSIk`uYI6H5{j*^!l4Ct(!7u?~-9&WbT+^aHMnQS*tyfp7UQA z2Y&O9Un+J zknWuqZEsFbZ)hNfu_0xD%Jewc9*x=4-Pe{jx#7S{(qG!!(+6;+%hqzdk8t$?)O3M2 zVmfqgEG`0dod(o7q4H6!R(d*HY85??;^?AC+sX>QKcoTm?bwj;$C zLv&ul*ntNAq33zq(zBXr{4D|fHyrNyfdXHwp|*nS`|ru3H|f>`tMMdeu?NBC&TYE5 zc~e8WZW&dN$da^h&vA)Dxt}$QTb5X$j{`mssDiwM52fJh>gCCWh4i@Gpr2*SifP_N zm((Z2HM+%1)G6tU9_(){E~~EETT{Di*@i2h3)BAt?+X?Xyi2Fpg+RS0%DdvfeQA_q zj2vW`S5u0JE#Ivml>$(5zzdm&oR^yZ@y8weKJ9z&Moj#T8{dy?izNx;=snYEnOfpo z25e_HQNxOY?^orDejco}a5v&q*#8+tDmM_jPE=eRCg%tPvq|Y^pFRKlVIp!ogY0%q z57425f^gXsmh9Wx8`f0d+S*#kbN4uPs^Z+a(x*y)^S;6KcYl9)`#d^m{q*>}?Vr8% z(kB$tYJ7s><=JPSdFGin-+c3VVj@c>9z;z4d>^xn?fiufe)R90LE={9CElNY;e^%G zg@dN2#Zh6^%4D=MUbIsJ(~Boho=1bCZhj=FGc<)^&}qvwA=Qou?Colo#BeLXQA2j8 zjOnz(qU9>nD>%J3thn$bb}h<04rEmEzQzQGEgf0i7MGVhxhfsK+=%wFr>9rZ2+7?o zEoJNK(zLA^9-ailK#bXplfn?a8Rn>au23zWc{cPm2!~j z`T2J5xay3(8Cy$pv;%|ciV`&Ss_H7XB90#`nr!UpxL@$UP(_NmzD&iW4C~Y2rkXB~ zI)unV2a6Y3T4$|Qe2VcosLw5k3Ewa!o^yA`lg5ZpZYk$isUV%%sH=nOrc#tM}M(MoUV$}MOW!=G;`-t zlis-dzR}^BC&%^7jgb>3z7u%vzIcpWMm#BPXO!G>R?ZhD1;@H^rhw0bSXtWQrKdA` z5bUX`#P+VxmrDA8!s|UFIEFe=kT1-ME z&mPI2EFCW1*(eEJuO9Q0ojVuZY;V-l(^bAIsRt{h5xt>Ssp)l2Oy89-qmJs%RRPA| z-QzU^r;kj)oQ~UsK*q$R2Z&#M<$)t&bm;u%0MkR|P0tL}3}C$QpF&XnEXHDAIb&qT z2w%_K);ME&p?Fdb8v+^SL}~Q#8F?^q$2*tzzk`3|^rS}Gn(7WsqoxJ^3#ee7O-5sn zYDlRI9fz8ZmX0KEdDH9psszv%`|}`t^o?q$p4~JAug}&OF~YnxV0O-8h3BS6s15C! z1g5JAyX-6prxVm?lmqgh8ACKGCFg}IQk9URtMd~udWqhl)`5uz{fQEfvKQh~W&j9( zdI&Y$Yubcq<|c^dC|7HmC!Uzb4_1TDy0vKOkE!1aKg~(c_eLnJ;9jL#<=Wn*OMR(%D9*ZhF%#)63WJnr~R^qetJh6DR%~ z-t-Q`=VUz^g$$h@@!T{weg0!Ua3!ZJU&d%>PKNp0$0R5M)5e%mp2?(5cy3API%yHR z&RYkWTtw*P#=yJIzD;-}t4Tmx@eWPF((N0vWA!go_ zG%I47K!c*tNz({$DZ;?AmItGxL?~HJLRHR5`XZJS0?*OG6A~US*OfTM`;Xetq=ys8 zZo#w?L14P}2jNXosv?>=^Mj;>wR0eS-7#`Fs2vc3tp#yheMqI2hq5Vxz4{svya=sp zo-l`LLj-zy01cAF_5AOE;W*I=gy-hTO$W)v<8rzH>D(}ll-NLy7qPmj!M%y;GM_um z*qpL7bYPsOM@C538sWJGw!&GHiDE$A5V-^19Xza6{90czI$|ISIT+oE;&mMyS2b5;VQ$;HXXmP~A1`Eu5!%hMTLH+N>bW!?EOwXgA==z3+^~4qqG-RQXgV^@;>2a<0Qx(fj#hoH{F^^tG zedCwU7Q2DxL_LHfuaXE20(Yf-f)BKEka!%OwfnbWu*TtnuEiK&Fi-t~fRX812dtvdq zikgh(@bLWnxFFY{>G+A=-46k;WNX+r6h3X#^c(M8xw7uc^edktasTnX>z^7fCb%eeoBf5vX zdV=X?t>LY$;dniS>GHg2^o?D=5l;!-mkDhTf<71fUn2nhkehE=6QL;u^b_?!4Gxb( zTaL~Vtm{a}anZbx2+lm8T2C6h5~Jehx0f2yugH1CSkekR5-I}<2g#gHY@xZw_dyF9mC`AzV%hfL-Q)Aayb0xTlif*`GlUV@4oxirSqx{c;>m^z4hjs z=ffr<{=f0tkKXwFjgJp*r^(Uh7PD`tEhwu>^TqY!$s~fA1Ct@rzX}SX5Ylz7Agzq& zVZ1Q{ZC77oLWj?ddmj)-K}XD1L_OuAM9}+X7nEoQg4I3P%G#G>25-G9n9gfPybP73 z)!EBDH$Sp@O+Kb^2GyI=(+Ok=wpFEJJn^-YzhVQ^{S?c{JQph&sGb&Gv-Q#ZDqjL$ z+_}^{&Ykw5ap1ITjw`OK>}pp!Cj|#(L7K4>mawZ zbTh1vGI?DX(x~SyT>^UJNk6NOMiBVu*`ZYYwU-*e_A5B7r)sLs><&C${jmwnZ~ln!2fR%BD)v%F&3ix`@}OkSilO zeeO*40UNVILrK?jWw)Tz!Id7y)V|>6z8lL&n$N~&b87h^-?0BGnQ61^0c@!Gj{HrkK@LH zIpZnTT$MC?A($>#35%WtVfuuT7OCm0rKXF2B{kjc?}e5QTPuxxw*Mqy`XnnQ{U)C~ zPxSbNo=8Od3+#c7X@5%MBaR-@-Q|24Vb8ygDtktHe8!Ee-LX1RYP!L6Z9cAYaVToK z=y&!0mPzy|g3SGW#*OpQV9Bi!2v5Q>YI={)q+z-nDbSGIbiC=aL36z6KB(!7$JN(6 zj4xpNoo1H+&ylZEI9)q&q^(O$=T^H6c(urzo-_&`;Z3jOAlD0y7mcC7X8heAyW zX$z2^5HOl3J35D>`!63&9KNKI+~LGwVR}MmC_W{xX)`8CZVZVi`hHT;y%7&Q@x-<# zo_HW4;jw`4*L`0?`p_#OuRQhu`y^hy_uf|@dsT$akMX=b@Xuev(Z3Cn|L0#itAF>; z|LLEsJVt}zuOFSY4w6>#C@BlG@SUQko90IEh|R5S%<=*)d9^Rv!Q+4WT&+MyiRr@f z3NW2Eq%y&X-wAh{IFI#QXiV=P_Zl@_1*?2N|LG0=jdN?M<;3tJ|9B>5ZswV)9z{&Y z?V%$n>kJ34%jjaF7iY|v2A|9L!iACaGEz+fhII1LPeAFJ<)UqzExhN{O>`|4stQU^ zC?Z)ACEEnHP)LeX9T_|zbkd|yHpRG7Cku>1UC_uMCLEpm(E!j{OdcTX3go`FTm}}- zVO=q}O&Fg)#G8AhQ^NlTqG_HUJ)@5 zV_ipN=YA<3Rqjhj$Ru77=v$Sd1XxDW0|{)mJTA(8F_$W8T~-+B>3IGfuezjT!>53% zfpqv3FgK7Yec57ob0KHVB|2kWq~)zuB6No1$U5U#8gho8Zy(ynW_IX08NOb)Z5%No zZL^kzMm_Kc17_w{p0d)64o2w>*mOS zxg#fCUiDVvd!hLvKa`Wk4R}+q8lH;K+IlkM70}|{WFE$QbU@uCc`f{Z(Wp2P&C($ zTZVFl4CE3d~ES0H{18s86jR6`ayf#k2_23kB&LsBx{PZm*_UYC3HmU7&P# zy5IPvrrOVKNPb#s`X$;MU8%^MRk7~MmFr^XPp=gAb{yP5*hn&MHFI;Zr02|==$1`N zNLVnCPWL0C!D)MRsELN2#GF5JVC?!I2WfFcC(_q~@vzjg`j9Yl>be}Iy}-K#a4&f! zwHQh4*yib1`sqj9*_XJ}_bpp?h20?o-fk2MsKccgjpjMQM2L91pv7X5w)uJzlHVHc z?XjG$_jvCqA^o^_!?{n#Xm2z$^!?6+wzEI{#j(qK4iQZ=d0uc%30;zCs_C>hK`HCnH(ME5*HkeXDAN~c2Ia2k0@IXZ?yjG?8E1&A?@fWE1;Vu zYC7;My}Gb~mzB8p;_U1oa@R>^vB~(7TC?Ut)-?;$-~H;vhbC9#d9K;`)=Mv=rGLRI z@rO^|zqY-pqvPOHZ$9_jTfhI=LH%h=XQN+#^l``M|4w%LZ&A}#KdZ`6*+#O%Ed87p zxLAf4SX*70WE}G45d!JUmj}6dy8-G_(6N3~acd1XKk{A*c+9l7@+))W%4X!a1MOid zA1z2G$#c2VUqxcLV8Ut+-Am!(7hw zd513S@O97FnvWSKy|juAZEm@|n$b|Yn|DsQD`g{4b@;O2AkS3Q3lkMtLme^uo(AIb z@>j34E2qhC-NYQ8Sx!_=iQ6Gf#Hy-kZJUaYj{gOhjvZEaC3#&@FUa_0HwIgu26+b3 z#fjj$S>7cv+&RoAqQmH-U4BR$7NBd}xl3cubW2Nry?gNISLIAc#wMv;+B{|DN$^%QO~BiX53>FnveD1ah5ecVr4UXM6F?d@#L0={+NX z7N$GF{PtrEDF)LM%LCO5bOyHX(5|jYlO|O9Z$eX_?cdl#nLrQ0=_8ds6XuNVkaK(g z>I8pu^97CYIBGhM7Y_R`b)nt+Yo`J?L=Pu&r`5I)WG76$-Xy(DlA7)?y*x@6(mVA~ z;Q9JH$1O%m*B34@4yPMT*Ox7bZU|kt&M9h0eSEsW@4zmK;F3l&>n@FE(tk9wZd4YS zAv`Z4^%iif3&Trj7hnOsGfpQYU1Eaa7^vvO95NyG%p_#@Bx*>#7EgErD|*BOArX&7 zz7p|R2$&9~KM)f6Si<+ee{KgU#cLz4bxwL2cp)&=;mLCYl-N5_UMRXspxalD{_6PK>ULWAk1gjDD$N;kPKB6Usx<&=t= zke5k{P)Amu2Ki!JNqkgwqwHEiPNzbFcOfU@ztD8og;isq;UKy#5Za)Zg*|n{h0ymw+Vr=)ufcX z7;XV*M-Eq1`-wW`C~|W=BJL@mE+PVvT{1b+If8gVf|`wr$k_}iXVSpdx;uWks^vNl z#rt9z(76h*F5O&cKFuIG$gT}pY9~^poG+YrdeZ?@k+_q_4VWADrli!ef*2@=iiPZ2 z=tsX`Ex!hG&EgiGJB=^qdq&%62&9G2jv*fBD+r}sTDw`VV}@fRb4nLj7a9SbThhf+ z(CfLKdfljXd%D`K8@JY3_iHW98a8m8(6TM+dqcOyMI?-e+niRHe);1?t;p9jamFYb^ws? zAJd_|y`3dD!Z9}orlY_cMn_GTjxK+?k<*p>!X@&%=*S$ngkAV?acF<%Qe87L_EkiM zS481Ww}w6%2KKBxuv+%;`e*#~*(@OPDU#3pM>0 z`uDW2zp!$1Y0$c}I2^>uetBrgZg_Z|Ek z#|xep7@d;A!h(z!wyu73$I2ZU_MnOi1k=fg={0_7bbgeYeoZB$C+I?2apic0b}zgK zI@9f__{EOisA83oMv)WCnD@}3+H5@OQN<<3GYzL7+D_IB+38JgO=azUgM;x80ykHX7@u!23$mw{yDZxxVCsWRqD<6FH_qZlcJlUhX{Abd!0sI$R!6we}|glP`Sd zCGZ^Qk6C_pt%Ioy`yI}|`PQ3n{qy&>pktHtqTuvTKmJ^h{?QxEg>VQJ7$>;OJPFxk zlt@tL4gvMBrW!xeDK(Y{6*5gAv(jW#a%2XNQglwZ3!Ls*pi+P`Y6x^Q8c}X&>l(>T z1sG-!)j@RTQCs#FMimD!%k;!It~dB}^7NS-(Nfgg*5KJdXu4`htI|@HoeqU_@w|E7 zr5U!;m8EgSU8b$sY@;C(sp&2`;lA*6g$F$CRuG1fB^-~8tGXS@as;JEyH_#0ZN>+m zUsLLrm8qIP5}eJgwD0)+?`9~A3WVXdQ29Rt3N+$H1%V6ROZh#Mwyw^gK9G~ zIMLV${&OC$iB?&$=~C0@`)tC}jh3!Sk-2$^Y~%fzAWEcxk6P}2c*Fujs~pOtvjnL*4Z zS5lmgB^_kOvyQMXL7i#AOo{zqx=5Vc#Bny*Hpn=$1ZD@9D@E@{QnyI@zNO~CoyO28 zRoXdfIJaRg<*q<+(YWR*Ai5ct&dp0`UPSyY+Vj9rqz**yHc72B5SZt!tSv5^2=*mKnnI6A2hb?!I#hO+$O&UmPetBhvy$ zQPUSw$7v0DFUbaG0O>to`YL03spM9XzCmv)H5W8uQdux}%EH-R*hR=ZyhKaRNtruV zufkcg8Z~`3o|XmvKAXl(!%G6GC+@!#OQd5XZg?LEU6k%MVX>if1-bO#sGn`+rduVX znX5^9p#zdbO&>STXk2&Qr8(i9cVfS<*LSb^E@sJURg?A1*7Khh38i;Mw%{DV*Z`xC z!s>P8ytDw^#Js@j5V|rMhXMnkc9ogxh%g#Q-6)Wb10D5~-+&e%C8=dn*9a z33(vofzVe%LLPhIfg_92(<31ER}yf!Bs>=KO2`AM7B$7Amfhvmw_oN*g8Dbjo1S}g z_YYscSwboh|IMs*Q4Td7u0GBe<{ieG{=BT|KR1z#7ObPD^Tp~=)4vASmWXa)I^VW= z2GhAEHbX_{D|sGYaJ=Omwsi{rxhb;L@xg!XmK^^Vf9Z&f7o(-Ga%kyNhN+tb*J03G zV!8o#Y3FF^rsrrNu`h`1c*Tiel;H(RCx;V9`kXpa7coMC76KIn{IrvFlMQ zAzn}BCZ_*|6W{u~F#Yx`I^WQc<1T2t|N59j@V@?CyRJanSp!+(^)W8%#0naqIsMvJ%7&;QB|$wSUn+cDkQ+;iMe~foPM;49S<-LFe*on)6*6DPZe?vYOQss~LU+yP@fkvsXX3n^he%E#&@T)V2ASSb6=9@x zU~M6g5qnEXO?vYm2M1|!^zOUwJnlk2`Vs?)EO3IC(ESHW7bF(cx`OGamNTJ{(PiJK zpA(%<*vkemy)R|`o&oRm4di2{rw`;(UC@xD3GKR}!!doc0_8tidQnBu&{gA1z- zr56*OPx&gDbkE#4ecvyB@rz>@_N2ShOUmX>fg|mD2>B!0Cwf-2w>J{Hx7}sB-5x!Q znge#6H0M_#&ilH_yqyj0`W-(1*{@L3JF7Z9$$-S>L)^GuZIjKHltx=n zc9=(%?ZSo69GL#@Tkn7N!n4o3^y<5xAf;=(|Ne_FKD3?53Ksq~KYQz$OK*N}OL6bV zAAUqzBg#mX^TP4IUj9zl$6Y-!?|Wotmmq^P4^n77yDXw8D9zqmqm&lVo(?MH>i%3yz&}?D*@&jg3H+f<86>V&6`Ba(v0xDsB|V>?m21j^=jD_g;sNS0GMA#5*-fF5G&)Kr ztcHpNPnsPWIUOY(h(E+`n;h%yeoIXkFCwYm3hO7>|WvA-Xz3IM(#;MFMgaUm9n+Pv!iW z(Tm-&R%cG)8P5!Z>5}0)$zwcwW_Wj7Y%DR1XO_-wY&(tT}xgDr(NM2$tmtCBFl zVo~3}e@B8>Cb7=t2Gj4pdjXg}V=*>iVKJ+|@L z<03J=Bxa7VG1CP+COB#kzc~fuFGRyfg}!__u_dsj3$`YZ(WvQ|W5D!rgu;wM$)8*r z9qsHIhc_Ki_lM9K2G-&9#Xi{6<&bfB(=ol^&8b68=W7#h`Z)S5)%%PSmGf08wM?r` z{i#;ztbV1d-#weD#Ox7K7kSnRr)h1(1Y(pzP|^|u)O1v=qW%7GdLW`Y))#1A5@kzE z=OyX*8i|)KQS%2|1r*(jxCpuhKrE9cEC>x92c$pnfHd@19(ZE$kt0upJQn&2ru0{a z9((Lwsp;DudjMBDPM23-{n9Mo-u5!+{^~2MtiRL$#Y>0y4M>w*JnN^&cH>Nc-3odU zr5}5oIAKfoR{K$sUP>k!2l;2Fg48Lxv*oqF1=Nz#H7rqm-N))STB3q5eFgKy%oj4B zw2tKT|J5;3cO^)-uJ!jVO%NlPU1vF7R0b)p3xiW4ajEFW{ep5XFf|b`;`K??Rw7d4 za^dPEZ_1QTRk18DfCzY>_NCM60)J4t+!5?4F zhULiKMmgtgm?TF#E_EmwksS682*`}UR1$#`p5~?83Gd#bqCo8D1g0mThm+e5~Y{AezhuTr*2wYC63s}!x zAo(X?l2;ge0wuOUKd%nTJN6b`jss>I5<1s5DKPS=^NIoNjz54Uq&wtvm|M91En@@W z4E}UbT?^}AopP=;{uTr3Fs_CZe02d5wWYNSxgF50Qx;4+mii>nWFGEzY{pq`#awJY zN6beFpCT~28M-YIx^~&InVc?cQt!Bmx%BT@FgI{M+=VyQbWKal_zOUO*FXGkVLGJU zjA(x4ICKqUXGs(v$TFn8tNl12K9IGmpOR4GQndQYZ~CRC_ZuL8Tu859t|T?Rec(6n zy|x@+6U5_YC>>^l2K6gV-8z8d63`{88~ckScETAs=S@x=tXJ(FSJ9fEv78{5WYgZr zsOfw%~PNC5yzv1asX-^y5izIZ^a|!6q(Vz7jnviCdUQh}brkC{m z{FCRx0sQcwI7gt1Lp$d~MLrk9>QgapL`MtK@z>lzaATn`9YV)avH^22IU5DZVNvVi zJo7V3*Au5fSss=W((_DnM_1Pkg=I!f&%B?@GLvT>ay*SdPmcml;*2{jK5Eq{{GX)(SZR( z$Kd1Ay-Drt5q}GCfdk}r0`04Lq?qSF{Rr2~iBFfs#ewNruT3B5OOMMPSl>K7cc8hU zp|6TRLqnfEnix$GouUB7@#zir=+ykw0&>V}PvzS)uH$+^PQS6_7jnI1t#3Hqo|REE znY@y8@9+V8dP8d*Ih+lr;C%aly$|XiXds(2w|RX!RO;%TEKVnk#;k-Gg zM0Zzuux4-I+0>rgvgU>CsN(9>;^2y4cX#3#nZVJ1z+K)JQF&@ws)|4PafQGMOtdL+ z-j|+7RkpaCjLoH`J67heSxL_P*;gT(iO{O%r3)6`UoNqIWd47=K}y->Cq=5`1zo$YR_>31QeBc}6n zmpI+nGAwkIu8C~HkOT~DO9r36C?RmbTU<7bLiXzy~vw>I%eivZ9g72xWh)n zjdIHJWSijl6QV_xSR4$>N%ItYA05+>x%z z@#Ci;)sF}JMCo@)SSPieyI<7CbL#GXUHOuv)8KO-GhK0N-F+1rH zYCv5q4VXjZpmjWx6F{B*N^_-^n~G3V6ROk}O;>mwkj;$+hAr4e^`IC!RCJ5!MT5L_ z1}BzkuS3it#~0(Ik-$sk0bV{M<52&{jrd@HNm{i^rfMwec+*?Fq^6fsLaO4<**%M= z6-7{->EDx3*Mhm@lNmi~`dJU5-~BB#^q#xL={>086A~;;?;)fGUkRfgI@d$e(ZZ2( z94*%l>_6R-5SS^`3&J_37YH5gTn_dpM|w!*A*Q{DxbwyyBz6a-Pw+ySU+jgbPhshT z+5TiZmc!^eTq5aZbrIh5yZ_(nN|Mwk%=@P-GQgqL$dwya%kpA$W9EKJuNDZY+ z)Sft%<-~~(O|+UD0r3vgi%$LMN9!ey|1DI%_1a7Y)Bo+`5_7*IfBDjd>CWWzk7=PK zOrIxB{npj~lT)f5#qk228Z@^M9n7?b2wkohb8Oh0>QP-fEtHm{#^bW;64@@;(q%t~ zo?+|q69Q~gD+;C8VNA!&B3=ApMJFbNP)4eBM!YLTxo}}bAerd^y-HcxkW$hF94{m| zVw%y!5ln~pIg^md)zPbQzOOC6U#=N(GzNE0axHx9nix>kTo*zCXau#TfVsRcYI{@% zrek9PwUNWsfK)d~Y$N1O$m3cZKhr````2Qq38h;pMIFo(kmq^q+!WRrjO=o>1Zpvj z{~QzlLc7xlrvH(c)lt+*Y@DWF<~TTC9IrfF3Z6O?be*xHUpST*#Hi_p)WxrcyPZn9 zh34kET!)PfwOjmc5ZF@J`L{QfDGo3f9y^enQ_wQsOG56up>t8bMeUrxhtAMKYxQ~O zKyjU5h2UI_zL3;gak}%4b?L2f+gh$*rV)tgM)tSvkB6-vr3u-BR`*>uIB#j}{bRpj`}X6A=MvD{ z2d-!fSz~ktOg~OZYMeoHYdN4|QmN*s=%%%i&|KX}P0)+_l%l7*gxgbznF-&Uk1svk zRpp45oQ@%dqE{?67sm44XH7KGiO1fV$n>$+_hP)Jt+< zkm5i{HcVc(u4YY2Uq-&&vpOyqWfTmfLnq;Ro1p@ z=^yk>M}H{ptp%ow!)pBwr#*cr2VO_vEyk*yT$q}giVp3I?PYt@_Og;Sn^Ugd7`$(V zEFbTDw?w`T7S2)PR)$E5xdb_Vxzu#-pCE9>cW?OoJvjZTa}{~5=holDUy&Mwf%Lxg zfw=bdcJICh0K1)P0t_+hn~Cqiu+$#c-rO+IoY9zZez`8823>wMk8 zU{2=nD2P<k{u4E;w1e@8roXCu<40Nv3sb7#48MP%KS&I-N+B+XA5@sH3d2mP8j` z%ql8M8*Jg>(YfBGJMvR@WK?CW$@dOVS(#De?neJH9tmWgjE;`8+(m#M9v&R$MmH^Y zDmiwnE_KhP#384|kHAgZW*uUWF?xDV3Bf~Q-n3?_q5_prA5R-Ey&vf^1U8D&)!)hb zyqyK3%kuKAorcrzLfqw-rIF4pKo_FV#V0*~(W2N`2cgT7jw$`>>tHR*B~}ILvD1rY zipuZ8?_scC#BRnEN*`G*Wfb2v5Tnbb1PSnUcL#B3?}jUi|#{W2h$fVs+_-Q z#fsg-ZOS9xx%Alei&vLWU3&fE=+)7yXLin8<(u>!+L zjI?y6t8l^0%B5W~P;z7J5H~j-*Y$Ywcrd-l?&1adQoE_x_16XGgRk#?eb78J&c8m` zCIP*&3&sBkhsw$$Pz0zi3F^XK|0u%UDLr z0}1T$i7a1Lmze40qliUu`U1Yg_)Bq-n0Z8E`s#NsQ%^_TCrixb2GhqOn^RyKII@U+ z5{pT=^ly}I-Uz0TsEs2g*GY>fOz>hmWP1%TU68I4(gf7>qIwjrf3Uh65emcn!4!;w z<2=X(aC*HG9W`|@69yj8-Ll%x9tS{RdzmCRjv(D4^-j7G;Z2W}>jh9p9fwTtrlY1O zod(k*Tgq2qMhD<75psvS+#vcZ+a3sk)Zvn8lf3*x0~f&PPE3E|2%Ns{u~$f6L`IKz zjMC8uq?-%RMdmNPZAe{W`nFfU0p4_BItN8#@s-&B`q$L-e>tAF&Y^0frn9eEABm#u zcN~5fr=I?L8lNq<+@pUJsV9ESEl?=R{mSDCrgMVZB~!*qPM4T@>=lv#03ZNKL_t(O zO9}0N^JczwA#v%9IRWfVF+&WFXG5C0Xj}(HFB(|aTUAMnI*)ukM;%9Hcv*$r1ulp8 zRW2&6n_I+X0zFfXX;2*T91t&(Gz}Z$B1u3jCJA` zCEvC}Ul)eMIib^LNIlZf*?Q}Q5!Y1>>fDNBAY5B$jo?~hx`wV`4Q@qOG2_;HPTjT* zn{YYLNe6Scx-E@`fVwU*FT`J1Sb+ZbVfyWa?|d)k<)-Wc+;EZW7f?qTr;?OYVE3+F z{e5GXall|-Z*Rur!diJ^v>m1wHffeg-KgnfW6fDo)3wPxEciKvqTUV%;xuQ;G3ky2 zt%la|p`)+U645ZaQPEow)V10>oSvuQuJ*W!bwT+j=?yxbhjE1;Ck+bxD3F>g{Q>A+nSALUg*#RyuZlaEUsRzWe@n5#sf+cynM`R^xg&(RF!t;qoAo z4$ErF{F<NN;U%KjokLUI^Pj64LA4l|VZg1|(vJ2or zbznUU!tPtYzOSY%Bf}n7m9ige?jOJW^7`5Pe(}SfAM0-)%X)nMdK)Ty{=oF<>r)yA z;sz)*2G#kY?AWeq)d6Z7(Cgy{>^7SJXn1(K?LB<{&CfpTDCzL?g0i=KU?<6zI^3oedbS0Etm|b1lBqEiVUdsz3%S%*pwv=!} z|7)`;`NY(u5>Uc9O}kd28OjRIFh_WT8E_r9=Z z3zVK*P(bEmaq+V7AnJ8_XW)3zn67|Ds2xzRat)WA1^0Mr6>W!z2db*FGdpyx$=JHN zD%v}LWrlmr<~6qP(#@qAr9n}_6&2vQ2W^qul3Mrh<#l zWvrITWr_N9o|fKhoGu2?A$3Ogv9p6$kNpHS{py2@W=c1wgw$X<`aGO|7h<}gU8WZ_ zT0Y>$?`$)%>D?=ca{*;H5f46}GSB(*LGj)30Qw^41dHOkN0+Fv(9Za)M~_~OC)Wj| z&DCSWZ98Yq9UUFreRUYQTc#J}^Mo@oJEu4>JywW&ANCh;vU7FiSpHS>L z^36{%6NtO!VvaYao5n@h+tJY-cn+rn=!1l@zdpDG4PAuJ(4z7Pf;VcqrKR7;t7GJJ z%=&FKDXL#E1wZ=SnP%dlj7jQN8?k#cALtn`Djz?0zGf2l3BuuYnXtjpyTNqSbZ2!c zH)+�^3(OM8wb;QqxIqp+^%{p(9>Bvr*HNLPw@yQAgm8^g>j}^g_@IBDUAK#WQ9A z$rF71y#jH?B%YqpgG;5Jbj13*dnUDvYsrMZ540@ond0Lxy+}=`coR;C(h-~Fd_f-{ z3CO%ewWZ7@Et#wLUthJF5viGgkJk*o#2;*VGIr#_mX;@1Ae*y2K{0apj!fg*eiGJ~ zaj?6dAYONWx{$6WxpB3+kfNruOS=9a{EwKq1CMRCzD6xEU6`)blE2JK!|He4EsOgU zpGj~6p?(Lc2z^jpX!B5DG_3WL+i@lMs;f+{5?2 z8i|s=4RPH3QZpJ6@#M4_J`YS|FToL^I$HX+CyqREWbwAg44;$m@)&JLA9#g;7jgPF zc>UE^;q+~9zx?*g+g|x5bRm`Lg)c(F5LFGMO z-?21wC#C=BM-EJPym6h_@fVMcYv$jirVG>gh^0=9@=-(tN7T!9eD2tA%-#OQTlh;W zag!s3qdMa=xBM<9{#&OVlrAY7gD!AN%W6Xl8M=ZNXX+(M5~GF^ai z)N*k+@-{qtKjJx^P7%(PqXLXewmwluO(-0V%RRIR97iz^KyQbNj6g3_1j4Uu*Um@uM5h(ABP_%Vk z97r8&ja6hCI0@<(u#*|%c)6WeDkqCT6pCOJye%oxX?Fnyqz?d=2Hqm z2iJx3Y}g0QV@dDBo8H%l=>_z|Is@agLbt><@V&F3@hII7?dJ$s9Dvtd23n`n_mHM4 zAUR69^&?)_StNE$FZdqFq6iPFJ{c4xOpim}mRpUF1NsF^?H}t~nc^~a9uxYX-t(K^ zK;bx9vJT@-cZQ{l(jCIOVRQvG?%9Ld&ibtNv^iRte-0r%FFZVF>MVzvuFnU4XXRDo zgjem&_w?{2a@wr|O4kR6h3U)Wc#$&#h$iIE7DkKI(u|sPZeM09#tL) z+pUE!J}qzh==GK71_r?NlHQJtvA$3LNO=0Et(XmRnnaTOdYei}dLhj_syLZUMjXzC ztuR}a@8mLHlGC?uuW^a;*!(EQ*k4#Jj!Gu>q6*(6MN(IU=^n&>%VbRgA()<)W;>Ka zee6ear$2IK*|O%8fuF`TTxcfOr!PxnJ>3psABWBP>orWDZehAQLTRSfjAf-Nqj@0L zmN9mNPNZMnIB^DVx?C^pUxDPK?fK2kae2*s%{;f}zC2EW`|S21UDB%?%BqqV#<< zYihRa>1qNiMLogKPlpX6G2MspfULoWKYdV;2tLe9HQqBupZehAKdEH)QG56AZqQCZtD*O;^m~{8NwJ zc;B=e-aGu*VS-*Bd*QyDP91(>*W{^*x%Vwvbkl^?^!W?ftZeExBBk?v(|v1J&{~Lv zg9}N0WM*)^Wt>Mz-$X;vH9?r;uOm#+K)U!`rz7^|sa+`PhX`Eso&xDmMA@j#=?2o} zU%82QY8jqxMaam(!}Nm|NKo};(1J}MYzUp4l%66?C&lpwD4kdwS``7YNb16L)s5;4 zJ^h9ibMeV&vSR;Z%t`KD4W{EVDVW@ZGB_E9n!fls4o*L}3UB)Eq{&s7UW(JFBc@Xc zil+tPS;d=^G0A7nEY2yIE=p(Mb%|NhTm1g(@9%y+dMKnjC}Z`V*j{MDX?p(QI5CY- z<$GBWGRc%+e(!U=vLOYoDPFmK^)ck|wHdP(XfA+Yo%}rBbOZ6plT1cPhCxg>!FQl^ zA}=~b1{(&AilQ#%rW-YVIs(_6lILP#R6J@NFZl6esCkW&oAVny&wPcwWGCDoB;a2&NnUe&v<_L3FX#BaXPOX}%S1{<^n%)B^QazWu1w zH3c&K*JH+hUVz`3UcFx#MwR*P?S`A}Av@i+IOmYG+%`~NPG&z zjYw`dRuJ!nbc@tk3F1YezD6qb7lv8DK}IiO8;l05&B?nIMmDUi3$-Zq^0RJg9i8#_ zMVscTeNDF*9p-%M%xvHLWK&D8xT2S#-L)ZI_W|ncsHP`>di*7re)$%>zcdvUzL=FO z%3YRqp%BVCkCcjU8CwK&zI5Z>qqxhFN$Cw)xN&_K-eskta~qq)co%L57c%M?Zsal7 z`r|I#4y@t=-u8}yfE(4^$j6oDzztrh@MfBI`GFbo_5>h2it zt{hJ2%xv;?l#0^%jfK+D4P|6UbE)O3NmS58Mp z_d@(VufM+i;k=DAn<_e+oXF{t1xSt2ds0zOztl9pfXbqxNX!AgsOd8*klQ1{y<54-IW>3`oKBl9!iPR2b`||BXLlI>Kovrjvk1+$;I_oIU&T+2YSHjP|=8 ze6*3SMw?gS8hYoocYZNiT8f(4GeYyBk-GYM@KtV|Nm8c}v8KPjYTUsS>@U?SS3c5nYdm~E&Tmk?_B)kWz6ZXJhJqq z^)r`NVnjEt79Pu^jtkQzr4!dVTFxf-9?#>Wu$PYl@G3D~)LWvc7a|$!8%xYWlTQN( z1H+C092l7?JN9p2t`Xl#6=q3u*MYM}O^4Dq?6`;dj;#4V|MQWZI|8)>+=TxWZ6@ob z9?L!LmCBkDLNSnMXZbk6a!B1jtqik^Q>;#ur7^(3_;5P5adOo2O|hvzTKbkP4Oz~7 zl=QWC^xfI!RxoKN6GoLym&;m(sP11{4y9+|&7#Q|lFhk+s@-$p=K}kLd)PKk(R7 zkG=8$(Jsaj!UBxx+)#f}&bfZ;ra9tpQ9gKXpP+W~!LK$h7*jIIv%K)hPjQ$0^syIS zIQhb@w-RGWmrl9>JphlNK6&FwuHHJITSs1yy?ogNKmF+=icN=L>67#r+)WeGxsumE zIeFjQ=UzCxOIhkj_G^siW&V7Kd>P_4a=O%XNSeN&3l}1S^DPoyL6$n9<#VpPo`{(> zK^R(a)|`|b{gqRXiO_ZBl~bQkLuyPf64Sd6SzkfjhuF|fqIAYG)5Zz)zWWAYdUpqs zem5!Y!gPpwO~D#0HJecE@ov*W2iDzW)O2PNoVsa01e8)QiJE@>T+BLV;F!5#E>VpAy;j}~XZpvgQc(h6G@UT=dIyW}q#N6d%&L^UPM;NoHGOh2 z=2qSXsz~v%Ag33OGZtXlOb*pOg~Ht4CDm(sF3dF7jvYfBZ!O8WkcVJ zdU;E5Obpnzb3uotroXlI&@G2{?ksrmE@h|h1l4Z_(^1pY4Wz5_=vFwM@z%kE+S=cS zH(iySMok}k#3~@Y*BiBXgdU_;_?l7Eb+CJe@x1)%i)#A!!}!Qb|N5`TjBumJ^T&wQ zc?hO-f*T~BbJcde=(_oD{iV2H&zUN_3I=V3rHjm=ORn){QM&9c8sIs@HoqiikX?Q^ zX`_otcj4m%tFKlmXz{A$v(%ZhHKbw!)Qy~Hize#xoD%if+I z2c-+^XRiavF_FRWZqJ9a}ZL*XRU8u?zwim`%Xh$j(*CKPL zx!byC!#WpcC5z83b@~z%YpHdQ7sIXl{xnB-Sa%xJi>`{$?K5axe^EFy3%>y89a_7? zV7FOGH!mCPy8(Y*kQuxjv-e(3U&Ouo{xfR2^$uO`XR((27w6vJ8Xz>2sVfP3lk=_e2EB& zPxBO2)iq@%`1;a=2u#=4RavrApypr5tMtLWcJ%1KzWvA#81LgmUw@gH4z*8#x?C{7 zHbta1r!Q4U(%09IXVX%_=~v2honL1Tuu&Z7)QhJ!LUwmn&<_4syr)E3G zAw!Ajpr=!&7e{1uW_V{n-B}Yri-jUmvz_UoJd}Jss?>@7a+H)5XV=N?6lhMPi|=IX`w^DBkpK z2*UYy6x~e`sgcv4{RX^g1`pFEaOU={Lbpb^Zr$GlraK~OI29UOULn^D_VkZx%EpWE z9d#YwTb?aUFGMJJRaTB=7lP?s>(RZ9nm)#{6wKx8kMqOJ&K_r)mFc^Y%=U?k?_50n zfLt$+yo5tWk1o$DapuY^K4{hX?9= zNVcLAPdsZiA^qWw4Iiz2`v+5$j+CD7PoG$5YZM*VlU-OuPRY{ zB|P#a*wa13B{U~0tII9p1f`o6pBAWF=d!&7$WVgm8;Qq^`b?zs6q>;%P?{MQz>6eI z#V@jEpsksPz3_WuCr>Bo_`s6fbmeWV*V)WCWa*Y!MX2*&C*e9&V>hnK&&oJ!CPaZpU z^0^mqaX)bSfg`7GTzKk6!pf;Ay>Ah@<#0N5t{P0!_|pjLn8$&2V$i|sxw{TO_QGRi z!N_?cb4)i{`Ct$YP;a6!(Y=P#4Wb*1`Y9sePu+Nkn$f}TK~SCZHHUz0i_!^XG^DOW z0ykZM!@`qN(=m4pA(|8PIE3e=U~Ir=N(=qZ~9GA(_wTd{Tl52 zH?6TeFFKU4Nj*;qk6E+Ei|H9Ly=RJZXj(KGH#yXs(;E>5rZ0|0G(M~-^To+VO`n}a zQX(kZLDYG2(pG7O(e2S^7VnOp3`xYy5i%V$eOf{9bMLjEt33znU$Y3)%j$Kj@umaA z$Wn_sfOKp+SjtINnHGZe9kqNhB)<4Lj53svuHC&ogOC>rMWv?qzWInk$d~la=S9Nl zLs64j9EWQ?BA87esLvXbmqp(6GiwFuuzt=uFnzl8u8>2#e)(Hqc7x=LG;y&wy+i+K zMeg#vNNLA-FHE1nP9soP|4;?ZsF0Lo#a+o0U<%&!6WincQ0|YdQz~)#E4! ze+%`ZFQS!$)^CC6su%rnQq0bvxIywhZdqX5>9-t$(v6y)^r9&#MMGET(ObZB^m8-b z+De5f>l{4DCbs?!bRo4&FGvCey&Qe;h{SZ{bW2PB_EX<|oVY}(Tl&Kx7daZ5X+d=0 zC7E68#P@|V`I8}>pH5=*O%t>)yH5|F}g+R-YW_f zL`ye{I=>j2#zEkRUSk|mL2RiWk+rl*DI?I`2XwN#C+V=;gZvr`mGt5SeHIYW=;^9Z8fj$97Cr<;w@ zoD_a$T|!&X(pl9YGq>d@SAi-P7mPAI5UY)fWFd0W)kW>>)$PdaJcOI zG$gG>{D<4qlj7)Dn$G5M%1~!Y(jw;=*VT6vA_v8JH-K{`APLhMykVy0k$E?*e;ZdB zE{9vqB@Av|F^V}?%>oeCXwU}Ng}7QrqO`TZ@UC$DN=&x^olRI*Y(};&{^;B$cm3TE zn_D!_TDmGc=c++Qpt7N%p|Zsjkmel2 z^}|>+=X?e7!I$6IR&cbuMNqLO-*IA zYHTTNsnot!dI-$p1y`Rq=J;x zJ(*r8SnP@Kdeo@t$KJWHp?|cikudU_YD^~=l%4)TO&WEhxYOyDWC8+H$bH#SBNdlt zagSCJt(`wFl(-iak@_}od9>)_sfBWx*2Rn8BBJi)dyl+y&-&1?GTO?^%6lJg)`-03ZNKL_t*D$c}1Nkk-{e=^70esWL@QBJ^`)k#mC5zu!bkK7euy00Je6S5OY^K1^IpHZw& zmY;uCma_#ze11_|8^039^TM$m=Bx5y@ei=GytJJEmorkc{1eFE$A?~0lA<@eIv=$9iTyusD%AU?o0iR8Mvu^4aBsc=|EwDrt=L35z}f)0aK=$pfFfr8G_I$+#F;feUR|(eDc_l2RM7|fnA_F`7Piu)^a+S z@=7J6qpSaesU;;BJlDE?NQUks6-$x!Y5?5%M9asIxcOx4pkmbziyNLXPcge zG(N}lQZRXN4Lb6{P1D;KukMYR9ITZFxH@@~JjTWCNl4*{>H04Pr!zSE-A)zgx!}N^ z)Idimc|N32+ zVI*^d={y1*9W~u-U(OfRr_!R-YDZ4vqyKty_8KIY%JE|GoHITaQ=+=56ot&u(dBuu zFg+<}HZGUd>Nlz(G2L8>(YY=;UHOZ!Is}eaoLCk^-NulPrY;}K5?T-ugP5KXhkKoPBIby4gN!Y6~*W>k*m|u!C4z41q@r%&lm2<_{F6 z%9JB}x&(939L-#RH;~|E?YFK{POAA$%v1@fg{CmA#pJpPuo^-A61WP?4VD|A2Wy47 zEU~{V6u+Fu#mL4>V!2B$r{XCFHw67fY2D&<{XOAs5jrb$aDzV|TId}e<_hQ56?2P~ zwbJG5S=ZT;d3jpPOf%S1^W<832S(GOI{bWjgIc|R2H=rRkn-|Bb8Sc z^*#J>Ut1oUIg7#d{K`VujTFY2{b^a%4VxQUT80M(5UB?|4j1v-G<^}3n`jqZK~6V% z`pnqS*x2S~|B5D0(Lh3H>5QfX6vR%2B=S|^(~wtKxSochd9I37WbmVpL+RiB!GHS! z%|=nvEhhi9iA=|gK4o(uJYA8D2GViDkgvXU{rbXw{@7%Pk{E-jgDjYq&%AT-j&U%3e@|;`uD^5R2Ny29_S$cM;Z6(PHxFvufImYCfw@>-YO3&IIDGr# zYpUE-6*^->RYkh(Ku_A(`uq)_zjkVwVD&6=x`pTVIdVGv;N#;*aYqZ%u)pwgEQyE3 zW`uw6xm+(F)%f+FZ_3VgGjn2MG}A>HKw6rkvU1#|08IMLH^*0uXOq_G8Y{1u*)`tK z(pX=0zM`phVEFUjPyBx3;wPV9Jb9xc8LxFEBy?@;+FJxZ z*={I(9CJ;7b{e#cS-!fY%Gc?rKCu6QvR?N0RC64HSomsu9&kFt*<3}Ad~Q=(z`y}U zSl7IxkAH@k{+*wH=ZCL0-1Gj&zf)W~kiKo(0Sb0$j--PJdcy?z0o6EGMh?9C4an-2Io)79XVvDLYEzs}C>gEUp;N1x+1+|iRWG%x48Vf7M2@m z|LN(U9w89MjK^+V_5eISf7gwt9{U8q#w0^PI;NacFPyq@*JHFYQj&|L^cPOh%Fc9%yKx1Dss3xRZ2BM41A3#>;I%gD>$`P-eMCCBz znGvne1=5wsD2KWkH{E1;)2C5(iIGIvi|U;u%ZDOt0QC?Ab=35sq3-K|deRmRr*D$! zMLjynP4C8&FIzg4ZoPfj!`X`cgNljkT~*u*q%#U=cL5w zUe+a(XO5aqkl|2N1pj%d`^v$?zB@f6BmFRw6n>0yr=~*?WdIqwl|sOJ>RGZ|y#fn!a{-1`c$_Wb*U9&z*T>@!8#voN4ck zAS04G(IKiwdwY{9B30X%h{Pb0X=KAeO*dUgk<+J=UeLAz3xw$WuhfO%ba~S;!Dw&! zFKdQ6k+N%xV03IkQG+pq#CWcWo8NmYppKpnrneKEp1jL|I%o6Y^k5)eYI^i@c+*iZ zlQV9nYY{3Taymv9>OO&VrY<{g!9~xDp}|q&U?5%>i_;IGmLDoWc;^y0SGDQZTaeAS zip<668eA_Z=+N0J@4wf-+RG_5om`cpFOl;iIo(pzzy0ms{nJtY8RJ>k%d;a{I)&-~ zaoZ0JrcdeVuY7kNq5{nQW!?x&kS85o8%04^15#Zzfsbl&`Y-$Id0I1r`0|*J`2*er z(+yf$4t1n-fu{s?`&+JbuE$~9o(-gf=rX2DNvEBW_Uo)D)}@Tx_TSc(tuPU zDu6F87yRj1%yFP&bU~X2rLmag!0RzaKW8P>ci0}Y3<5WGs2En%l#~R=VglD$v|Kf* z%mwHynoO)C`H$lFbXLO9A{V+`;o00GN!}liecCGNPcuQ zXd!PLGa6cz+CNkS<%TOkaU-4!&b{BdB0ksG)HP7oQqx7}(%r?pQ{-y_vAJno6$=ZB zFH3r{$a{*EwT2n|^?;bon)*XxmT9dH@3qU8v9QD10#~$32hUYu|F#-yNHEx`p?62?Bf>(3+*2Wd+?q|&)`iz_S)y;Wut{7t&RCz zv1OHg=RZJB|HY1~*xTma1~%^bNVbZYN%*-KtDZ`8(_qbbIQ%b{U1& z)pVZLMHB~MlctzAjUoR9@RyzKpPdljU(ugEmPO3HiyxX#Kx0pRJvol3&mX)q@z%t| zJD-2@!i^_iKJri3-j-08eYAXR=FFqnGmp-kSzhj1U+HAVm2K(`#%5+|^BAQ@ebO+G zQ~}XF)k-ULH15as@*%Dlsx}+RF%R_%K=CHyq&dtHkej=qrfDqlz_a_eh0Z(r&^@1> zee>tv0n>l-J$gj(s;M3Q!?VvmyLlkLSr35jG5N@w9u}r5QQqBWUqw#8|H+SPGQZ)I zkXE&!s)Pvud5sQYJ$a9ybiC>GDs8Q+tE*|PDk1nD{zh`f9uisN@Oa!5kZu?ruFCDF zjFh{4Lrrcv*9@t1(a3W(;!juFAzK_7@zl`JG&3_>vx1V!w(WflU12RnMP#S<iRQ2$Z{bUxbiW?J5Ki@}w$AByEApb<9;bD3(=VImtFolf~-oYW(eHPjr+{w4SY zfbATa=+9P|Kdl1zZAk6JjHSVqQYS`pTrbQ7J)YKhHdIyR#`WXJ46Yg=ug@&);iy6* zVmjwIUK9$$P?Tqw7t;Y<{O7_^gXfna`cug0Kq^AI?nHt%0=i-JPcWO%+K4hz1L_Z) zl;;K4%L6ye8N%msiPDAX@cA_5F$&a82`S?GLIu72^rzn!ljCopa1??3G@G!^Gw9q5 z%^gnOcnU8GGl^xi2i?{~v$TJr!FT+ER|9q}oJI1lY^7-Jntm)$PT@Nf= zh{t6Dpkc}Yfw74ey`UsP8U)&A?>Dq z)DC16q}j*EqncD%Hk){kDCBE(S2f!EeRCl4O{nQ`I%mRk zs%AB=zfbXv#KI_5eG1cwWLRC?3#A{NoLqCTHzsJvR@38_fa!}@4N6Vl-JUGVi-qaa z6DdYZh6_;B*XCflvB8)8^4|Bbv9NkCm>!tE>TWQ7a?>m$SWlmhgWW(nPL%~zkoL0b z+lwE0WcMQkGMe^Al#mX|>5l0I+X-U&;xmiSy!YHe1bI9!A*ku;VA4TL%#0|&^U27pJP4&v zPU4J5PJgagfiG%9ijF=(^{D&~0NP}5;-uo$!Io&`^a*upApw0Wn4YtB=Pl&B==j2+ zLlLa4(%iwp$>0dX=$zqZ;r!sCyKZJ3I2}IU$*}1hK=05=XV$et%fAej{{Qtl7FYAP z1x$YEeL*@&FGeKC(el)_SVZ}UD2V2M1Jsr^eV;JhtEGSYmG8dt-BRh|U+$$^lKHPh z;B1`d=5JhuxuNuQVfwGI;Gmf?zC5PGw&=jNn$9P|Tmx>?QPm})3)L;p3mrGpYcZlL zg>kW|9hH`T44;cCLMae6Dmr~c={$tUO+t&YlCwbNo2t^}SdAG@9>U0<443Y>G$9(w?(!T{L}$aLf>*$O^U5 ztB=hlFg=D9;O(4rCJJ)4)M9?8q7{E<)`@r0Xhg81JC<7J}(!V#8a-uz#!qa!4G%wmdA#Vl-)t+%gL+Y?XS> ziehzhAs{yLGXTz2AunfKHQ&}5OQ2uf0dCtXLEr*yE4IZTH&b@4#1K*26s`%qwNU5U ze22XqEoLXoGA+JrHQmGal}lJ)t!o}*Jx(G&d#1fL!#*Zpz0yBE|EgCU|Kq#<^Cd=7 z_x|G0kwzxuY{E{Ys*`NrpwqW)p_z*-3#aZ?c++9@@BZNZ zrF-oXQZiknrW+*p+FsO(6gAx}vl3vq=fvLFF)Y3bG#bL>o8~(_+_(J>cD$h(;_{7m z&>LRJ>rW(=Rb*NoR_JnamzGlUClfi5ds*RGVU>kWSFE!otz7!2Gu8(u1LA14bMJ|3 zQPWo+yZHI=`O(7tJ)tMMLd%Li7zNXR`^zH7zIm8e>S{KO)Z`NLqP|I}>6n`-1a*7d zX<1%RI&!)Lp9W?P<`$^w$mwq6;p&9) z8BIIhRVUKTv?V1(#YOfCX@I=xu2H9NJn$Ira&gno8SgA}rNzsRVJi0eGUTc`Ka+r}sRoBGOk$Joi+m1OyIEc=OttLkN_nAyYaMYf{FMECu{JT# z?xnm3gjG8z#00AMS=$R&%UJv~nRN-g@9qKOSRO8Fb_PUpB%_LONwrrRscEY73vi~D z<@ST=W4B37M@*;5k@=#ZQ8R6gFzyfy#AhZlGQUyf4FJ5qUs`h{;WA8Rh*;~@}Il`mEJmkj% z>6t9$V@#V1> zZZIuJmElN`_#*vH<1hJFuO2e7F%T_|Y&_Zb-M0|Ve+9Mrsi)}j35K5poIz*4?_Fk2 z+~kU`i_x{{re%=#3o*N(bg}tdrKL;_#gK#P-SD#n^ZAm`t&|tJ*14*079oq@XW$(8j)KjPKwM2ERnW=d&T|!NxP_;JFw>Vux zbj>s0xDd7unY^CjRC+0a>YU9X4PJpQIL>dlN%4}_Al*ifg41P9pCv6FpFB(M6Qy4_ z2NQosH){HHubQ5db9i-oGKOpwrV{iLGHnRcOAdPRVGGlPjOit2fovg62nZREkOviZ zAin}k4}>=t@Km!v?_|k@EdhZXLUn$D5^^k_hhBy=O3 z2PMW0MgZwxIu9_WmySb+C?OS|?@a$^L+k~*A@ST$x%NwRZZ33L(6Qie0@L*e1_^+$ z%K&UeEbCT9rsmw?O?UE2Ub7m0unGfwhjk<}0s!SA}2N(w7)^6{=Cw5$ZKZ zkQjkz59(XffRPzEY*Kk{ZT8Cz?9@=FZFR9`i!4y5O{wQ*(0DWvH9bZ+t)O%$eKjt0 z{NSsW7n8fbT)uQUUXB%06DrAkwsDfQ&j!)a$Kh&`v~ZmCc65yx_a z9R~Jhe|Zv#?hJ}L5CVkg)Sn`xOI+6_4?tQs6CKPpQn^l?Hp_Z0Q5q$%RVed{qir@`LY%|$IOHmQ3g!CNkMx5MCK8eJ9B5Z%E(zHm+W zq>cNgjn_q1Iuuip5E{VYd`@ITg?CnjBIY+Vpk6n`R^V7GKl=DR|Md0`-hP|jqD8}= zE?h5m45JO|rjAr+#0a9JGi;F^PJd|T7`al}Ve^Pi&-96Rv*TN~Z)s}@Mfa^r^QDz1 zwiicQ6Mrwvk-Jo9a{vf!aXNqqRaKE0(&;REcx6{%vyVG1I{^TL)Nve>ftQj!_V}}B z&Ypc_`QLy2gR=952MBNpdo*Ro@CQXQr{|42L;VsmGn>lFMt1B+;N^S=Htv*oY%c+b z>CA7kVx6In!s*W*h%BpU8oh9MnN>vkwlSyQh8f2m6f$CUKtiojK8;X4KEUH~1o&sA zHjRGt>8DS;i#xqP%-QcUo@>_VkMCzKUtB3j@JiC{T`&LcNLx*7eyf|G)!0}+rjsh?m`N}pu|&dnC!4(#9GSmLK(8uus(mc-cr?zAG^u?>BCB)tB?w;$1LM3nyXvuDo{ znf|+vKmNmKI9?(tR~{ukCZMN>nUW0Q3K$GU?T)YRscs#B)1P?bo6qz>&UGn0kq3xo z$q&uOJegU?rg5QgT!_mW@)?a09A!CS9~jKx4@~MFDp+%?HpJHf`ML4&ek^CufXSSM z=_uZOmvErLLSGE%BF?ckD3R+0A>|o<|729s}B)vvI6J~#njR1ua2e(M8>4W(_BE= z!VG;j8JStJq3G$LcU{i_FGU9l{CK;YG2}=$*R-ylc>MvaFFkmntlbY!=`m?L_CGxF zxe)yUko3v{p3CTB%r1!O_+AX2bB^sqVmje2vZiA)C+G!p$|sM#KoinwG~5)qDlPob zf{+3dK{m~zZ;^&@n-rH7o3017Zv?~tlW{Mge9}<5d62ah8up6GH7gcc50tliuJ?{* z2;R6z=8!xtI#;}liFo1i#$Cd20kjaF^(H1x?P3yeBi|>P81VY&R(c2sR~{or6l_oz zqMPgYBHm-55v5-mdSXCbuTy7)Mq1I8VEQchkv^o?QA}&RFLU5?+7uD7$Z0N@*Wa+_ zrt5FQzs`d&pc^%P`m8wy(Ycpo%ImMc?ml$%?hcxkPMdE3pn5Z+F_wgY=>?mH=BxFm zFr9pr2un?$oFtEN_w6xQR`87{;;so+Mg-a(-gGd%K;Cp@@(#pwoFL~;%TazSG#`?F z_c!_PPZLp@(HSZpWkoeJ#UC>?dG5^nk31sD{JAsV+P(P9x3;fEg;#F+WE|2p!u%s= z&zyPr`T2y}pmeLdQBrS4aicSlY1t_kVh#LMXI-Nm;(tlCj!Q{dQ#EQoEN zj2o0W{khu1>XV*MN71{|b+A7!F?eUv&BAmJ3M39t`!e@XrL%Yo+qFV?bN0KJ63t(*@wCkLo}k z!}5;vhX@5kYWMz!u2j>%edN1e8mBSB*J~rcQWpnp-0GELt_#^si_(!9<@4xDilqLf z-xR6A7Ft?{YKg;OC}?V2E{4<1_2g(c94TF(j^9OnMhSBvhH>#~953sNfpySVVJvC` zDqULc6nK~r7*VrAT0nKyoIN`Sp9}i=vDLSeRF3`)8e?HsVj~IWsPe1`$=^;nDjTbf zi@?GnwVoB#2}!>6RkLr$O~cmE+tJ@|=ULiup&LD1PL=3rdL!{UMlZ)TKf6{bFzDt) zPg0^PZ@UC{&|N0;m>4!EfxP{8!qO>YWttj|1D)9cnd+G6c{@x*<2BLAJ@V=G{001BWNkl6y)*O*!VR71(ugI-CDLIgAAF{gk81;mURwjuK7?pj)6W zWnIMH*_10lM@!!$Oy4uyy2F#3SpudH7d`WgKpjj+P#;EDe`ZTxTT#*G20Z9s`j+k6 zA6{80_NJ|-NBrx*{_C%=-8)(|T-dx9I#;fX0dnii zva9d?^|ddVYsL&CSby-^6MJXQq{C5we>oJM)$evQ-)PHg$PcY@M|zN?BR!D1hky-G zi1#ZsHI`s&Cv+%ot5y+XRjY4S_za9duXp8DrqMx?7VheA#GqkhKbU^vES&!Jix)pS zKlGCnH{hZ^m8T`#4kK(N&c64WmGI`Tb{4ku|g6~o6=M7n1~*uGI02{K5; zp=54L>UNqnQPnAd^y4uabO?1)##(jYSNnejG?#4{{^)bm^uga>{Qbnj8()6;+`~21 zjh=DE_>A^bP)j*2%~xrx>2wKdU16a-2lWRcbE;Zh$j`*NC>zJ&X!JC0{@yn~e06{0 z{*o$}6kkN^P?a_Ic=lrw8KLa5v;3h)jyz?;7oqf@zxn1lC zKi*G1LB1fmqdEW^ObMzwx$Oy5mZoJl8M_k37X7Awf{Ikr|fppGD?J{%^ z<%e1xbYVK$Iq!#hv08=~Z0n62=%}u;O)sflNLTXWy*994j_byK@|em<;n~L?lQmuT zm#3`uMv~F-iQ^y<(!Q_|F>IBa)MQ zxAsCeZ?+dd-5WGrx#=+frQCFR)0Onn@s*B_z(9^d%iN;1W^JM!tV&4DU`~PD-a-0% zH(~U1hNfvAVVTn>B2+^88L%2Nev8|#2ho2JSa6?aX7N98`C=H2k#=-1(&)=Ty)O)e=`0i)O0>; zGb(0Wb@b@crxcs6)O35iT~5%8L1_{7QK7uadHIi#qyOy-YWfe1g~dx7|HY+OF=vCQ z=|~V-U&M}fZk4ExgdeT{3)OUqzj)Dw>LPUO8XgW6j>71i^V8=_OnN(qprCXK>goDVCf2ScLlMZ8kA;NG@(iK4)H#fi;F#0DnXH1gCRP2F;gn z=0NTQzHkz%^E8-+0CSd`V-Kuvu9!>2cPa33_K(x>w+QvCoD7}ohRx)X%tg0evH5Z} z-OIf!Gr+4e>s!!k*jVxj-UEH>+c2nfYNA(u*|jULn>+uaGw&}< zCw><~DCkX}MjRn75`~0gI5U(kIbE)F<9WfLz5$M`%k*q+81`^{A5iZb&^0sq`apI{ zL^l^T2-6?lzA}&QHh}s}XIG_HP4^5K^&Mm%uH8aCw-NdkBvJa(#oP? zBIZgf{Ad~kpfj%r)yu;}=_SOjgIG`rvLWBcpAy;bTMs0NFV5dBJq+drlShS0tt)FDzx>FCF*70wr%@*s`{HM z&VT;G{1qmX@ehw0OgCI+!I>X~!R_=NMdrmq zfdUOk>UGHABd8B>I3Z>U@w_q)C&X9n+5am`P2W)T`9;CYDb7yO;pp|UlzpuME--zp z9}=zdbz#cqeR28`tk_JCOtWP+q0DrIZ=Nl{$m+x{HZ~r>o&KZ!+xAEDI+^K!)+}p0 z(9?s@pHTX`vhs(10Hw=}&UhYDSHjC5?y2wD-{|S7AuF`s<(5gD9S=iCr-IZs)Gy4z z1f@Eqr)Tps-+bfEH=ca872vN=NJuCxRc}`YrMkqgj}ZAnJU#Dpg0G_le+lh?BJ)d{ zxGtIoUpzSn@*xnWIkoEjuKBKHl5H| ztW!R;4V9E0;9Kn*+3bi66LLE>4dj3g#Rb_}DkmZ3Uq*F4pww?J$X{jaWig$FOiPH<_X4+C+@oIMOv)ib;|-=EjUc>rKj$VFW-9b))m)V ztPOn|1lNPTR}7aQIr0jd)FR`3F&kfoAw;$i>jsFy3FVTlr9gf3mLKt}<9Y#Z@&jQnX2P1-NQPEeo4@Rhjv^@h$ zHsOzJNL)!oKfW2vSW>)t_x7BSpqMy2*G$8_J}o4ISoFX(5tNcj&+qNk^BG3(oyh3zonQ%^ z4yqCLLK{;08?~Fj3nOr%U*Z->9*l?>Oo{>1RSO#&90A%*1_yQz4j#(+@u3byEh3>~ zdbt^cx(TBxV4wcX_?uAEk*4G-KYH|i)7%I>-Ey73^6l5lQMU{~o46N5EW1r;{X@p| z;^p~QzJ27su@&pfOC10CCBf-NO^57Z5FISE9-B%6t`*5hS|e6ZDfwSsP1ld!_%!%T zh|{@kh7es=7Y$Tm94Pp~?uO8fJDtMOb;UFwU4`;(NPQIv=!SQ7lP_d&2ENR}_DRtFY@vGX z64Kb2JxE2bU0%y91!bHEtXqmx6UkJho>zq-MCtW*EYEefVszfNloX9?i85|!ObmmVKFdwh_XfN z+$G7}fVnx>wMEuyW+emLB68~?tUpEZW@(4nl6>kKMo{-|o7-&3eyq7$Pv;%lXR~|e z!kApZbgjS(`7hP<{~d3-!Flg5ONG0z3@C0&Yj$Vjdr_4p|NZ&>U`S3kdb(UM6qMHF zR$~{h9yZ0Jd%*0r&0u#?AMO_*T{Wcx18sd3NmpfS`^O{UM26rgV?iXc=zN zg)Rl_m6efI@rdandMN#9Hg5TB0$7SFeJhBY%Zl}<{g6y25)HEw_O&#$G_T7gZMK<7iP8DFa#E($TrX7Ye(@>Go1qT>9W%o(k8CGmN7LGqRoi z?%@Vc0KFmI4SjgjHH{c9YH+KBRevy2uPRS##*SjBmPD0YT7IIn&nWFG+P!-1!0bHo*zuTQ#SD)hRa*+w6hN;zTM{f$V7a3|`TQijr@te1br?c-j=IH&K zydTJ)($h-b%NtL;@#G!*!%I`p(eX_wev!bH9m9K+yAod4 z%6tZ2I-Of-)*0RtnNK1N?}9^BmnEKYj4Cx7$a~2x;~iq=VcFAp4FdK6V<5)~uTfJU zo>@{2y<9rL1|=qx_MPFG`@abYCr&=Jw9OiRzhhfcwX)!i+fsZX%kd!jJ^J05~D4l7cuZ`&ya5!WxC0&sIg#oA=NPmTj zN_k!IzDQ2zhB2ta@26mN)MUfUpz56a@L&^7xbW0lzn?%%zw0i}ZaLJwOq{OZh-LHV z&wu{b6>@g}$stHzhVFjq6o{^?x-e%TxFFXnrt_3m+zRK?sCnx9=3pG(HD4&LVKcf7 z=`=S|8cX-WixY2k4;m<*3zqXx5Pt5&t_djpl*&JFdNCJ9v6Y{YDO zuC1oqa=IE7X>P((DR@w(7xZ(+rtVE7pkI${Zfr0jarE*zoI&YeJeZEtT3txhUP-FE zwqzMHT~w=CI7tS>GoBNAI=G)Qu0s;^i5~cf=T6{JQw}m!K;Uc5_7=x#lm#dbgAB$ z(ApanK5?KE>d5!v)$fDZ8T2s<38d2^nJ(>e&z!q8IZnCh>Wri=q{+{x zpKG5@=b0RIe`K=XInc0R z0bO4)PQmHK;z&*Bi~S#r0MQvaypkMU;aZM{E}zSJjs-#{yuxUstInviBttw#A>Uyd z$Csinqu?+^RM~L2-!MJhYt4N%8_jUc+~>7=R?(Y}tm32>*QsM?8=c_(aJkfZCpF`_Qcbt~E|-*K7*+zbEvDPo47eLw zx3HIU1K$RS!Ch+@z1-ZzZL#o_aBaZYK)AK0m&eUU3~-y})*4?}Pe|Y4U5DRQZi%@q zrnfeC`3-ZQcd@q5$sW8aUMdWm>lCMbq3} zKIPVLg%V$+r^D$p0Cf#kC?f*8rn;`Kbzrk+4~=>t?ajji?q}|}V>_VE4VLtALyi|P zz0jrTkL)aGCA`~0#)~+804qD^W_Uav{ryQ241m-01`3_UyxGftaK1VQ(r3BMY5A94U~T{=~75`m1Yl`&0a?(V`9H z5@VwBP9_DMNgeUzZ?@IRf(Q)YjHWONY|UtMql?O(&DI1=Bs11%zYr8F0iW zG*x-36vw_{M@^lN(nd|x3-LzM(V(pr&TM}qe}5hE2@lUo2&L*e6G1(`q$N_1rty+7z0_ODK<0B|{4cn5 z>ZzM;46R15kGKCCpr(^+Xz+ZB)Qya8Yw0q(@MRn?Mogy(slpf`bWoa7&Sf_l=H|>K zh_6_&0w4N~d~DvDc(VR9RhB~%gey@gXem+iiP1^nqf1!h2$960ph7O%zfOn z{31rWr=k>WpUbn~xX_@jsZ702wWAu`g-abDi^y3B&LtB18oGYI)&16eZ`}tJgZAvQ z$oZx<-4nc+Q)uht%3yK9n!`D|Ix_l67FZkQT*eo3Yp&&a(W6n*O(#+?ohJq%yC>I> z<-)lBrW-bGBI$9ixchq4bmKd}>AL$MbTA!{4kJp!u^t8IvzqnIOh@MQId)Dr99Px=}AUSR}<3bZ=Ec_S5AA<$q0GY;o~#KeC442D;Azin~-3lVlG$HIg+p- z>JaFQn*J4D>~sol$+(%ukpybQM8OJik2*w4)DSQ|gbm@HAwOp_hE$h9fjH%%#G*?p zzib>ER;%xV5>loV-2fM!(^wAQ5o2NI76II5Myv~pfEkCAStO}GKiPnoslHd z3*ALc#LHb+({ZMo@s*CR5@~^#zJqTCPjp-}WI=n!&|kmlMgLJ}bn^G2^Qwn_`oO)v zyZ0Z+c`@UaSB_+P>A||}RG0xe_`mG9>YhhzU(72eyz!N%-oA3xKYz>HhV&>Aj7G`7 zZ1ove8FPAlIMTWdH<#V@=dZ$`64Aw#kfr#XZ%$Uqi}9ytfYPh)<|9D}BXc+7ae>h3 zYGel1^x1rJimA$6hn-v&6l84poiG*n7YOFFg+E=qjyDBNhlC;f=1U#>cR=q0r7Aftl z#Pi}ZuU&=7hS>m*Rwkot>d-t9?L0j@hKHRhQ@kz8myy*R=X&uf^+V!mxsAnzwxr1D z@He77n6Bvo`$vWh-gW#hT+r+YRu|UuUMhE9us((9qEd@Yt=^*+hze@8)Ph?@G^ z_;X{8MTWN*SvS0ZZ_DjwA?xeK=wx01wig@Gb+_gZEdM_}ydUj~7EfInWrW$;VU_t1 zouqUU)Qx(K7u@!~2-Lw0${RB?snZ)CfYT`k1-(7PvcDLcI%;~+=C-~&IP$-}Z{^A& z_ZWfP*)z+-it+}gN=PN5i{}|!fcaFE4v@WWqCsSQaUG{G(r9)+-(=4@3Y{Wkoj~ad zS5ZrIesjaaZLc>pbJU-F8g>vBab9^=)97$Ri{0PICUwOxGU!hVo&WmUrIxyGEyS9R zOMP$GC?=oSQ04-isZEZ`w!Wfy}6?5~g$# zqHPVxbT{O8g^@L$>T);}(l9H?Cea*8x?jnt>%@cjIHjil;{5r-#(+^**MS40Wldw} zalKp^ElWTvZwW*6Mdcjn>A~?Le>GZfHHx~!O$!{qc?o2_K>oRpT44 z2GKd^k{6^eGPi~Mts_QE-*Csp9}gbF?Eh`0d`1MUK8U##Q|ho7IC>ulRk5$T7xUU;dkt@{V|??>PTE<07VykVsN@w2KP zedO#pqo)7-J8!;u_8Z^$#y$?{^wa#Prd8FSN=wuW)MNv=4QP%GAh`xiukLB}>_718 zH>Ib)+FDv#mqI&IIDKTto;|=i1e*z1`}(C3jME&3tXv&#yqLyF3aBzyKjW-2xog7B?X4eE=j8Nk* zjhmFKE`1!*KGaQN=`NYojeJf7By5h3uDQalliK9q!a?Q4*!FaG!N}?6p-BO)-p%$gOb^udDp&r5&~BoQVsdX*Q`(XcHw9ZnBffVxf()yacIs4O`b zO*(lmYWkVgfc9>>kVZv;>05hy)0On{-Z^Y05tAXf$Whbd4kkaJd~V6p#b@}6o}4aB zpA|KIK{sl;<$AHzbVV=9^rHW?*Gxlo$AK<29T*?F<||)?(^2*p9KtNWhF2957&U7V zt`~4Va1a4qhE+nx001BWNklyvI^Wpkl36$4+BF zKCMzg6jQkxidU^O(b|K6TOz&}d0&!}q4mI^sE&yr@1zB(IvBy{KbDw|0mfiDP8?3i z{JO_9N$+buBeHmx^KUm~V-r^&QUg6)ecXXD{vw~jwQ?LE* zQ#Q*RsDI_D*S|bZ^Mq2&|KnFzrOtyvkRq-erbu;!cWHf#f5Lzx65MAST zH1^q0x3XXG!+^fgfH*2O9gzq^rx7V8@SNGjaQSjPGsPlfdWtTY%`Bl-j&p40)S=*ngGhIMy`&Mextu3dI6AlHs+QHQx|ak%!5mnMNpUEA~i z29!E{v&pr<`0Q*cj4js?r-Q`|Ri<5|U*sBdrWLN-LbWI^7eZh>Ey8m6+#^lh@H$tiD6Mq6(9^;6 zjmI~R@r45h(|nd|y{jBPhtVr&z*OFKe4}e-Ru>(Px@Iz&pq0IRIWR{#l;^I@fAF3Y z!t$j?G?y_QSzT~$sq1!ODGOMEMHG>Cjq&Hk#|M<9+o~J?&X%I0NGd3O@x2h*0eTI% z{V>LuX$y^7ok*OB!^r8Bk-~LVDHSb!YwujSJ}kQ;%}LKqDk)o9@*T}BEgm|~yT%F^ zpZ!>B`Y+F)&mSlm? zJDWbh_435KMH@B{J_4nqrbFuV0Cn&!RM$C4BlZbMug3Z@f|$O8c>(oQI2RVab!y_` zMWS9_{@tDR^>sZhbPj5Ez|D*j)^CMiImI*02q0+0cxeot8#&!KjDspY5|FN#cEz!vJ(pCq#<%WhC24V_t`ToH zvxUf_K90k*6m9RLepGW5?EUesuCB1O1O)e*Jv&I<+<^0?DZx-WAupz{7qqS_QmiXR zK_@63ue!O)JP(hH#B?aV!~w8tfrAQwF#jz2j&d+M6P9;6{Y$e&_6hzKXkQgGO8MYG z;Bb0o3MHor$}-i5t7KrH(NMZ>@XbI?=THutzl7;{JEpQ;jP2!RL+xHIUA!(eU8rt4 zk79el=_0#`)N}h}V=J&a=Y|z8ub97VKH@c9Y?e?5E zm&U!9_T86m+9jl5x=K3d@?2J=p;%r17J?F2?3#}?op2YxoL?Es^`dKXrgzV^7`>yr z0|M^uUL%l4Y&T0uW3s%g}8_9uD2hu_MklJ$q6|7n<+I(pe|15 z>^=hL@ujn)i|jw!6BE&=YlZ2-LmdT)5d~f~Js3=1cWiZgVj`Hndr4ei2+&Ag3W+VK z>0dinTl+Ps=^3c$6LE5r}r(=n$@O{c#R-gG0TADj#_YPxAon%oO_you*!9cnsW71VT0FJDyC zI~H{;I22{XbSo5n8tq%DyCuAFmMThzIzsT#EC@UlXa?J-##NZ!J(<%x5i^0`g%g~P zat_gOsy(c0(D@QjolD3|puT$5=~b)GoQBZR(@z_{v>4+{jvVR|)Is&Yn3w|D)Vmi9 zCjIzk2KCQ}3U=O-P6tvk`_|{TKA*HT?qJNpIL>d`8mD;1Lj}PF^jXy$;;&y#*Z+V1 z%4A}Cv6>ssEkNn^ZT6QXbMvbey?&v*U(~H#!>HCkpNtSiP=BzGdng>NIN=54$TMB5*r;=#^ z=*_mV+!RwoD%6L``PTMUEnXG97#Eqk1U_|D5!7t;)6e`|j;;#eD#jB*GVE==XF3LDJH`HF^IoK)3T(S>oR$WWNmOYrgdSgfpZIT4b@r{ z%vAxeE)0WfJ%%A>ZPr}5{LH>jYkL=8TImwNd+#%sHoNOy`{5?*WoiRvrAywL%O7j+ znAuD3PMQi*1L|6APTp5*zvw@EVR_Z9^FOYSOd_~0dqs@TnE+Fz-aRpLK*w|w$S5f_^T=zF+G za=I1Ci08%7Icv+RK8(EX87?CBW#h)Z3frd1Jl~_)qiQ#w?W#P!{`f}x>gq|KU9s`? zyyM5a#`bm{UwM45)}!jR4$(inG<8OQVZ(zbPS`|#?L*f-^bmY*&IIbe*4gEH`a?qZ z2fLgo@)h&KPzPpYRpGNI`n>_t3iEZ)TeXG0lGKO#sa!^ye#KQyl}1gk3Wyh(qV6VS z`bV}DlJT*!(B&rX#6QiQpHC8YBrPrDb6sP5S0DNK>}k~W4>mMFqxEVgvsy!!e9VQWuGPXd{LRV5{U@eZ2CmzEQ!=fAI~6d80|V`x*w zXdiJa&lx%W9yK?rpHkClaYPUJ6apDh)6sDWKnZAWAw?v%oG8b4KSfU8Q}nk!ZKC<4qjtuvX{LEXl%9%cj8J?cbC5$Wd510En<5^rYsjHb?t z{<6{G@tF_3ePoK#6`KCxAKG5epO+f$w_``y%oANF@;S7?`&3m`LpY6QOwD0_rJ1Fn zk>v2}16opo(Y}!6`G&o)JEWXjxnI`aI zaHIv$Ix9Pj&tqxUjBH*)GlF|sN}3-jjivsjM1zKRCSXtR#OcyWf;#S|1Vibiy%c;xmT)dk*B9{4Q7FE2nwZ<;(k+Ke^ z&s~B1Z^B!MUc8>RMhZ{2Ea}9$%rSC0HJu%V73zfp^o+qoOfM*d?TMC}K1uoK^jVv5w@eR-d$IQBfBf3lFumYS4-Ae; zj@yY>CMq$gV3IIJOfQp^jSdCX9$Sq!oun6&q%!>)8BI{#!Q|-*Z!~K9bG?&mCJ)M+ z&H&RuEWh{e?HO26q^3jZz4&34oKw^aetAM!q5^T$Z0&tM`dquz^y27(Yi2Rsn8mb$ zK*lL=da=CeQq!XXWqHw)krF>N&3MxZf<&dpRe}v);gHJq3_OJ7Ej69>7A=^}fYW(y z%q3NMAYfYyKNvj>Rf6)N4-4j zf26eknfF=xxg`J_MP0TRFkO(Yvm`vw>tri|%As}j7P=j28Zn+1lC5!u-k8(k88 zJKHB~-5k{6IhQ2W>iO6QZph^#VSYI}`)r&vm~B?AgO!oynGwtew`<{h5*dkzjBa1f zEFdWv2Rd>)`-Fd8-t=1f7m4Qq{Z-2q4Z}=3eT0S2X8DwiZ8U4| zreJEXR4y$Z;^rPBpicq&)e3;|GIoboE;s0IuW9*TSciKVhSM)WzFGFCX|e`^i#sLyDGjcw{@VXH35gffFyNDUC7G$KJzi3)Bg>_g-SV_ZU zJTJ)cqI3i5z`8~YJ&%Ow$B%DBGasuM8>J2X*xtO#@r~;N^5d?;<6YTZ7uFv?zJ4z& z9bdn3@7U6@RC?%ShNqU#ODzwmY*2SmjlI|Iedxi59(rgm--2~ZOb6314{AhGKS2?x zj5Ap-S{l!&i1&~yDXWX*@=#feeFIwZxSh#+p}$OEy3+PATT^E#q(k`5tVnQHu3Woz zWudP-JD#MM=4QoUJIGwmjSrjYT72g0BWFK(?VS(Kr;L=9WvBJ@)Rm2Ils6q8OlLx9 zJ`yd3jN$cY=^82cG~``jP*lhr;q&VE;befYwl(^vR-A`+ZajzLEIA$Os+U@7jd|6L z*fxaeGI0brFiIe&J7f8Yj(+scr%!zP0m+(JlS(Kc1=Nkz<#JGG=Akh7csRaA}L@}bKU%W8dcQNPX->o>)R+p);L&W8H`XBX}9hQ`CeYG001TL+CCafMo z)z!pL0)`U1DI)#Rs~QJJwCkA_sag1}-9_7f{ev@h661FmKl#HS4h&Gk+ccxX-w|1L zg7K&01A3eGJ%_r~N?1!q1yS^S&H7x9?mOY)2n@G=it1K_r$v2RmUd88tDS>{fMk$X^kd>yj zW@N|k0J%1fX7cuNyD))+oApY0?~R(??3`ChL{DQ6b)9wcz0`$wqLw3{Bcq%CyC&|1 zz!xO-OT(X=9F)O}E?u6fj>P}SFyBaLLUw|0!^-V#Vdb5r91UoWbZb6F^k;&9lb^4T z5|K(%;PnKi)9C35q1FC6+EVIEnJZqT#{B@gC8kqm8cvFOqz4Mk^AW0P3k1)tSur0%SDp)UxuJ0j(rG=aD_U;f2Wvym zboE?xHB!15UBfgWVt*EO+&7mBQmebEfpsbBr(}cSbmPLo?n6Jm|CjAL|NaqrkXru_wGt!T+uSJp=sosI=HmYat^eQFDqrfH|76C0o=LG8 zvYA!II`v5V&JoG{B)@#=VL>|Hbkk20HaDCuOvmJuM4+Mq7_Dkz!|BD?x<%}KIA+7o zd`S3!DC(RAGz=A)%R*AS4&B@~vw-LjH>8d~g?ls7m5VM94E7Nj&lNo$%^hgf#4KtR zRf)*It|@?S<*ZxICQ#{VX_Ny}!|#ML-3}wGm~^14C79~KPZl==L zbLeBrC8*AvgV!ipr+^iKU3xk*oj4l%QbQ_j-ToOEFqh?p{-c+eTT3l~)fL0HTErR_ z>&nQ&EsMx4^N3B&B3|8L9N%A5)6McJEH|rpDcojk`=UdaW^K*;1@DVEnQ%q`zr(sq zu&#C3l_@FR+%%6RXPrB(FD|rSnoEewt@#6x&TF(@hj|yY!j~9d2Gh-Eyr1&$s(~Hw zNDbwQ6@^`0&Hgmxtfio{o5-cmrhXeFZSF@`>yUZ~>oYGmAP*$~r z%$EjO8#4>(>385w-`O_Aq+>4E@%6I69CdB%nz?>sc9y99!rrmH=;#;t2Gck0JzCi1_9;)D zSDu>XYRP}}!F$lpAKJTj@7O~R?wxsb??W>UrVHJrre7ha%d&p$Ue{O?{fA@2ILg+U z9k1l{EkzDo!mu`YNi<{I9epj?{8iGiHWYWb2yxi5ya1*pz6k+sE8Ft&))!_w-Pt7O zslPkzavYH*RaHItV`GbteEjiZOfMgljnp-rZ)(~$l3O;q@%THx7r8feDsHhkbY7{P z!}S=@iOaJ(=m^wHN=nNyz4(XfPAI)GwBoAs7cS1-^#F?V&(A)qxT}5sbA^5nUu-O_43X~d-ibLqk&XyOx=xP7N=K-aSG7414;+lq=Cm*J2v$9@A%$D zrMsNE`1!HlpE|X0BCmh=o6pVv-OJ~mK^<;|m&1H>`|;8A^k{DlrJFOGF100np$dcN ztd82<963+{&QE^whi&!s&QS^@ znlkJ5h4JHk^u(k2)YJBmFGKz!)C|bt_&`oia5@x>5=ymY56w_f*VI()Kv$=%6!(c{1k3`+ z;Uo&Zj$-PXnjNh>P_z9)BO7SHyQQxsfZTX0X&dD_qI;AptT{IPHoW);M(V>!+r&Xr z$6+6AFZAUls+40*pt|B-_)@zgGjPFx?buk9GOsBi#Req-VUaCNM*_$Zs%+yEniuNd zEHgZ#nSD?3PfN-2ZH~vE4yPxerU%sfF|#YBfv<93QaH3jT>zNQo@i=k)bvdMo)$!Q zUU9r#LYn%(3-_9wmj?iK<9E3vsY^;{C@%dmLeXzDP8Vu5rJG-V@>1V=A5o=7`gn5bZ&Xmjf8&rRT*r^I~4rN9YUkd>tXcC z!Cfzy$VHIc`Z8iVp)8i~1xUA-3)8>oH>xipZ(`0r*Z%X@mSB2Wj5j?fE@o#i7L&l3#NYzjBw_BJ z3;}wBm#miQC2C4dS4U9(W$`_0C?a^0W<_*9om^9}CI(DjyqYRdx{x9vhsc`_!S_b@ zQe}#uu6UVQsOj>i_rAEK_)Sj5OA6px)N}>37)-a4Ue>MsmYtg(B{iMO&{=rXr*8_u zn?CeaWB*ndqY`IkVc@ZSd29cii@}` z(+i{yh{*$EVm!>swK0mB4-CX6bTBDnGAJ=Ha4;%qxmp^jf^_FCKi*ofpuiZ>>Fhdm zHHEET;qB>IP!J^&U|M6&c>#X|rWf-`QzH7~M=+*ej_Hp)Ztl|oW^1MJt5W58`42+P z|Ht<)=k#xX`>DSK(=o&EXFI>Dn_<*+d-L84E3WZh_Va8UKKCyDuP=?7ZqDS@Fk-rN zbR(zJ(MUxKix<<@2>BXA6sB||r-SMMJYEybCx*~*w_qGmMX1JX=oiVHg>W%c%_UUM zB{Di{HoVQ}5Rp44DFPQaC7uY?JQC<$k}km=3;ONce{3}mgNZSrv4N0h z%$RYvERn`fSPPo^Dy6_Mi&(Pc*xjpUuin0!R!Os$D57Q+(KE;HUaTo78$tzNa%`0( z@!EC{3lQAMb-q+ks+gJfb&8hBV4rhHppi#Lfr~NeM)c1hnK2nwN3ho*-33C=N#}@! zNqC7PGaXvjbuXqHpD+oO%e0<2Stm2# z;wy)i3)8LBmG|in7kB9J99I_UTSH4Vcqo5u%vH{=*sz|D1zdF4Pi)q=UX&&g?6*DpLczIP+kE==Dz z_L43)qNaCoU)Iril!ljQJMg^hef;rtT+{Eq#>@FYeKVRUJv7ZPt7sn&rh8KS z8`j?WaAj9)c7@BGO)XzM4|9eEG<)3DRXvT)(bH!>e&mshuf6uc`H_(gO-=p#X@Oak zcYzYpcRtuKs#x^U=4QY8Ml9N3dP;qDs|Rt~8jV19DLpdx0q@&-_ThRV{O0&OPy{qf zmiV)RF03!!LES(JM*x63&M=2#Xm-?PWgRWQs_Fc@?-0rO!JbwmV7)T}w2jVV9zAQ?;jX zx_!EAo4Sg~-^i0Sl01XUnmNa|%|H6^hu{0&4?q0jk6zUTq^0e^i30~d`@^eeKUV%C z110^#KZq(zvnra-SHS7vx9xlMo&yI?H0Bdt4mwwnh9gYJ@sXJ&JsG>Xo~#E>Z;ZrG zv*pP*-u(K9o9iv8&dm%*xUU~+Y$0$RHs$RhsZdQ^4W?J?q1He&Z}y<4i_>ey@x9d4 zps?#c-d0i{1FBL|NP6Mt(2B4Pm~`VI;I@4#c{y_}JKax9!_TQzlxg zVtG;GWG1e0j8R#!E&$!wUZkhf=4dAIFW!?6G)~MSQSj!N2px||Q|E=I`Ily;ckI=%e1siKeul-zqaD^QamsT^e{^Ct2fs41XOcPyy(e_?}aaYUT98A zYXcg(}1aMNaxxWCvF&Mouf81z&L2G zlg2cz@JG!6F=s&Xb$?n-zg$AMEiV?w^TaUlq@i^B1##mB7~RfA7m7pVGLCa@k`oQ7 zbN*|%G5`P|07*naRLcx4;&juZ`>=wG&!_QapUhqf+o#>9{zZn-X^wizfcm`%>cVxh zT`;};_?F-`s#ukpK6jz!8N313P>7=L0`(E(H9J7J=gAoCw(d|_sA^c5D6HuY!LDOs z86~oV>6A;(nvMbHdOhTNqr;2oHM=n<`v=ucaN^{@bW6_HYL`4sDJLbQ86iQ*v>;F3NpMPVVoXLd+2$F^1w1>Z zm&MB$w{HsUrrW2~bd+uW&FMeg(1OXy#5f>5g04!C{d;TWO{a!5gW68i^qn!uy^_;O zMg&ok3PPawp+K_AlY#ehhLzupJ}7}6(@Xa()N~W{qCiH}bWAUhcp%<%G-&~O_blRE z)@<5z^;gMHkw}gGCQ5+>{l=fT{EZwQ(la9BFqW)qS9A*xqb3uy&wsmdIa24m!<`;BU}b{&Fxn z2jGvMtt!%Xj`t8ZvwQ90wTp}KM9|Qw)+JS-kkzDt434 zHIKR*H#>toBlg!A)>mP4W75GBn+jMoa>`Sq+fmrj$szhA=$vk(2;{sD%rB(k=oQo| zeNpb3j2QCOGZdPxK+EK0gm+~)GX1cB2wpzt@(a!nF|0Mjwidh_#`O{{E11O==?j^? zD6A_cKjjL3HiCif0leA9SFRC78yweTuNYctW4MvqrKNL1n=zJ^%hxqRy0+vU{EI>| zHwez6seAN{I(gM}kv!KqX^HnWeTmC2gXve8Ug|as)6Se8qfJc}%|7#JCE29^^?XC2wRT*maV!mjlfTx7HF-5WdR(=>i!Cf@X;d-pCyO&=4cFI~TM?5Ne^ z$kNlTMx+9FD*)!i-n}kdFR58wv4pf%G^NGkPxqubn;S@DtOSn2LR*U3TGABQC{FLp zDh+U(Kt?e-Ws@G?rj&-fzLkW;`=mLV2+VV0d{DZcCz9^<2f9WVKl1U%XNq6@?FSo1 zc5FC*ewc#B4Ws?%fAQLDpPwJ?4+z^w#$=>liVFO&N2JuZ4h#?=!w{*LG}f2Wu|8qn zwjMA&G_-lFqGIgxiBmT|@Ug;Po|QY@#&n7y(P}AhRL+Y+RvaX&;1o&8EYHH6e*U9R z-}&_2kJxHtON+x;GuXb-+$}f(3IFl zR;qURC1jTJp5a`gCE)PSWG3mW zwyR7CQW`^veIZ3%UY;sPb!*E2wj&yk*4MEDgBns^I(=`gzqj(Hn-WsHd=y^4g4B`G z<#Z9E+d8_TQ^Tm2ak?m7oGu#)9IT6OL~6VaqVqX(M8dj5I`*PPBK$9oD;zEc(x)j*T2PSPX8KsvA2OX}38V#Zf~qd?ub;HOQ;Q+*Tr zqAk-HX@z0$HQj-fjiRQTH}t0auIru#?NJqpu5JW)Dd{-f*US~7E1l*h`yXS}nw(Y9 z!Kmprreh+(^fEyOWHflbnD$1*GA@>yjyxP3k&zS^y!GZK{~T>&I^J~t>E4x|ykJ3a zU~qDDa`5EAsp+c?rY9LSy&zE~ zq`lA2Klpskx%T$n2x8d@WGsk4P0vXG8cj%1(`zGmd5acBb(8esHN8ybrejXWo6fud z9>?arX_mZ9xTC)McXFl!zfqe4X=^luo(`zXkiTdeOgwG+n!(;^VfvE8&rvH1Sy`mc z6*-2VUbpUPNZr^7WFHomBdu$}VF3yYC?KVNG>I;*GMfi6wJDH$c`zsuOrL$rPULiX z)6>&$*;!B!0;n^G8M-R{Ns`NWVa(;c|oNwl$rg&>R>S86DrZRA@{i)Q;i-*Yph-S94K8It83KyKkoy zQx+8zbu2HeP%MR;58Dzt*$UAW1GBD}k5f)uaGX?X7#VFH3dh`1%Lh+37E@2UjssfI zJ4!iPHTR>9Z(kKXd-;;tq_d!}XQTu2Smdo8V<(tG)~-SvhsLqpfat~Rs6SB)CFQsr zTYI-^PX+8;V0hOofSqL$aExc=zIG-f1UShv!<2*eO894ZT|An7Tapt8j1xVBy+xCc z9Lz7qYm=@(Ms}UZ7xeZdWvXXTI7*s2I(kfoz}AQgHQZ%lIN_^%AVP3d?$N z*5X?43YNTXVAl|_b&Zw9!+h(~oD8p9c+S#A+-VW~B38LvWj9Z2fV;z-d(Sv_YUFg* z<{`Knh3yP$E9Q##s2^UTu zk1h8JbJ07cv!bcr2k%Q~s_8OjV#%?<@KYHpTKW2g3$MR);iU_equK8MrnG+Ops5bK z2&7)Aic(Sy^KilBJN;vk44s8khtfB+s14V;IK7DV1`deQIjOF+QjdhvTLvOGZgh8T zTwe&Pca0x+ja43ZA(@wt(I#o*#`21dg;>>1f$3P@@r`>oE~S)o{dQ#arAwDSxPE-J zDD1@8(xs1s>ADL*AKSQo??Yo2lpE8_QoF;E7X6wUQX&~?($hqOOIU3ARb<4+yB$Q( z_=QR!?Q3gj$#*xm6g3P>apw<*+O$^Cg2tF1&{g4dPj%*uw1E5~g3}A#h5p8yPKhEF ze=Y8++{SHTqq`{~edP3OIMH!PpWm=&Gd}6Ercp5co%82MBU=s-1Rsf)7$n_)fc$W> zUQ&8U6A`6XHXhW_rT}^?+)zvcLTVFt^BEp$rgppE{@4%!qo=|tk zMWUwPIsQQ(m`+;9KW^FoQSr;ad->(%J2qg=-qzF8JW38Cm=2j7^3*@+zA8hp!&kf7`Y#A3popAAod&=_u(x`RvgX^Ek?hoIY=+^7KX7 zK=y%>l15Dc*m`5A9PesNsgUgY{=laK1>=SEMbL^wAWi#qdIHHJmNkEfzk7uCSC zr=+Jk%;oEJhE=MoQC~wOM^XHo%oNxXrk6DTdG%=N&jRY`=_xxD2w7K`642c2!kmsb z9ZrYT1?dWC)HuO6zci$J%JxDeCx;)DYtPgKNcXQ~{@c*kmLJx(wt?dzp?W7MBcPBV zg;`2jLUt2xL}#a;!`DDKotK#5WtO6>#}i>gh-IYQWej!^2RrX*La5~QsoZq>a9W9s z_Jy44Q%3bmGCG`0XCY&6vEX!y(QRTCq#I2Cs)1l&95PpX9)?)m!sA6(!|Bt$P(k_y zV!u>2YTsez2y^J^321}LfcZ(w?IHq}Qf>rw>x|k_Ei;RE5#^#U>DhA$R+%Gfx`Fho zr+ro0iFdE2U47qu1frX9BTbIj15rBPoV0x5O$+d8<95-OR2w??lA12wzK<*zo<@qi zRp82mpc_57`#$y#N;h3h+{b&O~26)nbX-W2g|X-ya_Kn-M-`?;flbuS4~$D>0;ZP zu5wkW=}9f=Xm5Km5LUjy9Z4G2f!vu>d4K={bZvKYU^wfuryllMb2Gd{p z{wqhW1=BIZBB)zqM)*}GHGNNb>NoyLaBfiDoWJr@{GwlefaxOfk*ofsn%>!ISz=P@ zN*eypP}U2F|;%5H8TKVx>RczUSZ}a@lbkgv>0EwjzvY@aD?<6 zrq~pL(m-jkN`oy{uP%YYLxbB0 z(G8XK9VIP}te577JX(0w)E&x>@dei zS63s{mqiICyEhGIkl>X3zwCKsEQa#q0r3iN4VRu!_u*0{IIL7VU zS1PcEjz=xN!gL@#m7X$mt^tl{Iim{F+!DV`zsk0ibaPtSjOhhM)8CN~=E3PO-~Me~ zqYtB|pS}3nZ-2RGWX}gX&hPlu{yif*#*c&Pzx?3*s3Tv)Q&N-JvyH?>AWO zgl}+tAN}9U!?&R%_k@PVhPjTWRxCx?-gV?Gn11%aWtcus>4K%zxR9l$tEZ)t8q$*1 zgz%YTqfI-0@#$-y{@X`8di)$MErsBvFujTk8V~6VmxiQamm|Njf%dBuL( z^iPiW^=-d+YT2%c-Vb{|SWO_~t+PMcuwf4|Euk*w*r*%ml_Gz|$sikRPtGW+q`*uL;a-=V_VtZ z+L~LVEJl^UO8X~|kwXKe;WH{!F&P;Nr~~OF-8lSG>JNPL&9A?C|1&lGVC9;TnhvO| zjFp5FINehcpF+E%5~=9|biInuk`wvp=>a9=-fw876DgEV-V6S8VqmIj(&`fAd@12j z5CN8&*f{-~Tedt5rRN8@IFRB;CnEKDN=x&p--qP|P6yO^@#?QMQkPrhXm*Fu_X{x{ zXSyie>T{&j7m>Q9rc*)+r!(Jjpp@fbK}z>8b+i=~-BH=xw!Mv6WQ#A&qSzH0N>$^H ziBC(()?|dB;~5Dh0ht87@L{O;3kVgZr>LzglM8a7WcxsG;!|@vARHgju*#`YA#eaxNhm!GQ0?r zv8`B0JavAVly0u-%)3m4P0LO&y?f2%8tmtoT}~ZVbtps(1xrjf=hk&e=~m2(@Et-o zXYepvFncFH*G>WHU)7nuuAYWDeQIyiK*{LomZGlZYc_Qc5m%!oq}rrj?Ilp>Jz9e}Q^ohaApjx?I)(uWtYC2wPT52Z$c;ZmV&ZOs)o=<;1{pmA{w`W8p z#w6d8l(cg}$W9viLXcv$|(> zN3B7QSM0hmy?m>d21-hm;T@51&cO!^?8xauLtptSlZ6G-72-Gqr?Z5xmu|kK%X0ug ziHw62y9Q-Yhrr2XtR*(xpml#T|T!v%5b=;X?HnJtHl>NRsvpD~N` zxvIs_PWdLu=g8I4sMG25$tP3S#K3^?>cw}G_qghAN^_EMzZxmM9d}AJ!Z>F1 zVzn#MQ;NZ1cZySE5)+wCMxcMwA_;p9iRdxGNy!9DVqQz+z!|+mmBT_OqPU>o#E2Xo z%d{kk=f&m1jzHf$Fq(aZ{&Q}p%@Miq$D-K|uMV$00gUO!C67^^nF$tkrU2kMGXmO` z64a<{#^~r|&Ha<@pOJ;+Vp0;~fyLMeU+pu`VRf5}Jh>+1hNx;$_`; z#n39Ot#b{t*3_9Wo$YvG-)3~{Zr!JSGQ;ekxdyIln7uI9tPNP`ZFbq(an`W6Yqr7J zWv|Eky8fceuUfGFXCLGJE$HN!KK&gb_2DY`!Qr5xkGsF$G2T*0NglQUOQtonj-otv z+#vc(koxhl@@$_XxpFD03(rj;vN0joGhEsBOl4V9SzUYyZ4?vYTk`ty@)~3c5T+wK zqEXY@leVNS9?C}%(>?K200NHu2u8k#qd`Uex%d$H$JE%28WTr-bw+ zE22@@ZWb=3(v)2B)R}uZI+xm+=5afQ8-|f&D;xT@-?^o&sG(?OktZN6Q))UPl{3nH zn)7i6so$oFAM{HDToI_b9BoaUG9AJ$Sxw@8}NxT_o|@>6!KeB|Treti1kYrj0t zbcoOqPcGtYk&Wpdx`Fo7yMDlf^1e^uDLvIR&#bTRDQSfQDG=l*(1}@sxNns9+v@kl z(ne|JClkLv^$0d@S{$J{Yt)-_$Sh#Mp`u5>D%4YS->RC?*m1PcC)C_~=RW<6Ps`ZfILHcHdb~?rub~$GrJ$kgfytC{hx~Wf)!}!7HyOu4SICSvr zXM65Ed=hhd9<#gZ1KS#FYDU9cVboZHj4HV`1AauJh0gpgOA4e~KgBb- zaPk=u46BSl_H>*tGxQ9Rm->;RsHUk< za7i_#m2%8$=N(jI`URAv#fL)SEsf--n>tcvu&ududY62G^iqB{%%f;$n0g|1~)Ivcz*4UG)8e zVf2$P$c(;>T1^ILHkb>_FFWa~_cqtLVN*KfYpLjn=y19$Foue`ezmU5`68v;fDD+M zFV3dM!kfs^reo*z_&*?9A^Bqu*jVo6a$8Neh}|H%NL_~Yg=p{MYNK0UcbyUSzlxHM zmd+X1q^e6;S1t|qakVwofVfZLP**;qQPa%^bY@XMfbE5Jy=oq;mCXb2&G2Ouc(%wU zMdNV)jSKO!3(?I0(-*EV_fU<>W)a`vPxzgCQIHir$*}f&uKj~r6cte%9T5~ko=Q|i zi2Tr~>5DI^>2b!J9vzV=Odm|1xP`tzTTzA6x28Y6>h86|^rTzJEfJ=NgcN}4iE%QM z3)4w@X~#1U1k3Vb#sbsA=b9nfkOm6V*Wjgzvr9;Kuk8g_!SuM~tr_yX^xpbBT4QoS z6fPCqBM6z#_vW0FJN)V5+JkT`Y>jUvD$sb-;q=9L)7LH`G*UV`^_SR3VDDKJHpunD ze^*&vbV#DRI|Ma-2vYBkVhg-WYR$@P$4VYCIXTfgfiE8XMsLIggYJj_KK-s2({H}{ zt`~DMNQMW}6vju>MPP&P!MH)Zwu6BYIY}5?A|jYuNKGd_CnPwAqY#6WiNP7Sr*GZ4 zbL&pL>2Uf^j$a_AFM!i=z6_zLBcn$plQXHo`vt7?{nwA_=7UDkOKR%O)BM4I>Ruy} zbN2oBX#*-T{W9ChR6xtow@n(O)-|yH{r@H(`85rRKSwQ;Zqm{f#HhZb2+mm1airs3K@-OqBE=jXU3Mt|+eEU+41>l# z8;u#mHx-?x(o)<_hT?3A?R@w+e#FCpUF_&NIp944do5mcwm~Z`RD7leY-iPC&83e~ zQ(CM=OLB^tF_4;wzOKj^{3gl7(eSBF%AoI7V%#7w&Ipbm>pg~}0l45H{OdT|T8ptdSrkI3U&p~`FaT!TGP$BZnrU`dZRcJECd6Hy~t>!85-z?{F zfQ}gG<#L6Y33Cdqs2~`y9UYxKm>6_*g))Nc_76dzDLA%_ABNU#DmN&rvr8w|v=Chy zyFqH}(E@IR*Vei`K*KD(^kA-8>v?h8tYn?pV!Cc81!~SyQ@5v9$#N~OG6tedn?-- z8rld>_s=rj7QplhpTZUwrV$X2{EXHT|E#n^JoSay73FEo{{B8`Vfk*X7)*AUhU6dU z+0llY{&DfAzy0O;p7R@O>UtV;iK(wV{)^vYS3gg7OVwx{U91j>BZ*~f(T0d`J?7VV{NKd_W>a?mY!SqyqJeOg5PfJNn6_M=@_4l`+P{7J(fP`T&khWbiO!3tBBUi3s4q#8=i1?Es5f@mNB{sJ07*na zRIDUMl6*sz45uE=Oc?!z)bxqZRYAIJV&dS?xjzitaq-rdfA`o0%;_oH4m861t`p8G zN%5RQEldv}*^nVShQ|Zc?h~We?<>`hv|=o~-{l)GP9J$z{Yak#(tjdISGdb}zVqP$ z8B_Lq8lm&sklitpGoWdbOCapX0S_^RJe|W8?=-~e8wp}lLQ1AdsXv_F>`+Tm|BBMI z#>Q9gc=G=H&)mPoL-l4#io|qAslP;OU&0slGXz&l9Ly&$c|-1a)Dfr^ki(Az^SP=> zM^q?~n^HvzX>Jv@0_@V}&DFjwU9qkQ8`@SDwG>wJJ2UPZ&o)U+_wy~GD1aT>*O`i9?@46j=6;?DJ_ajk0YPhnFiJIzyRqi;?txqqdt_JCODnV zEe&_9Z3wMw@vBQA1C{9oJy(^`F1vh*2f4hiEM9p{GdlhKc&|A4p!!i}C@Fr(=~Ug~ zrf+eB=q?8bPdMI??*!DdN{J;3wf`EZ`=~Len=>f=Bm*-#BDVBg7}O$B(WtKRZNBWY zDQq{;4v?dkb7o|8!{{J7o)?xGW=F`D=Y>rOUauGyoL_J2-RJZsYqNnB2q}CLx-$aWcdFG{|!{(CEWqUCTzIxw%1jtx$JlE`% zSX+wvN${IDLs>KC?q$F;3+$JzH$;P$OQLkvR{^T7@uiAXo|(-VKMnFY(Aj~U&Km-z zbI*J{>&rBaz;;iXyJel^ty6}&@SW%3iv5F{6*X8KJs6XbK{ko{+k?JV7t+aSsp)vr zbrBsg85M=UI$4E}hmvkNxbyj(n<0X=86i6<6HD3}*bx;>Q=VHA3&3mzolmEPltf2z z)79e>a8|mY2A~cfhpZtwoxY`kYeF`mrd!^0FdcJCNH8?_v#EVy>jl9Y#|!TjZ`9DHf+4~nv8PX)wxCin zy^lO{ZC1Fl5-*uvkkgH6JQJDwr70=>cWQ=ogodSm!N5IZwuG9_Jm3q1*vCwBZ+Q4o z{ttiQ-v9h2T#7y25U!EZ={*{uWN|2cv2=8bN2R07zM=?nSe+B+!c@E=hRTt&LGalG zreKXx7onUSY0cDr@(Kn{TG}bC#_z&r zl$}aO3+Rub9OB1j6HOb@W0=tqMyHsOk~Hno|bF z;MLN-!Dc})A6^}0qe)jVxK6r%aE!@nNsM42y}NjzqFQjR)W#4S4{tLg;820QKFVJN z)8*npcyA{U64_r-FT6+^p~_n$UwSgBj!K4!vEOtHDutK^yv3}BT)kXt-Mk!UEx6Sq z1iI$Z$lxHb9%^{nY(wm9@w_pXh>FdMa>JNm^mKW}<$3Wg(+=2AXD`yjyu&=JZYew+5qWR;J+`duE7HI8G~a>B__FLKCBBq1zeTP#m@eDP@tIjO8`eJDfMYf{GbPtE z;8ukk+Ziqc)2oI(DP{3)$Q$^F(zh$KuCL9A>G)sz+KMWH^p@dDPZcClniXDNnh@47 zFpm4zx5b^^*@VG_2zN|yOx?{lL8|@=SFg;&Vv^UDb@XUOdFsZ8yULd;8>Vm6Rdjsg z`q$SZrZ3$~w)*<@c-D`aoR>>t`mfh}i%9J#b&}Ti#)9ePGhIFes5fD3ps!H_azAdI zHfAj(Nw!roSLvKlK|w7ZpwgB~OfAjGkzibj$1l9X38hu~q*kPb`G@+)`eJHuxUn|7 z-R}GYB{jqEqoyCh;&Ogu7(@3+XxN6j)|JP9@q3wGS{?e43 zWT2;76`e}YCVjAuM8XuQ>GkvI6gzf-81u(uPXEIylB`0h=}@{j zJ$|$~l;VM!kEEu5`p&x_41D%zJ|cKOQ6%v)bD*Zjr&UE3dNBBGbf;mR(4?rmeBQj$ zx|$0FGQM@{lMA0PFF5t-ii1BtbKs+k&yn@AxJ1e6V0z6cZG6-bRGh8~PMq25XG%~v z0E```oDkt}ZQB7^ z(|h(SxE*I%E0`Yd+e|(p2<``nQ*4ZHCJiR1ZWKM8Fh+7;q^8sD$SCS)>0xQ1{uN<; zeRYA@-ckHuD`UcP%kv^mR|VuURA8f{+ej`hx8U4+WeU-!76`k+ z)j7sTV))l6>eABTa!?&0W{GYfjsG#D8#JEsx#-r7)LhaEh_rFF?3}A47a;xc1BVTv z8xZG=rQ9}OMn2aWdb;_t)=}3ZgXxId*PC6G^@T5K>1Ix$OC}`vz(wje!NvxxPc6fp zjz3*HV^cY-Zopa8t{3d3biDRTT?f*Y5hKEv9o-C^=?p+!Q8}hRlX12n-izOXbV!~s zcDZ2)Fp-=Nrq8iw1U!Q0v*BgY^h6z%$Ary)QVyaA&zc3MqpqohboXj6rY8nPbqB%e zal-Vi$mxLk?WpPLWUUv3s2DP&fDS$}I|Jctm3#`*trAj9FX-B;A2k)ED8zWM;q-zC zoHgp>6VYxkefPKMLON>*Out3J%E<>Odk^-aruQb|N{I@I3OtCOhaDV9m+2*$taf91 zk(w^g3u^k^MokCK(lm-1(#enr`Y_Uabn8~s^qoY$?4&6aZwB5Ll3q~M$${?}+G;R;mZWq8 z>eu}Bmyp5-2zdiesV*TVtk-Vt)${x}HcKimEca8gK#lx{pPLiHFb zFz#M_w_NEIjV_j)E>P#!iQg%J6;#D)0;eM^1LtV!04&)rvW@FoeSwVN%xW;UEZ!hE zzm7zygS^p6M35VQH+?-}T`(oC_?Q(1#{&yaa9UWT=yO^;g z-D2?IAZov3$nvMKIfz_GI9;@!2!Ydsi->>KhohV0bzxO8JNh{TOxFq^I(LZK<04?| zL}P$sOR#=&9QVaVCnX}W$5Hx?zAo!Lwj3F9*iC+S*i|(v)!+`^4OP5G^V^Z09FwFF z7$&^-dv1W%VsY;|tT_egUSKwhrm$Q=nzty2beSNHH>a8(LOLZlkvsu6gPMl^HjQO?TlHbTY`9P*?K8@ zYCZffA12DhoJ~D;>eYFdct6!B;G@GI^?fkhcOkEc5XCa^$6eV+b_L-jEx!H4E{>0n z;#H8qN(pJ+OBZZ8{Wxxsywz)!agmVVi^rt|lX_W|XTt{E?WpO<<-TRP?xMc7yuK}W z0P0)XkZT*LCgtWGB&mSHkh(if6@c@?%fqu0{BjejA_ImiBbz$2nzGaMtevUkK&E!W z=;bqJI2(w9tX#=hzqh>NDETXeMPuczqV*e(=XLed^5{60bsR5Ck3YD#ki3_@4}t1H zI!tbRT$Zl4<@5)yMM~E~-03s|EnQ*-%@w7iuo^9XcAO?T3khW1AIkI93HPdky{Q`h*&cZqs=?f?DD^X`os zHtcWQ7f@B^*?!^kU%vL+UyMgKhPnIWQPW$;x6Q++P~TeJGceGaSxOWM?SND!SmmHO zeGN(7_?vt7?Tg))RX%o}c0)HR>IF=vLnrvEzo)Wqljm5Kf@@y(Xb={wgWDb8Pet%Y zuQ7;Z{AjrH0K2fE-vGiuJ-_92(qgl}%Ed`m7icq^8pNiuv@+$NfXMZAH6MNY`?nVE zy7>9;7m}S`d~oRJZ#GmOdx0X-_cqtnh3^xl$A@;IrbFo*Lm=u9q(+&BdQqx-Qe;&L z?>vg*y1ZP0Gh?G;V`%J^MV{=~ZO^{?>K{I|Al-=R|Nh}-YAwO{`Z{FdlE!`Wn13`5 zl!(#82vQ8?6;_j=LsK6rG@WUx5a3n%RksY3_~EFb<7Q{6KMoi?Fv!%1>V7>3wmf4@ojNNz`! zcMoH$;u%vcUklmlssbSUh3ItUr>oDAMd8r~6-TjE^^fSWrVg`D8W(u#;#1d8ELi0?>T@*m~t9%cWKu29{KvhTDRm`x5aeZ`a&|fNS*yO zy1KQu+B-!b^13ZjpR4^apnVejzSq21z}&F8vK7shsn^cqcs;`NlP6VsdQ!f2N$L{S zts%oY^A2m+UKXChqHtYM-+CXQEn4n0w8+{bzg8tV!In3X|igeDSeWgHch3 zS1+DGRJPRgI6F68|E2lIEHyo3C%rUb^RJy*45kMiDp=65AY=hWn?#%MBww9Oa=g__ zdQlfr3R!g!nZi-NJ6Kg{syM{S!DRI|jp~k&>E$$}y|%Y|no3Axklmi|jVZYG`CBRD z%!nY@use`a(>P2o&!?*f@9Fkv+&9yigDk+C-t9HLsDu>L3#DGB0F&pMH4AI{tT}ko zyEn~J{iuO-?Z^VEU5)K!lfo+((coy>tZB0_rw=A#P$&IeS~_C7Eb7tG|G50?Uw`87 zpMK(vC!P>}2-MXf6&x`ZV?e!kB4RQKqkl1Ve=*VEmmI{bmz)?Bhi5&gdol^*O!|vI zMoov(cNW~Tb!P}O798lx&g7goCMqV7+EIojrt>!bEtp>TZ!b*GygO+A{FndXsZXBx z+5ckv?0?pzmNTozl;TAQD>eOJM$ltYUpiu8`tMHv(5(Hlf0< z!{flaQeP0y+iO{iWoYOY(}LVNBrx(wVi|$*oOOuPwdtm}5e26h)RU>mR4XND9LZi2 z1D-(fEHL`*vuQVk;UtGo9Ec8v1Kx(U4R}j44`!*+!h^wdG;yfh#5k!DE(7=u!r#V& zu(_$gf|Vfn7_y#}U6hD*o%N&m<^j5od9@BJK>b0aw_pK_Mzv2?ha*jInTjw!StqND zMh+er1+H_==;%obPA5*?{t0-Q63Cpw)k|n=uIUb&c(pcb8l_rv&SHVC7MlxeecjX} z7#7M4i_KM*YyB&2=@u(%ZEM)iXXqQ2x3t4*&Xdg2m)F;~(KR#H-O@t1Nu`Il7Dmyy+Zer%9~Y?8niOw3 zNiXueT)1%j=*+RawMBW``{LutMjuWYZX0gObywA(L5>rWQH7vh)|7@iUt|>eJ65(; zdgLWxV1Rk1uMa7`rLrU*y6mhdorj{{lv!5di68dFH&OJLkk(YuNt$_QYItgDCP%?$ zq=r_yT&~Kz^_A->!aJH>o=Ov>awLA2)15c!<9<-Zq+|G8I474;O^)bCdPz$s-bGO_ zmcot+MoyRqA3Wi5`plS-5I~dl&dxd{W+YGA+q8(MP?#%0u`NXbV0z~a_U5XJ*!&g@ z2t@;G?ATi3+d0FD{k~}IstRW_YP!===xKI0JA9Ey%l4h9&-I-B_~Y-Mp@#JQj^Xi| z{f&*yDP@t{FHk~?>BW;D=Iq}L5s2JJv`Y`&f=F!XX>BZl(!)?p8JJYmM2HTY z`T4QsM`>}iaN+#l{qD`rzVSHaH1@!{jTE1o+lpyk7#0wKavR_8u8KW+RLL?@(?5N8 z$3Vk@mT@<4q@$|JJ?e@dA6NfZM{IT$)twbh*@WR+8?3KKP5&`n-cMcJHSzn;^Nz** zeCXU~1D`87{qUVVgpfbGt+l4#WiXv5uYY*v4}Y){7>(cMCm-&wtAnKtrMpWU*t_TXhehTikJB)fn$4D!`V`(E zM+vqUYG8Sbk*~>m_iF^Zu?PkDl~!jncsnOFyPCTLFlrUo}$B%;jr@FL0REdl3nkv}3s!GOh1-_Kk)}vY(iG^mWSK=R<=0v3F)DlG(|3aW2yJUsn1ap z4g!@BOw-?=)^rs`q@~pq)pFvHH5r}M)tZ-FgH^;0I(b)%(7wbBd&g<{)R%1`h>{h)kuR>iwXAuH3 zq{wuF5m~=`7UiE()8TZ9>5#T5A&sv6`{iGM;%mQo;)yqYBTP5Sr&t|40;$ZA{tQ`M zVh*=QPXr}X5Gc7&n4Xi4DVVy_S-~+B-o6<9q5>Hur`wngk`r)GEh&P!a?_b$u*=yEeSW_nk_!O6k-6Tf-)Xa9@S&)(g^KV$~~EEy)S*-lOGyehnY%lv~+ z{qD$9PeuRz&wloAK>g4DLrjfhRV(us=@Q%j3CK>x^db=dRefrBDF@Q8Tm=f4QOCXi zLOgrwj6aH1zjEcvZXrO!=Tg!c*t6r3(~DI(D#MEc)9DK&Ba3ofu(Qz42u2sK!`u{A zQXGnm%x&F-+Z9__O9-PH25Ci6dJYudKAU1w9>v1tt1@DMZaz&)OqcksKB06XQfv#8 zg4t>z$`h#!6jw<)j|n{@FgPTU%pu`6q#Xf_3$pdiFDy%-cYepgY_-d^@LaGi zEH{s^(A})hdQ_BZJy~C5c+qC5_0}UpGzl=9;384)3X!den#@ovO8u!hMrZbn@>yOu z$uT+jcbMs_p(>siXgw(@-F}y+u-js9n_dkYTSRMJwfNi8pkZ8Hu^$O!TYzlP*UP~? z%2KXH=N3PkhY6M~xVE)(i_EV)w^s13Xx(Qm)4BCPu6b8mq^kzRHFMA%_I~n=I+@vo z_EwKDnzyy{=0#}b|Bdk{OfP@59q;EDOy6(;l0Hu9V9WXGxHw4Kq8|^{do4w%9ZO~l`D(<-Ic@J+j5KUXu!R@!96ZgFQcXnxan*f zW>dp#P1_{h1t}dym$-fhzM5fF>&P^J9}dkYC{?d1-cwZNXV% ziScDdMOY!-l`7X)ZY-QhRAblPG48{kfy6yl)Yb0-(H}A=dNLdxdx$eIUBj5u&9z@I zy>_qB)4esM5AN;S+vTL#E`?%E>^BKA2!Jy9R%p-OP}I^Q%g)M3`~jw_Wro_FHZzMM z3*J*ru1a`TK;Ftc)buQuFg*?Ol4qLoz%rkC`%>!M@4q579n*`u(oKH&qxtc5kq@iA z(QCgLj(oH^zP}11v~SsgeWm-TA8jQ%y)GP8oHP=WOb8qdh_9yOC5DMywB-W>2g1tB zkA84**RmUacjoM8-@s0yKbj00?$EnvM@?>(f=e7EE2?j%Zw-R^L)m4&WLogem$7fukFe(_@7_?_p5 zetz!5mhJC>>Cc_nj9R>{5lkn1ToJ(lH#h<%*& zj4&rsy5&(vPS=-zECGyi!Zb(5W^?eSZ%g0ywQUJml#-f52x$Lk<50J6zaX7VMc%Ub zva$q@J(;EH(vl%5{gegi=BDLj;T$-hur+l-`P9i$)p>-myqIn1Oj0&dHI0Ut z0!+PR^mRNhmh0t8L0zCeHH)x(F4pVj+oUAt8Y&lM0-^4u-PFsPdRB9G)08)T0VSl^s$&#JLcB@P^aaNB;#JcJjhbFNn24B$ zn}zB}0q%3k{(z-n18VfoKj5WO@ z1gCh=WODByR+?GeHl|}+$sjn9s>?)mChSd~PZ=jngEyU(DEY*3a1c~~v3F~FdQxJP zsr)oaFT!*a^WjvjPA%yz2Sa24nx(!*($twWgs8pI^lL0cSK7-p zfBkAYq8J|6)bNo#*nI+b9(wE3pZ!df{~~GZLoe@DSS<~GeK%l`WMjKOCk0p|K<&*kA(AI?F;vDGu3*g{he2(lAA8$ z&7a?#wS`M!dK?9n0BO#;W2SZ#MVmP(ur9lcGigU{3LON!SKmZE%gm_H_F$#QAW1Su95FIV>@IuKErZ34^N)o+w!LnvLl zreH&+4?uK;$pcNw!D|kO1LQFn&atyZfYrdY!E_K^YPun8?httg>RvcpnmbpxX}mD3 zs7G6Ca3@=gh_jg9tYxihIb(P@JHVuXhiFn`v~qfpGNnQBmtj3RDIHADK~Bf`0|ANPHQhTe>@IS}SwE#o2#n zxnHif?CCPVSofICYn={j0T%*o^CZ&6wIO>`2G8~6T5K~SJY@g?AOJ~3K~(d&?lG%i8=?Q7b*E928fBnMiCO3WkSZWt;kG}0IE2%o&-qzX&cvqGA=DIhGk5kWv zMSyC_rePu&hY4JyJk*Hk)R7uSzhgUhm}=6NmJ)I?fGfJ3yFKxBO?CVssB0=K6{Sq$@VqDqtoN6fiZ?^xlpF>S2S=;uVaSOXy)&x=($DnvImq`Gn` z{N*05pLnn<%vs7j!H;mh&hWY_PivLix-h?3QJKYilUfBRr$N446$ zy1LvY94)9UbY}aY*!q2Som(QTF)eIcXz*~LF_=SrX7oLJ>1}|Q4jeoS{=R*h2 z&q{{P`hO$d}Lc=V@;W*Y!hWj1u3a1J$?!G+59M}K2nDr69^Bi_NXLtpgP6V zMy~z(2S5Ap>>HNf3C;j?X1``8E7Wun zmF^&m1>W}!Gg&E+G3k@IgL?4650GNwPD{u}Q0LH$Uu2i7pIM3@cOKYGA?X|UKS@JU zy(T}u9s&tH1H6?;>Ch_MmcVT~cLM&^j#l8G2^hUjOXxJ3n?P3p#UUYw^O4>&ykif= z9N1VkZ{GY2Gft9=!jSakpn;Wr<5TJ~b8Bc}s*+KKPLAx~0jBRz>M1j*ssJ}Vim2&~ z#UJI!cN4WPMcv_~5g2d3_3ibhlknnfCf<{|bKlB_hAnvldy1DaRgu_Y<`e(-rh0*UP0x=&Ip# zfLJX-#p`J6#^i%)Pei$HSeTAU-4fJgH&>9lhV?=@_d3%rdvj!Pv1D{1xuu_bRdpND zfpc?**{~t?OPp?`bHsDex;4yxnEkQ2WI^EI?3_t7>@}$1{3EAb(Co#lGbSVCO{av^ zQq#foD10Z~fq^FI5O?~{f~|Pd@60Gjyd`<-Ed>REhw!~%QslKn)RjRsl+X2o$?e7O<-~~7In2)g z{FvUPB+?K0&z=}UpbKg`Hh9!@3^S0r$xUCoM1`Xet|Vy`b&Ml?JdEi@HK%-9gz0Zt zqX2<@n(>&hqQvxBYe;1o9NeX#7owGkkfzoo8>UMy!=9QhK1>P zk)tQUm&ric&=cvN4yFsDB9gZ%K(BWa^Uw65g5(!-UZjK+F@5VTTXkfDH%pbS>NrXb zX-II0Z0Xu{_FY&1`n~C@RuQFt^dE-~0o{k*`pthp-O|VZ=Z-r59qXU&Rdf>Jf1(x7 zf;IiB%ss!MA~}Lo`+~Rr!}7@duV?DQSxdtx@7C2nea<#5HJyIZ;grICVJ*xyQ=XW= zKuz~5={Q~}$xKeJ#RV=gUEwa)m_2*BXnmDFBRI%J>C(k5e+zUDs*2PtD~w7>#YSym%e_jr~OjVt5pfOpd9Y4WmQ#yNP!sHAWqWFty+tu|g4ZjKc)=I+4n2&J1}g zRWT?y2fr9HI;WV77?N7zl9S+cTTPeOg_uSBEMPljqXKgbEV^l7x~{_FlFTK^!{)l% zTnoZ~My!*nP(Xf}UnI1f8Gu&78G`|i?g5DUka~>K)-kVx4Y&%P4NaR%!|6JMlg+ucfSYD5F1Smq z4WS$0X2Z&1v`i<+C5^271sf$GOjd@a%`&Ra?yt8fijx9ycG{l#YYwfPdZK8MM zFqNsfl^^v{Rf^AdfM}Nix*TmMml10^^`w=RATY9YQG+85^|iDqvniLrip;v)x;kiG zyl7E6u5rGy9Ej;f8w)pLdvSHq=V&Z%FJ21$!KkQ6OLL8b>3CfBTA7Qs*~Kt9XVw>x z{%g|HEmpVe>JL8Hwb#k9|4jcd&O0+Bhf5Gpnr`Tm@V*!V@5@V zGaogbBLZ8V8K6VXj0#`gy7k$eQq!FZ&LhNwfx94}>qJRS{M%|n`r4@WtUVi!3b5FL8gwt*ab9xv%Nmn4|1gPDORC;E@`Mi~-)KS)BPp=bolx$gl{IiGO{_yO-o61r0UC3bkka(BU@S{h+aUz!ZdW<(1vtXKABfV@qVSn>QX`I?tZva=TqK9j;KK8By9P zB)$L5uiyXSW-=L3(`kc*$WC}VP8s4}(9}WvfKm>nFt12RAQ&YV1)5?~I6bnuiS9^D zlaSFRrk4$4GOrPK3)4TO);h0+dSWu%*$z^A6_n0Tpk}0uiqZXWy0mnpbdH8#ddc-= zh5?k5SxziEeWaShTz)QFP^ZTcLOR`!Vks@f661_bpmS2CZ!;Cjd3Ua@*gnEHXz-S9zv}5!jK` zp)Py;=M|*O7S5HBK7HDpSs0WB>14Zr)=25(y9lzU&TKLluzQyoAzdQ6@w^yH*F$$f z=3g8Jgm1uCVn7{MhubMswaFMZ7RTc{v4L8exCv`9sD6po?bpw{r4=n#x@CGXinrb ztUbLL*^k;!ibrSRNsofyrK!^)6vxY&$@zq4(0XWA_n_T{boaM4SqZr%O#oOkZ*s4hM?v`q~pu zKYjCW7}89|=3;bq5@eE^emEzG_iQj|8W#Rpfe|o14g_9dL0rrv(dmI0cW||Y#J!j< zOec`h^f}V5C@$S}G}26lq;-kt0(4_f|C>XKnpgVR*UYPhNW6=Q}v4 z`p2uL&a;DH>agA5fraD${N}9ZFm@LS*7(vD#K>=knvGf+>AK)^foYtUMz~)@=*ILS zU0j^5iUvxNQOvn2HJv0y)r|`0W!UCZgy620MSP@YlfbACSUT=^EH2p3?_PyhT_G@R z4Y-Y=*%txk%mY;fDzzIO8!I|8HcSnF2L;Aa7D4qgi7di&_M1=^*2J=I1am+d+U8sg zE*giy4VEj$#n3k-FIG3Ix-2rHa`Q}qn9)`Ijq$|*I`X+$&j3A-iHI=v7?q?lfzb9y zg3-iA4ttq^ayV!53$P=&=hWtSOGqzq<>i=Za9DTQSEg>W$UyGYJ>qObz+z(Sn)M*D zHY~42f@CfP^{fLN>n_97*134v=4*@6ZSc0X+hMkBKZ*Su<`!EpE1E5t&6=mvriJHv zM%}NiXrH|&>vejUm=~m1`Xz?-$p4(ujf>{ecD%nP6{8y~X>~71cailcAkHi=FNGmI zFe~uuoJmD%W*zl#9#0v#B}(tahej3? zBa=e9LK)MK*}l!8PFlRj8cL6+kEJ_5KeDy#^&=lYa`uzgUi+wj+}+yqXqU6AEH>;o zYC7KZ=KL_%sITKdqklH!CZVrSr;5#pYB7(8Uy+Nh*IHnf2fzKYsjMi;rELpyBCU%17^fhVH3yy*&3> z!^7{r{J@PbziGK%s`_huQInYv%~bi18tM4F`dr^O?g zr#a)D@s;lQG#@T~{nG0E0}=vCP^7cm-5O+7X|^{8v925^&^&LSx5Z#ZedzdemjwNiS1K z?j`lh1#=OoR+s|yshgJ}y2a^Q1xmN^+%US(T&5R8>6Z6JH%JAykn{`Z3+LX{ExQZq zyC}W;2K+98iPg|DBU|X_+ld&I-zC&q-WFGP%U*tKrxvIvHjpP8L{6FIEXDm~OJj7l_jl zMPF26$-3otFUIsjO5MRgxKgntLyB9B3IQ^&36z??c*#%*w~UfLMd_Gh3f91`*h@n2 znHbZ{>D9a6CpVqC)!pBsSJ7^!2D|n3J~tN^4~9(6UcLGZg|2s>x%-SHOk$)DbrWBM z{@rcortiLU_hJPyF6o}GOf``&Qaj)gB1p$(Go632e0Ub&z!5F}_n-au@4U6OgG@xW z0j4ua86p#g_NaqcfO;pG5U3p~Kz>-QTE6!56TkV**WUQyZ|)bR8&KDU@wQNWyCi22 zMhYV0T^^cQh>NOF4dOh6l*zzNYBf6a|6%X%!>X+Fy>DEG4FzU20-~Y<>X4X1VPa}a zK*)4sWF9<73WB5(i%3IFbRdyrJ34w~I+ucU<#EN;F*#eO+-$ox6*YB-{l@#i%$Yse z!>+5LCWq}fQg`k>j`@4NKi_j9_AoQo@1H&Uckl07oX_XEP8JJzo$vGgeSaRB{lvuA z#!-ayagyhe)495V({DJWw~n27o4BX}(sfEi)$qps=kG!~+M-sXi+_X5#V(DUI4)HG z)xZ3q92crEUGPm&BG<7KOh5XMzk3%U{mFM{zxzA4seCfODW(v%+xSmowKCmY8B*#w z=mf5A)HJHGa;Hc6FRV<+zpTlU?jT*h^d)4KOG}5(t?wv+4o1V-%3DN7M;>Pu=oYU( zsGi2s%qPk50+h=EvIHTW48v9Ifvhf$pT1-@CK*5VOQxZJ zg3ey7gvU9$jOdcqkE~ zT{GGmXjZf1NaofuhU}t099rq7HRq}6Y^}x-9%2~aZI-a5C_FG^!X43G(yeivZkw>9 zPSTdxx$3p-v~_6vPIP8}zFjS$e*>#?to~-J10V7H0?H4ipIW-ERwaP>_}7qFE+Qqb zIitNk9VHz|@9V=|p6!P!bMu0vUxVmGncGCZuQYw@o(6wIbx2%8c6h^DyfVRs?ZA3_ z`{K&=g;;vmS3>0U0mS!E3g1%ch&V=+^>k_L^7r}^5iOA|ixY~INr{PRZ_g-~kSq6#Y7bgLhCFci)*VfkJaRI~WBI@E?s5{#4Z~@k}Qth{% zn(pREWNeN|%_B50N{~7_B&INFRzj1a#4|Dg^bGn#VpS(T-u-2mFghhRDl$r5m>051 z)*GD{E)Rd&1TGYa*~9fBEgdx-dv)!xvRNsoKKt-9x{!WwzNogFOqXYT;YpFD>8R-h zGDfv#W^`v@WQk3pduWN6X>k>uNJ}V2S_J$`sE#Wt!tsApDs5sNHujdx)(_8Iy!gf) zyN|z48L48heDN$3af>D4s<&wln<1u`5nEEky4GXO>-P!M&;R-hRU+LLLwTs6^0XHD z+R@Sl>d|>jALPd6!92>i@&mv0`Q;NQP7udP+4GZoU-+k|-`u?R%#=eHPnVX?_{kgh zU7WdwTa))^7831f*)DK;Q54k6H{txwxe56Bk*7n7D%-2pH#K#nHKk>&E8TJK!!JK1 zBHbAM{U3e!!p@T95`7nym1xUZVF^Ukmlx|z%&xEZWp(?~y1Eh6lOo8bA>PHGl@#Yo zO3O&kU?Gc@J|3Kr6oP!-l~hmwrUwP3OsGj|qK|A^T2_HCiA>9okk>XZXZ27O6-!M|>Z?tJN3(-#-xiLq#xn3%-e{A42b zWlN7D{@o@BO_!XmAzFGApQDI`yzr$BIIIdPGI7A;k0GG5B8pDR;kskPZ3UoT26dG= z3NEY+Z_0?%oeT@L8Gz}Sad5?R1p&dAhtS;>hZ2UL9KtgBS(UKd`)gpB`E6?Y06y1t z9E$*7oJ%klq??rP4Bi!DJ+m!8hU z`#}vEIbzcE>#62BoTQU$uLV~P)5-cia9XAp%T3?2q;1Geqo$6+UH%aE^oJfL>gDlA z?_72SOdtFBxJPFboAS`1*)Td2Q~CFe!(-@y)63_aejZjpM3>=3X)u!0Rf%*(k2U<_ zXx%+7>1EH#PdD|vJYzeIzSb2Lh1|EV+`e`Dj1wz*mT%vK+xOFzD>*4Je(j9QCk7*@ zqk-QfHQjmBotjS4i~WP;>fk0c{0&1T*>AXc1HD*ry&U=u=kUnojT01FLy}Pp{tl@B_cQ`?XhJ``t_G>BmYXy^OQCm+`pl zso1gtPtb;`*U_<6PInyVH;nqup`oLQqL=gh5XtO^4$Xd)x=`kM0n=ZVsh_uloE$@P zy-U1D#^?+V{r^c9QrwS-=|_Lz{OG@uGVJgPQ{TR=cJrH$-<3q(%8QG!}#g5qGfg)D;ahUr*W5SIBc zNotpcWhO3=nG1<+QP4U7Px{NMWdxz4I}>ThD{;)pWmK!Ec$!VQtCbdYa-b-UsfP7wiMvB5k*mJFE^5pAR3( zmVmnqGJ{8sq@tN~uU}8?U19prVdG6sA2OIbaIicLP$v$OEXV5y)3=nwBiNj8n2Qs> zdu|DMKg@ozG54xCQs6z;-B)MhmMb^z*u0!9HUmpxsIdO%g5i=1v@FW)y{C+elPIsPE(z_G5> zgL$KK!{Uhbh=Z~VW7Jm>@e!*9CTYb`sZGd>l|wj;Ty4r5h1BFl3De^zq(xPz!h1vn zr6WVk^b%Ja6+Wxx)Q>;>@Tpao-&&K=v8#P&S!S&-t|HTSmU2U9dn2MEecis8*0P8s z3@!LYqKo&p%QCEbQFW1uIHW@*VIw&x?8Q}3{?0P`k$(98#rH4XanJEfz2$PbES}Yb z7bGO73jecQ(74Y@glWN?j=#Eaab4MtV~cy~L;CBpA6@^aZ+-KhUO4~e+S3;g;d&`TPXE~(o96E-E@=VN7srLw z!RM0F>9I-Niga|rF#Qb>jq}oy=%dilUEkZ0*3p^1qxHkzyN;uByL|ZNi|E^l$ka`o zdsWqbjN3_&W^Q?IS`yW8JAC!^9lS#f<9!|V8NQ~hf{u)OUz(3(pYE*s?)bEhf{ZLb zAfMG;-@UFrjr#yu9Vz);_1*Qpt~54i%2Lu|SoQpk+vdH!?c56z)JqVO;pvhh)gu+Q z;(I~ihSO`ve6+%>Qqv1_%0jG~XF^L+NFD0)&YiiVyJs9;d3OE!Z0hC4WH0rl)MiD+ z0?*t_2n%jXC{GSe;F~{M%;P9py6PG+DN0{FD-Ov#+(&o~2L9v;dAV5c1?oQZ^om-> z5tJeosYj$laJ`4T?ym^-SEpB$HWZ{q2FKFVG??BQF=WG#)~L@KQ8D2aK9y7oOALO+J@-Nkt*oC=!WS+boUgR6QW0Mhb^NEsdlyIXjdhJsQp9g$_A<#sq5$? zS0Md|s%K<`jsK;M2Qz|hEi*LNlCM2vOn2#wOtp#12Q-89ZvyqJ6m{8NXcE>9)CJ!( zbF1j&-M8)DlDp8*4bg2APfeFVe#J z^t(ADhFp8o(4heOsM~I$ygh3ACQnU2J;&7awX4UCRc%kXy48skJs8&uRY=!PoGsJK zlf$8ODZ__m&qgZe4*2k!dPdNNbopvDW!2go(9o|BQQN3z_9H_Njk<35hM{e%x2wF7 zl3sddGCq75opR-j(=+zWIK79(TW6fuFl5G_ljBd!#DXpl&dQZrw;rDSB&H{c*GhU3 zrz63ento`M{w4Bn6?Gci#mu6Q3fFpCc8GtSd>6pqzy9i9pM8mbq>6tTH40guFD~YW z_KX?1o3cfgh>lI+03d}D_~gB>zILiK&0GKgAOJ~3K~(R%550?Fh2TZ-#k}Ujxpgq~ z&~=nv+BAk}$eRdqw*>YZcwLmZYl)c|JR27aW}@q;>2&?DM@K&T=#x)iO@I8+S6`ze z?vrpjZ<+2l9GWV1lAf`=TO5@M zzzC?V2dVy%?3eVe{sYhc-tC~_zx>O`zu{gfo9ni>`ycu(L#iU%!Hz}`LOA=%Mx&{I zT2o`MB{lymYrlO~m@c;q-6uxq&W^Iufpjk`oro8L(WR!7i;n(HZ691MW?hjku5?D3 zT|n>$<$a+%(R7junT6jSl?%^Tk+wcb)J~EM1&bz*A>0$}p9IXVUcGSjILziaPB6zy zEtlzJ@L1{&DON?)ZCpKAT}F|!Wn|GN63_u@5LvQ2?9Dz*u~Zaph%QXW)`GVktkwoB zWt|PAz_Xv`ME9&TsJA&b#MiE!UDImqE#5cbT|&IPF@w2ymzSLb4{=#J7+|_r0-I|tUhHenw-1NILrV{DfbI=ydi zM(J1H1~&XZ!t{o{*-KAl(Jj%y8wDHmW=KjoljRW=1^CcAmu{7wzH~2P>J^b$QPh0r z*Mwgcd6-r9h`5zZe`;iQL*~*oF)7&%1=%y!HWZXo7IBs|b=ffzkWI?hn`hM zXHopZWyIwP({VG%q5*i7RP8LQqoe7T3+Fz2|Kc0S+@E)1tvHHhx-cU%CNraoev7E- zM`tZAB4|7+vMelkR$)~o+1;T>dntPgroVOhi?`0Nr>c&xygW!fHf3_r50cBR38N2+ z(f7dU=;+iReRtYhC*Fe8Pn=x&!ax1f=JQ+koLMycO!d+9(`3DDdT!tPoM$pIz08WN z!R-M=;#zPV({gKEfX+{w^Vd@ zboBPp>vI2o>fRTT<5bujr(^1)B{|s(PK6*b?LIphnHXKtMA~|>(`}B zh{z&;JTe@iJ0dPAIVGfmnyYX+KNo?zEH8M~>D3!9I+mKA8N>TjMpxIoP-*Mz34Qxq z-iy^ERsGStnuy4tNL|2YHKs=u#H7$+1baR^#AH=qQpa2csHX)*(3>_)9gPWo506{W z6l7|8AV)vCH~~LTPB7n5QG0t~GA97+^ z8LYO(DA1?Wp*n95%aF`zf2Y)RGqsqmED$=MRlC`JUPpPVz}L2)ej?zz&jbD-DrA}Gs*GV+qchprgBdh1Fs zoo=9$hrK*w<@OnuJ}3G|d(Acc7X{6qeDv9u;ABy{T;Tof1}rp>3|A?q zo+0?>34I}tq-Y|h}P+A44C76nYnuU^at5v67o4@K6By-d@^#rELk>VA)@@@nUis~ zPaHF5I>s0h4JVHyLw)4+V@6(oy?q=-%OYYqRIVRJ?@%C|CQfE{qzUJ&Hd;2iW{EZs zQe#DtdEKU^mzy=6BZ=NU^NbO-lyEuM*~js`t+iuff!A&l=XEBUvLV}P0Rq3hxHjRB zff~m`YUhk_$&)-ol_e@6@n-ObESc`T+kbP7J%p&jXGX$WV`gs-Cgowv85#7tEgbd= zfc3aW18>?pmghoeC!sh4dljHwWNmXc!BJVH-Q9AxPDj)69&*QhNXN7T=(LQ%HLpGF z)U`3M!ZMG>83ndtsV&sz+FQ-0Sjqw1fTbl9atcXtUA0-b)M<@dNq|urOsy}%Y7em)Wos0PsF04-C~6liZAgu6SX$7qrtgJ@ zZVBXzai*i=B`41!UL$)m`PT^P{`Q#4(rk~?8ygz4bOF%Ss2v)}^mQO(z;1Os`FwAPF=%D6#_A%Z@8Fu2^*IB+4R_(_N3z$G$r^ zP>2-WUFLMP$AsyB|MzwuuO_5vRt8agbh=Z)8Y~6DNm!3j(*tsPXhlU>XfRA#Ra6;L zlOjx)=_Rs)UZ;ST>1=yRA%bxo;d@Q7$Lc>qP5-Dj zsD*nIO_5YBiY0A{VQuL|WHU*ZL)xe(~kw z$B%#1v3?(zzP?-G+fl(dr!A1=D6)Gd#p;Vf2p#d4Ny;du?CD!)f6e6r(dn}?GsB4Z zNyX%%hLAo;e)L{+^pnWwZPVTrq#u9x^1E-HKu`bUrR>fB^o#TR(m(yllqW78*}rqf zKfH1AzRTzLwP$A1MRjozbwY8albcdU?@V1#=#iT{fvEJf_^zO?w2t)jt_k@qh+yQ>4_ zMjx+l0=_w52c?qg!Swo0rs`pHDkm||QdI&VEnG`&H_RlGdHh&8;AOlHLY9( zl{i~=Niarn^+Z*DBa-uz@p9MkV~vXg(=*}}{Eips{+5=O5|x0xza(|X9$c@NCmp_o zEoe{Qo>QG!S^i9Nb;6^3NmP4Hj`U~3=_PeL_Y2dpy$IK5<#79jy0E?oUlbqyFybB~ za`Tc=%yFe-V^Q8qE%;59BWoz-{)&{4(uV38D|54#`thrW#!^(vS~#|Ka$&e>L!f%7 zFGDH)%9D&Kj0zCc`DPK=U_k`pU(NM2WlCB1!15Yvn3 za~t^I8DQ|Qj2)5(7G6CEq|=Pd`v*30EgUX3SNBoI63<0lYTq$P*Al`H9iR)=Z&|eH z_D3uTMs61|`i6c;2fmO0@VKX?_lU@Q+T?Z#1Td<1sQ}%pMQZxFn-BCNMNhX*q-|ii zxLn)cGHsDPZPr-*YET~t>3G$Z{9?>3YKE-?P26qG`rfhvz1;J=m?Pa0xoriHyQequ zX1x71B5#JMbULwm3cknajL1~K%fphBCzpLPqUW{^i0R1O@HA@r@)?_Y#tc=`%knvG zW04JK%zN<3!6I53zKq#ZpQNzKWa-)?NJ(rP*)y1)qayLy!c|GZhc>7@lFA#QHXj1a zN8MntD=Kwl-jYLt3~Se4uPUU6h3V7TX*;f$?R&Q4P~YpXi}$s3d5d4idln zxY8w+w9?-s&kxr@>32E=s#qb$7_x!hax{6zxh(+2ACdw6Iu4AdpIN?Ec;5{p(-sZe z^;SrRRKL{m=oRA;=82Z459#dLkK#~=(qE(A5sa>ZFda5$#gk9ikl82Z1^&JMCml~1 zgu#Tnaz};eYKGj7*bUhKc)0>Dm;9 zeih*^i0q`GljupKUg!8RhSk!>nHqNeP$r;qEu=i?Nb{XLR5l9=n+V1ATLwYPqN1t6 zBd3pHf@5ix0GmK$zkR(;w8}oY*W;YwL(49#aZ9zO<7`+Py9`W|b=!$mVtB^3*c}R3r&}p^tMIDAz|qi7pxp&_%FS$i8pvk0sWOiF_{ux6oFxaB&KJ5=Csnx%OQwbadO!aF(> zwvArW7U?Cm*_EL-vDeWuJs7(K*o*&3+}28Qx^2`y@n?7Wo51f$enEA0daY@ya*qIQ z0ZylDCReu@ms4A~E8k5_V|uASeQD#~>{7DMlPErufMp_@-#Y_6`X8nqyWd}$nd)C! zoxL@?seNnqtjhN8s^Z1;A*J36fq_NT?QDnT3;dK(qBkk7m#vKr4W*@(iL=%d+t{8H zmynPYM`u6)J%13d&nYFBClRzKV@q&WxUX{^oZea6)y$}VZYP~c`Q4_dO-OBpuQn4* zM9ye|`Kl8B&Qul{&(>Y|9)ikcoA zPVF51wcwA;=oIDR0Y*78y+j+P7tn>&mudCimD1t7>EXWG@WP}E?|t~$hs!?dowcQV z{o=%si1@UG(9FI*<)-(hv_zz(MZ|*X5s57!>d*(M(*Y5DqK9L66f%A=fg@FA1iHwe zP)uRVx-I*`^!LyFv<)!M|rSX$ala7Ar^Unq8GNi-lf8^#RoPPY>X_pc0_q}=k zeDzl2u$1Z#dAzeOs`SZ(j__}=Z@QjsP347tjM??^mp3;(;dH?|57^8as7{4Z5L}*f zE;aae@UEMhE{gwoKwH;Xn>l$sAf;Ehj6RC#o&-Q4k z>C=12C&39lTzwZ04PAY5#-=gD4mnJ>K*r^V9~@8pQ3VLfy)vAvyupLV!zwf8Y#KR| z@W!d~SYu6pNWm_$Rgb!D@PXy1>8o{Xo=8SHwP|8ziOjQSkA1?lNkTKmwjG#3=(MTn zJtyYqr~tQmlDdYPK7M!)^7*FmGv#bSSC_^{QZnhbmMof!}fzpPCm?FLfzqP4Cicc9Zx(cf^}=u zHq~yVK^m6;AY&Ci&z%JoVkFa|O^yOg@w#`gVW{QDj6cyfo|5VY=?p+|wO4r{r}JfK zE>8?A9jVWL{PDkXHQmGHfFS+#v0{!*O^36AY@pkby3u!F`d|L#Uy;>I46OeNpUQ+1 z!}P#5qI;SrtZON>{-z2dxr~;tzAAr&WO^~V9Mv66H}kn0vI|N(mkwr5|IPoQnyz4y znd&==;YD^A4RE{6IgFkzEuAi-aJaJ4&E8@qNKG$RkA{iUXCj{~%*9~c3xYu`mzYjh zO5yyf)eA|A0n_PnI&%aOki@fKSRqeQ*@~Kw(;QMCi()OyIhZW}ip=NGw2)XTxw6X% zehJJ&+|sofs+{QcLkLt?RwJ7-(tZFm+Zwg=fd<%hEucMEV-F^b)d6m{buY_SDEQg} z24^{%{uoA*-0f_T;B`K_)dag^oR{lHKreRJCS&LWtDwf2GXt3J;ii$T@wZW|IQPoe z-&}i*&AUZnTuIPCyjvmkwPji!c<8vs${s_Tgf5`BrnQFVY+|{HZn0bE9YQ06ZM_&X z+>~=Kqr(PP*tS=8HW)W1XN7^d8|qNjWYAF);+x#=E*@;zUoiMTp!9xBukklDWJ(gp zpe#VgKE|YrR^gXs0`Q%h8k>rJp~DyK!{?iwzL%u*@Sr3M@#D8Sl_WnfU;c^Q3AHV$ zDW!BtZET|aXm&fPh1m;=+c#6$2qytLabgHH*mt)33wD-L*+{+@f?g^}!OI{7Mr~(? zXajW@eOJGziswt9T9D!y)98XnX`|Y#`mVe#-;VmO_#K3|tDZ}8Xk@rAHtHC1`i}1h zd@c~W6m**%pt8TNN~G2>r?Z9B^w&S7J@x5(e?Q^i=+U7Hdm%TYDFjd#ro-u|r4so0 zL!yh4$QXaAzlyG%MMa?#QYw}z>19w_6eV>eb7Facs_1}PNRPUwfLZPs1PNc&WH4)j{(P<{w0ce*My=&kr02cu>)$qyy<+oOtWqcfWX-G{!%s_fmZG zH|Nt&J+*1k`)A%fy6!2|^oKv#x2xq?RMTS2?@+op9dr6le+zghObjWi@CD^zO^GEC zz4YAacixeT4x+#R%isU<%fIE6suWXLSy!bSqGfeqK58x%)>W1fn+T>S2h}&xd$b-y z3?SZ_B_z-9%I`%}m+7UClSVX$-Vw|}aY#K)OfRhOO3SbB&S#dDy+b3<2#roG zT{C|k$&9Dp#9l-)BbPK(&>lfke;3s6H-@{Q#h-zyPImPxw-e>zvY?M>T_$) zooa17efsTlr!J(Q`t9ZKcl=`3HQqLDwQISOrTP~^UDl)^gesa1JOq2$A5O*Z0SJyA`n|NE^E4;f^@#L$k3dz zn_%t^XMX7?ce!B9o(_liXhZMt{gCeX{40{WQdR=Zt4%6cC!_{eC!hu9Hu%<1t-t@M z78sa|;%z&vwTH&;OM47xx7@|03SlT}*TI>PCZUu!Q*?>&${TO={xNRa^s`O7SKKg^ zTyHQNn7(PKyy-o&2OFlZ?&$$a_RQEwz}y25PrO%ENTnxF9Xezj1sG>+Ts^X9%&?xJ zsxgYUW$0|u9fYQbZW|16uUwcr}DASIWgD_CQ$IyNuEn) z&*2%{XH34%*xV#^p|oqV^xW{BLrClf=vNKAEv|#SZv(ui63&Q*j-GC?-bURgt|l0? zjcMb4y(TnI{vsyz>-kzSWbg_j8muzc^AIr6geDyFCXi$Z&Y89olGMlDJ9ec z(?#m9-F^4n57R&OwTEA$F$UckiQx}>Kd1k+BS8TA^-)|b9%wsKcj#@{uE{_A>L2%) zSP#+?%TE{5_pfwx?{?S5I?^xF#OQi{Qv=Q&rWeyi?yK8Kv!lQ2Z`5Bkne+Rm1ANmm zyc)wsPF%fg##%7l!qTOq({oe?bs@TAboCnr(^1vQG?CfG+~<_tw4ij{=LEvA6blTY zi}IyUS~h118of3q$&s~0x=3svF&-2rcbrd|>Cn#BqL4){akUgUx5O3kyC~YQ935OX zbn&v-n#OkWvhxuYJ&T#4YdZpmWmj#hY(@b$tLb@48#Zz*J7{nABvr=nTSB{*=x7G% z_8RcMp*Uv+ncHsy2NIF9yQ%47b9WUW_YAM0e&(zO^M{QixpbWOcB2tr1B72`j$$?R zzKq@br@alGD6JXRfWr(O2pcvVUo!|Wxs5$&7g8ITvoEx51GlB;g<-u2T1_i;K<{{3 zZm(!d0 zQ}1cu1D#*6w17B5L~;FQSO#K^btjxaFA^X~nF8#oJ9cDJl{1OZMUo!dtFt4rS2pgI?EG;E2hWE}EMblp4EZ$6Qm?MdyNa8vyA6c4vuUx>MXelgw}De)`j&{?DKO^nX2; zCv#1QKT1;iEC?7QPGLCK6Vj>4y5p|gph3v1_qSFPP*?>b7sgM>tEUTYY0!lD+S>Sd zf*ippP-;P3<@&{i9cjmoegD0uKK$_Q7ZNjTyStkf6o<5=9^0|5Q`G!HcFX;-9lagF zWo1?C%ZdP3qpM9+A_GFxWnkQUakw?dh5jTOSoP>-c_ER-kDAh+zzw4Y?q8q zKKe9u8^ zDCxkd5D^B(Rubcbn7dL-Qlm@mfALKz=|c4PfB*Y)7q(EqG>4wC)b!k0R_6Ct;5*?x z?&u)#JthigI@XP(n3!PFLVf7vX$76q(UH^X8Y)XV+%EmxaXFg1yy@DazPW=DpN&r7 zU7OW6bK3dZKMJ7^FE3A@AMzg92cFC!%jEpP`FT|dL z8Kx!r{*o;(%BOSY`7<-$ne)z>m(HAd=aU(y();!-zqI_)$xD|mDSmg(<&)bxeO=U9 zO^`{3Z+r_EMlG0=nBs@EWeYZ?oketJ2+rxQtc=OXQG!oaMn!OLjmhbmz&A2GVT%z# zWT#_$3HAB1x9%;-Zfqz`ZvfAIQN+Lm#rlYCWJG$pW>W}oWR_bup@~Tex(yXUml1AN z=ho?iWT(RQB)0UzqN++4$5>KV*^co(F^=yv5pzsvF2DFV-P~V;8j<(6H$!t9*f#yR z&LVp{Liadb)a{`;wwJ)v6<9Y+zwQScq>dvK(`QtTiZ-J34T5x2t&OJdAcgVe<0hpe ze8bo5BrLzum=mrCBy^jyc}eLk7M}+mY}9j$_`FBQ(d!3VKt-3Feh&<8&5SP?Pz=;v z!6V1)ZV9YDZJLofqI!Q5ga@>9trUlw4My0mS$hV?11KF|3zSZ~?IF5;g6h(-Z?N~q z2Hu}-zWuhI4c865o-T{^s0pqB03ZNKL_t(Ciys;~VNW5%c>=gTu+-ZW(RiV=!M zTs`MBZO)w2aM6fi^myePl3KmW!eMm2bUmHUYsg!}H*6g5bbJ;bx>kDnw_^Gzg5$Z6 z!NW2YLLZEa1dn&dr@8<+170}$@};X^op*TzpC ze=nXPfx0hI*4*wQzeDV^U3vR!Br)F;Wzf(_jq=}@{k zUo^0k?w;KrUWOaRd^+6WC zo1aA(FQ&gLtPV%qvz#2i4_)+ne2m{3JDs`gt`LYg1Hr*F)8FgX!$X zj-QN~$b0KWoc-PwV_C!5en{^p(g4gd76jXJBY2^(=vj;1z%W_#ZcVT(+BPb70B%aQ zkXwh*W*kT(4q(U94sJ^w!OeI>+e7PY-d@ zwiaZs?M|vlZ^&4=vYK1%89DULq&n&11;w)}$$HtG-LN@(C*kSsixUBNJTPlkZe3a$ z6~r$eQ8PTqDbHUJ(Ue4HVN)9Qk`m(DtuktMeYX#c=aE*B-Q<#9q7%W6(9qPDV>^zS zRPF|%^MK>UTl`y3O;-t0Yrp;OZ(slE{}87C^!r4;)TF@2NZ4@-=O|iSR0u&r%i&F6 zI)5fOy9ueK+$PxEzHfb8T+oD+f~5`Br6j%7*84i-&jHl&rpLACEG}&7*zxzz$nE*2tE|s=MbaZs!P^sJ%1E&`oUSW7CW{NsIVKF|*`MBUE zePSf3D?_VoX?g7X$m#E2JTPtAa3Pp>L24vUG3#Du&b zYAmU7YWn35&VKyd7ayNrklmL~CVnSro0mTS?^`HQH?4zJh}K?u;(tUI2AIa%mm4X~yV4xXkOATzp+k#J)&**T=J?D<8*tx2{2Wcl3G9 ziin^eX-4JF&DH;OkE)7Gh|7qHL`moB;@msX z`G_-jkC^__%-2S|bY|0;nWrzTOFz}gK`HZpooZ+s8W?OC|yT+ zTYp|qMOKzLJr?ymK8RYS@H|m4K_o0iL{QCC-If!RiqnFFiBhFIH7~65&;((yzPjkhFAD(go=-I+PgQ3$uz85?;N0Z&fwayv8$;SA zsvD?_#nsH=a)r)qn|?wUx(B|P476KryxCDYWjFPtU!&eFUEk=+#{HZI-F5qlX)D0= zA;9%)0t_MN5p(EN+B0PO>C-b#u5N2H`gK;6Jp>^F=Y}csHtqq_*DjwvevJP867{0U z^x-nj+<-x3`1l!nmd{zfe9oBJLx$636pa6lqjX{VU{v(MhaP!kC_k|kDkb!Zj4XRM z4OhV8O*c`abo`i}739H;p%drqp(xu()+0v}llZbFArgq#_J~4NbjX`-GSiDXkfvz@{Fbga+AeSkqza;i7c#d@K=*x{`p!dyvWLR?2zw zTtAlSv8d)^7)^}T<%Xnmu@S(s!AXWgNo<#v&J6?CuuM!IcdrngR7QE!AC*PjYXnh4_%FZz)$jh%WAy-p2WEfutAG5}e#7+rph8Xb zZ`ktVU;SPkNq=PnBYVv`TK~hZej!dUwdR%>byz(bO?>oU z*oKXqK64H^i~u#FHv@6Hst=iyWfE2w6!BHq(^sv2(6n)&oG24AUWjR2wt56uE|WUj zprWr@CXt<9qY(V^Wf);p9ElA9cl8wIwhi%y7RkcL3?RN993BHP^9jR=ZkX-`su%#X zkvLq$?mCe2Q8XJlIWY7e!5#zfBd5dD`i!ztEUpQCfzN!FL1~Cu$gQJsSY`z2DpLxP zOAZ&7n+y)e!|v?OVE}p=Xy}=0n9hD6x{m6~9&tqZ(#7g9yG?=VUcb`elu8;l_6nxU zyAt42LtP=LqhXs6i|b(vZ3CgS=$08XzKGfluZ6;nhWWjBQnfmVve39**sLaiwlQnG zm4Q`mjUC@M)z)s~0IqX9gX;jO!}o#Lbh|O+CEbf~R(8hjh1_?+w4H`Vb{YYG{{{qi z`wbYHdj6Gpr=**pE=u9>)W2* z1*Uh!`?45|d$2OE>*~s)9%)y6eIH(Nj0T9>7+(|dOIdys@^E~Wob29I%acz1-VqbQu>$(gNi>e8Uj7Uw5Kla$M0D#Nt;z7D5T_ce3w;rHN zcSmyn?RWnl5dDAt&;S0@@BckrSMrF@P(jH!*`<*pRSiZh4VodRl6p(|wbfgkci0|q< zOCQp=`gTTz0g{N&IXV8ADi5#dK&j+$EEf@6FJOC#EFzDwL{8}vx-!;nX*u?ybs{}* zV)yQUhSJg7%UbIqgF8rh!JK}U;yd_jxNpHXQAh?j&{*7cmZ+Dv-umb7#-IK8i!aXa zIt!!=(UH-O(c4a7cDW3rUp6KEi!Yx0_=WSAKDdmS4%=Wv-%Ppt>QB$S|HKo&J0Ex9 zssHqpr%vJDl(X?bTZPLGP;sjEp` z4uTWZ2)1|BHzlPIs1CsUI#??_??@{sX!13s+79R>ZhGw(cq`kk5Z`RUW|oSAs$ zojtAe`HUy}F)eRGJV`T`KDm6jFN?f(%D5UHAKg;dQX)z}YLpJC^HVFM25S)?s4CDI zE~m?BMn!0TehSifR3>SRh~yx8Y-~zYc0o$SRzF=H8Z!LhSy)?GU%`lOq_JKU48R^6 znt~Qje5#^}pv>W8Np=wZNlQXn zLUk7{KPA`ukN2&Z-oL`*bY^xd60_Yp%KW+8#VJ%js&jY|L<+CR45A z5Y$ZFqZ=N&iO@qiWe$PqLs#^S*mUB=q?3wtnM`cq(4mj;pM1>t9@az3BVpr5FwqPh z+B0&>$R1qZBZsX3pnEXaz~E+1mzvH61jcop+Vt;8PWO~_ulJ~l>lo8@t?(TTI&>nX z?zh(z2IIbTDZ^C)aypLm!5fBLzk+WF<XnN?in?>ZXimmq3@<>9=)H$U z5;Lu#emY9W^+Ji4aaVll0Y;YrhW?~BB&t!3Zlw&z{bw+}{29!}b3*CBy1So!m%9Yd zzQVl%O1b{(cfZn83=W0c^R?dy(|-e|AHnL(SN zbm{3boKI5vqRUNZ3UU2Gpj=^#s^(+yjGA&;j4=D^Wo!$UKd2*7CX4OR(8o<4F&Uf7 z^=+6=ROyqCo7fpjMF74==Dyux3oq! zhsy1xSv6dBkBruN9gW=yd2c>YDMlB;8qfwNG}Di@#-#z?wKX2vx~-VegqFE4;V%qq z^TzLDb@8kK1=IDKrl1FgdOvN!6*Zlzjgrs#cO8u?ml#Li$zW=<;DRAPh5Jr} zCZxm@q*s5iYh8W(!P?H+yjrxx&gS}4>!^Zrs`K^wE`rr*^=abQe4=0MR#hIFVAfLX zAPoiS4gRR5Ypb*UaY^kBVB_Mr;>4ZVyE0Vss2wrAFfk#akYYy-)&8hhT<%;oaLLW3 zgJk_003C&&KHfEh@-x!6Hl|l^Z6IRWEH8t)yHVXCjhfNPF)?IBZd$7J2O#h&-9k%Z1z|@^nh!$Op1WND5Vza0tpVt(JXN1KC z7Zrt68COAHH2RPpD{K7{HT}%brtSW`v$s6Fh%9xy;f11eKz$b@s$MQ20%kqkVdE0m ztNzj-@uvS<-@&ww^Uradh`SQ!(nIk^3cslXJLgPvZrID|JbERL%NFt=pO zn^5{|FP(V@eRA!L)05_GJlDAK^qE&Soo;+4FP99Pw6uK0@08{~IQ?WgRvS7w369yd zZVMMw`x(LMFSfo|$J;Aum}`DWiqj!Qr(&nOTs^BO>yA>FE_o zE3=Z){Cf)`(v-AL-O-GSFr|EQmxf?T8x;!!3Dbr(b3Trl}^Rc8_9P;pq6u-fwXi>c)5khbBXB?I?p!iMA`;f z^QDn%aQFcC%av-S0ZMlw`xL`*jzTj=cc^Yd19iPTUo`Qzhv?>V2{5`;^}w`rc1_=6 zwCyD7TSjymY;wmrnVJBKAH2$$&)APx%m{)D~E;X{rWoM_1cvy*KXWM zg;1;Q!j1gtlP8ZKKW5m7WgtC~jmswvmXfX}C&~>ELFq)RqoxmixaFsh6KKzlvN3i6!1c$|L73h z@&VJz$bc>$kjG^>S98|&F>=P3gPkQ#U`K@?*2cvJ{prV_;2Hx=f1LV8BJn4mVDRoM z)@js5yJ+~tK1Nl3(d{)b&n@%Iyg=4}Ay_E3vuZRcmdV{bgAi#F{iJZx#~e1k!cBNeM`_o3)5~=#j^MQ+ zH;?*PVK-+x&RefD1mWJiF3d=h7n@7RM{Q>-b~FBGu^Oa4b+GsTi)S6Fi#T~$Vk}k1LkU}BU`uV+H1aZjSM6#B{y9o4Ta-u$#PAIoVBZFw45zirp7YVXB{%ovt$`)h7SJS7J3o)2%M#k<9!=?jlgC)728CMIFbJ4ftw0$9GL50&BWJG z-puG);e9z=x3@I#2~WXak}tfDPKk<%qLdEq*|5-LdZOV|$HFop|6n|o<+~1co$935 zUT6Km`t94n^ts&UpW6qZH}}5Y_qu8zb>w3SahQ(tWkL!lSBTCVRFglbCat2hG`+FW9~A`;Wv{_QoK}<2 z`a9I3_jyv(xiWl^%=tWfX$6$1=ORI(u=weDG0wcyLok zoa%+rc~J~0&J(30G85ySTulGQILh5)o3`?v^1T3mW&8I@PCs)1-}v^9@~{?+;Zzoi zQ>NkK_2j72c1ccOydGOpe0)nwNBswe>7DuI<>x>6;xau(KmQ|%ju_HONY?{Gm(>Nc z%LgBSyt#^mk}X>nr(e1Z^@xIwAEv10(F>XnL9FrLlQ%s z)deuDBPTo=gHmrfB|W*O`0`6B>AzIpQ6PPDE9I>SK_S~D44I#TtAXT8_!v%)!sJeA z&;){BMn~u8hQ`r7GCV9UDJ+9aC3jbYny_@n45pw_6P+mOG7#MD59hMVM~zaSqUurJ zeNEkkT-=q{l!v4xrvSth6^bIkFnDJr-uaUK2NC+C!Lbkx&81bm$%n* zxl08OBV?`x_=)V?kDR{c#r>`OUzG1u2kYXSF}M9k4C!e<>3j)+qgoHC>eMz6R>){bD*$?M*wU zIsq`#48H+!dm5#)M3!_%<$>{68T}Tcb;_^aw!vY#dD8{w`U*7f&o&j1ru5u;^UxLQ z_c>}5KI%tMu)*|4uAeey3Of6S-Me3Y`2eIo2UtHzr%qII19hjaE1*Rw=TNd9;uv+a zn0c7h%jPWKxN-Hk!9x$-fMJ~+7$6-%{h_JDA34N7XJQQj^$jZy%vpVa!$R4chTf#A zL1^dPxF3sv{zMO)-ZPYl#0`V5?-|2&!}#&zdYEJpG%mkA=JXAdB&Hjt6TiM>s%hf} z>6V%fs;e2R3)59vkT(WZoe`H1GQ?p5{^(_|tU+3ViNJ)_GL?>_P9E3bf{W>c4# zu8bFSbs;LCPHy_+f1O=Oxg_WFGoh<56x;dPe4W0njnI0NhJ7MHV>Vjptmc zimE9}?)j=!lUB>&f?}>RM-tgbpujJqY|*lX=joO6cavdiAxqe&jf=9=JRhE8X1?UuJnjeR=o^$#rb16rm;Uq z)c2v2Q8T4|=y30^k$@6C-C*3flqu(AamxlU>J{J>X{%`o(+2D|F#h#WS?dJf;I!Kl z#CCM-Hier7+_sVpxkqa|dV6R$ed%R1uz79GmsV(%dl-weH~Z_n^u@zo%FXEzuJOX= z!Oz%#?6Y}7KGJ#D!F8wRrp@g`K?l)a=hyx9-sY~Z*ZVqqoBPsxC2-fE zZ7WB8!i1CwsVPY65x&yBwLy)IQNh`b1=(vd7R2Qs@5aUKEI>x*{y!`mf;%ENIhogz zFpglIkBV=JGpOm#c}}gPn*64Mh6X|$8`e~pgGe;OU{>tu(W9vTr@UzdJ zI``hGV`;u_@~fkwj>Y=Y&-TgmayBE*=c5=U#pYu&bMU4^R|2e~JBbg6tda|J!iq>_ z^y0+jC*HCXPOsYkCg$|dUIs%xKbsO7xuveGHK%A6sVg+x|LZjdmkYxq|Mp}=g#y)ztM=8=gS8kjy(Yip z#TO0I#psyQzx=YawUtVvIb3$oJrwlJDJrX)g;km+Mvo*hMx36b0Q20GgpiDw3@9By z&j=4mGQnLiPtbW>NDQ@pbd!T#1AgRbvVekpNpU{3_h6VkEjXb#7ne{nNhY}zF{-Et z_JzkpCFR8IEZfhO)#h{C-k$f){KnR!yrYRNiJ`!GC78~66jp}t#+P7tdFhoi&!0ZG z@;&&xv^DdY%+}KC3txVC`pio|+E`uPO5Qj*pe3e>x=aq6{Mr3L(4s)^xaNNho0f{wiO2Gh~Ogh zHbJ#DoAIXYl2X%#>K?2!YoIP@*YYV^zQU;7ak+M&NkMl*UOUhRfVxz3uOXh>bHiO5 zcq96;U9irMM%)g}jmk|m4@_ys7PzefLprVA!=AU^d>vA{nO=;~4Mc^cv{APOyy-IO z_dIgjBSR%XlgBb-#qgdfQz+~+v}e=EDLp-p+&Be8+?3r@rcIkNW%ur$-6D2SU7?9a z#zyGkbTzkBb{9n_QiXKS%C*Z^FBv!c`s*>i1L-$Br2lIaH+qBzlsqvp2A`;nd!)8;q6L0zxJ>;m6=8l>^Y$R3~0w9NC2B)adaIQL>nm&iuV)w0k zNXA=!V5}+Vi0LA7=v%KyFNOh_{?HA7^EWuuulXBE?((H;rCr0g<0&>>?)1TfPYk&Y zIUR-?DKT6~K6&ycdqUmZIMC$u{-!0<^%!CI6h!fEo$WH6p+Wqkk6UFU4C(^)C!q2H zP1J6bE>Qn#4P??YDD();90o zMRS3tjW1p5(`(z8PQcC~Fm|(-)~r0=x6;;p6QuX`t?6s*+q!k-$_j-{{P{MTt{K>> z2ulak(ZQARvWgtWNh(()1Si-90UZMi6UORb`f5H3pt(eM(K}nS{X_~R;aInz^bs6p zH7dHrw_r%e&0-KNkoCYEF4rQ*zOcJwbs1ok^diz_HGGT{MtChn+cCL7S;Vb{hU#`) z!LnO|p*Bp*9@I#&kcrjIdCI-Bd@;(T{Frlr8M#Es4R zuH#9Kml54glm&Jo+E>#wT>~Jfd++{0;)G&NLpQ4KhjJ~mFJn@1xq+}_ZEc01Zc@4} zHheY&771Hp#40yy+Y7dJ9IfR7UTf^t25#@|>VZ0Y8+xgc?La6jZz zv>36iC@wLMa5^mH=;Oxc^~mGR>8R;=Tu{?H4^GIN+gIQ9`lZ*2@}MYArv`N8>p^ni!qkWB>=) zZOWdcFvGbSgE=p&|gYWC}=zfUr45Rb?TVVc@@=tz~4l z)G3qk{WCAqiFCU!FO&kAJ5kex={XkiN#oCoZio-oO9Nx6i!a zb7p?kzU?pHckzwY+2si>sUD&O#pJyw9;Nf>e#*@a%1_<$Q%i1cOA+bh5fK#`>QI|gMd#L%G6eN` z+unW}LA|7e{KMP?ye>KV;FE;UwNR@l{rPuJ&v>u8v@9yKH2qX{^{K|{h70e#edd)B zAEK`}R%e&`%R*Brv)a{p>GGWI9r=9Nc`rb8f?k0C&8>gCDn;}Jk4~Vxs;=~SCeq)5x4Np5mpsakhAWb)vMS1sqNaoC z38Rx!qHFT`#V;*ze+_DWa2=07*97L)JX*IAY%V;f8LKP&`wFLD2c`4uhjkfWB%#a2 zq13?*qg=krT^oodzx5UzFJ6-QZb|7@IaK&8CEbK{K-~%IPF&Y#+4H`LzdabYg;((0 zBXzfa3UWG!K%9rnne-%dfxnjAWAgz{mzr+RD|)&dF0O4rPDfC;CRlf(y2t8Q>@R^S zjla3w;uaJ1GQjlGFR04|quiI<+z)E>G`iO=y7juD=+kr}r6%amM|!5Tp{B1`G=6ta z&+U(_m?Auf)AgKk>k6FfFOPWnCkX7H0PHB}Ft!79qjbSL3*8gb3+DCH%a^H7-D-oE z5fjIcd7S&~{By?3f=b?Vz-jQ}?CJDj#T!oA%XdOydht-*8#z{&9R~Ow!sQBwfabY)aThV8 zI3Br-8>nnb#>8IDS$ne`1v8_EAY;{}qQ3;MYjs>EF;FlP9 zC*e&oZ;N=LHEVS^o4xAvbPs?9E7z`FduipKtyy5Y7g6PYE52p8mRm)199@2xzN6sz z9CUCRw~l7coFhy(v$Y&%FDz%{Ni$^;n~uCLpO~rU z^l~t*Ss3edXR)l97LGQo2G;Stm{N{;Wtgy6pe>5mdhO+y*%`$};@Tf&Tq~ernAr{p z-D`WZ%&=5o%@(q<=txG;n&%f)uQ7J~IN+VDXPM@&x2@TMVo0*OaL(FZ2V(+U*GaKb z(-_g^Y;i}iCAL=E+m^UxFv586INa$y1(;x~KooAZhZ_y>zZjkxVza4jCHQ40V3}D# zvVhowV)3_;vxZ_}8wX}QC})L8TYIbNCHu!Z3pG2omNFqd-P@MgK(n)OFRr1zFk9(h z-dSizz0%dq9o|s?$_fMSZ?Lyq*<#?7RP-y4{%`$C7gD-uH&Y+KA@D+Z}y)%bKev9o!)=6 z?~{vfJaJ~tf?4>_b!8zy<+7q!2``X3cVbevoRcXX!^aIOr9T&dcL@uj5n+_vZEy}j++ zPWrv(wggip7evR4WfwzlzWt+DUO98*%e@z>pUEse)v&j*Aw6B3{w4YEXI?se?m}y8 zwQ6%UR%iP12GyTD@cACR@|k6X#&2oe+{!1BAEsn=>@L#M4bxSU6j#!$Svb7HNV*Tt z$jZPx-{D)37Vk^qZc?cfKqGbAh^=XLk{&TXO*KX1#Slxg>cL z&^5Ga=C6iyorwV5h8~7f-N^H%3(~Iw^(zE_m8|{^0y^#(8Dwa;xPjF4TYhjeFfJzF zU|23R7ofYDQ68ob;vA>-+`3^!k7O_YsrIaRr0u>b=1sqE%%Vjr?z$aFzvGVkcHc4O zz9~}{-F_GE)S_uq+NMp}{ql5~VayA2^7Kj74COgv&r`x~#ynPw*=b^Tbak958#gXn z_#lDMG<@FbgSlk+_T`A+rlwCuA|Fo8AiB-|O51|C0}`Pv_B~hbA;^(1M1(rCR7UCL7Lc9f<@SS8Md> zpXi@)i&3=PmQVwe?kpI(nb$cehdqY+Xe=)@Zpj#(r0s`L&w4r1=_$(T8=$+B=PwBp zdU9N*`NP6>fPEkOZdj-Wy6bf{3Shbr8&cPo2-7{Kj~n2ccx-Gde75F|`f*g$EOa); zH^|nMfZE}=z}sM&!`Qk= zv%Ds=n&XJxE4zK!{mR3(w{7&g-`2FfH1cn1df!+Rc-ltZmRJ6M;3LmZi4?+w1s4)P zNJSjvx5`~ri;L5md|g?4xA%3lEB6)zg)BwVY$WMje{!76?f{=K#?ZvXklg5$)CfoE7U5#mMPc>d_Qx+8uOp{> zkglyB`)zk^Z8J1GAwQUM>o|9Uy9>LCdchD4LPP2FD>IAeyvR&{W)!Z3mc&`*slE$8{_L|4-+Sg*Y*&WA0uxJFctlfo zXT31}quvGKnK4-zMD%5nLmvv*St|k3No6d`Nvz5#tcnBf!*asvj3Dc zNL5*4J)=v$#M|@AJLk@=#O>lwuWq2sXl-O{OVl%&nHMgcKC|hajg8gS4cY6m#p;Tm z-*a*ft`~gbp)DnS2i>T?A$|yA*fB!Bpolcx#I9b9gx+^;J2L&~C zsTWsTP*zq@d{#yJ*1g%m*+~guaS2J`cGJPtFQT4kh~#tux)k+LC8*P1Ie|T!BAUu| zvC7>8ch#g%Q3%&NF?7={EUF|ZC^|QxE@o#A!8)Wf76p@Vga3bYN(dDT3QFBygZ!JN zrvG_8-HFE@vO8w?@Z5>%TBPKbfPn64=~v`*57OCWlv&iFbi!TC=8crD{-bc{9lL+% zY3Y{8g7huZi)3^SQPkC=)G@Y);^ufk9G6SoH5+?W?v~+SpMvuRdpeh@#^~NLJYF|O zw-t644Eh<}oAyxs2e)ul@dGhBPigAjyV7rfadJC5LE|2eJ0Fao{7M7P1?mhmRL~0= zx@qU0gf2o4Ap0oq&$e}@#euH>qWpiB!(`FODYviaxs_y=a$=V zk@@A0DO08`nj#+zP5L^X_2o$GB6R_}o_h#n6r;Oli|IfO>JVsm8lGk&Z`Gs|Z6lT~ zN7|e&Z#rr^RZ7Q?pKWS7_x4u|9gY=71{l02E~yboP|1y=Z>kZg3h7$CAYDjT?jbpS z>~QJn0(0HQzU@24>_+6mb>aA^>*#^12YS5myDeme$@5UUy0Qw>SC1Vvwa4lbIdOc% z0Y~KGbJvX34`?~q4vhtxs@`CLV7Y^IF#Q1Om3Y;0HjD?y?*`N#CWZdt*S@%u`bPS4 z?cs+7>JO8fKJnqdQcU;$zox{;lWL2?)|K`xU#wA*RTuq8X-)RfIE{ZMfmWVY&TM&? zw>)0klYbT8#0L6OWAi2k-0btFIck?3SqIls^O|Z3%rBsIElBIa0NBNDe0gJz-NhtZ z;u2)XzXZ|s4R6Gi)$u8r^kC=$bMH~%$gWisSr9_LDRlUg28xmG*p`75hsV#+(9o4(^7ogboHwG48 zTM&zJy*q}3WA=g2^#v;n!X}z8sroi8~=c-!2VUpb2HXNM$!rX9w@E5s>Lf({&jY)Iym?%dopl z>)-i~xn69cEx$smaB)9TdrKu=>j?m>u~bL!rWirx1DZRYU|PVe_!aG-t-T{a$ZFm} zv|1|!^bg&jF|%yZkN29>D{GCmbQ=fO2bS8{4YYyVNXOBuY5CWbblce0*@cVS*BhFW zt~(Cy9n|ZpUE3eXh}uoJ&rm9stCJokXrAh_$gTOsv&v`r;7iUN#p_a#loHj@Q0lKvkK~4zDwU$R zv$K+)^MYb2w?vpEl%6#gP?rb&iq}O(^#1mkGsUn)V5yG^GZC>|Q}}!YLgv@RRT7XA z=N#!#i`V0MDJyHqEW>S|my%ag-rI|U{=sDe4%P6I{PC^JLiOHW{sP7aMP?EU@2`!B zI99ZNR#Nz>4?p|wAD+IjBb6dH;W=eEI6}$&?)>Pj%Wr+uTb|MCugJ)#D2o!~SxSe2 zIzl=nM|UPBA}<#P6GejY1?EH}h0^yw^UO2E92%!jJ8^*99Qi(fg&ZLI=~bytPY%VI z78FyyzI*|8^iHA|)nD|M<50Rfj5;Cx-@kbF-#tD@N(b4geDw4_8QXDv$1Pp}rgub^ zZKm1@X5Zt75rcozdhY$(51l!;GwbxlHx^C#-ae(%=t)a1o^`aUP6SL+`j<{h$MN#c zx%Q?7*!$zc>4-q-dMqwn|L77Zgo~fB#n_9O0j>e{C{k89dz|@UT${wjna#!2^E!qY zVgPk$T{f5CkgP2FiuwxtX&HVBd?xw2BZ9e0qeJloQOiPj4>7*bzcn{BJTn|jj}q$h zv#ccKrKI(R`EM_L`|Tr*t;p^r#YM%idPy?hOzXCnUU}`E(-#^qlwx;DFU^YNV$ssU zD7kxo79MsFO!|#g*Y7@8cF%r%mR8CuPZHxp(^Xn{jIXS zV15y%@7wG+eHK?LII6f9B3eEuDJdu~C?Ym}X=Yj|w`m%-h6IOF+6qq)wtOY5^Bsj( zR8|C2-ZmsO-bh`dI+(5m^>Y0)r2n=AbNh_wr-88t^FLipiWV1R07{O|ZBhLxuE5n2 z6Oy^e9h9F`nO$1lxW@Z?YmoluK)qi(H%Z;&b4CM5oqCyw>DOLI#2*7>bqDNbN=HZ! zG-q~E*U?9ybm|$ISwvP8DBb)nKgaPRZkH_`B4-s}M(9dZRPGBhFyFXQ+9EyOU0Y}fsq+Zf_#La; ztoL1UPW`a%F}m1XbnZqrcgyWk(;c4&(0qWL-k+P!$t_xO>xM%^SGa%3B$;D+Swt7o zo+%@zu<9;B`5pK1fX(#^(;)UK;&h|*-P5Kl!VYud<(D_TOgk__R+y7BF6}|qMrk*A zwt>;RU>(hyKB!3RHp9A=3nAP|>Yq26(n7dirVbxE_R%r3p>@!_XEvr68d>WjiFp}6 zUS@Uuk7pUIjrM-iO>^XU0o0|YGkJK#^|yUz6va;&$ju@)CliR67ooc5VR-g6HU2uo zcB$_sr?V|$x^cQHFCCaXWW!B^QPc62PaYu_M?(kHC7G_Ka+5R`Y!{!qHvO*?)4ktvvx<7tx+Be(J-un~F17uK z^|rctq<_2m($M`AwmG|du7AtAi*En;8T}tNpn*NG+Uj<^4y5WRHmy1;0}kfa4p{K* zljcje9@6A6T44IB2dPk`0l|tEwkZ786DQ1)5#uJ3?}DcV-5sFk4$Mr-kE*&64w%)` z@ji{D&nS^CraS|_0(GF*8py3OMKnWoqSCdJX2LcIj9EqVLSk0fm+`u>Hv^B^wY}qU zhu7MWeGJlVcRRk8*zdmqv}R;aciD-~qOOYqc4TirTPJ0puRCxo*URh7Md+;NCDHkv zU4}&*Ku2N&PJyRR+9Db4>f2ovcyIauG2LifjA@+dBxH&0fq9QUZM|)#j2DqNq^mC; zLTv^fb2G_55l7`(%%mG$0d*ZmE3~%`a%Be{Q&PAgw>z#ov^yUi!cIuL8|J%LFv#~* z_rQVeIND7Q+w01VT_D&utQU7j{3@nvYn`WtU&Zu*nr?wLCainM7+`v#zvt+nC?F3c zpw3HGQ56_e1egMA3*v&);FUDE5$kL3 z?C$1nRCYlIks7f<*evWfPQR`bQv4Nz^3qa5GyMfC3kvpbCBq^sI4hg`R=^MOtW+;G z*j9~C0G%Ba85OEx=%m(Bh;i@My^VY6QI{85y0oz%%HQBmQTI`7=}IwYXON!0bdjO4 zxv3GgS?0(7?st!U_t;~mnWLr$5Z&{v{}$JaYu`6R%rSpvY)eaO>cQCBl!IIx#1Y6S zw?I)*SY4RX$8#t_l$i;x(Px!Tn7?*_j=kKqFW!3Vi?_b`_1Rv8fux`~e`Dib%0D${ zQe8ASLu&eG?_D^SgdaIFDuyee!ovFWt(VvpHC-}#M^jh}m=+39I^tDd%&Ov}b#+IR zDP8X{7I_#s9gM82+qDHue-n4Q!d~tnl(8$#msOBOjU3VpcU87m6|Scbr(E{si`Vy_ z{pix=%X0W07scG83PuBsF7mr*0TD0ro^D^?y}qfbsUx^U)t#C;I+8*vx0IfqEDpMS ze&28Qe|hBM`%j$tr zC|rD$R2P4@uM0j`6H9ZGK-UAB4G9j3EQ%sO9_I-(52h!^3F9TF>xUp#=gGr0t||#g z_xZXD>XW+bGYCuR_NDm>x+R%&&z<_R(I~w;i2p{!2~9{&Q80RH>*+g3ytA_PnbK3~ zr!c*soOh=8om7dV`pU@A1Y#0{YO~g@TL-^qmlABVQy!bLEk|e3ffO-)SJf{0oQjww z001BWNkl_-y&NZY>BZO{dTo*JVVz1QWjqru$>U%&-$4 z9%4Z+0JldLi+vFkwuA1Tv6P}s<>no6RJ*l`xwi&aH*HBizE+@6zYT6z(d7cPDHT^aW>iu|blqyn1M)v+OvgNczkD#V2QH?v(Lx-HEE zDJ@>Pa@mN>Ggk@Irw<3w;lsgmm>PeI zdDD&4ts^Q2JUn77f#-6ZTNhCY=)}9o&~h8%y0g8Ex(*#(53RHGMsa$-nod^a5DJU7 z5oovJkU7&&V0xJjX&+butxG~T96u1CavQHA1bY&p9#ENbwIOxn^aFTZHo@xh!Hk%W z%R$oPy$|1Q^;{jRKMb+!!5oY(NY_Z~mVY}n{ztDd`t>mTPoK*`Ebia(s)YfJ7ESXf z((a)D2{sqJ_aEq+CTul-mRKil5Dn05cEIKVu<)FE1J-=wB=>=Erdz#eBX54nP&Zzd zRnWQW5-s89&k`_QOGZpz;_}e3uTQe;Ip`fbjCg&-pOpM!AgEY&#q9(WE(QmM@)MY-i_S;qZpkqGA)YwU`;2Xj+qkYsgzfuERLbx=5&X7a9J#AVire$Jk2kDw)s{b%L1`mUE zo7PI3V>7RPvzYE3B=9~3Hdgmqd$*jb-oN+?rsu_`=H*3ZSsfh|zQRI4CMO((peo~H zLbsEGx`^~U7@q>X!rpmAzoh8bF)zr5@hNooOiRm+i0bafHP*0{2=M~IUZ}3^l-V+2 zLToHl4Sc6$ZB5_0l>&@(yNy)ZCJW=Y2#kH zb#L9eb!mE3O02)3dT)9}1j*9+3n91%(NW~-Jf|uxsky{ZS7g@K?pU{O#|||0W_6&n z;6;OSv%oM#ayo8xkKW~DpF8(hY)j_-(Rs&?9mJuY9~zdxEd^w0(6DatVhWL}e`8cs ze11NVZiRwWL=;c@*|Rdeyv37-MIB*tK~sA*r+sQ&R%Y3*s`X9jAAa_KfA;CI)C5i~ zED8WEoYh2V;MtFa>AjI#TBzWY(86U&Xh}J1 zqI=PcF4aYDbYpZO`p4%%NJ1Q&GJMpg$C6P9r$f59;$zYe6Cgb8#N~NMj=cTO`?o)F z2tvR3#vAwCx8!hv>ZMA%tty&TJWH|U_ml5(ju1vYfAq`N%!-b#wBGWj#Z`6tD|0f! zI}Ee=lsV!SqKEULGY${S*;$E{UdfdSnmbRx8Zt)%|4Kt#4vwhr?&|LF)z_y{ezaS~ zjWX)HYkl-9wTu?=$vnVEq_{&@b^&<%C+vaaBQ_2p{mXenH zH=lm#%=70iTv!UFHsp4@$sQl@J@t%Q3=V=v=xqok+&Z zCogq2G*o97_h@5q@J4ybD*f&LwGTev{eSCM z)BhZ&J4M|rE<#NL2h};!Sze^7qoxbc`Kv=4sHI;g+H}nv=?u`)ZzSL4R(ZLh@o6hS zTD0_^AOG18jnZ$SW2ER@^ejJ&)6=KP!7fJc5&N3mMm{iG5wxJx1gr$UnyO=h7Nwjx{%&}JEoT@ZKkFhrQcz`mnmX& zqx7G9sIJj8r1dE;Zd88L@HB(7mW#Hbip~Kj`hV&G31z>hkDL! zKv5qy^|qcig}li1!c*RJ^BM;L-6Qo$tD$m$j6Q-ITMZn>V43=ly1u6X{$z*gBazd^ z>4I^Fn($gcNN0B9U#scm8!7hN77{zG8iNj%4VMGh9N5Da24)ZmC}a*-2R3DeCi^$) zpXlG?>l23N-eRT^;W!2Ct&IL68~WFe$O)+YsQp+M@?+L*6PVjB)|ghGP)skz?J}sF z3r3E0OzQL-oiuZjx}7RT9T|Nb{iub}a=OUM;*@C3irLM9E-2Pw6UqT@0NkcQTyZ>X zEV>qRt1%~}7YplmLk#Q=%Y@`?p)o{kV{I>xw#x$9((UMOgTNYjY)mP4^0&F*brE6f z%?m$xD$aEslabEZUR#G&^A4}GF%-A&gBfpL+PZBg<2qlQulIh7(S_&+>P|M6Fl^2j z;rHJN+WXrTzGVvmF54Oei;tc1Z6m{C$J|11BW#Z4fLUW}EOv;^-T|0)Yn-mF-S{8G zDm$L2oLAB7*;X3rP{!-pLThv+ZyR2X9re_9c7krG<7igf>2>u2?$oqA(5~p_?rjY8!vLj%0i}v z-Fo6zQNEN32ld2K&NP{T-R%?-1ynGfH>8&q`2B?7MRG?zB`qZ-39kquV@gVFra!$P zGkb4AY*17>T|qf&P#TdHQE18q1qG#@+3CPOHIaD0=XT2lMr4Y@4QT|ueB4J@QcN)a zcDBA3%ie;H_UwkGaC$3hdeZ{uP5;}x1rY?VMCDM5vM??vNC*1kznxtW`%FvIf(1z- zu>=yv((O>3MJt|FbQG{lJX%NgPDTi9iRUAc(nrN5$kJt09X(3d)b}rb_T!&nX1PSS z03TT9=t-Bt_q1U$-qS&PMsrc zF=+01r;Au42YZpEaqR-FGeHyA2gBQ7IoU!gI-1tiomEfgiSB{|DjX@1k!t`PBViRW z;R5uO2~JO^3n_aNBvTX|iP&C7)mIWiFGZd^Uu8U{OP@|v2;_2ZK)_o?@YghntrLXAbT?(UOJnmpQ3LR zbq4a&;yU8wF#*=O;^V@1R`D(_hA;mrl15o zLSYmXNQ?{5s;I4~jq*{W6ak&0AL^V8vEz3M4GN_^Qd&8JQ_Y~{1Zvao2gf0s)MRiJjL0zZ&=%BQY_JVeQ`}_wUbbk%-rX!|%diuAJdO$)Kc#6wa zvB$-ikYQqrv_@fzPD&T6dz^l)I7>phK%LNZlG5c#zg1O7Md>R@19yC^&Z9EDNJ}>{ zeTCF?JrsDZNj5bp-MU7a!fv8C@NKpibD&SbhCT&WXCQmJk-6yH@ZF`X2b6d_wtEE) z?=e~zHhax3Ap%;uEH7q(VH`kp`RWDfUekMkKYu_Is%v8%Z~&PHCU3dtE=_uBx`Ddh zEI?gPy=QvoHUu!8lbogkuEPgU6{hoV71N8Sri1CX-*uPNbb63tdf|C>n+Br0w%g=$ za@7y0f2jm^tS|`dyLZbA^Ap9wIAWKuu7ak5b+q+MOl)6xUA^2xI6!y$JgdVJ{@S%tlLBW}}nRv93V%H?1DvO~;(BDEGswr;iy-S5g=8f`rcF zJ9;BT<5*yLS_f10E442V(iw3~D4hpoNP7rPAATF+B6*C+=@P`{K(@}K0ZeyeV{`Gj zNZnBVFcsx#7+>bh8F6BhVq!)}PUoJ$xbfreo&4|!9!q%MJz|6u^obK+ok-KvYnrpc zU$L4V_{abMnz1oDb&dF$>V^r`iB_#%g5yQ@>H54g#m+RTtoEU$k+(T%f}z-WjR-jK+*HC?BdO_Es55i+=+suA`_K6>D3Yah&aK-+`l zva{1m*|Itv>HL&K9D18F37#)SLzmmd#PpS0_lno4X}UDKHY+{7APDD;lhaL8S4@nx zyuA3@0<`oUJF?aR{hZ6G^mP}Ybr+W|N@wcz-&zc#%}H%1{yj4$ZFF>PL>{U@bW2nT zs3@B^5q5ElyNN|Z%3~> zm}b7U zFUi#KM4LXkGe?+CnV%3{H%Rb3s=D@Az!O`~T_ijG!yi+n=#Q6(gpBXvYUlpcyo2!v zo9A}Ee(9e-Kk%~?;K_08HfqT(|89tm1^r*Y_~O}Tp>-hrgOAVd+qD1}dvY>`Lz7dF zWgg3X22AJDr1eDt*())q_invB?ZhqbwvBy)Tx5yq7Z;(Xzd>!J!|gy{N4189Vr1YV&jj_5vI_exuBwzvKDf&JYjATvr+*8iJN&evcpXZ=!ssrM(Q~L%*=S%hW;a0Z zhjcNzBxoWSe{kbnH$v&kVZ5CoB(0)GI9}k^MLnqL&g){{bRoIf(@jkGOfQDuCZ-#t zYryB;5FL>iTz7~rRCixmKtEE32I^N)x=HC*sp&#%<7-b-cbqOr7o0Ny((OAjPQUp^ zhwDF}WRr@kN=>(+y=`~hbq|N)8}k6&;GDrde6fOr98}`3nbSwFz1J zp>@3_bTH-3VO~X&(AFKzFH@3Zf7?D|*(b{mtG?0n6;4g(Ot8Fw>xY!BZWeSj@Iym+ z42Ry4+oidi=S8L$VfsKd9a2Y6U%qfTI3{GAP3k{rWuVC zo<4cp_*bVtJpJJ%4}YKBtM+33<^c z09FUg`8X(S(LNOh>#8wIcsj+5Aa$M#b*-jNxRnBzL)`WyS|0|&YF3_-VS2*3pt1vL zcv-qRjB5*}th2&N>*8u-U-7xbY$dzU416tOMR0D5tXz?{(Y|8q{$0H^MuThlRK)3q z)RN@wOh!(hJca|=N*zuI7>gsuGAjG#x|TZ%53G=MZV!F0S2b@xTNc1{ zdq=L?YT%4_jT3nL2CnMwLOLNgmXe5JArVfd6b+&K6_I0&j2Rvh6&_U^MbF6;Dm?n= zUQLHLi$({K5z`$P=Zn@;^2<}wBK*}dk*61|D=003^WNj zNV@Pb(J6GNr2LR2vD9MU=)h7=oge}jyAB>C!!bUcSiUulrA_&rQrY43rl461%F}#v z)7NF>)Gc1$QJyYu`ngl75g}-&IhmDye^_}~Y4usubdFO#D9zcT|Pdo?fB(OopYO;>uZBL zNXUfIKmW;3b|1gvIRDO1++t1_#k%}Eg`2`rTfcZg)B0?cBfaOoC#=1H2t0ul}Ooqu!_RegOb1(zG(ox zA|^(hPEsS?Wx;v%3gC*7r+nr-iuAD@sHjK8h5N9iBcXTjm6p~~ivgyfzKNowfIXcn zq?_vloS}4-G$eJD@DNG^WZ>pe|5eJ3BCB(;6P;UDjq&B3w~qkoTT05RTi2d>?F@BR zPw{chrm}8%c{iGKWn5Bja(PlnJNGzBTGu@P(ukMN%=vKdg%`OjO3e%EJ9*$Ry{WmK z#FZh@FXD7%AK{lTFD@=FPvis)Lj8$62)jDwQ?ADAE$Je@c2q=6UfW^ zf-y!pjB>mLBy~jfuQw>X{|UK+<|9=l>n*M`<#uqWWQ96}Y1?>S<{q`&0m;hafu4eZkq@YVY2Sa%>aPz!@H+%mW z0dVds(0_FB;D??xIekOVqA9oEzC!WosOh)f1!T+ea-V(uoFC9v8wU9)Q%*i5H~K%% zIB9PORIm3%Ri&(lt*&!+PvOU~V$mY>^#e*>KY8-fQ;NRcqv&f`7F*2p!5au#dl}O)=l$-8cFUv`Kfza3Lp6S-DdkzzOe$yz~ z(V_KGqaGTi0!vcSue;$|@w#gc(S_>naUCxOrBiwdJ z&+X#%8 z)#^FgkX#q=7Ff2%gyV8B)vFjJUY86lC^x-X_mWsEBMi%A0S~NpRLnd$tgZQCMtD3} z-fxyjvu1)FrIn+Hqj|FpQoatUJz1>{bO@t&cMM)jR|-bd+F;n^kz}KbuC=v}Y#w+A z`?@H&o*MvK$4Yi`n=l?aT<60QrMWQHNKcNyq_$@cbQj?d9Xi!}iw!Wv=pK~A+sZ6) z50B9`>Ys!}uYy}MC=Nh+dp)6{=dJwM<5;@7?T2M_)|dU|aGN$!n}7h>~~)8G2H4?fDSZHWp= zNQ-aY;m;{Ly1t-$K{}NF;qp_d#|Q(Y(ksD>ks+Zi{%#5!UB;Z=K{3`^UspzO2DLW5 z-0NuT%c$r@vIA$Ky4K;TMhHd=#k5c&^E#OR%!MNEt2v>8C1*d0oC(vx(}+wg~8*$hTj=p8F&@maiXwFf}!|C3A0MY-(%>7tK+Ta{7c5 zFHbLOx`?J?b`hj|oSqa6o+l+G(v=|*^E!u6_1_w<2Lgod#^iP?D7~1vMry^>Al1*I zC`9#2N2lawWVbgieBkn`2bOr4KFA|!*Xw* zsB2<$L}rBao1t{sxuru(Nk=qagqVK&E%)5_^PlbJsf?E%Ehf@M@;T%TqvJ)_vqzB4 zz+t+Z)*>}2<$S@Lnqp)KYBS6Oo+cJ+u^uL*3)bxlfRQzCWYb(63~0{zBG-%i;_S_# zZr_We^jmNA-V5G2F*|TBL8K#Ojo@@hol6$3jX?BKULR61dZ3}E-yBfW z0qWgT$UGb@HT}t{SWc-x%7upy$>CqFcSeFpM6_Vp1`)8Xlx5qcyq001BWNklb9mB-kwe&0GWw_+ z9>RF8DXHror;FSH^?*;EBl4tEvI}LDNZB)Z)P`Yg<4=rp{&E~TN?ydG{-Bf6QPg2K zJ=8Eo*m%ye8M<#v`tNqmW6!der{jCU+pfY#C&rza{P2<`$mr7_KJjWBkMR)ttFZd3 za=S=Omjy-y|6iCM;EVtGvDsY|rl<=u^%B+3U!MeKrKT$+oxH_m%)44fBrq}o#gCXg znWPpARkR|XGOT#rLJgJiz<8`I9a@dmHioI?j1e6N&{`~PUqW-kX9H~quB8${rj+b9`wL=OL122vY0yn6_;sn?vIx zM=JG2htLblFr)84174YhgsFFZ$=T1>MY*h&&UOS~VhN9cx_4CHX}7+NM6Yk_fq zW0`lGc(Cl4*S2!Y1?e4 z2$r@)30%V-rbk7j_zSX9@>8T^0_T=424er8>R=Y*L)rJj`4{%hBJP7al%bJ%xv8lWQe$INA|mo?Qi77Ag3A*U zLvZCsGzH<=SU{K5j*tI1ZQ9R1dHZ+2`_cPPT)g;q|L_k#{_)>keB-`}-+Q{9togju z3HRUs<+)#q(0Tm+Tx&^j9B!HQRmCM``;q18MOjo7PC$HyoGv-2=z{c&3|Z5|LW;t< z$ACNCj8}y0h@$lb(Vd#E2z4Pl?xP&C7{e;CuY@KAXGu#(QLiW9y`wv;JF7AV-?^o& zBbqD6kU~OmIyE3*g=ZN0Bp zm~3G^M+NBs=PfI4Rvx2d4j1fVh7BE5h%QRMkuUI8hHj&D%;$?10qM6)yYFW|1Jd~j z%LC&z>p#i>T*tj`YPyC})Aco=8>z@V0OoGu$`Z?WfzzjG1BdVsJTJkQaNSLLFF9aj zJk2~~dy3CZQa9F?>qVe0QC*!#L3O+O=#O~`sOb*YuaG)#l~~=5Zj^oxljO~Bxa~Sq z&(YIu>^v~c(QfwsF#_p$$X5&={^XOW=~MZqjqAnK^xNBZo9RU|IDpQ;8rwS?3_`iH zrtkhaZ}ZDPJMiO^C-?mGC$6)p!*_g4uF1j<>LbW=9J=hW3twV}h|JbO+!OzDI4CWEL6(b*HAUL|Yf9Yp`|3 z@;Ni7Pj0(jGQD!t+2w|SmM%|_&|L)YOfT-fgB{jV8CT$Y8Fu}s4MPH9FXk_o%|WDo zfJjEK9RSs=B&B0?btmOyP>9sG>D0{1s zg_7NuOq@J@;>2+X>B#4l@T88Xbabid7{eiGFkBhuf^i|V09hCg6bsJ9;#zEzTFed( z&JB(Q=QP^_!5pKBDB1vA6^__a*enaWu-lfnBkLuG<7HvF^U1J4P8IAZ>PjvUho#}@ zF%rD3aTa#fAm=&=Zq{=pq}w^L5qoKwJDgrmK(3c(i53sXRTp?Q9aC!^@CUk(Ix*PD z(u80GZKtIRQ1xJJ{&Y=T1+5;x+7<@o4x9n#E4~zQs~yAey8nRQf!$hmFaWo?D+8l% z2k1g?ak^V+BV&A<>c@09r`ND61a|dQbgl4CX~2|yZ?=!t+T4{FXNtFGz~Zl3)dQPq zdElur@1nO`;CD4T1g`~KcLE0Jn$WOyOKP zh0K^PxjmgNy!FQE>?B&}Ayj9T+%l!5{!CwNC{Zv7i&0cM+NvXx{!*F+yOSnk-wlL* z5KteKr&*}oI*E(aWy%?ZfJh0^Ji;+ziA5n8q}IPKtJc@-tF5i|Wp|gSC8X4VsVP7@ zyJ8JbE~a~Hnk)-xM99calMkl%%G&bpQ11uld)MZr|pmjc2#23h8^t4jzM$kU@Dw=C)KfHhgr6v~@i0q=SdA??6qjti*v% zMIMUnL?(dgn~CzPQ!P>yP_kYSnd1sk(~+eqJq3E*|IB;JPXF+|PcOZ7{KTSZ^c6k+ zBrX@4bs2@vzxYCfci;NrgG=YZ!=nqoTG`ji5))M#=@9V0K z&rhk%pxbX+L=sk!Bp+FSO-TxkS#b9AwtIfIar5S1%zNqLA}lXYz5eMxP~qr}5qo?j zKjsfgC4|ul>Eyfo(-tl>NV!?OtCG`K-J&|dXH-l@MP^|Jk&Er^64vSe5EteQR?1Wl zFA|%}>tZ7&QPUB}Bh?`kU=NX!4yXr*#Gsld)Fh`RW%%fzinpejY8|NAsO)4pvJt^J zG!BF)9TS`YrTZ&!4#^0gkr82Gn;aBk+eeO^e&_j@mYgFpJ(oA3 zupxUvcXoDnVIt`}d?M7ZIB{_msp}>5G(CN0CYZj7;p$ITfAY!aCn@zsO6kG8=5^BI zxfbkON=IfoRlm^K*pR)GG|tGB(aAw^3l?BdZ*MQecg`&cIy~>l%siHw7m-;I5gX}` zi7cv%!gr<%8OmN+z$wlc1a&$G<9Z?bh2GhUW=u#BsFM<@dZGzbT>WaxO$;G?hYq7? z=~~BUiEo47gqrBw@PeJ$?T~tQ_Qq9L)O0El(VUj9(VwnM>S^lzBghk6hiGrza2uu< zXLvEbw8I9vje_U~w5C7{Q|T58r%Owpa-Vecg6iDyUQ#v>k zd}%nKf#FU?mt@Y2n`1(@mq25kE(g43sD1_6ZK;#eIY&(}5?AXfytc6zT}}N%jnp;1 z(o9Wvt{2a!Zk&$!#cQ^+9ZE;#-hxc%p3Nnoqq{M0;mtRDf3^|Rq46O|U0^z(t}djD za0SVmPFGUGas=siNg_~p@5Gd8@~Z10{>J@px7+~kpM3HYgLeiri&(cQLAra0;sxt> z=)IFTkK#Vs>_-wUvgj=gg4-mNQ_%^W{u_*9CJh|_Pl?a;M$^c!w?=%MdCBwPA`q!+>} z)r(YD0~@BQbW2+gHXFIqWqZN+LO)Pty|{{_s}Go_YOpR)@7L7P)|c<$ze{~>SNx83 z>3e4^J3yHu2kDzmj2!pigAbsjpLi8Sw>FNNqZ42I3aCFkaijNh`mfP{{5!C0p|D#D zxnVhA&X0Z7swGPvlzuMD3$!kWI;rWbgyp5NPoFq>%(%(p#=z!O>zq7sJRL{H=1wK2 zh7ogOaSzj>XOTB$hge}$E;Kemwyih@!aUUO)NtXh!L!CXrjT0eB$=ye&ReX*YOT0i z%zpjQA*w>8#kSlnG&x^(c5O0b$he8aOpj+XPJ#=9kt6jQ+Cw~!Yd!EPIuO)t$Fdh< zckQZk;F3ViUd)i6fvM^Ocv#*0;X3IT*0hKCT!syX#^z#Co7RL!w3<|NvkVQGSs+Mf zso>bwX<%e6j@FDVy=ts2C7IihX>U)qv5nnIQ_tMknkLWYb_6Z^TGMWU#(ia*)Z6nd&AoT-4P;~9FMAvNO)tqI$c@1$=`!uAd^sKZ zC`}$59!V-+SNyu|>G2b~(zmbcsy{_B(!Rc|wAhHe`lYaWbJxMHu4c*zi{QKR4>mIe z4hLnWFNLg^qKN?8h~*%=EQicF?~5i@Vlv;mm%quZX%x!Kv@YEpVrMJcR7o#(1eQ`O z#!p|=0)G^p=HdZ$>t3qemsS@-q?(U#U~nQQEonulQ)UY63-N ze7*=(O-u4o#1eA@Q8r{}kRC%)T}=&WW1UiKlEE7GK8UFUOs@gO|DDIPU#J7-2Ood@ z@!4HxUm!i3s76Eh4?gNV_Smt^?)B?4GLMz*+J{AF&wt1Cav}BL4vFa@A+ZS|QMoOR z)g5R16d2Rn6jv98zKX$yQuQH;)V7Z<386D!Zk@a$_|pk{$tg;lB}&JOqO1;odllGK ze1GP9guT3f@x8hHU=CAP@%X!cL_|N%gKTt~vRs~hmL344KwH1B=g;nHU*EL2996u$ zYe!ad{Dhi=5%FCS@lifvx9J3#Uhg{?-&LCxKf$-Ipev;-tDrt2w@YSxZk=Rw(;2e& zgX6nTEZ?=hbNLz6^f!KT>ap)XB~1Ux$!`4H`6Vw3(#`Mk`!^%fI6F#~?mxP3*U@Am zM#@yfl|aiV%CojhM~Aa9o~VQoK63cEh+7GSf`)i9x<-cU%2t;(-JWvjs}+S+?xfyq z&FJJbUx!bWUfa!x0(B7)VSbAGP=Hj@==mQK0U zKq^Y0j8tMt*%}P$+uniF-+AqwbFGcl{+-$WjO^^V_JT^h-MD6o6B2?m=zzI6XJ30_ zbV5YSGp8W+Gq1cd@yw=~pR7I!r&9*IzUv^Jm?e>C&h12#qu)YxbpfVzBGw6WiOi*I z$Ap^lCOX!}Wn^V##_rfN=k)32dzS8yr6ni`|GeriMUo(|_sL&LU9c$W>9M%d<0Im^ zOvTDySrJBtIweU%l5$g`C&-wdkm!l#;&HE)aIKk0Z6jt&Y!Qi#3V9h_lM?LD-kH6# zv^}S?VC{oT+}~SIO~+UMgKM2J-Q@HDQGRXg8C(LusjFc55%K5h5UQF-Y>>cO+%*pa$LGQ#AA9i$sxUl|~&3({5L$VBzKAfUp&!ysOz$7qzTQ8^JJ80bwPAUAa;hj@D%py*MYvub>FIH5I=2qM zbC}((N@U8{w+pF@ySY38wUNYSVBxyx=MK<4Hb+c9ZclGsb&-^{Zgg+UOlD_5$5UQp z#fID9^c(QA3?F<5kUoUp3gI-@aiod}hU%5AYJ;S495+tDFRFHlF7mkRsG@B31RZSOoEET1`uR{!pN;hroFPZlcM7oUP8|#NTGH!9 z?b_bt_ph5?MCS&W8XBZKKzD(R9swJ`GVR#abYx8qSR$77u-l_^$L$WBJ)UL<9^!9S zdQ9xiioOF!*Rfdd9nRQ1u(ct$UJ0gl$I;|~riIMfN-Z{e*O;vaZs=aio!7wEb*HFn z7QHcQI?6XTd*kfAus2X|pY{&?0wqVr$nio|n24xwbUG}*$eb`v6oPYCO6T5FXwRK} zbMu<}UhnFCJ-s%_7nM@mcM9R~VAsJ3U7hLmd0l;-z)5poXFNWT+NDdgD>A602!Y#Q zTe;HF#&NF5rY@D-gm6jduCd5D&?UU1uUkJ;M08|GN$sa(ebHW$=G6-o$4q*4qoKcP z_A;#(WJX1VS_e{@R^S!_>J+z1ZASY}0c{doc!*KdAn|-eVl2H@d$^ng!;}LD{>N}I)RhobmoB7vs5yA>)-wzJ>57MR6l?IY<5FwsxbW{3X*=n70ldI**K6Z zj%}&hmA$kpJN|s^s+G%(BW|>vt*XBqJOnL~(Mi<-I6E z?1mW%%Oa=#45too<+1Z1Tis5)+mbLft3w zU2;f$^!t(ViBJiN3n{|9T~-!clp{_jno)xK!guaGy}9+xb88xRmQ-%uxuBA?7ea6Z zypiE_S0Gd|ZWix8Dtt@kg>&cje0X}!nK??XoAddclZQ#p*t>2=3U2d*2b-Il3r=kn zpA!IMT^OqQsAfed*|eMziRR)Q z&wTsNo!O=Br5l%cm_7)z%QZ5*h|+I%nz{+=29sYIT+Qe%ZP4kj5eU(>>dZbv?Zb;RD-f%nG`p z-Z5d}=`C@tzX=|k=y$ID0Bc3CyOG;m9 z1FSCscG+LHlhU|~)ao%qhC4<#Dg8T;x|!3-eG#9#2dGZk%Ty$FE*Qv8A3kdEim^Sz z+S=MI@J01RT|-kxQU%uabQTywJ+Qn8+vXgeu{C|~r}SRhp&Ux=>6=cF7sGRW+vG_L zS3NKhOS%W?6V+c-okmG_F+Mlv%ftVL=>fd>D;Q&CQ9V&eeaR9`F6ifibQE(}<_KFl zRg6|Ys2a7aDL*=qfOJxQs5`4rLpfR?Y?xKrHtec4jNYTxsnhUVYPlhHC zsSw`4+920x*~}{a9X-X^P_aTk!k^)J5q6boT%?)m$*Tz|(7va~Wz0@ak0S zz*-w?%|I5mnZSa;*xM5`i|rHOcoz5DTkJ3*@qWvTrrqYo-3IZ2J-q`t5FOM9Aa&&f=m$~LKRpF#WRbyA zo3XBXFLch|TB+zzy84dNBUB5SMI{H)@u@3i-MBoP>_)lO{ZvMZB3p*|#>faR6kt1S z5{g2E&8hb&W4bz-iua*^9gcxsr4egPK~`o~MN*3JTqS9Y)uDAOp~QWDwHj%Os=z3Y zAFa(al(#oIKP5H-XF4p70MF*IIbB2#9<=V2%%o0$>3ctbeEv5~hEDT^79vVMpHWsIri<>g{LyFwp$EcR@vF zE4>N})w!~=n?8SuPWe>SHBlsp=T)t(i)) z`Z0p!^_`@}XqFBK@pL`lVyvrkT~=0SeKSdvC)$>r?d|*tiRl*?jX(Y7{&h1hzVX8! z{^Z>LEx%Dxy4sI^`DO{4Jy$?A$m#p`@83sGBfTOcBQtFnl^KIMocjXSO;q9NlE{mc zat@|jlDg8=2XK0%x`gI%izmlWT~X=~EcG_eq08ufYsAl0sJ{{gpOswjU^haV&MBmFR7rH}S|z@mrZefA`&+9Ut4ne> zS63#^!t4U07w0C_A^0mKk*hnIM-p0cbN}|47oWLs?$ec@&N#XHlh0S5ynNvDfz^t? z*qffI-;aawnLAobs~a0%sHP)Eb@i!gbzWXqU*C*xzmI)R0{B2W6T0w4PLC+Vvfo0= zPT9`Nx*}}$QCwH(*MYS3B;pt&e5$5Of0BxrilhXxUWn*H9M9EFn6Ed89LH2(O$nJV ze9(C&Wg(^SBwmLutyih(*Ze@X7ruMNVim6jRjvpMNxQJ<=kxvvef#?IJnGyjkln>K3@!mq z=WUgc&M+{gxhuN*24OmK`Zu+KrWgAcs{W%7@j&nzzF|?@loL}ZOscM=(E6?Nr1QMI3ojc775dF zo(v_BarjLzx+SUKgk$9f+%ThVTJ7Q;m4HYs(?GK+0sEDOrj$y`a`n3 zJoJ!5b4z+bwC9z)rgIUlZx}LmIMt5Gdl^fyBLdWs)km17t{$PLs9Qv%N9xeJ1NNB* zK3TSB@18xMZvS-dr=KFHe==gzWaY1qJ2A3t;;O^*Ry{m!oPrp~O&s?y4>%nO-FlH) zrK5=>?tXa0e^3|Fw1l9v6jXqSZgs%icVQ%}T~b$S9g29d=TZ z%M&QkoSaaeuL^u6CEA4b`MG&12f5Ro8pHt-lDVO6i*xDclZ?uO7^Od3xw)hmaFPkU zXfi2Oau=GzuvmZ6RI!b(8sfUt#fbCbW^=CBxI@l2$2nT#pvn215F3{0>^#KLwHHsS z%;HAJ;i8Omn&(T$EIp-SM%A8D)OVNcda$?BH5JZ0jB9+i}@VM}fQnXurDbvOq{3%kW%8&KjK= z-vNhYJ?o^M>ul_loRV&*Vaj>{(+w@bOCVFKvC90&GXMY}07*naRDrt0bmqkD2CL$5 znnqglP0d(VE8Ijtx@LC)wg={3Xo?-f7+4*ktPMOQd)Pkig_tvQi?niEbL9kV13Oin zn7G)Ap^iGnXs@Q14&&wFzzPA-a3hv_-#~UK2*& zy%_mjDl#(sPyoz~Q}AkAtsqK$I| zQ_*G01!^>!z+$%36WJVCAC#XLikMDu(;6f7ntZyPlI5Z_7licaROIx$a>R7f7=i0w zfAs4wF2llVZ_yR6fT~DHq`hRJzx7dP0jKuD3)wqbcO5PCbrifuZu*CNPM?Yl*L&?J z)nq62iPC$`=YF=gE0b!a>lepSMhV|bWo3~Gqq+JMRkpwAXdPi4R7AqZofua{Z_}c( z%*YmM9Ff5tmVWBO9%_-&jr9AeO=my;;4)`~&jm-0Wb_X%^>ufgT31U%NpcXF z&IK1&UXk3TK}ZMBxh_<3BLrg}(#V75dhrmQ%S3haWJ7w6!rM7|*H|lEod$JR#*`)I zhGb;;x=B{yLQ+kf9v+;;#>7c#Q>p1O8Ns1SVib>u=ioUCtMmixIdZUvL&3x{Qr4?5 zCyv@ot!t#Gzw`Fn=c-$G?r*IkK(VgQC_Nb=nxGVa8P$24igD`CS{z=;zk>T|Et$_` zW~T4merd+ZWhXzur4D(oCO~8F>+9z3Xg-#b>ML#FdKFQfTR|7-RSK!o$)mGx#(_`R zo+fMiob9JNo4K)(6cH0shm#*lFT-KO34-ZZ`okl+Y^GmBLw^k+L-}09TK!8#UGfa?&;|s zs}Df)uT0(|KD}KrBaaBnh3H_WbGzK8_(en0ekol^jGmM($_;?}U2r0f7je1=>E0TX z&jVR3a;nSrV%aao>H_$yY%c-+?#J~2lLs)Bu}w0N(9Y8#xn9qjVBMQ>BkGvy(c|VHJo1A_1mfaxdm}tRXJk!_SqaLk9ujXL?IEFh|5FR_ zl@RoD^UbIZYHdA3HVoY$N}tMY>8Vq%+n|V-o)x#=ykg33B46&hRn>}Q@KHLtr7J4- zMY6f*+%4dJp&~0AiRA5J3VA?EzY54@m66ruE6r5*TZUgJGCnkP_LH;4=tR1J<+#vY z(hFV}`C&A)FAy8pzTwaf{c1W1~i+vS8oVBflO?Z(5)4$qu8Y^pIj z|5Igpf%OmFH0s)G)t%H6)YV1R>^4}`WxT`7?cV8=4j-Ngo2$3zqvIYOckiS3GP>8q z^bvP2;qkx&4F6-i>7z$HFk<|eanm21`M~nK?_4Fb2e_>vvKA8IY%}&M(wQLcK4$TH!j?EWEr#7Yv!Nh z#OBYRzwpS$ZQHg!KaZKG=Rdt>&C^GY%wMzS!8@NnvUBH~PoHCp#L##@p&@FPK-w&o zN5qg9)@2cMTA}^nY={@GhV4g=(L!Od=vXUQr~@FMGw1v;!h2D%j$r!_88(^RqwB|t zwplLNR(DV2&luIuFiGz^y6qw-)L=tZ%7XV1^r=qh4n) zP>)4MldP4l?m5`?z1TAE9TrydrKdMGE!{ZX;V6(T%r@?22>Kek4;yLS1OEo`w69aOggBfW!+ymxp|G=0`8&?zf2{1q8d8NQ$-g5Z=oO-&Ur zeckp`9T58Ky^rv?1ojirm%2(9cLFk$=hqzP3NpQ(U z1fbApWJRXG)bGdqLg7;D zTH9Ct=m}`)v8iqeoX+MG4*vajAN$|m{omhxj35p!8t|sqEci7l`df6!JbU)+M<0Ep z{+aK-``p>H4VkP}BV_TdU!Of&PnaLMk^cSb+p~O;-~aEQefZ&rpB50{fn9}A?6R_! zva!t^@%0>%FFw zH#ets)%WJ-=K=7zU^+35kOL2+^X#f`PCM8&cU?U@Gt#z5LEEF}xtA|L8{_UZ5u=$@(4iJS{ISho`YwC)A_` z+b2rg99&ccKP%lu1H3PU3Wh-H;S?Ogu`V55h8Lx(3)Ri>f|RbfMy%`XN?jskciBR8 zXCkA!GaEkd?e6Usr+52&WXYJC?h$=bupIBfIa~_pMnq0zQBF)zLISxjaJsG!$V@4U zOXB(`ge>|kjYr;@_l~j|=bz)h#agn|Hz($zCq)-ykOBXr;^(8}V=h>0r7;;c3(Gq#LDM z?NM9G8hhFnXx>KWCaDJq-CQpscY}3|FW=A{w-2QEDPP%&y}c$v|B5x;)^G*^LH#N| zcX%EcLhH`dRyGXdw(?d6*1kMFHT*zpTo`W&-R2Ngo7id z8}WkbgphAgVEPKw^tLG^y*%=WSzVCP4b-KlPcc3R#6{^0)!h4_p?ZsY%`?0NW;OQK z1;W<@W0_;vdeQLfh+lk&%Z1sGKQtR3j>6mwj7?5AuZxNs@lZ2L#~E|z6RGL)m7E0A zfpP`CFf>p%NbfhQyJai4&R8~S$@KAU*H5K$Di#=#ISpFxSJQ8DRh2Nuqeh~ij~_W6 z&&yq<^Xgi%LC&BGDxb*>xCjm;|NV3 zHy)q+#DyEzE?i<*PI)8R-GKp+zT|mFAUwdHY zwvF4CEj)5$_UW~acQ1Kx+_(pp&ztw)yh-y`Eu3^@{__t% zdiT@9;?wiCZTsHBHQVNWZ`=HZu<`e{J^l3jBlCGKT)1uH{Os!Gr`I-~TRHzUWZjxm z{q(Ze?!9v!RDR^hn${OiA6fW3$bV$swvEeG=FfZJ&gbSq z?MIFr*|u;S+cD`MvMm{k;bs_@3Hx&&`_$t*=?TZEfS) zwc8$C4#+>S(AixFsn3BD7Lm~v?}Fn+kuQu9*0s!*<9tC$A2D&<`0-LO zy^!I@D)t4y7FTOi!87{|A&Ze6%t=0m5o`_2TlY?JHO;ODbaX>+TdQphyX_#T=-N=b z(L~@Z)*KzNHMafOoNEh?$SHG`F+`pp9Bl5d(I8_>_|mgrJ7_mZ2R30)1LJ;BHzNKT zusTKis>NF5+5k*N-@agFZ+#~(UQl*)aZGJc(D#+}^4<=zUx@L>?GZvv)3Vn3&a)pOzW=(n zqc-!I$|`PV(7J;OLWwL%aF?T>kj{*?s4Cb$2(@(RZCc{$Oo7^xbu^1C-_Gv`)z0v93OE z0-Z*&vzVIR+>6ttV{T`!nO;EpxmjR(Z)fj!J3HgEO0$~lf7|)_i4%Y9`(OY34;Q7U zKk?3+i7$+}kL+~WUEp-`T{f3QbKR4cAH>a({JgZTT0Sc!snO+4a_s1a0JV$MGt@CU zL5!igkC}vL+>9-LFdal^;M8>0Cpo(X%ddN9Ki7pMJWRo9V#(96`KHj+0!^4sik}|Twiz36rBDEwUC@BqbTw;2z zSiD4oue4mdH3O=1Bbm>RdS;ZzRTdbc3({%xXFlNlN4rf5#5Kn1GQKGCB`{#@R$5M^o9-o8a|A0M1UU-Q(bARiayy|f#^y%p zW*TQHQ6_*o5A`SIAtTI{FO$@J3_lr)$_J9UEw=?$3W+Iitps(BWUq#X?g6_~(`}(H z6(pxy8z`X*&Ic&!9;-V=-J&J|btLjfOi@Qtzp8QN5}A$H^R^(BgX^g4fH~0ZG|7&6v{H;uZD{5S;kA>*fyn6!*sM+xN1_H5m|tOvFkGI+y=sW)AR54a5<%j6ND zx#C{{bQ(%3=+4BF19P}`!0+-Y#Yj)CJ}`oem$tT%BVqn=^Hy#>yyQvD=@cTBdj0_I zK@@aNF1ec}BlP%>QPT$@l8+cO?(n4Xk5$n%Xayzun4 zh4a@uJ^%TMVEMMScfYo4UVVRuC2av z{Jjsu!4Irj_`P`>@BQ8p7H+)z(X|U30q7%?N4py?M__;cxjUbmf8_0_w>`c2>20O+ zzPE8c7X^)L)-=xF27J#y^1{)&r{~>y_wz{m+q4~`{hbdWhSQ#3xa&`owx%=T)c|3gYqpv>t>ce;2+}*Eg(F1osY`8w}g~lUKzp#c2 z1eE<{cOLN&N7ZIk*2wygS}##%k&s>a>FDd^f6_HrCK0$8CI@U8D7b|=0W}Nk zDQ-7~+9+F4i(oxeuuKz~3#2XZMGJ(!>;~UDxCXh6$%V))<7p0fZ8VlN78dAL_>CE= zo}9eom@#5<&9RE(>ov4Y_>A#<{CFm1H6KsiQOVzIE8h$58hdF5!gy^DVQY~P9fs#6 zB&`GA!f)-x3ibojHLHzPAqh3z?ZP59Wx3d$vtjEirWYZoJv3&+G$^w>REDdoP`RsNb6&9U2oA&V6;iq&cML zBsi!r43-S5s6gARMGc(z)E8}B zS`eRyJZ+M=5Zt6`2GX;^a;-4CxP)zK<@`FSr>BPs?w4yqzEjl&?d)Y0j6~PbLTh@0 z(zR0#7P1&AfEpA*5ts-c9U?J;AZ0Cp#1Z&@W0`A`QU?(&Srn~ zu`DKUeY~r;bE%J9cCz>e^*YB1@!m?)Trj`2G`zHaz+6oxl41?>_$GaNqf}>&q8(cV}bS?pjcg5thYu_s@MCn>erE0nN|NfKlje` zg7oyv_|D$?OUI}E@lxMU|3Py4p(oCqi#Tpj^5o@7pUk_ znqj(A(gl`UnT2|8k}q8aIz3MR25u01>3XarJP_J_=+S@qmy^F%l(+fPp>%P&hspAe zgXm^OVcHz&@butAwir2IT)X5(K4snJ4=(hrTP{8L&2M0Sp~=ef05L7@VYU}#wgB(oIJ6G94;65gA!b-}z|PQ{`?-az z=QMTV8&^Ji|D6ZFj+%}){gJ1k^jS)Tkn2VC%$Mu@*N)ufiTVF*3QG%8z6G{H%mgqv4-oX)3VMT z%h*}sYf$wV%pF4cI^ITg7n6A5mlqd#K z8Pib4Gomuo7G@AS-wl5Y$7u|z-{PI-RA;cj&Cbi~*2A@oPu}7y#X66I=Bvf#jQKi+u}U62JbwI)sS`+Pk*6FAcM}l1h}`&E zlr3I1`CBu28I2n)4;ujJP_gBbi){HvA&duajlZ>tF*{p`iH)#TCJCF04CW9r-9N{I z#-epKsqehiW>C8l(jogv+&C~36@8NMolU3An1-ER^LSb0x^P;&?Vz3skvE_%CyOYZ zW~!^oMsLHM*2YY!gmTcdX7lqg6-6CTxEd zq&ikMf*qvTp$TQV4Dz+dxu%Vanun3^pm}9zu9SFIF<-i^%8B^);3nKVx2ZeJVJGO$ z!IXHL>)x|66JJ_+*mmBecOLeof@aw@`SWtRDeX>2ck6n;!>H*fbEOoQ2?~yhfYW18 z?Q-eTC$oA|LfpoAwFEM*Ur#P|S3l*@YZIiV&)?E7yUYA#{nQz{Iv+V5I_~P-NF)ea zdihM?83TxMIwtcGarfTG0GX9SERwI)q>Y=JE@3XPF!87f4YBJk#b^i-&nYeYA0a{o`>&X{rYUWL~bM}TwqO+cB1q4 zAcf;`p+t{v2)q+PP5@CJ(QJ7m;P(Xi2we)x-+^%`cc7Jr`wS)iZ z=?fPwANl$3ZrteYi1({6$;=P$ZLgRcTS94~H5yQ8l^DR7C5tD%_+rzGdnTSxXdt&X z36tY{;um+!@93dhtF%uy-JPhi#mP=3Nz>pYv z`oyJ^{GDDxU!Mqia{}rxd8%k0*OfBE6|ZhWx;$Ajl|!uXJ&Uk?$g&>eN8wTKEc*NU zcH_Ik`_h$M8;m|5jb!c#>AD^8lL#+Co{+=T8lQ=qG{)3$q;z6mxOq^?r6BUv)0S7a9!VQ!`2VFDTS}x-oR2imBh2kO-!i z&)?Xyv6d`Gq51;+FAI#-LG?pt4!v@A(Th!Ik=w!dfj1VMxw!A*l`C&tBvpd751mLl-PB+frEf!l|0j84>rqA#gmD$XA?bxPT$hU!))h<{D4^D{R(V)NmU?t4FT zPe{7_Fy!vg38bIkZ1a$*-sp<~E-AEb<$o|bufT|oT z#^~Q>Z7J|9kSSfTZp|PaJQt$#GQSI$Zl-jSPrmWpmEYm!CI%l4*oEs~lGDZL?(%$h(}PIq-{9q%&!KLBK4^6L+dDT|nhtZhX1aF7 z4Z3S+)7~VYuIBxqX3sb^1wGm0bnG8@I!qt^?C47^c+y-J5C4F@06ZSOrs+Mx__d7 z3)JZZ3Z>K2_z7$}+)BLsFVDTs7fJgtqN}|iUN=e?p@ZnIiPhy*XY>N2IV;e~m(G|f zRZp>us#dDTa2!RATJE}M^w`-8=Dc!f!T8sIu=L67gwj{3MrqPIFg^n#4EFw!ceTtA zluJbi#~Cq!0fxbc3!WSQ+|=hzvEBq)3o0w{))KjN#q(R&O`niAskw1Vz!>E+(YsjH{I*2v8Q2A8)ouyNxm$pE?=4!1$;Dd!fZoV(t67+Xr) zTR6enu46bs2yab0*O2wrwv1zk(@??>FFdyJa8}B(jHts^SWwn=ZcWKp*tReVcRLDq zTU%6K6ash~l-{;5B`S(LfL5>^!5-C{SqowEs7loDsLJYvylZP{Xv=sjW8pQl@u-EB z3*UmhyOF|qsyb9&wGnroE*%%J83;E9*VsUv(OaL0$v@Fsl=MbX`nC(qx$p}OSqkG{ zY2LpTQMnn@0dpF>j=WCl%fouHP&JRngXq?0RGBJ(Hc2h~ zyrphSQ#UF%KBwEIdXtLe&ARUV>mq7lFi3pYl*nmQ1>}%9jUm9zx(3}2ywTr*b*b>o z)Z)9QDAOD|W?J)XZ;0%|bg{hFw3I{$deT$@I^b`cs~4yaBZkI@;$gbP@lm=N&=Peb z9m}1v?Hs-qkBitn;?|72WP8zGnP(%m*FH>{S7}q$&{GUhTxN7OWoT=f zATM0k!y|Pq_x9s$>g{Z3WTb5?xovc0UbY{trM>AnyxG3EEYj3%dkx)l*pY{C;ikFC z;aYmvQ6ujP-!aBN)Gs8cv@9`PVtPOTNf@~#)e&e{nnbE|T=3+@_r(!PZ6(=jJ7N+N zVko0oI=?qza$G{M+I-M1yrZ|bqrNw}s%XoWq7lHe6TwC5_r}FABQ79d@e)Gi=&LD3 zoguVtZWik=3Z;wHO;%?K%iwPygn>*l&i4(kOHP;V#mDKg!Q6*jPqVF{?Zps0S$Q?Z zN{2yQSC>^4P6E^w#165m(Ved-ySzMUBXM`7rH1JQF5+(Soz5Dp>5CkuAOFb#dYZ-- zMELiulQo@~7sT|d{kL(v{FhH|?96QMsvQxRo_-&kzUB^B2EPK>XtP5j~URCyUl;OD1ze zwTA4!iRpzgWHcUFRGW|z3@T~Rsl-1Hhf z8eLOUp45~SN?p^qi6hea>BO!{_m_o(a77g<3JZ!!kBwEweF{Crl1m>O5g0}%Qu<25 z(nP6H=Bcc`yuH0wn2sinIfbsIY$`pyCO4!wOt+DNfx#WwLUV2&|Jb+tD&Gfix7Zs` z*MI+14ku10C>`@TlX8tPiv*ZxeIKEgUW~6K9M#@$t~gyOI`SgbRc$`@)?3HcT_;9y zZEMxmv~%ws{yCv2VL?>;Os4}ws9I@IxPJlXp3gPq1FR{4n-dd)v5J+>FGUQe_x1es z+}FPF!l5BieL%80U!!~A?jZfjl`GdjdXM|ZWiQ-@)Nc-`uHy^+T?suM3B8H*DK3N2 zDe^?QqjsV!@%@CR7Kf1kQtD414E2EKwgkCfw{-47*kY)m;D4O|JVW*AFEfTK6P%_+60xZ6Bud75?~X6PlX^>iW9( z>-TILx00;zm7@txzjSHbvzt~D{qphy-+%f0;`9f;|G>-N|Go_BdTQV$y-00$xGmu3 z1*1PMVmD|PxO*)A74&WkHCVan;Qa^DwPj0xWY##m@(0Jw!qozkOHP+l-F)fJnhvNl zSKq>{q{^%g#2wN@KR)x$oPA1HF(@}02gpfjSW`$Ih71f;<`dI#~X?K>XE&xLVZo1S zbTyLEXDf42Q80Qxo)pIC!2L^OFY&bCjs;953q6WeWqS5oF(t$K`+f<}<1oh@o zqnevX!R_GLs7FSRTJHPr_5bd8;p}&(Pk1B`Q~7mzfVO3|0nr&5DBSXsoHGp_gGt)y z>p0Qrpvkv|_*)RrQx3OH!}JZO!|hm1GAgs+Y#OAWf*m|6s@qU~VP(cbd?%I6$jFFV zh{i3g8&xCf*s+Dcc=f`!B!x>1$DIOCPm@ChYs$9n#%)I4VsIAZHFxW((U^wN^EBPq zoTmY(F2!7%TZ6@~F|mzTUh{=*Y?;@6;VmfrEgsPYM3A@(0A+=X8vdWnk1U30{axDFGetb^r(=Lt(^ zgWzTn?!sy@w&GnRhud9%LHeXfcTd0yEOMf{ zPG>Yd(naBBh~f6y_N>n^j=gX;tZI8_hL-xg=?0eunEIc>6k~xqr0&3WIL8WVzreI2 zRO4E+Y>R+Be)WyLx4w~+vRO~4{JF*qv9PUREUmwdHd9#5?idQ)HN}QHJ04n7i?pjR z?9e+gTThF<_u_wBof)-w%~HLYgb}Bhed7 zkD(Y0Hr)!;NF~9A1`ysfnevqJB!S>UrzVhJaAHh+KmgS|I%meSQ}lVQ=_7bH>9X*U<=G4!}j+=>10T0 zKMYLMHa&gJV&wECcq)YQB7W`6AblnZd3s?0ed?I8n1d75O~q4qT@N{7Ok*e45pZX) zB{_M1%;K3RHtr80>sqJ9xs;TYOg``vspUpg>3GjnHISa$nm(p?b1QNX*7 zU%hRyDwl8UoY$Wq+*N*K;g~gjA7Ea8|LUTS_{{Lq?0FxZ&BpYy@8k35FDFpbHIY0Q zKYBnmH8oXrbU3E(%j~P~rPtv6#Kew-1iuhGBYVJfQ`3(YS5RFC?Yw61UaB4K*i}=I zThWn_SYC8%-ukY2{d1}>@W1uJgWIAm-?-7*x;BR^n3)f!< z+!K(F-cOPi!6IYE__G5Q;S}PAg^=DAA%al>b_SCcFBt9`ECE{Hkm_iA&bRMw2<7D#MF4Gp5rW0GD?z zl&qwEM@NjzPs_SZESb0^|*6UjjU#UD_Rn=6ur>Lq1vpTg&x7HPh@lPS0 zzRUUqY9WCk(Xj=Yi8*t*_2C~;5@{?@I#p0ZBbEfH20^H9ZEKIeavQ5U&X=158h-fj zFUSA#2fx(R84}m85T<$Yz4vZ`>BLGRsmm-gaOQP^Iti1By(Isna?_lP`2{VV3q!YB za%_raRF975w)h;DKu50``{(FPczNOunr`gi1c`R>XG z$s9*aKlv!e^poE=@#`e9MiEvW6I5ImZGl6lhG^hx^!vurg7s|j$FA3OuzI1*)K$2~m#Jv!d6OC`4f|KZ^#8hW!NYk|w@oE7rJ)V0_**GyQEv&?fprvaXj(j- z)nKA`lzL$vLm+3EwNO1_iLXJJo>twB@m>uZxZEgepts!NG{??1W<~L|ht-U>8Ct{S zOtU~Ev9>0J;LY7aY}=%}8yq+FTBBvHn^$q~6wc?s^)%TGKW+to0?mxQrK5(#@I9lyj)tXer%Bv7`&r z(a)_x;F`1Z;4T(q(rZj1A4EcQZ z@%8j?OGqRc4*!C`Urc>aeN25vPELJzeL{Qh&g9PIYkF00o0a1oQQL zT)+q-59vxuiF&2F00w4SH+u|JOoU&2Nt|BX7-%hCYNGSS;`BIx9jP2G9mfkVJ@36& zp|83lFzFrZ3dPscXYSdvr)E!~by{WH`{>(=a2()Q+Kar-jf4u#SP><;Vkiu~EP4J! z67`ndTAy@+YL5XUVsa`{6X);V{r~&tfBw(^@Sp$l&+gt`+kUmKt}c1mWvS`^Q+{$1 z4ZFxtzi^@Z^1A+cFK(O|kUoZrHie|C_hDrr3$df4equl`n7*D)o)5@^-zC_ZYKPBE`AO)oq=pZ?qmsNlS`@8Vh7ro+(6E<(o0-GucsL@s67OqZ^1@ zpF1}{XTyg4{2V|3keTUm=@UbO>0%p77H1}&ikP6lh=>qylvqIjj*cZg2@`?r;vM-r zbJh<$bn<3$$a`#rr85lnx#3Y}l>kNV!;oDCIoclIP~451G!m>yBGW)0tN z>`5x7xRJ_`5-q5nqc|~CIWrSYumQW}dfwiM-5 zJ_4~O(Zcj#zaXsXIO@BuLg;#6#P6+5jF0ul+ftJ&Te?tP0};Ewe-PQ}fu!)7Q=7|C zZgoEW>dDX{?=mRSFFdh`nxR{7T|a-gs;Q_bY)4gH^qARpjnA zic6Da&=B-<|Ud278o&je+5~$-_r$1>w!8N_vXD~xVBy0g4^NsK4a z(jSM1X`U}#a;x#N%;~NT`o=}=f^-GlWZW_Kq5v454-Wl%|HVlX@XyMOzj{ONpq0H~Yw#YA(%bjRo#^3qe3E>7R% z950^lMI&Ak((U2>pbjlhp&llE7IE{UM2@rKp5s=I1A_0Ny3d^lH$A)ZiAzsd+@ccH zzi;j3??3u|GrYjx=;@Bkef%wC_L|W*=njT^B<=yd+ho{=05)nmrWe$7N$Cn>Bsl&4 zgE|wCTtlClZk88jVtL^%Zquf3tkfYC6{F)lPG~+h^><#`M-1XeJk0Szw^DJsrUm6* zd-5ZZyM@A#$cwnXV)=5uUYIcfU452Bbz)vxT1JfPf&A5w?w>OVS-yhfjr>;1U?Z;d9*Uij9e$c(9t8EN#p`~?;jd?y(h zZvoYBbx$+MmeZTt3RLh6v~gNxrDjxiPs4xWHHE-~;DEM_C)iYQsL*W0JM1dxjTFXg$IC1?YTOyP!qPr?FhJy4zNU7U}YD0pl6hu6=T? z?b@|#fVgfem}Uwnx7QI38DOe!J9aMR-K@8c(V=y7C4cPH1n8?BnahjLi+CS`eXP(C zzciB^pz9kG2kJ1is9dfSkeq1%+xUIL1YjC^hIy&t3276~B5$~{Gy{NE)C|9(N^7Pj zc`e|K6sGr48($>MULAlQqs#nh9q z=*Wm7rJc&GVY=)c0m^PeU^_rLCOd#cmMb zbg!{saN0NTi(_3(U-Pc;9ZTpxT2>n79}^HA5D_0iDju}7gXHN_a^PkLhmME~Ky~CR z{h(5$!XSc3$ZI52Jv(>6{E|MF&`d@kV`6sW_wpJy#wB2%x%K+>Tc_)qYS7Zx#74w-y+1&DI`ADI?U%5q zfBk;CkY2g?*#5^}yoJp>6lHn)n@w-NdF%Z77y54x4E**+W=H4=QW+=4#MIZ<^R-6E zo;^+lEgW<7XhmvtG@UcIZ{JSB3*;MIJFlO%;&uIxLU6%_r!O?8-01B5-4XtdrL<@2 zLK%w+(WRsp%%yT>LBZU)xpSix`Az(~bmmYMwZd+_BsLxkiFE5Ae$13#3iS^GY(sMW zYoOft%$Vo^Vii;OHpTbdJoV5(S5EPHqFz3I;-j9v_^hlB+Arz3e|5(@ASh1k<6Hx&_xj9%8> zPI=NG^lb$0x#1P5K>uWpf znszkpMO9z7wsdjqlI=flNIBeD9FQIxAC2RL+El?IBx?qRC58lWlM$Xc7w>;Xd*a;i zaDVzmkfo@vLU>Rwi*BWy9=doRw4U{Y1p_x1{P?EJVZ3tXWBe}X{#4Ab?y5b-sg&(q zHg6u?PYGaOj;DQK`GP|)WGB@3CU%f!8IIvc?iW&Nau}s@RVLC;TjKa)?n?RHH#%P> zBp0lM>YB5vxW>()M=~Lx0ahv?-ao87m2UzH%XZ*>*+pfo4LiNR21ClZZ^}pNyw@x> z57bR{=MUM}07=@{Y-mdRJ$DlAqN1aE!0FGLkPfH=td!*ZTgm7=9yCY?elbtucfs-U zYe&lH)q-O&x(qK4kIm=88=28X=#t%q=rpJtDA(u-GrKSt@}+Ca)6IR5&a5YVYdpcS z!NyTJpbq{;IQPy$vbxMJ?kO}MrmAB}myoVbqylw&tB-7II*`tkN$H-PZm{kKqIAA` zunWdz^l9pLMKyRDeD^@z`$4T(vEoq5bUeVK!|JJd{734N2*Gq2KknRgaOFzs9O-lF z3P?!D`rD2K7p5yQhFgLMzW*;czCd(2TO6nh z#vQSnygmr)f^*HWc$nv(e1QrYudG<`@NBZpiGjh)B21Ah_|g=tE8~~HiqQp1$IXJr zVFpGRO}+l`_!e2&#pTxIKp%B!6iJR#Bd5(E#_?e?)Stv2nS{Qek{!uKDknTAE9)tV z>7sPko?5;7Dc7Q=Pd~PLwXgf4_v8A%G`jDtr3;r%-L_P|@?T_NBX7f(f^7D5Zf zL37rW&0M%H)CSV!(Fewv;=A5vy?pILGn9UT`Hc*^QOb4v?zcR{I*NS;es&%>+=b!R z&S`kKp)DUeU1O zxN)s$T}W;Nx02LxYhq@$wt*v@VBUZ7Bx#*%l?hJJ-Qw0L$WV%ysc+99NevN z17XKj3d~6F3hVy_M0CNW0VabXY9E?%Y;5Ff@XNr)4oMv)e{PnKRox<=cr7yaD4P|u z?28XWa|iW~sdZz(x`W6*^hSFy7&j?i^WDzS*xiJi!F<=WhOhm(X}4SwI^J~OhxCno z8~@p{yW#PHy6-Q?8h;96GYuZG6X|m9YjoZ z$O{LO{7hJ{?`?0-pPRq4Hzz0iM)H;$?He{^=Hu93x#249(~f`&pA}`}Q3f7%Zs}Rub+CTh4O#;pK;cOwzXSZkDNRA@7J!i)rryRW-2Ki zSjX)$w`>P?7bFSK?H2$5AOJ~3K~!`y9p`dW1Wy{hB5jBI`Ng1UM?}QXEfNOxO9)Kx zXCj2|3dMoYD?f36oaE^Rg?rx&>goFoOz%(Ki|YkW|IU@>5TT(JNF*QdWRk;mezr|Rt3P?!|_De|U zs7;2_dpOs#&!2tu_HE4PXU?48cmCr~uUvWe+^zlgV_vg3mXt((8JFRHIs57hXK<;% z{yJ65mt`k*)F*O}fta4kZ5Dk>!-eUoDmq~lxvCv#HI_M|z{+63&G(5{hK(0B~dq06uohJp3oco23|3yf5TDsx7f%*`ni`MmW zy1He(eEZwp4{GV^tV5d#yh|ZNS}}l?OJ`5I>weYyp%W$DDFx~Zez}CCPLtQgUgWdT zQP&LVKJ*?2;Nou{fU|2{7ldx+KK?i#9*p+*9>gb@=kI>}<6jEYRfY5*hdnrQ962vi z)A6Q{lU-b-P8U*|vePwB_VlO!hS>-ClI1&gXfe9ubmh@J^uWLT_{=`kbotPMa);vU z4!RM@K@1&**+@1{dbe zm_0#f$4Lywq}ODifbvO3s&8M}7#bYPr(kSO$Y zlhdPs^wm$HtAp-n>whgwzvHf@8Lv%>Y$h^M(c|ZEmE%>phFmVYibmbkO$EfO0r3gl z-3aNxwsiCA%I@mCsd>z7K^JGCBy&`47Sbmcj^5_DT+GhAybDk`b4(`(&0%of3(WK2 za&w;x-AZ?)(a|;Sa$3XX*2~OGYfAyk zq4d_Yl*@E`?L6Gw*4i4y>j+&}`PLvU?MPeHC&yCG)pZ_j$Vh3b!ujI;TahiDZlX}R z7@bTPehnDI=rgEfG)mrc$><_;6mr9K@iz%8;4;4v!fz4z1dtxD%LFS9Dn(kGIA%6- z_b}WNQAEB1XsPg~uS)_KrW@n}=)!aZdF@>kZ3hv#O9$8Cv>_w17wr^SeKad-4y8vq zGIZ_I8Fd^nwF%+Qonm(pW2cNBC-&z|WqwC^*Lpy|4lGmpSZy;)8oEKcbaZz=q0=$< zjD&n^rn=inDg#F6DfRF8vT2(&OkMYuGa3%(-kZtn?cjdy_iAD6EUU3>Haa{L2xx;cd7UfFxwWLofjGqs(x#d5fNLhC!ZKy z-di|5ygsqLw|?%19qox_IMZ(=Z&1tMkVDtHx%utMDAQ$$(c!__JF>$FdW^~OianJxdArfY<3V%9DK3@~ zW+ssSr;k7Wy>i2?Ry||ae)!WLl1HNUcfb1SPu~!&!|VG#q8*3YUs8clxPAA=#EtFk z?HkhfB(1-tg-<@emUg}K=f6As^V8SgquqM%?0d(z+_-wD@r6UqU?A^xFvUAM|CGC~XGA4RU%sw@bV;Io%iz+ycyr&@>M6u%M^+T9U7Ecs)+Gi|7ajv;9t|Ux2Ny+>+~TltEoCe(u*P)&+i)# zuV1=#Qq9%;LsKz@;B`Sm4~Q6nUe8@0T_U(A zz-dKKPH;IVC!ahR{YEIeac9}iiX23J|6ok?xo|qBcQ8H2pRXg3*TaJR{d#M&dr{MI zyHH$pURTE*yIZQRxFO}fG?enN z^Ai$Ev$w3h{`~bSB6ZRWak!J}nZ0Jr_R|gL53j8$3?rvKFfc)NR6|u^D2Urv|MZeI zv6y3D2ceZGLz~Y8VAwag#ym zYch3{ybI&`(E>oduz(w;qer>7J$iH}qkM{Qb0*yA?TOw~96D3ouhkQvAa-s=MRZwR zUHeXcHS+W2L8A$~ztkj~+iMu4+YDQCD1gy21I_IsHQl7)XTN#y8`9E^(Gk+WDN1*? z^ame&)=@ekFLI?LrVEpyV?8jht9jbCP1}3ro2x^q(YnQ_1LbCYVXSVW($k+{4kHi9 z<$f7Na}hc3e1vWrd)64CItSLhgIJtq(z!S7y>sfhaNcVywkc0a_hfWHoxn*AvEIw^ z;=C{J3JjCceUs)6GLMk1pWxi{yy*Vt|B>m1F|T_DF}-s2Q&|Mwsbyv1eyN_V$}H$- z_kaECf5Uwfu9CY}UgG9P-j{Eos>9fr(6Op(G*q8R5YEdtkhE>A?%_JigzArf%lefv zt$P|d+hrzK&b_Cmb6bE19TXR%OF6)XBjFr}i!fdD(9)%;-#_b~uRqOg1iu;IdEx*g4*8?1YpIy0VBeLFyX1={&? zwFPt=rN${w=4rHo{-evOXKG6isWYioS-zaFCup`JN$tz#CD-;^AqxSz6~0#S>v_&G z`6Q;7s4SFpak?~h)76pIVfLqvf$OV(@Yhk(?}+@blNzUG6|n>2w_?bCCeX zrAuv~7)G8_(q&vhpw>4jaJmh}>pVmMdFVUzVluXZBr})gWVdAXU#?q zW;-TUvZK;m^pq+szy`m?1(!)NSW6VFxyJnD?8HmI)ol>XHHEweAkS>(7c6TTu1M2632u~k z0ElA(agzE+&~$J6&iwquon`IGTRM}sv;)=p5WW{g6UGyYvA?5oc84B2L@W2H*Ml6PJg;NBkgze7&_PX z@7K;x0LJ{#jW}D9LdL9t{&~oQ9zd*%ARQ;VKVBOJ^@mYglL=KG#pnX0=hx4LLFwn< zFufwNtRfM)A1c@H9tv`9PDP?6sh9E#n96TXM{g}kb$=IPwX57z%hxbLFnVrHF2APS zPD(|$S0H^<2{y#nU7X5wP2WSR3yX*$PYfeVoqD#}^NBs*`ux@{RbhqHEGn!is-ojU zc2HqqQR}&s>vc6X@$)2b5+Po!xR4PNzHR@|z0= z4)yoeC(tid7Ikj3^iL$WA}rOPf~16-BBmE?C=jOOT@jj#&v$YU$zbQM4M*`h5%PlH ziI^bz7bFFbSrUuIC^|PfntECM15MT!Ed}`-yuSv%KYiYKP(M=*Xt_U?9iKgK)Mwj;aB;PD{r@AuSy)Hb!UYrUc70<-FKKc`q*XMXatx zuHun%z=$Eu{o+|*9FQBCvjkFQzRwTCJF&VpF$LaZbqk1e=b^nDoVy9}xZeAebl;SR z>)y!I(QO2%lV}5|qo^yDQC}tSaLyMlkWW{K(FbweARQhD)a@xX-H=^kx|;WcQvXrP z>P*i%M5)JytfwfiBeAeLvT+oewdv{OR$hYBc|Ea`{w--sokz>^eX< zQuhG;0mtd4tBcZQ8`m3f8eIR@x14cZd(pgy9)IA`OXQ~CbMT(~4+7`2%<+QdMNuzi zO-D`_w2RQ~F^fP(RR4qD{3e*r!Q^*QGg=4JALk5T{_%&)&%o#g>OM~QjRAIOUDz&C zU+0PFf^@G@1L+0J^y1I?vR7Yu)oy*4%~QY^u>m&o)#rJT`E_>LGL|BoE2CGfbpHIr z`Sa(O&o3*lEiWI0biU}Snpag-wQMVYA=a&+Ux1A1!gN4g-WP*(iR&h-|CLNHcTCS4 zITEdWdS%09p|QLpaJ9iWU@a>Pq$@NRtux5$j+F1kaNU;4rB0M0+nD4{h9Z$JgdJuG zwY5XHSH?WE*gu7eMABJphjho-faaanc9;-GN{dPrKP)Ajkxer(tX*!U$WmwPk+#d) zHSI7vy$q~3a7_CGpc08+e)){H477Pfc{-h<+bbca``ER%?u89E+US$o+_(*Ed-ai& zYZ+}>V0zuwg(SNZ)b9OTd02^yib>bM5CC12PH*8zhv%@lG<4CouSv@`wR}S4B(Ru8 z&@l0g;Jg96Ez>5ZhzrSiI)r9ydbP2*I2&A^Vth^IAa)8)E0IOGEnGHti($Inu`Saw ztFTY)3C7l;Z8K(QV{L0&J5FZ<7HCg4pS_sFT;B;z<>YOj+8Liw^0=0o?}Y`V%0!Cy z)jd?=x!mXGYyr!4GHl~8oi{8Nt&7s7tJ^nYtn}4ty2@-0(CL5*Q{?T3+?H~ zdgIpcEGoWrhmReii^82+ZeTrp1#jA0&ja0>3z)qo!uC!YXcvq-%EEiz>Lb{CYdLuQqLXT5k0g#dD)XsR+WcPejSzxOA3`F zDM3-(1IpuUP9S!=EGMTd2g$aoGx^4ropP#VR!~R10FjT@zHgcRzvYhePuX0OQ4 zkKoI9vRNYhi1xsgj>yR&G16crfYmpYQDhN4H9vntey)GdttfQ@y3te_~}oH z0^~va$9=@G?E6P%Y0htc_)}wY!}GUYv*}?22k$4p_xAT#e)8=%{_#gY0{8C*)E6%% zJ#cYw_B=Y5@>g75=c}-^rNS_Iyubg0+a9Flwg2+TwYT1S z>%Y?8!co_HW6RphAKV~Oz3=M(VExO${D%4iJ@L=bf%M}y&i0fyQQxSK<*cBl0QS#* zd%KSuo#==?!6!mWi3}$+{r$s| ztFjZ~dy}zyRT0W~eeWJ|y1s1S-vFRa`XXNk1o~%|6y&t0W)>)cox9B-esm$FrTzs4 z(Pd>d94|aNB0M!Gu|AzIOCp$C+;r>u#Vem)x%j7Nz;x_j^&Nd3q{S5IhG-3r{?ei< z6|FknPc73AZ_lH1NO&M>y1I39Yr>sYYMFmb1e8t&`kJ_COYh;!9Y`Hkm$1$x{|t@W z^9y1@_qj(acGVTv&?jPM#7yh25KXt)xdi||-z16S|B{;SV|O#7OHm(emXvOcZq{j2 z(jiW$Q$0tYz4KX>9_0z3f74OA$Xt3gmKP}fK_Ge1n66wtY#Kg2T|n+Vo-k~8v}`i^ z(14k|xg=)iAvxU*R|>&-s<{z|qS?^soGEGVwuRJpnOuK|n=neLCv3fG)1{V|Tb{VIl4?=hl<+CI-1?{p z>el!cLzDJS*bOuzl}q6ko?HJ=MxOHp#D}KAXxRK)($~3qk3aD^-t^H2?>uP!7J7+N z+{pBFt7YWtLTWKDmh_@EEScucgTi!nHt2aVPS^e)2j5?Q`IjG_A@&7Omsmb$-5g2i zPokm&=r%T!3#4vF7dJ9YCjrK)l}cErJvrw|(40DVaJun2m8s|1msZK^i`FYsfB}W7 zYqPWG&o7&wJzs2YZ3hd@j6M%Wr=6`LBkcL-*FL}Q5WPm_MvpQzUG8)&FOJoZJ#|ce zm^r@xUjOfo8DODC~lN{3>bJGL8`Fj&0uLcm|dHH`dw)bgRkHE+ij$?8w4LG{YdBLbuJ2 zG_RjF8hgLx_c{nhnsmLo@Q0ZSs<*p2G2IjfSonXSpujVUJH)z64tXZ zek_5tP#Egg&a@L-T_zJLd`u-SJUma+>P13|jBRy5=PzM8I`d_`k-d`vs0_WTuV{H0lgSI_tNV@)E$ zCc0o*IR=C<^$$%AO${lghh0(8)+e8zmra_t%FVD=X)2Zh>aFuIOovs3==nMAWO=u5 z>D;n5Sx(oIxf{x0@d_b8{@e}8oonm1Y^mFV*}F5jZby55MNSDxFLWw3Loxz7ER(|y zbAn{=^~>p1`IqmYe+slzZ zK_hGj4h>B33q>+!9tl4_Mvt|d zh2o|p`a#}4dFtfay?bx%qpHyppB}t&{q%V-{mOf*(&;K3A2%~Zco@z{;Ui20Iw>(4 z6c`W@9S|Fvo-4;VJt67!z>Ohye&ysZg6PTzl+6XZQ%+)j2b6B#spL@Ji1>42L6eZD zC50>9oC>1=ekitbepv{XX|JXFD4r4%)@$d-r(@VEE=Eq*2Xo$Zr>5)MqTFIK$5YG8 z$Q@5DQc)FOp)6ZZYCS)p)DXFRqC=u7A&`)WKeaS>$Mv>z=S~xc$=6QY z%xJ&X0t1tM5y zx8M2})(LcUEH8>;G)4w|#m7eJB))hPER#F^lC7i_HQ_}xnye0K3(`GOcdTv*?(m%X z4#)+mM(&=Lt~CwP-2&YJK;Dr0CdM2_53d=$+gUSZr?0{18q)bDZa*BNE0FO)$~i&l z4}OCLbw;4NM0EFb*J;q3ZWDF^iF`pz_dU48gQPxadU@D5-73{rM&W*GSh2Zbxyyc` zY&}ZhSe)u#``SHbP+xhe<)KS<{rD`xZ&Sie4Hux}f$^x_I+i~0xC$Tf@Tuxf=)MbY`=u^`VN=@gU!0G6wr)%1d zkDdO3=YA>ki+YkeXS!frDmpEVhjkv69bIWKK3Es1<5G7`v`)v;C!bf<3^htnS<69xN}ir&(O^FXC{)l&)qfx|On~P~O((*K((@`H+n1I9woe?-`}+ z7tM0k^uLyxp0#vZW8SpNwnLYJbP$<3MgVq-V{Z`rNLmA)?FM;Dqq_nvh^-mT?Nvl_vW;bS}2}Q+h zL%HA9sM1f3>RP&OTk~6OY3HgNo7)-|%GloAJX(Y5YwWM{9PF)TXpa58`taIg+g!cZ zMlm{%#%8?#s7Y4W-R)>InlDcSIZ)r9jCAr)+56=y~jgW=dEMf%hGKOre!TLgBt#1=1 zP$OQm$4NFvW^|)=^lUfn`QU+fY89!%5)`f2bGdHZ5roY`XxUC|Qt&Lk7n~dCJLJ|( zQ{`E%qw@jnps4A_{Ra0sF}BmjtOJ81l0)7)e|nZ`xAviCjhuDY1e;>6QMv+@Rg|I5_Le=P|V3KRaa`xh?;Xw%3Jp*Ur<=?zorAiSo3dYXa+l6LlVo z@w|{Qmz2D$s)+KWU`e>2Kz)a-3c>|@;E@QVG-A$NirLRir33tyExW+<%*_0q7+Z44 zd&BsezpJWqEx3;N1zzt=ZpRjrA4?z5HT0Qlr{if3{RG(`5 z&&{dpOsT#wa?>pN(ebF{9l6$a147%yg{N_GE5eb}b&*l3 zbN&2M<*CsZBCg5kf{R0vb3jRYM0kQ99g2ejFsR^AF*@hyb_O-&{AZSseVYPDmv`;0 z`-mXMPrvi~-?#nYx?y_LOuQRQ7EdlM+qJ7bocj&x{P-;y6Qkf5EKKOm_^HVH7H#sI z#Jym77_lxA@KMqATM#IvSmtz|7+)avpv2U~uws5ai$fFv^QMgoEI<+@3^rT|#V#U(v*fA01 zRnI@a^;OjLU~U{Mav~t*d(-_R7RLnn&3k@cLQGtA)nTfv)@>)mQP&L%zaF{?;PV9G z{w^Wc2+5pFoa-ME5E@EXk3_%B0RLdW=vcq<=-7w?|J=m-xQIR5x4(Jo;=820Tx`0v zfB%US!6RZg`QG08h!}qFVp!Z97l0fo-4oNL zraJ?S6VwMmoeMNfRTrGwmk_#!^t!cM9ynd9x{uO5RQLX4tbCXUZE40*Gg3v)|$=?#(p>r`hqB>njQPVBg1vGb@Zj5e_E_TQAB1*@ZjxWZk>3?(Z+Xuh- z;1dr(`;Y(Xah?o3Ue{5cKu~{(uCJ2Rv6aiCPBTxsZ0Vclh|={i$BTwGVX!^~>2j(+ z`O2X=64h0W8cttE574t)@UJ*hr}`Zv4wJ*>nt;mP!$wtGSX-gJ@Ht)=?Ts6Pb?a7u z>DGO85Yksv%GxOFfI6~S1b?ipniELt9@+xP&p5ZX zH47nq(%2R_x*7I;r16mpob!>kg$VAA^k+qm&+EoK!}kUY4{ya{bGWrGEoIR3!aoO> z>;t3A`Z5i_3kH_4L>Pj@LuxwHnn_1dA*_rd@VSTZB6atKnFZniu!C?juRBN<6SDzW z%|I)tu_sNy!`i2gW}6#;Yd7qUC9=v0+`)47OJz-r@U}T~IU)1NurfkC*(_LL6b>Wb ziDDLo+S*))5!t&TFfRkS=Gy7$U`F5UoezO$N9$=*+t5krdS~5HwL{mG$f%DjOc$pM z?HOp=`)hzGDp%I^0IuOOPLi2efs^;z?m4p+!YWq4UFl^ts^(p~Ycg1U06TWI><1+(4`a z*apf{k!=wRcWl{$SiS-2u3+xYvOxcwiVF1s2(@S6~N^ni__N1Pkggs3k!GgmG-2u8!M@KvVOpyNe zXD1zy-+cf5+wZ@B8A$K{fCta3TdvNdf9Naw6kq+$J2#iO zOzH(8NmW|$qmSt2r{tJ7C^zGPny7SZSC5e7`qnS#t2)?i)f9Dm``Wf`k8HzH_sPJ8 zQ>QLXo!!>iPJDXO#WyZq{OD@m2OqqTif;Cq0Wmt_JpPxyC3h@|+p|9j6eXY#w8NZE zEz6JqFx@zvVJ^2cJGZt`%1C5xQu>8iPhSAnqYnM9?np|*yN6HjZADE#()K%$4N9MD zoKCk9TrIrOn zlYXe1v9facQ2<+m_La{@*uAv&g!a6bsW9{Wft&YRNIQf?L@^rSr;o{&X#phQd$ z3}rS-yh4N^++;vKySBHtH@h~N!c^2P;x{zcKiuv{bVs855NzX0O;?vuz&e#>{`5jE z&n3hrJvQXlRx~(5RbpbeIq>6?uNku>z&}2A{<1CEy*=^ivD;4{p>D?BF(k$4z5{DN zPkk^d4v=w4$R!=7b%Ez{9fQhCRgcl-`Q4A- zy>kB6i32BkCdc%Qm^>mNhF-%Z@d`K%j>m9*UtG+hu6}MXNrgG{!m@cqr6qAhX8QSY zgHu-4i=ZBn89}epHTTB(liay||Mop}T{z0Csi}Co4aj&bB#rS+l6Q^*>R8oxVfrK_ zeQjFW4yFI#e2FGJzk=_=3KWs*{u((n+WNm za~p2*iRqpjeI+&!=SxRRcRH?7y5ajuiP(a4ld^sB>EdxGY#XlII|j14nCV4U7u0lf zyl5baTu;x{0&i-bQMw!10&lk4kCwOCQvfb4-O2t=RyQG?nNrvV>uL_#ZBlQ%tQUPq zpPp`_I(kKN79KDl59v(-|6?^WN}X ziu&g$U9>JaeVroDrKjswT$V;k+DTjAau!%W>v-M7b%DFrTp2togvTaE=st~pEq4hk zvZmvDsZ^|s#B}qgSFR@KMQS>EjQG?4N?k}NEzcU27d0J)ypryem*H_t=IGlBS`>^& z$(24s=5!(u^B!qD+(2aFw(6|3l-Z4A8y{(Go|V^{Roytj6mC)Xw1sV*X{g?$C`QV2 zG7`+rn;MmcWn93m9;dvle5ghsrBS!7r{${7s{LpsjRor4NRMf2$Y>nh+&r#rYl`!- z;F51%*v64A95zgER9V+%qGd|yAZzfOow()LT_~r@U4Vz_ z>_B@nLyZByh+OM3pKG9{3?;bREC%d&7^aKLee$oPb>EyJavua#Lr}2w3k2)U@z8p3 zZQq0=Uf(;$-ilwEKWr7&F;=%#ZQzbMd=;kIg@HP2uw3H0J2&r)2C>~X^A7ukU3}^7 z;DI#pA2+*9gJ`ZRgR9vbTU6uiM~tCoy$@7@28TZ|MvIZFiQWY zAJOsiXFvMUJO6YOV+)K8n!j`VM<4vG|7Sn?8B0FEMSj)L{OZ-NtNm1Rw6xk)Zzl{&(hj-v@7|H236AJaEfNsz;#{lEU=7u}nhiC~%4Jo>G)8(n>wp{%m+ z{J_7d7b<*ii2iSe=simg+(&@?9ZP2J$JtS8x^|GX+Qgt>%o8SMA0?A~?#{Y()4Q8h z$_Pq-8a*9{=Y{40{P3si>JDeMoo}cruEQnRcI`;r(OpzA%FnM?#&!iPE=K;DG|!lhwJ#UN z+?ZHjvLwPz7&V;=s%km|T~vNk)i2tiOH0_GCojZ5Ej((*m+MIDhhhGBsKPmyn{Y*hY4tGV|2;nOV_m2oI z%AP!8WA?@+R9otuOo^k!jq~Ou1lM=;mhOM^J$_fNT)cSwR!@9KPXhO#8#g9}%q&i- zP3VY^@2%aK5FejFY1uOi&fLVAK5+Ym+S+-qmX8pTad3C zMC#K>*5^ur>CpQARkZ!9PDH1cp{?VA+4Z|4M{ew`YfamlYB8N_)^Kypodp*SE#3Fk znn&k%Qf%}KoIVKYtm5PJVP+Sfihk!e=^FS=4N%c7E?q1t%gZ;P6~3A`9ly5ZXX`zx z;-gTy1*XG~Vq*`~MdqfbJ82z0wkEk-6NZ{Dq>)+Z=d!2!UIyiWx1)0hP{I+0s@tH#=b1@({NO9KkWUO&XBf!QpYEbQ^etK71q*9fQjzp3pho^uN_e19d0m zojBcrslP zzC2~c=FOW|5bM2K-R0C(ZpPFpqwo3lo%e6rL~&C3l(u-B4y)_?1=n5{iR<+!^^bf5 z=14V1Ggr6^D~ir>!pIC`%^WH~_R51|be_`BX^znkeqF{Fh+QKUAoU*l%k}lIAN=~A z)`e91JdpmVfx7f`^(U1RhI<6-@A?Ghmk&Q&0jWDl9RrNBzPzH|ql0?7)O6m>fyKz^v`LzM*vfZ#bMWEibP{F)rA^kMZBh;RXyT zc~NO8)l-Ma4ZG6+8{V*;HgJC>I;ELv3V=xWFHp z7S#fykvE#-0G|1y@0!Y)jk{~)ELAII4GznhINl#O&bz`Mr3*HFT+Y}%zsRU? zE6z!iwoQW9a=2LAeNG$y+;+~H?zq`Uz#2P+{Bx_iH)eBjNUimZyT4*JH_L&!!MSbc z9l^)vwu7OK2UYr^SznwQ+(I6FeY(GVeBV_YympS$ZLfov?iUmj94cqJU$CU~`BZ2r z4r?keo)}V|92yrFT29?ej0<2oqBpdKznHJz1A|c1Ljud%bE08~=`6WyE|63sn;WKTI2 zpgABfkc{tK>fvnM-BDjteCr}w`uE;GzWcx(OO^mWSaDrDOUCj>(<`qdlz-h1Y; z|3;$B#eEllDmYhjdO5`+)>5`=JwDCU(7vDs2O4H|k_{NIUlKyXUX($!{fh_FCKT zb}5T5zaw8}@7!EnR&-u!jsliKRAH;;X|6`rpyu#`xOCLt(z4+6d)EX+6Y_$TK4wob zr9DDJVkS?X>=zy1BXjzVy?dJ!o&Kv&pZKrWPZL`5>8IDX7XZnNCkB@h?$gT+pR`{| z={Z5+(c%8#sX@__)63hbc+c^nbe#gtJG}4Az3YkKhMUlw6xIFFSY4_O0S{syL;Vr9$a` zO5{;r>!h%NCERcJR%{^YazkQ8U`|Yc-}-rzdunTYdTKXzb?uHz=t`L1KW~1|l8)Y6 zx1O=iqu0-#ofqFnN=*kVt)G{)s;Nlp@2=h5vAd_I>-K`zUw<9X6qJtpYTi7`3K39y8Iu1!fO>1unoBd3#{UbuZP(Vc)g*KO5Iu3d3)1!_9KB&RRq zdg*NK+;J3>&KSr%Ha#;lK9iomOnaDq-=N!NP*DGZr0yWy>otmq?waZt8DP4hLAqmf z1a)I{qjW@ctS*o`A%&uJ2wlc#Ued0850lazD$DfZrks{8bGme37xSXn7c~@iPgVC| z-Q4DA>*jWGCKu;<5s-T#yW@2sx)1R+%|Z}f$1qUeq!BM^=o%WN+t8a9qMNp^h1Q&u zjt?DRhtdViol!*hlP>fWDiycH7Dkj@1~*1pRnS?RMk@Nno}%?jSW8@UDKK#Q%Ld?x z>fpL*=o-iXBUty~98h-;1--!TE1$i`ak`^)i*7%t2zM0({klzP%C&nAg6Tx3-+2&k zy2YqKbVBz?U5k>-q)w!FNQb=XrLVIO%d(!<9!=VfJOP_tB!?5G<7 z{X&cIe{A!VvB0!x&CR0HyY6ZpH3h(KZf?mtrR~{536ImW@e(1TR|n{HCq zKRI_qR-a?XDvxDhRYw3*_NjEeXb<^zd9ER&MiEXrd4VW+V7M0tI*5i}&(G1NM$=i8zOvYMQ zyw8xgQ$~r<*$JC6WhZ+Vd)J=Tja2sxqJ7TUZ8XbW;4f4mbwco0L%PtDRR2h$}(DtitUKB#<$UwBzrcuckwh~zMAvzge?$y0=dkaE!%^YfEC+r#G;eZyQzj+U{*un>QLy0Aj23QrFT;gs^{=A@SH5AEp4-&wQh zji2H_zj^$?l9DA$mXNtl>xt(brIaY7xVK{0=}tPS&P(pPIuBa!?@!L|ZC`)(?D0j5 z7BRea{O&*Ay{NXMc6Z5&!W1{x*bKgZvE-vrx?+H&x#+T!2kFE{@ycp|Ku4^{mno9tB=zU9we2FzAeb! z&7Z8hePctByy+hfybq+y;ciZszP=5+c7;(xmHMcd4i?WO%_I~%5%d=xoY1wOyACC=7)GPUQ9=`>G60V;gL{n$DcIpLc%x$@{F40A?ga(epAJ*gDyoERKDIk=}M z+%KW0|K!OF@9+J?_Oow@(m#D|!FA;H-+y{>KhU>kNzaK8Ri(vVA0pd!SrC?U$>UhU z1Lapy2_v)N7@r5qknS4skb&F{gp#hVM8l;0`=Rtzk39x#(q^vO!?oe=kOX+}ygZ4l z7fj|7(}}Q5?9HLV&>AqEF01wxKw)uNF&U#|tIHNouck8)3udI_uXBPcWuvs_@0e) zcfd!*ugxMBb8ES~<3LZs`l_P+MMb+w`{`m$xc&I;4;S2AetXXC7y7A6y6jbQDVA+1 zkK@BdQ;n)5GdQsfN+++Kyc$d{j?(wiwjZt8O98B-+o_^jynRpM%vHryDBV*ycQ2T} zYuE4U_*b%vDq#h9Ue=6JFK+zpYZ%|_nO>Be?o-m8pg!n&F&m6zbOi$rm(d6F7Y7j? zN;gnPRwjPX(WsSYO~8=@Plqord@=P4L=j4VKwn*JT5V@J!tvKU>9c-c_; zIh<|fNX6=cZb#lGn+v@~=my{(h0CC>*^J~&_a1C3+<)Q{GoKjjLn<-djw2jr%IMsN znsQ+NxgquzJ~cAB`i`1_E=65nE-l@Gx;!ri=|h6L&+Q^L-5OdtPu&E$AjZK?q~4!x z2kFM>m0*adUD+>SJ9d}lxL*KDvR^6@+p)uBtsXyhR~6(0IN+fx8Udz}C zr%vTXPMd}gy}7Y?n#p*R5wpsnWm68Uj4JZDaMw=BTu&yyk`LR#Z2#H+BZ`Pea`AK9WZ7QBHzg zG&Ww~KB4>ACv7Q|Ep13^Jw}jB6w&Ehy=%VoVVp>GBVB5gZU%I@Tg>VLrBA@z;#@C~ zGVjIG_H>1e0A}GcFB8GxXoGlRuBaNmhFitIqF$R}iv+#`cB$k-d0S%*Irsno03ZNK zL_t&#)1{<~+|kjs1K~P%2;z0yDXO)yU~HeZ7eTZEv?jC!{ax(L)(-P+_gZL_FMA3+ zZPRulz`1cdvN(r=!o~C2Cp@m>Xa>r;?jiKv5MTEsI!)a=j2=CzWztBZ*R65m!TQ>x zcZCfyhm0DIIluT`bK!BLSNe;3eso*c-k`8Uzh4Ewo~_*Nc5o;FHUwwu!TzAWr9x~Y zW!dy@ywb?`ArQ(qCB%JBlaRDSX$~Vj_7w|GnC$3Mhhg2CIRNkJGnBATb zl)RO135zJslbN|8yF4f~7@KvVrD2Ef+_JTd;_pEl+B=h#Dp5k8HT1iZoOY$gQ5~}& zBy2|!)s)0j7_%`Za1KF1`T5~~p`p9u>+_Emo_GUFfBUnpH8^*dAV90#LC?!IB^-~S zcJxBR53klfa;p)SXN zbn|Ux!2IxgpMDB^Qy=NdPk;TZ$A9>De@CxXYWJuSpZDIIx2md61LGt4sO$wkKL|N5`Lzw-Onfb^%EFQ9}T%46d4lb73H#1`}M8*@HTP>dR3-B7L(+wA^oZTp6b z9mO?Ao36i0J6|4~oPs(1+L50lr=zBacc`#DyM)4VV?e}ABaB-iO>wgHbQ?L0$Cn*k z5*HWa=O=SIG3Sf#OAjGcC1Auv7`>-wL}vZ&1IGtWo_zlgduyI~gG9zpzw^MA>zx<5 zk$Lyl7=+pTW(LnJ+0dR7u1^tIN*_@u-Cr1EW+gtklRR~kr{<}$kl2&X499*}}q%G?rwZ_u!z!`9XeL zs(J}>3tCe+rYQ{b<52e! zPJwyz~>ub5|BvX>hj4gfO!$W-S z)7#OJS(2GB@6}~R$@8`(2gR-lz|cRUq&}#g-x&2D@F*QAU2?kAbn4Y&e%UKQy_k!p zdz?Krdv~0^arzItcJZt`n!lI+#pz>I$al?s0Q!Aa)7SkqkecrKU4|&#+%IDDubHmP zD#G+ZQim!9=!0S~#&l6S9Y%$w=*HHB>ECgnE@%4RQhXHMmMS~a(jW4)bcAyt9W-`N z`jGN48;ql6OL`GCQ?G}IfwdW3n54=7KRg*J7K+a9DHwNaaJfUZdF2_4y6a-K7w((|~j%b$4aBc;5As zA6>l8(mVgw3F`8w-|6$a==R8GdLgfZ8t9VLZNy-q9)|3Q=+l>{IJI|0%2SxArxTxD ziEjGH=%>F9I#X`*u1lc$rAyofnXgEkE+;rcN#`=Z7@L3pQTmlSzq)2fP8XYNvDn&; zA6+?a6Cvr}yyqTztQv{SoKAZh{ah2?Tg|e@->|RW&o9aF+;oF;hw1`#qjekVR>0;z z`u%_T7isE*sf*El^0~+7LUcDNrnZMu)n8e@*+IG|vdaMTq&>{b;*-oZ`}rr=dMmln z;GR&?^-$xol6|S3y25nX(xsw<>u!{lwLGh#VROSe-+!IOvf(cSCPD%l*%NOSY3 zJl%90Bf^GT1lBQDrzmPS`V<;f+mX)Jg>-_AqEKn8cdPV+AJ9)@M&#^i>M<$_U4*W_ zqo%A+&|GMnHw;yh6g;KbI-+M0x{y}H4c&@cMdMI7gsq2A)`*&cTro~1m;TPmhU&s} zw#8X8N=_4an8qy4WDO(eyC%(;s;Z#Usv&mmR5(3rmWWs@iOxAZ(-Of^$T=xV_8w_# zS2~Oh(ZY4YqHrep2=b`wRQT*uTTst2uxNKQY3Ev*ed_cy$Jt)k6Q6CIby$VZ5%{IO zJ5qO8KXRn^+ihOzLBGq;#GgS^WitMa6m@$V!FnZtzM5uz?vu~&&aJBQ}jmNssv z?rGvaUHdDJ;Nx_*U^nia_By!b=a0*~FCFbmYYg9yEp*WR73+DkhV*m8boY$}%Y1)7 zP}4#2Fw}Ion)Gz|8c+(MoPANzi;E{F(Wg#=sN4Xlp?(1oFsz;0B^NDv@x>D_zPN}7ZTF(Pci&BFdLO8My#Gg^$)FC8 z1Du~;+;`>;bud+;BOOeMeH5w7g8ts0!&eqK(>t)d1Wcp=XW8>9-Ta;7e>OvOMzb#5{NVWQfr0*7s#}JO)0;X) z>F1l$D_R#?g(JiCd_YpY9Q9*>(@jlRWghd@h?9Y3b>7qjz9yVaP_+`&V`2i*N&52- zSiE>dXlclZ5GZ|ed{0k&JcC8IPm-LDa=Y)BaQfq){_1?^IbD&TuZqpgyyL)$nTY?r z?1)N$dO?+n%(p0`DmKYah%8>k6%r{Dj<%z(3U{O`o^ZnTgF(}tt&!rsRy0?bV zMOo835_Aug8=6!e79&pQx0>wp=;)x*(8-hM&s)EUO9gb}V*%4e>OG5aMqRn`E|EXC zcE7kD4@_5W{DHnji#B$xpE-GB?fTt|S$k1m&+-0!XZYdvbi_+Czhgo} z9!nSBOk6J*Rd_~_@2KdQ?QillP%o4}U5#?LO-*m^r*`jStM(T+ou;Pt?{56zhSFee zwDO@-)8p>DZ!upAyYGburN7Us=}7CQu4`->y7=5ZJhux}>1DhaZGz~$J?P_fBUHht zY3We9RCKG#=_nn_quZh=oxpUW1C7z8UW<}wK?EtzpCDUwDk5V3P=I79S7^NGYYoMN^ z^19$j$LXT46l}tf-SqS?nbQU5_w(W+ZgP~4m@ZHkq;uufyb15m_7A9ZsfP_rS_j!N zs|(i2dRe*}P(LJ@cLn@7JuB*%TIIBDjgO2PP4%OD4yqs8UDDB?c;Y)xSoI^WmNg76 zhUl)_s7M@C|Fx&952tgdcZ2TAO&6$dg33keVsW%|-4S?dxR3 z>FRFUNZq$YtKgF7=c4+gM87EY#Xuc6H#yzu>P*^GcrA+O`Q(#xmd|;`fc$d=E>8EF zhvwdB9jGq-oQ-+R;f{cpBXomw+%C(rP-ml7^KuWgTbG*-woixFmp809^w%-H+&ig} zMDY|V1W}wbs&#E!RAtlvF({E4#~Ly+vetFZo-_eOhn>e_QE49CeJG_eB`vG^RHNoi z6(nPNnSh!enO8l%fzG7knwz86Rf?n|Pj&MUlZ%bnsoqOd2iF^=sH4sU)-+|l;D*tP zM$!(^HI3RNSf?>MC6rHD+m_cH*2Bl|BW6rd+bx$>p z#TMT(3fVrdn%Kp|t!>+MyI`1(LB0Cgk=Ea-3+cJm)?+DIQ46_O@l_#xYQa+&zoz2$ zq3q}+d0wD&WxT-H>P0Hci~KL3xzRfF$5PN2Z@P#bCN~O~aBX_JAv^N~^=5%#hT$>V zvovuMmZW4O$xF@V#ej4diO-Gfb<{*kWqDsyd!m_sC;5N&h#KZMQT8E zsfmc`F*5sNE)K@n;2)Ho7#&ZM#QN-I%jh*9Jc15s;l0_3)Nzw64-gUBu_3!1kV@3TXqmFX?7?XLstsO7B6A9hB26Oi$RDuz^VEirqiLLH^l0 zwMPrnm(c(8z5_f&82HpXFxhO#@9XXF!kz9QonbxpnxrBe#{}IfN$b^l^C4;;Hdu7` zi}=-d|MB?l-DP!EUB^Gb`GTU3b`Fi-dgj*co1Y2PA$1MK?`p*8z3Wl>t&JUBeI+F$ zy4Kgq5P$pT?RQ={vv1!kb7r7=V|RJ~_KnOnB|Xn~KmGJ4{g>B%1f_p`@$QoP`uZjD zJ@e;neeybGbef8i+cVb)(hq>?nW3rJ{i(}CbUK(GKO$gaOlj4+0o*Rlo4!px`qL(- zOQyey-g@e$YH!vDV=bv^dh`6>Uwrpnx^Z@r_44m+M|K^p$j?DdM?R+#5I;Imx`UP6=Hj>$69cF{o2{=~aF1Z)hSPC}@Pg6lBbv*p=*S#S zgsvB1@jR1~D7|_jG^vR~tyo?R(?NBQ))9q6iZRSU=IGra`br=uH5CgDG4o(^P8sp! z=_T>L5J~yd`BuiF+4*I~_Y#ftjQmbtX?JT6EXehE{L6Oq~(OT6G3_(UrtdE*#0T$@4;&(lqn|x<`w5 zQZ=4y^0t(q1sW2)22M-1Qvfa%siPSM$x|om*MEaLeSU!5<@MJJ63R z?yy|)xK8l9N`Em%hrwm8H+28o$5}Wy*Nb~$7F(&OtR6DEP=<7{eV)?o{)X!Zq@$)A zse9gZQ`EW2K2ZM(H60cG2To9zLtTx$xk~z%F0G7O9hG%xh5Q&4jz2~*%7qId_36i! z<~@RM{A=H)%jdzBmmawEfPuQ%i?|flB&d_`;!R6h|MmCvOesEN}>;=|N*&2aqA5v&ma z$#)%>9(a!AmlsgfWmAXBMbm@+7h`Lms!sP&fP2n@6%4&*lKWsFj5f6ecvhG+=Zd*p z1nJQEbt807#;1-EWY3NK#iR#Wv zX+6|7pb+zEQ@gWLs$Z+lIJT~G!c>RpEvJyHN9Sd=u3Pt1B=9};RLg`@6V$77b4p`m z_0-0^)eV(EaAWhh%5_nbnkP-lo4{(Oqc`VWXi)`IN$N)8>cXkorWqMZzlo|ON}VAy z2$Ufz(ZRYrZ0o0-Nl*1X#-L2%oNL$C*PC#VFwT8n-j+maVzi$o4R%7|8^AHEa%j`&X9hGiw zE*F~=r$gQlI?eI9DAyWkhz9Nwy``ROV9lElo)7Bm!gvGZDWfK_HJ%b-Hjpfx9Wyt) zEI!vPt;%BdDxV8;#PCovZRC{5sZ(%(kD4$8dx;=kNX`OtpcpO-qqP?dK_YYZqi}RH zl!MKpaBe(I-Pisk!W&JqE`*JfMP~x0PjP3&zJPh1yOv092gXtFjl&JXwGd|4$?$oF z=@Qx@etke@4|X9%`yCY2-NauaQcsO`?CM1IzZoR;jn*lw(>Lk8mo^B1?0epuUw6=VH_E&7{lheK5 z;XBrlXc1IOI(1NJP-*#m%AsQe#{3(yr!;hC3_cg@@JEk7^~EDPEPIQb#26{3;o)SbqrJD!Eg|o2O+kA* z=JXxyIhnB$xR%XMQ(E2&DTW05PYl5^(+loz+!!WrOvv%yP&@QTeT7G3t?_le?CEqT z_4AL;!8(&qem0ceYkGSB&c6H&nYkO+-_@M@clOnfUR}TF?z`_^Bu=M2bN3&g z*}v$I$B+N9@5QF3?AqhU|KT%X`mf#~?}d(wUAG4acswac*Xz+wsdGxB>!@kzfBMt@ zp7^VM@$nsG#*oYY*-cyR3rY!{@Tm0TmjSn@tK~4 z1We7r8;fpjeg68^TTSz`%X5%S7cahV@ftiZRL%tZLNO1NaN<(V^ zQpglCCYpo<87Q6aEO;)JvKO&yuIdSP=dT{8*;NakilabPKXAn&e ztG{&o(RtMLU;XNdE1hd~?{YB=i#F(YBDB0cxsI=9NG)u~mcq|{E;W|u zrjVO6H>ZL-J{_33TEg#CaS)v!l0r|EhU}TRYT_PpUAFIcaK8VsH+e9P<%LC|guPTC zf&=z+lAwz+Miw0B#Jyl&Da%bS;EdA?OiP!X9*x@0&4Qv`f>Hw`(xY>k;_f7rYe1=2 zauZX*^sT7rgu?*o)*^~AvG6SrvFCi75koK7n$)78fTCqvk`v-%st%t!M-NOs3U@&K z3*gI-VjZH)uOPOhB$jRxbLk2l7#bYBas9kSad^|`*RHRHyL%4w*53ULU5|0RJb$aH zY0<{XwOye}MH?3%*p0abRlOr&e)fx#ch_!QUwfeT?3tSbFZA{FQXniJ&pn|t3E9bt zdft*96Bjok!C`u)e{qdJ9Y2cP{eNsNYP*ehNpSjBKy4DS3THpLrRr=_a97(^4&Jzi&3 zYvOmHTD18y;$86PqogyCsP5}g`=!go47;ov$dyk2Q6510P}4UW z-k)tu7ssTedr!yc2I|P^K)T{zhzOiMJw-8%>ozwWKD<0j7=P@kg_V`#r!|f~_%~nw z`u+Bw@~E*bV_g6YeLA0zok&*+3b&^y+T1RpbYZ$Vm9$8+wcTRZanWeUgEnPGQx15aIOuX#M*-MeKQN^tlO-;TRSu7 z%=y+g8h1(uc2Fk-zBTsppKBYTvTyw+P&8w$PjYLYv2r~oY`N-x&Pvuq5#_^I;i4_LD zd-UpcQF6QBKF4s5f?kb@<`jmP?(V5*=)AA4JVwR}Erq&Cs$5DnrL-d{hf@v{jo6Ta zK^|sD_Qv3zM@Leo*c;4!7o5#5P~I~(X93-ETrewYZRN=3$Z3()Sq)KUgTcyPcc?Ne zkA-8oJ%}RXMVLOVv2o;-Nz&$3y|ndm+T|mZJZfwGdF$bsH)J%)fw+g~ptYuCQP&#ccA>P^XFWB>?0$+ETYzkojEmcZYw@*j zo>Xv_+TNLKvl&r1l*|}TU=rJCABMtUx@p_m3%j>HYjYqR7T3)JZ$#6~P{Un63RPVc z%^ZQX7L1n2&eT}GB$&i?)@D=gn#FS7;N_t>sW@N$8_$1EEn#;OB6D`6AC6AQ9gj-53Ien!!dhMfF7KHz1`!B`*oHV&*ft4us`;t z-D%Gn{~4j)ovQD+zOmb6*kOhi44e6vCfUFM{ci>@hR5Z;YvaBB>V3HD=s?|v>G$$K ze?UkAq%KxR14ji%BMc3Rm>IE0-9-tCMty~i=wyiXT*^46=L8})5_{Xj;v<5CV-i)` zsH&Wb=HcN)dC+aoFR_%_$Rz+QYY;Z%dip5EJDwxOb3We*EVh)u^Y)7zd5r^on% z=@CR&13AGl5E9i~f|5ws+c#Hd!orXbZd$FR0mU|cMinFqpZ*3)H!c15|N5sl%i|Y!&F|U0 z%;R%Wx(V;6PCm{QJy`2Hiw@kkrsFpKJqIqgroHwnZ4QvQ@ui-ZcJJ<49N*V_wSVB$N&=4&(~Z;dyI0=sZ?D_6VfP2zJG^kb zucO{CbbnIQPQQ)U-~B!HcXkx)IJ~e8Q2)cxqe;8#J310h6d%nA4onoOOF;)w1?Pt8 zHgv+a^lcNl!D;05i1@g4I@kXy0!R@C6r6O`_|1~fbbf%fNYG%m(P_kZ1_xSsf)v17e>m3n^v44ALLTJz8l6cbI z6Dd?Xzr396Q%Z`3VrRd-;O6Z`lZ$Ki?yBG`3UY=qf7vmyxum>^ z%(v@0xd-n(ZJp8nH%07R$Nj7JZ*SUubnmXy_|xmCOIovQ$BrG`h8LfhIB{k=dqcAK z{u&sVV;yvAI*=|pw};cvjUhc6_n^|poAwqh-S>WIEKG;crJ~#T*~cFe?$I84`GF_C z0|BE{i+P3RhUU_)h2k2UlrD^hp7k2Ub*H9lhRE9BTyGq?i_S&i0#1#X5UJD5@xpt9 zbX(%g?3%>yZfIhd|uqrB(gq;(lyXpFv%r2cIlyu1H?FrD4Vr^Cen03ZNKL_t*3w0|k-3>~wJ z+jU6Se2i|CuF^-3Kl(2}rl7@~eTM3yZ3QLr;Hv`$E(%5j4vMe%!Fl8PS6;d9l=s2K zGP4NhHB{2#=5=%s-K;bh0s7{3Xy@n8fB54Me@r0c>%V;N^#x~EtT@CKj6y@_DT51~ z&RCRAd&-pcWA^5+6v#L&BV%DyD}0XWC1ve8Y8Z7-t0bLs`n0^!(~dp4b@hx$dXQp! z89O!)Le5ANf=@6?htuI;kHVobr7A7q@wjaIo3B>@lm23 zGq@)hDNKjCM=o4f-JDlF4KW=`x00jXo737-C~?H>8QrT>QmXNl9y!$Ah#WmdT6$%5 zTf>otBdte1p%^!In8U4Gi6&ln%=@=8!-CQso5RuQ>8@#V2;4pAi-dK+TNvx&)AdG( z4%rIFL0rIEh%U?qopHiwxnp>+UlO|35q@i~fEjq6qPZe?k+Be;e{-1anRGjqxrQg( z8@Edi7l`vROqK+1iR{{^4y=Xf-nKh7G=-k`BkyXNItgXopqiEJB=km`puI=xjF_}z zYjbwPTeg&%uD3q>Id=z=&hK)(Zk%q87|pi3droN3^ddeNdGd14ujbETb3NkLMq*my z=`Z22Z~ec7$=KWno#{UMAGV$KE_L&V;N7=;XzV+JZ#=ZbO?_#;6s#|<^o94n52erO z;rjo&nr@r0y7xPL$CB8%*tikt0l}20pC2~AbR+Ism8TJ??V+2UYQh-XK}RrLeNZp@ zWjJo;dXg6tDdqy%XA9Gld+Ey;<5yl58cy~$wGvUoX=RCi^?pIB|4!yLv4AS5Qs7UN zhKv|$6}^%?39DWci!dJ(6CZ$*>0gTfW@7@axT3y3zvjh#xW{kqTU(bHkMakki_`hi zzN9`gBAR@5Fr9=E`O@1Fo3G~A=ld0hZru1HNiTr;qD9E+UF+u|tDn_-HHJ|7Zo~AZ z7w`V#@ppjn-@J2t_u`1cg1!$v`|P)L_`GdhOiw=g=nwzyr*Ak+|M*}3^-rgpCN8dB z)ODNOb@B;M8Keu-HU0R>&wg~Zv#zr$^uUt7c>@Hfx7|oPPt?oBi)VLFRP1#^(u+w& zx2l>_gG1++&!+-TTpam1x%irsK*Zhi71URY^I<}>L3+!n0n!~QJUYfQrP=Vu)ZsAC^VpSUOV#Kg%x7}H51>5-s*plA1qMRQK#x8Jq5 z_|+dvO#jYvx7VKs)35aRm2BU>>cEK;<=jcMqnhXDq_(4>8=_atr56JCQcBZTk~%r# zxfQ8pVNGb~Ct&pdcH$X&ib^_{%SFRy#OWY9NhRsH#^o*v2}qBiUJ_?0-sUrK4~YXN zwVbR)PFIzRWKO506Ui8qi!YzTO0YKNTytx}iqXmW#S9KktWBO@9^{`?MbCw;$;Fb= zh3V>kIx(!gG;D+@J%(_Ya*mr@Tt#id#F+WLG2wNs=gyI8xOYQ-eMfjb9XP4E#4mMF zG#z~lDC|Wcp?v)#2_7*qCLlUIch#Q2kjV!QOumDT&g6LVmBXL5rx(g@GA6cQ#Ns7! zNZD~3EQyOxkK-3QeNV)m`xf`SaP!04T?tedt%*iapG$z^nz+Plikw60wG-9jnEs>1 zI|y@eU~ZHyVs~%F?A-1E>P>H&?S-F9;oiNcTYtW@?suJp03EHM5G$O{4>&Y9f}7@o zOz*D&0=kj9N$LjahUX5|jnNr+_7(@1;&P$60Nq1$_ttQe0f~&B=Vj%C*g&5B+Xo+% zjlwmwbnNQ#f17sg6%{flH)0oOLTM78j}G%-3^}yfwwsMzADr%m?G< zGUUNl-ow^=Li?cjr6K>N&&%nYp^wWMdv87m@q%^9?Sl_UT{5~*-3^q(NNT!W6W`@w z?7oBWK;15~W*VpKn+#vm?b6roB)wJ5Lb_pdlhcU+STs4GkzTt`%2J-vaR zj{?|r4KSN#fS9W*r{#?##GL2X$bY#smM*0$#p#!Hx1uZdEdp1lUj#}E%sq6rADn?Y z--tZ$5Nka2@}&F6QDM~Si8J1+APVPtIAfU#Jz{ln!emM^D{6ag=0crirx zNL}U^iR*fBasOI@jN29xkKTC$OwY(`*xHJw-kp(kDCOadY1A&7hMGPNbIXhwlnKh4 zfPJKaC>NFFR8LPDCX{i_X`AyR8}klrUdm{atlv)^s+u*ubFyd%juRpim6Z~8 zY+?1bYPu++m`i^5+66bp5L1Z{Cyj=vE^CY+UFnRr96V%`>gkrQC^7$$=BUl=E;28& zEoxdLWZs>i8+bmb=B)5>C4b5w~=3Z7GGDx$>T9Bayj-Z=tv5JEIJHVMS5BYqp_Q70YuY zp)5)(27hKvw}x+@?0t~Y-GsX& zzN_-ZYvbF$E~2;0`yIaH-njHQJx2tnNWHcBIE70?W~Qg(7MJNo>;@MFCHA7rk_Un^ zjwlLbgXKZxl(^6&p2=JY+()#>S(JTW>mCP80s zC?S)(Eh}+Pp8J8)(|;%xMEPoHzQRM3lR}Eg zcd0^5_hGs~o$r$ZgX5RPkBA8kDlgwbu48fWj;gKmN;|g9Ne(Ywo6>gV=XI2L3e1_IWUjXMlZ|<(+dkL+IQ?cS^$_YQRXRn`n=l7 zY{7+~vXSF*uLr4gb#I1Y`uj=tk*o;A3?Gx)gQ2=dYW*=|DIjZXC|ES=7bo!(bh!i}&~r zO1f5+`Q_3B->2}=`7@xpiR#cg4=CNlagjKaVES?yS9mJ|C&!U?ows@+pR1Fo_+Ga# z=;>Muef|7`ho74|_0)4}FaHaVmmhfG;PvNbOv_j(Ukd`dkIB*1nMO)CpSt1t z^uJblqiM&MrX23(*@~-G)^VDk?xyQB&SPE$Lk_U2hgLYH#AgEtFD|j?Jc;w z8&RAlOh+o$6pXC~_&q{63`XNzDZud+MiNNW^>&Lf{>v>i#K zgxlfP!zl}owR(Tl%R>R+xhBDGlhzHm1=T`bjYP{H zrhCiSv+!BVWe*36wY|sM!g7dTHgw@PWUV|H@LjvoKoYw_Jd?UVU>Cx6$LZ`+*bd=y zT$y5Y2HKCP-rFM<9T-|i)uvk6I9-QhH!RV5yvB{@aBjzACxPD}xKN!HY&GL_t*KpU zBqo=54$AZOf=-boZf*LhdRN$om!H?tJtQ4k=uJ61Ha<2M1!}!n8h-`<`ef-Z?MX9y zPI2wRQ2PsOiSgZh)^LX!eEWq}_13NQ6$}0kX1U|AArl^V|F2=XJC?!vAf_)y$%{*0 z92*xG5CbsccBaTt7pD8sUALF%#xc+1hOY>?je#QL)G1i$imi0NC}Gb8+B zVx*qaDK*p&UXLLaCb1NUx=J?YV2M$Yow?D-gVF;d60yjL_~#~)$U)4te@rxGt{7Ww#r=RM{&;IFn- z`0?8qLTI_YtxYr_{mcuu`){AZoPOcE+YgV0vNUnh_HxmW1y}OvUIPG?zY}Xyz4V?Nt<_4bRPu_E#s_QeYjkdTOyU1A%h0 zpo`1lbGbAW!3d;3wjD8j`}U;bJ^s-(Y%sTA%oy-g9YVcdNSrOjsk!{3N1P}HbtN3kfKGEM^hF%e0`4F%BQ zAtoV^oEY?X%pq`ka(Uvs=bzj%x1jEN%DE$__a2=)w>}5^J-%aZ+GN@Z`9~C7C7sfS~kSj};cij=&O*IY*Gr?J?hF#quszkw1$$lRabZ zTU>kl!+}@UhZYwWM$fHiZ{Ham8&8C3KpA>Ef_kz@J)OWUICo7GrzQx~=|4Ko>E|-Qusfl+8P#V&@E*I{ zJcD%H=?~I}l+97obt549c5M*VZN6LJ@J$adUIacykPcoEfjo$&A4yQ^yz13y>kd6!J#_-~ z)_82~!bsvyrcR*D=rqhCS!+AjHB6&(D3p#5#zN5>)3Wl&gvpAWnl~vjZ>mO(U^-mS z1IY;l7cFPdRkWc25xjBRHd0_f^vG%|lZw@+b|chJ%bTRR#IFm;0X?c2k>}EIIPI`> z^^ET3QwlJnjRel=8ma@J<|C&sTzl-T*SZfYFujr61F?EzcN>0tev2#H4l$dS*G5Su zK2zQ_1p2mhR3zH=^^;$Hw=3=Lgto<`zc`gJlEa@$)V*NN#0DHjz(xl<>B=0nIVkhWcE zYu3<<-RZu7Lo-h-&N5q1Jy8{@sAFg)-3Zvx1kT#Kjdea8keEj84NYBpkZO+cM&J#s zV@PKg_I}C)V{pgm@V%WH8}jfLXE{G#MOcp|qS;U9tvbSh6^MM8F7%6g&95ng#%5Ph>_!_M|Z;>bJNclB<_4@#vUY|?yF(*bd8>1WSM zOn>!-k6yjC=x&l3ZP6mLsH3I-QT0m2>2H7b&egs(cl7oD_U3OdC*Oe67wvwj?`Jou zR(kU7@16X+58t@>?!`adT6O%kApPWL@6ZhuM@S!;?0sE*ADB1&N4qz)p00Xz{ei^^ z*#qkMnR5N&dA#Wt`Hmu{B)&elw7k?mx+14Hc}xGi-k!lIR^} z#2G@XbA#HGlk2u5?nHkBbz>WfUB(N{Rr93k%bQ=l4oSX9wwFMLYa4n8YMdVJk6-?x~z)SZYl~ zE<$#8M`Faig`MZx4wFicY(BRlC?v2rq$~$I$2GzW)|RzLm@Y^U&!LuTNKD+~#qnzj zYHpqX7|Y9>tMqD9Zcu$I8KlbrE`4F0Hu8on10{x{+l13nFoi9)AK8iM*I86 z^H1i!iOI|8N4hM#cg?-=L6}y2YPulZ=T0|b7qs(gYTE9cMD!xPbv^Cpbvx=#A301f zSjp)}D|YTkh0+PMuSiYxVY;+*oasI)lzuzdRB2RsfuOn#MdeOYH##@G)B>;ZUWOO6 zbe?dyOJZ~(eCm8icF04XS}i2Uoh~r<9%fDFJ#xB-?Vff%I2uOlM&&|waN9b9DxFdM zuHK`DFkh5XBH7^+(rQd`M!`ZvBonIoT?Zjw5x zI(#l%7ovM5NPV|8Tr0bL-au+P4}9sHberUBO0M^QP%3rlOzBZFyokAd#uroBh3fdz z-Lln0zmU?X_?IkF8rQ8`yLQguQ7Pq=&sQRseSZqOy(3SZF!>Q(nBr4 z`gc}Zu)0hpYGQQsbKZEpO4XC}gLG#(pR;cH0^B~E zMd&u40W1!k%idy*Im~j?%v4)3e!?YOF3+K%>q9@z&zT4yB=wdDCQQpvP&!ibbTVB) zbY24XK`GsV`(MlSax81x!Upvq&FHRfSi3Ict%ZjX)2mMrdp>H)tjM*ii6xW;Byw6_ zcScm&+SavIt0Mt-^&f2++t@sMR%1g{*5QWL)f4h&OpBy7fhz2tM8^peT6o7UmCmS_fLzw|?(R03)l=}}oWkzz zP~DVuIK2@uz4=&c#=a)S~OWK7{F_bV0aIR%mWa?wsjb#1hz8>u8CfT-?ss zu-F80*j2L(omtFSNbZ{6iiQDeCdJhPZWtNOeTuz>qDPLMFhxo<{WWct5S&98hl|mz zx96xSGa@~Ej1f9E7pNQOxe3_p(`0ll;>dP363BUr>aD%%reWl0-GGdhBgUNsOfTFP za|7@ARmALeNamTGZo)pNN1sydg;N8>Ia4~6GDm9}%d?dxY>7>MSxx^Eaei?IWa?4YLOPP-O|B@bhz8RU zM(JiaH;0*$bmfAlr(gVt_?Qtfa=(NGVVp&N_Qy6+;g6br@_RqLd3*`Z^m{St5cn)q zzXNl6>Q0q96{m0L*ifI@v4JQ@zeGY)WO+d*e+CLa;ek52FCV>nmgMwBw~B79mm%gQ z*O`>%FYSKmkN;q~kE%iR!OhbJFe0idHvSenTsbU&6zOk>E`OgsPJ!G{CHkcaA-_P zKul?Ql0ShVJCnI?;B@UgaQelV5%nEiS8=$sKh3aQr7d$Gd88w>;fEuy)I? zW&Qmm_Mz>6_V#CgtX=kG|M9**Qcbn1_QZSdUU~Oi%GRP6)Ml^^@xp6q`QzrHOMh z>*ISe`%3z5KKiW>Z@u}4?MWZ~6Jal}{r(D+{^^z5SNnDy%`aI~5Wl9QC_B5%k1t$e z%94|-lIxP&v2Da+5~s`PoBR1DLCJ?CFQT49>2HeDw}Yew3jG$QW8R*azN)xMlKQGu zg}}0)k|OsM&jiy+Y{7G$n;K-eFF9S1E;T(iR;5$NM4)nG#z#Rnt4|&%B|mL*`yuc;vrzMvo+OMSqad+!aU%n_MN z$sO^r!4!gWobEBX&+y_1UGG*k-O}ac8Si^(001BWNkldos_%2MBPx|2?@ zyXZ)Ibmv|?NfkURDDCPcr>kQOhL<5uH%3QAS976@g7rJUc@HdZOzB2&rB6$L)|1q= z)TDHQx=I?!`10U)zhyyxN_u(u(I>u3^&+2`E+JiJ7ak7RO;cx5&4!|8O%4INn}Vpp zZEJ&&t{INT4Y*A?2f3Vr&Z?SllDlt09Y|F&300ldOj74;+}VlHP4#zRu9N)g=F`&E zf%I=t)9E=1m`hbBg;BjoO-+|QeRy*h(%td+E~>laAi6z)b@vs=*ZBLV=9AC8u|srN zT@SCRH>sp_nO@YC|Dy5qtQDKr5e`nDQbJ3jxKJHYz2$)xjOtIU z6sUV17+o54bY2?hR*NpAfIHrFVi*n5?_r9E$K{%)sV}M1*$vh~bcMj&DbtHd^p8tV z2gBum`TT^Ak) zbzL1tnE|ECxgPabszSQ@*wktX&sftdv(nNa@sxq3vuDhhF_r$1lrCB=DScF9b$8=7 z!Z{CbZtYC&TsmWh>^%>hQc@pvL8ItaN=MV#OCk4`X_3S=o}%2*NLk9O#}n_E5ryvs zQ9W{kyy)0cA}5WV&`2~3C5ujRN05iYtyURjX^^}Z#nTDZJT9}wJq_$vr?e6i%8tl? z5p3~JL4j$lW+g%I5j)( zTTBg8)6>E9HSu#3Q|XYX7?FDNU2-<$Z>XOe&W%NA@kUQfR|w;aFHw7Ry&_*|x7HH? z^D4N$Na5)(?Z)u((jV^@YyZq>{PqV|ufG4=-wu3mV^?y~dMxbk{N3Ma0qrED{;OZU zvG0sQ`px6VcN?U4Z0y;%yQib)>ie31bJ3Ez&aG$9zIfn7(yNsh_`CG(b=35W7hhRF zF*KChkd4IQB%-EgZ+X6dOIL3%cJz6*y}jA}hp0D7t_zIb+;Vcx@vh?^-F zztCSBA56I+f4thMfi=SsUDJLl5z0gQy1QK>R6H~=aein32AxcCdP2|S6O&I&Jdt0I z`K5#+uQyMA>j!_@yZ30=@qOP@nbvpZd3hL%(5_t@GE3r!lH5_0Oi3XB@SGi6lG`_^ z^FTywG?=d9nAVb-NT_lBMJ>|hu~mBtqYL-oOFwbqCy&is6`@M^*8Oomf_nMhiW+E= zw8b@)!ZJ18^z_sktksy$Yv?%&cFXXBJf0p~m>O1GLswPgcB}6s$4f|H2!)ga{pg7a zrf&^{kOy-Z4U*Gyi^Aai0E(xUbFUeMnvPV@fRX}RlH(JSw{9tqNUuBm@8_=L8aay1 zo-VNdxn&#XW~!KONo@MW(6F6E#KY%)d~~c~r2*-DX;hFtbNek}`k!vS8JfN%9(_G7 zuEdOHap?b?uDY-?;Pk1>R2X+(eAk(Q1urB8?`fB7Ib;DXV1Up{0@MvmSqHo{!S43n_?B@lh*FkI{jQmq%s( zHu!ZE>?X|tZa{9xE`i*Gabc59J90Pe+~(O#Q`wzR?yX1yx}mzL5}I@2>N39gdX5U? zd5ZFBwgV5;1?j3t%G@DN|7tM*!d&p&TrUqIrn@er#_H(l>OBgd>w%W8%jCOMcEtuS zs&|z)sShchmrcH(gm?Soeo*%k{^votP2fv+gzkiON$b`;W*44&kWLLGKr#!Xx}55p z4-@~QlA5FmE`;asFsu3zA?V{a-G%#Q3aow!RL6cq5hNMbm4xFp<8&DI@s_c&w1DF% z>B>*n5JHCym?2^pr!(d$ab1wk=>B_FI&Zo`y2SE9#eCR==CaJ8y7$Iobpf=Lef<<4 zc$vyasOs+^s}D6SEZD?p64VXLZJBW05jn#Z9@5X5a~>W2{P{D>KOE2f$#--sfT*wb zYkJIn{{gi1C!Tw*G77s3k7Lr*8EX3T4;k10T59@&g~zhsRMhmmZIyFcQ}CBmR-cM& zLEOGHYGmH?t1+cuOOM>Ptup1*|sZ&6o|PpK5uoWzv*KM$S6ckTQEh^Z0>j zDD2Ir#?K}KQPoDtb;(#ARgJ-=ngKJF5JO>7IG$gdsSi(|jsV|6*HEAvr+Rf;3b@>w zvbuWO>}f5HllcEksg9?Ba`m%%dX{V~+)tp5q06_7mo|ceNwu{hULrwZGm=_Z%sn$YDVd!e4su_+O#pT2k4?Xv}c2R2M+2W%>W*P@Xeh)H&(dkT46 zwChnVGS#EQ+jj&ac5P+*^KOJb51IebI|u2m!V&Abx3S`#s@PhC`nV|D_AzWf zgJ+;sKetof5Pa^Iv%%mp!|Jcv!{DyIaze0f`xxBO@YR?(IRDF({skM%@D1Jc=hbv# z;0S98iJ3@PHkb^j)5#5$Z*h8XQaJ@hforO*!*L4DK#`R!Yf58sZ+JvWNr20F$<7RK zFC$64ozjnC7}66-LYL7TY2GifG)OZQ`j<-p2y%Q(?7jFGV#s8qVS4fR_orM9TSU-- zRQ7FuKmT$fs1y8=c60K>b2pxS2h+)CKO?JiZ-$(oXw{G5sn`ExVp;+I#h zU}AVQ)h$y4Lqayno9?{lq%Q8>{o>s(BAP2n{nfK)pMO&B7gAq#|8e(A4A8`DUwY|h z|3DQb+Hb9W(AT%K=MPTzXz^5QP%((#6VqGdH9Zf6{OtJdXMhKRR>%-E+rUU##sPsJwRWNZXOM$s2d~ztG?R zDr$NR--qa@R+F2WJ9yJ&6D&}bPW^Ogfduk!y)_j^FlSjWNrC+QFsDz1)F+1QK46@F z^W|?1bnYeevEw6pk$!sd;+5Zj{OQv7-@i)nQwn4*>F6lWPA&?J2@egcYR`?0&QT^J z4)3a_q~iU1Rz22)q;5S&#gES*rwb!j5u3j1#EEB~K}=sYv(UeABAosct%2<&tgNDj z$e4mL_s04YJ(SD6Vs40x>BWp{iUUJLxUuPlfO>j#VXQxCLv*PS%G<9NW8P5iC@46v zd<)gC2oEh}6Kyr-UK7*F?k_LHGvgns-(RZoYE-@>tf_3rj+&6FqL^&V=|%oyLR$}0 z=x*;`*+zDhg~So0nV-LNmr`E*i<44wh@a%9Kv$4n9O>!QJt~MuU-jn2cdvYW?p9NA zXz7S0i{rrb^jPWWX#e-^Os;bz&kZl*KiL)HV&_pSO2gtQfn$R%D0#nhYsY@{zAB)r-J~Q-9I###Y4BTS)Q7#va0BkiQ za6nwH7t3IjLhhT%QpLR3T5e@2>87Sz-6U--t(_g}#O&-e@wsL`m%%w^Ooz~2A5x@r z($bwF-Ni9#+H%tk*1e0S5f{o`v@hHP8KleZq8lckmVW1un(m`?$LBt1*E_80hUZRM zSKT8esbhhWhh0TVmu4(o_>?qt6V;8>k5QFJU|%^K;S@8f>K~08x$@FjMD>JXbOv;q*LA&O7%`rOQPSVQ*gRU3#6ZP8g z38vj!57mdg`4+2lCW3YSz(}0=mmi-wgHzp_%r9{Ff(3f-qjJHy8VTr{R1i8(f)>v& zKfi#-hYLRZ!H2V7*4GH^+yMQDKswX96L{d%%i~qmNLa3+_k`G)BUxR~zowdg@A+eC z>)_wCj11)NtV3y?hnAvn&yGAbb=clH&z}2&n$XjrmPe(TN+ue?xUm&J)K9l(6uQ9znGlfa$ytI zjYf`~)jYZ}t92ptPNF&*{rD+)+ZwkuXLJJf6dK)iw5>4`s%}i7HfkQ}GTf6$=Vvd~ zt!Yu1(~mXOt;7z-eRvUc7yViM9NG=`S zaNGgBDej_kAu}4f)&SpO+)+4bz<72qyjCS5akOw=v_2zJ>x;_;$iiYlv4Gp)+*>$$ z+>{nF(C->IW$FaC5Q&>T*kWY(hJv3;)pLrgaw7KM6<>y187s)L04 z`Pm@3(AbC6jE&NL?}x8EH1A9MatF5+u*D3mIDB)azqH*Kmj9)tbnnvSWm}hR zq0(r1PE1f4k=BXxF$~}v2&O^|@zXK>1d0GYK_M_xU|4EUMQT{U8vF}usEia&P)iQ` zm$Dm_O3@j#=K2_d8U6jsOPL!Ssv?%TsT;e%^zXg>&hefD!gM?{&h;L%P8^8JKZ~pP0fA%x_i2ms2O*kD;e_NtCZj+`rU))I9)Z*g3+Zk-w z+1r1U+ND41TT{2?7ION`1Cx_+r$7DLyRTqP-*@Ht6B9QkCQw^7AwHAr?T%jZX$YwK z;P${L1Eg6t3hPKKl`UR$pDT zXJ#*geox==eP=$Dnm)g$cO8GKaAve_&EDPLzo_=^jrH+F?{Ha=(v^Plxdu-1G-;Zl zEH7$-A!t^Uw-u?ZjzrQl@ z+5fn@;V5eQk|p&Cp+!~6VcY?fCzr*Hp_}54Pl z&dkStq6crF(^b4fPiLi7Tv=`p$tH;%LnW+Ke!zjnM4|_#hKSO|>$yhU=@Hn}#oB?z z#L4hE?DtANp#AtnMaf0wK|z>aNMQ`4=V;+zT>9eJG5%rYfw*S;={j0U9bCFJm&^51 zCeuq;u9?&4muHs-6z;fwjv`0&pslC~@+Yqdt((aH{0;g3A)!e@`Qdbw&E=+me+F}7 zN{FT@i5;`*v0J$J-~CflaY#~PPrSr*8C|^Qod;(_D;%@ExP0ELFWg@6`kAvE_uv8| z?IpT~!obCR+k;F-bYm<5#gYk?uqF>FS?l0qe-im>Amqd^9%a07=6>T4+_+g zn6ZBV;tyd^0Pjfhd-#i#)?;M3Qv7cdkJ{H7Ly-P8U($$7&lX*~Pk&E<{ha zt*OP6b$DItT154KGpOjL5O0sZ{C&a>c*kegM{C*C)PXU2Szk^SC_f zq`>exH5LE|)PZ%^J5+(91Z;5!Fdl_f+*23sjWIXx!M`n{Jp$C&~rl$Xua?_`0ZC*zg(zJ!u zdCeoMquQ{5S5F(iboQyKIG!=RJcasA;Q6$LM4e|HKAZy5r)=5s)a>U@&6ql2YUG4R zwxw)c4OCZ?tv)TUWkSm|Dj7}fo-vIa^UAD@Y8hCd^zPZPfA{R!B5*`?OfOl<>&W*+ z0;d-#X)Fz#L}zMeR<{Z45IPAlaD5)x>~vJkYwm7t2GlP^HLSg{nS!a^-Hmy7$rWR{ zFU=Xw#nPNNgUFXj(*E-@fb=7mkEFHMrFBP6#Vy~qc41z1_xSFtL+neZ)!cpL2s!cB z79QELwl%CXg-k0CBEfM7h*#+v%HDVXH>m@t7W|%+52wuuGObd_-enr^IKi3Rn zVL42khHlC^s7{=Vtt$wYp?r$Es0wGLuRCl8bkVG5Ph(%2Y0Rquay0`KeTTmW#G^+> zj-Lt=n{CC2T$rvyYFj%ocOnSnqJAAo$ZZFN)R{YK?1TxN(rE4(gzjQ`@ja(Dg?(^H z(Yfv{+#UtuFgkN(hT*(;-8F6`Rv`8+_ltcHJ8@)v-u)k8x>2#H)j-xGZcY2Z*2k}Z zmY&@T!&hh3FRtzF-P_slm3;?di_gve!aLt-{GX4tcOkb1|DkyPrNbDkdsq05d;Q5& zq4;8X5}@usF#zMNoZFPE@t`sM9t&#xzKv9!Eu>y~B7 zy?*Vzc#%PMDYT_w^UF%feUa-$uV6~TBW;G}B2uR2<^)B@E>U;D60~%B8XBhO`llj# z#>8ZT>6tOnG5#tV8A3*3VroT2Sm~k{P9mq@{27>jADBL7jjZYS-3RJtQvMOoi};eP zY-NHF#z$HBpg}d=TrZN+6_UPakqj@O`qq!m63DoFx4B*L#OzKuvHtk+chKzr;j`a< z_FKHxeOLe3b^Mus{LOFvUnu=}EgeO>1nTrAr86n0+~2?D=Re;{eaJdu#P{wcyk+N3 zF#Y7)xBHg#cFsczKXD+gmud}9AB;SI9W{Nh24u z2|)TR94~m%&%AK_L@gzm&YnHqbN5-?>+?>{n$^6yuD$>2BC1-xBQ+gc{BhpY9{=EH zeVo-BVEVsrKD(&4zpcBi?cBK|YukIe&USSzs#WD!erh%LMF{qf&pnaS$r3kKX9T8e zGK9OS(m=uqk(E`2XCk0J^Q94!e=>O{6-jsB1k<>Z{7FCufG53mET|a{im-F z{Purb?aQaS{hGM=j=4o!s**xO{ZosQ!_uRRcN7&hrPg4(PA^2!-HxKZ2TG@ztwmz` z{>Nrclz49P`Kp;%Gm4SjAN$EOECcNEo^W57R2)%ID9a0!?gy(w=VUU5=7!*L@i$H{ zj84b>5>Xft;F3i3JE7(uSYA}MWouP-P+$@MtmJI&7-;cEbw)|5#zVv~&~G8PPbU;;O3Tc`wX4GjQg~ zMIk4)hqjW%BPrNN&!(pUrEJ#;-lPUCc zKz-Maov7)^>HKq1^Zpvh@uG)R+GS_4f!}sNSB-r zr*DGO!Bq35J4dq%c~Sg}H3MLue(sDgqIFMA7n~z&3%or=T{alKbwiufz&&lgNPMLO za&-pv+0ZphGPM7Kak}SC7ov;Eow-HK?t7`*C>9p2FxYUX%cicn zM+oLj!s>*pSHk5BQZ}!nVtg9)BeRZSR5w_s`q8v)6CN4&^xu3PSNZ6X3R9;}sWB|w zN?1e%TpYqGyGzM$+5tA9(7aL4e0NAniZWlU2?kRyuj(h!Q2R$89aZb>0$9N zwrFtRK%E~KHxB&F;OSrf@|UlFxBy}Ol{06SgW}-$AtprRA6k3;m#?!9(JjBk?xENB zC(u1q?w;@9?fJ$xAN#%Q`#ys2C|k`&z?PPDxBGzw{A5(K*tl9ek>)W0hDe{YfDQxyk*YP z8M9|U7dc}a{V>;dqMM&0doeGPki@(R)sYjrmtr)h%W1|oL3$*_y>#`!(xu}eZ+f4C z>0=uwWK^XYrbkxO_ko?Kr5!$0w>C<2jv6mEZvpuA&>QECK~it7P9v8kYC019I8=4Q z7u6zpE6)qzF=Iz_6E?=YPY}Egs zxW56bt320zaVZN{Ax+RgLJ~{}AyC15R5aKa31FyzumCZDkS~y`1OkZ(31AXzKBS5} zX+pbKgrs6?cG^%)4-}IwlFd4$7tmELQL`@p(b!9uRZo;FW*I$A&!uVpzx#Q|1QKmm zd-gfUcTUC}W6Uwf9PYvI$B$o$>86s8_+G$qak|uWAl|4P%9eyK zYKQ7Y-9loaE=UWN3e%0;#p8nE2`;CFQ1lsYb2(ukWkhtWE@I)?)4+P>;9(3X;$zXS zij_JwT1vXQ0RmtlGSAM`*d0V(FmCqpc%Dc~w#tM`{nk`lJNL_kgVU@V;5b`P>A2mt z(nB~6FiVf1KVb(ZuMMxvo|ApBg<#$2oIMK7b@<-KI&5~qT5fdo9GD%4<8*+2%HNIY zAgfQj7KL6($yb8vUv+X3X6)3wsw zWiwYz4A9*=AEr+VtOyDX3JXuI#Ena3qtFOHY%dbiq4ffVnB!VOS)`Usl>#%sA_I}K z@XDs5!pfxZ!d0ZEm&T=}6h*~$7y9E@fzwk6U=Il-COjkrkv=d`oL*5OD?z0c`MCKC zd)W{biAyCCPmLpW{1$P3iGEGE)8k@sH^|gpF_codySuWY;fYVg>HQfU9ZpT(U}H!( zfFJJ0Rde=ia$(`QOP3EWSbxVck_g^<=C#{+ugFEe@YscS9ig8Tpr5%3 zKl*})*ROxL{U#uN-=>Vgguzl=^qVqNPJSS<`*Qm?+dGeU_x4^WOrpo~UFJ6zOtuyyn$_ugSgM)hz^Kbpt z{SW^6^jjal|0!cgai_okoy(uS@~1zLv$HIxgPNO_HP}kR%0feTZ!e|OR8vzHyD|sA zc}_yx>I4cF3DYSq>e!Jfndye;Tc~q1IJkOc8=wiu8?@iWm{aPEW--_xJTw;Q=iCJY zNIA}6)O220=vFF@Iz1gZ9hCBG^wFsh)UurR41Eo5ccOW0nH?c%>7={>>W>?x%he1@DIMfn-@g|rovNhJFBvb&Fmy(B1u`A4qo^(Cxp>?S9TmlS*HK6xeVFDv(ue=Cr@zDWAWwr~2l}=^ zbOE`qb72vTM(ExgpzbJLx2C5XncEOjP+gR6q<+;1QhWd0yJoYzoxI7kZ>j_-Q=@bb z)x8f2X&mTYq%uY{n>Z+UeD0gdxUM@fyu`51lyu~B6+qI6(&gZIZho^|>JJ{;m@QCG zw{{GRGm5PKLqpluUr$EF1G5gkgHc@-ka%P6b;0T&GIV@!0!iqUAiY+SI?Y8fGUN1f z>F6U(vikMcuQynK05_5t-7wr|dU0fK#6E`Fopi1hcE7wXW12`^hhh!EpUchPei~K% zPH_Fbm*2bdA#UD#np&b$f%4hkK6o=W9@;JZ(C45bq($Vhj5Q0xM%LjU%qhaRLm^VF`2bB*_Y!@`7R+beKt}$ zxhuqXVo9g)r~(&r>!wa!91c|6Lo$m{R4!ps>@Wn9(wM*3PLVEx+E# zu+o1A)Su7(_l-E@TXy2QuZv!rnVl<0hv|7#%=5W@|MNrg(`&N{ek4EM`(1&;)uzoR z;zol=Y2Y@H4v~BEI~~ptF41Ji=4TwWaV~K5)Agwo9MamJqJMUJ^EF zs{yHUxxnD?uw-z490ohoHRzUr4b1Z#IN5oebZZUKoH%6yfh{mKzlI`dN!|dnuEOVo zvyj=RP2(wLsd4ab$77qa2Ob2Zv#r(&v^hdlds%qA?g96R=ncbd|JseV8&59HY>tDc zCEH!NZoVJ74&2Wp+#yc+Ur^JHURC@@Q7k@+{;I7V%dA(h_1HU@zv4b0{Eu$qBW1Vd zt0R_lEo*DB{S~{oV)3eb+)hTOj`IJ~Hd^n!s*y)nVEV|Cm(Tdu74|FC^bMh5RAEuk zPcS-_OGQ`+O1cE~M1})$fz-ih5q5Z4SWq!nxE{SRvMC(jOGO%KjLAbQBI8!%1*BBs zFiG$JrCLX(g{hNJQj6mnPwo{5@Qz<9vp?s|D%NN^M(Z4E_bMV60D z8fs`=VpWVjaF!Prl8#G#*RD;cu%w`-_h+S8yYoe+tl}r0S`^jgL)9*fcrtb`YPcC16_p!9J-P_eZLQRL@ zKY9DmrF`_8`|iJ#*?GByQ8RUO?tJa1uRZk8eMc_6nfWFHdfk~bC#lp%K)OYwKYZq! z3(h=n^74H@*q1RgVX%R;lU=2|1`|34mV{7JKK~%2ZVo*;JT#QGwW9aOGRce7|5--* zdtUhd3*Wu_SI1ue&-@=`q;wzp`HAIm`MpzDk<&Rb@7cip845t@BaSN@4ZgF9!KfK zyxjT9D}VaapUxf4>lsYAp?rAzwi-MxWF?lB*5DecIY7qu%9WvID`E5m6&7u43vDCL zrEM@`^2O&NpXN6nnI1 zhEpAh5~RD!sw&ab!*_433eTBeh|#1lxhf$imGJZ~!qbl~CV>>ci&6Sw0$C!nvN#

VQ(3v0`vFQsC=8$#0H^ldeTZA%kUQ(Y-iHgl1TzNw7qtYoBahO2QT zRClc2*0wS*Ha4~x!wbcj{H=%P{YUcwq11HR^&tA!9wr-55Gfe9hGhQmHwb)r~c@Z@~(crsr1Yrsp#3uo-0AC~C`Y?mWgi8vYmE zel7qjeKA{S&kGgQjt+BFgk|Rh3z(k)R^7PvP?1z zYWh3!rb{UIY2{G`|}#r#W0VMjy-Se1NWT`_92{fBzty%_z`sV_YE) zUFH_zCb?YMEXjre6MX)6f9u=7{Wi9A%C9oknehz=4}Rx6%O9dJ6z+36J-RXZJTtQs zFy%-3I%>Mi>0esX%Mb6^S(ktOP;)gT8-3*dYS?=D$*FZG;}!GQPSOiSM`u9kF*tTI z;bZjlY;L!0To+%xGd`E2&)mp>h0Ce}if$g?NBN>7YwJ`#G@jg+_>%a(+#~sGL2Yu* zF|W^7z{^2mTrxK{=SJtIQErOYWOQ_M z&{ZIdP%dg`&NOvluE^Z>BxPPg^@Lf|;w@+et|l3sHR4)hbv@7-Q|JK0+9Gb5OW<X#OZToT^0G>;mx}8e$2F&fT!f%om zd8A=F3$ngwpE?K~nVye5*{hm1o7bX)z`>*Ex7tSRjIHzxdd!q@-oK4e{QR%xoQe#? z!k|F9fvzULpD~ZO`^GH)-(RaqXMzpVm+wHssLm{ zaifG6?v8BguFOlU+P06Pj{b>7QRQ)DE{f1WoiH#RWj+9JIt@?{rEC&?0HUj5MC>(w zBJFu`3=qW;jWHdY3O#`oFuh4xFR1BRW)QCGNhu?Y+CPl6a1}VpAjSI{wD?IIG>CNi zr1Ge}-NxzgQ5cdikOZX%MMm}vB{eKz*r+veI?Z#xv@*7o(W9sOPw9HCf16uK$&LcH<(@WZ`-%2b>`BJ1WrM~>4OoNO#Eh+m-lpEI`i;?Go9Oq%k#GG zuWB9czogK1Mzd;4Q|YBU|NHB&KiE1y_Q~gub#{LE{7YNgumm*?M(|FeXd{vX=++%F zRJRFl6dx6WI*z1JbY~D%V)|CPI;;;naQH;oVAvoTHe&Q=uj_x~ELD1b@!M~`@cpS6 zT@>*0>AlG5|9a=8KS1fPyq#AbGI-b0^7`#H2g*|EGqsg%KMw6~-wtY`6PG2dq{=4H z85LEQ8Wzx&6B1mJuv%I#?eJh57ImavNyu=z^xtRi8a#YBH9V`Ro?*lU9YW|Ui9LkN zIZR$u*j97g7o-033Jtws^r)!7z?{G+^)2}_h6IE};^$`I=#FiLDWU#+1B0vD43L>f z)ea0G<(z>HB>gKBMz*dXY3Llexzl$SXH~`dZA&iQlzeJa#JrU?U3iMNGXOI$uYT{| z6)5VlIAx+@_jV8AN(a;V3Z}y8vcw3}ai)Lz@t?QvU$(a>q+>p6`n(m=@(t1*sE@EZ zoF2C0vEIhU3%FiRH4LhFkvcVjbZY`aqXLTk16IsiIxnJdTMb^TsNdj)aQ%vgI($1%rR+gwwM*RT zQsH5FC!mjt=PG9n&~y*ceO(;)_OWCu z%$e@vbP>8!)4%EcV}!P=tKsyixrpMHvlwG|&gfCk@G`>bg7&d`yDfW@V{4De|AKhl z+|`v0sDo`?r<*%FkEQ1VT>xpis@5EApR)d&>-keR?&0z8OuqM^a@A$x)(~Lc#RsOK zrb|Lsn&Swmj{>^p#<2R0H(qOM`Z%B;2>;gI-xaG%O?N0RF!#Z^NL-tYG_$aa&22^# zhP3(sosS>W{7rWwg}bKIcgDSS-$Ck zcWyrTorO~uJ+v-e36@xcbPB2hzn9P)mt#%un|dUzHhX1LrpO|V@O zompKs+Z-;ky#VPg{PfkWCAvQ!o9Dq!$wPD_}-Ov4zJTrMpF2_r=ismx%d_^`BSMwa3wY3)FdlRzS|K0IWb$zqgXbGuPVp}fAv7IpIweW{%OeZBrCnm42=Qk> zvbiYwJcO~N33wD#t9b1M|1<^dP!_*iXw!al=iZ$ilBj{ z;;mqM&_F+y@bCVV+>?PDD3^}4UEcIb)RgJo-Ce&-o|iHT&V-e14c&@{8WP#l(9^o4 z6+e20@O)S62Ug06MaGe~Cba_Un}Bq@FOQwycmDkOWC|R$qN(@43WLMxzx&aTzW1Yh z7(M#pkACsSby!c5h#~pl*?x$_pS=3xUtW0a_5XbRwoNl99sQ`Y^YzZ> z|9$s?8_M$%8ya}Sm5f5~h!2LhS^Bf@N^+*GA^t=c@{xth@vUM)Ty*)9HXg`N)Xn&l-YE-t4$5RDv@i-td^q(SLmdR10P zK(K#c5P6N_V*}+jzWj___D|{FU6~S8R2+o6oNfx00V*-R>=vw3<0v99Ic-VW4<1|M zw{%hfMUGBmd#TK8qW&$8m*T9{@Sw#--QDV?s&^8WT9H~25`t47XZq@k6d+{)>CyVV zMS)8@Iyg<0Lq@!siRn5J&-8*}XHsa|s#U8<=6vtYCo&G3nyyn10d27>8A!@UNoeH! z={Z%8)s&vvR+=y=LE}ivI0JE|oX+skM^BU;UVXT2@bH0)gNNaBoJCC4h|+0eq%Bnr zDmix+I*RGnIB)t0B3d5c<70q)3{qMYBfKtTr>WABC%8WXpiaK=W!JU~ScJg^KsPfw^HRzM=b94|+kzW9Dk_w+&aKh8mergZZhEaw{|{4ju&}etkG5aDog*U%U69#FT!j<9Ywuv zs-hN0>0ElcuhJ1~@wzzwx*p*v?QRxLcpdpJ$H2~N$aBsJsn;Gl)YW|K80*x~jMt^t zO>0*j6ddIY2py041yx<;j~*bb=YiX)ZS+k>oO1cfS48Tt`n99Z7lU*SDYYNF5vJcb z<(-2l+n8P`ZK`jEaksH2UT)w4gl-itCX;O7g+SB^;ko74-@r)|#sxeJ%;jpPjxsWXAobu+f%ctKPL z*1s&%%eXrx?#$o#QMODZ%eU3esjj|UJ#{Khm)R{7@TS*P_toWAS2yQV=ZdocU8kuC zdg%C}^q3tRbK^5HiPw>nSa;;X`xo_504W+9OEuhGjnxHZJsydjV8+h09r+8<$D<*2 z3LDL6fwWuhuVFYUV^W*v-HQiKk9;YL9&m|lOp4piUE;Y8Asxk-Ez%nH~_# zkh~o=S!)V+2StV#7N!J;U^JJauB|F66wMgYgd86m++7(Q8Osh6jKu#x* zahX(4@;ek_mo&4@}|VQRwp&|Bo_2EZpwJ$nfE^yqSM~zeC5fL zFZ}F%)b#gX|IKfxM7qc@9dmj|$6c%Em6tapCxulcadIXgtST)uC*eR%YC=xbirB^F zxYKv_q^u;^WjRP$n!okJgVL6D)^`wNCop>}XvZtpfr0fJ|QH;}NdMVGDXE~r%U>pO>)u#KpJX`aJ_k%a+v-$;zam zr>N=P^E*&?$D+fTKIw+QipI1HPaOH=y-Ud+rt3Qq5D^iIF%7qU0K>1BMpSKERkJF& zFk*f}LWR%xViibDQOECM?icx99zA^GBK<7`bT}O~J)w=XRGoB4qA$&9FMeCSzXot1 zgGh0tqoaS*>FEMSL8QBgBqgeQa6U?!tk#BKLrMSoEsUOo!f~e?q>E)8rAtbO((iph z6^~p_qf8|KBn_QybfY~ObT9i_Xed$i%X$Nr*rnyX`~2XIh^;+p7yJ zlhjxpJCJhIzdm9Y8hHnW>egHUCMBipGcafRKR*7CU;75O7d{@Jn!awW|>8i(NKQ?@J^1TR_DibZQrhJm-Z5rbN=;-)3pKeRY@o5EQgM)1?^cKk95DY zjuiFfr8UQPY)2q}z6;yA)bxMPe!lZVr1Z`@95vdB`U+_3j5F=~HNoj--sW1u4wr(AuYhFULBx@cCkG?o|fu@==>&6`H<4$B>^2wuC^Q3B-X_AGH= zY|Q=_s4N0c<-Nn$JygBg!|lI@=_5q$v8%aI{u-^0(yotRopHstq}wqFKDydg3evB> z_b+m|&$OZkj6SVfJG$S$VU7oLH8I>?<`=v^x9SV-xO(^AJA6$+2sW1R%F3-$%R{Na z2nz(}ERDiUo>~!{6cU&?zd)cK7$vv5UtmaBa8*@dX<=1ZUQtnsf919vJ8DWJi+AsC z@>lgnUrS~9p-!kLr35$m%jivBq|5hFWdXfZ@&B8d+vEPV{mD~H5-KKY6bK17L!)JcyV!X z7;?P`O9uA;9smF!07*naRONb#f`TK%Ty8pgI&ePd`Chc(K%JX@oG<%!ys_i_zO!Va zNHacgS6C0VNbmXGPe_6J;DdjA3QGUcPk!Fo+K6zP*CUU1$I*rlo+3K^g_F0Qx%D%0 zTF#uo!-AUrFk<@pGY?yN(vy)YQ<8x9Lg2o0a#(a}*b zFidQ_F7k~J3?BINYsX$|-k7wZpuRKr!~gvMJ^wF9^OiLwEh#-vwiVZlAbkz*r-$fh zsQz3a@`QnzNiz%l;sOT}`E)}AqXK#V6O(#)p&bJ=6BCCMTTk648C@0^QTlsR7oNQJ zg_AFw|MQn11hf-jte-IsMs=yApEpHVjbhsUgHa$v-5#bX(Z`gsM}ABO;=r z7B43EBw;YIiD^O((T>3Q(Ws=jrs20`nz1HO&#ONQz@NBl<;+$^4561Jo1;<(`#1TA z2QlyxN)HO~OU&z`s%cqSPfuP?6W)*g3{;&b){V-UH^1C3jzOQ)GTM=r5|)zo*tTtH zX?UtI_-H6bRawrYNl4K-IrzOanu3gUD{jiL39-7qk3o3Yh3SC0YVXbqDlH5MA*QEs zL(cB(*H0hXO`tiIjgBtMTZSiH=B?PpjG-kzB{URD4-H9_>1FkaKa0}eIIyO^ekdt{ z=yH_w6%=n8kR*vs8J-fv2Sn9@ zkW&2V$;pKwO9Mkw+oYz$!|4Y+AziS(IwFj-S$VM(2@b1R!iW^EzQ4Dk zbeczqpt`x!eFW*#%SV?r$5|roFwFegH}uU$KW6}?Wu~JYi)e4sm_I3};`Cb|xaASd z>mqeP$S0^9;R4<=raNT6NvkZ!QS9y1bdkBIr5m6N!hN8wt;V){QPX{ExYbxvxzP>I z#}c|2&OMf`*ts5~A5+sci~E{G($ScV&IRHn~UVNfwqCv89U3C%<9K1 zFS4dPIo&6!OGVc^sQ1#0>-2WUd<6D^n3~RiLZ6xrYMTX}5RQd}cgXqzaMMOW-L{aJ z?l#m^*bdyYPLzIZ9eO(QusN+EP6Kkeiyf)U|I&;^$~{gnM!m0#pVl%Ct2)BC3@{Iv zu8skQ6X(}|<*Q$jq7JA#Toh5~|*Bq+5sUUs*^%ME)hY<=beT36TXxsyKJN?4S zE0Eo%raQhyGiSJ`_oJDA0?r|IgLS?~M&9mQaknFM9>)wFF>dchWxxGy&+(!ivc|r0 z|MXAnQlm^6GD{fc$%Rwt&>T}&#uL)HH9)sX38*tZf()>fU+4~OXY=zi%=2{Y3j`OY*S&k}j|@BQ z>^fijQtjsL+ea}SAU8&bz)egSs>`en?wZvFPFItUMH2f6a|?w*Suk9D&Q{zAb_L8V z$)aLFZz{F`9IbC=T$K^bQw$)Wn zprcbq!FHf6v^<5U)XrIyl71rx#pOodzYXMcIn6!zl$YZ#sOeCsyT=6d5g7g=ULCpf z3UYM_e8s9SS`ca*qWd6y%-($d7@t3V%w4`+jV&VTTlY8KS}%gvqv5c6SzdqSszXi^YgX;pwmT}ayE`s8r8@-}uN5uy}8q=O66P$FJj-@O1 zyzvus{TE)i_12ST;B>~k1M3V6z1$ho$y7EJlGmSp?}blZc>0B>FQ0t+gv+{?ku?a{1*;Pwea6v}p<9g-Z%k8zRUXFHH^8a6t?_ZBY!f#LV6H zDDfyWdyZ%q7g9o!X3if-lvf;#E*QX-)Kkt}MCyUk*N?sa+UC-x4S9!hsYCjo|NbO( zS!Xs>RVf%nkj{^6`}Ae>J{hkE6~`_q-Lz>}LlvLQxnX)Pdm}DppMZzGB})!^p(ZRQ0L17ua|`_Zt7`@l*MMZ8%H`XCvhI9gA!9H@=8ly z63kp$_fU$y8ybd*Aty{oypo7@`ka-FU9O}AlcaQiPfZuA`x~cI<|xZ3zA`vCB6P>5 zRcZ59Zhc9%7s{f}Tef#^{bDNV21EvD6+!9q^6Hn7bDo+SHq(+`R<6AGXA&#_e6ehA zeNWQN)xz_6M*(uwbkqL%BJ0*S&+kM?X>wshQtu^PFIB?rN9nEwqNWF>a%Kup4+x6O znLd4fL}5)@&8mHceoGVDQV-+hmvFAly&qH4Z2>*~@Btj^rl;foPgqTMOxi1*jP)O6F+eNrx*uKY#mE;K zR`}@L0{gVaN9tF?y7r|9yD76;a6cTJSq5j%_Gbp_pE zQkMzl@kh+}A|h8Y(lO26Q*T*4B?synIf^s=8+g+hKuYsIC?jkjyLvgU7hQ6fFIPUg zz#Er~bG_Jthvz;@m(K-Ahtat~0Y*@F5;3Z|X~R(F96()~I>SmCucuLwN{X?ek!y3~ zN#xdlYKQ6sHG;8>lbdqwSHJpA#*xbKB39SLjVBeTkHo1Pr?0>EMo@nWrxEWJfSdE& zOfM{%yX9&!clfTm>~6P>s2aou&4F_tsAIx0Odp;4JTTgr4jEuB7S~!podw$kAG9rU z%b63th>yeQoG2jJ27}MExeGOD)HQLs2kSPgwGz>t5r$RZ``Yv`Nljlw4bNs!moSvN z`ybnwsdFu)vh-23YGQlK#9WLi%^Gx&8%+#)b9PsD?e5(#)gC_{v*1|mOKIKNxqU}= zR724W4PARAJ0G_=ER5epwinVFOWJ2g?>N42ZppN1B^X+w*KX`YZf7hf#GgrdqxNwv z488(*XOt{hw>f%7$&48cHI=uey^k+YXY=tL8}s{GAZzN4P9P|~Z}~#P7x9%V_61Py zi^;C7JyKGViQrz+f=EsefD$0bj~_ooEs)IGL+qpT`Qv21JWpv5wgK@O&8jM=sOhI; zP}6hq#vDJ;mHlX0zW2L=E)A1oO~>~k30=MyCN`uLaCN9I>gK>5rJH}mBy!O>^eb@J zeS&cK)nssYtH(jfUNd60%^l`WoG2k4sFusb!7w{uQB-V?F-&Jk{QwW&buZ)%dW(<6 z#B2;&Po5$6Hv^0|;gM3x0cSlF>D(D@1muX{j1HAtu4A1>94Fhb3yd@>ROF6CaBnz1 z!3pk?`qi1xqUd}~Q+GoB74f{i79EtD_YO-;*N9N#QgOHs#)afpai_O9La)C2eYaO_ z{&|L0(E8PDeK3C2gFRTka_v>}_|?1eHrBI@71giY$6sAykGkqj@GhU<+`Zbr@S4YN z?!CjP>B>pWsw^Xi4o8cXIf|M;FVM{8a5{1uB})C^9vD3*(JzOL#SlceBm&io{Hv&K zw4UFB#YE`5@zi>vm;qB1aw5i!i~&{<{?ng4^~~A+-sGC@*bN&Bc{3inwnZhE+Gv@*G*f){p}0RoXIZi zP2SW%(V~pueq?maE@1i)iS7*t9zAgS_5c2Qb8UEe`Sx^~UY`Fyz{bR$C43IW{>4;) zl0Cg_S+N(Et--co#mg3VCvPHA26M_s-NSpX>u+tH=~tMX#BkcP{pb2GJ@M+#l(?wz zqDJYz`p)-fO`Cd2#`w!MgeJB=!~J*v@UnsSD{l`F1{0RIp>iLKNP;-Gb!Meg$;mG=w_ z^$)L%oi`6bnlHe-C^_Im129tg)45UG8Z~M9q=I=-5dm?5{#AHgR-vYcB#{O*#8Bm6 zN^H@Wqt;PbU{1oyh^RmuEyNGeL8L?}O1gh&F<(WK)3NN6%UDUb7557+t!=?MK~)vo z8XHp*b5`!IJ)Ph6(pKy%7_OETDe#{Jnl)sU)F>)4{PyE zr;^d=3F;n~8?{SEk3l?lI=Vnz3v1UMn-ilwz?EDfe-G5TiOFw9UENVz%TIQ5ehgYW z4T8thJSRQAWx|y87}23`&V4J+V#37hi99nrmzXY1-6yPD0*vQ@F#|gU@6`0~eCK9; zBVYuvo2qyyO_fG#23E3PM_T}y97Bs7i&v%=gyM!{LJ)tDuv?U zK7PC_8$~^LTwV6=y@#qZYcJ%ImEIm-osU!fGM{=~E_pA}6dOHBCDF;Vs&^czBLgP7 zWZG;p%IOevW@g4Arb`%7jpx)i6mjN{SOyj@+j+YYU(n*r`m zZh@0$wH#cy@kq=`+XT!e_l(>$v3Ol(Zp+STJ16{bPI_I}vFzjjQu{Bp+q=?pk8khH zBt4zRK+=zvWuwc}3*fL?D6!gJ(up_ykGY*)T|2g)&py7g#)s*qoX@5xk`vPn+hv1M zvjvmXMeKrdLvlG_AZ0B(OlQvA-44G+z((xa##R~BnzAjCohE*kja&N@Y?~E@4b-Gh zJ8~D0JJRMJ^OHzCH&L5CFlS3jXdFK+ey*Xr@R+sAbGM^lM-u9V>h?GUbf8^(r39*k z^%>FA)Fa?|>1xV41p zzjSNIXNDJhIuF#pXqSI4rcb}YkHSUaWN4sPDoHLVBoG|;qv#R;y;%n0nFIv-`Q;>X zK~*O+(Jv&#FC?WWuBma`j#aDDs){0`^02i8M@E|Ih5Qyp`!Sld2osI0>Ns8qNH2E=uqs;hCQ3X@(`G~;!x z8U3nH+JEUsKYHqydpbznNEqxt3!`Ub?AuqnqdV`Kf~AQC=;>RYdGW=c^nY*(P(S$! zVJ?@C)YRjTuCH8Ews-G26*vOZ-@b6F|LhxQ&tBZqaowiNCs7Kr)2KxH)*C0t7<~5G zXFC$n#FHATHkAt0ORK`dc7;WR9Y9WRYa0}pOGw`ew66r!xgPIh7ng}#@6BKg>l0@$ z^!GRRUuYaCuiTd0Fc5b5#EIAb`|FvncWvKL-u>aPKm1R!UXGSG@f3{9Rgj6a^sus^ zqgEpxWu3x6Q0=n3p|m0FE=v=KdV6}Xp$`uvb~KVw*?-&1pL}xph2MVL=-e><{ZGI1 ztEZ4nStLIzq}&;ArO{WmYXElz*s?csr48C5-r*Inps9Y|V|lr(c@ z(vrs3j$Mrz8B3B96NhFdZ90`PbH(DJhK7Xs$#2|sB6gJ0QPGjr73}!-@X<&2@2$^k zs^>FB;Vy>JX<6i%hlLhZqGAK-8hA;e9#R?w=*9k#IAcg>p}gp%4LLZr{1g5B3%9M> zu`iAIppf7c|Hvc~;)x)_7*)Z!3KCwT82Z51lkwB)RFV_QbNRkNnjx!FV=&O#E5j>m zx+5#nYPKy&45^5nv~qj)X>2cKrypJ8Dr+&26;5B4x3_!mnyj#}kokz|Ik89gA2|Qk z?>|0&BDQ|0z9|lC`f55DPE7~O-E}Oj=S*5UZ+>a*zEu~fjrj7Z!;kKlm`=)QXkbL} zl8S&h3Ndl=Nxqlqex)_Z+g7cr@GD4YGfoG|X^z!BVn>U&m4^>gk`#x!V$%tDjPj$3 zSYpr2M8BDFGwF7FRYcx1I+mA5 zkfE_Q+--XLt>3!&W~z@$XV)N8Q`1eLmJ{7WbKQ{nqEV#oDsGmzu2oXgb%n=ASY2%H zR@r?_Y}s)a0|wm+Q8_;j&TSJx{OF<~zK_-Q5J~w=Z&fm*mc@Kc;2>=f`lpAfhuWRQJ&g%-t*tusF-*O(Wm%O+)mj0SX|EIej z2hjB+NEf1m-rO*~$z1?Y<(b61l*C8xj3#+;+KhuG zvu@iMox8SrDk?o$jn&zi&7F9oj>Je4XA_Wl7A!xxWkUSMwUGG1Xq@KJeN*+u9Bb}s z&b$m)%jBZVWXvr)c3{kbwjp%a7W7qjVrL0uIEo@zjXXiC+RIb zpUmn1PD0I-PiEI0Y(Lp@5W%{IUEocxlQ})R*#?pBIPXE^h<45ap{P4LH^&PCIU+lD za6!55Fh&P{<%JQhvr=NXEb2z8j#t5Kqia}Lt636wIuG_uR-K_%Pjx=}u5LA^pEr(;c9XDDXaB{~Xee!Rs;ieeqgt;M2;D&qpAA%tP72 zI9;Hu-TdWUjeXGHIzPHcUfReRgU>(u@5S_MZkQiO+&Lpii-Uq0gc%$bCrl4PNu=xz ztit#*WIWslD29PiiJKeB!uPc9>$(x4gk`bPNIH%rNs0#h_1>OG%XaPFgBYdsi^2Cr*jLZ8?^61 zN%xE|UXZ%sdd3oNdiS0E^Ak_J`ja0$)&FdVfa07Om4NE)z z?WezZ@yGqGy%(ra^yZ~^FV%iDRKF~;DU3>=`-k^-Bd5#sGTfT6aYW)2M*i7(YCf6G7QIr z?d@-7Jbd*=B=~^=#=c%q3DVvRy@}N3E9nQRz9O_eoZ4r&hLnOi%fa$GE%ZFiQXu1FGS1-SCa_Y(N zTk#_4=!_rz_y^D2_QZv^8Sc8YNCcFr-dbLy7cnpJNKooKEY7p z&{SMH0f7OG?&gq`{2mlYetNS6Ib3PA^qYk`BNEe;^ zJTce8_v>#Y>BaM=V|zjGhP`#p#b<)?Dd(Qg#UNdvE>34asQ8K4)> z=(Z*<|AIEURu3Yx=9Y(%&>wl^xd$dbG9E}DKUuEyfFS_xUh3R)hPp!+{cqp^3uVq}_#v{}+np(Fo`$3Xb5WC~)VJT_z*fHh2a9(8d zW^6AT&&%!o()NvqVw$@T#pH5MCcciW8r&|`b=B|YTYUL!)bwchdq&;;)zNE7PUo)b z%Q3lF#53Xa+&T>t6?>D1&Z!kb8aHQ0lchL=N}_y^c)I+~u3C-x#NKjn_Q8YG*bc{f z$)W6A(qsB$acSQvQ0ME^-q%NX%*63`OqftNZf9;xS2llZyKuGFW-{D0H%5AT_Vdp_ zk3Z&e362-M@G}_U+Sg2U!s_Zmv&H!bxhI=e6B&Ha;VF?B1gE0eF}ryFaQ7` z07*naR2GyjYBxHU{e>A5&`m}cx|@P5wv`*)HG^a;Zp6KwlnzikriFXiP>WEmKvz7i z8%UZd^I9)7_iZmy*4>I)1cMFSwFPUHtRfX0r5lXaQ_vZ3kJL#ldJh8eDZsuu2~4~j z!WE72d7yIA!S)5?amcXy2~#Fco@K|Ti7YV_CoZ7y6$>1jBzSdB>`3gu?P!@yxlxk3 zj$B8hwdyI1pXL2E(n(l}(;j^ORnv=nFf`w`cKd~>{Dmt;)jm)8=izr`&FA@ibZA_?m+G_`r9A$ywx36XQ}5CTn^? z5N3%`%EPEa45W_Y2+)KDLX5_kqBX%q z_-TUi6BLn}xEO&kN=P1zq@LAX895J3-;h_7k`g`?E)2uHfSgWrI{kpS5F1!p94bst z3R_%%w0>|4a{BLn_sn%d9I6{#1EZ6izM{DDNz`HK>2fPDMi3QLi88563YU!d(BXBY zbE)U1qNA@1(m!x39Jyy?^y5X@cj49Vz4+7z&+;Vb*(AZ7+H|1weC>`M0R>B!$_hXK zKi(k!<(D613{`dyk=f2q*Ke!tXz>7I5^la)L7U^_+={9KEqStufed;!2>lHOUuF@O-&ty(bZ5x#p;hf zx_{*%dG{{$GF-G{07nY+JJ5e2IccDA-(v$a8^R7;eChRL`LCbezOo?kqYwY*hadju z^G~iw>={T(X-sNr;_ZOaL(7VlMS@L(K8=EL!Ukt?uziKmZ@EKle6?D{sH~ z=4YHJIEmfGS<*lL_>GHa&u;1M1><{qGFmtFU&4WZ`4SHqc;**y`mbIw!2awKayo{W zRvle$V^2q-V0~a_#wo_(4d+Z)vsA58JgI})ho;MBFhdypk>Q?2+jvV5!WLs zN^8;zgX7}L{Zb0kwiWt^LEK3URtT0MUkQX2Wh-%}EBjx=C^%oF;-l6^t?59$m^heB zM(z!-Dk|iRM{1Q{BZY;su)Ul=&1k0WS>bDNcKOE<11+VI$s`>(@$W0AxYg@cu*8>D0QSc<$tMK|0tfAGQb;N*AWHjFx`$t%TiS zZ@BqeHxok6X2$6FW8ie9X~-xe99Oe(qf*X+T({0iOdNrag1RxfH$qgK&>Z8lKeu;V)N|^=?%^EA2&0>%ZVq*c=o~6)xuyo~($O)z zDDFkCf&~G(g)wUG8;_fYeuXi81k%6GTWydoEu9M=1s6G9^ttfw&3#ZCD5V3StKKD% z-7%N(m|tczX?!#uVqy9sV{;SInG?;+j&7K4GpOoD=LVfNYqajLe$gT#WEMeJIAf}F z^N)Z-WHjP|+4y{CrxiUiO=ry=Bmu~|NiFG)?G zJS#r8?oe$r7L@k6n~yB7CbMukMS%Kdlb4Q(oQQW^D)}+Ts$-yQ!d~F?u8p6Eq1xW5ZKO-wE@U){-$^*%Qo z)YH?~Pi)bE*OHQP$~bPXYgUjyp)_5G=u~8;-6(VTqFkmpp5P_q8Y~8Rr?WY zdTwr?5@U{UUpb2DCZ~htpt+jp+nNM)yeyi?(_)xz>qN&8xX0kaQUh9jGX$z8aNFIs zk;HawBhuw6hSiPc*c1@9dG0e<*E;9%Hg31=-6o>uDUQ}{Uv3Xtp~o^6>gxuXT|_QY zCuC^~p({?R7s#t@Fw+|s;A%OD>4j&L-Vf(^XQA!}JN>zYTfQ^>ZbX8jg=(s<$+{iCEo{tZ){>{l9_D80|h! zwtw%Mk>{oU(ckr0-)qsIW*RTRy%2eLMqc;dwMSo1XY@fnOur!qnGQ9ZVWcEms0e8& zYC5%sg8f4vUITTcSTuFK0pVdFJ2@Z>5Hu~WA?*UGa7}S3k%`ncG8vtTZV9Gawx(!J z7Em6PB}^~uj%3JPUP@(mRd8_;9^0y-aw;5^m*ZPUCPe-YSd2FVOplbB9);@#Q?-ii zz+Rz|YxZsp+;bLl`U^kVlzZ=YmOGJ0q4Y38X>9jMyTmkOMD|o zT^{2Wv%o;+($!h`pjDXewOy>)bn1<>5B}hj7hinp|9p0-)b!ZWRislNsL95FAGnlO zFlpZW51#tPi$DFhJ;O^X%CgAs=&9e!OUI6Y^ZU{L!+CkDeukR;z03-0V+iSv9Xl?T9WE^; z@C7Kkr>#t{? z-m!nfhM~?rVLDkafLM>laOm8SG8I@X5(rPkzFX(Sfr+`^|6e z{`O_(dim42){Nf9@`3)I4wBY;iHm8>fX!Rgx#(>iU`2n%vmHr2!>zqN5vNY|dI2xP z!yERf^v+$e^-|@9=_iVY2L?`@Sc9Iz>U_jSOmfiSn+oDDa`2_o30x zY+BsZR9^0%QdtD1pZGI_hJQ~Og{i zgrre09d;$pn$*3URoO^-`n?K)F)iKHbP3PK>cUx?19N7;Wi@zRg1Y_Ks8XY7#C3yb zk+~pRn=>cCcFmP3vU^Pn*JgjU8I8N$G1ZLiQjamDcf9Tn6*b+GTTCr?YPy4QTVbSb z$c`z-dMvWLSbVzCI$am9k3%oU%{iaHy}x>M)vSZ0u96SZMe1WP{Tc&wARR#0k6F#l zW{!hg`ng=_)-*q7&apWrp*vJ(W2x<<&C}8!l9c|?h`HTGJc6EcI&r^1=_X=kKTn-f zT-sPC7>bCd46;$*b~SegcRE#_OqgreFYwfKN9N!D)z5zQTh;t@ zUKhc+*DQwxHV4y9KbL|IY4gJz6TT+;u^Vs3mJHT42c&x|#O$L@oi4tN#^+*mE)S1; zU_4iN<(*|WWdU@e<^^_PU{GbWV8$G9P+ z?eVuYU&c^!vW`?nqR8=*;H~c>)IGBk^HO?x_Ks#oej=!!-*ITi`QtU`Yj@`27Rki3 zvm8dJEK&?VKswIylhd$=FdnpIV{JOJJmKq%)a>khKBkW^!J*DNSzbI$$J;!irLOBx zC%NZ!e0w?-hW=~x@yw0Y8az6~Sbp-sS;~Lu%f>E42jY-U01$!hK)tQMS*Ae|?#E6Lr=pyy7Gn+i>*>3kgDddQdb zBE4MVxlI*js3s<7s*#}*#hrW(mI|VQTTwdlG04h~*EGtL1%9|!T(2F_V0^{7sM+Ir zkejpJ0=K%u)&RxKu&JI!j66D66M5csB;+h%$2taWqrIv}0Fs-lMyM=39}*XyGtr{0 z5NYdP)@UU=oHb>E=$ivt0OQ-K0S#%j9c$M*T#-6YXR}OYQrGTus5IkyIuFw%#_L&i z9C{iWkM#Z9keGforF)SsK9>C)ro*(Rse3o0WcsQt#NJ{!JrbEcB?Y{S@=GK*2BS^T)-}|`3@s|= zCU8)g{@oY*I}p=16cpT`w3nsR=f!4iCF!L|04Hk)YAHvo0GWzZ)N~(+j|8V1rkk`5 zrJL`CH6Jj_6nO84)1P2`s8iE1)Ra=ZDQ)}l^I&>{QeJrGg#YuY7k}~82YYsfSC*Bn z!9#*4z0#G5$4H--mv`S7Q>gHpa`OW9kHk1!N|7*Ek4(%-;F2Mgjl$1mbPu>~^jfOQ0 zCecFpY4Y#sDer0QZS5E+NE{wQMMp-bUAp{Gx)m7((trOk2fSs=CV0ECqo=ngv9Wj4 z;Io_3(k@-T_2knR_H-=m{poLh^P6vd;<8>oJ2#vG%MWlw1>*F9Ycy?bJT-trr>6&- z`l(IN4sPmg9d2w0yLifTybKS|Tn(i^yJx0zst@-7l#7Q4!uAulSZ0`B#JL$hV(QV- zmkUp6LyVTodS&^Bc`H%V51^(;QvEYLEVZm=5vlg2jmgOs0l3pAJ$k(PG>*x# z;!t$~*pPE6#YvIN>M3ee5Xcx!eCsFP!Y%aHpAYQMN(oLPPo@Iv{1Io!)jF{`4`J&R<(oZbj+q`Oy$kbEkul@=qI1j!tZi z77f!uPY_*ns!&Go^mgbRzEVL)64R}qr-O9oOqZ1IHQ|$o>JroKB3OppRi4x!TsQK& zK;16$MHDYi2czwlc_V5}$fIa(n!4foRZbUCxUV_VcX)oqvyB0Kj?f%0nwU%7^mJ!< z;m{?Y^U_DI+6t9jV!8}6qIDy657Woqj2V&ZDBXd&S9;Xcbo)Q(Q`4_e(MzGa2;CW3 zq?x0d>!OKF=%$`aNoR$IjiRAzwc~To5d)$drMtD36ypM8WPP!eM@{i8%OVV@)2L)a z1NA&nJ!W0?LdNHD{{2P`E9F0yq4~ASSSL>Xt6%vhs|?*0tS(|_gRfi0Qx9<1LF3D;*%O-a$|ElZ{zNhfIf10 zc;dt2b8E_&1k%;sd1vy?2WQU)(|ONStW^dVINitNV{SRKVR1ON>W^&q<(Xb)?3_?y zn4a6xzHsAa&WcQ}>sv@&q5#D}I=?VZYF@aLQKNlzSj7A4C~efj@YBgKI=+;ay6rX1^7-UGsV0x`UWmFul-bF*FzcuSRr7aDVrB zZ70vP@Fc55>hLE!ZW%8zeLdOfb@?16l}L}*bk&~EK6d)0&Yh&A=f@NGsQO4Pbqk^N zm~6TReSIIc=bnb?v$r04$wM4ZM#t?UR2P(k*AClFSoa89Gz)@NQ`cLh96-@u-v(HNKj4Itn@urs$8@8n- z-mo-b60VnypTGF&i%(tGF;p3Tplr>W$flI;HEXi;%t5H>O-)T{7(zb#6Im}G4fm|t zcWOszPC;VD{gba<@auoCK}~;S%Yi5NhVM!pOidXA0g++D$}n_f5$ETB=<9a!Bq{hgPcClcmcZKGyvug^k2MA=9!F);fB&p4%3H+JN76nFkv9k!}MXuds*J_ z;sg7!QsZ-xnvQFyxQJ6U#nin@jmSx$lLpytDBnOCQ!u^0sVOTM$4e!Y{-C1#tAYs= zRR(-8qoU`YmurKLK5#3>?m2lXYjAN$HP?|t`KS!N?lvr?)k7EqP8 zFWIlKsx&-jQrY?D*SpSd4=*d`7e%L1Xrca*^~)BM!;&+P6qx;g{`mKwe*D(O-TN_+ z5o1~z9=Z|?|ErBNMATdgODpYt;>hKfpIDNVS{ce2g{)$1QBe#arQT_AaZnNGzWf9H z=51ISn1o@TU&4ljrK_Eu?jv%S^y0ojZeG@O$LT@A{uKKiuybMz3HKW@y`ZK`PnXp~ zTDn+W=5(4(3@tV1a9z_!Z1!s&r30i~l=A|&-|{$Ow6yfQZ>E9iH$4En`?Pd?FQy>2?7C@0P4{SAa4s4bn=|polNzau=e1TsI8J1{YR({g3~4)L*F9G@pPW8I z==MZR^n5(XC96N6F`*`%gW#aIgmqr8buV;cK%A}x*7APXJZmJYv&j3Q5=W{*IvVm~ zZ|KOos<+i?=~B|aX@(bPd9ja0|M$E<+l&Ie+zF6leG#qeVxl@^&Kfz_1?@)cKsqRo zoGxrP8Qo~z6m{jjcvAd`xbCUw&^g8zv#x6mo8@P2Bp=&Ied9)0o%omBI+N55UUTJt z`3I}|_m!_u&rP^~*@YI{J_mO--{p0{OE+e{Pw+<-~0ae zfA!vbKYRJTU-9YO&4~qVTYW4a5j=n6vFP;tx@dJhUdztj zi0LJBW9>$)-?+K&NUtr;o>NB!QrH>4426;AP9uu(VEgQ8CA0CetWB$h>odDD*HP`N zudg!~0LQLgJq`28$=R};Pe!e7+1dP(OyrqIHg6`UaVO(JTiSCoFV`KU5K+m&83(~- z;F=&tiWK#s%hw*tr+C)MK4R7d^lA)xn9vRu-qC&s7@m*irR#V$V_lCQ>gqiG((`qv zyLj^GS>xGsHZ{KT55=6R&W<^=voF0bJ+rH}t8@4E+7V1QCpvZ)qjV*=NVx{0VQ2YO zgq{Lu_|s!(5F0#q8ayw^Z7Ee-kKhWV&yAnDaA7oUZgjME<~SUB)sBSuPHpEg=BBX? zbT6F*)=V~t<+|cBiP?#-U=8aZkk4OPA*7! zP}jUVBDTFqoqKr>?;X~OzR{!?AC~@?m@cSyTKd&+>f6QtTet36_59YpSU3OtTHp4g zhXtdLHs||c-_}Mq`g`WCeu_~{*YHpkU=M-;Qo}+LG=h|~>cVt)=3j^hx2OUl245l; ztA>J`l0pV%EPqQHdl`govKhe~^WxxU8*sarnNUeo9@TSFf8tsr(u; z%n{SCxn}x?oE6l!1mF-{&DkMegQ@w!OT0RyLUZGE&4|#wMuv;c;eSC&C!&#iH}#U^ z^3z}LF--T{w2DN(myXx&*jBjo27)>g=Fi{r^A}(I#m}FeIh3^2 zfsWz+3+Ukk9WxtNHRr#UpSh!{DKAZ~m*+n`j_GA-NY#=Gtl4PFyputLgGpQ(P}Aug zHHFBKf`#S6yYF_s`Nuaeb8c6~MQI+SzxBq&!}uwx!1<)aq)l`Xwrm>g2GitdE%PB-Wk4 zrPFT^sPpZal(Q0+4`&j5*G1nL zU7djLt#YUir^`cASsB82qlxlWI9{$+)6HooL>DT`^0==MN;JP>NkGny*mz`4JJ!|EUa275#}U)Fu#%!KWzpbVtS(F+ z0d4|LkWv2V;=#A-cKCnRhz+$ds9}kS@iXAfeGVW?_`lr#$i;F+|TX zR1{LD*c@{D6cf{#5vGq*WI9Dw?|ny!>C5FyKb9`Pi{7cf)O2FQHDUahh3V^}CzRx7 z*Jj34myFAO@c!!MQqtq+#;=WuXEbN}&Z)<;OPiz9o8x~yHGOktdj9MAuXSxsKdlob z+1baNC#Gj-r!x?_uB5J$Ql{jsPwiu*=VWRT(O~U4Y}s6!eIK7RG3m|OoltfD{mbW~ zr86k>AhwuUJ&P-JQ+T-V&Pd|U? z7$NF0b@7xuZJ$+=n;UX+2WmPeS zdn}!cppD55)}^?kWpfqNYh$q~aLdks^SSXlqoTeg!O6f$Ifas;pdsIo%_2->qA8bpAoVr>1LV#+Jk6sVhkR z?2Dg%@8|y^gUdDZ!SrpVH8mS|Y#S;lSbD<^2{RM-JcXM6#-4$p?#csbu|q}m;aQv` zP~QaUzh`Lg+lJ|He)7sIe>m50>g>fGyUWWrq};FQ^yeQtPi%TkC5a$3CE^4W%b5-x z`lk}U*j9GnCEV!;kc3YiPzlnu13ut7eE8xqTrYjKyx}t&l2&pb5LRK7Q}FZaXeJO5>GQ%_=2Diu!o^z2+i5T+O2q0mqpZIDuwm&dTt z+INrSA6x$ZRGcnu(5UmIfBK7O-q^FNAqNrHKXCp`;?HMxBy|cNL-QV0h^^#YJbkD$isxA!-#6>0zEk?^%>)noGMw2sK@GjKYHB zDDa7)oskV_&y#YtX3=@_E9eCSd1wfb9>`By zaB1moJl|E}l@)Xb<>|8AM-bg8-Q9Xq68$Tyx+@t?QI%E|5mETys^qlN(x^$rFLgDa zKEHh{gCf)`E#{L9L-1dQCk0atkuHCJ>;2z<{O1!V_U~S^H7vC(G|DHXdq6&h+1(nO z@_G(zOIs2$|J2KuU+!&Ok`k#BvcXwJjIE{|Q$-n3r;7v7(}T%n%puZrC@nep)T(50 zdYKzADli}AbWch*Y&UQR)2qTmqXGj18L6!vc7&hz*T7@|>FFlqI-GKxewCc=*b7)Me0CSdj!1vNe*C0$~=IGs93TB3<-4aaY> zsleO$(gpAa>TXf9&@{xZ4PQOn}Slk5hE2#Xc1>TKn39S&F3 zQ6aex(Cya9Q}iiFccVyk5m*P+n;DMCa6>byL+dn4*P~J? zkp2(Cb^I;s&E{hN%D(!QuLA1VBdGH_iB-`kUyU!OLhWz=8#?;GzW3gHpBSd|twB%M zMQXY;yLdvn6Vvsb7;R>0xth|)K>Fji5aEAi1JwC0N>YD#;w=wPd_?7;m6fh5YP#w+ zO`bh>ssNp4GCIAQ|EdA$T)(U;q;saWmsDpS%I9UhgX~|9R+nL*S8lJ}Q!kU)oY3(QDXGg>9$mp}$$tYPsApf|MapP{B zGUblk=CxfLH#eV0C#SUBhjan*>t?r1o-l(fo4WL_{GELa-1-o=dwN|TgG@JKd^zs@ zuJ}CUGmOw-Oh_AHT|n-zTvJ=rN&z*vj?V)_3lt6)%iQ8zEz-hSF9jWLCjV3$#K%vY zB^ll*9DenbboC0UpJ&8CSK-Lu$W)|5!dg{7G58Zd)kt1^e^gA^w*-lRft8u*WeCl$rZ=tg)FUe}|a9R)#b{l$2W4BSDB5|R)3@jpU z?hvMXjBcO~vRllIj?U(EeA+n#FW0;+a)KQD%?&7YSaaoiA?GDE zRdQp929Uzh;&fe+#Q{n1IxEOOHlV1qG9aM4Dq!Yd@?(#!DvS)om>w6kG?5ILI3x8c zP(7s~3~a9;FUFsNb^bU3%2(utcNYZ*1Yo{EAdib(R+I<7;(BT7NrBT9;Hal83J!{k z5~iacQWQ8g*v3XiVaJn@YFD5Z&{PnbRe{> zA~bGsQGE(kO&eMvaHMk7bX0V^GQWit+_d)hJ8IW-mo@;@Gg`NpTHZk<`wjC8Q7U&| z+<_y!r(o$M)bxRlXP=VVe%(;_-pZ=fs=^^&L|#$l5c!J!pZFD@uEZ$_vVIj}#F5vT0zZ z(eRSn((j|}&bFSsp?9nQ_+jUVhjuUXOByVtCMKh5`9S$F$;+F|sf%GNiJqiL#*y9nap?QBb~=(-Kh~ z1v0(7JzPF8fAxVAf8M?qO8-ph>*wl=ak1p(EnAkw%MS~R#CYC=upLws=`St4Y$#8$ zk%TywgTq*pnubz#gXh}{iz2&gp!6Nb(<&ACPYaHlH!qMr30;$r2*5NdA&^U1>Go2= zD&}-{%dU&*erjrBx~)GUWUFD}B|qB2HhZ}GOib@48887rTx%nEQQK8DS&nDr2yZU;L3j?f#H&P=}Z=}(?$ z?1?O{Z8am zV5gOF`k^c|mXb+<5dpj_5m$KAy-}o~x=2xSx{2pZoR$ty+PrDN#^^x#Hy~DFI&(1k zHyBv@bzc%Agzix~ZV;n%CL(iDx%k{=ZGi0VBIm+r^XS}g85ozEj@d;C>bfzfi=Y~q z_Sjkg?kFAh2D6FMTXVeqKxkji`xoqHD< zVif(NRXU#_N|!IjwlrUml3s-8-i^J9BNN^_z1_U;U)9B7x*IBR6{e$(Bc3DS%HLv$ zo)4-^H%C#Ibk2P;#DL~*@Tkq0A00j)tE!9Lxyqx?&_^Gu8>(x=y{}f2z{cuO0EI^V+`o@bzDVir;yFyvw^` z^}Fx>?XUjzzrFYBd;jgHFTeM*_x_dC7d`_syWD;IEtc29XDmQ>KNjpV`Yn;yMdxL# zadO6;pYi$6zhR8dS965Zt*@y5B0a_j)MHc@<0JGhCyLL3^#`avI{BT0cwTg}z%}K{ zU%~0X`xiC6XJ66~(nXom!1UU8^V3ThLW;~itt5VG{%uF%`FE2VN zA2~d(pE~+IzwTqKr=05;(g{;nSYzMX+twnc&uW33+XcL{uuUys%)_+}Ip)I{j5r_mm2?sZpWn6pxafceg8TSejLuG-M2<=> zH;kKldb@DigZCMLxND&JY)D)W#x8?tTy!qC%UoP2v!~6CR(OgN%SGEX?L_u>A-X+- zbqh?aXN5Z+VZG2<6Pp`1VfNH@%NN~wMtE@4~7LRL4DGTCymh7S2h`DKyxK_J?r@CA2bUlFQ&{hj3 zL}R~aTr4zikJh&K>{Hwuta2M)5cOiR!icKuEseoY-Q|hTp1S?lnASlvTlh%*uWkG{ z+~-5{s}AVuM~-0n)uiq{Ud5K|>@#lx|2f?#Qg$+Cw^#4-uP$HxIPV<>(}5N9mQda( zHLNWm!7nPbA{;+D&J~;nzKg8Eh=xQmX6@dc6;QdmxFPk_WBXQ-^AedyPUC#PkePm5 zl9H(YsaDZIA@cAFV1nvJ^@~wH7YA4R2P0e}&KCzSj$2k)PholF^t@m!3)oZ`ELhA_ z1_wui>3Lu}D*x6Ze@wl5$uX(go0szj{P^APe$wAKzre)w8&u(_ASwl0{4y{dXM{$O zG7gs9c69mhB@H7g`pAsW_0oEsY8na9`9VcL%x&ujV0!;kpT79>!466%O`pH%)V6KA zYj*5g)kr~4Ix)KjI<7-af2x014{CTtLqkdr!fttNBrF@!6c7+wU;oh`&ZrLQg>&Nc zZ9`!Cw)*mdj#CfupR2tu|FzfN$4Qd0q$#gy8IBoVp}><6lB!g+PzdV4fk#)CZQpU~ zVwp>16j%|`fwA}igGkR*e?;Zcrlg@Jx(DF%%tR^}C3IjiXVmRuYx7U%zg}BkKD@27 zE~fMO=a1LNH5}MyBCx7Pk7XXICfYh2C{nTU0`i#k%lD#;)Ym zt?|l{zI|?(+Dn5;O~ZNhxPSmk@>A%=5vIadGK_a96rgA0Kb$+4n74XmLQYdpcN%nF zdps?rs50$1gMN2+XZhnz=i7(ioCuBvRfL655FjB?z0kH$94`mLQ>z%xEF@PCKyo@a zY6jovTdbRrKfPcT)uQ6DGBi$OFm<( z$ttB7X;2memID|`LN(Gj)^JXt0pCmVs#6xsSXOqxzA=yPN5&r&(w&xm7ri}_UyReY zmIbT~B#k{V@Gq(9(3D5%Hipz_U5HNepxw#4<)VPWND4sH~!-CYX=0zyQo}x!GZ~R;G0$YfXKe?z5|y zZ$+M!zt~3n?(9WEy&=Ck1&03)(eFi1XFGH12*cH>kd|%}gK>FZMCTefDt`-C?v$v` zENkszwT*l_y1kdaw^Q$`gLI>GQ`3E>7yc8t|8w4-ZL_l&sLP}-W_P@90=h(WcwK8` zb)li8o9pG6RCDKiaccS%a=P6KWRk<^W*H0V@w#rYy^yAkzZp%PMy5JJjY#U*xL-0= zH-`Wa4_s9nwXbBtg7y5@`O13lU!6vdDvnW|5MJE%60iBRykL3-cHWFJ>Q=^*e)2Q4 z^qW9&@ZAUI#^-J_7SG+hJ_{=z%9n`mo^d*mP9yzNw~uof<4*ShyZVb>=%~I35!j|a!AJWLt*`zU!Zzr|A`q1(eGFTz zTa+6=ds@qamgos}Yc+P%IskPgzpkTNRLn6V6>|mdsvtT|3}3Q*V_I!p%Y>F03=JJW z?qN*Rbe!6SF&-CJDoO`mis2O$KZboKpQL7xL(@B^xYns&ZctBkhkic{^a0}CC<4T{) zU{Bo_%?MKN$I${LOJtUs4k$ZJ*B*V%;lG4@_hd%ZdVnC^+$7^BOk22U(S1kmzyJOt zcdonhh~|z!>^Rk}t($Wn^p0sAQpffpScb;stx+$*)Ok@lZI%d}W73XgQd!uD|DquG-dz=>`}VC$4#%BBVRrvGzkv|H0Y73R29VSZ)HNa2G19-XYVYFm73Iq?V;2Pg z>1ClLo5x0WD@uLC^y!H`DUoqFK#X{hl9P zIyJBqPs&ntmm&2iQXVNVgfqga>GE_$DjTGtg0e;;ak02J;})4x=P1Le>G1g;r>5^g zO&{3uy%&G+<7Yc=n6zQ~{6`}lU#G^)TY*f4^Y#e+A;u_$3;XWX)J9D zHg8fhn&P5XtjHVw=#?{PUO4&5rQx^1^mn_r)$I7FJFg>Q%MWm;ub;AW(fjZJ^sOy} zyP#iQGUpb;w^IKVqC7xp%r=5J9^JYX@5{v+l3&^mD>mJ6I{x%Wv(Kz=KXajXs7Jo? zo}Ro7d3aG~qVY3jsDNMEYx&1ccV-Xe<)ytTIsNpZ%JS4r2M!P>gS(ki6-oZ&&mUd3 zW=&Z*#+vh+-+JF77cCy0fuleC^f#QXc=1Qy;}t%0c1uG;SmFSPuEIkF^ay6o9E8$` z%ku^X2M1d(A*cWBLeu^O}9hTDqI?##Be?!F;{#;>7e~`_4Nh-2pomtzzov65Lopx!91x z!s?t%Ks)Kw2A@4N8Ckx$;c)Z3l47&SeX@z+Bs{(*r3VVH0*!BmD9;eqiF z2xNdqK~nN5ae67gy{mc0TztCD!T31c$>`SGJIwcqv`=t8EOceyO3pCEMT|{)aes2n z_abOCP2CCVo;AZ1bfa~rr9USD-N+PDe?&q$MMgcx3kff>rZZIVb~A-oWctI>(uL~o z>OqymrAI~?>~?du5c5JaRJU7GxRJU|`!>NFoR$nu9L!ZsWNvhBiaHa!wUth3XDU$C zg3-C{X9UtmfSt?`Y%dx`s{L6{g0Z9z!|FnGK-?#$i^<&^p100ZYX|)Qyu#Y154#`$RtG_G2IF# zX@(LwR{zLGlj{GRCA_$p7aK+jrpsl*d#ktgZhZ*M+)fd!U;PR|7oS7vK2X=Uz%}l< zvM~q(PS*fk8>MSpj-ZZ+E*X8~R(AvIeBH)0CHJew785SM_RhUX>1gQ`it=gclzY+z zO!uzfy90REI9=VlMRc#e&G+y1|J&Oc_un7i7jvi?DZ3^9!Hvt~r>))i;O6B(=D79= zcZ{2O$1KJuZrmKdb6W15WT@xv*in0I{jamnZ>;6SNHrB~TMiPv4~diOSlxFLGdX!9 z@wt>IYTlT=x%Noi*AXiN2428gy3u9$hKi-e#LGx&>!zW%OG_W$ zKI`E4hp$Hoo;dDn3m4rnd+xF9W`>fccRt@&l380@N3eQ)bY1?&uIduB^!D}-31p-u zQ#;X_`NuffUqQ?r;X*kH|PMtb6 zK3exKTn?{mcO#e%83W27Is0LEUVlKkx-cDYjE;r9QDX`D+c;XB&WmN=yw_6~-FLsk z^ZP(_IQ_o+*3H2HgRU-AmjUL^`_?U*I(q^XEwUz#Mn-Ws-7wm+9L>mL{RW=Gpqrf= zg$u;(4vGKjcd!e^uWMh-x~XmHJ%B`Zx&pIiELx77&W6?tL9~b1wT1T%8=?!;4b?}0 z+_!k8RzAiJVnFN6B}S)Xp!q6VWg|G4=B8urB}qz`F>C&|SsU^?_6f)C!}M_hxzEtT zUoUz0JW{uD^8YZB@Zvita?=Io>aOVa{{cw{U{h%(nxGN<&DA_LK>DZ-wzZ} z^o4&|2!(>|B4u5bAlKmkUbCjMa!qXPn#%3TQ2M@_iqMqsxLE3tlJXZ4htVa(4^WSb zAV@BiF?UPkX z!t;V0T7}+uAhi+`H&&LQ;4i({FZc^bM;T#PU zPh>#Fh&SDTW&H3;a&?9jq{e*M0Co>rg}gk1df=^^+0{S6$eambRlNxnZEU zzjsq_#z05^Ki~6_Xjxr+_{gA z@3^=N>v-?|ea}7j6$JHPFMR)vE&nmt(}d|7EAuj59`W6&qBPM(*|_#K1_f~dosw3&$+TYs5)!4jY$a7yVZ_xZR<3Bf>%?6v%gyt0Zg}thl`D@PUFKq6(9(x{ z7&5G{TGK!h57oH_tV|5i3_4ohlr$K|cQDA9{*`mX1yMOGmJJOR?yJS>lGYu`K;}x$ zQSfETsw@kLilTy6qSektQ4dgg-GU7{0aSfWt>D|mh3_|>eTV7#0vfM7IyYR`q}V3- z)5&G5N?St7q@<9c(&UPz)906+|4&ZB7N?{X5lpX9(~*o{4lO2T^YDo`-um>@x867* z0AD#NXP$@XqXPQq+{(7CWo^oUfzl1sbCOmiha_$K!6$PrzkI1MDTo83s}e+qCnPR} zXP_*w5*Y)d80B3YIIm!OK@#pP#&ef40KAP84)hW@1!JX-yzh_Q+-00@#uuJ)_twyr zQBkp+3A@ttVt;Qvce)%HW_c6`T&5gFw(Ixi63r)c#LadsHFVG+B^u zH>y=?Iu}RjvZq7qOyyE=76oAw)P)J0P!CjeuBN1Wdb;?`>F7RCm+90_ zKkA1%{xb*^5IR~nxcBZeT$eg;7oJq&yq<{0E$Jd`D8_%_c0IYh64_ZS8eWVpT<3yW zogePkn_g7C=3BEs5!Mb@*Qh^{d@s{uc}|nfVUl=>#Z*25zt0$!I{4I{)RQ zOX-J{MkMv?CyocxL1X(onCOFHurd8P2;CJdg3?(~yZdonbnBMMztq)TZsEoU>H0E4 z<7!N~I%+qqeZ&{zSY6*bchW{*H$L0jG0V&HA~BtMJ`2&(W$5uWy(2a+Kv#Fgz1UH; z-R`8)(U+yBUvtOo>X_V^L)l>Zxab`ZE}RjckM$**fR*v%CQrCy!Hgfy*cty|^VCIi zcP_^&5}n`7S&-(@%D zR1p1;sz})kG40CTi8$X*iXwiOmV@mjEzvPuG0~XdS!f^Mt}3t-Zv5u8Uz;-ixrslV zoj+}P*Rjsd+;no<+b`E{tS028ju4pa{GCSW?J-z#@TRwC9zUK<+)J1Dy8@Z3zrfVy zn9QCw8zvV+^W&N)dPCQ6x(0tDrkh~SgV=1w3^6r?OFUxyRMd2Kxo|mE1~~uV!*s|O zKxP}M>Fh>yPoF@0*1XB-3@*jyZqP1D$5LWyx~O^l@xy&Y3Ojf>LoEJtBfmWI&Rvu2^00=fOC#j^1Kj#oc9h3PaUJXTi?{JH*6NW z+Qr*aUJ)lev%&|~W2xDFWSgkr}t$9(;4?k9ZILYH<;c{&Wn5(k*M5R*a)&>BP%QY^X6@sjypXLtsXRklECyNl{=!ElC`YV zvNZ&-hg5{(gt+VC`=2s~^mngb*U>R)HI#0c&cpK}(KEqx((s7H0MwOSQyfrHrTRu6 zU~};>T~fM?>0ax#*mNx{X@%0au-KZ?U~>5f&#HP-PU$K<6gA}gCAFR+47{V`hCTg= z?N4n<2t7w+d4E57;7?p&n$eF@yr-x4+=V}$Idl25-@Wk3ImBX(BHg~@{Mn0ObjrRv zfB3`ao?E~Ej-9`G?Tx|Kq@)VPMlP;T*_%S|gz842DrrOpVfca49go$NmbD#7h1*r? z-JHf{j~?i3k#Q#Tqox&faw=EkG5T*N880*U2+{{;&Rm6#aQbvDap><}{^RKnJD=a) z-CZ~o7h1Mek>lv%0}T}!rJGLSnr5&l&8uK^GxqZDe)q+D4AEbF>gQ)axNdj=v%Q8! z23J)EH&L=u{&ygKpeNBUfb8+s{!d_AI!QPRy9_HX-n%R$WH1=FQMqmX2Z%m=OT)~e1C51`Xi zmE@OLxNTcEv zYM3I`SNkY^(xiljkfq5NesJIA_b&fnNlNfmPG<#Br#B@fG=vsb!BB72HSp&w7&bKC z@Pe6*$$5kI5WzHzw zDb~j6#>$|X?^fbE(Cqz)t91{OxUC+;=#pl+7@gBga7&)J?(m#P(cHdFPIo)CCvZO*cd5?&5CvK)$F6(Yd0cJNz~&9YTK` zHs_lpNWX=vRCW)@JtLJ#?|eei&sF?LAFoYyDDMF3{2Wv^9=iCk5lqK(&l{pt^lERN z-U&QFOr@)9$&vfowTr$S)5|r;x+T^4wi%V#9{m( zbD@sW$&=A1XUv*0u4G2t{V{#h5Yq9tERWHk)Xel_`7zNYEp@qdv&mjmBYJUMbysd* z9|??oG1-)|?c%2{Cc85pjwcxAA$^J(S(oUY9#NCVMk!GV}vb)8Ti@8|9ukzn%ZN4371FS0w7oOD^D6 z2g5jB2PXVBkT#SSi#s`;L8OT3bLV1f!F(+-c)T zv8*3qrR?etEuX7IM+xB6BhtQ%)0O=Qf~&ItjPvHR#N86o;cp{#ZX~#?Bf*9or4Cx1 z1spM=bYuAiH(n2&yU=wWsx(KrV0dxtgB_@6AxF%_@jgt~Unq~sy}wiT2Mf-$I{@^N zHo7IN9J=dnWA!ncjcot986T?)V$}@Q-R$2zwI}p;Bsj;<;!!yB9;J)T)z(|Z2mS4G zO=|kp&17`FD0?%mzE{icCH_q>)HWZ%bll_tk+^TENKSc}Hot^G4IouvqcF$lM(L)e zFIxi!V|giF)4jWLwlT)(?LEJ)&Hc^s8-sN_Vr_o8BV+O$1{I?MZWDzpyVsB{9otJ)g)g$6;UvMVAEN`4h8CW+_CVPEvZTV zVX|>ZOvn5}w}yg~I1zNIEUkI){HX&~H5W?{Be7$BISi~HXe--MEra`+BWaAUq*~O9 zs5rbXy3h@P(-V{LBV+6IdHf>hsQ-2vOlOQ}VNpm(LqkYp4?*U={b!$f>!+%X>B7;a zql?gg_q!kcNM4s0pL*(zUuI+s^b8LS_cZY}2&<^7st5tmx#}69^ntj*(6+#^j7y*0 zbn>$c-H#r4<`=*D;iorW{)2P9e3W=iK^{@|mAeJ$TN$WYO!D{26)SR9wu#bL-nBAe z^@+RgijwDrildAzUb$xXUJHsL_JwhwJu>N_ruXzDZ7q{^A4-SQ$-69$8%zzZ&s%0f z{3~o-SW~kMPT%y{V><|8>>jez&;Z<1aC&%X&ZOz{u%`QQ$(g=1Cn9R;q@1uSNLzX7 z^a5?1w5jR1Rk#w<&zI+Fce>Wl{Ija6$c`yYONlG5*tTlhswIB&r|1 z#l@ulRz-MZ?4yrf#8C9{8+WZXef$eK-6`kPX$mMSs|aJLz*Zl*FHLADji7=p=Jb~@ zEg4Fp+iAaqxYI+_|E2g?co1f?3hZEnn+7Hp6kL|dzVO=xr(ccf{MGf;bfZRjFCG?>i`9KoW`*p}f#w=E3LMFuE?F2>|N4lQ z4x)3t_jcrEjTuEv_mp%99nXuFJV?JnO&6B=qV~MeqF}N^b;EMW+$N+;?uN8Axw3f- z?gMi}_A#(7I`=`n!9M#CtGnkgEYx1Ld$)Iix~@zlrwh&Ty}*i2M|Ui4>bad+uzriE zovVrFCZ>zdS;-1Zd*R(0ZM?H1l@UZR(qV7Ib>Q7#TwZh0xsTcf;LHQzy0sf7x>|!seY0*^L5-@Fg9C=3M(i(h zc$8YYZ0vIs)mQ>~O+;7s{geC3`YDivWNR~;aF&9IbCnB4Q%6dt-EET*@mx&q+87y~ z0RocIrKCGKT~jgo=bP`*?iMl!(e;HgLf6EO<6e`}51#zaLW6YqTWBAu$Dtn~I^7Rl znT)lq+sie19c2H~s*tu!Xm43dxMF^F$sJT7jgN1>e{DPkLT5ymjGH{JWe&79aols0 zf0!$sed^A5Dimes-Y}4h&ZXWcP`Ptm-g`suK(tg@#C&n z$MreV_~Ut&80EsW=VE%;dv>4Izr;hx@a2(R-7M%{vLVY-jgZ-m#; z)PeN{+?4Jf-AW?Nfie$n{u~!{Um|_TRNdrk8ujdf5Y} zU$bF@hL95VQjVHVLz$)YD4|8SVySXZm(Pw(`1a()0RBHOJT_0RGDB-zd*ShLL>z@9zs@>C1ZaH(5^%)pW zd-KehKmOs>&%XN^a{9SH{a?uGX{Sz|sw$tKF!;u6(y$Sh+JE@^sZ_#8!eG0i6s#q< z+#^CFLPJvz>^?v-_p;RFn#Ug7M#9XF1E#4TmZ+ZE_Gs$HK0+D4*_YkDcyIlR#gfxQ zFm9Ec^`HD@%hdVvuo=2Zhx{em=UHu^dx?8+shyS)G`-68C~h< zzj#rI{uBND^qI47^k+0A_4G6)kzq(Vq_7~oOR1qVBiu7MLER5CbKAi1g%=LK@cm0^ zj~+OSntt!MpLUpz6J}d!q+q!iP37bt#WvVIbe&F;IZ4pVSDGZ)<()-)zdiU)h?lLbV zc}MN>?P=XqD$@7Ho;9?Bz@MBP5Iryl$BW;*N%M0ssfSdR((eea>LxFp@AP86jaabM zAJo;GXl6uD*L*P-{~)uy6sDC1&-W{Y(~~RaPtVzYsQGmEcD&+zib-@VgOe(TiimPQ z@#nXGub3CUL+IsP=3OnP`pj6G70L^-sh(#rzRI>T)OX*J1_Mv2`T0f zl&2XSthky8s*zTZqK+#};Y%2I;t~sPD8Qh;ExBe@O;yCw9NE+D42*HP&|HY_yXfo; zjaZ?w-Mhn!7e_6=T20p!eL(GisY3L)m`WRFIzd%607hNH88b85PP_u{TT4U5~%R+3R-MCp>a1RUG++%aQ zb!Kv*xR>`LNcTd}9g%DQcDEkp?ZrKddm48fu6tm6(-Z3vkRq>!RCGYy$ef;uIDJ$> zH#`@mOJ~=c{$mxJh7OFUSo;-f2e zWPEPs7a7xKP1glg-7d1ZI7MAlZhS6Mm+fVQ(w&ITvaz|{E$TM$oK=p%M?hU8M-k7> z{vttLHITB8psAa_45!2D8BTsD(ShD-E<;4mLK3;lrDq1r>Sd3V{66pCatRz^JRI{$F-Ei)YiT`2SZ47 z^L=xg@2^HXM;<>3_KusqnGu;2F{qE5G2@Qt-1wGUB=uw2WFl_9@7Qv1bD?DNmRYFj znJ;C>R13T_$zZQD`}oPtbL!C1*@i|&I`NA$;*TH7?IX~I@ufs_a@M4!{f?IOYATnK z5>s+AdiKHg$%Lerdj?&-GjsXu7DRL*I(3ckypYzO-TCX1zUs`( zYJoZr9>3r#a3a4D*MIf;uS{v5*cX$|w}?FTzC*{;G1hc7bKan3@+`}bsq172XF*TbI=$UP9G9Nxv~-E*Tt(<=u(SxBtCPHSqb5vWI2YqNLqw%WTf>)5RilMd7g<|A z6`o$Vh)uK$s2d)Z+-%lwAEw)Lur~r71ckT`o))S>qdLN9svPHy5q5Lu@I;GO912l~U7XSP|AsBcH-{ zoEG3Q8f|I^AbDH@xzo}YTrV+Q?MB3U?$N_MfLF&ryOQ|MjrR@<%*EaI1Bwb)HL>*q zbB|6%scx;OI#_6<241p$gki^!>KDz*ZSprX0rS<(t-AW*-m=tmUo-UPiNJJaRgJRw z=p0)6)w_4ET&S+M!jSxP)4$_|>OCAWz1%RskWDPEV7e+aCaAWNsp+7x)N~?WEcFF% zdgQV-k&#)Im60i&`!7sOzL0$3)TSks00V~L$dIs<$|aRc!YO)*Wu>AbBxmW;c}u5H zFPI;dSPn*0yL1Rbmrx&sF+B?}%i_h6O=#%_)1!j3P}4y=0{4QF7)7caNJmPT9oCqd zp0x&BGiv&$6e4}Kwc~~yDuPbOnSRYR1?5qU8Co@j~xFN5Kspjn7DQ z{`r>H3#+iYfaw_*E&#~=Piz9xk*hP$oO$K#w||G64yHSI`i0~j+ZWGEcy`Mh@`Jw* zr>`%0Ev+b}p&_-xKPeJxFir+~ND*xnWrTT`g@%SzrR{i(qW2H(xL9?VQIiZLZ3{b` zTG3Ye*jfvWIn=#u@iHPV^Ww~!E{I0!9thoc?AYtCcRg93xA$HBMSTAF-pcJ{2{s{* z_h0(yFFyT+{oObu&5WG7))wN zCB~DJ1%mpw&s}(oI#Bb<6H`ysyj0j-G(@4#V1ii~FS|H&D{idNoIoyqRP2J(a|-6o z4^%193d;LbF`U^o&cOKSoG*@M_1*KuzPL3^DbuC=bojosG_oKBi^;0AnKw+@TGN%; zb$s{M;wZ)v6Cs+EGL+O56$+-C=LIp{$a`hZRh5lKhmo$NLqVq&w@x@wKUSu+U{WYf ztE!p3mxxYJZcO4_f;{vpDL`*dgFYD%%i!Z+e}Wk+9j628Nu>;U-nOkY6g}OMxTYSW z`)&=^0d-4QKR~B&Yt)LoM6VKv{xZ<`Qz}U33Z}#9lGB};JO-`3Toy>G$ zIj>7Eokn*>q^@L2!MRquA0LJb<5AIlKO?Jskj|TIy&@UYY4#EL5?Qi4b?4*QFLzgjdXLFiBCf3b_B_p6Q?`L*ofWp zc(^sPxTwwPJR(ZZmZmOQy>qP+)oInxIv zr*-X}gC`eGeOiSet@Nm&clw8RBmLZ61?pU+rE_C*2J+%`^S(g%Uy|u1eO!Ee%pr!5 zR=2cISa^T!{d4N#8Ok{g#kzgg___yYql+$>Fai1+cL$IjpNlvBzAoa^)8na8kD7k+ zBo6MD8M(F8Cn6+0bB^*7VPM4SBeyL&$p!~ObZjao8I>B{o_<{X9n%F@NB8wf)kf29 z&Xu&yQ>x(T!P%5DD(O1i8AH9j&eNG6Vjur?-yLUiyRz5z9VEoD9mflv7tHA`C4J8m z`F@PCrKs{K?5sN2KJI!l8ToVcRR-}bm>9pVuVtE^1=CCJ&h%!UixUVa)c9W7>pIWC z@98D%yX*Y%u0tL~0_e{7B0L|{4AZ4~J75>>!mb{vqoz~62nL^FFl(ePOlK{W{t&-l z*i!&z-Zx>ovAtnBVzV0XtPX%7KRY!{mxQh-rJ3|?HgbCqFg=apMeKUrorEt6(&bP$ zK(~RT%;^?@w`W~Gb%uerhO|ze#v#lA{)PUC>Kp(^D@5mK799sDTMD>=ws2hPyB&w9 z-tLh)ZqP5q{6@-=U5}0~{oI0N%#6-i7&+3_w51I@9p@WDIwFvRrVhi6)E%Xdg<0s; z$L?-B-y_{dUqIGlAMMSL^0EF;nUp?C%p=Qx8PmUDm$u5Ja|3nlL;^o*`dCKyLHx+= zm3xwgZm)m`qp5rE#MQUQDX%rWb^yEJ=Zgv+(MMMnUNjgaZbL_)}HWFx`W6 ze~pl1Sf+nvcS__?V|Qa=@`e5j$;oMrOZ)>Vc!W%z6kGwJFBzihWr{TRoTZcIGlb9F z=hP{U8?e^9EpDjvLSlD9P&ZF#Q)l|3Gw3 zWg$;Z-@`akDs}cIpSy&b{`R?_FoyKU!=%1QPVYUH{L)_Fbj!Xs-un2hxBhz{dU|yB z-r&@VhNOr%4VRVUI3gi}EJ+|eBGf;mqUz#~eKi+h_2kshwg?Ixg>qr!K-jj+?F$}8 zOu+hq-6PO2JyC8HT13Ldhh8Vk`=!10d*8*G-uZm(?xM!RB@7+C@XX6d`L4mrzb_wT=b+1U9{Z#S(d-o3w)(wmiho*H=^1g2+Yl~q9L zZIABXy7F0JdWWI*+w~_-prp&CBQYIAd}~tJU>Ii)wl1r0s&C?3K%p$Y5sC+@IB~ea zKawCy^SrS6xmEifytsSCyc;4?DHK|yG?vtGcsht-4oL82VODb#K*#Jt&I`tLzN!qS zSi+F$6iMm&0y5!Srw5HpG~-y^@w)EOZi9k%S5;P)rd9dP!(y`PRO8GI^D1``{`J!C zm9b5JO-Y;{A%>?Zs_m{nzxDC&5z}=>M)vbqTt8RK>2AEJhJ50F;ukI;G>C&=nX`fI z6NrASSaRV9VETo|q~IXlM8*k(r-Wg8iHJi{50I8l*eSJx8BFRQDc=j6zO9CDYiSt2 z#fKRLKy6op^buiwl+^+CmFVfn?DJay03ZNKL_t)1&c(3=6nX#Ad@#r#Q_SgTxx(~s zJ`6n49GoMfI~|=H5?+Mmx@hnuH{$hM2-(xXQ5aqIM_tH^tRbRwU7g=WkZ!cD;A$Fd z=Ghel^-z=nm-yV8Hv?FU&4uQM=b96)i_0akL+6gyh0``C_1nxYK2SHDciV~5_2aR+ zo`~JKXJB9MIW^S+TWVi!1N`TzUL_=(y+s2?rJF181>e5oaN)V6bWcs^ zJsS(^qn4L%epT)D6nKB(zZ%N>_H8u#X@X5{SWU^yGOlouz5OEKpM zf4URawZxE8GrMRDQM#F4%;h4{TwZM5a$}h8s2x^!Gmgy1Oks5y)m0*1CUsbyA*Dc^ ztm??jGQjZU>2gV^Rw@4lul?o%3VHhqBp&dvC)XUpv3)KUlCxdz@JrlLlcZpUc6U;(v`CcM)UpT7Lqowz7A-j+YLI(i0GbK>>U#Md!ebH~OmPKnHc z(M9Pk?bF7`Z=AEdnT9SvH%ixxF}fI9YWg%)FOpC$&Dp>kvWAEWEnl>D`SOPzA{cSeTIvnW z)#Gg+&J->|9riU47QchUlcimQ(6BR`PNP%7E@5Qp@1kuUf$1I3`|?H0UHYONF1TA{ zaJh5cI)~^+>T`J7wMtK)rl;XLi(*T7=yd=*g^pDe4fZR?#Vt&^9#vclxEWWZ-D5Ws zr#rb_`|%oJ4y9lF&1;>SE=->_!JSQzH^!yE2;d#Ck7BxyMfqa|qVm_ua2(3iimRHf z^we~1?zZ}?PLV72AbfVLYe;Uc7t`Xe*y^t=j57V0jbw1~sp;AqCUvK#i^ zGfMY8xTAD1BD4W^4@rnfNC=r3vhSgT>ld{5eT3_L+2Xu7qFz9B%6`JoGZRv~UVHs@ z0$z?j*;&n>M&f1ZP4#0)|Cx;${TM!n(cgdVwzI$d@lW7%wVyom%o|%cHrn9e;Nd}v zG?ne&zaJ-faro}7IXMY!4M_hqNs4*;4|1{m z=}(1t(HWY!b?a`Gt0EbZ4j7IqU>`BPZ1?`0gl9<{xvRi|`H2(td(S=T)N}@r4h%Jf z(KVwLGbXr5jIN6m^|G?V2U40~^zw4^%e;N=?Nj^CzpL;2o?2B@b- zDkmq0qR`PJ@TB8R&q<^JX%4yLVd1d0;$S#9oKi#&3DJe(Hg#&cpxkT4+-hYOV=$_A zmsV!&F7=-usKQst4Ft#RKJ+@ZNLLm!&Q?jJJxPg)fvY8^|M$0uvw_X$!Q*9BYhthF zblo>;Qd==c92%4qOxGtkJS;poG-n>59>GbB%r<9caiTsFT83}7I-JuJkJKqUlq zN(R%F#jr!4mJY3d3&rl6urvSh^3@?wkagt19i{%;ubY3nS4*Rt+X|fQQltz z{ywY{YRWQ`ehq%2m}0-!9#+wPUnZhX#+k-8zb&|9mG!F}sl>2!3U zUF+;#ZVbS+#%nGD(zi7B)*c4h>8W@nwWJ*U@*iBpCOITsLk@ zt-PY?4fft{$LM=Wj7o2h_o9k-9KjZIMaoBr|Hk?qGA{ zbFHwZMaWwqzP9?ZR(X(ax4H*>XQj=IL3H0Naydrz%=^u#PRJjcdS<6>UxznF50%d* zW?gk3q3Sehk}^d3;qi{palyEmcQm&2Il6x|ke#Xef@GlEw?<22uj(GMOkBDeADDf( ze7;vUV{|g~)!(wq1ALHbj2T5nSI(Xq-s9!z%Z1^&>7w)xF}(=D&6>{9J29R6osMos zb>{T|u$>>ZFG)>*Z07<1mKs2H?RQLBep`O^^5rMvm!Di%7k!Z8p1EnYJE7TjK~Rid}e znBm2=Zo~BWxeFyzi)9^6i?XN1lkc*eBu37+a6wL2th#%+Xx`&phv|AQ;92~vAFy1{ z$1^YoD>E_v2h|nPg6o|Q;yQv|=xn2$Gj8;@+hl+tF5Q(R6|Uo5e`wv>ho(;Bn0T`B zvu2Y>Lw|z(+Ahs`V}=w>oB}RsTox6u8&+2z!ul2P_l$$`$6K?5pRz!O4G1;4(Gp&i z-e^auEqulo!*t2+;JWt?`?Li6_u=8FydPX0r;cG#!&Q;0T?DL}qm9|-bF(8+->SHC&27r>0&A9Q(EnDLQRTPQ;9lDBf060&%tpo=tW?j z@quSfCkX~oeb=s5sp%R2Cu;hOsOdMrP&FjW9 z?rltLWc28!)=gN~JBE@kY{Q#=<`3t7`N?N5yqb|$|IwR&L{2|<;rRBglM)UO?i$?k z##_(4_5KejCwgevOhyCxQ57m8gfL4b;{=9K5h|DtN=i~lMQUMcXll)lQ-z@+VWCkG zfchYUdjoMUPmd=*z3vd0z9O&5j|xYL9m5?W^^VYri@07opMP@iySa6!>Btvve)7pD zxLs&CT_mG_`u^*+X$?KC!@qnLQ~FPy`tjLKOO#ZODP@ovPlr_owfC|IN3>>91UfunfW# zRL=~EjUy_?Ka^x2F#T}b>bA1oWsy?T?{aGTIV$iR9p1ZlnKzy^kKDnqvQQa)!ie&W z^rvW)zfwM->!7d`sT7miKv^fJ+n>9z@4+{AY}d%koG5ZaD=RC?%2F#x<%g?ra3xT3 zG$d35NnvF|@R^-Y?s#x2BPoi&UX#)nqo}jJzHHo#w6S8kR>J8h*I7ZuxVbA!OM~V& zY}?nHmW+rU_)=zP*T3xEnpe=26f)pPo_^p`29W;#_itgqHxi#0P!U|5m9?gLo{q%V zjM5oaOaFt@OCcEBllbb>hbX4B>h!i9yGvJXdP1(3-o})WBqC{oB7-X{>Co|-0uwnc z5YF(?V9p!G7I&AXkj)rKFr!~e8n%~x+e$eJlE6p#s442J4c9fG)UGE)=?>s!P^Vg1 z@yOrX5h!$OI`#`m=_aQ$!Vv}idQVL!AKlnU2!$$cJZftC?F=6!SWiN_F1OyR;1i%$ z7w^hrcnFy5*pC|tM58)Y4UEQs=@tSpepmcSKV05RY%XLH>`9R!^_dz*ISES2`xkYnwox6+Vbels`e~5K! z)8)1nr*qN78s$ih(}8c_h4sv8$*OMJdad*B7q#pDG40AFh!(0vRfp91bDW*s+)VW& zoXc{&P|6fe$F8HArq%H?#xYb2D)=g)dz@;&_POhCd=89&XyEnn;PXT-B6HsxB^bAh zCZkt(w>FgL1%rz|POc*-QQ&nc>)epfDYJ_;gLD-eJve*zNn}#Y!3(F>P31U8nyRZx zN;d@ehLFmWE?M3Ck%DdzZ)dqJ>lhOXqT_lY=6rU1?%KYcef+!a!bd)(9l}32tp%scf+G(uKRKDDlF2Oy=9lNphpP+Zslgf$E;X~LsHrKXGBR;P0hL5!iz1u2KDb7vmq|GhgkeX;6=hWxuX%Dee+;@ZvupQ){E<{u z535+BJamjLWAYdsue)i6i+ZsIGrf@X(u$gn3*_JSblfn1Qf$pj$N&BKzEdF`H{39P zfV>pa(ObFu#i#zGwQ;CEcu8XqbiAZ@*GzKLI|>GRhK6d-oO$IB{ryBTzPc%?{@lA{ zr@#I7xwM+yu{p7W*vm;Q|M>mitY3eob9)o`iHaUU-B$l3^Ls~73Z9Nil7Ewba9Ckm<|;3Jfjz!Boy&o;h-EZ};LnvR-^6NJ(Q!h^TsP(d(~0|Iw4r z_x&1cdgq7fi=KYktS$m{q56BTJ&~-EMHFGZ^y;Mx{f$c+T0?`SDmUd3tzLoUWDp&; z7%d&QKMwOKMl{lgXc$Q9Q8qk9Pm_{JH1B@0GVNu#UOwsFb?QCj^yj|wrpf8Ayq)BN zO;)T?XN&>FDr8#}oMm!4L4b=Bp2hT%VBYj|!zcD1-TUOxdVx2Y>C2X7F_f52LfByr zB#bcf9^Cs)sL8-=*?~4}>6l)Idu{Y7-Jg9IFCHKvC1FxrJ%T;1ew6rBospopW}vdt zi3kb=j;V%~6N(ni+K3?3bnA0UOOI??yv)9A`mT+#xt8oJsGDLX?jlCj?%Q6CB4q|(vYOV*F^zAl}o}RW(IQhg;$1w zj6>tSC4y#mRd8%XET;}O6htOd<|%m}3F=D|+6EQoX-w|%xzGNBo-R<||LCJfi54pJ zVY>Yhu|J^v4OBDRi_GZ)b@BoUd@=9K*Bm2>mcCByQEOUd#YgYG2{qm1bfvst;#S7X zD5sA|>1KO@%_XMmGHQE~D5@|Oqhp%@L*9~x;0X?~UDghua3GK~}L=rm27kn+wojyY3f<}S5onCM=_RiRQ z^*Jrwotco7j@d;gFHB4Kq;&7ky8D-AQ}55VQ`5;MH%z}Q5nUD+=W}7s%r8z!*Bwy# z@@nM^G9!13F?#wUdD6MsvSGMSI@kRu!|unpT%2yKE?&3h0A5SB^%Z7y*QimJR{ANvtp(i}>h`w>YW_?B1 zt$FTi-_Z3Nl)a?`>4bL1HYjmjCYP()y`v5n>Ww-XT}ryl@lZN?YkYis9ae6dQTne% z=(^xz(G)DV3(H368bT`ZTx)Gc)^*J=p!7>p)2B~ezLw#dhbRF=a{2xDS68F^nwXBo zx@E%J?Szsemq$Zd&pr1X_J$j8oVEF}b@I9_TuV$kHAM5fnvdl-&zXa?PMbZgL_FIv z>yG^U`LND7}T480q%oN+wQ3{RXHflen_+QhcDBr9eI=cTYBQyzn~;8RvU&*Y6#w*%-~1}3 zm-X>;7OL>k!C4QmQ8mtaIwPp*&0hx0nF7P zRS(a{s_91Dkm;;x3?bDUV5Su;DzK`=^w|J9Xiga8Ll4cFgGK$Jsl;8H4sRLdM#lQ~ z8m4RfDc@ons|i7C9@X2ewLz!mQ4t~ILelWmMGwtk$Lnyu+8b=yl z3Z_3ahd@SC&GDJbL(dV2ruD3>Hpv{}95k0gE=*_Gs5sp-t00lvi|4Sh^za~cLAY_4 zPL*IMr}LB5{SOT!6_>jz&C^xG`)h%4KPQ5^ePB-OwC_5E{zXsEHUcN-%}FI-qv7~)@5h(K;Mk9(I z(LIi{`12DJqvjV-FzAM*^Ar3+g1C>QY5WF}iRE~}WiN*cmlZEw7Aa0=2YO<;qx42Sk|(r)puP4)4xk{`ak!>{2NH54h>D1ml(G=ZrKVvFHgR-efvw>pIoDooBq&G zL+UQa=?3B&IqF7_j*KDg|DaXgbmv>&wM5?Z)LmO7mp^m1zp=HoHF?`(wI7|@1f?$} zoH}u7Q|po?|Mt|UFFy4_Ya@DcVZ-pi%*2@uGs!N8mKj~yqavhl5BI-{n%*B4R(bA~ zKZ?`Sl55tim^au^Utfuw{xQQy+xu#V;usNFp&0BX)PaZ7DgF-BhWJM|#gXJeCS^rc zaup=+=SOCqKz$&A%$1J9OLb=!Ea*G5m)fr761O$16N#H##)Q=S-+%4(uIJy4*;#iC zOh5MD-+y1@MNLM>?DEWmr%D@p5_^&wk{XsI*VOE;q==O=+?$5;>WM5LUe@H#iU#PG z(o3WwR%Xeok<%6u$^(`RHKZ^`cuCSgTu=A@{Z*GtPQS40;xnk}H{blUQ`6sUOweN{ z#Zs*bJzSrrzC93gD%s#|ZBg?RM%45_J^AR-qfb6bY`W|+=jzLfICnxYVuew97$YJg zi;^O_$n+ArwY;3cro3h|z2Hqx+f;hs!2YdmDMoX1j4l=3K%I%8Ud?W=er9~3IODjRunx}$VQ>OypH&iEWKXBkWQ^6Ev>&TYvP z(`7)BKmD?KT_m7G&}?GhZ8sjg8;l#D8=O~53?I4Qt+Mi?7)3N*)N_7->Y0$7%V}h6 z>1H(bwbhGq7v|~-^n)OozHm064l-WL|0wtG@!It_f&`KzCFS9H&~RF7?yKm1A${cT zZlC+cbB{bSk)EGqbE9;J>RyzKnb0jLosvoqd(AK%4nb43QHJsH6u37~ulu!Qbswo) z$3#HxUYyD2qH_7uxlp3iUbIdmFkJRaOM02TGj|-rI-f^P9~b}FX1S;d9G*&(Duu@Ep46^`v7@TyW#$d}7M`q7lcVtB*A|=f`x_;$n%O1|(B&l(d#;Tq(0k zHqObFvd$ZIu%s_OcX_o&AvDLtV_cs-VFsc&4OCySZexBQ7MN(BsAP5@Um2p#4^egq zIFIi;IqM{2J-Mf^uQ{_0M~mDopnd#WGK*p|;clK&Ti}FgDLJTeO9<+d#py(B#1k_) zgOtXD2WO3MUr?4qo-aub2r*N{H(=)x_72&ps+vwbbbtj@r zMR&5g%qUtCrt4cbYX(LcQqR3wM5aqU}9TD|P zPM-ljYerUdN#0W3H*J5jQr+0s`UM#5~o`ej(!n@dUxBs z5{*Gw+r?Ge{-s3&aYNk^-o0YeQBeOvHC=y8T=t^V$boRF=RW7Ttz;9{Srj9?wk>Qb zIv?Hr70)V4A5qiw()6Ny7agd(y7$ChI(O==yJ9cS1!NnurS~1a2BkD0E+CeXo|87r zpRY>ljIqPC!XVBN*-yNf7i=#@{yobghf>OWmVoJLM(H?VhnoBgyA@SeS)n1HK~+@@ zY{N85hO{f(SP>Kul~YcFy5GEl4d~`e=NHV&i3=!7Su<2Q)Z|yLmD4w@hy>CJYGGWT z_98|%aski4^q{c8;G$&#VOwM-Kuy2rvk#zVFn#69KzN-&h4WS{UbFk9e>wiq@#8Pm zQ(e6%D1{N4BUMO8+~_`17r1}WpOLXgGdN((^rGpK)Qq1$_2MsHeD&35p8D~RpZW1K zPn_+~z^J}7$*-Vben`WTjErYqeDNp0?C(t@PaU(mqOuv59A%Mv&Fbyko0V$OgP&gapz5NXPc^MT$S!Is`=?QJ2sfWW7a_GE8@ikWgo^4yB*q+X-<`3Jkz7Mt_CpgVQ-VG1^wPQ4Uq7tuVZ(FT$_e z|DV0TkE`m=@4ewz3N6^kB%lO{0wRnMl^$A|5{p3CjUp5%!$WycL5>abq)`xwLW@M= zFh@q|^o~4qNTU~3CM6dJF#!*AALa$5CkdFCGc}W(SEfmmI&zs*P8#Q2iNpQ={C;br zNi)-)yEDx{^V^%X*IsMwwVx2*>$5)J&o`|UOkWqaw5z>@o?6O!d2pQOQKR_~*A?sk$H6O(;oV}iSq`A~%DrYGq_CZn;c zi{8=G@x2^z{u-FSB@2IG`AcQ6(O?l6DLLKI(hZg4c7Z|-q{F3_(iQTejF+z&IUW0p z5>bFzu{tSwAiB}bjX%Mv>AG(MV7RM`uCk^ZL>Dz{I7q&L<#wrAp=DxiZq3BpvD_^f zH>9qK8D=AAsaTD=U-B7yL-Z6NDjrFt3#OZE1T}+Pk#j5F6JeR+PVKsAu=*(J5 zHy@B)eaBR1C-_(y_OrHAYfIN(bt}BsuS8Sli!#pig*X>+xlz=moEt6OPA#V!F?|C7 zDQ`N)bTPX7hglHas_P4UUOg`$H6(4NZ#S$PP&dSCC3J(@cES`wHA1_5A7=PD{i zQ?IKvk?QFW9vsNtZ5%Jf#ju`U34=Pv6%Vb~e^&etxmQ;OpXtu;Q9bB}bn_AY=5PKU zzm{gG36w78ljAq@u|EaW@1udO0d+f38oR!~-~U|>l60u4U*r27O26;1#gCEA&1H$$ z5w~^t<7lzbFgj{+z2x-F%#W!FH6^gl`__%@EvgKNzS{l&>wo0! z^6;SDh4p=Xshea0d9se=zTJrFjOfC%&(S0=8mWFdf%M@xeXO_&^GS#%U6YGbVMgt*zx8?M6E~g2GqM zoEE0T&%M0|2e7njgpX6EKxAlYdY_WcanQ_=>k=fToPmExn~BGRqU(1Ll82t&mkrDd z)3qO!mWEeH6px#Xn)@F3%5U7AogE#d=A>lJP;NRnKcC{vyCRM;KDW@zc!cj(lkXPu;UX71x~8A4|`5sb+5!gOt8)pSkQKX5N^%oNNzpRiHWZ~wK@ zpDpLdaOj;B$_h*5y1hMTVD(>D)9={AJl?AK%-;DFKX+b#RSa%B;<^6F*l~N#y+mcD zW^40z$*k9$p6qi}z#^YXK%^D3r?WPu$^Y;w`; z#k;cHgR~gf2YHVYQ!pJo!y|*ji87xi5FzNrH!246EU25idiA~>dbo!WFh}8BT<%?W zEnkk4xoTq(rt+c?@sN%Vz@(4_Uw}mNn#n&yDKfSCh zYh%^PK59_Tr}v#0mfx5lm19kmkh+UV!SMwZU2G1WPfXl%TqbopR6=^~o}T2*{|u+U z`~=pPZ*lqSzy8jtiR1nKu?^Jr`6iVoG;DtMxtCvldSY&Lv=&UqOii!VWE?8K4L-iD zBk$0K^u4CpAK(U=@J|al@!s2T`rGeJTy_l)_eWvF?)v+;kkjwoyMF%0fddDUD$6S= z7$wls6ZT@z%u?I*!7MHUtqb5(XF{dwxDmiqa$iW1$XPie;JzlGxac9LfyJBD>oY#%}%jn<^qb zboDvfnEqv;)8Xiy5ilJsJ;2Z|eiei1MIizH{=3d@*%et-_Y<`gozHtGiL9&JyWUR&BH&fUMI&B5`lspR?7;43kG+pe2GHI^5}ykP%{<(!ZxU55nd z=>;Zo(MajkK48?rnNH0xtCf|6J*FUI+tPh}(p>?r#Ieh_9)2HlI{jEZDp1dTyo2fQ zt3xJCJ(Pj)ughnseF%4XV`)2Qu{_nQVD+NplA1(Ny(A%Lbu2-irG&ab=|XbITw$18 zB&+K_(TrT3zXtjf;vW2&(DgUvm$p|3$LVqeTw1|ca=ICo+yC_U|M-s;#rQQ7#7No; zly36UrHiY<5e67J(jSBEtv4OZ3rQ~ys2fB#$ZkO0U_Fo2Rl_j0X51Xj0u6Ix5FK0> zu?wW{1a-;k@U^JjthaNzCnh&^Zf=Y(T{|~>1n}$=Thg<%&RRVN|Fh(D^mMi{?iU@e zSR1+^-0JD@xtq~VFDQ%WT4x4k4Q@H|(J-{h=gjSI{{|s1`YY{>I}Pg27iG;Z7S^Sm zOC!Gn(Z%QP1>8czW>7sU|BITCnn&1$cAZdMlr3yG7wO$vWYC+5xkW|aP(5$dbfzo= z|Lr%dT$88ZB~j~GU;lW=L&{Wl zhC2(*;c^M;2Fsaf*eSR8vh-sJ{C<^An4=<2?&$oEbA+Ui`~Jtw@erE`*Od(|N=GJy zpnyGbdN{K3<8UY>3an?k?JuJAg`u~lVcsZHE2%^54z3$$FaDBBNUJjo>v4h)5~KJ~ z;L!)GDRm62k1xicUPwAhM<34f>`l?p9dP>J-21@a+<)JawY&M?H)X@g=?BlDrAK5| zr>5_QW+B@d%s}Ha(Kt_*?0y*1&kT&lxxX73J(aek5q+t<;nQVGYcZIvbj3Y&GM?*$ zgZfk3+Sp&8RByC#cw1X?G!$Lfn@WQtT=E?_VYI(&Lf7@Qg+MIvFCF?Jdp*0hZV$~+ zVa0pz|BYn_chD4RWiKM|%G15$b#>Jgta7)In3uvO9b~pgnD$2FcewJJsTLfF&I0dpIFqx*hkfzk8KA0$I7ljp_O)d#9k_{?nyDV(x#>w{P8l+r+C2 zM9a*-3fufWw0qH(=07L>7iBNEcmJ8WJJfXHxd7WVG19FWB5`Njo;5*?zo{Hh^AOf+ zYx|g={WA6Pbi^PT-Mnuz(K3GQ$D9V)F^K8O zNjO#ll7JCB0?JwuE?dkPIWRpm-8wWhJq@MLHD9loo}PxG0P_$ZA1QiNwb2+c1l17D zHb0Hi@jmolG5bmI2|+oB(v?WDbh$_`E-Wem?v1%?_40k|@)fCABv9v|!61?ZM&!i= zq8qWVBxAKnKKA!Ar_{tB_*UE$Zh72H zH`_we%@Yoz>*m^VF#X!KV?D{ouKoQ#KYQjoFWVdxX#LD7#lFz^Da@y`Ji-6?TW4N= z`3G0$TKYyyQaTeNJp$TYie)LM|7z4MYWl}-Pal8!Q!ss`s_4Yw8*fWapSXOveYigq z&qh_xkA8IO$1DB@*UHd|6BW}wRPK6LBo(2hqo-&2B>8as!np`hU0%)h+U=Ma5~oA5 zXexw_J+|LBAvCn<;0&=^yIr(63JJ;b?Fycx!c*-?eSH%j{^Wfcy@BcRn?AVm!@u~S z|MSO$K(^d0DJKp6NTZ*3Ren`bBld4d*u#G+fpY;qX%tbSUpHVaq8tI6I#N1=YF>q| z@F{N#+tvlGi`O;9q?8-k-I&lhH-nn~(XGulId*#ScmBWgHtOZw*_eIn!q9oiT)`>= zb7Nd$pFZVhr_OHKvhBod$d+e9%bcpw){}?-akwnYRE1ujttf4;I#ES8&naJj4j1^9 zFrNcP?d>(?+xEq6zI=IlHp`^M{N&x)*^x>A#%@vtdyYCaWyeoEBaF-Rz zsS~XtpR>TbGOvV?p@8Ia&loR%c)g-h=YF7b4kv}`l6=>=9-XCYoB z;@ACR{A-%WE{`R|WOTKh%O*U%J1Z_Oa@(#RD4otmoHh`r!^u9zVFRmk@Wnxcr}+%^ zId1C;;A>EItanHP<{pk20;=?JFC{^yprkpmY3!Rel5r#2qF3s`H!}zj&yDNd?6=FV1O}C?NL*~#qpl)q24yUuo z`D0(x(cq*J)YW~|4d|BA1wy|qO2?S~wLkiUul=#n)c@1((*TGe zEgdP{*wn@9i0P)g(H%vk;JQS0M@=^&jcjk+CQKDn{#h4_0d&jLR^K*yxMXqT95*yA zE*H5wST07_a*@0inX8#uSjuw<)9)B8F>1OasnZdMi-Yl^bQ8g@p54`%@n9dM&dZ@Y6R1Xd$a)fB`2Udq7V(8jR5!}GCI-^Y z)K1X4SomuTOZXKva=8R^4Q|cVJ%P+0d*HGAA#@7mxPjA=28qE~jCBGk6sbQhP#=HX z0d;Uw#Chl7$U{dUTyK*)Z&_FA=n~i?q^3LH(|_XFwm*4*gq?V*5yLY#WmDyw-X?S|>=>^bs2-mQ3a2k9kWOpN z=+i+fH&h3O7lP<222Q1kC=T#VwW$%|h|!?;KZw(5IJ#_A?ZM2#aa45r7^R*&N5|0d z@!IVA4rRWW_(hR=U}o<)`=F9EJados$7WdBv+H)#hY3qMV)`;%?tB}mF4xXIak|NH zQBA4Yld>dr6d>1&*^_pLX@(CA%l&`wulK)ry8oziR!&=yfARcw!E$8gyMF#AKjV@A z_QknT2-iORXYb(^7MHUKOea`T)^ZQS=&nN5a^7iVtSiPE;4UD$A~}GvQaYVSc`YLH1-%cO3r3eR`Vu9i_>-ct zeEGV9p&{^^jK%`(0D=n9J`<7}lJcjg%aa?*^IJV8r?$LhOfRo|dW|H;yNsy-Yr8Og zs3N551Q}=eL#gg}G~+CyeLCfc$ZiUXC65`$IjA4cDGI ze(2hvXP^C!K%H3e=U%<1|CxRw{XEku%l(7zIfU5$S69bITWU%+cSc3>zDsJFYide3 z)Y(c@`kQY6sz6o04mNe(dgW6v{lGBwk=S0|eP?3g$-~3_i$>@jbotbePrdPH_df8Z zLe_*g}#}9ve;lD=w(+~gR$A9rp9|GyVzB-Vps=}88 zF%O?8D)9Elkv`HI(uf>=q}1PIa%AKzv6lr9b$$p8KQ)zr!NprGcL2vogXuC`t3H&2 ztZm(;2_s|kZ~mv3Ui!hIL*GG7fAKG!NXECXd#&3S=E-jX77=e66Zv~1&$kxkQ$)H& zn0})5nO*&}#`W^<^;xXx2g)WV4X4jyHLu|7^T2tN-^$Sfh|NhES91$pS=+ZRjotj# zlP*m3#>&oPM<)Fm+u`&8pDZs@*@1KzJ$9GhRB}>MD~&-zNP*YkVtWb4id>TeeAi`o zmy6i>-In=W!^c{?_(fMcFY&v60rjsyQ!@&%yJ+xh?5i{*Y%duZl}{!nZr_iItEV>g zO8TY7+%m7IZ9PAgG5xKJ^jzhWirq!WP<@vY?fGZKIR;8zwT6i(T?sboBtY|`5m-Gf z5=dXVFLzy7sVk4;vAI{DdicSygarPnrFlkjC>I)vI~`1qLe;0eZ$$vROslABEDdO9 zfxl;Pa7IpUPB6)g&54Q4dF2@~v0YS&4jV1qFuI%85z-B(OJsNcUI2w|*PuQ6hZdnD z%Rd%>jO#^!X$4~dRr6mpU5@A>N%5!wbSdgz`TXxMRnpz2 z7bsnoq}-K1U1g-UmK0FeaI(}jbH^~$ZB|R?c2;3wF_5lBvb$&_E#Sg^-Rd4!6m+e3 z0$#-Eb`J*6&9msq^ZH3;dOHdJpQ z@ddnQU^-DjXMJ&fprO%vg|9FK=`zB|_hRXMw;Rn_TMU?k?DJ-o-H};qK%I%WT(qi) z6!9!iZLpnJvnF-m!MeJgNb3jdYHRBb?%0E%UW`*c9#qHBtz31C@|mFeUTIeh>09Vw z)N+Z@%}Hn${T>ThA%^FNOh-%V_BWNyZV&q~^E=GMJ?;lz6cBy?{d<3JuUew7M`~Uo z{{)!2>hVGp^~WhEwI+2mb^5F_q^|2NIaiUo4n>UPMG5Mf6Rtz)Us}@3;=hc}BsU$7 z?&vK(`XEv|mKQl+!aJ7q-gob&a}m+?@!^kC^a!p!@HflW7C%)S9$sG#!@zCJGHSuzg0NxsZBG1e2W^Cy7 zxGiCC1uzn4UY{OO52FL$Tu(#T7}E=BZAw!ljO*D4>2|6ozPC4`EgmK|`y%EAotzx? z(b2(qsqWC^;=R#Fo2%IplM?BYGhjOE{R+M`Kz&6tC90`(JVMAHug~PfK>ER!7KfZ1 z&x;YqEvri=2fz8jgrXZWMCn=rej>eB)7^*wa|ZE@U^<(K zgAJvF>&Am3bsKCplnx9F)0Y6fBqwUU{3)Ve`Uo|bib^1v0+%XutNJQW)^Rt;6;4>gY-ZEnuXE6GdqfbdQ0m&O8Uh|}+-By|)h zbUUrRBA}o^eUrRBf&Qcv!UoBbTNIPC6fVc4zAi?|FN<=}X7{bzSOHxFh(1Z65y5mg zLCVXyrleFPCHW`#5i1=R8v2Y}FDfDJM3~P38vB>7CP^l@EUA6y#K~@i*^^|3W19eq zQW(cNH!sNPBJ~AC7n*Oz^K#90B6VA1K=osr??F62e(l=d{$B>uU;eBAa)u3+_2SDx zLqf{f1m^UYpWeK=r|0J7u};6zo}R-kqs`4jBXJ3NWAD8EfB)aFotV5uf1`vNRfT%uaBc07pI6%Ux<@K0HH~YHo1J@q z;O+Nref!iK=Pvx$AO7%%G=IBv@^A{y7W(+;WQF4IjaZ)V;ZG>0Pd=Q^@CX@c^>6g! ziP?r?0I?%VIFaX#8LA;w?4f&b_9J&2SUA%3ZDqa8&u#t@g}s0LpEKWnSCycjzB{sS z>8>MbJQbnbMbsGBrz9eCmoUBi#DO>pUUQw6Mzbfohqq1k+al80qO|tz6Roo&zFlWa zhYQruKL5nY(W8%C{qU{IT{-<{T{W)hX^ZJU`3dH9k0R3e8zaMF)#FrSDi%pSIhpfA zp3t!|&E!{5K3blZTvBp#bt}Nr z3$F{G0^g9Q2h##c?O=UnWnOzpa)wvUlZlrT%j5Qi9i|uQhux9Gk;?Xm(m%Yog)qi# z{DN|Vf>Ko#1aO7c3C{_zoQ{}|qa0tEczw5B8>VJz|6^RK=- zH`0(WEghba7h!r7l^$R^#~Qqgu&hXrDirkqZw>(fb-$>L+&TY-hmTIAjca3)#&c^gsqLf~i2de?Za*PsYComVEHZZ-DP1zUJBN|D^xrmW`W@Vz*H?8WBdaBFvw za4zj!S0;AG%o&+o+WDRfYbf7@#LZR4a4zt9bUhvq#K!Sxo53Qkc1OW5BP17wn^|r( zocVdJlfo_+jOKJ<0J6H+Ha}XR=R`7B1#5QpfJAlqU(~5|XKMC^4KlyzwG^{oIn{R) zco!XBc=!6R2+)5ICjb0!PFLSvZ28;#p8lRNUON2m{n}T4)3gw@H(&XRn&j{hmB*<} zZtnx8)1smD-o2nr??a%vK%F5>|2(MIb2woz-GI6%odK2`ST}df1aSY-l3wmw86Htj z7t+B^SU`$f9z;u@sh^pNFOCl{dSSkWS1hw6)W#u{J>*@D8lhUg{!FI%#2p@ z_(OaEyAKuzjR*0dz_l|lIH`yoE0%CI9u+&d+dEf$N1whu1$2rT4uDrlY23 z9{jMTg)mU(-wLw0^loEfk?X~}Sw!cMs>E{9x$X$l8B+MuVL$dAA0`k(f{^OU|$q%$HDY+ zzo?j)82{msPc&Jb9zK^Q36pW1V{f6Rzx?#I&YmO3E>CoJ2Ky!V zko}Q2GMUpkHu27DAHVtD^~qE6rcbtJofsazp-jf>H8*Q3bM`f!80q}xcfWV)>KlLd z*!nk9PaaUN34L=seJTQ|Ix8I(-{MOByH-7x%D<6FP@&EJs z;h`beenfPBV7NeGhyFT3(@XP1{QRm;6pf4kr~GOZ_>?F6 zckSA8q_HYLOPFqpNUzThcON+$d)&(D*Jrc3+lA=~XD?ptVVo_kI&fq3kq_T`>t=Fn z?9#^e_MV1GH>STcn^e>~l0=8vuHdPu*w`(xQ?Zab0Vfn#`0*Y{{NW^!2gf^7&jTt; zll^iy+yb^a4D_ZGDXT*~Ibq}z5>-KM0Hn-H&nRG=O#(b4y-PuKaXR;9Pxqj85>=a( zv{EYZ%SdkC?y4z?+PAK>whcL*!wuSx{`ki~{_vtXV&DVoqA!s_bUsr<>hyR`<0I7( z&$?~&9VJzs@4$xuPPtfo%nEfxTAERUZ6$I4+^g@;&ozzk&&Q9L$>69-j@6Z9z&g)G6HMnhA#@eC>M?3PZ@e$M^M_zMKcaN0>6+Xz?x1tyM0cBC*u)&| zXrfORceT5SRL1n*lH=uzD1E{7BJErte*4xyy8eT=GZxn&Uu$rYrY`YYlKBSUl6l}6 z8C^VT@=aI)ZZl+gQTU5#LkfF~)U}-1c}?wBTCkg0LA?1f>5alx!{`#!nXlI2fNo`O z;R!Lf45&-#g9i`RJp!vA+=2V$!tPDQnbDcZ{Kb^HN;2HDra?20Q^U#ux6-cv%s|r_z z<9t~Fb?NE#yu$C>Om)lY_Bg}{>W0?E>tc7xO20JIOJMZ5>T2>2H;s2JuHIe;rUUBO z%c1O!dwVa`Ro7P&AQ&DU1Y+I$zzVRi7-|<3FIz^3pbjX#BYRE#>1fhnW)xdag{Lei z#H_C>T!v^(;U{d2>b^JgTy`K2g}mWg8Cod&tagp2(p9f5JvCd#er>uwB3oiQk?P|r zAO)*~Fp(cl&BPazN(&{nVLaZk{_%4g6hO}Y*qWmyp?h2EI0-QvZMbA ziu%j|364Va#XP()Iy$p$Fd{v@8b}AzFQkvwrl;>%P}8mHWx@3Vs*B4-=~h8!Ua&5K z*$^)fiwVWxylm_glZsizwh%uKa*|$<(G|HOU{{MH&QBPWHJmO(i>?A_*-=Elf?8){ zRx!`5Al(i)eQhxwnnz`PXWzu5OFHMmGe|(!9Tas5?8TVjSD42F>c;e95MA25mI~7u zlEQh>Rvp*tlJf-=Ulz2C!w_Du^l)lpS*jPNH!mtT+pk~Di#E&kVwvHkvI`@nGr`KP zN32}=Z^z7EZTau}1eQm6gdi>YdoH4YG=?HJ2GTjjY(9QzWaw2Umx^vGD+!J(4X8jf zhtlc#)6(J!NXo15E^jXhz}VpJ*GSLG_V&ZzSb+rf#zwUDMh|a@hB{FwgcNh1s0yPJzjSPh~FFJc6HG4TpM^iweX>#saLOC4iQ z|CZyOlQ~!f?%Fqe@^J0>E9cLje|_}zzSrAPgpHE(WT(4_TT(|&*KiE#nmu+b z8Hf5a&s;n81HxYH_|9LSdY(R>n`3h(o0^&?b0){0KJ~xoLrNp0vtT+MNRRmjH#Dh3 z>E!W=xw*IB{P?x&q2GMzrB^0qC*!Jy54`j4Yp=aKm)O#BGcG4`IHc*;OaJ}M)vHgP zUf)}N<7Cywf-3IY#@u1IN(YKPKuvE2(|t-C={iJ4=F~2_ z*l+XXluAraoN=fBL~8nxEup#Q-aE6iWfyyrIUq_-?m1kOnAnqC+I@Jm?yajgOZ>Mj z9q#VwzSzBh>B#9LMI-)x1(ANVXob?ZOzolx6r4_e4hJBV!xAG(6HhhAZLg%aQh;B^ z>P0E4mPo1~n9;*q3F=A6>K^5;fGCPIux3#rzzH26I`i^@7)Cb}EHDLJoB$(iF98`D zdD}}|iDXu8J=`})FVf**Y3cv#!<*95btQ07)uH)(mO71r7mR;DX;qB{_T)r{XMj#s z$#a9n`=JbnQ=3*2}BkY?^FJsw^clH8_e>CQ+drs4WWSKmn`BQx9pt;IN={@>8l#tTb2zEtIC!x?Gbz!-zBhJO7zbN?yP*-Of z{4VmsP+n@pbX0UzoNBlq0VV^`hM~0&i{(aWH^j`uE`q%6yd!-ZIv0lv*^TGLY@n?T zup^@zN_X$Y*^xo?+Y_GMJii5eyDfX5$r0h{dau?9kYBn$7umS=8<-ydjfW$s$q28>COPqA#{!lq^buNSMS;JU@eS} zPyJvz(}M?hTma)U1CiBf0t)>|LNp`r^kXD4*qX3AnB0-m_x?IAcK7%_g~Gt;=Kfyy zQgaKNn*|2e0raoz-TM_T&Y;MLu^3>-`O=|aj}?VMk0Zf8K7Je2k|I>Ez3wTQUczUhNmmRn>=+y!tqzQ*wPrk# z;CQK5#y>@<`ssKqE~|o02hE@e7X~dU+*!Ofy8fx+=pdHJpsg5_)2gMsnfeYh`)qAk^`+Vp}*67*FTq z<6v9rIi;i*j(3c+%e@f;==t!tyfZqf(eXGP{4lNelEFS>Wcc;#_tegt^^XztQa>Xh zeQ_aLd|`2Yb^5{j!cFNP$n-LP;X-Q5rR;MT956EP!9sVTs9QtdGN%;ec~LRxGOXz8 zMC4GqSuRQ!xeMXJbnzR?aQ>uk=!5K^__WhTss z)nQ%{GP6d1H<&KJH@0_mA(fK;XkZ{-rDFay=pPK!&f%7h3=q~a!|Mx^#|DFnOfN>K zH^{HrRbwJI0=-ek%~qII*p$ILFwr$89Y(K9FT%WF-lh@LE!FdK*sXcXPG+RpKZI_E zAf5;ON=^Uwq4)pEqxTUo4lDQ*njRNJyK}YK@$=Ccb#E_EKQ99KNUToAeqD*0=U3oC zRcK`%=hL^7=pE(n73Z&*JGPbyIW4UelT3l1u-%jS0B>?J$bq48i$6P7h&rBN$RCZ| z%PR)AiU2)__A~py^rDcB`4vNSFr7|GO7c$drEw1ex*BzIvuIJM#PsBzx6VN6bRk{0 zFE=M=^EaQqr=PIsee1Rj-$;M&{P}aQAHLLgKK(EXW>N~>h&o|#5M4=&#_{4Nblttj zHX%KB$ZVqp$Bs>b>7Dmnd-lw8&pq*+K>a(kAEO`Z#KiGuz;wLnACFD`;EAt)`tqyfNUizc&p4$J-z}~%Yrn`zZrWwte4+fWpZ%7oKNHJ_+K0#1#^yV`}1J0uq zATf^u)k*No#PMZCO|Rkqm-&+iM*Buf+eiCa+P$M%l@y&b)v1&>3n-|G2Q)Ml!zk&g{~qsOd?51yu(OrejbqE$|?Gr|SqY zBP6k8_`{Ad=(F0I%hq zi7nI-P*a)|06|A(!Q{RkVM#3k=+a?=ba>d)E7H?5%+uCM@Ii4DVJ0zNn(Zw}@|D4{t7DHKsDtL@s9Q+qmKLy< z)_<0oZbV&(kt7Ybm=0B1!2Ips`l?vdpeQ2oSO0_#j}p-_r3=!3=WCATMV^=2TKa7n z-9Y-Eh`J@B+uRq;8Z{kMXI7vtLN};xCJski7{3Fm?JPSpT+V7|3y06mePeqOjY~f-VREEjm2Mx+X0G>W-J zaf91}Z&2SXp4S}>g)$1q=M93JS+m?Mvda|p!d+u~fmscw3(g%aT|&BkKzDO11s_RW zC8gOr56b!?0}Sq$HZ?!W48)}_4-85o`k^_!Pb2hI9ld)^O{ocMv}(GIUT|PsCUrb6 z#_PiTufyd00P!R{-oCJrmD44z@8$YyaJqivd)d4GUKJxk9uKX22wDYBL0haq45&4p zi=lM$UIgoy?=^3@UGMKsRh>0E|4;r4{>5#(Vo7udnBIn(-dlh4!D6US>IcDFdJc<9jf6Gl>RvR=ZNWWJoh1WWc}W~g$L8?4aU>s z2$;WHTXV!f;(O}Oi2B~~L0Mkv$0IJB8@)uCvZJQ!<%`ngNQbx!#pUp~esoYKWH&4> zZCz+<21^(MSt;)Fs|#AeTw*ELVw{1Zfod}XqqPh1uF=N9-X&7e4W3KxHuex>bI}th z+mW3bLe@is+OY4v6p>1(2hlOrY|s}Y&->|Bt4@bgUO*85oL-DyeFI+??_`-g=u*w` zx$s=pnj+%9n*_%D7GqFZyprE$9O)LUS!Qrt@0EkERlHuU*Xz^^<^}1sp_$w51^;@> z+Qz&wGqvm3l^~tZ#GRY|i~9xs)t-LFC$P^arGkpOa-1mWo1p@LMT?^RDYo+u_AmE^ z1$+T@e~d4>@g*{2I?t83{mJbm4gM)9zH$C3IAr~y@5&@*@CHCJDnRw&mb>LiDYR}$ z0=ntn!^8dIQQR*wzxW1c#6jw?`fBCAv~& z8Di7FerjrIOx$GCssHlP^OMHfK0JK*y(@#~-+ST4>*w3j4MZWnH@-Shm_TW`Pl=4 z=H!ozjD7Sq-09!MuK&a*zyFu<)|~#@YqRTiZQE9rEDvAJclPO##M;cdHOr*@5)D$;jmJD)jp^J0_h`drJ=x#m1F8V`S1b2Be*cD88v zA1^Yx1@xba(&bK{_2}9b+cnvb?Hx)d?S*iaE{-h8tP!Ob$<~rY8EINO4MdUCy_WiK zuXTBNmgMDo59L)PZH)?u3QG!z2{?+2D{7r5ewI9M&j6n=?*O9T<#%B)6{UM{mIE7j zB`25yO501?!`8JoAFinxTDNpt&$%C7`S2zuFi1?_!kgDo&8}UgrRByUFDH?zNb|k* zsY*~UE%nS;7wPBYy#bCWb8RSQ)w7(Fhu zm46+?y+lz=%D>exP68z1$uWcP2G5QsYcf_ZUmff3q5zp_#`4&G8FYSfT9Trv+u^v> z|25N#To{rnWqtWAW!^D_qIV1gaP?*vrT-Cjm*4+SU;BM)1d+-tHQkcBdn)*LUzGeJ zQWunSm6%R`x*}hssvA9B6RiZ3?GHD`2jd{M0NYL1%vv#>8H3`MrLA7B4K0|f)e-Bp zn8#|KAFb1V>}KY^yzzQcIbJlF$Et1--4WWsbe%HLJ2m4DXUpwR==SF&G2MN6Kz)rA zC@4rbpbnwSX!IFMze7%U{)$8A#>g!%i&))pyjY3dYUd=opp|Pg@SL%m%s}{j6PmeX zb1rW2TpLM2XUsFzR_1QRypqrzxVIaziJ1}ao1N?4yty+EwrY``YLPT&GmP!U%(0eb z#c(b;d~LX2h*URMf*MmFzQ9YxcUvDX1B|u5a7G{^kOIhi?}eq6|MF{)x5jN9o#y7; zhthTVidnr^TbRiLtqaceWB6R0E=is7fT<-V;KJB(K@;V9VDWfdoG#nTxFlp=l2U0F zZK>9MNosn>;)f8;`>t#n?_C@ZrpL#R&#Vfc2`Y@fke!;D?iz>> zoLT#4YiZoGvSZKg_Ol4eB4FfE!7{UIyuNsMW<+}1AfL$mIBGa>4Fj(X%Fd2A*ga2gBGGsBVCMSA z2h#`nz_^c?t{)=QcVklz??q3CyphB=MW~;6HR`+eL{hr&{XT3j1LAVjbnsn>&a;nm z2r@upByineI!P~^2J6ym+uU79`8M4S77OJ-wE=XdhQ@{A@@iW?=QlvV1yC!4dFKY6 zwVb{T!o{SHF9@+)pU(<|xU3a)i`BtiZESBuyM~6j(Jo)B&b}B5_3Uk0==Ae9MXQnx+-pa2^NPh-Y|Kb~bW*N<{e--MJTpQgOT?TMH7Cp0DIH6W8? z9be>Io}7~8pX3|m72}(d;^XVYcP8#hZRioPO*OD`k0U zIClK_#Hnw+{PL;4{rhWgU8Nz==DBZ9T)ld^v*GgGx3F7+<(D+mA=IhsjmNRm$(N=IImz2B!auckS%g4Q{49Ipg>27A)S z#w%bR%#XNn;>5}J_HLR`Zmbx}ONg1A>_0wx>r-g?`fSmAYMVRO5?`iswy*6)kxeq!mnK2M2Y&h7Rp0QyVmX7H*0M#*Ne8sQd=5psr{WX5(6&|U7x!#cl7%8rgHCXU56_@S^@Ie z1Kr(*(rtR9F#Vm`k!{-`^y8ty_+4=_mP%2-gx6jvb?-?@rWQD(vCfXdS3vU^Fh)W7fNS_WER~8$|JG7 zU^U|86NB%+G?K?K#OSI7@T;sO>*eUH^AFE;j!Y7jz6~r7ZROvDIbc&MDF=2TaZ#Mz zAQ9F0)qFUEML%IrFF1Yq(%jr&q8Uwwx?j%H;L@(1BY2L4=*I2h$m+nl^LOQo^jqsr zha|1(<$jaMXrR*}&)@pf-;$b66(x|%Ad``q-v?f0O_#>(HoaI}2Xu`IM)#P7zwO0< zxFQ)HYG25F0n*vbk}`x09BT-eHSWN3b6<$f&uv0?78oM8wim0pTNrmZT@PhLvoiKEH*oG2(+#IfE#pI%U25C>U-MU<{z6lk4K# zh{^@%2G4)Z-e^aA_fk;$03~yTMX$f_{;xc6-`yRnATKN;u%~go@Hz~qEBPf}MYmGW z#pgtW>xOq^mN<*GjLVmU>31!AsJH&ysMPd_7S|vBHeQLD=$YtMy(^1%Wx!U0*y;V57PpLGIkl;DlMS!?j~WJSa!T%i8$Bwe`hl>r6~RX`#$9y*OD; z*FU-&V#L0#5>vEwA{bLs2hJ(m1+jb;0Np`a%W1@YLKK5~mz^Hp**q}b!KalvnofW0 z%)-pkQN=%k+Zu(%2UF{6c96EX?DR~gf<^}i&(&JXi+Fsdu=j3$de_e%9G3w`%dC_> zLj`n1U21j5UiM;g)9c3xx;dBLm+tODikc3oOF?EBMcv5ff_0;*o0$a}-BLMsEv_5N z280;`YeU?EaX4PgZxm>8IqQt-Y(d@58f{xRtBWQYM!B|*aKM>VMY&Yg^9!g0MY(DS ztX~xb(o+!tWm~rjDz_{*;j7lJl?z@34Srg}Qnjdz>J*~n)gT~Izd9q(Tj{a(oU;GIy z_f5i=;#2Mw1EzUY3)D{Y}A>bc#=CXlhD1HrcS> zl@K?{2BDJ)2?@S&lsD$)5aAJ}dy|mFWK>)Xy*ZKRqY|S0Q+yWTfmSJ=H_eI|YN;57 z)EVWQd)Hm7_m$CUlOoC1I2_iYix3RiGi=Y!8XC$Qe7G%d@C}YVKJoI`pZNOIn~x!D zfAj}fORn{=&RM-}c=+`;DE;K?K>A?%;i5<+d-+$4YOb90+eM@j&keC}zGf;%h3(e3 zuACRVFcQm-nKiJ-vI^zu9-=(#fiB+}nq1YHM5a5<-tp9-sXInEo!I;&C-se)z+|zZ(S8 zXNww+9ZL2g08$x;90p*yc67A8s=cZpGL5guaJmfDASK!7eqoWu zrwv*L7;vR!5tLq{61zw;adpBEJh$@)(nGw3l;+LJ=$chGE*)CtO7dH1_WdA6JRX zl~Q4DM^AUlBO%3{+_l z78d5^iLERnXX)zI!6~l9C#9%UfE(L|^QG&^S<{x(=;?0%i}SbPUt+q|c8y=!;dBQ* zEp)2ikr^UWdUAe4k~(5Km=2}?HbtfjlL+jwR8`v$GJ0iKb+db|8b>ni;eMfPZp3cQl(%lcRw|WL09hd_ItKyp{ z|Atx3PS`-k7dE)f=_(_oqSky$`fNCaarj)z%%|l@=>l`(OXonyk<(>Lmn~hUmoFa9 z7iAbdf;Oav$;IVdG;w=hM7B=(s6gGVrGw@c&=nhKL~|>tL*`aMx1or7tXY6FLGz+< zew@~%hQV2=RU&Y~yqTXjMW)QoSL=a#l)0KY5xTX)YiGqOF3sez*>ox0iATMUKBbI< z2ixe6e!*;L3^1F_J6n^zW;c3vbYaK(y)*?8soyz3a3|o!%IOZBTT}-xN@+FyG zR^HvQA$_zjb<=p^z0pVO_RJ%gM~C;`UB6@Zip9kP4_0%;!TVaZVsFr%-Nn^`)lY%# z@$r8)GxKLNcsDxeB3f4;y%tA1*d9HD)h9ZWU#aYfJ=MtK(d56ZnmPRs=)U1IV0tkr zEQPBm*(8AxvrFHaRk+A;xF|2aR zZxK4flDH7q;c>`TD61Q@OsLB+OPqP`8nAZ=U9ir6gt&%_?e^LUY>e{?28NIIMDQ@P z`i*4Bl%?NH@R(JCWxJ`N^z~BHS-297e1%>l*^%s@qXqLkj+!oKjb0_k7TD4`RMDY{ zc~y#}v9H#_bn}e7EAc(7Zt&gs-!Y`S>rwfzcrP3qd@)k~YUwZj6WHgA4aFNXYm8TD zjBnHarj(|{rkv0Oa6B#{v8f@YVG`DEV1Vgk4Gm2Rlaozj`!|E9+s7u^j;z0wlBR@3 zlMN{&lapE>H`&lIO%Y%NVtkw^I{_6qB`*m}2mA+?_@LEOQJNHmFPPx(q`1{of!-Ap z7fKHw)WT4RUzDzg3emZ8%n-~ya!#I^IP=64Fa6c?_jLAe{;v9wUhD6_YdN)rql4#P zf8q7M^KIt`(=Q=ZlJjDy+d9+T61usycRH_)iQP8~%^gmcOa0ol?_f%Qo>0a-k`T8y zB+LQnq5V0XPok!eQ8GGq^{r=Rig|wX6ey9e7ZN8FI1SK@f(QuZtQAI%a0nNh?K0C zmrhNPoc_sQ{=-uX=JcGU>o#IwZ#>Y7oQ~;*i+4z?PjcxN$>|CR+|@N1cb7G!U!Tq0 z0;Vr=?CI|)?xkj~rIs+t%Bil{t{k#_s4$)#>6|(?;`XrH+u7W0wADN`H5Ck^Z!yl7 zUAvBm({aP68DBWobYtvkRKKl&0?$fUQb`RRsa!3@=nM_H+M_C)lYE*>ypzc5sqxub z(wtOLQwgSfa3(?4eXe$*kQe2Xn^782((bz`Dbbaem>9fe|K=aP@#9Z^e8y1v(xt<2 zcI?vFZGL!!i0t8b2Uj{K9Q6s~1LQOX@_D5^O=&(lm(s|23X`SdhID-Go?SjAiOq9# zI2uTtoQ%WtqCT~YTKU(c(@dOe60nQdqx_Tbr2FAGqZKKX&H)AGrCu4Nmfn?>CKDV?|6KwKvA;-Y zR{5x))e+O(SZ@6UM>#5V_vilp*u^=4R_u9yL|*861RsD?w6pKX?}RTI?>x9*NYjZe$+X1 z;lqK@4XZoc?!GbLZnJarp+f1hyx7~%8D2j3mDn$8xmD5~Sa*9~9A;-J+`Q1j$lNiW z7e`Guvbv>o+Z72UhtlOt=V#vP@;2s0ByZx=9p*MXzJT7A#LZOhbe5ZK=e02l7B&WJ znHQX!-RJ=f1M1w;q*PL@ajHM^h>3q0$lgur3odr(m{bkQUcq!THq;08f*!O$+KYq5 zP3m8{-^|Lj1jJ^e;N$FlexYgVmX zJhNwBPV@Ts=*6_gqY>2pe5>zjig@I2rDfUjmev#)y4`J;x5Nm%NL=iKTp zysAZ-F+OXk)eM8=niu5?s|^`TPIl&G0I>rkw}kH8zs=^Bzs>KFpqn3d$Bf;DmY6Nf zFB~*1PPZyHFz$?nMI1y*X@B5>ui%UU*STXFg=zzd@baAN*ud!M(#sj3I(k2X{7Mr)6=&$zp z#h<`(T;DX2&sdZZ>l>QTv_EAs<#JOfv4i^?Vknw~+Z*DL(VJ4nd`WR`+CP>6rH}0& z+l&EZe?lkWC!L{9+kx|xv8II3No_xwz(Qai1I=V8%6nc@Xs)j-1@lWjgd)^4nO(@Vi^Uc@Zz4hr!uY5Xp*;R76q+wR>^tW#`w-W+j>F~*u zrQO}_Cl5E@XwGX0otip6JMj|k^mk$1;g-Mn@elc%_wkJbS(DEor?;xVD8cApcsbbJ ze(7)@@i;H&V>@^5Jc@cZsxykLpQqYo@@*B+dMQnkvX8=NAb7q%9cmE@!;ALFPly}2 z_0r6r6FzzMMe?{V7ri2`D{smKxGV znkGTjQ^chk1IuhKt*b6>nV!9F8kxR>y``q*k+)iYdh_DhEtG}EZrwV3VtBH1sTrZ_P=+ugr#DUL&1uwp;AipZ0JuNNF!&MSl>1uWjHMaoi zQF+Z3NiLU9NllVRrK`Q9#wW^E6IGHo6yS0dM51-`cpaK>0n&kKj-5&?N{L`EC6f_T z*#66TiI?xWeCmxeXFmDllOG+rXG_1at}ubqGrH(L1gPt`p4@cRlPW+RlR8H}oGC$1 z4-lslLgP@nI33eWWMf*RH!(7ad5Ht>zxvIQ$xvT4HHy-aEaoTi`XY1H499KA>6nqq z1M(wjk>#C6nQM8epH~e3vPia}m}L895>)-WGRVL=l6<6#i!r|#`^&{6PPNtNn9#W^ z+lxg=Fr8u1(~843vjqH@c{q!JW9SMb`7;ewf`zyJX*bGBed{ zFsi;$_VtR*fx_?eah3wMyq`}}J|g2x*XQfbc=?Pi z{qx_5^GDp8(IIMP93fpZ7O@59ux&Mc#SO7@-|#j-#W1k$OyosZ)Vg-$JlNbd+Pc{o zq84-;$`)Tcj4kjsSF?8BuCPnwuF;&`0FLF3?lN`m*j?KDsww5ZQ2k)tBeirrBL5|O z&zcPg*Gf`1iaKeIIMvr!R*#VXWwGgi6hG_Donf(}&wBN<;vfC*aJJ8&=) z866AEQ}r{^YYFPa>JyQwZ)a$zj-pZ89L>a^Ub*bFOx-iedJN3QS2;+)N<{i@ByTy% zHU0rLeMRr?^gR%IbwoW$kkt_bG&+6!@l?89^zS`Tz4&YqbY;8=4#d~ z;I~!PKZo(+c|*j8@a;q$i1_6*fXtjT-20KUMSZvw^$(|W;YQK_I<6GK-!C~`50|E{ zI2X~ggmPXXZ|H7*k&O_KG!Mgba3ar(FkN1Dy$!t&^P+f4cB#GU#vHk_&y_re&kA!q z122vKv4H6!cOLx3NcpR!zxYpJc`zlN6=ThE~QZ5nQmzq|TcVD{tU{Uw? z#f&p$vR*!Y`r7fopLpe!S3V`{C1>B#ZKU==tavzxKB+A!Elo~ta5!C(xx?lQw}SFc zlk|ci1~uKrtFz^`fBxscB`N*cXZrV*9j@&gb&YVi5t_SbQLJwY1*9as^fx6QdY-t( z?@SyA(^XYE)*06{aeeIi*lgVF*zAFK;q>|WPe1+i2Xn5QC5ihdTW1MVr-*cPY`ZHe zw}18;O8ZL_lOwm@T)($|^hEw}<3>P`)a!D8=*xFeYf1o#l=QAFIx%!|=tO=I7}-+W zqDGu~uv%EKAMHq^=EjXV{UmJNe)w=jQBi`AZ)ogs5>qC=`@~1L-hKCa7V&`p6FvRo z!S_zI1|Od~cFbpE6_74Hod%1ne4d;9sBH$z1(`7ap- zu69o!S4&L=f_jBdxl>N@r*aB??#X`Sy>$_X+O&PtKe=bbJd9yY}q^(^tn*2)fM^Tf9C_xo=Dv zsp2l>Pw~S(kJ}%)otsjdr4FQT+cvzd5rYm1mX!d-KsvtxaS3DFUscwN&Pb6&LlzCz z7xB6mlx~h|%`NpGlyLj_ctma`JQHsYZW|JVu$|@Jl^c_=pH@dT+nY=LV>2=cl`rk; zLQyyVbbI6cUHLo|+WSzt@nT3$zYXdO6e=o}JS-c!=v?C)-{20n#`Llvr&}^N5iiD_ zZdqNefqwTfv~dICCgH`+>(r2%dQv&o@vIwG7OXoz;&j96(DFiu(%Y)Jg>LuMY-70E zL33w?^}D#YvbP4(%`9_9=NFsnK!S;-bo&y-=!Vk)b@Ks8Qojx8ZdSh&&yB*4S4fa< zgmj0`jWJzEL_gE;qHn`~QOhloL)OORVnN$+t5b6cmjl5Y41ojjg7iCv`z{Na#mqhr z-&;DLH+y1U_|AH61lP#q^CEW#%(Zi2xVhCbXSoD)XVs>8mdOmWu+i-~Hqp?g3`dh@ z^F3>_+jh3?c=&>HBqk=A;>GRBmi=WDf$zlkExzw73Tvc%^w&)s zI`=H08%)1r0@xU8htZ{=8x?);dQ0g>M_*7kX>epzS_AB6c1cGEk~(%4d_xH5rY{sn z7JBtM#86Wx>^n}8tozM;S!(*d9V;%R*P>aEKXhMpOWmI8`c=KX@ekJRi4R{Pt2usu z<+>~`%-$0So-65v?ng7+V15ZITpXUBN(FCV5ao&@^l+qdIu)g-4-Our_lB!(4`%kY zbUg}(dks7Xg%<+gCLw*Gc0N2vUUj${OkZ-EKt@tu0BQXE)z!2m%_gT2?>vo<2z;Sy zQ6VBZ2{IJ8rh@5(Na?9-Qg^0CJl>(hrOd(bLY(R|Gv=w-T899=cV};(?q z_S}ZO1r=YNlzKT_82_&ypYQu1;)93_n`)guYBcvGJOzI}i8r#o*rXR^d_q@XR4gXI zs7&LAy+ydPjhG=emAk_k!ff3!x6VZ1Zlq`fyZS{kzf91#vvlEiOG_-83yAH{Vxx1z z=EC2Fh4P3SY8Jzb#TSO17pLn1Mq6JmOt;4a_ExevjLs{k&=gG9b~tE|({aY|{`Co% zl3Cug8ODO6=Y!4-p_^Bu2e4~t^GlZDs4=_a^>8czx9d~*6{i2 zte00TE|bk;O$g?ocV`n!-Z0jLK0el&LR@&~_LNB$C4lI{^rp?+bmmTujWqzS`$PK^ z#`eeMOhWZziMZBL({tIZfn6k~G>s*MHo35w)5Qfx^hSWi7n^cIR9sX@6j9$WO>QoQ zpcJC|lk?I*b|B@ZGRvsvrhh|&zZx6`$1)A=oZQlL^~@`jk$&{nwdel|PJd;tKR0*j zw&Cs*+qUAe?rv98oaE%>5}fJEV`K=@-Jq@+XMXdwS->1fXDj1Uhtlu4_P5V|>ywu! zo>`q+bofT!=yX}`2!|X#w3hKrXrhvDGIzGK^UxX8^uIlx&^kTR)Y;iN*^d*0ksCML zIXQBYBGNZs`t+4ge{j8Ne@S9xLhJ1HwLptglJDbL zURn@oFdaTeOlQ1z`1QVFVLG}u<)TnJ9t{+8bYwp+tjPBfU<%!l|NW={&d<;CB|3e^ zWWBuj$%}vU;{0nSIi1o@d@9~&=~6#3n>A9D?_EH<&4m0Y@6zNgXH{ZJ;U{1{b?9u0 z0rR<=ht5uIx%t+&Ck*EQ+dC@8r=*fN#^w?quzZMAbyvHqX2`PyT6a~3 zmAmpV#85s;x6=ww0NR_%%mR*~R6UAIr2;}nOAkOySJun^W3dgF_a{HO`Rb`N-{S+| z`u?f?n~(SBtnN1vk;_#M>Pc*mw|9s@9U)zkI=u>P%_mj4+EYNOdc89ETrmApr>hoW z-j$Uxd5>(r_3HaO@t0vw591$97KBcLXfUxa!T8ga%mlPA^7ZsjN>1{N+8P!a;*FCg z&D)$oW!9X(^8R9t8EY>d_kSJ12jgs zmhDBxjkrUUVFz9|P`U^aaby9YVT*{pWjL?r3i$Xw{GLq#JApuh(!f zv5F=q5%SeNNc@Wj=xlM^P3LT;ZOu|Gvy?94Cfdcaskqw=2ixUWH=cEIIF5AqoFC(U zF^DdpHG>(=>z?r34rU#~)v67a!Ks-vefj476(P(O+R;mq!(ejT6oqE98^3= zIGQbqa&m3dPn25BzP{1E+R@s> z?L*D!J5$%}2@E8KL^YW~rwK+}SvV7p52Y~r;6R`v&f#gp>16qJME9jElS~;Q5l? z({+z*U`A&2!szkp)IQLB2_xYc0{NwS#zCn`H2OoDQy%cj&Ny&-4<7k^f86U{G z0|ojRT^ar~Lc4g~GPWdXuEJFJFraQ$JCN>xF-Yw2`NE?`&4$uN>^$CV$uc*ly9wN| zx|Xv7iQ4Gs%hBoEB}4`_cphh8DirkA5Mb#rb&CU=SH z91LiS71XDiBNgNJ5rFGzlhO4|_W8vBVs!0E8a(@3DWeP@l6K7nxEI?0%A5YPp!yfT zJaixJARh2Y51E(ov7*klbxMV zebfH_oXP!7{c%lA;_?J+>TH5J9ka}Sw(ZObZE8wD?S)W~Xg7i@8x!(Fs0$3sU7kzK z3w=bFug;-YA~}uz$mnFH%j5#CC-`>xk&A7IzdzjGh35JZwvi{!JpF$G>94%>1H!`h zZQDlH;nJ;JGr$}Q<$98PN;W$kNbdmk1y*O-@d>(+3egS9cXmp2htse9Gsg2XZ}s<= z(baUcW&|@%Zdph`L8Lc%hq;^{;6%gmLoYw~bzyp1WL*E`@yY(l{{Bf$9gMUl9iJq@ z{k_-T{F*rZ`dA{Sh0@ZY8(=!w>CLX@vB}*2$qBMvKAni0e!F-5;_A^8!y60Ko*qB3 zY(NPiQTWEw(uPL+`e^)vaeTD4ul;Zh`fhXW_B?<1ESPU9c6wm%n|ll2t9@^@d-zg% zoy$kXzL@%R;_f;1+(%TAzBAj}_2G|y_`#LI4+e+I=w5j&IVGWs1AvW1Aq3i&7HmA( zr(m29&cD$2cScPg?W-DYEFgEY+@FL-oausc93vi>VEm|qL`XNJsp3-FmKxy9_b^4I zx2~Rg;>Axs`JJb5#WOxd?Jg_x1FQ>*TB#w;Cte1sAEC=_59&C!j<9XCBZ98ani$5n zZ+&?4VwYdfkFH*|dOCrUvm+zqzX;~>vJag&a3KG{0meXHs{jBX07*naR7XoEhp{a9 z?1*ESi9t@+M&fix-CTE>UxL!o${wN_OG|wKZa(1zueg{PKXOC8d~k*2C$)3RVq<<1 zS(jnnLlsGBd<~TWF!Vb5c?Os~MvVEKLjclkTO;du!Jm$r-V@MMaycb5G%+#d^5x@G zZ$0-r$muV>_}q8Tyn2Z}%euiM6liLg)gsJ!V+M!sTGzl1*Be+xL{y)PQ&>7 z`1^%zjr2%MV-LJ!VLEPher;FNc{Q)5Wjpcvm9!|uqh8um+NBKjE!L*){9XBCHC-+Y z`P1p~=y19vbVHpErHj)gr!%2u5?IGvj+SmbFTZQ6M?cHvx0ihtfBGLvP1lW}*tu9p zcOyEttT46{L+e1gtmH=RHhg`ju)c|yLeCfY{4#Xu=Fs0}bfcr2;?aMDntm4u zEd+OK>D)8JK)U60(X%0Kqm(aT`klniy!_~PGqZ)^X(k}Jv)IC@0a9QTEES8h((=7U zRy9VFd~Oy(=(?CkXkupcPz|#S-HL2=MP3XD1&3~bT?#+tUaRC3kRceV|*)nSAg z$lilyjg?wqD-zkWiGO)i$0*hSv)6>ch|i7H#UXQu#z2jkh|=XncZ=w#jO)ci0vHiG z`mHqFhcp4w$qpowkyOUV@u(y3_TIbLIAD0KeDbtOWk!cc6zA$KO8wW{ae5sUe@RI% zL3)4S^)10T~rKSfGqK=*(zKR}5 zD~b>9K|<&7hbVJS6Konhmwp~df4%k+{|Sv=8l}oNy{@@#Cs{CLj*!Q0Y%B7koQ^IY zs9qaH#QACE!OWaSk?t*QYdIJZLES-Wb$z|8?=&Or$Q~fVP<)Sr}b3#J$OUkuZ;sg5kn=>aL{lGCx98|c=rxynpU{V0OE0&h$l zya8?%oQl!4AI)gU$4&~W*)`>;K_twqSQVsW35Cv>Lldz77muUA+T$000=dETYxED! zh>Z;fi;scnonw?qHl=JHqXiAF#e3T|H$IOb=Yw%xbXJ`L2$M2yVYUhZ5DK6=Y7k}FQ!uk1mtmz-k zJ$ZS%E3cxb-SrNf{_geH6BFl>Vsa;y$@uBhvvG5$>42PmvM91D-#Ynf+*c`;K2iBmks*W) z@sWr4dIvzhgq-_Cd3r?Q?xD|-M}S|XVh#&{bl6wuUQt?+hB@81)1hlurB@i4F^QM^ z`wzWpD4ofFdGWb3r`~%0P;9K*rM`8WALyK>j}uTI@qp81b~n5BE1;COG}2P~x-ca* zdV}>OV|sh1;Z5J4F!$>F^WSdb2r()yD=aH4vdgd04-Zkfj~@Z3i^x$|Eva(U;dZq2 zDp5LqclNsD{^7HdCU7hP0!gT9;!Odd8 z^KT4%!k-d~O&zIj%sk9$IsH#R<4t$dxj}O4d|?sn%M_UA;y}7ZVyWpSMBR$&qG92( zGYCR7Tx}Ha1rleGmBh8~HlsU8ZOTSJZ**aMdo{arcHkE4?;vzNySy(Gme&Sn_lh$$`PE6nl3~) zS38m8#SBz*L+ysuiMadha29AK9B-z^9b*VxoX*9l=|(g+NKG`h%rETRcw**ZbsYVIHuLT|=XL5v*uFax6&*sSmb5KY|&y^e|c&Ai7DvKtEp$ zf!`|~9TwLVeV5DQD82wXq3KFa2iV8MzfWUQ!Ucn{tMf9mcgTNZz63Y6)8o~F_UZ?} z_&?iU^3vtS9pQ!FM@^bY|fcxO5~V89?6n06c-sFx*1C8^`5$C1ism=F!K_}2nm z2Nn2OD5J~xyoC3acWVuA7EFIL^W(O@D;L@>WV*YMs(&X9JULh)^M!ZIG#ok)RFhBM zdvWoj>ZG;i;T>z}DnyYj#t^h)w00S|aeNqAT?P>=SA)aOFoeEvhZ%U>UYQqgn_(f{ z&EU>L{mMC;2z(7C%URAatZw+)ZX$EKZ0Y#5B&EabDz5<39e|h6?j*sO#|ol(9p(kQ zt3sudL+&O*Qr2`cv%=)Eql=rZMC5m3I_4iE>+2w3@sbr%(^suntf$rCfKVOR`Y-wS z`B%GN_yltO;7-rj7%E7U_;QtuL4ooUogLHo(%1zcC;ZSE}?09a$4Io#dU5* zMrO07$zx-5HE(DLolMEwf0@TM>`&Z(3}rqMatHb`(WErR#fj1oFAItY>D!o9mW9`4 zc`iLz?pn8RUCh$eIC*K@gH{ZHki;JB+hv_DG=BG=!kr!*+m-C^wXQ6;Y+vrk#HUZF zkW?k4FTL~;#JiOCI~ajueY*(!P~Qv*%LJ=6jC! zAAjbVwhp_7<`HzMn6a_xt!=4>h9@rz4PvCAHVzV=v?CVJipwW z$vG96PLxfX?DI<}5Oh5fkkIAIfDXevx0N358x=Xft{C_$=g+r~*7$Ans%)-lN+9Pl zGZMLOeV%LmxQ#!lm<9J~;ou3$Op(`M*1V{vR*(4NFbuXbHTnqSDl;>9S`q z3PQr@6U31g-gJh)KfoSRP*qih>*Z@NJ@w!O4URtf&wuVjGD=Qg7kja%r!k~;Hmm4B z0jL|2K;#S5e3mw$r4^OQd5I-w&vv=qdyiv^^dJ57W>;A0&61wvdpfN@-OxU?j&kl6 z(d{C9E=~7Lv71TbdZ8Z@2KHcxA9suddPD2GcAb^+g_xKlgsA&@T1t-#O(;((Po}4C zc|{WKmOPS@LVQBJlW5)kZX4P&|nlur6O#+QH! zYE&zF2!vVJ?kcI-PE)L_&wcU)rNy+b6|aAC=2YHP?CPAQ#>}#At0$Hr)O3A(-a6Ky zJj2u5zo5KPf$60M+G;tM3{Of+{qU_|vhnuvb&=i^*Kq6AS6>~QjBAbZ$_k5$Bs@kJ z+Ftqidj^{@eFSx7Gvb2@i;PsoD)qrK>G(v_RW&4PQBqXy^5r?f)2=yJQ}gzknwFZ< z*shX=c1J&}y^*`EjznJ5iqwGmowgUp!vT;2>e$G|>L!6usf2$jPN%SR!JB?3qu)7? zkZwR-I<*_m?aWs#p1UP=!SEdep8ke%Uo2ef#<2KpV0X~my~3DOK9A@|P1j@Z*o^^i zXMv-ko5KTX>Ed+#V5n!9jdaUHID?=w3Wm=OqTfby&8ga!TQh4tFVfQ8db;_H9mmTT zbNZdR=@2+R0#rh7t&q;taJoTkqoB(GBh!m$JwiWjR!96cV>dexq3dzNa;uT+0YYcP z>1KuQK;w|K;c(XKs?E)2W>XnoB4kcy6GP@I8g!_90o09tuB95f)&8^}>I;#`c{|x{ zN_@fULT*)hTXr@9Fc>X%?5sOlcQ7@3$G`y2bXAoWZ%~6JUMk+0HQ5muV8RQ<>c3`U zTqHM2cr-&8V_Yr|EO5GXbhu^ly;xlyvQ`&#bTIuP!|3q2VqUny=W0YsDW$nYkFV-j zQD~a})CX4UJK#lg(Ri58(!4Ldu?=5R3F+<~7ap%aN1V#|L%o|?(hGa{^zEn**GY&+ z#h|3O#Gmfi8@^|T%ySquaGokq+K?)EF}gZBb$fQP?AyI7qg6Ao>B5C`=hORM=o@{Z zuMa&PK^+53ZQW>d?NRz9?M9DArVl?&W2Dn7SDwZ@Q-4~f^Hp>pT}DgSmDw%iY^JZt zL_Y6WvU1hwC2NE3i_Q)VDx?4u{5D5K^%tTGBhIzqcEQ%d`HGoBj2Pi77gyJ1uUZ*| zHAe0j03De;TC=C=NIT%Fr%@>jA@joZOc&ox-z5Zhd@_v84>0Fn;l(?QgXx8f8hg?- zNDZ6l*CaU|MrT>^hBXg^=sVWz7+~_Kv~?L|5ZYI*iZA9<TMX0bCN zVSgxgkI7bI(+t>L6$ zTvsR3cTYAajwSkSi;J816gmC**|O$0_wF6`u9pq~1}AN{m@ zYuL5}>n9FXuQ+*ExkUQe55p3O1dEZqOSZ3$o2xIWANxn zK3fWAr+CDz&Lw@HS_~hMJOH0jNSJcf!#sRE>AV%-Q<+5LrYN-Z08VN|dH}n$A>wr# zUwQzg)(Uzt)uV>gOF2yv5V?-h0ar~!|1*c)fAIj#xi>CP86S%g$}>Ex zY;Jl8b}vp!BvGe<>4l@E#?k;k;v1K)Gn^jgY4rOvN>;snqI_LMEN#E_{`{+B32~v+ zafEI3NGq+ZB#)i;v|zfgm&Ei%6ds%Y!C<;aT18quVfUqAdTB;jq_>A}6m5Oua+fb% zG@X~{!udk|Y)_ZsaJbm`bmx!E&z5nGoNk!X_+Fe!Qe)z9!>A*p1EUyUWPl-$(RkCp zit9ycxpU!0gQ=DvpML}H#f`417JSv%N~{6hVPw1{;Jb`8($a4`UyPz{Rd@%o!DVN- z7r1ZT%Pq>grE){(Rtz_@f_Ae`6M5iuIf7vR4^7dlEoimdn|jSA7Zx`9(DK5xidAdhVBrgmd|FuL`UtjQjzt9|4ko5=rS zn;lhG2NI7c&$AF&)70$h@ZNjjZ)uNiHC+T_#vN7{2hi{9y;n-Qh9X@UcFK$lFXI4u z`1s?|;g3g;!|0-Q!MY6UN-A8ovLh&3Z%$tXg|0hx=vC-M2A|W0-5b6n(@R_S?!xhN zeQh5QFOXTcCwf!*K>gbK@aVw#o%6U{Fr?4)uD^T325HDZdtl&rIOra|D!Q8V`qY+| z9cay`PcK_VKz+E<(A&i5u_g#8@^wP2VZ*7>AO2luU&F)@8cBZ7N)vd zh)7qfBR=`ly-Sv@T-&>NplVpAu`H-=&LM=$^AZ@iVfVv39){Gx z^gVQh!XtwnM%_LsKE*5(Z%y>P5)6m>LphuPJS%RI!=wA~L2^d$C) z%z=Sk19yejR_YhK+tUJeMo*_=_5YID^jEuI_ypE@ zlE)Yv3*jO&dSzioX{8}i6qJnFB!sS*t<#}Yu4-NA! z?^@01_r-Y~8bc){&JKnj{fuPC@%LL48;jZws%K=NrtiCJ_WDPE4(Yx`o(k0ez?b)c#$!~-XR+A^j2dxjA2QKCr3Z+++4=l`!~pZ(5vXj)1X-;aJIK)2&Z z-~EFpJ{owTJ2|;LVah+bd9L=g*Z%iUu3sO!{A6AhVc}0d@x-SejYv*^Z06SWqVC47 z&dKuf#?tPpkg~W|f4{Cvqn8Xi<3~Z~K7X=rw9&IX?{Z=au9hg0UVMGyTKjOl)W3J~ z#Ky8k4GmMF91_JDi~Q8o{#zzFeLBCO=ZF85te3&QlN=gt4Jk=3SH=jXpBp2Gt4vs*B45qm`9A&(cc1L;?ml_=1qmoLK00yY#KxkHpe)^xaIFy2=*?q^d2g)37UGki zR#lajHZnK=pK!gLdP{8j$Gn3$8{;E{=U80_b@pUD35xq-ZHAbqNg)OKz4P7_)>!Hw== zKpj-y#o++M&p)7&l42To<;M7ymseJjG0tazmhAzmd-_C?G49I|QdD_mUL|Li=(kH7 zE`n1$JQ3IBOz}ypgo@>PQNRmQI(L!-k}Cu9T+>lu?KM3$EoXCL6Xklr?(*I5e(yO@ z{l({=J98C_Isx+dvDU5YIzB~H)?sob4^W8Q*}4()5SIPVW-%^Z8sx=W}z+pkRihd`xqxQ<3f%Qcp zg0_^@G$b_)YBXYL>0BkGTRfM#%rH3q8AvyX&SD^)+;n*Ucg>GN7p)t{`oAG%xn8sw zR@OvW>dYzk#m*au7Fz#_TU2+D+1$A2#oX@kpWG#*W)TzJ-d?Rc@|;tt%3y_kV)qN+ zR1Mg+FEF_v@OFj+@9w(}JsWjfdvFlitajL)QdE(t9TLJd zw1G77c^T5p*7MxMsxI}NS>0$8gXemTI9^Z24T7|uYE5cgZC_h93VLmAUE7XS?C32> z>8aVu#tlTV{zX^Tp%fa^eZKbWz(kmWsBtvpq%t8 zDisyt$l#(_7s-VHh-@ysA{q5Dau{8W?CrpdE=XSmryEkQe;hjhKBWGAwK=Lsc$V~R zTa$)|2R%;zp9^xoSW4&3WW(;ezZ}!cU2BRnJ30o_&!=XB>8UhBOi%FJ{}ZazdL(ia3|rzRCfZ}%YxR@$*Df`!i5W0(kV#oOUHHD zhwtUmVHEW~a$nl&(m8;t9oVgX)7JF#4ArEhve5A~{Pe1sLOkkFcm2V(3-QrZjnW>I zqRb_@T!K1^_aL_S7A`B~2#IW$3z-p{(l6nP5zAw0=^)4P^y%=$9S`mdEL_&1mZyas zRF}?2q~EAhpbR$ny}y?_SB(e0cYImLjF$DDz8hJc+tfi8et&%M!nrG{=h|wVl-Ui! z^hY;v1j3mDL+0@k)lt^huH}pXlKP_$ui1bzX3Y*T98BL+yf&Ip@&gL``zu4scv$ezedZ1>xn1cY>UaXXFcVqX7+Al(+(wY`8r9y=W!6Iwv?mGI20nOoKyX zgQt=kx?*#3Rs-rWIm=m{Lk{)Qr9_C7<<7qS>Ac}|YDqDWeErPR6FnwAM2-iX%Kcl8 zn+O-T*~J!!3e??8HcxE6X5d^C_riOw9e@55y^G#@W?dE9LE`cLn6wi`Ky5yV=I7_h z)w3!oA=H2Wsh9r>I$s!{JO`!2=|Xj^FF$?t2?XXB4mbMw6C>&0?z;Y-G8wN=T)te> z%Bz3=Q~IZl#l<~%`ms0X-#gJ=>euP(kCVE+Dk%$lP;ggGAAS@F{e{0nQa6}hl~$Q} z^zwc}aQJej7A@M^TH8xf%ub3c>4_9P849KA=q<)e|CCO9m zL)we42mMQBd8w*uBn2GItV*l!PH6gQ=4)X3)ia+w@#5e7&!=n+DbAEQ-y;_`S9?OZ4!64dA3gCM86KH zzYD2hQQ32Gs@9 zusm&%7J%73V{eII(JDOb=Kk;gK11{No`dcpd@V2w&8?_hyLJ!V)zHxbj(B@8ft_dJ zQDzT{Pq(KM^ijBn!|L{=gK@p^(eWWNY=VxN{%a90&iCPbQO5FOCyt^nw>mUzdKVep zJX@e{hq=|nSzrmBJ4QX%HiBnOxN^_v>CUa@&1Uel0dtAx?oHVkOi`>j}D|F)7GM>V|(dS@hH?@cM#KZ+rjkool@Hk ztOMy5+EaIAuR)7d)u~Pj&?=LGvb`rTnqK!SmfUy$SA;eCG2$kyE;y%GB}R1IE>PV= zbQ?7ix&!H!(8=N+$BE9BiDP(y((Q;gO^&PwMu~-FHIna6#ycLEHQAhV;5%XL`I6N1 zJ%JtT?;SsvKA1^=&NaKU)3b{svgd*6J!?>nF{iKXy>IcJfjzt9t4V(;rj00BlNgRt z)9c!>vrufhc4pNI%1KeO>m#x$YPtfU(*jS{m(d%-bR{0+Wl2pv$U)P=fj!m4teZ3z zD4dGVXeu>>P`20icI-SD52MQg(?QU-^z>!Dt5Wxj2T?WJ8$Q0aep6-yaf)rVgf{9Z ziEl(Xiz}I|udmAn#8(i(vvNF>U(~k2b2X#$^+5W{-ripy?;BWqx?`E_=!$AL57ZPj zUGA8{E13}&uGC&~{;iP5xLazvcv{YL3F;hOaJx2KsWpLtkM4MwsL5hTeFNqe{4rp9 z_$uu7#T1@0w>GdCc8`vKREaUs*w(`pAkUj!D?bd9JdrW+4`)lTUm>8SfEFM|az}Gt zNy{lEnk&o2a4)}&I$|`xloo{Ta;Vp!w&iUL%&f=r0;Z#(e?>aF7#&tOXNdT{{tTx( z=)F*}>R`KI-~Bum%#E0@;{%-z0ORdi_cp?B=d!SfmtiD$?MvI6$1vx7!oRxtrGEnJ zynyuJ*jQo!%e|wb6nl~HlhSYi z`vqG}_w^%cP~As)Nuj|Fexb3eRb8698u@+sat!QPefRB~#jHFxKmXBdwA;M(gO{+W zKk>wKrzVhMyBt{CwIy~+OwO=6xt%vWe#lv5#dHVI-JE{>o@>t%ivH{~q3yM`+xLgA z4n|PkxOHoYPnu6Txg69JR!w(?E;@ebJKy@Nm!Er1SH^SCeewpT7dtNg(`&GX(r=wa^eS^1-La?=9+)(vD3F)RsO!6RLquEbyrQd zauUK()35xKsyiJuy{e!x@yRC>Q}Rmk{1yc-iivA=DLH-M#>wec#MIbOQFZvwLNpYpj{9k#^uzXgiwzUi!JV!PG11qdh$(AHMO%xeqTLIYL>% zu3i1Pak-{s^tx?#BvQX_hOFwd$nhGj4yL~|Jr%nU_QG;Q>RX`nUArhf_LuHmS?(9J zdTFpvC38Ljc{Ri>2JnlG6FrJwOJ5B8)bB#a<>dj%o>a&B`)j!eZOWym!hlTlLB(^BK#A8Kky&m4MY|F_?N|IDeY&z|{jFTVKQSFi4$(m9}v z$h3e)PRtb1U@D(BU7ezIPA?J27|=-YjWNbBSq`R``;o&FK<#U(zgJC5!=kvRM_$GC z!l|nS9~5>Noo_%BI2}1Xj2Lxaqo(V`R+yJc9I)r`(xb{U^cIrR$idf^>sIIbwB+q8 zOLTd}G3?|akwMXY!d0t+Ib`aUUMkv ztXs2ZaG;JD5a_%vT}7hYBAUbDx;1ytnY(T&z3yN{_KtMc;#o(3mvvo8%s$yA?soKa z-Xr7T>@{ehO8^|Brz_k=0_FOLMCT7-M+ekNbXkH{+p*F?bVp4eFMM2#u8T3bjDKHR zx`lKIy4j*?&oD`oY~D@bTce!AzjH8YlmJ zef6H~>f+r4I8>g(=n=Gdec_($J>kWB2y4{4klTfWq3prkq#|yBTI0h{hlc~!9hs@= z=f0nL&V;?3AB+IgxiXPSy|3?FDgy4Bf)7TI9A^)OgY)bhZ~D22O_`~EZqo~SjPN(Ktu)4ST?JicAA>qHj6?bOZ6sm{&- ze#o5tfb7K&?~whSSaOb9cpCC1^YMb1CBs^A7K87e-AtCK`4otY^p0kl?Oa`z&Uvc{ilrxm=62EA3Ak zINSWv>Gbv!BxVQSzVq*$yJKg*JHJiOo}WMN*!<^j_{&?nJkHB2V^K_OuzzI=zTAom zX{SEf|KRkjY;-nZ0TG9qyWXKnP!&#&MVeQ=CSFR{|_*`37nm>dl# z9XJ=NgE0GYGqz=H+e+7XWYk-8@6c0dw)5J=UsF%|-=BE-2V)z_;K|B=XIU zOpcbmAg5a(*AfA|1MzN3=kD=qXP$fc)U|8-Vd7)4G2TPNxJtH0%JX5w^vI3nbcF1` z_UyO51<&iEapu&I-U8Bz93d1OLcIFQOP{{l*IlZE9kL5a5`6dndF{1#=9-&pTqAe& zo2;6TX5$VFyt#M%$D;?lG1B{&)7dkvqBScn!LO@^&O=mpo_B2HB53dOJUD%OVhc@< zf_*)Fv!>JE+}r!+eBV%ORB-TdP(3bAsGb!(H8nCvS*9>O1J}z1@~QexK+9F&rZ`(E zg!u)-1>KiM`(Ajx?*(&0^M%n%HJ7S}t4>N`AJw8uH!j^ce4=q?e8-dYwnH-DN!-czTZdxA!!|IJ`JD){x;++7!YE|z*%ojBQ3+5@FupL=KS z#@xvhC+Wb^m;PQ`+aS#|&h=gDp(p0e53js&<-;D+^N7BqlcBkH>1Yg59a1-NZn#~E zFA2$K56Oid?7Oj5YWnrrT_)R6=+0uUhSbIBI9@0i#cbo7k+U?I*^0^}9|F?zDg%5& ze3JaVqtVGw#b7k|&Lux*P1ntW68=Ds;F|LPpa#M3Ehjml~)AcMVt?}2L3 z{7A1bFQcZ*Cq~>0`T0aKmM3{*vR_B=q!MNFz0;B^stUYfViLByTBA5rOm0r}4UWyB z9E1wnBVDWQ9~d_be)iUJVi-_|F5z^6rUU9y)CHneGd6LIkgB}tDklY7`Ehh}-3Y{O zRHLJ(yKOIKIYcZ5mRhZ%QZ9EGUSM=~1}ig+=fyZ+z-YEJj0|DBg>pBjo7{7W>7sSB zcHzcZVwduGBeI*dz&}qRwl_mh$Wy`SUlpmFmxdo6cRTn8l55U<2NU~73oGifl(K?JP>9s9Tcv}5rDdlkaSP%1i&MIRFUX^IDZ8TFtLVo>2K zqoX6B8=Ffsz6qf@Ru|EDz3s&*8wiRzY!021pzc6>u|ajJ60v`<-mx1*=lo0dK@N8!GRMJN znjm4>7HtESD_3N4NHiEhZzIlilEQ*ZoxwR*k{Q)SurEDzkd-^}v=3whv*^ofXOND8 zW>e`|SWQ(g(dd*O@;T3_=<{@MeR>-U@x51Pw-Le^kx4(&y3AEDwlI5TFVB1T>1Dl( z>j!p^7p@pzh17o`8&SVHVjP?OAac5b+1LMC@4!41zXUx!2u3%=uB`Rc!H)5canjxg zKd8_CaMb==S^lVU)9JtppOg1aJ5n$ja$XxxktlB%LyHg{T94*E#6P-&7#o2%YC7Cb z4h(*EFugbs34QG`6<)jhev)A~wK`V@@9kG55yX267 zo#JZ8cS2AiybEE=)~*Ca>N)YDz{LidCAJIS8Je+8jEv1izsi4OSFldd&7MT(+LaxG zb?uf3JJZt$ug!jpo!o3?INNZySz#yk$!8MP6ACx zr2w#fNR@^va5sdIh~bf+R|#ruuSqOv@J~oeG7gJ`&Xj~n+Jn*oQO#dy@`&vP$=O(X zAvq&SYAMc^F!@{hx-jeriH=a`w? zvUM2Q3knVt5ucqk+cY~nIcv<=$FDv8(SJuz|7Z@6J!-lUQ>UgJHJvV_(6}4YMeYX8 z9Xw~1O?_b@+Z@|`?D#Xpj=%i!)6YLYF>yI1HmvHziJ>Zd#2kL0ww8K(dKM*2h9-pm z{j+#pzH{p7Q;cVyed}3zW|H-CaZ0UwmM-m|Kuv%Dg`Uzz9_8m3S#-dW({I$&Gw$F&Et!h~pO>4wv@{M3mQ!^qq39LQRC@xu#$0j8fnSu~74!avRQ zDB}B}qf$Xth4OH*p}zp5j~;G6Q4v|xefZJ~jM3MDbp9eAKDklac^Z(OR?7F7lw{LN zLga_SJCoKJnVYLdq%VC}m`)?oKmW+7_XN}Xw@jU#BDU~wd#PtWIU_gb-kW<*WAHt^ zF7F}8oU3aoAsKMj5jb6X`b|N$8KI#$ak%(3q@eHPJJ&dHqVdRC950Nnt|C)xIy6g^C~G>PE;YR}Zzw;^|7J;LvnzD;QfO?g9d1Jxd}!Chzl{|%-WOOQtQwQ9OsQ5U5f z8Z{s)Ass%KV2(@O2uuGw6C`E-W(O?p|(g*-T4C!^Z!O#%|zY%T*BS<=&))agbwque=o@SGO6;c~(Ca<0(hz(n|dk1*XFqhLO94|%7JpBEPSGe{bW<)mE=JdI`(2RI0Kq^$zw0v%tm{^wE;XHwN0~e^_d#`~ z!U*N7zpVB~j|T3JUf=rx9e;Y)k3X2oM=>x^%{$0WT~lBD)Skf8i`Q@3SzR4ozXMD*y(K%qHD=u_3wDCU=w zqbx|*5f*1Q>IP_+^c0+qYg^hj<8)!YOx!G3#-gC=;u*Xwy=z>lPbqo z(e!!}(FM%r#^+W`19On9MnolT|>!VjF|-&5+y}E~OpsyJUJACsCLh zAGC5A&6JAcSFH+UmmIEW>t%RHR;*gfEi=6S(}?d3sGi52Ms7ciyB&#K87#&rBX)LZ z9V|A38wZ;WatqcitJ@iK1Yl+b=!VjzfD6BM6d*}lq%Cx3=eo7)-1}xb_eG2JROY@O z$ENg6E~7z9?9|g;Gc}(W!VkPm&u4rsHtPPsnfeA-Aq|Iu9`&J-0cpp|XMEP!hvC>0i_Y zs3)XQmlxoZ=0iLMpw0!p(E!t-1W(u@tW4qP_|XCNrR&Nf^Yv64H-;QY%JjWr6R|N{tLOrH zA|zi$d8NQl0H&AnPC6W2dm2oC_R!xRx_0Oq~0u|TSu4p{t5i@^DW)o zrQSL%;azlK_WFAtBd4EiuGzl7vp;k*nT(%)G#gVfxPI@O^Uc!@P1_S|N=n*?hLVyn z`uo+49)3ZY=0;6_ol?uu0<1_4iKyw=j!KB`@Nv<;V*TFU`WpwbTH_WWrel{GK~FF9 z>&c-VELsN#N!ne0UKL4 zR-HWDM+%n-Yv;N94xdE3twKu2$fS{!l;qnAC-R#S(u!lff-=XPgjeNyIdkeeKnyX(fS_uhVQ@NEDcL^q(GUf0rd@hp+&$~nLJ;kh5a z@zzbr;fHXVD+WC@mqG-=IX z7NxEV{sEv&V{w7h74bp^DTt2m1>k3CiEF6HtCFv+CNH#KNjEQk@7u=`Mp{SmZW&JB zJaP5R`!Bxu<5%C>{LJwJ6_0Lg^`)e^w6q)8=B$;@Q53lO++p<$+K~F;l3ADG+2s}E zMJjtj%Jy3iOHLn2XaMUuld*8&_{qn^%Zsy5j9_Il!s$^&29a3f73M3Kx~yybO9ayk zJbb-!lk#Y?mB&|7*_^k((qEv?v5fP_LVvUD_+mX5n6!Y280>bw+-CIOvd(m4PZz05 zRkn({V@{{I)Brl$sh!d93eyqT9f{rE3V)L}NVC)7K(zRnqUC*eeLr52cn-`7SMHiElj>4}a1`RoL zkopOw=fpdn=rKHy?QC(hj zly;+^Bdli@Z<6aoV@K)^mS?Z2jwY+I_aR&_($pWq>aqel7oe|re8uBnx*_z($Egc- z@?22UEuKq1H>IPN(d$L&(V#h;uECLkrWCGLJIv0*uzT0n@BBCZ@B0hhEWSFkaDCxm zYD9hS`plMFwEi5tm0esv|6um+Ku!dV7v8&SXIpV*_-+|pI39wpsh3o<)sEhSsbr`l zH_rf(%Q`xuv+=dyc)|4osJFH8p90mRfV!M7xYT8Vp|S{bd1~80dUHBCLr)Q+GNY!U zkUITC^;yuNs24^bM=%Gq3)2q|W^URvm`Vqx>TwqI-rJF$PR=@*9#3`)fid(pD(sE8 z)Te00%m`lNCR!e`;okAK@eZ1!@+deRuV*G?-oY6X+)9FUA{%?_`_6Gzps@a2_TVO_ zZO(^F;^M<=WHLw22Bb|NP8eGuFQVfhpqji&xm&>UM<1p}6kj@0`${&3v5S=s56Gjj z^U0_|(28&t@gPb@m#qp6=XAk}wdn0@SIL=dm&^Wq1De=@B+n{pOQV1=c zLjmn8Z#>@YhzD8MjX5kZOU36RcxM=v=dtc#=6=Dy zzF)k%<=Y>8P=EV=A!_>PcjnKY@BZTFHA|1yJt$89g*^Aqd76KHRoSAL99*iw!JPOn z517XEf?{eo3_@3QT)szZ($F-S*+Z30Bt$>5y`jOCvM7#5N2c}B{{1Pw2`SUG=ker{ z=8eY3@Fc}fz87Y^JtH%$j=oRsm3Jl`4?k_P$bS0&{aZ4AlS>g(g1gFAis>UFux z@3M#v)njv6x-NHVjKZIjhAN7(HWmTtMZ;kFfh^+F@weyZ#BS;De`ez4uM?fpIVnaz z`wTy4&$?xDApF{bn(n|kH;(DW%o$+U+_8pa|MFw|-y-bg<-dOV6nQTNCyGv-z$3!x z0BR^1o&}M<4V|H#Z%Is_xOV*5)IFUVn~xW8T57({$Z+lfp$ zaouzxz0th=^4VR%bRwlq>BQvL50%MSHw}OvZD|>8E~!YOxY4ha=FFU1Bn^w=PK550 zwKW9*S3`;`ugSIj==MCHn1tqmgVk7O-W-@NY7N7!9u?PGHiDqOH8Pkp9oI3vynDT< zY};8PWRcTfKRLX0=~92H3B5xI22b)VD5+_0uNodc*?p24{%+bCrA5&#bYu7Ex$~C} zGdX;?@7(Cgs*S@1Rj?s#UNgeNqWn2vqt4hP#NRWaHG$mpw6u&k-&^xv`}6a#Q= zeeuOV2s90jKE<3q8`mEiI@08NXKt>!rSBGzF2MN*XdQy}^!Mn@q?V*xIJN@GkDNtM zzw*Y_o6N)M7p0i*!p9SbPaQ_zHoWafV`I~Gz;$Iseo1qF6asUFt0K(R?17@5R8o`TU*qy})l^m{miV=}yvSFnaMdJ* zMR^2NR8n;+$4h|B>5dBQKbZgkAOJ~3K~zDVTh#Q*l9B@(V@obmRh`g(>=f_)dv9D$ z3E-&dK;Adu^jkC|ed|>T>U2B0XVKOJCl2IO^5G4pH#Tx8OvN>aN?{p}jP4fH@pWZr zSq9nd{uwcgI37)zdzD6{W5lBRG*&GzI#KqXX%zvKd?@J!EnT4QP6cp~Z4%z?ews3l4Q;V(G

    H>OL=}=&Ip9^?j_qEjInHp1=p46BVgrJP+23VA{lIc8@gM!pwxz#wrJW+- zs6;|j2!nJ1t24=Nui034w6wPN+U+-Ac=O2Sf!Q->`8o40cM5lEaIW!+@+x%oGi_8q zIv#r-#(v}cg`R~yA->CfcX-G>&=4>tBso7hdDeJ8=6Uos>IrY?X$Ws{;>o+Z@~Crb za@&zFkv)5FJ%8-S+`=p8`?l`hy+HPk`v;#F`d^3_lq} zCAu+h&h*K2&ag1uP`U%rO{pl?#Py;uM)t=9csPOhE))l#>L)t+XJ)u&>dor)X9F4k z#!6xoN{T8Sf$8|tX+7%D(oMt*V!9=kpPy zD@=#drJ^IE6XntuA*ag-$uUs6Y%iAQ#blj31Z=KsIGYYfrpb|{bpBh-e)N{Di0f4G z_g*-5-uwLPVJ160?ELHA=bzmcdJMc~qo$#J@V?KYZ5zZ#@tkwaPIto+U6Z(ZBor+5 zdJNj*&#FW1tJu8lLSEib#Ijf{wZMXYx6O~Y;9Q+2)n=4<^of$WKpV~$r>iL`LaQ*{ zI3V!ij(a$aI=a=Xy*H%;>7k*Umkw^eHn^-HZ1JW|X$gC0B&l|kUp3kp)g`5+q{XaE zOIno{8fsyBN5?9%1LNX;9rssHDE~cg^bK@LMdaVPe`iv48WApOL20+ableQ9!WQ4o zyS@1KVmN)(?XaMVk7V2F@%`Yw-bau(;;`8ZTTcrNf3(rhgH1(MY@Hw~nj9{I! zjgG!SurJ;>=x*!y&&arbkQ&mIgYT8uYZAVd&zkpu7|E!Z64ap}ObEQ-0`-UFgPQPg zp0sq@kD4?_L+P=~uvEt%N=Ger7Tw9+V1luwV;fMn09c$2VvEGZ;?Nz?C>9hA3dseJ z0(6`&U?3-0QY|npK}Z0lg?6m{)kg2ZW1sf1d~t)=&}+$Q(p88H(C z-2&cpRmLiiadhx_&ES3*TGYiYN>}}+)O3mIvDA+O=>;8&5z}Q2Q^*S+AwEmylf=9L z<(v&uOdUvywAU~f;6Vu1zcjcMJ2PxT$3mkShCy|JJaDeTaP1kNizzA{C3RZAnqel5 zHqGC~>VehFjiIy)X<5 z()CK}CDI-TQqxs4;NWzo}cHT{l+ZjgMBh3$@tQp4z6265d; z>o%s}fpy2X!5TkpJ!eBc`#^+;8!>wUW9FrrNXCD;+FWwj)6>T%ktU1nQ7GtC`N8S* zWdzNQlUKpZL`7tvfjZ%n&2&pl_bMhyyEv1AyO5vS5H+;=yo|Jmi!m(@vW34sN}VERVi*7%6cw{^+iz70+G+`n}lqWN7K zx4JjQ;x86V8A3Xp5!-v~PzPSF*J4c7lLc4$b<7;0W*h0Wdcu)WC@G4?RSPMSx zsR6`wfJImZ0tnSh{neY_|IKspIc-cdA{%;ogqb*7=qiI<$jK#nmWyj)QE{PHq?>=p z5`HM%!jaZ96KTOz_Q^jUj7w??=;{51IK6ea_vVqCbR|{T3s63Q#Rbz#nnO)Dq|RPW zQ?3iOqgh!{`oe|2hY#nrXX0BXvz@7h8K;%?LgS%~M6VqSf@9XNUmsK3zi>Bl`ioz} z-_Cyr57ZpU%yD}oCY?8WF)ff!2V$6MN(T5`3KrYO-Z6MK3txsC0_rjO1q9OS)@jr%bAKxK1D zZd9@DdO2mV+(z>|WNwxmN8=S9e_(!g*GE@>cfxEHICJJyd;6~TU3%{;&7F`L4r_92 zvTJg4i`b|md;0CowX&qi>i{^wz_k z?w)E28nQ5dVe)J`JY_SV^NI}jp_nwhhdEw26A&tnqjq?0nhft) z3@)bHR7Iy6Hl*u1v>oM*=>(-GM&iNAgzsH3x+NmYd)nUycdNNJr7MlZK>9bW>QPx< z9{HZ>Jj%nCmae8oR`uvV5P@R#9yQ==3P|mM7ZJIka!WnGTSJ%k#0)@P#&p}9E|!+` zZJgEvClARC#ioA=)D5#6(+fhnvKZMjoUSEny!FNp{uT$z zx9zBxM}GLBQPaQs%{`>P2-5H9=@Qe8Ki#&c|5vI_HKe_>Gec_n|6NeGSAk`Ck(drz zOUSm%MEUw*nLTXhRa?^Wh+89SOO>z0bkuZ{nGV&*OKevQHwLbB>vHJlmfeMlOwoA+ zws%A67M;s+ZW!5OY~eGu6*ENW;jL8)HP<2){nFD1Hy<;Njl!rO0N;=-f~`uEqF@R?LX>>!td&LS_CuZ{38s_TaW{gUdpf4Q(rkojVmS01wnS z5y?@ixukO=r?O|^xzs_hZQ?^*@}YaiN=pZ8;5c37o{qegM;6C!?-iw^rbldFy8YQB z-UTsb2^~ota;4)>tSh6nMN-0ygqT%9<*Q-~s@Hesq@$*Htn%(&92Yk?<=^vO{j0A# zn=Bu;$t_$sdtv_UeEw%q9-O}*WTB}OCeKF&!y);c9Wt9^x(JR%F3fSRz~)g|PEm#! z<|@|S7<0fCg6$J^SuR9>TW)+o2mxQZ4r!kY*>QS4C-J8p&9&5D%Njb8pFBGx**?l6 z;1;W^nSXS;-65*sBrd znyw6Mz22sV)N&bs<}8RhIn>hFsSn4>@Ip@`952M30IflIUKBMS6uU~C&M??bCL%+& zkGnZtjBa2VnikqwWG5g82F2`xKclAWTuxJViw5p&Fx?;^065{Esk*wL&|o0)`Mtm( zO0ED=G3pH2On9$y_e>OU*6RYgGz&&eSAxyG95cgYM>;SaLbowp^99kVp>(O~L5S&j zmY6=>R9|yH2GGqtvi>yJ5sxE^%h=&i)6F9?dlr?OeUZ7@acLF==jOIFf0kuN69u-$ zaPNY2FkL%HSl~e>tVVoW4p29+t+hH`-hJJZ$?IVqNKV&U6=)lU+%Zpb z$mxzli_}>GT-59f+0E6o$w)V$AwV~;q+SsV)XfXCh`Z9@X_(iYHEkQA*mx&>oT-%l zm`YjyENGf&AG7#fI6o2FixJnkhIuEN38eKVz2i-HQ3E9Yd(jZ z{=rAh9=kl}k>8RCdBafB@QRTAofVLT;#VO(4m`pVo_%zT#{RuyTc=snCE63 zFD;#wk&#Yb9zIz;m7ShYq9|QK)w>QK4qm>btGT46y}j08`e&bgcJs48%jh?6qCj_H z0m&kNS{+G?tG3iuT(c>?x4E-ZUKiW%atF}06i-ki=WN|N+~0qA>*2%eMr3+9(1Iv^ z>BJwuXgd(x-%l$Vy7jpepFxRVXHkZmyaDVcyZ7@g&@W8?pRF-X%|%6p13f)OsE_LZ z9^gku8h?2WSO;ne@8(3TH7!CS3u%tTs%me#^2vq`pX^WcZS5oMg-}L{NpE5;=gENS z#)qC>wsJ;&6KhFwI(g|WO*G?dDz0(KULvbF%v zrw48&SJ&dw`oa25_356;vz`5C1!Sh?Pu}6OW=(Q%V#~R6Z=X9&!_?v0s;C{=*)=kbfBYCpJ2)9>zFtk*x2?FW|dEVeG!fSi;?z? zm}fk2*|0+B5bEhnV2_up;q;h@0cMX!-hAQqty+Hf3gz)6VsGUb;QxO1~5Fawjg`($axq`_EAMmr&h6v+YfHm|g_b z8gjib{%UwJSH$yTsp(qHMo!ngjZ!*~^^Tx!FIuh_1Lqc`n?*+j>Cb)wfJwZ(G~2|AytK{T$kCzh0tvyWkUr+u~>*-n0n9S zG#%x4o5Da7@&P~q7-Jvjkkcp9!-z$oV-8dfcTAo5(0%+`j-4=d+(Q%ZeR%4$u+V2G ztq!V)0Mn0c+q4wJ%M(Y!mPL@`(pa|hs!IK1>XXV5)WP(Qm;{+#!1Uturlf*`grJmF zDT{v{_@ASulV@c9{(T>nuUuOb+<)8n@-@DE>`!lL^!(9Wm9$FQg5%ZX#Bf$1pep#`cR6{bV3L95vi5f;WF9Z1E(#;r1mB0 zAvl8xhbl;^7?qiuOXxK2UKeC=jj7~{%Jec3c$au?bGgBEdrzlZPlWq7M104ZF3U^x z>IvqvGH$Gy6oB2D%&@BX*a*i3-4faDb*z)Vq^0ZA$EEJ<44T_Vbs$pbHsq!^HWv%k zji_!&ohb`t0OnK&tP9ocA^VHgCWBee6!RKLQrFGtHPR*wty!}(>@7QseGTh+x~lzW z4lPa>uUmZ2Yh)3-Zb-K#Rv(3Q!|8_6M-ko3eaz&I?-XsOfxjh_n*;X5O_O<4oTf6biF6O9o+%P|8DJ`HYBt^rw<0|Qx6lGBwJc;?iBE%WCC zfF-#|s_7=O1$yn<{M>VY|M$Om_uXH-`->MzE_u$P_FKOi9wuxiKR+9C?&&FMYp-gp z?GdKGee>G5s zohK+(7>N!Ks{8naj0vEXpWqA!dr|2=ymCoRZqa0?-~7eRU%h+tdp8Yjw>0x@&+MY8 zs2ohkkPfE9=yi3Sm0j}ybuWKQ)#xVxKAa>+>@K>Vk{GX&#ol}F*16N?uC`?Poa3bbV>D-@=*wy*HkH^A~TuxUD$;`M3Uo)qK6LGK&z+c~ugocO727J9xS0E-0OC zAsNp8iN!fNrS+R)y!>X(%J<8R^mh&pW^S-xK`K!%zq@prDZ%C8G33o;X9q8D@XNh= z;*(GQfa&E6Tu07a$1h;ktTlcl1rhu0w?x9s8f4@#n7NniSU!IjVmjTBAoc5?4;@%C zFF%zv?BTLRb{EI!DtT?^(W7-OS23qI7qvBcHFXwA)b`9Rgqn-m<1IOz1WD!?>)P9M z*`AYF)C^~`wW6sccUP1xr;FA3`wQdab-$PIg=qdZDE$w{@pAp-srDLDDT}EZ)m9W| zXI?aC7iYKPLT8T}-s=Iod(`FV&7Zz`t2Sf-6|K3s)H~N?`;8~VbheKge5K|OoO1c`bFH-{cOcK-bB*xSc$Z654f z_dGZ8%JUz;^zkXu>)v?d;;{=ANa^mA!RlhKLW25f-Rh2eg^8m;opa!H1a*1cDI;~G z928}}&{K)&rrW5>MHQ7UZZ|?axs0@yl8BzDLhrbQ$|BxjF5f@%kL~1Ubpt7qH8FS(FS!x z=|H*#>Z8BAfAs>&ysf3*QPXWu$DTggh*S^UQqxsMDjnS@>DH1Zsw?W{7k_6keG+Oq zx#>VS!RcW7H^1?%JwLRxbokv;)WLKvfdA!@zx|O6>MA6qj&#pA?-Qtt(!a^t{?~B2 z_1tInZSS+9(+4ZIxKD;<8Ik0r3)y{rXZvnJV7HWX_L0uhIT?Kv(~Eofmg0)^+R@C# z+NvsF>@f^uaj{G;hSEW8i`C)b_$r8e3tfdwW1%hB&qpC$sLr|kSp)OSmMWXMd7~4? z2%U#nTDnM`hM~swVqe7Q;gGq^E~A4ZM5I@>`ugsk%|-zJ5YfZ6Ibb%Xud1jmnu^e_ z&M-PN-ff{n)r}`tPk(soloyUX^UUL89Sumwf#OC0l!q6`3y8q)=Nv3BFb9raI9>cU zan56NrUy>ttjESqtz$Vu(OYm#YWmW_jw5pmB97eDy>fFC}$z5 z12w%PEeT97SYO^1LU)n3XjaQ2@(DbZd!$0^ z9Ak~qRm{ai-gg1dJ*;CXLZ}(>o-lhf+fg zglo_QOiZn0M$L4Mn64+y=Sb*ozfum*i-XIB?be0tQ*@O(!{T(^h*sWLP+bZ-8yd_i zVS>X$)5FuLmZ)w>eJ-N9HRZueq*s^QF}H7~AFKn5)9*%gi^_%S4m{U_`Df2eqD1l* zoJ)w;Yi4!^(8cK5=|wWHlQeWQ^b+ZXG3ypiAIo=+@mBF(o3lr6I78?L&pGZObn8%G zJq|_}l|$$@r0ea;aC{clxagUPvWyoFy7j2KeWk6tBw{KOw$Yd^5-{+@xv z#3~poIvVqRPGYA|mRoc&X3av?WA*g+v_6NL-dF2YQsNesTi7#5J*=mpscg)7d$ByniNkZ8Np-BP*rdL?wQ4^5WCiY4Z90=kI?$($$r^#G@)W zc-AZjqDxKBZd1^UiBBi%r700_dQqZ6Ua*F+C{8CGot-L1qjD2Vh#PO~Y-?(-8>zoi z+LY@N6~7CHU$^dyKL_Z>lK%0!kCD^OfU-aO=+!@b^2z(8&zwBdv?SlpWk*yLb4?F8 z9cC@`@N@C3iVTk|bj{56b4kC}d+juse)~r6!hV+>8+UBX&dy#ke*CQ2$(X}4=FuEB zze}-UVQ$-i@zi{=HjvEDRqWICewV13gtpRUxkr{?k;TH0n!!vV$3Zr?jG1) zWH{rIL+YA0N;v1w;JNlddUFa{9yq$#SX4r0YEcPk=~R#Uh|<{vq@q&$+u#nS|Chg! zm@Y*Bt`XCLbVpvg)qB*+OMgq27b}TT9e*5BI+**v1?lzxg)JHVEVLJpnZi{|kD$5dDt%#df{`=@@)a z)A6Q%o8WYYLrvHE+G8kPk~-#eY3lE?gFH9Fe!Ez=9>0YIG&uSQP)*HHR@v7fav zUKGc;w6{Vg7Zh;-okPC3swVT^i8gi@D@`3lr)YGHFJgKK8~dv8t~>CX!`f&h@TiK2 z5lQG+-N}tnFCz+laLvg6Ev;MCp=jlJPxu=hd)KhM4%k<<#^WNluUCQR1y{O^ z>A*TsFUn7k-S#|@j7BoIuzb*Ry*NOEs0$5K0X?BgOdEWJ|+ zb(u8w9=4c|y+>7qW2Ydd^9wt5b!hdnyx4+{!3qIO=!K<&p|Q&`f|fS&t{Z zJOTB*yf{53sbEI+{#Ej(H&&PCG&NN>(hFxr5G{EY|EH9Y&RjF|!8PnGIavoRf9=6F zDD37$9W2zz3m?R_r_(slIbTD_UML~{LAF^f)O&0py|5l!$axEAvbR8o3)xpQ-|-L5 zPJVC!r>d%Zp*C_6$3Ju7*Vb^;x(3Z|zxFlVEFGLRlE-sMd$F0bxW}(?Gc&)&eb3Te zuX&IIF36c2FziQf7BKIa8{u{qVqnRaiN!qHd~-TdiFF;$)H9g5hMTpX9(TwsIX1t^ zC_)FI7pUvAI9=Fe!4NEj_eD}MF!j(xFrDtB%6Ktix*&bk>Xo!K5~s6>o^Hc1m`nhR zg@zVv8Va^pTG@!er=dAwU5pkB+KUQ>h2BQ61tlFY>7aD!=a9M)vdxXk)q*qKw>zzSrDC1x!0)coCBt7JVXVl%+iLUhLVKfwldN;tx0Q5}I>RD$EeX@1bi?VwbcXm`oIbi6g>dtra(YqK;pIyzKLFEzcf7f{xU;$0 zb(e?7JVh;=9FD|dFEl*V^I`%{A}Jy@dOYQ%orrUj{enFhu8~=y^s<-%Xaf1UbD%P{ zC(CW)ItQk=@7gt=zvUiFQk!oXoB7QfLvqB7jx%S5ehH@E8aZ%yH~lyRe3$Rq;fd`e zw{2rpf31b-Z=Y?>ZE3>%pjJlKP@vaVjorJq-p>zC>-}4(BkfTV%$5UC`t^5S`{?Z1 z&(58A=d}a#x3>1DX8X%xaF|l6!t_YDRPyw~`MoQyrOpbI<>kNs{`YS@7w=V)LHA6u zUJ{wG07j9Ku0A*<3Tdl}N0{Lp;5Q4C-@@4qZjo$IP!F1c-hzXRX6($}5$xOh_rJlP z{{5TpULMBxefDbe02Q{3`s(sh{4NOTF?Fox=By?2;A$eZ8~VeeqIP-qFC0yGLEA=2 zuS|7~9_YM=o__0GXO_Q{o5$|mTSn^Z_c!IQSr~Hp#@z4!59IXb+6yoKgcW(Rz8Q0R zQBG9x;pGd0U7S4&qjEhlJ5Wpjr)A<#uP@ChV(NuwDWHUIvOZno7l7%G%oy$D*d6Y0KW|pG_fRqQ9RXUhSIfHnDmVTX)7Z!ywG1!T z{)n{nS1num^^-$ooirXLpd~7bPk^(hTP{)LE`ELi4dJ!5;VQIjS|8I>d+XNCBj1^O zK6{C?lP8S^XmSLm2gjc>-tu>^weH62N%jpJV8C==*`@k@!=rg`WG3Qu zFJUW7dhfMuw~n2^ar@YfTiZ4-t!<$AfGiVo(iQCZ${TW}1L-7)0@!{&ZiyLAt~3wB znG)%tycaAr)R02ozDVUVX(6NQQ_B`C<`|^CkP2$|93>kDpNnOEkqgG%Gn)3fU^;5L zm6k5U3!hwcd6&udx4|7uM@<)}%flhd3zYsXdXJj&QCg4w-QWH5Kfm!~EH7`ph%w#a zc(H8hCgSCPih4m`_}2^@)TNgH--eLgmeY;th4q8)5t2s4yGFhf8>XlUNp1W^T>xE;)Agu z-PDnS>B@sK-j_XA;EO=r1UL%P4X6KW(q8N*PGckD7_ZTFl-f`cI*6|3qxi&#TJ6Wg zlI}op+LDs)63*K(1WM;3@x`2#W6m~FjSV``7z1)AH_l}fq zh}{y_Yq$8$oGGUcm_BAQ58RVrDHHuZ89lvf%x>RsYGmUpwhV?A3clBi@yKB2y>HH=6CXo)e{|y1 z#ympOV?$#r22s`vbzA0w^0}`W-Na>LYTZ0-T&YQQ?@22bet; zot+~2qBGr6T%7%8yO96uo~%uPW0EOenLoDQQ77Y`?C#>> zoIKluK6GB`#f6Fps)|&5L$>9)xI}psd$?1yMO!x??jV`IaQ*~d(KXQ{dBOO}E`=T; z3)rL+&@ekc-_JQQgUy$G^LiyGyYHCI#b@hYlGiL8zkr7qki2k~pUc8EXd)rA1DpcJ zxcdYI%not#4DcJ{ibRGjes+MHYq4ht>9p=hW-d;JPVTOJFZ;W==6WA!m z2$*yDH#LodYmN%Lbu>tFgq%xTbRzw0ZO;h7!lKDOgGN-g0QLM z#;Tl}8LsBB;&U*Z*^KpB5{jFX?6<6r-!(>8i?w#X%IOxP3)anCgvpN9q|EAUe6X~A zqo3bJ>fR1YH-{3`;dPs}AI5+LraMeX+JwN$G?NfZ8fUE=wcH@Nt^}!%;<;gWsp;(G za^b?(&hYuDnl4N?Yh8_}^m1tEH4~|8Xa=N*!Nxkhy$p;C$}R1SJahm6AOJ~3K~ylm z>nP`IPH3MYwOz-}c!0N|B8X7qWp3x3IiqU&co$a`IV>-Rw4nk|&!W!s!o$J-mA0JT z(o|GA4`V>)yi9)Am9Fj#rn>^kh6>(L*-+WkegHN7%&9L9MCH)Oe%<`T?F0c1U%rJc9b@{93$&N~V&n@FVNQLq z&h#(3aqYl?`N6vvgt#o*UuSMRne_I zI6V7)@tY@6(}6P2++D6cJw7F15l=WWlJ7rsb(3R>FMZY;oFkYX^2da`xjVbVeV*a9 zWps#WEb(8yyHBBvzxn>n=S1CapF7(;+}YCHj3YfKr?|K&Cgv)LPK~T080lM|+R)QK zKv63ZA=q6^x{Fb^hleYh-3~`pMR%5+Moy1uPR%HC^W7ahI9Oj_mkFo$EW7>WTmR#& zV=7+CMx$Omxt2B#6${Ky_#xD6sMVimuSZlT;;oi zyFNN`;?n6)alM=+6LYw^xvuPLXUj(?UcU4)YWkUvvZX8gXJ-2QWjlkQ?asMP)FhU; zWoBpZ0MZY9aq7&;i|kIm_s+hP*A<=K4wOGQbEX5)twSZJAKm$CsOA}H!=MnmfjOi=K~O_uAX4JpKl}){sB%rrQB?6 z^w@0+(yzt$^b0x`ViQ`hJN|+={l7~}KgA4lOE?~t0H2H!+7RG5_jK}%^m3w-l&}_6 zi2AzAcFs>Q1Ycat=MG8S*|jhdOec0od_G1Aj*`<&#)}TexTEX4%|k>l;kA|oulFuf zZGMNjW&8W~E=>QDnr>mb+|@t8n6B2NZ~U{m8ew^HG&QoMbRtr$>QN)7TL5fx`d5rE zcWLQg0(arF5z}$JNKhA}|374VA=XjD$n@L=cPo+qE=U)iYi8kqbhLC6FKPC*Y{}|k z^?#s{^o{R5@?XF8qZhvYp+Frq{Rex%ZcS^zbi?RBz_zYzMi|`?Iy8@*{iV|r-C#JWQET~>iWu}bi)%ZonbjvU~bNfPLIY56YkDTkxX?< zO$XFDlLn@=Fva8!p^u=X<4>=s=#57vrxvx9a7FUiwNuhcv_M=O4xw|j${5HwfzzoZ zHH>bbC{X9GZ!^|(;QV#z=;y=eMjH0|`STdQj#)aowSR4t&0Bj%Q(u(r;yZJ9KMA?& zzr+@#!YY~`FC0JfK`KAoql?352Zy7k$B)DhVtF}vXv5Do{Oo7m)k7~#c;<(XgXwa) z5Vi=aLjhEj5+7%hUdG8FN~fc-vaR1c=^^?BqCWE5C@L8@@xDm~c|pSTW6|4Xdf7$+ z!1nE%3doWs;^k`D&X$g}1aKToj{?(YRL7)Lm#?tY^q9tK)O5V*-YJX!Q%o-dLAY+h z0#l&LhZipnoD{fXaUfVIvqef!T2R=ERY5Df=dSR^4!kmfH1L%x)AAY%(pIGvl-I|^ zl*W`%M7VM#xs5A>g7V5jtMgW^>L^&Xs-PNti(R>R?utAX3mWr68>da3IPrmRe0}1$ zhrata_rVzB?wvAsRY#ilo^dI$E4-)8<=#5V%IfR)btjb7m(`apD=*E>sU~wKv@CSl zrt*TMvie5S7@xU!t@p~6vE`cxwA>WBthBy7w4MrkublPu%h<@9Q@`HJGiFnHQhAVf z(5gUh9%nUMD+=<~&P^*X-&D`Zfs3ZC$_rXW9*H^sy)5r;w323BBePKrv#bmQS~*F=sOz#Xh{eHYQ!WZ$!+(Yb5#(7mk>RQ!HOwafM2nvyc-M8fDa`=z zZ_8?7!MWVrwxny^H@Ygvxm&63nxvXQMkA&xc!Y<*o|ZH;l@MPVFpfAMj^6mQ5=B04h}9q0*Lkj@GA&jzRKEY^f$Cj`GU42g@zZ6e1?bLW^Y zrgB^kA_o2ip{eQqF_ZZWdC5#0t)kTqh->7(>* zWOGC1Hk#|%GaSS&Z<2js^AhpWm{-A|`oq%+=y9xfK;7bW1L_V+H>-Foak7`YI{SD;MWv?~d3pL}rBUS5^TzX_`~3Oqe*gP* zzyEkx-t=3oi0=LUAq~zLo@;7=sJ6BPo&&a;e*1C&f$m`V$D?w(kR3#418!gMRus)v zECgGDbYG5aJb>rri>p^ZxODEsiC2$qeQEc?h51XyPmZ75+Dd(rFWOB=Z8(ys@9YpD zi)&Fws658#lB{{2yEgg{r-C}pOh&>ZQ8ID-6i3mLCjb%P!3XmLoCd-h#?a(QvmJEy zs(~0VeQ#5LYwvTS^fzrx|KQvQXPYmR6k0_hAw(km+=^;DXAHe~hm)Z$6cw>{|} zh?lXu45wywHW8*+RW%$_elFqG)ytKY#l`NsckduOy|hzTjd=F&=r;4q%>zBpza=^S z%wRi{sYHKgyw$*>va)?LX$0!S5pwywn(B&bnvkj^BYh$_dM=+0i(+7J`(M91ap}_S z)2HbH)pzaM)ub7pCR{a`e&P>!&D%F_%+1Ei;gv|ieYQt?9T9_Gnf|m9-LZT*uPU{p z*P-Z>Cx_nKm$Xj~^($XMxZ@X~r6Whf=)n$7uW7;dQn&y3(dMqswwgAOpB363g?!Gu z1^W-%F510v+nR`PZ*Q-whtUnBzyGu_edtOKE90(McpKQibYR2!$N?pt+j;5Nzu35= zsV=gT23if6M_^$uw?ZK+{bYUIkskZ2JZhS>CG)f zmHQB*o{`wxoWIa_&~W;V=ZAZ+NcE7ic3(~D8kJ7O`UcO1Lb z*V^C1mf;6+^XE52diow-M{wQiPhd)qe~B8oevHHoJ{iqL&2T#NV(NVhjp|J$Xn^H> zK~86pxuE=3t|a#}gXVMWgoRzHF2xO(D4j*y_9BbV8{c_^HKU{#Al+!?>Td*e|7Z^ZXV1i)!?=9oe_Nmt{zG{2q?%>fwZJoMO}i3F=pocQ&LV;>F+j9qpt zHZ(7N5MntNN@_ZK`u0ubWic_GrTa@`3Si;t>Sg8Wc+(qiC)Ka$C=bdTsxC!qsjluQ z2wM@BlD9sl+rV&7xSG~TxBd>dPS{@fF0L|0VbU84c zPV(h>(;p?q60jKe(AWRwArK2p4_vuw@w7)L2F5Ms{($Dj^7^Akt7jzatS{SNwy(N$ zM{ap{*y3u6G&j{(rzMpqqy#RSz9J#7J8fTm>85IW^p#R5RaP34Q=A)9Ushh9qlkl; zoVxmQk|oJ~XKuk`SiG2!`o(MWs;kS(t5>cKoVy~Zu_KKb_?4@;MBv)6m0Xm=z$i!3 z3x+4KO|1NaL+q52t`Y^kBY1;Iz?AuVQY_s^h3E`IITi9^Szd&L{D-X$n>)#{F0hO1 z#bCNIaUcfU3~Zgj8c`67F=KGwAUD`3^5$_EQJoH@SScjjBFjV1B4>%ShRi3KjBk0@ zISOBMrh!4TXM|!S!o&a5rkmnX0%)-I@St!;v%N@a`owz;pX*Wa?-)k#7pEJD)fCRm zK32-{qIh_T=>?%34>P6Z<3M=IRExF=XQOE(2I!&N{htl~}X_%P|L~beO z9An0;mcSOTo8vaGYyHW8hNeDU_LsXrU2RGsb;#V>uwfuwoX+6kV@}s>$Rc&!v{{)J zr)xDyOE>=xPUlJ6pw25{fx5A#TecUI@M06X?M>(9)0(y?M=<)LJ8HTmrklHGMx*Lc z!{n0F^~Vtj=K43sM*&?6GQhAWn~M|z2@7h-rgx?p+T!E*{vb}!!gOPL!N!5lAUZO# zXx@_i)T?0nzkJZrOdMdQt7k@*(ipM5coCisqZfNca@5T>r=u^UFlW$@)7fLPJDLt5 z(*vEC>tbRCeB7Kfb5Z^%zXU`RcO3ZQ%6of1{q$T{?txtZ`QecM-CIAtf9vpBnEan_ zU|I*>=gH#BbfoxBb@m!T8;~$wc4UzcpAUnEop6{GE5M96xvN^a;fDqxZiA|M#TMn!F`= zE3|8L(EeUo7G^J?t+tN0ZvM${zW;7tZ4t(Lyy*?YuDK+GNKIGn4OOMZULGOX?q($i zIA^#GM7zhXkd7%`Wut=hW`y*X=B|?BT(79;TDO5RRgsom&WbD!4}Nd~ z-)N;Vkx*alvLpZW%3HsDx33}MMZ(k1Ts$*)ILg@>Bu{k3nyiEmI9-2<#5p#_)Rz|3 zWcvG;6cN(WwLEzClCJUNUjoxn(=UB``}AjL&)&SXH|5}>-yYn1{3A}ggz1H-myOvq zHL6Fs(Y+Q`3~YapQ7B>F-~B`sB&gCzJMlx_8E}FJ655;yVYHFCYIP za4tw69mwgqEp1&b7+;XnOG>cwd&z}Px$;0Wla}UY!ao7^qIRq_BZkqH9rOOhix_F% z2iU7iGX|jl*GH(oh* zjR_5=mRrZjS&SveCH6+gEl3^ju0`&7x1W9Xb^#}ahsevhFyAG6Ru@@E8Mw~l2QLg^ zN=H5BZ8td}Bz0Z}Q?`<<43bVId}BPPsgY?=#AK45MZW4y$~J0GK4|Vtk*WT`0>jo{ z<9cyXKO_=EeO-(_U2%*edQ2~g8Ps|^F)t}(8-k>C>P{y+l3px4l=;Fz>9Sf&OBbd; z^2mQv5+hRjla}LU)R&Ga9mk8^)JWEDhc4~V(`^_ZMREt4e??OVogMX~0(A-B+GALX zx(R2r2%If5qbTn9F1zdSuJi6RF134*-pP5f^>o|!q6cdX>XzX}lx~_F5uq+r*HbhH zGU2lzHQiu3()lCCoBqQ+-(r0c_43FM=y_y}E;g(iZpW8yxn3Um5o)@+9C3N#UgS;( z?#1a)I^!=>`lvU(?}E}8iA;yi74o9)L~Q=60I$=<;b`SK2DrHd26TFoQY*?O!Dn+m zEZ#TL3zaL|1xhC_MWz=**azY3C^(&+1>`o1>wvR3jeV%xELsP(7}w1y95wLGg*cnu zM#sWlH^JMKkXnVLDC@_z#eT{4^8BEt16AR(XNE702;Z%+MRvH)XU>#dLTlX+i6@kg zE||G+4W}-g-CvkaOng;qMQcSx=#XGK_F0m?r|_GPlLcI`#B`Clw$@7roO+KoBeP`x z0~U|->nK-@elZ{0L##2NF=bU)V4l?Uyo$k&V#nGxL1!i6wn6hHk z$`x@a+iChsgVodGQoPe49lUSnQkb#>CF z((>-0RdI{sp!v8}-9dTi?jU_*Bd4qioB~16{6<9h^@$wLd2~V`9e_4G^XP`al$B{S z!ct~5ChaWU-`JgywDU^&zQ&{+*Y>2KxH!Vx^E%3wkz|>WFk@|85_FF3Gp95Oxt)Mu zMm>)O(WxvZF|#QLL7ww@_;WYR1-|u1PJMOUVonN53xmj6NXT17KUHte#0Z|Ua;2WR zcZ!Dt(&PN#OkRFm@F7(1Q(dx}Tp{(xFnk?~^5x8gw!ycgbx zw{ncbyS8X9I2CpZGz|p{*HjGwsPjgYBF()E?985_Js?t{pN z9jY)@-6AfRDFC8DQQg4=OKKPEE4&aLUedZ$cr!r|EAyf}z^h|KbO)bXhq}7Jk~x9y z+b$p_<%MMZH1a2zf=Nx!!&AJh< zGlc3I2HMREvyK~-*PKS@=yFU;*v_E*8G$(iNu8CWY#hs{E?l=Zamb{u4IJ9R=@Z!a zz#gAtGA~m$SdOC@!c`Y#c1ik0O;wO znF#Y9F7$$sva&iisfZLg9Zb*iU~4&cVJWlV0A6!29l9x|!x7bM#6-{Ao+B?CJ9l?^yoQ@7MkBkNbXg zi`c?<5n~OfQ%=?@G5zfDLcas;ZCx;IYJY26TTxF&+kv+BbP!fSFSjp;A4YoF`tjC} zEll5XfBa$8^sV>Dx6*nves^ny6q+slgr>LBe*Ne>XWn`B9JUj3US1pN+e#!^Pgcq4u0-}M)9`VXDjwZqjJM>0BUCS+Mci+EKKDw?mT4ymIl zGkg3jzvjr)S=q_K3%a_pXU?DB^}odFzkc@g>CbN64*czg4gdJt-yZzr#HE*o>DS-C za&&oic5X?H@ZQMWRC8jmPef(kh~wpq>P9b~9ID<_7jy3Ps+9LnK7H~1FXoRQFVD-D zFn#=z>>AYRqky{1>20}9?UK^*yhLVbPRD5DId5!lufH;6oGt+RMYa)WP@x*voz&Sg z5FPawV_u+k(-!GKZr4Z0Ph9%sWu?5FxdQW#>?r0n498;B;O+#%I=lE|aC8os+?DMd zK0vgchjUG)Ph@&&{nBfj@u&av+0Ef=W{J|fNMh_Nsl)}9(bimPU;djbMKM+1uyIS_B=A5#=InopFrQZy(znQQ^CWA}h=;sm{5%HC>fmS@V26RjxM@ ze^@|@yDK0yprLX=MFmW&d<>@JPjRK+meLi0bl3$O0DjZSPHeXFaE8;}xIm;=A{W8& zBF~GKu*g8|7}Ul0;f0izF!-EE6bm{`wGVdg$nF-5<{;r1*+nVR@B>>9jCHO9#>y(2QVmKYBWd4xGveNSE^2XS-edX0j<@i)` za?0|$7q3{{T`(k-dPR3$cWfh=9-HDFHto@|d*+OL^d3R4S)Ft4d+1&;{bv&%9k*x$ zqIcSgz!{Bdh`P6X@4lT$`_dY(uZ+j|)mDNL!n-A|(YFk6V?N5Y!zM z7r0>>2%nNd=Ol4Di`}s<)4}Pe!-qWzkup2iZwgg(`oElODH4$+(u>E$Z$Rl1kxliQ7s=^PP^>6a5TiWCJ-W_Dx)m|l`g-iEp1t5_MRu6$|Z#`*FR_emYU`EERg zegps>p8xy#tvcoMaDMhiT*>l-^wbiHQaR8DF6Rtf*14$ZzEplmY0!5!KQgW4aMXh7 z@wK)6A+;5~wY{|=yNBQX{+p=j;hmM8#qI6s1H(-wkI^fdIZJ18ktdlh0e&t{kr?yw z5x6^rLr-*{R9s1W-O(#M5B+w-;v2HN+~{lVyKw_SovFuXADlkh38lvzjcJN0ili)d zSQeMg%j?hH?zkM@6Vfv!<{Act|Y5Of$MJJ(J?9_J>79GqB1-qBXvz` zb4>mE_2Dyj`$k^9{lt%d`4)2ex??ZGvoD^B-&Gi({Jk2HdX|KAdfJf43_l zVqt-==`m4MCj}i5q@CFJ_BJ3LNrdzHT z)bygZqx+9{wV{j^%Ou#*Je)Zr{L>uJpx-+7KcU6kSOVfW%^EpKy95oKBVB zmeydJ`9LQNIoA!t%RDe$FBc!K!lFVd!qkt{1xPmm>SQePhdEtoFZ%QbIAb;!qH9P_ zXW&rB*Ngi_winMxFkOvDJ)rc$aCbdh7#@yym|iR;*NExg{D$BWvG<#z^dH$>jlTEo zzf;5uO^xpIrAuAbFpMrjw_{!$mKR6P%P6LQW#P-94nEt%!RWS@&Z;rZjvN5)ICOlI z-FGbFRDSPHJsE!a6PcR1b57VH^?5z~!n$EI{M^DxWuz*v-So-FnkgXvb%%MX9> z!ykS~8`5u?fJM~wKN&x>?CEm%V|y{NjOghOIo(#%S^olcrD6VsVLwSFy%;gwV(@fh zL|17j8ah^Ud#B?Tw*%>bv#_?JqB!2@?DmD^oY4*`9Wh}z);Rx!!{YsO>iKy^*dZ|Vi>rSF8=xTJKdMI{?-|uI` zrU-}(H3=B_*=L`K7dU*})Cs7AhS7Bls^H`Y_rQJdFHhQ6eWiYXJ?3vV4>UHG?;FCZQr(D_UEhv~9hQ<3*4>!4cFKkgDM3(uS$SGo zw|89Nlt(9ydsI^(k=9sQiSE1a(dj9RCoLL_nocX!w3H1g3H$c#+_`VYdpma~HFh`d zEInG^*xlV2+a0)~x~!}`DXDB{+0nA3(wf};Lye^y(a+1vkVX6oX`licq=5PLvO0N ze0T~d$Q+Q2N4>$!;Js#{uu-eQVoehnAg+{X9)fu@YJMmgA1veT23`usv8&KW6w8N( zRCT%RX+AG0P9eH7B~;&cb3>o&Mm zgS{r?g+{el(~X!;1*w7<%`h`tYijHGVCmDNQ+OKow~;Pno~Om@)-}z#5w2UrZi6`o z4EuuOb~?q^^Ixf2_?G7N0LNFVLvxMK3v17Yo8I`Zf^G zdiu)XB201aK9O&&>0x=Bau$RKM>0}GSauZ3UbPC8ti{*Yv0H55w(~5`unl8*DmPq zt*ydmjBEbJlfSw7i^1^Lo{U7S)2;pZuyc!u?=EEH0q$OuOcfv&M@MR7LQi<4o3o!^ zO=A1e{a2Fq?fvAFLyHa?v&-{?TZUWXZy~7v=H|PAx_TUSUaf1+ENW1lC>bu7FP}Yo z`t;kUwTx9?LFo+Tqz})_Wc6m|5?ILAjG`hBzv%5a#$|iCJe=xQ+zi;IFWo*^v3quZ z$nfbS&)#_Rt#?1(dg|EF^Vri*ZRzhJY!N@XvrlGjW~K+5KKOSfNwTT5Y=3EKOyc-t z|6I{?aIjxMGK%-cwm+Wu-S2+=`fbGgPk(#p<(E%TJ!%c9=_jvHLdxF~wB@?Gc3ezf zl(ubbQSs;jAX;veD@XCIQ=^&MP|~vVB=L}<&cD_u%MQaT;oiXgq8*#wSxFY-A{N{Xr?@hU9{UiS~5Q$+gW z4P?Swx0Y>M3hMCQi-;f}JvQj}v$wIo9J>{|EXD^{(yUpt{4-I|ot<|uU&>$uM^*+$ zTzP%{{N&zWnCv&%*~2x;jY*Xcb=w)dRD`-f)~=dJ7_62?jys(s^{Pl>`aLsU**fB% zSi~(^PsY@a>XT?eI+PBoJ7*-~Su>UwPfum5n-43qYTNYkpy<$sbSNENSd>nhiJisx zgKuMb!I=JIsztX#Qm_{r?E*wwf+b|1zZ;$o?{? z-_7NJvh09(hnNnmn-Wr6N;flsQ9WG`$pUpY0T9S2OB4hIiNK#hb^CcG;Ci28PAl za-!Td?!xsg6>Nu82&9A3Tghza(pxrfKlZFQTy8w+-skbXDDLIi^T$GQy^Lb|;Q3=x z?8oo|MQ@L&g3(*6s`|-WT(B?%Zx`nDeuL^%T!;8lb;0Qiz;wJkj(lm1QYSm1> zAld|AYtK7N<3K!>B17tXeVcDdgtvG&Jx=94~3z-N@;S4^89z#vzUc zHSViU%Ij_{D?MtwCRfVqOOx_I^nF9+c*&E}()JB?cXzMu4g-h-7lX=W^;fEg%7@bC zZkY7cQ*5fZ_o*qkiJ`)W9(wGdd#8EFg>88BsY7d1xbc)lYtxc;?tC@ry`A)~dv9;! z&ZG61UxpH5rO8**C+g__@||_1`6Fl>u&KcLE=)&9 z77&ZJrkG6tmWnCI6Yl|9&?=+zp|KC6CS!RqN;;HoeCeWeTW^)TDzp`+>y0LP+(J^` zbYQzAYcaN5ESwH_@%r-w40Coqsb zEkw69bzV*LXCb=fNEfIZSRdtdL+E$ZbW-qbPS=a3!3!~Zr_6|qcTOweOXEv8ZqCuV z(<;@WwXUX4nH#$-#vMoBgEJRS&e;^2Hg|$KTNiYEYm9fMpv?Tc%6bl^dwM$g^fW}K z^HqM%QoUPRK$GUE!)~sbZp1EUl|%xKO$59s+eI~`#-)vxOj{ohkI6eGA9k;r?CIW+ zRoQ&GC5E2%Zt8rAC&p<2j|fQ~EgxNyPJiiY30$AO#N+V%mp<-04Rqglm!KEbkZy$4 zUy?Qb)^L9|PUzqr*}Uim`=mH_+9OZ?r6m(Cd14{G zLx(o-cktj5IQ>>{^bQO)t$ptT>NhcyoIQIv=5lXuCkAveIfPE3D5avR7G(hFa;2+q z6!%9Z)t*HJw&R9}v%TD0inm7$TvjIIwdTr!q9Qtf4n(kZHh%ZQkl|~$-+UHJ!gC*g zd_k_47td6*I%OymFxR=k(}VV&o`kx4N{98xtlK2%q-n|c>>70L;PJu9$+H#&FW-nc z{nDj>47`o(|LJdEe)`g-mp|cOpf1wAex)5q$DUr|-&A^(^hLHRZpPzg!d;D@{04gQDGqSTY>y88IM_(&z$!cz?>uOGvnjWRB z@f{lvD46FYLOM?L>nG9CPr>1AQot<5;4H{Ji46>ib!Xj$ds&-S6*Os22y;cnsX zxf|=sHbwN_c$2u7TLW1axtMBm1{iESjri;Z8h1itU`ch2;zadpjgA}%KrYfENgac82BKRu%;R1J2a zz(X~m#FhD|h}4~+B@%^b9*Z3v@bRqjx~v^0|P+>%M~Nqi4wSA|?HfnvUDW7}MoUM+vub&pB`)xZ^wQPY#WM zu01Yk9k37MYZyS+9{1yTD0UgCnOxWp+*)?Px}4J22ih5!9tsmVX zbH|b`uw#d@DP8{bJwJNf>PBin-K=<~Nne-m8NAqUKDQ=tDYooVR)dKCk7dFQ#;RQg)pN@_WsI&7vANu_2W1)T4^|!=t zKA*=eLUO{hkS7VIbh7 zC%jk3ZkL*VY}@wjY`DPmvT1!;+Nvbn>13TGh2q^VE*7Sjm90o9FW=WuAJc@;eycHI z@$DHaW~ALt`jhwM|NAGbaqG^j&I{}Aj_bzXf)fN>$K8V5+}(XLEiJZt@yhO$z__qq zCy3f1_`JsMm1$S%OR3FA$gVG|uI_FOy;9vcRK72EW!%Z?wC=p2?v%yAddfd~2c3lD zsiED6ZN+=qq(>)CoPZ9@TE6e=G}D>50rpwB=&22dQquOVjEh^lp*tz*y@Xd2UX_}@ zZ)bho(fwG>_o3Q{Rwu;G*x$6D(-@`1w&j#w8A5TdFD-v>D5&C|tmlC(Kdu8|9X%vVaLN8BC+nG~}&VFdxA+{0(9(rorqtE;-aP8W;8v?rv z%0~kkc~1ytEe`~4?y1(B0tNy(4W&y@M;jKV!{`)`u38PXl!vbQw?Ygv1)j&U%YHaJqlcrDQoy`3huRU9jB&OfZ>DC-V(+JI1#ID*jAgvle zR~IMB515!%V@>zgq*f2vJZLRx2)GTUOAY2D!@vEWHk%`KiZz6n4AHtZ%=OIL8r`$e ze3a1dELg1WAayehvAix4(0MUf5uiH_nGC0+sRx?bjG$RV{u6U!%t=^DoM$~*qo!M+ zE+W@X!_v})?Z&}wi|Jx?Gt4WlNs*=p4mEv|S^Ex7w=6HVRmFPd+BXwHEoj=Ji4A|F z|3)siR?k!k>FHw@EHs;YzlJ;!5VbvMk`WoWisM_usOiYTPEPW&kgtfP+RZJiVIVSU zaQjY^$%yLR)R{=Cv~wanP}DgugFc4Hx=K!`ZY|PSU?LMEGr;yj57cxN5clB8ekiHU zEtflKL+ay!n(j{982sGi+?7<~K=_xJ|K;U#Eg+{~S8n0%ek*%%vsxdWqU%vtHu}2y z7dR_}Z<$ zTL&xnIq9X~$g}R%b0^;Z;M}Vx-g#$V>&Jcf*Y@@-98NE#c}H*jmfqgmZ{B$K0U)RH4Dk5n=?Lp8!Ni~$5E5+ z(h%9c3-V8-UYBW9rrOzic|=7ltsOv4zlA$JBNB&nergUs+=Km?o-dz1_~tJGsekzR z|NH#UiDeu*wZ$z`Ep~je=CLUNKaOXv8@*F=os*NBfOL$A&a<-pvuiM-1ShNi(DIF4 zubnt?;@984{lVLxz5VIaAi5&cjW_+ob&TgQH_?l`+S`}6myV3IgU(0gOKSaK`NP8r1^5hxG=o{y6)Rq}f&%+c77$?kob#1hdqVRbgv7DT^?tq2zTXLvH zT?frC&+Z}yp2z+NVfytiM%s7nnB2a!erZf(c9D_VVLj-rmfnnUIj# zL|Te60E+O6-fI!H1Fij5b5i0im-zEGn&h461k=YaoSE#m zW3q=Q!DNYiES)mcgVdes4;Y{X6Rt#$!{C0eS{e?qVUOcZq z1M50sQTm?+b%&a+B2qnYhW7N2r0ysowIE$_FA8M*=O2uE)2Sl;5aSDK`U7l**z?0j zkkZYNp3bt4L+JcbM2b6xofV&Mw>c8r8+ZCQaJ~FxNdGURC8UGK^&-jKvbjWv&>{1P z5j1uQy}%&)79@|k6#VB;?dp*J(5AMu)n+OKlD z1Ju#YjZsDQsm6T67pIyNZQs7_yf;*ipe{-`!n!x1jEj$LJ0E*&yDCLxq}g`TMM6Srv}F@6M#sotCT28;WtfL=SEr+Ex%7bTKT} z`<}6|lVDuUSR+NAw3d>T~v(z~T=- zob&`+*}dmZ!k)f8VzWY|s}p%tRB}rMA0V_ba!4tT3&beDlj)Nu)BLD zk~D7bl(@K*lr)MskLDyANFPcV!mVCi-H1PZsBx$|EoEhO(#nSqd9RG^o)*`bSDlm7 z9#fu|7DnpIlyUb>#8ge|`p53O@3H&7K5m-#hDm|bHejmRm&80JWy4-X^u0-Y_wIWy zY2VH|Jdy3$xoG6e%CD@iZ%jivFQxBx{Z4^+&i?A|wQ)m9`>^LE)wgFR=VDPmO6m(u zUvo=$Vr?%-ONq;in=YYzap0kp6+nC5K2-aHeT^$qyaU%V`$!3Vbk3vCEYcPP@09N9 z^5pUMH-j+U&>qMp;{xLK#65`T($d-50-p;r*&p|CUTB9(M@ojcWIK(brFbFTXIaEIYqbPbl!W0m(3$`_*|sV>I4og z=Zhe7(v)ed10}dmFkvnZ9<`X1V?t4eDUan5-Af7SLzrmnp+{vN8PE>Fnme!{-IQd4 z={S7k?^%tQZnhs)$4=9yMGx9QCb!9ukZu%Xo`$u)?x^YJggbkzQG@LIR z;dEAvP}_oT^m3W{^->xSk^Q>L5Hos)xulWObv1+M#_eKW7Tt+fwKjJc`Cjt^tyfLk z{`~mr8II!y((j$*9UHnnddva>5zNLPnu?JwF*_%3iv6B({JO1i#`2;pMzRHw$1~NI z$IZ#7Au>FD`-S!vJM5*iod)w6PKh`!Iy>2R9*NxrO2^EOJTAPCbd~89L={p1QS#AZ zC!m8*3u?NLXK}Hob2#>ONCFJ&s%+5&;N?r_vPuS0yIR_o_Z#Rw+h;HxHN9)&j$m2S z-@M$vAh&(vj>*{@5jw;fnO=x^pK^e{k;jYwx`C^vS+HYDUus`WN<;%A|nu-e>$NM8puY-W!ol zzv`_YzYC?mxw_u70YWROaqCCjtYJN|!mzwh!WRjolZ59)O`aQIvYFiq8ur=%wIUbZ|(Mqkgw%8T)lnd z&0oIt*3WT(H6tjVnz zADo?>oIeXSUBT%m-k*N^?YEKB_adX8IDY)M~Henl;fu3x``Eh(46W3p@J5v`t`GxYiA*WWuJxgNZ~Bd6n2&(3Z+e*D$O zr2Ta`zQyTi^2^zg>vCmCkbeE*``1zDVf2m6)tDR*{B5ituI*o(K}{bz+QLQ-!hQtl z+8tQ8t9=V)1O!n=c}@;ahSD*-T)IU6R2(l?+7GlJc6C;Nj>7cyF-|@{sOaiyWR!Fc z1AGGL8O2r$Pgf5@&nYc+_DWY&%Z(%7xqXY!#qf+GFAvwmDAIWPceU44wopad+V|os zZ#?<>`CGlhK3Q}=#d|p_;jm^^p2WN)Qj}=zhqChpR|nRCZ)x|w^7e64ZSZy zYItmIPs0> z+5L(WU9fvWf4G9u|Kg}>b#E=?5|(7I^ciYEYcC9jg6M|OUkBCClf{UvPBCfT=JUwu zZ0pnwRve2xzn#*4dW?poFO5J=j{wsr(=x(6fIlqhL>~d^;ge_k_VX`BC$UCW`}B%! z)vJf{hQjb<1WqAZ0tKDz{_wd$0f@!MbUD_w^`5;4(9Kx_WKbQYd65kB08K^qP<8j= z!$+n}ABruAeIhJ&dql)0l3wtpBd4>Ah>0mnNF$VSe?eY#`LgQjO-1ST)d?%hI@gya zB$San+|;>0DJdag#mX5g82=f$=?^9skfnmRC55aOOzL4PC8Wm%;Y@FAOrWGRkW$M- zsOtE+yH_0ocVTK$5GmcPzk(&bu`!8!#-ya7>d-5Mo|jj550zD?1kT+stvfa@uO25) zeSK0lruPj~COkR^GN1Gm6Q27?+52e#03ZNKL_t)(zUQGmk4^kp;3WCdQPXjz$EB@Z zyDuqWFTNK7c`>PDGv_ykc!2uyO`CFZ>XY<^-&BX6rF>^8C+>^Gb>59wo|aUXyd=A6 zC&GPM^-g}Ano6tprKKh0B@87j{@Dhe!y%X%BYIl(zM;6lII3DP<9j2td*gX|3U7KK zn+&{}nRqxboi~G^)%ae-vxd|4CNS8E0Q}H>j~T`s8z|FD&}zejwjo+#y66tBGjb|) zMhz#NE{3EJ&BG3zix(V>$q(<2Js}U^;<`hOfnt^0k<-ZzGf&=#(m~ z^CjZWT^t+Q;cfCygrY)4VLTTQui7VY8$xR=GZXH?`u-=BZq@*IgSDNsc2kAQdX$)M zN@Y1jOt*qw3RY`UD{G6{>9b^po`{~s1K+*xyKD`B(nr;FYF3SN$V_+~yzYQ?GgHWkEnOwd!IBFSR?9*j~(Laxz_#3%hydR!)@4fT|FjEVmI??Ky+1TqvD}@)q zTu)mjgz3C=qHpjV(cHGTh|^Ki0K`B$zlH4>Vk~;s0>ePM(bFvrU9XXO<8T*_`_Xzg zpl&7wS~Gv1(jBMjJz(Ak>|uD))a{-L53erRp5wWIhy!9~^+QE+uzt0^wjgFTX?Z3i|6FW=FY>+eFGNHGyKQSG~;Iy+6p>5a3> z<7=mC^nMxC)yjx+Qst(%n&bhvSjI_{K+xLnHZXkk-09OFTz&12VEVItANTKe_e$*v znHN1!+e7f<@N;i||IH_V*+*-n{{G_hoK7hJ;~RKh{`uEeyn1>Dnw#3ZB6;SCUYK5> zW<2@KJlvS*I6Hd~MxNeKe^yw>~LCr|(5LA>I9{kz9R_w+2(;~DO~ zW#Ig6+%Gn!Uy_u5_Jh-JGxN~+;4^vDSxc48(N!KB+exygj}mu7)gQ3Oq^ByqV&K{> zvR-I%)Ty>eYbK||=@H=z7pBIXzI}wSm$!ryaQgKZue9%Q%4%SqQR$KC$~1|8kL+ah z>|~5964Z-9XE2@p9M~TPlZJj{o7r@wx+Nu44+{ ze_(v}j@(_jTdljf|W+MFUzGoGZcUxZO`3AVJX#QX7dt!A+Aj zudV&cbuMwGrH#Bsae5R@7-flJfx}!3=FZ%ciFm=ZBQ5>p7wsE!5AQ1U0At6vMU*Wq za!d5V=n^1G_lMS9oPDS;;Bx@_xb*_#Y_WU3GXa*FUE`PV3Zr=7NZ{z=XzBP`z-;#b zPb^o=4>8X;W%xMZfC)$rQU6gybP4Z@P3JEF3p%Gsf@jE9z)k3M-HIcSQH-b|Wfxca zx3HyKTKe}Cn2wkZrT_THZyC$W9WC8pI-VDZ)>yh7s4mX6hK%1Jxy9+?aQp9WR5!~O zsdG_VPd5dh4nC*C)*j}&%<&EO)kCA7JG6Jb2Koln(3OqjU4|EXXC?}^=f!@owwf+d z7plw5qknV2Qyo>*$xZ*ENqYGK#&ly%{~<{)1T22@TT;z6zC!6p>Zs|DTAWURy0N{0 z_8L|Zsbx?%!Hj>tiqw9x`lL(!)=mRx*S}ER2A|$t~ zyUoG=PFUjR&Bs>59X8$dm4*^1M}XD{+XVU|A_pfJ+)$G=-LH z16PoYqF}_hxq(z*lCMI%N=$juvifpbsg`dlTUJ(Iy^lylxnRm^LgXFSy%_Y39ZJHL zzOOpgyLrcRluPfK2W*}NSUP+gccOY z^FoNX5yA~k8+O)*Ni&V_vMJ!}D!FC7+22Msn8W274oue;3VSdY5~kXyt`%l5-5|Jl z+p7JuA~ZT_s!!)NK+U zT{hynd4VmJ-G+3tj>Pw7reqkMSIU|Sn3)l;j@CS@R5Jp?q-MKEI~CK$E*VXJynae9>7 zKvn~k-qJac;p0ZQIFZf)KB#?(bY+k7YBqBEi8}JSySj*56m(zyc%3{irzj#tQk`F` z(}sr^upGQ&M_bK2m(1Lj;&kGqx5P(vUj0B_OFy_a&{I*d?l4Na@?O+)lzj#U6U>!l zrkg_+`3sp>dHL+=OSr;6qJZ@MU-z}{-W`&io!a0sJHVI{w*HDnp>Mv}ryq28&&;kR z4Pg4azq$GSzx&6NO{|jvzKs)$o0`yC6Ulp#CEqQa5Nd6P$fTKPO>W}ReQ}swrmgKR zKbq_88}> zq=+7{B_*WGs7{xTG(_qsVJ6D6zbb+v(hm7v);H7NHGg(^#Ng71itymz%B#13`{uK7 z`cHoTlb?X;7tfq(_w?yWr2x{O3>t<T?b9FdAV0ly;v=db^Gja)sI3eC`TJN<>e17?=AjES%k#|LnBDc!7w?@kNi29% zcIA4wf$0sEMP560EME{j2ywqp5ou~xC8|63qI>3k#&b_?Dt)LEsJC5tM=>t=>EHic zHW?uN%$X}!Mg;cK`SFWTluTAAke=0$+SY!Gy3&(L!gLa17$mHlK*y-)$d;0p+#3I6 z`VoCZ#ETV|E=@i+x6q?%hlfjHu~%VCdU{i5WQIRdx-;dYE;yJ}4Lm?UPbVgz#hCZ8 z!-P<{8MCdo@7nF3e&_ZzFuftMi8S{}lI?po9w>p*hkK75d-0W5-uNdF1!1ByfB2@_sAUGkbw2YjZGr~szQ#8%mA*7IlwmNpP#(&LGtCt`1vK1;?4(3 ztC#IlIA5fuyE+@49JDsAjwWLaaHoXZ*wviaoW&<7(7hI7-g6cjgp7d-4NGB6VO zLSRaDD+0?FB=={R?OqU3yyk1Ot7_SPSruIoKHE2B3|q4J!kmnn?pu}azQDIoD!Lv> zbVaeGbncYe&d|`Ig4JP9JUq0RTs91%!U{Qb^^+;vx%#jO3g&2;6Xra0&-A=iQ_&q| zO&|y6g{cos1U~jWuxH$dA0CNaJ=ehc>bz|g+dD|nMonkcF5SL9J*O-!Z5c@~1<>p= zg2s!RP}9Nm9F+7<{%L-cl+dwv@!Ay~Wu0aJ8K##9!^_q$>kiy7w-F&cEUf^m2*gUF z3pJ!j%+mtNKM(5`zo#rlb;oIQ_y{p*iSmDV_E%7$svpV{*_kNu3?@+ni+;-p!bvSCHs+U}h@ z_wT2CRR3(PRb^CDeG;{{1scA9vXubTTe3XkXdRyo99sy3+dnrDdY` z`XpvUr8)Iw+%waRMN^T=H4ZI4MAxR2pg8Z86+u|#Nq-@}hNez9U#4wXyZBJbN-X)g z4mDk`yGYPz$)J{ai?<4=sf1X#X>s~PW9L#nN@Ds-6m$#Jsjy^OI=X;a!$LFCRwzaN z5~qWeGM5N74SgC&mzHkL10LW#hUN_Ce*M0`0n;Cv%EJ%@8cgR}mN*XfNk!*G4Pbg2 zRiksm;O8Lf0c1nxY&{0107%}1#Y`|qIY}Fn4E&BGz=nsS2cSP|r=wifzFng(2U?*i z2+~;8vAmextBShu=96Jjr8Y#^kjxX2Y3I8<4LuXtS{@k1bgK&2!RH(s9Xic`yKP-J zpG$ON>B+XDZlSqhb$ijqb!%PnSadQM*O)qiH8$nmdvU!`J+M-7Jl=Y7%$n2-WKX3m zQb$f_4I6n}Q!R_s9Xu{#7q^>JA$7B4R=Gn?=XUkycsVpn(t!Q-B3SPQUWdQnc)6R; zM>$=7e^%@<_g{OEyzfFf z^|%H&D|=bWU9MMRXHjQymFM7@ZS?Cz^!}j5tGyz6z$-C>-iwKN(A{#qiqngL@2FjSkSo)RQ$W58S3!=CZeQ2dB02p;T~zdz z?CiESldg!E4yK>^V%>Ztr^lOw#>@RR5IYs5UH(f_v;AAr(>t4s+bfDYuLUf%h~fBMzO{rxVOprdvK zyNBebA{zbbH{XBqH_!KR&G4wYHkt|11^dSLzyJN8{_N>G0$H+3+G>2rTT!AR_8@;VNa@$IXwjm2rJeQtMODXhwui~acx_d;V z_mrJZI(@GETxV8KWyr$W7}l3YxV>~Zf8g|QDR{gggZf)Pzy3U&KC&Y`bvU&$%h@%z zFxR8TNa+?Uk9S5o@q%Zwld-R7k6+^FvK%|NOfMIIeEV%9r=zBSM3w69@!4JE@_^}Q zE@BlwKyRL|t|jyQGZS++cC}skgX}QZ&y37p4l#S+z-Y+ui7KAF0~NGl2uwfuMNwsC zWD%H7DXAhEk?nE4bY17Ol4#(g6DPb?e zJp=PHn~K^>2)FO)IZ#v5oSNEu>qU}JUU}u8UZ3mT5z{a$dBJ!Rp4DDs%^Ipk^OODj zo&7Z@(i73a_*t_&2r+jFU{VlC$wm(!K__|1GW`7VlV?5n;F>kFWs-N%hs({$1oPm> z2h;JCNdUKGaFl+v9CgP;U(CeO%`JniJItP)oS72~;}Oq|r-fEX^0AXajj>npb~s+h zqgFjC(T(md4oo-3bVYb039GG~ys`GMc(j{l9$UFQmQLU)!K}p90S%p(_I27Sj!{t5K2u zq?x0jD;8a5b$b!0XGCzqvTe(T!tzcY>i+eiLnlvmpB$>cuxw~(by!+nd3}0xaa09g zG10XcOscAg1gMIVe6H)tlMb?vs_86(%~7(w>s+0Q>!o7zps}Wt?gF2K>Dr%bmY)sX z=6$|kdutUY>#ur%a#l@C5zvYjeG%K{h;bAWL4JSZ~_^?5WU4OENKAUW4pr%d?Sy?Y*e?CXE?^*v8{hlQ<-Owel-F-c2wa<%Fk^2*LUn0Vdue0$Y6ZX~ zahD0zg7UJYgcWIxo0vG1Un$L@_YrllD^sRFH3>#fS>e6HJ1}mgcM7OZTupgs!YaBN zF$D>to70MEsOd~Xy7Tg~9csEo)0Wz8EF&--tv_){sr9JBf5=e>Cg)_<+rxFAZb!MRu{I#-6`Tl8Jc;I1MHeH7)WPP zOBz$AaBBiu)7uC!-I!ifmgz0ai`uVBO^=Q8bc5=~^76oa_M3YY z%B=;9%Pm%Sp!=w_t}0XG5Ya=mhS?&a75Js0Ppt-@X^ZOh43Vo zFx(71Im`ZHCNjJL+VG*dj#%8_xuO>xM=pl-vu5!H>HZm;@LHJw*VH!MnDBt+Lv z!-(mI(jBfB;}ep6ZssG_myjO5nVDEmn0n#GRE??_N3GiU9YaxPpJSFkUCizq?U@rh zW#TBNuc5t>DnVU|xKN^?lP6MmlUH+OMnHJPg^|*$$7N2roYk45o->Ig$l-nIY|0_A zrO0y5BH$seQ{+h0AL?I}n}@S!VR}@QQ)FdU=jE2mb(IYno}R^M>~79Z#l>W(7uCkE zYZs=!eCg=O;ro4km$yZb^K!a%#1_+4DmZ`LHF5amRyT6hg8@f8z0M`gZdFyyZilxN zH($ly&G~0zI;mmWrL1%V=xEiVb=)tl@~2Y^+N+ceUxEu-bF(UypmKS*1xkPV{U@Fq z{y4sMM>}T7<%c~RLKf`)_G+^!4XD&Lx~KyIh&o6A-eXKWAw~#QOOQ)>K};{o5mN-@b9G!~^{CHj2B>HGT?{UY8h0dmc_fdYg;Bk$4UhV))X4-VN=<+H=~r%l%538F zX`J03b>;gS*1P_F)xEH z0L+1Q&kP^Bh|+$gsj{-c3FVz4)#Tvp<&djh*t+BYKjQueAnGz-`^VSizzM7|xc?HX?*uH8;1X%EKQn6Q?DzSd=lsrdo_k1e8d}fAu-Pe7+uQy#t3oDxY zzQZ%aZRp0qb%gYjeH5oQau2wF($aiV)cVtB8Z!MfIe6+Cukgsuo#=zj2_7oX$;quH zR=zPl2itfKi7`n0TmSS2rPRol&ipTTTG}*sDx}?~tcv|GzbuZbdO#nEs=iDE)B)(_g2p5kZW< zup86uDKGMETb7rCB9Zo(PO zEJP2}JY3^Ve}I|HliTiB8&YL5+PjcGbn8r18=GGFGs9kTw+_K*;f{)YPXA!iCQ zquh(uOj$lBC`b}I+3h7XfS$r6p@d>m+~{G+B}3e!l9Aex_KoL-yN|*~AGIZ9L;jY{ zF-40)hmRkM5kbBexe@HWWh9yM2`P%QtLYEnNFNH4J@~X*+>E&WC9LUpLsEO59`@Am z_p#1<7X+^khSdu;7i{0YYnY~9dkM0c#k1mSaTNs_ZrZg^r*zeN(R;lUtRMtk< z*3zU7Z+b1*9(T{)=*~FeyT|XTW;hq4llo*UeHFwjdl}q9h zS`sR1J8N1JP}BQr%W5-}CDTlOYX73j%8-?F@2Pn$De#^o>@_(}g{6baZ7(GUG6}DG z(mhGbVsW+96crX0u3J-qixfY7Xzch+I7t)dElFGglm{;3AuXfewWwz467Pcn!9+D; z=kcCfl^Dxa@bg^9bUo2}A&6I{M+3(2F;r_TFM1W&lS_sMo3wOXAoJ8t$O;xW#iOEh zi_9#u3Ae*d$m?KUXo7To>qK`X!;3gsw2SlIn9+Y|7ori7sPJ^$a~Y zqozaY0p6j@WK380)y%BD1taZqU2C722gT#CrW@8&!yq`?y8Y#R$Ai3yv?QUS1Q_&m z?EdCQb0kTfq2F8|+VO_F#p2%|0(9$rYsg$jB42~Pv_Md*%Fy8|Dm9>vnr=YcVrxA> z`#xcJFfkFQTf=ZVCeV#5001BWNklDG;# zeQr@YTccOd_XiuyLlB&6uo}Py^Tp!bZMTgHhzW_#Haa@)R@q&U)WzqHX{CLq-W#-N z!Z?Tf{|C!`P3$*?XF+gE1Pkl*m%-JWlH%@}v8X4b@U)TBi;Htt5U}Cuno4RqeUa5D zQf6sa7$00`WgaaZ=LfPLDx@nW;V8G>;$mcmis;_72v<+9ob23eS5Iy^r?$A4XzXJ6 z|Ce73URm|Z#_q+Qsvy0*>N{cHcSz}r_dU96hSAFp^_D4{aa04kt*>8MopX1!kF)!R z;$pnQj1R7zzS^|{F&(!{LjTj>cXJjRUSoh3$B-XkGAs{4W>&>|NViV ze)~TT9lEoA#UW*`Z{+tgUi`&Bg6YRU+s)D{rj53?l-~OKqm+>Tc-w&%N;T8ku-?Gv z;oA% z(frDW`rY(UwRadrO0Pfk;_>(1Gg|t$SFc{Wa6y4E%7Z!7oo(A!8{K=}2QY^p=?G7~ zs=C5sEh0B9yzpw=)zhcrF4oP8h`{|^zGlIKW0AfKXZ4_gU&bC~e3&4yCrA=!3@*vD8>BgJx{p^vizGjEL_W3XW@ITwqcMH?+ zx@*eXE8h+5r?M00%i!Q(UlX>KzUC8uJ~cqb%a<&Lr2A2w;Odsb(hH@JHk{h`b}v%y z`Kb(MI;m6y-!-$L!Gq3LB)@>^jTb+xDD13wtFMptr4ah_&$lPWo_L45f_Tq`8=IK%1b za60?g!Rq8PvIddr#M9~HUhQA)PpFKFJbbEsXSvK=j_qan9A9T=l4soE^K7=5V>J#P zMbl8r@IsX+wsORDhKmOaI@B{e%d^9a#LYv2jIz6k=_wrbpMtz^MCPg8Moq_^j+V}* zIVn5F#roH9uOURiB9Ly+cv1DJEHBDSKm4o-dHD?qFOIx)d9}Z%ro-tDREKY0rLy*M zBUBbfu?DQn$L18h1K-{YKu)EmG6}mOI`4ScTgFx|DK;v~j8BSkL8Ykzw3A zvb$dNYin2@7~>z0EJ>z8{9sbxK*0X}-uwHn4E7hCTOAtG?%iILpX-?c&1Xa5HUy|>SM+Z#VRrk4UErgMJY z(M3mtj~)%*z;&a}qNc}$XNRl{S{~$1LnZz)Jc@ezv4H+&TrQZ@OTv=Frnm#}G_uxo zL2aBs{P6YbqmFIJSa+Hl^ah0E){t zO-Kpin}}BlPXF}N)o+IuFjt{re8I8>>&d;?8?yNlMWn zsp*`m-yHLH{ajPCcjd~T58X5}ap}K%QU0I5V6@Ak!mQYpNkpGh3R*)ep(Oza73;FJ zJrL!22^w@L1*L&;MU}M~Si@;ZSD9a%mmwoKgCItd8cV4uEi77xF(st5s6TMY_^RM} zRj|eQZDWWlPYfU<1<)kiWqLqnpm*k?qR0pw zO2^H}`g28oMgBV6H<_hO2;u@_<67bX^`zHYiYjvRsTXA>8fhOTy(nQ>`#r{#Q(!o~ zGQYEw_(=MvR*hd7OLL>8?V$(fwb#&*i7RtNt5huQ?e`>6+`25WY7!V9i#DI>G1|^O zAR^Da;b#Ea0(D_J^~QQlOyrnv&fJFS1)sJRAA;G$Vp)JrSPYa2hYbls;<}mPM6jDq zMVbMK&~+d1x^SCI45iD>tz;Lw4E@j#A7UZmhj)y?X05pb+oNw|aCV5^Fg9FnhAbNd zFB+r=4Ru}P;*feQ>xX1rz6|HHb=tr&q%@kl7pF^Mzx`7-$Hbl(MrV>@z||7dQPPo; z=NU>jn7%hNCYb&MhBIXkH;+pU%KJsW9V4haDE)`_*R&=)T944M6Zv%-cfh*!H)44s zw(AVTyh#P%dZRk9*4(}0GTk>rBD^KT4^tbb5ktp7+AMfL>S*FT2s>KaAEP*$-8y^> z?s9%*m(mTLi_rPfuuiW3QWrT0U3kyjNC(HbZh3J?>1H-&=Kt0h=}6i3tQFw+(bTD!hDLoc_DtT`TO`&~sf)cX-pKs2{>R+1=H( zn-)ji-NdK&Zd27e)9KgNk{>_QWtKmFV?J5v z`-s~5?N5)qc)s3aY)=@u<-{0n2%2;L}%LWSW?qHcP6Q+{;D%$d3jt9hBtcl7evDxwb13!D<}Km-rqys_-O_Q-+1GTH%^f8Vkn(SRYQYk zB)ppf@RI&GbyUyp+0ilB%}+&>TA5Z$&x&+RQ(g@-5!1!#e`@})xuTIaN&iX(>hJd_ zCVutBYaecnx9zj#rRGr{N@vn+Pp1waCk38(vJ_5^P?)<HER-FaMRg)>V<{aZa8k?rvn>JLlT`GYZ#a5T0(j3jyj} ztgua{t3ED4zCrG);~eD_5tSY0zbLsp{OYwIzyA?dm%O~3ym;mcc&aX)-Enm1v#X%xU>W7{_-{E*MyPqCM@$rf=r({D3=5z*) z@bRDJJImKU$alG2P1j@(^`8|GT2V2`k9SYW*B z)g3!_oP719V(mY(ld>JuZ*a3YXGeF#>Xunuaf+7r1)cnF5B}}(P8n zqC3QN{rsu)bSdh4?l+`v^mI#3zhjS_Mq+h631q$8^1sA%pxj90cAeb(Xi(kCO4mOy zSY0Bzb-hCbII4;i!qu3;93Nw1IAM$}_+3^XIC#)IravUcd*Dp__|Vcd`5DI+on3S+ ziW;MmQKP1kyaI%x#|zpO+b;X~UUr|CsXkPCm2 zlu0phWf3NI#Prgvn!uIA$5jPPKqwE`G=1Ed#F*H*)AwMn{>h%9<3j`I1!PiFYHZpR zl@8l9j%J{-0YBdq8yi>HTocz)LufjbPKDPM8JJ926KJX7dgQ8S zg74%@#uC^V8%o2{q$E#=I%$m5aG>S0mR>D}LunnyWKDe|?U?@H?ZJVWff%*Lel)j4 zJQd<`U?`>B;%U%VGP8Ie-wC!Cqn-=OEld}TiP8aflm7{&-y%0UaIT{t3e)et4M|(6 z^TKo~;hF-7u?6nJbjh|x78c8Ei_O6G!u&v-t!?8mSl1J>>ngehZW5EcC8e_w+!lk) zF}8Fow-D^qQh_`#q#KU6D1C2?hUD~u@#;WoUmf67Zzl*D0KY?=&I8a6mC61g2d0nV z4!BQU*IfCAZ2oVd-C(>>{l+jrF9bKk0(Q>ot!fS3x&0u!%rMo63)4wz;X$w%U~+53 z*qTs*)z;23q(0I-dDib7Snhyy>(c95J3k8Bt*6`knRb*I-6C~E>5h4knFVMzroHoT zhV>9c=+?YL%DT0lGkkn#=9c79c6~{W_x@Mo-rQy5hB~gW+y#A63;q72L})}plD53O zY14eviF^fNFCXA~`9obA+=@$mU^nX3`-h1!;%eVjhi_5?G_Meacg7MywpAzcw-ao$g zi}i0FI=FL z^!+Ure!f8w5hcA*xtN^Yd^$SnFHnT~?V=u4Lp2z%-5 z^@+-@o)gp?z9#(Q1&TexGS)?3JpI*IOA^n#Ej1l?`Yv013O?u(Pig0NWK6%S0fS{q8x)A=^fb5{dVF*Y07=RG}yom5jd;X&4CPf1Uh zN0@6zTUlchKACd^S8RE$ttn3QMapfm<>l1XMPz5MdUQTh4dxeU=}^3eBoyIB~)E;(?4E5$5i^CZo6f>XG-K zqlmP+8t)brZ8MHtg3(`o`PrWy2GU=DeaDWo0=>~6s^k4t_g>N1Q(ls7`>}QWb z>W6n61&QU56meNtMC0b49dnTH4f6~A z(rD>;UTBcy7?zyQ?O5fi*XIQ{tS`8AfO5-_Ze|}Ar8`KS-(m83_0^s4{`e^jD^KE0 zH=Is#`UB*=T=%9Upj(uFT}d}*q@_E&FLphhuorwUc1l-ifED%fxAb)T6J>{QJE`j@ zgmtmH(bNrzN6t_rBN?rS_@Wt-elJgoMwDt5!WTp>C@qS~Dvjwsc;LY51KtvnLk3nK zgrHhT*XSR>o1E)83aiwpQ4-Tpu~p$ohtl0DE``fA6q~LAzzfo6poh~FDSW+&WAv6a zJyiLNA^inMS6i+Z?=zcaPG3(fd;PJqM`JLjhi7HwsLeomc=)2DS?gDHg@eXfFi}4+uIo(9bL)JSyNF<$!K9|(rarf)^uW}ek~d`y^`d^q`Bia5z9Rx)baWH-*`IO zDKm-CMX*(v+D>@k%3zvxE?b(Egii!sH-RaXjwX~=R;(#3>RgjhN~LCD0_y|vqPI{S ztIEwH4CFY-(brWyIvfo>u(T8dI5(XY7(7=gFMCGJoe(gOpp~R~6UL9Z?LkZq6E}?? zb1;_T(M?tNw8u4fwvg{wC@np{44*5LnfyhiflEuHbMuR0X}r|Z+|sV>NE7vvKUi9X zEheM0W*OU9lempknw3jy=(0qsRN`jHfS(sjDx)4(4V&MBk-eg_u$gT|w$H4|LZ+uZ z=~5EY6PE_I7wF-8I!Z{fQ`1by0wrD{f^E?(Tx*tCOckklA&m1@2hvaje|SMmcT2g% zbpZM#c^m#UuQYQ*a!CWImKv^?pY&&g#r(j`MO1nRlupj=bxJ4a<&KFezm-AWm|P%r zxzP=0gWIq+6bNgIx^=Ipwg%<}g~D_Vu_#y%vYSFvXkL`gwY70Vb2jx;@wwS#a|dF3 z{V|WoG-(2G1NiG;6Y_#9U*)qH)I(q5K}bc1y7d;)FqCe2>CAjK{jVV%X=zl}nA;uyKJ02bTmq%LMRZ^( zpeUPU>NN5viaq%!*=gMAAI~bz&20j;y>hW0IOXL?H8;r;O03W)zKvCU^8Vtz+^EVM z6&C46nm4AG3(>{B$*l;Kh=P&WVp3Xj>e@VeHq0_=`oDhnom?*a>V@1pPNA(o3Z_#+ zx^LB$OCNpv-tqH6Qy+a4<*TeQZWEvLAn+TAm<>%!^&oiFewAAso}ca^MC2%{+> zwT>0gC^h}g`rR{*5sSddmOFR%Yb{&bNPO) zy}6>n*(svDw*HmCwBMHF0Y4{&(O(pI@>OCrN`d>fB?t_qiF2wWlPfxF^E~VClo{sK~ zh>BRaygE6YOU^G`IJSO8_*QXx;*#JqU((}-#PbAy^GxRKm6hI-=Cp`^pnq}rvLVhCh}J9YD=d$a&o$!ANq}Aa)Hx-f9m-! zzWDRN0MY2DMCpvFyo8v;#Had5QTKJ(Jv*pW@#mYb^u)LMm8DOfIUm!u#B@SsC?fq+ zMPuLKpfLU1m+dihI;uNQ+P+7RYg#d74JErgq4aE7ubKWyOh-i~uu4tOjjtm!)XhU8{fB>0=h6LYJ^Ec=V_8`wdHYelDU>%yu_yg<^P}_g-DpST z%pB7dlct+3o);*qBM8&P68WQKdwSN|vSl96$%t^ewD@Gp6JbU&ip7dv* zefC$v%^hgNcW!)T_PxxJ?waiD0ew@okmBRx=i?Mlf6>X4C#Nfl(XsE-{mR7YZmwz; z+AU{_KZNe*U+ueaA()P_eGZW^D)K~V_ax=i1N6pA&IJN>BdE)p?jELWMr|mV&V*YN zXWq_;hm_Yr0koNHFFCPZc@5f1_ z!~KWPS_TxT`O)jhEF{;LhQV_k>&qHa)2-AOVLG7h7)0c7&}z4RA<@2sV7I_nq;5Ff z+?I6*H;x^~7prLWFFY`#qg#^@oxiT6%k#4H@Q;7=qx&Adf26$W4mI5vS8g?UZe(7HhZYbN$k!##>R3NX zJU3Q#dKv-D#`1FP5S-3$!f~yO(jz@QU2}b1!rV%*wSb|Ui$eP0qJZ}O{rzNY7iA6< zo@hBSaN@+^iT3uvgi4Q@Gy*LNLw?U)k(|tGR8$FzKQtZPFoOg}<4~tx65e$|`UV{1 z8_?Rr%GV#;ax|1&7oyTBAC1|(dB^6MGpkplr=zfM4_Uw6`{?FmoaS3F#GgT93fbGW zaQU3x@O4|VLSi-_+p;+;Gb`py$R%Q23PNKtw?ss3Srio$vxTg8WAfQ@>`K&zY!cPi zWK_0zCwfmGdfOO55=n9xUX=A>KJxj*!~nxF*e)X12fj&T6s3a&PmABUd?K!wVT3ep z_ntRlWPxPG&E<=z9t}|!(o5*+YohZL_Qq9KpgK{~Qrn6fy|yqRX<6sR!i%WtrCY)F zPTCs<1|;78^Pk^7KH&e?hp^-G_rLITw2P`K6JrTsR1?w(({YN+&7DXhxe{0cX$h2o ztp#U&b5T|cjg5%nt?X1A>cXNTtmz6XFRC1bdi%2mDJd<@Ttb)nSRCm2m8CFpW)@K| z<40~AI(^fa2~{v&aH7)ih7Wy^5R+jOf~$hL_kgOEOca#ESVL@jGmS=TD;gzzHVyRT{$;^I#h~WF~KmSs7zuL zxJ~qZ{tQ2Q0$*%0Qwow`@(Z(Ic?9)kOJZ3*ps#9X4YFCghvOLlEbW52XbFY|ujEok zgEq$E2lpuOg$dj6;AK>hE<;F1pN0P*PX<`a5HzC~i+bg2G2q1w!O%t!*Qo|KYz;~2 zb~pDAZ*j=!RABN0+d~6a-6CCY!9Cejq^5HZMpZ{nmwwJc_zy1YE_4M;>Drkhc0CmPi`U&fcU=LC1BTOuuNw9pG0xgq7PZ@n9V{1=>o$KP zjo!Fvl)Y{r#uvl8Q`oMVHP4VaqwN9H^{ipTQt7MrJgo>&3(DNept^UPn!NT6L&tgrFfY;#nmy=vZVaX0SOs9?%$I?5!|9fq&WrB$ zaW4f2X01#1SC9*kPNa+D)%m}8|Ic0%e7(eFxxbT9)BT4yMMXG;`M7&{MB2(y^V0HA z*7H0ouh@!B*vlX4igTMNBc(NByc?N}#`(fRdv;E?laD%M=0G>#eX3i$lb^5OC{K(o z#l-|N;(1AFr790&I&8#Wqjt8r_7sEZzx?IrZ=Cv$vFgr4nA0!sfY=`e(@$R6_ua{p zSJs2!S1$yueRLJ#8Q%11{w0xh#T^~)o*QV7bn1ocnBHqw(?7H5T!ap_-?x8)`crB~QOl9CH7;XkT+ zZB+T^M>>B}d>scUJAx zn&{lzC=bmpF}siys(oC>bS6F`43XQ#Jv-ah1198P!laHe#W;FnPz&PGfJ&6Rhqm>1M^ zTrcSUsvO0H=0>HdxsuCRWu%9BqC{VzWdCO&&xN$~ z`;0N&N_lzW36dBedF0(^fBO2fhSKd~x*Gf#W4hh-VnM9k8X`*n^-j56s6hqO;dC7y zMpJ(R_4(bmVf9DA^!p$G)vGr%`3+>YQ#$BwINc8D>|!14kZxKXvFUb7SLLl4mYB{X zhSEn{lDkpUttwL8g1Jqh`T)^DF2D6VG-A5lp)Ms|dFebdOfLq`?VcWEO1H%HS9d=0 zyzhc8Z8z zkQ{X^oH%eg&QPGYZGY(g_E@qRTiOR&1_p4joj5TNyFY25u)@`O$`JPwr0WgI$uuYp zV_rC93N9ER-7z>PVn^ae=dK^yJ;a@ymn|{gREv6V_YQ{BH*a3Q`ONm0-e0|%g3`A` zkFGznIwoX6{n!m#HfNrRDLA@r@7{F_f6%)wBs1$MJWti865?XA(BKP@wnJksZ7GOJ zK3cGO^PeZ+eL^!lhfwZ_4BX#-5YmAzMCVB7mX^l{yiv6t#OESQI;uIMob+=N z>xS}^fd*0fh>3{l#Jvm~x%#Ed(2+0E8*uNI^39~YWQ9mfKMSkNn;zF$n+&K6(&?bt zTDbSMq%{?2>7-O~SshRrmlWW=Y18#JED% zn1$(morQh*6*=@9EnLLSR<6mfj0>nT6Nh$`_f3g4`3-))8OZwj&9bG6UTZ{3rUTI%rcrwi}LAGn#F4%CU)LIrfW-Lz1snKicW8+ z=@zH+YEUJqwd$e_Zb8>@t+Jqq>Qyn~_DL#9#GP&;7zJ+yUPVi|Dk1jF_3->q3Npq95c>PHy(G9zR}gW6E5bKt$XESXdlWG zq$A(*;vOf>8af{X2wPOIUznS-NZ!mtEJn9BMwCy%tC?u%F$10OsR@I}eowBURCE$< z%s1r*3c+FXuPf<#d$4~jXS&?!ur#(O<{r2Fo#RzK=icnhG1i{Z3_*kK6R>M*&Ct%{ zR;96n+yJ<4k}utwh3VX=o~i4Dk^)R=dT#iGJvU_QaSC3&ZKPpzlWuR!>Ba(Mj4;yG z0c`{76J){XXLGPljJ3tCnj2!*bw%t_(~XdBT_8xe4{Py4uNNK6ux3ztG@5`&2>9MG zuMf@T7|gQ}(u=~ghfE=R5n)Ms*?)l2@0}AFGt#k#mk+VL>Ha}JxL15&V5#Z!kZH}q zT<%IIA=5DQ>klp#*JW&gFYz+ug1`DXAgnoM|R?wSeq_H=c1D*L+H}^ zaaRzg7d}wou7%U0GIB{hiHhu@)z0QGuVXp}@>QR0ytDo@L+5r#=fqOe57lotwxRpZ z@H=0*Gb0+)%jt{8^zz-KpZ$+t{L8=m)4%-7zsT^y_X}?xy0g3c&~Xdd-;@322;V>b z>5+fD9C~29cQdIb@f{rzp03F0n9^&b3l)<7PU6bMCHGJ<(^rvER@R7hJf}CT15QUx z$MVuK%jVT3js7?p?&8n3V!tLi^-hDpMop*t=tl%gUN~P*Db}u@4UxH?VZdlN-AW~~ zm)Gvw*C?Ua&)I{j0gN`eO}Snv#d)}2l8=!+aQgH|drya#JN5R?T23dwW5)W>V!{2`O%Xe0P^CjWwrv@vUwnmUn5*FnuLU)X{`A8}m9vH=e=X6hxAWKdEe}LTI zpSybcYkVV6`o*?3r6>ZLyBDUdWrNVu8}~88BIEqr^8+I6-+%d?l=QWa?!uieIo(5) zK5bfYo^#LcDGjGEr}v-iNf)b5o_rT=e6ZOdr$2gE8!<6&y#?x@`||e#1xpLlW-VNp z)*I%Z(oxM~L^Txwe5K)dfqNyVBdq&yX>l1jE`2A?ee-31MP6|)9`>eHO&cP6b9z&p z8m2ZX;ss2XE$7t9+B`p7q$jbJ#dW>$d94v)P8hbF{cO1zYu2q>lk4Z9j7<{(#BM%{2p4YEUs5{F z#yp1*cV|p5KbY-;n2slhH>#>mNqpoFTj+|`1 zB&D1FqtL9KWsRR3SN98tfA+9A9Z=UX<`+Ebsz{ZH{;OX-Y0f;k!;Z|?fmvs6pt}X> z`~xuh_YFWt88_{YH2JXjoPU1ij81X8n0X1py19b6?B1zHRX1w72wjYB=X85ntKIlw zUl6!X>6&x=#d>_ov@wTQUnDpEfuG&?z>}XEHGR6G)A!tGsp%xW0Ok-m(dnEs<9Cga^~TgA1|*<^?hR1^xXPXpV*)jfv@B*A$7dxn;1hrG5A&l3vD9(nlH{gHKN& zT%n8l!7{1~#9;M_Naw80L*gBrINtI3`rmju+HD>p z^ugdnAh$hm=}Oc0rv}$HJv;HiVB*HqLI66zo1agDigBV8Lc};Z))y>1!=4mFa+r19y4&%PH+`zG{L3(@YO>1USdi!b&lbSwkD8cEmYe|sRRUShhQersqY!bs`n=`p)n zlx}?K`ZvNh>EIaVoMRvGN*fsvnzbO=oop8v-TXUn6pd;nSckto2y4um;P};Ye>YDh zr#t()N6^*<5Q4emb8FGfJ$usXQgWgzFJ6>8{gbU}Kz2%M4~~mE#7<8)Fi{PWbQM+D?@S9vXTRd;!orHyy6VLRKVw6AafV$@$Mtfx97DQ^ zVU(IqYRil}?PnC9K4Zq%jfgxO$P%8>b>U>*nXn9u(LKN z9(R9AL=N8lS`y{8$l&f-n@bvqt+6Tj5Uv;G^q^V9efPR|cXVC+Sd{+t2SW9afblq2dS$GM&hco5Vb2Bq$iRC zRF#|#sDtTke|pQr#QgsGb4g!)efmP$!iDaU+0)V@JnBorJi|H&NoVcA&yQDMs!BZ7 zZWFP(t(e5j@0cJARF>uCv^J{!XlrqCu~*sR#;yO;XzB9g3=l@sWW&>*3h$Fa&vB0U z8AhGyv1nZ-wo_MUWaV7Fg56RhaKKOk;NeUsP_G=Dtik&yl~m7_xJk3AqtefTkn z>axAuf7BrObzuG;ty{cqM|5ko!eKFo(r@@)w1{YtxOJ?MbjLrqn@{=w$ln`Ix9;_Z zn$G>g>c;kBDd;%Rc}$4u0(3pV?~fN=+=-_LOkXWEU4uYIqo%{#4}j;NT2i|GxAyBu zOMloLJptF7xRsXeGHA=kh=0* zjG{h6!6=Me#BjRRt%w>so5Y`>h;TK7Tt}csQ{+1Q5%Ufn*v6jh?3TPayo7Z)x?*t@M*2QgHUe}rWOpg&i$mm$8IkqfW8Lw*91GdL z8hZ<feKd>U^a;-y*9%3Z>o;%Tel%o7)E4~TM`QXoZ=wC;)g+eR0pq=y+s|B! zDVRqC)2r)=-q`LPn6+rL63mf0sd04R9K)`Qcbn9dP?x*=|eOidFx>BR+J@gP)9Pw0e3_~ss$_bw@*h;iQ1c{ji8{+rH^b_zv3 zU#0@eOj)&A-_1%WO~{N5XeSVb^2>I*{w!hUMGGN`(fPS*nO%b=yp#^4gdbMs4;Cem z!>A90$ozGSG6N>XkY*0N7cI&s>v3toxarf!1VcxO1w?EI4BsKD;quC0(ApZvLVqGVAzo^)eN=a>yZD3<93Ouu6y(*=u#F|k1A;2%(J&aqX7 zz|Bn?d&e*c-FRP&u2fD1m&{80?~R5t&Mnqf@sxsAYq$#67L&wB`tr7jy2n0w>mH#nkAi5w0eCQ zY&Gy|2UY{@)~bWq7Pgyv;!Sz8P;X$J-NjVq?{1M($qwrFo3)-hGUjh!xE&^D}+5yokH2FHgRB`P=tC zrX%Ppe|+@O9>28tZ8=T5Y)zhNbxj*qw5~h#XJn=b>|r&kUa1&(HWw@NRWD z;*(_TXERD>)T@N_4+hi!RqWpAWysfViT%exMpJaqQe7hinw_=~?d z&f(j4A34+CexT~LigdrcT1?QC(5A%KR>ma;Af?w7_SMGw`Aw^K>L3S@f?5T`<9tD@ zbZe@O>gbL@c|In0`itlJoO9o>p}xDrbT|4My9?tq9Y|?m1fjRq)se{^T~WCv!)vWA zGOUZ@Qp_^vJMwg+*lFA%qHrcr2f$ElJ3GBRI(m)5UQS0xm3TPKS~x40sDbza{W-{#}cwQsS7#(~wt2WaFbfyRJ0tLO6f)q=a@vy?AjT)KMJSbbJ^;SdL3&;jC(T zRTzljWQR^mjmX28Plbo2sXNWbRCFEFnIE$oxk&({bR3Qq_t9hz09c;(h?(Q-L&o&JE zgL^T(xO;d;crk-u5V1Z-H zfBojp`(^5oH(hEvoX!uN(S@Q_;rbH~KfZI7ozuS$=m4}4(#ehhHn~=auA~PZ*d2P_1C{l^} zv%4ewBi60)af+@S?60XDEFd|3ATe?JwtxfMrXP5|{rSPS2B37b^!?B8KT&xiHmNz; ztv5V*MOSiEcTl(b9hqVGr8|5tFgnI`tnV{Q=unX?YdW46Dd%|8j}}l#N(WNB>2Nyq zUa)!nc3dxe2~$54lGUHJejS*uK)65}qk{0>+c$5{N(!B~J@b8Jz?ZzU7Oh*9m3b5+ z4CS5Mak>}8AiNF?#L_=?;NZc7RpaMw(H7`CIey>GMui2ZpY$P{I5H4DI_($r3U71iCa34+>=bs zCy=XBTA4IHpq&<^Nr~f=RC!sLNn$x&voQ^o7GgYai5V;`ReU*inEsYUm3$;DDs4&f zj?FBsiODKjSIE3B&^ur{+%`V2AT~5KkuF&CHa&QIKxn|YVdAzs?s#yz_tM~lv;kc? zw`%2Uc!8QL`e;E)YD zC661K+z_}J4CWNN>n1q0Zi(}T(sgxScN6b6(z(T)4ljo}z58xMbE0T*92>z_+)j<5 z?u@g5GCfK8N#Z!37dFEB0RbH{2NJmpf_2Oz&~;2Tt1i?e!szIR(Ivp^<}J9i-?}KB zgRp+&_<5nrmIcztvj9#nh*^f9zHE{-VjZkq!jcpR4LMWn=9D|+crjBD`yMuIYWA%D z>~9T2?Octa4Ycn&rXLpE3e~L}XC8w?$gDr0rgPuin%(}*(^5b#3Rh)pe}adw4dK?2459NNLQ)k44m{w@#~T?FF)TrO@*oO!UHrLG_)Nr>ip`_;`p- z{@gUbX+V&FcBGRt1k&2tdNI0~zbj5jn}$ah#6<+&klR>SjGF%SS0BiK&3F%5zr16{ z)KR-c>0jceI7xdW0t!*n;l7@Rw&FIjW||1;o0b>3DP1RB()ymUyI-O5?|j`Sr~i8Tx5k=|X`{@y18oV}xtqvC%$6EzprL-IJ#rwE z*2p-1eTXX!Fisa$vlPjH`$Q6F+e)Iik4HW^UN6@J?-YciphI_)v zDWWl_uI}AEbT{g-dXRqp*FSu6`jd+nFA{5l%Ik&GC?_wit}{Bh zH6xiyugKo+E~PTQI0HL;FL_n*d9K_?1VBk4uNo{-mm8KsRyywVxYL(%-Q6S5p*?5t zF`e%@drm#;0x>JAs$y%djaz*VHGSYpN%vY?s!vC8S}MFKWYkG|Sp%G&Yc)NZ>ESt( zi%5F;Gnk%u50w7P&*Lr@&u^n=kylC@&q5nLOs9^Wx|m?eT@ufQ>5MN=5zsS#2p2Gr z(~UohSAt4ABW5iey#k&d7`UQHN14;@1C2g?KCTzaQK>~8ymIk#)@_QXOqpq;yDX2$@-$c-Lroh&_VXLQQy}{lTTV`0D~H~wu%5N)e|qb;zx^e? zbZ&FtyQYT4yEg2KqzctWAJepHvu0Hj!NY9F)!8F*T}I@B$_)RRtRcBNvl>EvkrToE zuy1;UvyIu1O`z`FkX^Zg>D#5NmoHy_8AyMY@Wq`+&z`&!MR)e>Df5ZIoRwCMRYjn_ z5J=}MH3i!XqP=B(Npba?KiT(YIsLBmva)z*=M*Pw@IMw`l!;{8||Mx?M{*I{MGRbiOoXPdArq{YbgenwwfipX&#W21o%VZ>h_2Xl zGrKUDZfq|+L_LnbaQL-#^cPOZYt%T2H~n$E=?_mZdbvUwF}+qfK2 z-EyTHHkXQy55^oDOh--EJO(*^&(qJCxEDBGpidPktG<8Fkzw?kK;8aCtrwm%)*lkC zpFMkwGh%c@>R4Y?OS&R=2AJ*{N!@3|s8J=JVTc5Tsm!hpk6x1>P0yJ2*b@UWEq#^! z0f6rQ!~<2^s;Zvfe_-JG{iIfb>IV`}oZ$akZPB8lb(a<`AXa6p5)<*h2-Gp6+np{m zIAa|!u&>y_wT^8*wmt^YeEarLsz?jY1V1<7rB7cnkp4D(KHv5}x<1qU%w8DYd-dji z6!gt3w{Hj9GqcD*Jh~l6OwzI>K7Y4Q_>_;uc_9nd(=#;$2aG&0xM;lb-iuI`JXzL1OR0(ND^cv$!?<_2&Rk5YmqQTuORjO>BG3l1;Itl^M4AskZ3+!noL_aW#omOJf6@ zvAndD%8{Po#d-kq3mQ4;v@^dlfy8wl?!5La)&=m)6ivNJO*cU+##Jr!(@R5oI(Q8h zL#)8CEHT1#X|smolQLt%XRk}NW4SK67kv50Hv;o%(O1T}=?HkH8v;yRLAXd zli|heH+Cd5GYJ6Zq3Fr9hBl4|qF8sH5+2}7!OKDxM6twfeG2{W|0}q6fw$w2M!U$j zB9Dd>-f@%kmm{#?!yR`EJl-2!c>3aL%00in&{o{qnq9&te_k;we>w3i?t|%WNRU{j zX<DYrKBE7;C@JIoC^u>;1Ivo{bRZp8XjRcvzs1lp4Zk90p>kp26d(B|_ z&Yee*CVO7#p|j+dm|q_K8Co3ajs_-#GOZdS=WyPetS>2Gi-AvoGDxbzw))!t--F zI>NHGxj6(DmM7=-mXxn3?~N)yUw)pk`_hr;f=d&ss_u#IE$(ei$;*q+spxD;d}r?X zmFo5ucNH~m+yhE^T;;`GI9x38wD z=c$uTqt-TgFj?x&aoAo!azEdhx%q1{Jg3f_dKY@SXM@na?N4v~_Rr5huf+7Jg@6P)APp#G}HT#x*yk zI_L*IgWtf@Txq67=sKCI!(!SOk@52TZ%z%qwQnoUv@V{XHF{d2cT8{erVopkNa`tp{8L}p$AvfH0@^XKssI-lWaO0)#$I6m(gS!VEm~w5* z6R^K{j!Iq;y*~5InU{CIeB@WZdiU_lJNpsRchli_wy!g}NPd24c}xI;gz1wP&iB{M zEyXJ*LgsWQ6_L_%)NkfwU;7M&=@C<;^fHo7-6EW-{V4+_#@yeTH)2!-dOG-RQW;0j z@pm4wP+~gutb%n&-QAhSS;V@Kq3QyoJNrZFG-1+^j!tbUVmg96BgmKTrXC*B(>*Z0 z%qH%I4W3HEqnE1>b-5bMt|M+Ty_l322cs(br=SKl8v7656FFL$UWCetE~q&%S3rxsK~M zF16J48%nrC5!b1`qSUG!wbXPl-QGCD;&fBDL$f2hmTr{#>-S=rUBur8!Bs%2#zuOC z4o;Vxev(JM!{Pebv18{G50jgYny#Q1E9u2j)4_BuxNduqKmGe!I^pTlDIhf~3ZOcj zNDjgfp6yO|AkR@` zc9P18u^dGrC@i^kT~R_{QcKJ80ox89h#6=<(7vsGu%&%JD{u4|*pIBf?ZETYinO0- z8MJk_ltzayTGtg;5~hHca>`Ik5HrG*B?GF<@*-T1nvqO{BNEL^x<{3-523jzd`?!n zlGB5?uYP;=`y7Ii*YT@+d&jH~QD@Sn=}CFQqfF%L0=M{x7KM zqg_c-tSL>P9u(h8pql;!RC&k7Ce?6S1wP|PK^`aKg|bol8z}-2xd}k-$0pN`t-L+6 zJ+P$|X6`4|1t)qY=q~@v5~VRx^0)~|FXb1Rp#k2@GUtt)K4InfVR!sQ=yu10Lq{%c zUxJ!WzWU=$a@so%&I4P!7P8;0%lbgkmq_ zW6*i%+LG3-x=(588g^WlfNgMD<)aABhSYIzm=2^5anUVzkTfKk`yQqPtE!4LxGx&# zyzYb>)BT(K6Oo%c(h1j~F4|J_ExlbE>k!i&n68O{ozmfWyK0Y`uIrL>gW&}cU1~Ig z=`Ws_n810%d2>L_W_3ZBEZM6E|Z#W4wj(qAa%K5EE(O%>EOBu-NETn)GayPXz6Bqc?LB1XT!90dOkIbTZj`q zVJv%$FDNA=U5@nG%69orjp*ySuFIXX>02o9%g)K6#U(AwHJqr}+g0K;t-3fTIU0k? z2Vej4>ksRSTXR`M&&3ywMI+u#UDoM7N|GH-etOBl110@Z@*vsX+>)r=@-S*^F7#f! z)LPsMsQ2>c;5w>juV-1_R->kW{lV|P{q~qN<6!(T|IH?GF!><;ycH!y5oHB`B~?yssB75bUx_P z+wTYTC%iNFwdmrGw46K|(pMxTVZf`3E$xh-@5kPXXyu{jBBobov&N8WtIbIzhc6|* zmpI0pHf99%=M~#>^?XoJcbGA}5by$`zj0b(`Wt<9fM-)=HmzFeUgSC|cfqmnt|(h$ z#R{4ny+)jPxCPDGedQ$o zhwJa%-Ce)pSk}RxzY}*cZtj@3&+RxhcyiU+CR=K8bzN(jKv6t?SGsHZ%*c%V+%gYx z%;9wBvbDNAz3+`L7%Ct=eX%RdxeQe~)!En2udU2h=I7z(mxmXm!Got}A8{`LF;5!a z^s$S1wssMnPS#5#MVat*UTRK+f7rcKuc#4e|96j?JHCFTsX<%gDK#}c_10Tkx6(}O z^9yOSrqyjtYXij7nBOtG!#czIXGL>DU&U4!oyF9*Dz?T?o1d0fs}#p`r@-{$;`8T= z-PxeFxBe&LG)7AQ*S@W74Ly(cFz~%lZqXp!c@zcB)LFXH=_xmI)J&Jj%SZb%_sOM( z+R52}n!m4~3!y4hWdgWPVPS3%%9N5VAy==RxpwsOnO{Bm?8`?tAEIsTZly2IPi5Xx z#%{^;^K-AB1*W5?`_b6c&nF_sZ5l5FD4k1 zFd{;7y6;S5PoEq_M| zM@8s{(ybPx@~7XVrb}FZRgnI;RXGZ)1LzMt^RplQ2!-B0l-f&~IFBXLE-g#yWKX`|hcVNoV4B?_Kv!Wz4?oUd^JeYwQ?aC_2@(xk0O|lKn1? zleJW{$n>jgQTl3mN4j%5Z)f9N3-r65tAV8)w<{fSz? ze!WHLMoeEXLSHZ6%X&*rSC69&VeTc_1bC9nLI!6LRx0=Eu#WC(|DbCBl-B&DgRwPm z`GMHj0|%?lk?+#KzrE_f0kQA4>C-tC0uP*MVcc_1WiS4zu(7lWO->%mzc7ULl5#3k z!E@!u!0QAtqOfm>;<Sl0T@7+ng^6r3S5UD4^=LoumyvR!6%#WaSjKYAuJ^XU4J zc}KG{Hy_(fVlx$^d$Ga99Nl~guR7r*WaDk$n~57{?>a&H`bCQtg)E!&(n}+QaW@}~ zjg2*&&a{F@Fn#*Z`J@yq47JYi=?Nb&fGj>u)yIg>dE-Sl@BytG3NfHQV%V({_Y8es z8(Z*pOi1#I%#e~5A=u$fZu%Co)9FH58%;~?*67Z-*Agfq<%fg>yy=~#r7I`Iq5UT3 z7M2oNm>7sjIkamAL7g|4$-3lJ??l7w#&u-qTh+5{ouPE=;hA{}H^n-H z^!gv(ZJs7Ux}jjl5tu#(OdkoGTk{K^G9HIT>Njz^W?Q^uDHw&+uPf@h)U1|BZ2#Vn z<3)pG>kQ|O>*c2MQM0w|bWu86s%`t;)|sbNyEiyAg!n})rgKcDi?y)(zxl3)?IU9x ze>2$?14R`5VEEwA#*{0j@JRzb-8@}A!ra|`=)ve;hn&v1P+XTAnVcPg#T-vUN}emp zi{!qzrQ-7dHzHDU;`99ST60p;)JG>dIii}x^yuiq3y^tl4#hV73RM_SP2Se6c5nK( zAAH<}WNmBuZVd z8UBOcebj}Hj!y+nR}3R~zH#?P0lGE#6uEOl4|01{WcI8JpM3JcCm+5AQ9|iWaJr8Z z8m0#a3kc z;GSD;tE*fT`u53=%(Z2E)v7gVN(${mXBF2W+cy#00;XTSz)i{?|Me$-`0F1&-g>e5 zjkmV`DdCO2#>V*CNQ!nNbG;(7M@6pNyd}IVxwWyeb^~(yw@0pab$3@YhXB)YfVlf0 zfx1&jnjH^XMnzP2^sc+Q_oLINFV%IFgjLU(T9S{Po`F4=c*pR#cjhLZKK;(zNoP*& z_>#a&!ZxQ>GubeuoX~iBy0eF`hs|TEZ-X-q6y)?WA$jR~2riPFD1ef8t6?x}6* zw9%YD)44&vPRH4lSJ#+YW^15g)VN;0BmrN~(^z~ktK@n?PB&_LYAQvft{zjT?mBf! zdip*l1B}Uc5pk{lMw$~esW%d0`dfWwE^iAj~254lNw(}0`D6q z-gv9;Pj7wr#v3O-?CZ;*tri~vgA|dTy0R}a;yl-$_2}ZYe|qB!v~)22%TrBT8$EVC zI(8I(S^6jvzdmYI!>9(2QOtClJlveTTwNDB&lxQR+?Vrgyex>_DFfOP)ee-@UQRNX4wxR{32dihV8GaK{E6c@D} zb`qr%MCt78<75AC0AezfnQnw|P+OK4x{p5l8%s?8#r4c|d0tSPtw=_pxmX=qXT0#j z>ypwfTl&L>((gk|=Qb@)M@<)|Tc|Eb*EoE5=Siza=?yA(oU`Y!@S}0RI4-_^%B2js zUMNW(ZRmXJsKs|d=(}gHsGkj=JE9m3qzls>ZAWzmy9r+ZM(pLlYNmGq(#QUq}b`_}uO(qj^*%lTr4{Y2*ts?(2DYC4BK zL^8tY&rGxgb^6xZhZr3>{d<(|SZ0=tZa`gXI^TQ|^uqTRyy;!wa}<MOXru~T`Ixx?yV^fp}|LMKmiken{-i#bMI z-;T--tRLNyRiNC(%(pSItOwI$AoO|L&kzo`_vqfttbzko-btB(+mqy2-@6D-w=3!) zODBw*1U4ouMVnq!lbN-sl5iE$VF+NKK6E-_dVqKA($aM} zV3G=wLK0$jjvPguINecsBdm5FK$sxU^h^aRB#l-Y=VRGLfD zy!MrICoG})Xk6S0_`PkWFEymuo`5=3p4lF}w6rFmYVP#8_mn1d=9eb)RhE{vWX2^F zE}}chG9-4E0P>57PN&5Y_>OOjFm>gp_hH+ttSHKCDO9Lr5l)yzGaVA90ZOpaDC(B~ zL^`do+uS+vXee7A7tT8FPd*v$!Ge4< zCBSG;38}0$Qgn^tFIH!h0AbyiHq_jjh+WJ+W_*AU*A&ajFe2wj0k7IXx`gpmGR%<` z{Em=reW?oeAw4cR(^=soFV_CCVK5!87mC{tB6F6lgy+I_-J&^|(r%qqqb6;gHq7io z?O5g-<8Gg5O#Mu0?3m8%;|8eTMpz~FszZlPVC6%lugeOSs%xwnH%aQUxRA@pb2)O1 z9P0cEguh8rzYgn`S^WmJ8-u#>s0-Q+s5@d_%;uU!j_ZuBZL_vd6EE%d;V%V*?p=`V zkJ&|Gz!Zf2Cl}UO4R+6TVEP<)FVu7dH$KT-ozV|50vk+E;pYt{W2+;wOENky$}{}+ z>EhztO0@rOG>g@kLE$&Ie9+9^l2$!o-}!Os!r=|ZC!J5YimTj zS*On>Qo}1gh2D~lb~PO_{X$ePEW7mz2`}^@C5Vx+Z^I01B7p73^;3oE`_l11%nB>1 zw>34UbTl4mTjXGyEDv^l0!)lB6{!nj`N7=y}cdPL4AA> zwEy|QJCyZDx6;(U`Gk?u6Dsm>wnU^vB=>TpFVbE-vDztxB_}?fz{K+%)oIKIY_^i_ zE*{OdU^K?j&(6*ztHU#63mrVVl4~2=%4VED^d3cv z$Ll-BhT)2FB~3>0+A1UT0Pu*~ar5*)A622vV(`{b4+2FZz`cy&lU1ep9Q6$H% zxOzDdO8?~-Q2LDesaQ>*bet{?YuoOc-!^T28x@_X%{)2Z$yYw`=kJ*OJi2(4-070j zdx%bVbwx}sOUsLoY#23j>J<_fzZv+BqESVrGiIhQCR_&Z2e)u;U~sVc4JL1-3Z1?{ zaN^ctnn|VQfx#)n^aH_teH95OTHg5Zt>!P@U|f7FKf7mYLpp{TRC?wguEpnPEu8O1 zPg7C4(f9k>w&q3l^mNY(qUVZxH|zeQboT}qSEi+8yU-lh&&`(%cM0G$<7BXB!E~G> zW8Fu==j_n>j`FTcBu!j9dTsBe85{3BbZo|0xDQ9VPce~47`Z5Hh0^o#6uvl_+giSy zL`Gj>x>t%1jLtx_cH;dtf2N;3>PD1KGgcd`INa+He`5Ao)gv*dXJ(t&k2-OlJxI*?8cDUZgFHyle{G#%qr8Rh0b zW%=ycqwk&KPGcix*G5if#l!77rV}=DtD$tF6IDJcWBOqt(@o0DZw#bcTKY|pt_DYP zzL@dCKm7)+`MN9J7+rq$%zZz5=0`trNa=vPD3|dM0(9NY{n%>`V}AMdsyij43#2tZ z`-@%Z7C3YMrt!TW9h?r26S|0&&Iw06Ni&YFzf)EhV@bCxGm_H(vg$9N{e_$7i~INt zNVgBUUHr*SP6eKAGtvb-omxexD(Ahw0#Nf{$Y5i!oobAZK+hYuPLncs?G20#Ks%D601lR2`>i*_HRRu-Zp7}z`+9t z58_bY2B_mxKLEN1K9Evvgmgk=Hk5BD>FFN3dp5r+ z30txL=w|%ohSJfe&ycSe3ZHX0Q^1)5Db|#Mo+bY!s~~2cvQ^fFAf*?~3uYlchNwlt z7GuY6J2;R@&y~HjUD>+`XS&9^MMWs;Nui-6g6vP+zlt4Hm;eAE07*naRR4!-80va*BjQDi*gb8O>2ge*m zP0w0avO;-`)1x~JqvcKq&}*YrI*PX>E8hSv#H!1 z3C4w+2PlKuVifoXbh+g#jKC$49l9k(@c=m7vT18 z%9(Y47{m?mL8-!Zb90i@CCm;JYy*C}qL~VqyD^ocI;ZQK*R{DTYoUl$0XUxD7)<2Y zIyDbWRIZKXwnW34AKZTXm`T9~(y6?}%q_O%N02wLzv=v;iR)N=&fMGS2mXY_noLo=_DlS21yN%kBfLpp_{ieBUc=|2VP z{MnQ&>m^KU5Py6wqI62?x8 z>e`CqbCA=0XmpelkAWC8MKGu8J*N)o5D_l`aFLii?{X- zQaf6OE4{)s)hj2yS9PPv=z*Sz-5JMaAN zcR#=O?CX@~;tgNxMQDnTSM6HK*y*$tP4|i>H+|;J2A8R%yl`Pz1LlAkXOCZg4NAwE ze(Azz^^0lw+2)t-(a^Bgwl*ExIQf_~=&^Z9JjbT={J)<1S7G|2$e27~$mw9ZC(-FN z3(6}li|iqneb=dT$m!>HEvC)sOwtK`{XCq@{N^{5H3`#CeK+{wTh!8?CZ+OXF-m${ zU7n4SQ6yh1FZfF6JKc<&{>EEx{Px6e-+1FsAFheq<=%r7KZrH{)OVx+r7v7Kxs9Gq zqI7Czzq_)JTGPl48{B6FQ9j2Yo?MjfKFTB8i`i6eic@Pu%KU`_>&d>eMCsU1eEn!Y zI*RmXwNs?9_|m0ISF?^@i@BC{sjCCtW9MM0xND|gO6yi*$w^K1fOn@cqi~DxStw4Q zJZF}l|3X|Z5%IFTF!41f5w6JTe!c>92B4mv?nLk-&nYxTZHI!E+}zxq!n}~vVeEx- zgz1xwE8QsSNa~(pOfZ~0DE*|2RG7|7frEOJVtE19-AQ@@=>74!4*}uHuk@mJ#4DGj z7|=XuIbM*_vu8TtuMwoDr24QFcHNt9#B_x*0-^w_8XFz{>9ZKqZ;nj2%<0hjKLh4` zI~bkQ7Yw7LIy=O4JDUIOnV+GgKlPOL<1-IG#U046egBhBLg;`xC-*<8y4)SB90jEg za=z)*V7l~gbGQlGO=jc99^trENy7=Ne@N}m4v|OeqC}6IYP@;ca-Ad@;5aH~V-#OSkn9$N!*x5w886?z$ zbE^(MkHH&IuNuEUluX8|1MU0w&2?i(*QXLJg)T!@CKA zOThHZq?+rsUyje&|Ay1$GuKfvMQ&Lx5sXDG{Yzt$`U@*di%MfdW7^}AmWBetMK#MZWjIj|JY7I39F6NwB48(& z%0p#>K4s^n6f9vUi04-6eC?+@<>kvfBDBs~Ilm`=4e zU>SKh{ R?=lb{v0UF4jaxTin4C+X^ga3oJzu%bMEZzopRju<=gC}SPK&lNdRW7z)C|I{_>N;cn zU^Ozm;e)wueG#f#Subp{nGR{InDpQ zyZ_$h_f83M{NZwcXQf=Y;c;=NAkmWmbfTUaX*AF&>G2E;qt|6*j^%p!kf@X1ULU6( zTYOs`p@d#JdGRzP1yE9eQgEHHyp%LyRVo#SwF+l!rH%5%XtGgK@oePAdw}VA9n<2Q zYKzZ9>A(Ey+e0&E;8>5`b>-yAFLxaM_5&&8j`8vN^BXBrq$F`|V{HnBp7mkQY3Dm4 zGosF4+I#IIbG2)i>Q{ZXN){I^FIZpdXLNPVK>x+^LHQ}PerNZ_sg#gz4D(2>yNKuI z;>E5RGs65_rVI(262yvdiF^0dAw#;y21S$)sSXON4qE8n;OpW+1z|&jM^8h~;yw_4 zzcBqm`T4Fs)6polrLWd2m9Xx3lkXy9gOe~l-qRLo;zusd z#zV(13)4UU{OZRS4%Lrski$NGlr1uHtffpgz{GjQt4s$I6Sc+Z~5l4@!K7(+}aATYLJ6p`q;xo%#>JklRj zWX)HQuhE}_C?HjfmTofi>tXcuSC1aWlYZ^!`mXw*IkYjN26O5ZdWxpy5$}ka?&I#s z?AB)*Yea7GuD;wBH#WuDd7=L_A4-c&`KYC*Q!NUo(*xFmboRb8dAAxHQRc~zf^0Q5`i%-mU-*sq z+zhLN)T$x1Q@R+P@wyP5Z+I5kSBoUIAbr4`d-{Q=<$ICyMYt>Om5^?Muw7L@{PycR zcGxZBpZ#T(VA>G15xlXdh|jHK3)W>?FdiObeD%#8*4W8-{oG;Wc6k@4i>aX1l7dJZNQbF!3@9BH z{Jtj~x#^JlGpOm}^gSlx#VG1LI88?Y`v< zTOLA#6Q|##sN0_?yCvPCb@e*J@nRS~d_@$fO#UKvE&g?LK7x>Qr>4Ra?I%wB`NUw~ z8-sn!cPsi5mK;2Y=VjpBLA);q4tO63*fu@!#JTmlp#S~SuI>t za3<#L`k3u!$VgWYMEE?@sOT^{i7y5H)V1y(XdfsDrKe^vpRkrZw$ghg1G#g|$N;wZ zK)?YO1h6uXsoG?5iayP6!<%j-M?OK32KlTv`RNaufEN&iaqCUTci#cAKg8kbPe1*1 zp&oCKBI z8u+N9c(bUe|DMB{M3euXaBBmQzS;V{C!wdw&OlWKps~TBI*QGUqv7rI&S%K}D zF$kC>GzJ808iq+>;@v}UA9j1dvUczBRH_7vhWD1@{h- znhg}OtFn>WQNY}&%E5wkev-*s?vVoTF;Kc=sR_u2t?!`antVGv6yrs)%3>`o{kodY zy<5vw{DEDGx6U|}dHv)Vyd`xVVY*SMwL2WB&fH`8xCa#*#Ego`^L0jdJTe~K?IS0R zWG75m3Yi1x^kfPR)hRPa1M5qzvREb`FgXGEOo;UG0d+gQ^Vl8ZrnA;X64fm`4E}U` zC8>q!b1gaD^j6~0T7WJ{CqG?#{Pve7%*$L9E*)Lj1&$Y=1GE1Vr>O8#7CHWIxicnR zS0}tK40jK7I$SS?($UjPNZa*_%HEK%sQI+q>8CHwDsGK%3iFICYm=I;(AfCm6y)<_ z`j#4lLJlSXGNVa7Wsx;?T8g4x3Zns(lm9Pu)(R_RL&}Y9U_z`wN16z-C=IM#MXQZp)-K=^INwzw+wCtI6vI_)*A_(tfWTf zM9_0{mOuF&ZppdXxzW+#UA;p*cP*Z=8GHI8mk*t+4a!amM<~mydr0rGN3pr9AS?~i+kiwx7p%tc{y|lZSb2v^-4b(=jX00-o3cN zxlB{KJlFV?;%w>?q^9>Z^TKOa7^x|2BxY*VyPw1uMd>Ns@ryEQN@Vq*mTg)`C`F<6J<9tW(`4R=jLgdOJy^(E>6dr&Ric($DW?5%a~g@ z+5a1$1mokd+K-B%QIp?2tO81j={Is-UU=c3Eh$~%vpnh2)IoHvhEv3ltVQMmbrHXv z&YuR?ElMZvM`pd6d zXf7lAlZT&VJo3ns?>_zrd@i>Opl#H2Bc_{&Bf1t}GZSI6?E?9yPdp=IIi!9cgbtq@ zH62A=YPuNz2Bs7BVlL3FDC*^5)O2P?WHJKkQ2HIBeTL-pn;4x^Qu`AHlA9JrsOP4k z(J|~Us1uNLIjutRqPYpv-BHxt>Ml|TvwD8LZWtfa&&ljd9vx7M7Yb0lHF6F z^c9gCN?3#}3E!Nxneq)-+;Nz9CKO}(+mhAgfiZQOXUI!Go5i(oyBtL`$D}S!KT5s` zqIxKp9!sw!GXDbRtrSS8-OT&%zyHqr@4Phf{eS?Ph6EfKf1qkEj6QVwQ2LJ!)j?y# z&n0bfD&Wx~yO!LEPB;7^Pdbn;`m)BY*4aD2k%_}T{q%h>{mhy5$zXb9MpmY}kYY@S z(oxf+D-_5W-Hg+vD06R7a&2UwDc2AI8SE>z?FU+_8Y_=x_G zo-TLUi<_L%S`u4oYGCoexb`^I^rZ&_Vv`aiWfO#Gf>R*nqKq;RV7PD*^`e29nMIXF zSur(5>naz)>q6?Rq-9InNpuM=sL3n}sR_&sDJlxdEC`t3omGV81zz`V4+x$&;dbRQ z-u)nUk)=tQ_bg4U8lQL%9A4N-`KXFWiA^u_YpU&os4Hs{S1v{8hpg#IMQB&8X--N# zXmmyf3p}OmEtP;hklvTjJV;yb%D%EP($Q&y)RH8fT|JpHT4L#@YCJD3GN|h(EG`Mm z3i^}q$B;0|Bqb{;>2F{<60HRFTMT*2^rC7_@vz}6+5kb0ayLlT9V$uO3|<;( zC}aQ8zOe5`EeqVn>&fWp2Ga$?ns@-hI>)$u!Xykyw@ol>I+RGn#4Ib|ghe-@dSIYf z-SWW5=i)tSj5WDpw@;EgM)YpzoFkp%`}(j8>~Om3NU0-cm?MelY^T;+9H{9j_%I?P zBHSa7ZEm*Y^ovSsDIu$|tgen?%joE28PQ2^0a?hT#+}}ZK8aNUlL9Vp z2zJcLiOQu*VsC^~{hb?DT{$Kf@-M%-eEh{1UO>e9&A(hGJDnlJ`3D~WwI8c|lxjrA z+QsR9X+9CXm{9PIr}fs?ueo&964O7p7QRtEM=`yqfD|V0I#gfZH3L#V1g{I(%Qw`o zpsWhzXR9zBOs?;$9~;%xRo-3R)jhj@16N^mmzURfbk)!9SW%vl>=8sO5L^!&rqm{^ ze1GLTRde5eAO8vB^vWbCodYPIlM`0$2BR*R5B~ZsmUNYo)?I9F0XRQ=KD~ zyJj4^itXicS9gi02hM({RIkuISPwDE;)u(H$Mtb;ZjUhJ`Q4 zFU%o_r0&v^pI7~^>Z|6kJ74|g^>4n!3PMLtS2s^v6Xq35)pa&~NTaQqZ**}wsc>rFB=-t)r=H1ok;QcR5y=wxcmx`tbyqTF&#{Q1y0At z!>lEqr2=9!Q`2YO+cQX@%kM)VZ(BB5LF}|tR&LmoD-@TW`mV3@!;4$nE}Z`A>rXDs znm;*xak^*IuAazUSZCt%irWwYMd_Gc{*32E-gF`#T~picTKnC=^WyYX`&R9{a$*2T zKX>YEMj3hSyLw7|C_{A%>zKs|svc4;XTPs=x(nn=t5KdJ!u;cBO@`AK&Y3ktEI+oI zqwenVL&)ftV+eO4dgAJ(u3jSc=`}iqRR>?U-1uomPM@ZxLXs`R!g%)5s1|T_2E;+@ zg+c!Q^Jn=3=Mg^6Y8XIHdxtxm?mn4Yuqa(KI-B!M7mw_S$Ou>7ehd$1>?kn1#B{cG zrm?+DnF4jwv4~@S$+c`u*F0=qp3X$46ZPVUL5B9E7N}!=k&PXN9afjr&R`lq6)($V zIbNPFGe_f2Cp|rz9Uw~A?g)A@q;7oa z@}|G=o5Mdnyz@7Q!S4t5P$bF$h{Zl*xK=+SrCWneq^iSw>>qwCU-}dO@WhW{-TR+- z1U$a~ktZL4ln(>azs8Yb4`dOizp&#~NL?2=jO&KhfpjkU?Bvd3p#9s$#N5WhP7HaB|q|y78uKK|;RtPd~*DWBlnDUksKzj?7Qn zXhv#X%q=mE8KI~bsp)dP=m4nS@{r;oZWhxW-t;b@T*aF+W^BN4g7JhN%a~81%1Lq! zbJN-k`9UB$FU=BC^2?gu8a(m*e%xSx{`3CW6K~K1va>JYp8c@{Q2F$2dxl{}A5%5` zKs!DcZ0XyohHpElQ-M01jMMZs6)VEJSA?%92@g+> zjEc%GUvxBNbBG~yjs)d0yKpRPx+HaMFml4!<@D_Zo42!Y&1bDZyGyK!l17PmrHc% zqt|Ff^wzi}7(Fg)QEPN^QC46ny*cfe-kRLJm+Y5NC^R!EE7MaR_m9-fe(xB;WM5tkZX;Ef-77HfG>y?#F z9+8#(N$r8lViIX!DsV3?Kw!@*Z4a0*KB+V-bRPX;mw`Zup;bdof69sTinyJ)WpT^q zZb~F-CSi~~M&#{IKHAWO^61)Hnb3)lUzkxrF)PvNoqe@Az&pK`h-Q&fzO%BWrLvC{ zcd{*;YX%Dw1`}%XZMDs`MlEe$TAIQ3QuYt7Vdek;AOJ~3K~&n*8Q7lHLPlgJCYp5# zG3}XgL@+|=?MnlReksg%&Mk%2XlU!p zlDLJaTo*mu$ht_TT-SlV;&caK>M|iF_(;qPV!EQz858$lQ&-`r*j&yD%RgaE6y}a( zd@)FF1+{SVARkO>Zd;+~(7l}xrH|_#DR$L12tI|3yvhxwGw0AB>e#wLkdn>Sd0m@Z z=5k`hg{Y=p(tx^9)l$<7LYH}u845t_aSPH7r*j@e7pIHTmG5E()uSSH2c`!D&bQy@ zaJ6$AhSwd8?y%4}ezs0WfazvvA2Ow|gF5fx2XB$T=4LhBJSqpKkDD-Q!nmPeIsuY0 z#ZfJ>EXkZAtlL#}s!L^nF__MCq8W`UXYHWw?al0jN3O$lP}go@osL*_RgO}gV2my= zsT-8enn{&rRlHKP*L7?T`g!=ck%8-?M)9#a2d@i-qkRAWKk%l`$#&d~QPUCAS#XEm zT*+IMM;(@xz2Sbb!-Ob6QwI&-gIu^8O3`F-AD& z=4Uu}bX{6dNl<)A{h@C$zFeAdKFpoEK^3TGBd7a&P(fPjg-{y3W=(6|nyaVxo-Vq0 z-Y252ZsGEvt_AsP^5YjSKY!uc?|xVHyMtdOZ$wTPrVn00V$O!2o2cLc)YI>pDgC6f zGSb6^wr_rAelBC{4{6~*V*2MNE?&BGW4A{co|m?CKlJvQ4e2x_nm<3iEWIJ!*)PS_ zWAWm}`*ztW-8@}JP4DUHp&Ee}o{jiqh==j>ojP?@|2cH?D;t_3JyL0v1gFQRRC~rZ zULjO*08H=fBtic42VZ}HIbDrX8zRxeQPZ9CQrn1Fu+(&k>EQa-zD`>nlOt!`=_dvT z1~9juyh5lag8lFNuSBx6ljrFXxr@7Dx;bi=1oe)wW7%)Mgd}>oiu6BJibC@Zm!*)d(OPF`cZ=j1 zb>jU;n=lGQnK4UCXK~AAi0>40V?icjkt5V})NfbUGU%G%e3WuwxJ)nj?(Lv%tm#0$ zqF%svm6xhPDU)$B_qkEr>9gm|4hqXA*fZOW7Nzbk_WuTg^!o@nheq+P;CV4IFIZmW zO~1+Xa^040k{Dn8AOHLUl>Yc*hf&jo>Bi$CpNj^!W{#z(a~`vcP}j;!L1#A3?I)i2 zF%Fpf!D1A3;X3I2`i@sWvtkqf_{Ud|zqu1~|H~_{Y$POI!(wzq^o_54#@EiB#}B>u z^1H7e-|;domtXygY~9ray8& z`o4j5ZJ{=k!Ab#}{un#Qa5|nByy-%5^%ec};b-=sfTN~ALlmPybPVeD4oBZSY~6yn z8T*k)AKS|w!d{3@$DaDsc;YveSJ8}2>wK&bbA?*qez{hZH92CRaen0h=23j!lP z9bDH^Jo?_S+eSQOq8MdwacJp~8b9803$BETSl92qTWb3D)ok4QjAJ3kvcoftnhvF( z-Lg(N9Du(;A&nx~w!DZ+gtqkdVsOR!lGnAxTTw%D9@$M91grf8*)o znb=a2l2(pPY$+nsB{ncFDN&I)ri8RVmi-yn-jZ)R0m0*xXL4ScUP`nJ=9Wx;TnF*4 z%a6>?FC{pgvdwwqtQQrnTa+0{4r69%=RxG` zL`NqoOxtS`@>BC`mV_={8W{L}Ot&%_#h6Tdk-Fu2k)AI8wggfM*W*mb&ygswWGV{N zsS@F;a=dUgQMw&_4JI47GFIlvOrP01*rZcts54ZSprBf1YvUGn0p4CAYjTg7p6aF&$Zc_M9p9e;=cllXc>Tl*ix*hdMcou1>VP zNByQt55<)}#e}`&wi?$9VK1|CH*AP(-CA2gTlJJw+TARipH_#`P?xurBigVN^@5z< zhI2P1&A+3gytnJpB@E~@RvlUeo}Xo@nI0iu?tFH;F#UH&o_+lrT+^uO2GhU&_C*N2 zqZ&XCn!32>l~>e{e(_>tUSA)#oaEZ3-t)zEz2^^g^_~}||MlBzm&!LHqbnHQ#4*-y zTmgh5qIV0`ySu=2pgVj;_t^Rs8LglE^`q0xngW#X?t;*Fmv;rt30qMg)rD5d4_${k z=G3!zT#nG*%}p@QcLbGHdcQw+?zVScdg;iwKYstEk%^_X@wFI!a-32?W|VYtC{uk{ zL5RmZce<-bC;(_Sb48f7(e>puYWa4I+R{aAu9IJioT0|eVu&KG}+mi zpcu>!9?I+X$R@`;tar_&@MK$4WJ&jV`mrAQ_E2{i;<0N^ZG1ebjHG*{db!4XxVZ7@ z(R#j>Y8v$PkE46b^NOqI%qa=qlE1EX;lerR3n?J|-R}|?^}Mpx(oi{$b~)&m^6sqHtaQiem`Lm#?a~(HEybzEHorr>w0BOfQQEGYby znhoX8oQ!9x0Rf${@5(+)Mqj)3k18nWX=oCrV}f5x(P^8r^VBJeX&L(ab7z}+JUv*g zQAq>z>Y3MwZRN{z-(Bgv*x8p?tyLBIX?i>xzRN8EYo~a ze3wsl&1MS0wAQ`4!>0pCN1pafb#-+a0`$wPGM}nc=sky?NeriIMYu$GPF_9}(>d`v zO=@UG>8`TPF{W!U$IFRyMHr|4(N3a<>KzfIu_acDbD^L?o&wcSJB}o- zKk)Qp52%Lpv4@{}>?!U*&~8L&QLu4|$Zi6qKk_a|($sg*pVSEIJ6`|wj@Ms(^)odx z5~u%h6^B25MpGn>&pz9+^Vzpwe)-vVf5n00=Z-x0{t*cMIcOb9H(dVQBmB-HbX0N- zEtXpTE_%5x&4?2tO9SV#SutM>ms*E;U`YbaDF9z$79%0^4a8sExVFReHp|b`j_OQpX8IAb#)77D? zy$cG~M}>#1K~X1=QKpym>(;NwJsrI!WN&_QIG%5s2$dF*G+dOm3^hF_E2*HgXkBh= zazet@(xhc^=hCN?W3Um5O?aB|)(>p&2kw0M^Ue?y^-h4_4$SRMPMk zJ)iWJW+HMv3IrB{28mWX-i%LRAYF8nssRZTTSubKp|JN`x z42}R-wp}NXtl3CQKQ{t8_h^PBc3kNqa|7v=N8;=-T{+G4SwI^)Zvq={Eh1=@$(qh; zA6R}D1Lq1$x2i`K73)ybr?^M03muM}u7_*}(-YoZeCr)&hIz}Gi>z}GT57uWIQ3Zd z(4~0~A4Zy`Lrv#_nzyqaoi#AM7)&3z3`S>VivzUIiOxA_-7cz2QOC%`v#T9r;2YPE zrX~FM2(~nJQ$T7}ky4dlj4iq&?P9a@C8bMPH25`vFky4!M>e=I#QrsIcYDGwbIQ^H% z>DeA7W-5X@=b$RN-Acx?_iB1;xKg zzmRV3_Ni z_!nAN|LFY-IcVsp={>9DeX+dhQqV#5-AL+^%u&;!^^M1l5u5%=(T7`uc4K7kS^J{deZB3?YLuCB8K` z#V?gJDY)+QoKtbU*m4?)>&nS(B_|Q*ur1Ywu^LDxhVeA{E}t+zxNu%|hiPf-FZ%Q} z($;8eV_jaJGqVt+Rt9>t2kkO5=y0?k9KTWID0k)xgi{{5Oz%GyJdo-0=yF7jp|gh{ z&SqEoDizmtUWzWR=pOvdzB@p_amocTS85@ z_c)sAm79^jsIqCMud{DT;nI0A{hJ90zj{q#Iz5=Wx?k}uQw1rQo{i$}RqL0UH*FeG zER)mcPxf>7SiAU9K%L0@eTy5!>uV|I#P!lMsz;DsRq7x zNKdKh({O|MxVxv+HJw6EKXs+Av+!cA--SQOoW5{5YWmC+%>}Vlk<5rUed~vvc!b_U zO@HIV&aIuDjmlKdUQ8>dFJfcyy69!~``^PMR~n{n$jzx^Kj*npsOsgF>W4AJ*qDgP zCvu#Tn&Jbe$5Y9g7oVoImme&|@zPzsVu8XJVf3r(FY(IZy`q(@AI!l)lv2xWa-(Up zs@;61%o&BL$HV62la|(tl%9?1PxL;kQqDt&PXEE^Ietn{R{#)tItx@`T*(c)`5cMq z9<@zW@#17B2^0SkHWyDP4_BeLo0AJtx--57uZRdbFa<4Vk}fYf{EbBJ?q)b0-wQ7= zuI@^hiwrKtnQqx$IF>bC-!iKka7TrY;$5BMJJZ#3)Rft?r%ahMM;bee0qTHi|3`s0 zTF!Lv`EjuHN!0Y89)8w{>A%?d3sXF5IbN`$JHGyhfpmOpCc*HD#~#DN!A(3xedROH zJng`AyC>bmGpeSPs!}uHbbEFR9vc;u3ZI{R@?A_QhdF+o;FrIA_St8zzW$e2Uw`%N zuQ?00gXzZW@|UAK4t<8h{OC?3bd+*DE=Pd!cM;K_dk*QGAy&88{E0Jwig`@3_O1@cJM@E|6qS*X=PJ??DMh2&MNKY;DPB9 z*3r=qPTynXbc`_vR-bEc57<92&@$LL5F689nt=;`MoF^gShB!+%ge*d7f`%f9==(Y zm!l$am5MTuq^aj4dPDu|rEpP4T5twnM{3`^K1;m5dHYMNCsk1r$^@b6z{oM<4~#q) zeBje<X&=irgIjd;e&Kf7(%`-|4>4IURz6>#q0fic@CAO*GbnJUyWr_$9e zL?=>?&*xziN3fO;kKby*VZ=lzourpNBg71xe@Ne|+8y@k@YUP#rWc&e4X4R>ct4JL zCLL#Sr?1-*9$lFg7)ZI}UPR^1St09cQPcOLrf<$H&0HE{FCoSBvTSc0YI@T6>mRUx z^E3GW$c3YGSB5T)&7@NhF@->EOVX06U@AHf&P()eUuhy=THsk^YXS_(EF7$)1?b?q zN(AbdL~p2^deWMtkbIkSMk$4;{p2$)Sz5CelUq zs+oY9NDBX?=&A#~AwnUzT<4N)rPSVLbllI<) z=!$5s`O8PokDy`{Y|${T7gdwy)wVVwr2{Xt_vtu)>FDKa+js8#jh)W%w|rx4E{Ct_ z=Dxai_SKUoSFKw0*~ar1tPsX;zrFhAq0c_s_(u@EaUWrf^vW6K?$(Qoq^z-thCzS2 z^zr(u&6h0o{dcV;cOs|H=(%&lAMgB3y+>6-O4^I5B89^-wv>bEl#(6_@A~AgpA>%B zdVWS%I7|-3cZHK!5FS?2Ro_85Y1az=3{jnkn6YE)i3yIxn9!8IwlA@2lT4ez*RZC~ zeQ91%j!#62cp1+IaxAP4I@5Zzk$(1gVGz=BBGam-3@tpO+)z4(m%sj1z%I*6u6sjv zTOPsf#K1H*<~91Ia~Og$hWmV!M?-F8gGa`(bqkW6au-BKdf!PC1sNi|WBHu(r+zAbS< z_njvXAO8I*e1mQvDc5Ih&b|k6zshB&0!A+O%0x(}TKu#pp5DwqtfVe)SSl zH)}#WXAXAtjojooavhFJ`+r*_YWQ94dM}iWB>PJJTJyhj(m)o4(Cct$MUlC zpKi1ueZh)&f!I|!Y64zJFnnEM=|8)U=@QNXemGr9x;gogWlw)hCr?@KmxrG+5;aHv zAc6Yf$NvGoHIlj@8%nKl%EzufGhR!{(N=zK>U_^~YKmQpSrXJTLtyO7QW_dm%MI8p7W&IzpzUR$0Q z1L?Aqqo(7hmzr)|FApGtOHF?YN*Ac>H+-9PMx&*R*KZ8m>DB<$EiwIRx*R=y-yT7u zMd?OQ|NA|E|3lM=6!VMyi5lhZo}C;O<{p)sEIYcVdl*3OImA6GIhj*3W>rE;$pgR5 zjmF_38U4@d*NI@gfB*9X18o>vy&HeEm(IcJbb~H&2$u9PybQ5SPHgp z*XL(x0&awR?xAcDUeC%b2=!Ll3lxu)Wx-}#>f5tIyho1t^wa6n$88(4Z6t@)<3r~W zidVJi=T%FV(87M+_;H_(<7@a!FAcvfcv1M?Nkd1jKIlChbGic4fBxW5MW)MYj1m1d zxKXrZbW+QoE-_uQIdE_*XM|^F+zOxHf@Ndkh&?0rAbO7bG}wD}fw%XT*XYckv`I#j+ zk9f(OMo6SBmfjN(OJQfy3F2H{gVj52>9w7G#HJJbl7v|$Hjaiz6`jq>O`y+qa|^|+ zq_@*=w1!ys8l>`~PF9#RXl9q+SKE+YyCxy4xhc0I!&d9%g)gQE3p>{&0<&_ETG1Aa z>2kg#)MQd6OP8ric7NP5RuXQQUR3UA7}G$yp?3LRM55M9fhZQ7QpTk&FSz)T>4!-T zmnmDe6;ZIL%+BfJV9~H3U4zR-(9+VmF}=hT7cM+BLzrm40qN<+_5%M|fC}b|*T=w~ z+`euMX9rs$ayPyUekVUVeizL^0Zk3P%(Xe(t!`U)?$|yq)uchgoHGBwmTfX@1f16W z!=zlKf>M=`Dxz`H7~Qu*-yK7eI(4v2YRoExeJ29w_Pyy))9($Ma&JbU4E^SP#+!>d zu-PCXE^H9XRQGYP$6}ZXDl! z+XT{EZoh5hG9W$E1hkUifAer~y4)|zmU)k}n{gzmYu_^SnPifupmaqsYPw>+%#n=g z_F?xYY5U9u%9pNjeOuVeJV7txb7+);m_>&+KX<78{mmwn)Id11$ny~6abuXf$J>W_Ec8CKj&R?7toy%E$8 zT~NTD64P1Lrm1L&rx%%gjcvu%)s25@>pnCi{1dMG(Fb2$>oRfapKaVQV-*4Egs0EI zVbi5x#u+H+GY)kf;)n7X-6-hEQqwhsv8GBi%aWp`ewL^UMZ6Y{%~I9+9mn z#nBh9UQM7G>1!XiR;N{0&lwW6Wx=rpy+2rJ%fCmimv>I|UAeOJFljHRPF-ngj4!Dt z7ttCsNd|1J$jE2{Yx9y0R84yM^6|?bef0U)pP&BZ;|0kSYI^vlucZxX`r0y%h&rc! za(>&a`E6{8RG_Vkc1?lN=g;>CAOo_sIz`qcStgJ1ssn{%gj zO)IYR^R&69r6HDkrlysd8d5MF?WC^wlg}}y1J0u-FL(BebVW9Hrl);sbY-*tfp@+| z7Qj|XEERcab!pS;Qf4ime=*^!ukh%6@x_wFUw;1iAAY;<(Wz5C702I};>3%(OuaT; z=r1aCt;V8FwXPHO1a9$V9%Wv+{?s8*i%`z8&*f{E&m6s+i6OnWdp7ggIf(j1#A9s2 z9YZc;N?P@_Y13rZ@t-`$g^dHP)hdX^4GzrB0B$$A)8TYqXD8>NnL&PT%-Y;h$5{ah znml^4uLqq-XA(KD6FmcH>z=f>VjauN(-qH?3+*FW(b75q&$2JmVOibPf|TLz>=f_C z;te4!PR_2mxgN|uNMW=B(>bFWS>sf<_e2u8^BQq?@r;UcOL6iaGM4O*sdMgS`$qe^ zyAlZL0O>#$zwhVjX8+G&)O1BCnvOoIwG^elzVjE@U3N-M7nO66g8t7E)L+Gw{=y5V zXgm6dI{*Cau?N(|NP_$Wz&JQ=eOZ{!Wsg0D@#X2q(Au$b8<3a%MIk80S7IpE;H^;k z$#-e3^rR|3Uw!%29nbFE@uGT#nmk5{>Yu&(ELTyI%aJ4R{uHV|!Zp_KIDYhHA-brX zQ;F$6e&ol`f##0Ek3XiVsPuCC!5Cid$Cj=Oz-}aU1a`S#*bLKt3FAClsHp_CuO!Nw zZT=K5`NL065R0o~lt9LbGEdyH=K%@nT*i@6(1q#-({CX9^>Yq$x)t~G%+uIj6t{B+ zpl&ScxLypR8%h1T>4gcsgz{{9$R$JOB?#>!y$u<|fOXuIf=%=1P#(lQa4T2NBZc zOD7v$$~bQG=T8jmf4*hl;I@Ime(E}m0R~KuJwVut(iqXT(bUc0BzT}dVZeJ}fBRs| zz(CFZ{)Bvr409u=PMsNZTocF@G3$2rz0oyhxB^~RE-=ubZ#Plylm+tXy_%r zFulAKymxa9e%k&}ibzRhBa-GO!))GZwkZV)AyHl$(* z{4NjOG4a+1pB^#nsoOps6FP5__ayIiE5a9Kl&m3+QAscB<$A%JUYHrTH##{#Gcc|+ zq(7^O1?7aj_Y~!a^rNPmK*nU^Mndihtci=OsmVO}AN(x-ue_QmA+2ea%Nr#;p{6~! zY7+*g0D=ZXPTutz5GvKclogF_74o ztfYSC9GM|W%jVI~bV)$f@J+*qPKYTjT{dC*c=$alt9=5ID6IVaWW>mM^gK;WWI_<>mngpmUQ4KDwa|TsW*lDmNtsXcx*^82xL36GT#L6hG zDFMII#_=b*vbn%<^SU!_-3>+;PqGbMZ{!4ER7}j!U+eCToNhQ>0gc|?0ZJH0q{pZu z%bjDOrn9fi1jo2tRMBoEbsgJZy;JanmSie)UHg(D?OX@*WxeHoa`)Xgf89OtHnzfG zy0t|C-l3UUd%eeptO;ee8`}^)4|pG2RBV4-fH9cPgyQxI1vp$RI;U~58Y`GVZv_pz zs7}s*=t#DTXPM_(lO@UOPcU-&A1>Owrlq+h_f{_qs_spWPVUXkiS$yjX$cwCyCOaO+S=%Sls4`Bc}h92 zz5t~EDHx%+4eO?obRePME}7Dzx%dJRu@M7D&;X+1{gGT(7t=4veN-~ zg)?^V-gsxpMbz|*oypxD9sX0oJW(0Ldg;Xec1^&*dem3eiZK-7x&$>lLMs5JDRF&yfiA0w2VO4AOOELdAe_f2PbZL`UJR#C_8pb6 zW=(i<^gt+ArX=2yJ1t#+X5z}rx| zRX<92Ww|qgIHs4jwQV$Rh0+^vy3C(Ht8G?WUGe<+b+ur+4JW!?L6`l-j9ooFJ@gyp zqg>zfC-3HooH>8~cc;Gj2G>h*TXAZSCl+_tlvFT1kJeU1y--n9*r!Ow55E4SZXvxv z=gjoxa5hwq}ioSe`l4_^5VZO;JW_!{uCY%P;fBDrrOIQQ={I`9( zc8|)Y?6fYAki={Z+#os$<+E6Tm_>I`TE>!QT8N@ z?(9R>ioa7tE`3Ga!d#{-oZ_nrQtkJt=`M!R4W~0zRyn69wi!d|xiC8q9J`J!l}Qn| zHD~#hg$h^)!*SNTrKa)@b@q26I$e#8l$LJz-rX406~m~6M&oxeUUhe-bJ^KWKD@$I zB|CP?Y_UIu1(@G?r+ZodZ|}vKP64T$=?}}PefZsHjWPWINeb`DotHKVs}AE zfBb>Re)hAUJ@B&!e)OXs8U5T4`U6loLzK?YMF9Fg@Xc^stXYA|GUfNSv-*#P>ju;* zCjHgncV9pH?2hBFAK!Ugl>X~q^G)daXRp2tnm>E|#TR!RKfd!>H1%hny?mVWJ1##f zclvWE>eP|~=Wsa(eUaaS>4h)c=62hQfLx{*E+l70Sng2MG2h_4AwJ!BRt#w?Y*Hq5 zOB2V0f9q3H)A<=rf8x^zq=DaZ>#Za)+Q)TJ#~9<#&K-n)J?DiBtRhnO(bG>GP=5$e zw`?!M^gVxXQV?w5?pL1Fsy zp!xHJry!JXJAkT=aE_?XrR@Xl&r3&_v<}Aa@83WDK%&eqbR^ZW(#iQH`6~w#_xHCz z^a$&vi$WIV_vc489u?Ac`dGmAx%9n zj!bSiJvcbgdu1Z!jryqc4lW2?J$};gO>jDtK77LX;Qq~}C}v|eZJN78LFoY_$H3<= zy)<$pNAGXnUhw{;VUxC<3qI$~l!C@a22{jGIx|d_fueQ1yvCi*XT8#1o)$eoAPz*w z>Y}s{8D3C7F{Y#I1;@+-V7wPG^T{sRf;T-=YC0vP3S=zGtjQuJmlPLLQL+m0rek_3 zT9AO6z6{fgu$>k>V0u!2O-tN(`xEuwc{19!)X2<($j$8N%%p=uhy8q00A}@2ibvbq z<7)Z|VQE3LPG}jV-%v&d5%4C_B`^~$odoqFYGGxI$uA8J?Pu;$m=&iC@=VMw0kH+K z!Psy&O%F&4DP20|_TZ#U71K_Fr0$>&_raeBB+i?gIFAP1iA)D*c1j#$XJ2bud~HQ- zVu>sGTZKYF^F!bOGE1x zXNm-kgIuozv8CpC!Z-o3!7|GLa<{I8amqdn3X9MfB4;z;Tj|z@)7c+(xD+t!z~zEX z$>1QLRi|hn-~_RUdBw_)$NaN+9J%R5bq%a_MhIQr(vH_x73b?DfZL&sPm z4R4k={VQOcboB0^^WE;da`SMqAOH3}Y3d(*`|-ygAL?3+LX9#?G@^eRcJ4N}`pA8M zYAU}}F3-ycjB6JZn64sH^&-Xeq5-6D?0%)&I$sa1Z|v3&-BQypcII|>&sjKyfDU!* z^Y5-6i>99sT65RALraN3f4 z$ZQW>rDL%rxO=$!x(^BR_i>BxLQ2mg?9nwhJR>4{P5y#tP|B(P{2{uLUcNdbGK##8 zX}FxB##B-nO@-i8=i1g{^?SWa73tN&y7OsiL6fI=yP(JgnS{pjbX2_kf9NN;dXr3Q3u zV^bp*7MtJX`E6h}Qg&P0{IzqzK!D2|gXBTNMyRsW-W8~tpcyaoy`BPET zJ?5u3$(;V>7F%&~8{wa6c}}S*i0XM)6wuPw*jHHDxwZJhA3pf}ql*g#x|2P;2wik$ zr%^t^^oGKtW)3JZNHKIMo#yA0*GmyI&5%xi^z~O?eeuQV-)h7EXXEU#o_>B*^|C_b zn(CYm9{c(^J3;F-&V|qs)G3&z>#qFS-5o0~g&d7h&8QsdE9zNn(ia;r)fke%bizfa z5wkAD$H4-oyZPQrA1U5C$mawiI=iZkD3ng6hnur6p^T%c6@`L1xKc*y?jN*p4s%{6 zzV_LXDBbAkv#BB#RVmF;%Og(oWp}0emH7!4dS}0xa|G(kCkH9g#n*+tzj;1Ra5`I` z6Xk0B=#aW_eUv+M5$Z`Lu48@CB_{pF6qT|pV<;Wx552rddekj)Wgq4U_WuUtya3a3 zrax|VHu|Y)K>7?CG_AOnn|U-%}ek!n&3L!ZUYLcsZ}ul|~Qhtxm&?AK>^ z9DeqZN1okz_RyPe9(wWk%Sv8kyi7MEInv*KYD+fk;4? zug4s$AD^URRzDkT*X1br_~WIn!{I+BHd11`3Q6z3|1b*xB)i;qtJL&umNotUPoI(L z1vUL)lypl^7p?Qh95nGT2hv?E%IAg@^kTWw$*?r(>CcRK=IOf$W#o2H)44e?9Xz+b zZeV&?_JTF&<#L}VC$EU2X)>c^R5u1EB@cOodD5+x*LGy?v7&(!e}>1O=W9P4F1I;! zE=qsCos0Mtb{DKLe1Y(aNk5PXpjRExIkb0u^$!*eghK1MWgz;2{`P_Xn8EgeO4Rk( z#QuS$vHe(~v*O|cllBs_uyon7W%n$*2N;Y?dMyrSQvjquJuZ$c6nX<;S|Gr?rF1Xa zF6tLi4WXgllg6(OUcGwK>d+WIakp&t9zJ~2rZGVJJ1bX07$YYTm_Fg9Pe*=w`};8y zLT_6=CUpO{gG?c|4IMU}v=>9v`0;ZS*Cmtx9=Sz9FIge$*RNl+X!D|cOfP#&GomYH)kaM>rWY`MO=)IA z<}zS0N2ZsAtb3Lv-4mBolT_vSeEsh`9X)zxNKF=jhHCxW~(1Vc$_AeNV+MU_~3fMKY7+q^(; z@5JDFvEIS+Xn_NI3$u>e`GX2Z&MTsDSiQ>MrTW*C?r&Xt7eT!I?~4V|B~VdfseRkH~WBZlS>*4=Qd zAMAsxjTwn>F4WhJ3I2`G1ag;jEO$DyYR336JTgF=hN+Z|THmUm)v|-V^46?G7%5#l z@Fq2#rhlFxlduU{t5$X?o!ttcTSI5q&o{m%qNW?gS}O`{OF>rAqDAXM=6Q$DUNlr{ zI`)3v$?R|Y!xEs2)^8s-!8;fe(3k=wb5XiNpt3fH6j2nzEYmRr@Z$8Of|1%Bxp#OD zZ^s9Yb3}zC9}^>|HXYte1&-ZbnWD z&5CxJGW$Q-aP)8glNjx&uHe^`{aKE8bA>frT`{jjD@1DK-6cXGVR; zELzxPdlG{HSi$7ID&2F#L`=(e#UiSH59g07zw_$o4(hsgm=&Y%^1sEyobNLPlQh|gAVLDIjJ7IB4?~f#+P6I@zsy$d-}Dh9xd+hv}LQp z(6x*mjC}>o3+wO@f4spc=~$25nH&7S?EMd1m36-Ejpwjo4_MI%N??ivvIR*}%LWJm zA&_8z*a{KIKP3ndFhMcG_@fRRiyh`15wP)0z1Z1on2`{6U}pJTvHsj^!FqqM`}$lT^+-xXQs-HO zr_`3DL`4<)*$-_U96fGqFSvh{YR|2d@?qZ!h|P1M$5BsZ&sfx0zQWT-2+geY+Bj!P zc2-vHrksRDqvzrDU%&qPwtY1ZzVY=-U%v3+xH4XZiPp%hZfR-p^`$H{^W}?gyg*+g zlg0SO!I6orp$EumS;HQZ-ppRP*>egBV{GnS?pvJRn_jtQ`IzHOUrM;^k03lWR(N2D7BaXdn#@5@tev~M;z&1zMi2Fx}Eas7$k)r*)!R7dc!qx zUC_~~OL$SyE*n>`UYo$&tGRf&udnuAq;Ht*^uIG=I*_W)MwXba#zq=OOt%mnA)WnWi0rbY|LCqe zElj`jZ)9|N33Gp?QH<-}1 zU+xurqyAGudck(-HoK8TLXp%&k@sw=_cvrTS%AL#~L6yZClMCKm9RW zFOd3F*2`aa@||e2zS#buJ8#{cA1UcvEkRA4s4Ot^{CH~zQPSyb0iZ1oe%mcK0uMJD zo5F23-Zaa{J-L*ulDS|yu{mLRcrz@d|KwL!k04Tkpp=!8lxG}m>miFQJtoo{ob_`8u?G+^r+{T^q(Tw#Q0vc%~Q&t)c z0bw%Xeaj2+Apuhi^ymy4#Tzx2G}LqQ9pn#j^T#hS?J<*ibn4kC?8OnYkOS@zIG-FAUvNCGG2iAcv;zrP%mj} zFD%SH#Z06Al;#_Xc!@75=}Rn&Z>X(pC=X6{nd$@yo~wXVWN9>DEgDh>1&yF?KwbU} zaU359lGH7axOruURh9N)h5*eVw+SV&A-c|>H4D@&uGEbzvJ_nEfB3Y}387ODDnQj@z&P^7$+*&iWhv-JMYrL(Z9AF`_*dVzeY#h#D#*{6dy|!?Bt6}z z=TnT%?3kl2S!=A*g>(}&BEN;{?gY0a=LQ71XUz`2*-F^4Dgum*ZnmVgJ#Cndnl2DG zRGya`yt`s|enmc~{4<#%b=hBXb2oV0ZJx~(rpw&#LD~zB7v?C2)S0YkwlXzTP%2P2 zPtR;Uo0iVA5S(KlV(*6fr7}~}%!fTB-a%!-VFk|9{xngH|IR;+>)v#nE?8{&;twwZ z%?lhs3O^vd2zvlK%R_ez)kd`pjEK{Jd#Tbll?J3kU~M7sgGK5)+)j8#QF~E=i=AS^ zN6(W`evM3_Y93(#03ZNKL_t(^I_f<8;iq3^?b-9yS6{vJ)mKj)$mTa9$ycvz`PDB; zV#g8k(MRVdCnv|qL4nmPp(Ye{+nAha0}y+uv@|}0{!lx_KlD#S=~sV`nvNQen$9q4 zx)xSGP4ElnX6@5II8Nw`x*qNQ!PA&tXm9j#?bfYH%lrx=`4(f~^$Ew*K-N1%7Z+Zb z(xVDmK$_k!arU8+p*seT(AJ0sM-RO{*S`#6zj}O>{@eD<>YJL{n4nbK+oyu)mHj#) z^`_Ep%i}8_-#a)qaqir?Ghn*n(vvDHk+`6AJ7NHH3Ng$;QuF9vKW}gvZR}wvv~;FK z*xkw5Lru5y^o*)q?weK;RqfUkNem5XFPGmN9dw1!u%IDB zWfAne;o64N!4pS9UtGmOCELWitW8?$m&(VXSS75=YvH|fbh6vQE)T-;`4rAxGSh{4 zBuq?hPOkLyq`t!*cBW-exTEapIA0bapYy!^mL+&iOYl>30<88qY2tK~WMcv`!E`bj zO#nK%inHyVo$dHsx`61_j&X60yi!{fJN`408u6x+9HZ@lfbVK&d0re`oFRM{5@VQ> z!16#lYPz}3l$9c-Ps7~qMF2a_2m)Sk$)l&QPViHZzDAYQ{hS1(YyYR#1pCMbTfMFF$nxI9O|NUklj%FT@ODYmkSj7H!%EN zQ;<#`jM46q&tY;nUA}Jy(dyEzf&9hvJc60gzhP>|o4DogBmaelqMxl?`Pp%Wq@$k` zzWC(HXDliGq>;)oxDfmDs#J80=p0z0wp5mNK{{2Y3VpQUxZFLItLhrKUFdEd)`9X5 z;CwMnn2f&9vwGk`HV_2Pb9|VL`3Kk0#0c$N=Jbb^o35Z2VZDY8);Y8Bx%6}k*G1>V>a0ac7oY0@`L3YFC!`LfqqEDK zj(lDkbM~x%%qvG(?jDbRCFCc4eXqp)B;;b^v7n2`LWarp=!!p>9E;0k{dxrD`Rh3x z&4%IK!O@`chP*w&L9?Dm zO;1eR>@#=n^Up8!K}~=D!oxGb^&0r%j-x?5V^R7Hfx3kAyT#?xWqM)gL`fbD)~j^% z))|ip#>l&5nC?cL-Zq1^Pu#Nb0)=Hk{+r#scO}-dIm5DYiGv7n|Cr7R1ipaj`MI$b zl#r6gNCjmsNiVf{)AK1Itw^SLv6dzx@$p@;>r4IpH)q83d3;9+`**%||17IE243IQ(?$9~r_T0vhvc|HIaNW8wGz>bARo8WQ8} zZlWK_H1DQ;)s}PtjuZ{TQyIthD@P%!>l`@(!#kvaLjs^n$`q3!^&J zaYelpR%bUE;k=y8nmn?CxEZE&5*V=pHf7gkH#N0`>m8EO>q^Gsv8FdQ(Fh6J$IFvj z`o~ExR>F%RP9eI%cAW{;ji9d2gg9NF9Gft08MQ55m1V*bW3O|%DDCbf52Hy1#5F?lc?D%@3Gi)bt-pP3J{iA7)E( z;*;S{Hzkh^V7Nu(^xew;cEIc4`qVXD0Y1Dg9-23qH`dxJ9<*Xm%`E;pMD-xfE&q>2 z?FQGcbGqIXgXw0jb@Qyb?!gUt8PD@}Ja67Y&3A(E)$d6unC3kDPiap7qyG_${J;wM zgCICMtB``><^%&O70%1J)d`Ao-9eUIDCTGW%0H5vKGM?E(_9!{Nq3(@w<01#aAh|U z6OQ}EX~zy=8*|B-YiF)KX=+D5__ShANmj|Gh?NH(KcV=K>WIj#l}YI>BT)JuAZ=({ zCYN&`jg2*r?jUJ>^ti3XC`F=C>1*ViZfR>v4ecN7C$qY83rXSzMn~ys`V>(w zKalCgWHK67X9b)Nu^&IK%X?AN@ur`{Bi>Q6btuVeHuZW?lX`{{p$%_W zS_r}EWLUcv4AD4#?BoMiFIVMW3-b0RzW3zSiM{=yZq;<|Y07ci-b$lQ*b#SlrKcj% z!N~qC#JCe0Nk=15I*?92$c|9yp9r#yGz`u5aFbdn5dx^z^mrW#3L}k%??#qO4~l+j zNv&s5Q~dxobjP8+qx2&E=c~u}7UbBw0gdE7(pVC{PQOA+rM{Xs9{BnN(#6NyGb!s_?q ze)*g6x|VO);n`d{_R$}%j1b9);_QWYoOj9KZ>p1Bn*H*0l0RX59zX)LRKo&SI?&RnfxIl9HGS!DVr-sMHA?)kZL`0KHSD|qk%Ljw zjhv3!K8;(E^=PUKsd%7o(#(yE);c&A6c&Wr{w2urB2@#PsW?7voL` z+JB54T{rs?lztap8Hn{x#B>AcxLIuFqw>B$+X`p=8y#d^$A3*gI78~X(ipL}h|2$H z7;?XN@xzOS*cuP$U{IYFp}_fR8jU{p9t*^!KWVHi!gP9$zBz^IZ$5)x9rAuakbV#P zIpVq%qW7+P0vQVL6@rZePrp{>zUBdHrqM@{cs zx=y+2qV%N%G~Ot)%AK8-0_OD-Uv+^ z)60!;x|}bTo^HKSb2e?-9c=I%NnNx~yQ4^%UxeF^ zjuC^peCbDjBSHNlc>c;+E}532Cfo(Di!#$q8L2U`L+Sglxg-w{4_Eb(nRthgec-EM ztTG1uj~%;sjN8N{AEZ2Reqv+k>#uKqef`0M!t2C?2fv^Q^otl%Mf$~j0<~fF`Rfnr z?BM)^jR)sf#U_$+om+Z4b`~G^n&{oTPe*S+zWz8mcXvbb^KZZY`s@A=0qM|&k57%q zg}KvjdcuP$)R2&iH5Yx3VohHmmD6T$fyfP%TS%p{Kq=}dga$!wr57nfU)g+bL+Em< zV>^c6iFxtxVfTMX#zQx|*N0^xZ)B-=%5ZT0&V1Qk89 zqzY4*UKkZ09N(3(K4X1fUt^<>?Jw#tc{V2jlXrPM!g&DYqQl9Fi7}(zLuyOHGdgRxYQBBJNC(wc}& z7kp2NeX_hX4a6UU;0G$|J1UwWYy|a)gdFgKzNjUL<=RV~or9J|`BxJ@bmadEwJIfF zUFTfi1f_EoZB#q*Nq`6O;~T3=TAK)KtjI5~N)9M>{|=^00=5CBaaew{u*O^DbGm0v%R#x0?nqp|za-Q?Vx%%6zCbiG~%Qy8|AbaR^%UE9p;nb2x8Y@hDD4H(<6i|IzZHh!0d zk1o88qh)@9&)Mf9R@YzO!iCd)jAm`k7(iVn-g3};yL;G5NSRh!4kNawraNZKvfz>7 z?gOTm84@>6m%QNo1~YVK0XyxI4XWowdmE8ok1Fivtz+&I6jDYutpD6uYRgLTtT@lo8z_VCnaFQii+i$r-5v{ucH=vHI+KhMzN3Gr>8o+$PX7beg65u~!X9!P zfmIkiyWNcl^)$~owcJ#%Pssc7<&&s!U;g5QPaCp&?3@cCvcGaY;o?jP-Xl-9u1W6& z(;0&F-=8~2XbVV-IYgRz|0tc>ZF;&|0wp!KeA3pI?g`KK(^PV6q_e^F^O)1mL+O^9 zZew(T`bwDnxWIj-#B?d^++^=(do4Bn(5c8RJ18BDK(5R|sg`A@t*|YwnkGe#vXi6& zKyFP%N~UyE|Bk`qD&O3?HEXi;bvXUx)t#ezhxET9r#daog;LT&8aWjsgyVQd$VOAg z?lLyXE7G2Vk@GF1m8lpk5O#4(q^3H0s=p3a=N-#-C}3pSAYZMavz?e3NSJlBk3-FO z3#V&QN^M;&$^sq-`y$s(guPrn`QGRjS9@&n+VWT}T;S9K>H?hNcsGVphAMHrbjkHH z6mGwI4zZ3U?_|$gwpOi3uZ&!3sjGVFYpO_}{c`vlAbX}Sgx%yuPtlgTfdN|VMXY@M zxqtWvg}gxNS4MVb(J=P$!-uPTs|iWR{IO_FF540Yj z4HadyY)&G{d8z51>3GKpJhyLMvu5q`*`&TyXKw%Mn=ij6e6fkFL|iWf7^b?qHT&NG zfr8UdwV|eWG*z~I^!XV@G9ox8{IyGebFKDIK_!?rG4 zWl{RfC68pzwzrQ9_guSnhvyC;oo+@_)9sMC0dZoH5Ys_o*V(IP+A*EOB}VaR0ePm5 z=;fO8Ix)?~vO`u4*7UV3$^7DFFJFuk`7${!UdHtzPB*p})bv&zRBV8t4s#RxqS!@y z$2g2Of_~$5=hgVx(b&|?6U?+g_7(?cP~E|q^z{P#YfgywN_R18I_KsvZJL@GY1!EY zr5>M-lb;u9?175{9q2>qV*7t94~igtDP2H+j9QMA4y6ABa{3ght7i1s7qFuP=nv42 z69t@FP$Q))CS30AM(L)$-p(^Ai|z1Z3r zJ#*hlt|jz^=A^GF+HnB4y@Y*cK>4=y79U6ojvQ$ z^+yxWzCV77q!@aD9zE**ia!yK{&0F@%G^oO}>_cI-ip2M=;~P?ncN2jze{ z2$&y?XEmd-+gyuJq%nDZvd=BI&AQ<6DpLB#W$4%BIYxh+o3}GKV>8;cI{@LP zJ$xRfH~0PxAs06UWRR_XVFg}v!zm_Uzo6PE6LF+@x=ro_dhy0wPci3l6(hET^dm45V$XL-83#R9H3Da|P z>x;s{^Z;69##SWHuPCo=DlC!dW&QdL`Z?t_{zs_ka~weK_~Gu{zP{*gN&q15j+SaXaB^dY{zAQv)Tq zUg$v7eK7X@gNc2_ycD+$93rg?DVd#=>*z7c~z67I_@~7{`nG^h+jI>8inWN$LEG zfpk41i*U^Y8(CeP&O^eXR(v`{>Tx?Sl-F+FOmfnVkdBltQfK2?d~O(By1F)~`LTU% z@asJC^#W4E>9^gY39)5=(fRdZHZxb=BuqDrKdl)9iazF?+db}>W%PW!=~I|)J#+Ii z^iq7>Gdym-8E<-URWQCQXgqJX4bv@HZ{U((T~}36<2?1U%-=Gs+H$sTFy_RbJd_>OSTB+unv?XGR1`3!RU zrIzNFo*^f?&qzv#)0=YWLX(s}+ALE##C_)Sxyw%y^78C|``~!?r|)cv+_VXM`ld}! zJw?Bu6aTm*sd=pBlGJos*?e^V+~m36!|O=uzdx@gKzj#&u=2+AUmeFc!+Fs zy2~7)y{Me&ri2uVM@^TC{uFhjHZh%oQc@X3=PW&L)O7Upr+*M>yy+b!k)g{o!F22@ z9GGTQ$F(6`(n(Y!uE#CTk!%zDoSdQvm6;9>p2z4iNvo!<^?eUL|2CDJWU9-Vo(7Xe zM7YH%Pz1JSvFNESTep&wKBkEZugK~=T1aA}tBbQMW{Gsdvo{h5u(g$(A4-ST+ zf^C7)AwJ3Jkh-JOj>1~NIe#G4t*Nfi7y8|L{OaFQUAuG80jZTj(;_EdU<>A=g4NCw z4^rw-ZS826RYY2u-eWg&&Z>xaC<+){eZ%O8A+Qn&^_Bn2} z3M#)e5w`O9&!nXvBrE0fE9WP&Qi`5Ba3H&#c$Z$vG?ynWT9l6Cgc(+E@AAy*US9J6o*OH5zu>-@;bI zx8MIbnEty{ZSCdt<#m}@16Ef8L~#LPJq^DCWzAM7t5cPlZ%U^Q;vPYobT%ClGBmh$v?-g zf*H!s*_F^vlF?n#TvCaTk@PK(N+7;-2m9i171Z(|CI?c=xr4(rFBEw8EU;Uwfax3J zIfV}nmN8v&I`;~sv&tn>a~d-pU$tmj0{w`c9i46MjTZc!D4j+_Moq`_BFhV${?@ZE zSoNYHI{ik~$OtdFB3jViA$wHi>y1bM<}rC+?v!r+@WYQitdi2lh!?-pQqbX0%Yv=s z^oQ?VeDA%BrBDCpM<6g4Of;iTbWzT96@V^Xy!4qjmp)*S-DvB$&?yszlucMlT{m@SRQ4 z)5CU0=Wi0Y(~y*_H|+@~%EcN`IpnQ@{Y9V-rT3kEA?BEvz&F3#&}Gb z=>({A^PdclSM|jV=MQHbUE#lvMntb%>_duY&|~Q6#aC)DiElobd@#Nv9#V(MRV9i) z8Ay-s=!hR7jTIV!r8Q7~K~ zapLraA}@m>0tQWg6!39j7FjQl7^k;-l;!2Bs4QepWKq~A=RLW@GQC3SpYGYcrz9*s zH&>XRjN=1iNNrK&KviQvLv4IAFRHw}L?)Q3_&j$y)t8kv#?Jlr8}=`@G{+&YF}g1~ zJ{Q+Z6~xWV2qz1c7x+B8exR=14Yiu!^zw14GNnwbdH|)G1eIY7?0JfojOp9Z*nqL5 zUT;luqJKtSeSO|~_ly{{#}#)3l$GX&l$Js!RG#MMt|!3yZuph)z3<)X@Bff@-+b?5 z0c6SaDc6O#mw|y2_ETq8H=QCM@?diJLHS^s>gZAWvhlo(mkd-?l%ws_(GN^7kFV+| zX`*2f2o7{3lEdaoeW`CpKj%eMG*;E0%C6>h;NB@w+!rsSgBMUg4(-#^)a)8)3|OBL zbRE-SaZ63Nlwpf7In@w=8csK*qBc+$s*A{FRacsyi3cB#26RlDo=TtC=Q-GDkE-{o$z%$pKYGkx*# zhpls?%iKL=>7V6|kgqv{Fx~W?;>lP$HkdFmOVY+P+mVeo*N2RB=heli+nbK>-?2+(404io1Lj9iDL9Y3K0Mph|eY6w-rbB_V#QZZEyeBB#5p-QzM=_q1ZXZ7M?g!>6yMmpe|HTEgq7Vj+ovr zX}18s3sQPq0kB?x+)KC7o~YW|y40xp0TgwftV`$wlz#HPBZHA!3v=Q~6L-;XV2gG^ z;*IMmbhL}A9V3u&^5Do=`i`MOht+dtm%Nj;XVc)uwPWXSr!%=qU$*kSufKlw%P%j! zUx(eC*0F_YcvA}N1|}HC!Sweo)7A(|ADNigI<&=QNo#gHRGyhhnI;DC-r{By^k%H- z)p7I}E$$_Lhkm4MGOG`?-hbke6Rr_dT6(6b8Lbe#xu=Dwcwb+Zm)p;7^=-xUqU^=5 zKP*R0C+jAMGE!%UHEZt2_41n!Uv85*9oNgHKNxd5m_9QThr1oSBCZb*9dnW&ULuwN z03ZNKL_t)soru$2Pvp3^a^|vQv_IS~DZMvoW+v|RKYadf@7lHVkkftB;s9yqB)?E< zbZORDRFsX}xHW8N@abIBtDI(|^cv+4Z1pNV;LLosB&L&R zLD7I6d<^g7dYR(|7Q^WJ%PDfj)xypv{$Ti%!s-H7i_tgET!cY?jjs!HD($y&bd1A5 zZliP~rt4)UwAvGckCqOJBZQmabduA7{x}>eUV)3KBAv5wnIaiUo1tS8t|+Hag`*4I z8Gd$}jL^Ll`CMakbZMXFr>h)^s+)%z~IMJzX&` zQ2O6L``y^|XTL^9hv$*UA@sYDzwu<_mLXvg2_1vFJR7LyK)Uh;Ev3EFRv&3v9a&a& z2;C|Zr6dzu`ck1eoX$W>*NJjoDEoZvzQs%5d~Kc7bR=_;`09i48C;K zbcRvWPrmkZZgJl|C+~R%F&#^c>jDxjXM+!kwO_`3qM%K*bRBgagKLebZk2}G z@KG>s19H&Z)REfGt}h$cI>I{OCxM)EVYrQ&jlPZx!we(q%G4r2G~G!trbCpXcFQ(H z6r=n`2FeBNW|#>CQwZHJgJ0#5%ySXm>R@5InFc_jmZZ)cVeSCAKt{jK{0&%c6!T)O zco*XeGW#ARsB4?)$H?fmt!VpiBudwGm`!6g4s#i{k+$L8v<d-geg@q=Q{i;;r#l2%|T5! zd-B0_pc75d2}sBA0s#W{P~^7KPBYl%U?V_c;xs8|NR$lsge6jUsL_{EXnDQ|Mz8;qiCjv)5k{F4i3uD zK6ak;LQox>`s8tu`PdYv8&L1Bq~dVzfe2K26Phkczjo~$x#@H@k`ev7nl2svI6}I7 zFP}+K*Wd=(=SN6-i67rOxYnyxv50s^Xt*Bd7#BW-w%tFizn`L5LR3`tM|C1*iY-In z`Pj)HUwv{}`ztO;>v~Vp{d!ydaF{yuw~4sn9I!adMcss)(Y1 zJ@h!*aS1v7mm@8etLGhmi|q6dFJ2tS@vpkkG<&@DJ+%!``uU%|ciE!!FD56CAK4o2 z*qUiyU0B`L)@G0CdrcwId9!|c*UV%KRQqCmS#F%_)R4APKzf3$n#Sx630kCHT-;OG zQw*jTw=^pXv9-1OaC^yza=pYiSB7gBgRhsvD!eU+A1CVNColK5Q}bU>4e3XJI5RT3 zR``nR#f=?0p?nG%G7YJ9sGT?+McdVdWJ^x%?9z86_4hL!NLrJyvFG1Dr;4;??b^Xm zS4Uh-1tib=(FBx2gV3#!^X6?jvIh$+qTMy}7mw^+bpts{3Sb0U#pygv-)f$CYHB5K zm0k%39?$TiAtz4)dDywc)9|#%#T7Ao&T2aayx^yC4KH$HdWYpiBoB+**>P`xItFkr zU_8Md7Yic1FkNnzZ{6u!sp~T{?Pq5)L6b3M+B|W(8wIv7eRwzyG(U&6VEUYmYaJYt zXlzRP1gx#Tq?DC{=qAAh#|xW@IfJYHG%PN(AC>h*d`@d5IbLSF;7)hZt%ttOQ)9M1;rd=3-C)nCFA{`g4YKnor}}q?{)VrUc7D{ zw2ed#aqFq!B!BWrqlGKpzr=9 z=|)XAD!Ksu`gqW=Iv0ifwwGzs(=|1@4(Zz2(D}sQ$e@mzF84H$t^?L|30$@}im#v3 zcr#CvLY8|vxQgUJ(t;^<#7|9wAz`hYo4bi34hvI{QMeie2h6DsWytNKOa5o6`8(D( zJl=<%E=GsX_tDsMAAsI>)Ek8z!CJRG=Ke}X2ypDaFXUJaj&^e&oMU-8T63(1d*2)r zo7`RA9UD78mO@fAbHwyUSUtX@Vgx#qs%}oYSw~<;ymeK4d45HCS8~};9}e2R8v*^} z{d{FY>aT{lze=mp=xDuwu&^WV9B2L!7RFD=W6$SC?+*&9$p~?udtn8^Xrd*<3DWW) z6$zmh3V>7wt*jL{!sA*m((05o9RcyCn;uhfDYD-TLZhF*qlWw55S9gpN9-X=LZ+9U zyRoO&hecJzcG3DLe*=v^qXTj)qJ{>lVgu@<2BM+{%B!Hto?5KwT|wkAmzL%x-+uiY z_Aj?E$1yP|CYii+`lPDYs4_2Ub5vDPQs3RzI9`&|#QPHy(?^CmZ%aAu5R4-EoWbSz zUrIss4N6$gjfp1o1!H^wlGo?H4a*Dg`okZ7 z@2_rIc=N7Z{sDbK{-tE)V|7Y?A1^xXjoPZ?>PkAwX?~h~u%nK4MB?{uZbBa;%0KI( zPMvCRs&>gy#)}dcv7(pMVN-7^>EN5Mt|WVa=g;1XZ2BD0v6S2waK7Y}#C9?##rmYy zxRlU$HLAQjk2=%rj>g;=cmG{QQ@~^i!8XjiE(hCC-6Btb6ippPU1bYXqz-0k2tO@? zH>c1#_7_W2x7C_{i|dBSuO}kvl1Ni9Xs(en+ORs8M9_SAH4G5~)=0NE3$Mk8a=r-D z8F03t)TuLmQ^T5=eJ_{J9m6zeZhd$F_u&EKN_D6PS^Bb)u!TW_Xh z8yVZGWwq3F!7*s8nZggh2UaV<#=KVZ`VFkJf%RSf zBDR&@BiV=M>Jsl1bBdtohS{!p-m`o{0s`oNs>cp1P!gjJ)c-tx??z1rfaql;{oJiU z6>nY`UVuO)Q@D!JapQW0(`~1=fdtu0mhFYI$W$`G>DE(NNW;+~uo|z&xii$jf$!RX4*{`G?|O$$;rBZb!g{>x{7@xhU(v6jz`=><%G`sowYUXC95 zbm!#dbJwJ)(};9*blK>XL;dRSWm-?F&UyO4;jd_#gy^oEmuqLvpr%u=iHL5g>4J3~ zj~mmA1?Zg0oBo3z6k&Q98Hq37G`Kbik8T95(nFoL(8?%uh~}d@3@+PY2P%^x56cuq z6rpp6&U^95N&F_@x@%k8%V+(ce>*wbK8{eup-`uAyU_j}{d9{Dk9g`S`iA1nXR2|9 z3`RJeI@&Ym#zu#R$dOO4KJfSf&-BzCFf6EvZ#y*(@e?^cbZ84AExe7<0-FuS7e|-S z*$G}QPL2-tPT93lQK;&8up>eT$z;SNe|&I|un#xVc?yQcwV*Yuq$DdW^oEV2BgpAj&Nq*496U|>&X*rvJljDkRttToeAC?AqO#sO z{^@)FM~;k!V+q2{RNU6mUhNXMM$Yu&X36KcTr#WGku-A=&UT#Y zZtVviQ72M%9K;c@qR9x;k>!9of_txTdSNr3aj(|a?d|Pfee)Zl(}!D{(_BxqCM;UC z`bBb2?k51|H)l^_k}uC6Z|WVxoPMr3X`}cxQBvh0 z<7#5srF+lJ^vyBp_04g`n3MEYrIPPLHK~)QAA3T0`z+3j4PdJ z7uAe*Vv&I`&7hId-~0`37r8c`FpPddlcom*& zwHz;iIV$%$so4)M2E7%>LWQW<9Gx7>e&D1UjXrr2C(Awe!Q@Y#+>e@$mj2Ailfb-w zTN=FXiAzMOKO;3=xr}eTc^_iBKz*?cFLJ$D`HV2S`Wu1lSksAlS@(uPcb)=#zF2BH zM|oaQ)0u;yrtez^*vp)LFGdx->2xMVOW!9oeVwf7QqrZT%k;wC=ylp&t8iUf`hzR( zwe4=O+8k+b#GMNzryI|UO-?5@{d<3HlL+Z*uP?cbpc$AQm*r*dzHRPcyKcp)(7xtu)%b99 z$UdJ}&IXygIQo-|KMA_{in|I?(bTua#J}H&PTFy>3p}srsOUP_HB!Mj0e}@^GXa`- z9XE{5tsCVx)HhT#R0O=eKX?*5`swJ9kN1BZ@@mM(As-XE$O|CxC5#;f%t=lYF2Y2i zX2#pm`$KA;_o=B_(b?Jg1n9$Fe&I?dpknGp4T>)W!nGS897jfzur5Zw^+rx^WQhro zmawa{{KMP6_vnn9`05XOyXNhX=y!sngY&}nMB{qF^rG%YyQQX+1)m(77gQP$&=)-% zUmGWHdVOINI}Xarn|r90q~&Ut`!)3RfV||J|2*H;|Bv@NvtWH0GJ0uWG9r07^c_#L zPJHL%_3<(OF?nRDkf2UpWTM&#@zzi|T2bFHo?lT#$EK>}(niWe{b|ow2FTM0i8f7D zB}Gkyt5@YF`p_cwA#d-weacer>q{QS65|iu5eC8*{{CMrTrq2x_xjS(m>71FFhvlC zAB@FPwV>?OMmwh#G^(gh(s@a} z8(m2CBI@hAW4hIel=~#bhK{4i@3>-`+KcMqhnX14`O=hA640l|2=3-KWY#3l_rJMl zN=-MG4Wpq;6gJSVb4yJ(Ygj2w-B{FZuxfo=qzRij9~W&`Sk_Uc=Mqb z`5Hbq2+T^U^cLHTpOZ4+xlc!UI?MrSCq{CfJKFn#XrX7`0K zeTKG@RBWASL-G6#ru)ym-6vW>>&BB#ueI6|Dok^-gw-Ru_3o2W!mb{ zt~=&>m+?Qgt12HqT(S;L`|pe&CZ2A=G09VpbHWv;pb35 zum#0vO13bN?iQX-;@`x?o_E@NTTI%^M=h1$3W+GF&;9*LmKqME!_MbNCdT?VMgHpt zQ2CdH7yj!9nABNR`5AlB4XeNK!s&+mGryLc{?VnV$3OVso3F;{fb`ybr!O;%*=3Th zN28<1&s#opaeIGi!QK-G4s1EDRTAybO`adceJ)$N4b!JgFO-n}4}((Elo66%M&k32 zjP{d-IEaUan$*4Exhyt=GTQX_Z_z8Fp%aa`BT0S?-2$Gk1dlHhA>P`1_*5*7NXu%| zpq!!59Z0Lrq5YNpl|zw{duh=Gq|1u)`_JXvIX^l!f_Gzd6lSh0j%Yvdcsdpe+SKE( zmYkl73@a5h6!S5nDRC)rImEZPP(X-1!QO$H5)S2tsG_ji6dKJ(_P;p#DRTPN$>W3U z37|*4s~s#yEkS{uJ@X~PtO_cJCN3Fs`q)r9HNgpU0wd^Pvni$GG0*#XZH#)4VcU4;*fUW+p;!ro-4(=JN!aJ`-cX1Y~9p9xRv-t z+KpcOI2T9yrcg3nP|;!Z8*bQ`WasHil+7BH?KHX>rNhEx|D^GDQTyw;oc%1}gr*Z` zACBXMzYj1S&Lt_yUR{R>HpHB+DU&nh98kJ!FRKYtnd!AAa}lp30X|kWtfQ6M=(0q7 zE=VU7Q;P{SmBpM6OXE$SM&lu)ddE32IdND!&Ckv&P@Hb1z2KC0+TrK7Y!R)vEHxc2 zm*IttZ?Cq(PTYwlq)(G8oeSKrv+Ieyt+O2{Q6^l{Gt?=vz?q_#1shidI#~ZWEHxc# z`WyF|0#ej;CA~;Yf62;vQNK|+UdUjiDAX9)ajM+asjPGj1a>k7A6xjCf(3zed@l@{ zV;DbD#pv~c;{_bYNFpe<%qFn05z!4;F9qQ5QFkNUDNws;TOzkaany7S>B8)1o_q~x zx6)i*d-55n>4wYcYa}qIkdzWs^Q#8hVfzOb-}j^<*hT-EA0W;{=-lBOJi7FB9n4rq zYPyD*B?!+on*gv?^eWE27jODqHP_X2a?|fLC8Pws!03Rw2%UxN!*n85ggP=hcVHcb z>bfts&y;T;YdV>X%z~8mVn`hpGJEE)cOeDQl}Sizd$Yg=cP?oS*Mzvg9R#o|hrI8L zpAg1~>J6m-PIaV5I|bgH>*Uz*_;~jC`@?5Z#3>_1Jm1#|s;}7Qy~5*|EHLJ{0)F53 z%CU=8c|rSp_SFnWD^{Ix>{yJvGl=O7?_)6?@dx8CbyOV88|gx;9cd&S9UR9yTAt5= zAyr+tj^zScm!O+ppViQ?vmu`%u&xdJquGnR!QF?gM?iYb$38VOzHErzy=V9SSA$-4 zf0g0>amd3S(HqE6tMR$e`S48_W^_(}*gz3bz>t6^wlYkv6MV2UX0Vn;P9H<=BR^d` z-fvvki3f&?(oU^-^wFE9dw5^CKtI76F#YuIyiI$eySh-*Ki#wQ(>=lY@m(Q_85Eet zZziHU>X}^HZw01$gBRcoE}EPbf`O;f>V!eL5UdzFLs+;6@+T+ zB>?|$qBl-r|HRVL{Ol648)5kF@~VtoU^;^m+}k>5dHZbh_m5Ft43Dmq7o{=|oXY8K zs&6ED5zbETsBi3x<;_P(?*`Wg1_o$kR7bZWSz45eUP6(mtn{bKS>T(1Rs2d7MwyB} z?`_FgTjJyM3023y6Gu5I(?J>Q@z+;i_UYy&Y5LI@5Stw0J>y$7T|jP`HY5#OqOcKz zr^I3rDWpEd=>}N=bMqlW6c&@)1a(ASsm|saDeVl+5Uo=!S;Jay5LuwkN^=6h+qhj< zS?J0<mX`U_t|u78{bas9yslH4)`X4Wq(yCHsPCM?}hx-@f!k<)F!&MFJot@SqE)a&A?`H5N363@ok zO~7oxM5s`3N$4VfLK}jxfP04o*M^nUW>sYf(=Btlshvel*PKBcni5hYW}9cO=Wd?< z?LHx8xUIaSO`&K5s(F3|O@gzn17~3rpK%%mtYc8G*l;`l5^lX|IugIq9r3*Q6IYbK zJGd%3i2QTJ`P{B9JTPU1zue*Bj>_JUH1aFEB` zpt68y#B_GF6)A|3qYUc*?-Bfe={Gid8Mz#=Pyw8$og6Rr_HJ(4ajzZt_@14e?0Sk) z3sZ;2qK-UuV#%5o$?2b8s>HTI208?9QTpUL7#$`3+!2}=?WGFz_;V=dAG|pD0i8%$ z_*X>jPoJZ;_*+z_ef`!;FMV8NF#Qj|I`kn`jZ_xe_OaVAo$$dI1?qTV47Oh#JC44- z<#2n>sKIo_ydbe#<)gxMo4Z9;7c1!H>FcD9H667*#gvei*RDi0=djn{`O49iqsK>& z>xh87w|^^sg3$iZ9iebd=4j!fL^_vKT$va^1t*^oSadCdm?m8|Da!Z97=ru z=#J5?Th*cI{72Z)iGs%gFZG{d+H)ggEn}6<^cAJy4=ma5>FK8qIV=|AWTEek1NLSj zA=A(lkU5LoW-r01FmJX)E70lY8XC2!zuEh58&sYCxG@_{}hiQ~i;S1w% zCOOgyme6|7p-W>EU6aV^BtTZ$`6g_1Xu4Ea|IUHIjr0tXJ)I{x@dBLwc>y1Y~jqAOOTzS^Y&8LJJi4R2>FXd zyL^24W0_sH4z40U33E2liEG!cU1OKs6Q@o|=I8xy1oPf1kp-9NtWWAuE%bSBq%!zDMQp(qI*E17*$zNnFa)|@c$&s{o zA#5E>lA&~i=mPajIGwZ?TrW%^84lQK;B7}wIGi3y&VC7|j&za3@+7YvcKn?>EJID# zJkJa-G<6c)!yS?I-6GZB)-t;I$@*fXbQ)8-BBwjpr(x@2cYw-|odad3TeZseuR;th zV#e$7<2RMY2&Gd&N)Mx#-ac`{`wR0_|m)F*T<@$YNx-lLa)b%%~ z7~MP%p}H9TK4Cb|4XQS1uKH17x>3{bL^!8@R6}a|U5{ZVM@@flQLvAE001BWNkl;P1M)c4v5s@bB4}XAY3nhqM>0=@Xq|;+zspiAi-tB$2HpXuy1Kb zbdAsc5bYI+KD~2K9!3~*jE?pQ>Uw(v?MZ4bbarA$?=)&6z$E9XMJ`7FW~=WUN6yCa_6KI@LRFL*qBAt)pdOb-q|l8<WN2=QzZo zbSsGl*EUUwm=D#L=f}rZlvJRhC*$QF&!x08d46{}ZG{GKj!?1**TxScrstORMfZjH z`w)-0fec6T5HTPE!Q3F9TG<%)zJQp3JVIH>Jj@LqhmaeCcFFdOgXor9I&bw}PX%dW zauzHm}(?;jerUjhRf-T_Gf=x5lR2Wt_O*k!9htSQWjx(z_r&(>Y#h7wZ z^U2eR(bom;*VSz?tA_B^Vpw4;=xMRMxt%Cm>nz>df_T8*9JSt{u3RuS)4F9{SBG6| zUMf7dhPi7C<)`k=P_uaodH?~ZMY=$zL3Lx~0O_e8)oT`^n*;k6v~A30F;g6i)u&E{ z=tB7GC8U~5n0*2^zYfljJFt0|1tWN497pxWzYRBwq>Cb=^8E32H#ie~ydW?t*K|Xj zGQD65_x4b`EP5;1)O0;-V-C`So-r~!nC_FDzem-g^;z}#yBnf5MUi@y&CxpJQg(J2 zB_{d1qfyfr-g@)x7;QA!0n_hrk0!w}pXyRDeU?W^7l|>{o8VRt^2i9z%h-U*&gSCL zR6)v_wmyb+Z~iw>v=X>#)wJ4N@7rf(gb35gZru|2zl7TV2RD*8U2-~>R(jI2=iHaR zgm#{!Vo(Z4Ih-rdMa3ML?&cZZKRR^cMCSJDF^S+KV?A`XFLFy&Qu>(k2Sw>5DxRO% z8u`_U!TujS{v0;wPeYHt0D!;n!DlGfqhpt^?SJ9D=k)#m7TJKW>yCc;%ikGH|MIOb z4ZXkhw@*UFSFc|F*~-CXtKrJ)pgsxudbYQ_jr|v+rkl#rK`?#g2?$*Vb#!%&z3NB$ z*$+hN2HnN&VEW3i5div9eAbcCt)qL7Fpf_gr_^;)2Z{KXCnxp}lEo)4$};Ni<~h?K zbnwN&y_3{#zM8S0im78q$$AOul1HY0D>`^w#MYjn=27@>=j7yh#ns?;`NQu=&R-hq z=}EbSQ~%Ofb8}o#M0-SGAvLxXSQ^`eXL`Dw%G({$TvKVQR7~IuT^rmmaL}4`_PlwS zF0H=KF3wBl(X?c1)9a)iqutC!m30GO)xR^icJ1g0oPK3wZ1l(rZMZZ29U%YC`k|nHn z_{Sx7C1=0<&6nStYH8^$=DVSzr5SJf=jSVXjneGp>f{+}?bd;qA#+FA+1S(t(V8Ss zCXt>_XH;b5?K!RUR&P`h>E~GSiAISlEKV8((#7b!MW;W$eC_h&?ujFN3BZwzE=XUr z#*0Ryg*{Ep%b|3}+9cw5ikphlcx`y$L3K|RV5Futho{N|Qz_F4U3vq_T6AEhrF3*x zI@f~fGQ4OAujP6{PWP?Ol%T%I%N0&%#}yM8s!m;m?!t3((1nD|1TS`_s1Xr*x&!Ka z9O5_@H2y5%at9_9xL%fdc_pzb$t%fknr=ztqikwobq7B^uwoxw$x}B0jF#Pno<`0< zdgzJS&Mui=X>rBuDWf2wAhJOAbXqxC|3Ma5IWNS83({XgOo!B8c4J0&CkCeRyckZGpiU*I>O&=r-}B6Vg`ulX6cT5=`HWd6;02q@$v35@ z>o>Wf(biQ$y4Z9y1={6!VTvF%o#b@Xbv>?exQNji=1g97{cw<)u3;FP?nbET7uMCR z6N$^#a)H=M1u{NyVX4Q`b%c_z+SHL6kk^gi`zcTtq+9i*=H8g=NKR*01cR-)kb_Bk z;T~@T)Qve^pgx7^kT_6I<}W{5&~a+0PY9#NXT`CDze7ydkskzg`Ccdx6_I08-#0wW zKeUS?bj<6b^lkevysTJ}7y`_53vQ^j#`=Phec!&Ief#?Q`i@;Bicw-baL;)Sr|#~r z#Na}|MAXLoc%X{-Zh<(;DfN{B$;sD}lLM;Cb%T7CJ$)C+Y|qcV;B#SC&4%4s!u0H&xp@7-bm~WU z=4ND+Vdw}+POeX;H&ZOHuD+*%q?!Q|wirzu3J3Bih$TSMKXG$u#zX%H-^u^GzdFYu zx3Mg-ly*f_U5-~^O|PKq52x|NlE|^LprSKN!YP6goCuZrZu!!KRVM++p%M^6Qc5Oe*h-`7!*iuy9~iL~cqdE#cfu@$><*4aw`8>jCBl z%f;K)4jk*U?c->4b_2=gM4wGyT|6!_7sB(wG|p|CBCplvO3p0V+<2k&m(Eb5Oj5mZ zh?w|8C9CMDk2@!VbQ`1V&%pXq`1ZlAyA$XNJ5kX2F*>?*cM_1`Vx}i(>Ed)tOV?I0 zG;Z7Rz?r!`wU*1@{x=Gtm@+r7D{r@Gw+o3mIK)37%z1WTARVxm1O}2-sOm~`8Wt>= zw#VHkBe)2c2s^Pu^Mbso-n5mFdh-h1?+~VIuLZ^vqo%8R^E(4fC$`)pI$z-~4Rl&> zsMrIPr)U(J(-d<7PG?_Tey+#uH!ZyN_PIo|g5Ff1qNYbz$he+Iu;Z**KJ+~X+IQ0{ zDKEq$BR}sBKGb@n44<1#1*R)xKFGZ+KP*d_KBs`*Yd3ql2UP9OuZ>EXy_#3{zx!AF zzxI1GePwPzObzr<7Rp*xa7fA9fTmtPz|t=iFFJpMGE5PaL$uAaL*dHIFs ze)cT7ddL;I(|`G^f03I0<(JQX`S*s@U-)M*{J;L!pB;Z{N7C}O@{){A3F@Px#qD*+ zrLLd3G9m$c5Cpe5U9KBmSY;%2oijjn#Pp}yzv>vFDd@Rtr|B+!^}VacTBAq03i@7^ z?VCIo!X9UD-wvmvw);7U(syWZ-m+0l;V18T8~Y~7W8Tj^|IFzlqW+aDpK5Q4+^f>p zj|h|$q66ulBc(I=w-l9)>*d@>mqtfh)B~!mc!xk3(dVhpv2&r+M|Ch9a8U-6D!$#(s8axG__}k3lJA z=+MO2rOB?Yk*MaDO57%nOIEGv8K`|{&r{5Il=kvVOgLjN{1`d?IczWQA9|P3(XsQ$ z@qc>nz02<%{Ni&O8;zWsIMUNXM^eP}?U|WrNnm<$j;DZ_>e1@nG?~)dxrWA0IhlmO zRHI=ZI4sx8{U>NY>dLeaP?wkM%k;Hy*L94376Vqf+nOCFgQxOT~j z`yc;`iq?x4KOBe8`=e?HE?pw_=MQHtjp9E6ViVE`AEIK^khvX2%N*$wLt^btzFam$#2;!@NV7GVMCnH@E>A90T-&u)}&VLCARZQ-c zO1?XFu7!nm3OP5N?uUX-XCwA`@K}sgx5DsZ>Q+6M`z2|f74GSiOx?hmW(buH^b7?TYVAX)tgpw zx{E85IIQSM>5lwCI;>r!CP$0b!sH@%#km+E-PqK$G>sbq>C})KD~#e^aHh}G&KWqJ z4wdF3<>0H&8-Mhai5EFdo3nuUbld+57!+%|5z}dH1f`o3j4ltDmZK=yv@?RNm#VYR z6P>C!z3cB3;&Q7(T?FQaGo=SVA%nWo(bdGrf^@Q7P}9Nmhw*qbgdsAdCq9=3F8k}Q!0qVI4iHrhx-S8yN_BWNF z&adl+@}@Is(4%t&2ABJ+XJSy@>`}0ukqy$N_Uk#TACnYyOHF^`K`7lC!gO5E!gQs) z=*PocXO#5oH!|%=h5QVI{$}~Y!z8`f29_5kDcqL_ReSMQs# zVjDloOqbimi0V2)G&ji3lBK0X=gN!We`3wii;4a*@kDqGlvl{Ats!emc?Z2_2wC%( z`~0k3^UZ4P7_1k*S5&aGxhr^QgK0Y|1pioFKi93ByUwTPLda>XH2XuyW;BBO9t3qb zeZz2WaMyRCS|{>IxPt z7DHg4K9|_!=SjY=ndL)=C3(|>H|>Tuh;BzsN0HlKssI;)4r`fSbP>SVQQll$6(3*Q z+|tz4!UP{s$E)5LyMDf!e&!{Y{;z%e{wZ&zq?gk5LGCg0b8(Br=XVo_-3jr8Bow+Nfox3{BBGv!+8NAF(ENQ{)z5B`}|A02~z>}8!*nmy;UJG z$+=X{a&N;`jl+HGhwDr733@3-dk>n$90N~{fJUk@~6p_YYPCrGgx{?Q)Dw1l9=~LaFxeH!0lD$zRgD!@Wo5IcFx^nOSl#d@p{C|w zyJW4CPOR16$N6Feby-^&@S?4vl#k5RvIXn1R+*!P%9LJt&atF` z=A76*qZM*6j`vvb+)TC^GMfe*|{0P1wwNI%5I>hiY2`tifRZfai1Gf5=i8BFqwT zwDgWBK?lh5_nvj@^jULfESw=xUYUv^x%nkwS@ppiJlLt=6R^9!HmtT@PWJ%skcQwp zX3e^Z_ke(PrSBNO3tf=-Pn(eu-B1#i5{Rrdt-*aRr7Rn&f*WeXBH1PVXQuQU5-1>q z(Zh!#!>1+r(YBsu;(X5wHyrI~-&3uIoCGq5x^5{5k0{EHXthsI`o!Y&=EBGKN=b)) zRnB>C5=NhxI6}*f$n?>q{vQ}~`g8JFeDJUTIA|;(+|XpXOddb}Pak~x-sNB8d->%r zKmYIpVfqLE?VmpVfObefyKFf9*$?7IleT9j1dhIlRb$cs_4%=uuii13P7Zj~%Fmv@ zZftqV=;>3)E;hH6bV=zNhudHNw~^0jq$C_SX#UTPt2#j|=jX>Jm;Als5r^Aa=RxV1 z1@Nv9N=-j<@_}dGen`^MvEE^)VGzaI1 z>=aroQDf>BF*rJLQoTrzY@uPOYmr;wQ2$V2Qv}ZIe!84)*%Ce!B}$*HxYXRz($W?e zN3!>hsM@fsBZI5grkk{v&(EKK;m3db(zCz#@ZxX!4juZ{p^-zA?@cJ;Wm1&Rn8dHs z)^_--!)cgWfbimK4BKA5n9G;@rqRkMvv+&u_V!0IAKAX0@N^>6fp5nB91a|4kI12Y z6LuU-6=`vGSPzMbY2wMy<+RuVZ~9m5-?V*r_Tt5_$4@K?ToU-={nRB~RFwL~8t-de z6Xz#J*b_n0%aza1H`~nVq)%!hIaNT)GA)9jT?k$N7mP5TSpA*Sa`4y0Dc5l3%-)uN zqsP&2FCnDYHm#}TV>!wGl8^Ua?wXv4+A?poX=H?!z81TSXI!)CmWmnN)qcsMRfyKO zwVj>ux!|R#G%4t6|3!ZzPkEGJa(00%gTNOhc+n=vFO;1wurO_8nQhVO)GZEQ3stC0 z!PYE7O;>FCBC)vs)^e&{$g*^?&rGoJ+&Zb3z<*zo40J)JVM{0Z9SZ-LWys2 zkUEb+oz|uhxI}!W2!6gCB%~W_%WTrqBQfKUuFi9$6Djd7aJqI1IS*QtPUNFKuZ9UC zMHrO5%H(6i^aYZNL2{rREXVXB9bI;GYY5S$pF@^+J@I!Ikc-h7!t^`ud`yzCF~JDb z73*S79!7wN%*E)2(-oF(ibMtKkop5SOV**L8&KDYOf0qm9ILmHF{*2osQUqA^VbZ2 zgWm%8KN=9bDE%Ic>Tl|1HZ|R_x%nk#0JzYha^b%)UA;y*usHRj2Q@?2i>A4)@xCZ7 z{<@rw^9M{9i^J%cUZkcI^l~p+`o480Gu+kh z>W0QGfgBQ7;3BJ}oa+kyzZo$1?(CF;t|WDa5!0=k0P+6&JakLCm70Ht$nmhc|F)xv zAYl2Wu8yktlkveL`6Ha5sX~jvK8R5?)_y*jR+6ac9h0gl<(jUp(vbb^em;#{{;~Pl zuwnm(VfUJv4G?;CZcvTH^)kunr*m_6e!6>@GjY(b7dk27d6L z3e%;S3ta?22FGv3hc0irpa`_O5tzCS(?9D3>k`{*&WVN(a`Xc)8@14`i3r)+d*R*xsnW z6ngf-0_a%2zMoM6LVgQ-q6;|QsIA#%m*%ovtzO9Px5E?P?cSGH(nR&9{3caZpm9h{ZgOdKd_C^_s^IvlXw>xaDso{;z5RpcvZ)EsTQN7W zbbVst`sAwQhY~yLI?&Q3smH6=Xm@NfQy2W`%5opzo3ZYc!d?!>cARRe?@%8jJTEXh zJyNUU*}9Dt1Lb`i@Yi5eSHw$QdkG$wc;eNe^uDV4^1epco|dXP_3R#~l7gN+V6INy zwk6O@iO{kDb7RgCvUetHdg zUT}*1(AHMx34@fdrkT%9EA=}Gg8GU5^Zwr%iKR+?nlX4`5Ry`3B;gw1K zdxhz5y@2KX7ytT$L4&M7tJQGy-0{JcPyOK2(|7R-~Xb$GQBOQdd;$B6nLJuar#8jSMLe4QPZ=ZLew@iZn793|G`s6P`4Rf%-IjD zWJWwMj~_mD=vS!zSMNLdz{$V;XP6vXmxqL-W(Al@%+lrKIfu79fam=ratz|JAAE7| z@ypMgeBS@y@4k4yqjqfa>OI{2Ja|6AYo^iY6r>}legdh+mMe04DY6tbk(F@+!!OPjjPT3sFwO(RCebAuQym>fpoE<~$XNPZ% ziYnr>H+W?7GEaKq$RIA7h^D3?Mq5E>C{a5*hPFg*-8xoru8Ty*mdfVlwjMk*OBMu1 z()v1VXzkjhW^wwJYnKV6Q`QS|`k{9Z9qPyrX7|F?_s&s1s`i~D=a26l%xOD(_;5tE z%0#Q1s?&Vetg%Z2){)h#DIU$--qyZdl%Cn^i<*v>ZYcf!b|5_mla%F6FC_e+8+&3K zo#+Ne;x9EdRX>87{?*~b-+<}A8UE^#B`3J}Ay4Gu*B4=x3q;ai<7tfifmz_0bC<@F zlH>?UsLo-h4t5vHM~Py@oo+sxRNbbfImJ1$Mj45owD(Mf+8tZ~V7xTgUVi!cNDEV} zl%6OU{o3XI(Kyn>w)zDcMmJuMWpo+!OD!x;P3OHxBhTE`1t-hKjSE&KOmkS~myW|f z-IGUSP%Ryv%8bhNHFd!40;JP2snAXHt9i1j%$7f$;sQlvB3HAgB#sSdaXR@i8ic?X z(zn(vhnd8820JEf*Jt|DiPUe|AYwZ2y}@*9M@UI!U_18;B;s+-%xS3PB)K^7v2j6t zw-Gs+i|mTge=29Lrza{!tdi4bOP!wwrJG$e{2q{RPXZ1vNKvcKyxysAG_-U&kc!e@ zVu;dNHjIvb{G-47J3+c}mf!VvQw@s*msE}3xe%;;0vikvYQoWtj&3L&bO&u^V%HCT zaLf8)#B@QrrJxI)0bW~kArZN3FZZd8)TF+Mrfozn@f)6>?ueG%30LGP`cKO=yh|VBbjqZ3di(v*PTx+ zRnp58r$2V1QPUrmt6gfkkFmVyjv1Dy&gm4Oa}S2nxmP+ReXFKFw(xH#AbpGt+Iiy> z;G{9V-1tMIrGKlY8|9o@s-O&iFukmdb4yIuDT+GjV%v^=r>_wlF06*tMdgykI|blJ zeU2WbSX5Ci+Es|KzU}sXbJ5x@ql=14xfz$Zf*WvV)`0IYJfMDb-?3vyy^-QQwgq&@ z#v`S7&CiSP3Xae3>Z+*fqKGlS!pDOxK>=1SY+DgO3B8q8=`&#W2-)Dx0qZH1$&*cw*F>NTsYm zx_;Wrl^`R(d^wRVr<9mpLc3JX>vDKPB|v>Qk?s}ARZVG4Qr{)_WACY`Z?71RFRATL z+%-3meFnJ!iS8lS+Z+8m(DR?G{-j&L=;Ycvy%8UagymH?%+AkCSpdDVQiOh;(sk{Y zygS?*B9<+fmJ$_~U&j6dqo=D2D|O2FU#5fUw|pPdiy9(GP5*Xi8B7oHp5?Kjp*E`? z9UsqoeeD+M$dq1jbmpifeG_I=r5cP+e)>&w(h{JF001BWNkl z5h>YFISPV*ZdS?`*DXaU*%47y?$NdR{S;SssD0*#+{vOie=mq#O3zJDX{bYVH>r-oGUrLpD0zG+MwA9VbqAjEi$? zDnxga-?pG|h>npF$mwg6Dx2RGUH|r@OV~ZGqN7vJNt2@5OHq~K;qyZ2$5{+G?mdo$ zg($|aUwBTo6$$QG*THqd6tA8i^*nI+xhJ0iw`EYjl7~P2gU1h~IYtbP{!AEt^}l}k zio zghvprO=BA3WK!*YJ=4^v24{o4pNoSstsR((g6V^x6#}SYuO+8bAW%Ze(2=c9u916J z?qoJ``S{)~MeXevBK!O0u}Jl-Z0_kf5;ai{qH~yNt|a!`k={$w0vF8AE_tW6b|`6W zWlzAbpa1pi``>)yfgc-p`YVS{)sKJr!3+QJ-akxE!pEZYUtuL0e5CF0_QMBUS}79E zX_Eik*EbD!`I<$hd=!@pn7;jR4q`jp-YQ6Ez~FGYnrx<$fMb{1bgHi7(EATiT^bn3X?>*q@F_4Ilgrl^Km6*e55|Yjg6xd1_bq+??R$QG^6j^;UHJof`d2>x z{8Dq$8iVNsRmPIq(s zRF!D&0G>7?WNiOqP}339ANa948|m<*7#&hqM&pA&x{KmbGi3dM&Jlh&8Vwj5HB!1( z$PI!q#6UWB7lY_zH6o{*YvAATv|x^lbtdknGW8xAY94rSv1L-RU|fEcH=yb_STLRy z1MkwnIWkG%mHbFAQOqt(mzs`negQ@OVM|TF@d9=iK;5#un7|kPvW7u*gmghZul@Rx z;dE=hLkCiv{%lShFE;|}RuL)A7n?iX_K({bRf9sJ{oS#<7)*D+!(A(-sAGLWPWL(X z3T78oj~d-uVdas1s(Olnoe&|L-O2+OV$n5{m2lyxwXaX z+%NW*8Zo=iu{+jxbph#JUGuwy;-Ybl;D%t2nxpIB^trhWNUFGq4XP9DO}qkG>9D!{ z=O3e_NAGvvkM}(KG_I4=JELpfu8{|wmHMII5gkFJLxS@|d~R~z5F%qb4PS2~hOtvS z{>|Qfsp_}V(bV8K4i_V*OG`&Pmr31{0HQ!$zu2{U2Jy_dVb|aqjx%P=x-jd)h38+T z(dnnV-%%z#YC7|WJbEg9nimpH`_1`@-rII=3PJiDXfv`{~vV-o{|l{y72 zU;^7$3pX&&MQ6)ubIXEjT~`IVrWDi~HC>U6YKH28@!s2GhA{oQnogDH^DJ9OjoL+ds*I|BG-bV+O8l$cy37n z@+cDg?8x02xnT`KGQG&$e>);N&+Cq$5dO)A_Owg2G+PHQUY^uPdkQ_auH7FbeD*)HXU$S zL&mvjA^L~kq9B9c=gzB~bEv1MIkl(I)wPIf#<=j%EytgG2|4}iAOC#vJk^y9Qp5%9 z3KZuTlAe0*jVCWpo)f13;ac7YU;g4>5BK)sb^pC^{Gb2p-#;5sH{Lza-n+c1d}2bs zsr8d%S*JNW^Xrc;MbLWm`uMIh-EzDbIsN!?n>YQ$-jah~eDSM}Nn%X)?!~Mwq1+6l z`YnTlt5*+>9)C~5`thyoFbNOe5*~*n8op()_5O$epVxnV<=nZC&U_>u$G4+1Yy5$V zQJRg8je+o=T%yzGB`Ce_-T0BZ=Hk?T?D*%-jEsyC?pK{gOB_NLC5)nEIvH&kJ($`6 zftI~JOpcgt2B0q63x$M%fpoelDlbXx-*hCrpwMj#_H;b-NA^CI-CpRH>S^y%Ku*l^ z%BWfxy=xLkKNo)~WppT<=_K_r@ETOfVT;JX`YV zbI;Ln>M}`;=RPu)mw&r-Wbf144}bE=BZIAYFj{lAL+NC?`}$Hpx`ry!HS{Ef(^=i# z2BsHMOlmNl;PeCS2k16L&^I1wySTdYmJaaz(94Go9ejV}(7?MLO_`4z&i< z@#!Q|oF+k9rhL2K{daYXGT10pxVK2Y>;!5n~&eNx_UAs&lquo@E;z(b8 z19CL~PXhg%oeEQ;)N2&S3?B4UdQhqQ(!~TH1}AjQQFu6!=s zBJ|<$!Xb}vZaNqN;nN)0<41`xO_wM{)u(FOye0EE@}Xkp$83-f8-L!8snm({>GRq+ z_3s5w3skN+Mg(=D#U-Qz=};^2=;WG+zyVB^jXrUkBGPFn3Z1LHJ!g+0qu&eAKX4bh z=nn(%cwY1i+#IwO;Tuc$VgspDV!D`_kVPQY60lhoo@0EmSY6ULP`z~B&wox>x`_L` z14p{BoTK4$>}XoBq50Ge4X00Cu&7-!IhwiA)mgr83dwmIwsaSKIB&3H!CWC;H_T24 zQeFkWDAcB#(G$<$O*hv->JLjz$D01I#B^2~=Zlu0a{;=3^qU-6G@x!2dbJ`Y=0%u( z=My(7%u;GPK{~{+8*e(jNO99xdb;hMGMMh4kxQHzlzvA>GV(e0bO_ycjl2K0L|M`m z!w8)VvL&M%$OgSx*QrZKEmyj_9_>R?H@Doy^}9@=saC9blppIi45@3`c3<0$Z98_1 zte06UE^Mpu_n#jdk3yatLc|}=kot*%iGhZO`aQdAF8Hhi)IEl&_F||FL~RsxUnD@} z?SFOu{tO^oCUh7bugmV>;kX%b#&?@B{)CB5v%X|w+IhrBn(gsgu^$O?&Ya9~ zlyKy2YJ2Mk$ULNgl)}vXsxlv+kYr#!x->Dve{M{PeLKoFoSc)boR#tl@SK{_cv>OF zR|S_SlcgI4ezSX72$RH{Z$VC9L0%)BjS@E}CSyDAsB3Af%V}%Nsl&Jul zU6WehQEZB#hbQ0EMExoD`ljqtB^B`j-lc@xAm+!!lr?rUsVd8Ln2N9Z%e@2tUwtHY zPa~Qul28i<+E+E?hS@NkRUBk~(e{x$#x*NHEQQv9fwLDB;7O6XAa6RDE>x#6FeSV+ zn}Vw~zJuxF^|^C1ayKA@hvb*2qfuCx!F1*FiOu=;L#r~~{ie-!!P!z9>_6A%rkm#a z+)PEPFdg>Z(6y(?Idn@{9+>VElovG{(+*f4SkMrX8`W?JR(KwE`g9N2+{YV2&n7s13In(xl>D*Bsd5kH}7ge! znUQ91pBmm%)T6lQRM&{2ud-d&q@$;sZlp3NT%ANN9vcfAOiJx(_FbMDUV!((HLkEf z^eduXI9%S3Ed)sa2-3F3m@M1p$5#IAr62$NNRMeo`s@AAJ^R7qhueB7G!>0s{pY{^ z`{!2HjlbVfw>-VBqq}@7p)cl|u?cC}gqHL~SY3-O-;3#S1gi_zS56tySu|?;-lqrW z?aey)#qa**Q27M?f%@rWG&S&aN1RGQH{ZH-<%A3{$3wS(zD{tTGEDlx)wcPsgXtfA zZXkV%&##}89;25v)?C>#a_CY^-JwIL+Fv?539Z@V1212?G;;9Z!M^BMYuj&?(F#Y22hc7($!arPo?;JI-AN^jO{;Nxf={R1t&l_xQeWaCKpUhS^gT0a!o6~#K zmlJ-H*=t%Gan;PUw!$1sOgD0R#DN@WQf;x)(waKJ^!E?SSR*z4-BTUyc-l|3*FAEW zc2{3xb%D}<^P965&z|ibkJ@@cdvYL<=QopU7|_w$vU!i-itT9 zNdDr+jR^@}e*6w0i^aw1WWgh*b0EOQycsS@G$Tb4nC5^_D80ESoLEu}H_ItnWxt1) z?BRi4egHjvKpj1OX*l3KFLd@ac0@V*dad#GOvT8=8*3LAhq*n@9@h(UIxcpRdBRNJ zoWh*yv?*h{%;S6!JFk{J?UidMY9{Luxu7G=7;+m9E!*GFQLVHs|AldqHJ^ zI-Gvr8wS#0W~s}Pj=}PKF=uEQJ|`>vi5b*~0+*^5h0}4kh|*zOBy(#>I#2*u*m` zpUyo(=|9AxE;;?i@7ul(2pi_x%{@0nXF)+5lHC!c%p#n=*&lZI-;CwucfT`jjX>}f zs{fP^y_4lm;kaxsgr3tz)apsfHAjzn2+0Xf2janT)0A{dL^r=9y629ht;71qj^1(1 zpJt^V+q}1J^Cor=Gecf(77f{8@p?68%MPpGUE@=;w8mqdNA7MC#+AenRU6e)i_VT- zy@9$>4Czy2zxxLI3GLaG#R=LvQaT5nfaxLJC{J}>(G<=G&7CFJi@f`thS5dnU^+kS zu$BcKOh;6|jcF=Bl@_u_g?(O03D*xBXMW0`qSW1e`dLq;h9_${VBD1ciuBo}aF}5-0p`YG8 z{ioB{d;f>zrn^zoN#U@!_pyw=z6|N=jg4h!>apG3$rwp0`sP>FW!Ke}E782Js2UZz zJU$QqdR0J7E@F8_G=QHQ5KxhwgL;i}ot@)`vqaM_D_dQjm;93K2(BECP4w_rZA3u8 zEVR#CI`{d<^u=~3`yV3-hq%hR;--O97$#5EH@^PRie0!~$ZAnz(s4c|-R}?7wdJ%m zRrK|}-`Gf5EB9N1ELz{4h&#TFNXG1eig8jJal$Z7P$(l;i_dvF#J}WrpscsMk;|AZ zil_5YAG3pi81HQvG5(2V80puSCOfRM{a5>Q6V!j+zrY;)Mn*SYbQ)VPSk(|+f>Zt5 zZLeX{rITsQA0@JTr9a%-|2i1@oHCXt-V=hF?#~0NG3)I?$-yB(V0u{|Nl(#WI-d3-rMl1&ur|blTGTSS z8-+#8R&S$kU+JG^X~8tt$W1AcgUj|FA^SUJUf?ojC1AQRgdU^x+`$1{SlC0JbWy-!X?9&&x++?N7n!))1UqX^bpdDCHbN#}bfN`LY% z|MD*b6Gv7r+d*ax9Y(iA4iz!nBHG&fw+^+Z^&gi#osLYQIDI_(J?ZNcw`I^Pv-hBS zcp4A7&EWD~Mjsm+8tU)I4c`072!t+7@BO5Eq@_8%*sZ5hdOGu%%E}#ft_3bG^b&GG z3UzQXnC@wxhSS2yPJ$@qfF|ZeqUWGR>F^iH>P{&sC3UrgG7h<5{pNMx+IjEzUK((c zq|)X(SP)m-Q#-=`W)Qt=M|rT9XdB+ zI$ApYN9BIez6d1|$-Uk0nY4DtkkgXcuC7b$qI!DY{o=~O(rc%qal7E-S+(HB7w4^7 zO+fmhHJL?BJL5dPmM_O{Ps=9yPo)>5r>A?SGRN>s!uGOYW?;gyHAy>qqMDJ@L3&Q` zC;39@B&CDR3O)2x$5AJ|;Ld~dKx79$C_RqkMo&*@-6_s9EiP5r^@P35Tx4(AS`x^U zG{U+JF23xh;Dd&F2TyyBVfV~6IL-ArP=6xqPT_>H6Ustjs-vB3EDi~%=^Ga<^U?z| zQP6}M3%b3EMWv==OQ(vIK?OKl#@>`Xh|`UYiW`X2ai@EEp{Ivy%ER4Hn@W0tmgRB5 z>S8hakA4KTi!>h=hAY0sh~u1V2*r`oIasjH*}ZSP@y0sCvV^-Bp9?AJIJ)IY2hb(O zKPYcH1Ivq1)Tam?Jjdh0sreByE7FB-qdfdQOO=$)@;&z`$y``Yg(yeHldnGc>d*I| z+`s=x9bSEMziu@(Skxu(-f%x|bz8kC_hQ!2J&7YgZVfFPP6x8B)naUI0YlxYB~^K; zjt@R;>uzL$y2pc3(-}`ZXz1RMx`%2=IT|UQUoyi4F{*%6lDzbF#tO0+Nn^b8#>Z}4 zc&A9+vb{)Ahcl(7|L{iB;>h+LU?@E(V*^qYA#FjWnAD+m+%61cO8WRVkOW!VGi9375CQ=tuYY;BWW$-go;$ z0Tmr1v=hmt*GS4%SR72JGHcK74XG;k~(^Sqe zpl`sfPCz3ejlpyrA!Lw&Z7MO(#alSz2igSU^ajVaec+Qafg?>D@+2yNrO70?Ll7zzbn@ds86F0x^-B?bWBV5?nI_jbn%2-&BqbI<7+jO+{ z44?lHOt&Xc(cgd9E^OipB z!RswWO%K|(!h3zo+&I zP%SApSg-&vUJbXeo>r7+{)L$uQkm1eJ$&X)$3>;^`h_!$nEvlzI>G54A-mOT6eR$Y zd02r1fG$K|#p7_QnpSvy3)$)U?jAljO`qj+yYZ%DO&51(6$A!Oiww??r6n&##cFfr z1l|CACx`6`qMwn^TpEOpGl zOSt}G|MUwBW^W4HwCPCb-mOO>w}c%DU4^(4jQ{~v_zx*XvGq|g<^EOI9`L|!c_37THN-8><+d2-t+|p9m zZ^`NBKhjO5rngV2=?2xm<9c~~r47R6q+V{k`Wb(>p%zh8py7u#OPilK7Q^S}QsnTrZwr+AcB zqhrmZLlI9sePXXmWlM7l7LS%w?;AD!5Uqo%TMK(en~~E;n4*LZ+Eb$F?4ocy7kmtE zZfS_F^nMkmBX3d>C`*FU+U0lwsemfl&^u&DHPx~gIfX2fCKtc0dyiZu?B%`V&aDOE zO>H@@dkYGCdTR5GDLtN)l*-DUq0o7uC!9s;&0{SsO#|a!Bp$nxcqQ?5?>E%w97^x} zja)BZe)z(BlUL94LTH?N<_eKJlGEFIq4dmYOSZQYyQomc?Km~6i+!t`Ghy1M7UINv z>2!puo>{Co##ShuaR7HZt``?Sd(`x_<<(6u*S-7&g#K^JlVR%e$#@=6E;XGTNMCvkd6MrU zP?v)4h_}X3E_m(lv8P>-ql+C=FXl=qh0ZP!TLO2aY#O?BaQ>BR0bQrn$cX<9FLGD~ zq%T^O))duL6c>lfg*^la>Y8A|>6HpxB+#hQF_{>qcqCh_&_L@1A)rz0VZ^ehSt zOrVV?mJ(_&?Q!Abh=JGfgY#Z3^Rg&C&iHc_=)+C`UqW8s^hFMi_C_wxw5Mg0boGQx z`YhziJESYSB1H<-)y@AAYD>Adb*>lT@h(7ehDO8nIK3z{zml_ zz--7~rWa~RQPOAI(LUFeT>z-XScb0OmSHYu7bs>I#9Ouv8Qd&l}O*IAgf*=DKHec;=a<>qv4W zhfz@e3`b(q-{j{$sp#JxctrtDIL>-}XK$frjzr+C`Xn)=)L);B&UPQfBJ9g|LHw0a>+>l%Y%`n>n8k8uymja|I zH=PEqV}M!hny-ChHZ`5zMp$3wlJsJ!=|r=b#PsjV>DX2>a-(Si8d8Cl9+tf+1xzn- z<&nADIi|A+y-+M!AM<-u7}1H|H&4Ia=XN|arcY5&Ms!t{>#8}c3i3nftrV13#Pi3E z1EzE;BbH@P7X7N)1Br#AOASF-c{M8u{8 zCn!uysE66ZkiI| zPv_#;fBEOXec|}v=x_h<%U@fZZuwn=;b*R1e(CFHAAfpiV4$Vt)TvL}+v=M7M<;ZZ z8FZ-}YL9rz)R0YTVugvk8!);Pq;J{_adaf+lCkWRPU)n9d(uIE!9ogh5g3jLvG1lR8bLnMC)u9 zoB7|~bZ)2hyWMhU8DE6v64E7qvJ=M-G1T6vFsdXfthTO+GSuvXP~u!BE|XKUb8jT2 zsBP^>iXIH!QN{U{2vS(w=SM>z}#vA*-e(>uDeS9oA z{n_U(pa1>&-~ayHnR8eEK&(1tm!JRYlNLBVbBP00qEw2)>1|Lt9eR3w*Ysu<_f`|{ zvV2W1{g|+)bJ8j?{eDg!fzyj3khwi^a;Nn+b=2W^`IWrsI=fWYf#IdDy}Gye@HgL> z8qyEPzxn3Ci4!Lxa+VV!)7(rj*QUv5s3JWd1*W&OwYN2EJ-tDfOGvi`F=EvqFBA_v zaVoC#^qiJJk0D3C2ac>8ZYcNr8))UK94RcI}RyA{h2a3Y`K45~M6zGAR(A454!(=#h{G|#Xk_~4 zP#H@{0%|$+I$Yy&jNYD*K=Mz*Y-Vf@%$CCoR2<8+2VK1=+)=W5f^0W)HYPYbhVvwN z3j9qf-n*Z@((!sJ(=`&`AuM^gK^~Wl(bGH3wKq@vBqhfVx zB^fe}vZKk&j`ykba@^4Za5uMH{QHiuz;NU9N*VrWf0{9$#&Y40psJzU15kHb_B-&^ZLrFT`Ea`YTFf zL?(yRA#MZR!f`E&%8}1ua!z4xCA#P)*M}~_^I~){ynHf-(ha2RH_R{SeA~WVM>ikc zw`eSCN!i147YGx zi!7mBYpsS>XxUsgw}sH5^a{ju{3#d6R==t9hn<>q*!&ZM9( zRIkxaVY&)SrPR$LE_&g@N4Y7We)o!>vakJukNZ;hpq=EVpAO!$DR=`lq{>at-`UX6 zwfUz%oxbAMM_(74H^#=s9<1*%C8P>Wk7|ml>uD;)=^dZEImUZ)qPzdDS^wU5?Voww z9Q)F;Qb66mFL}NHF@N`%nCO_q+{UxX!}!vX`c?Kh4*xb4R~L$R>qt_OGL60k_v zcy4k)bYE`OaBw!&qZQ*+muA~%y0vH554#7Imgd&yH_0crJ7~Ro zS*eGjUOI32-i*14RrF9&b0fSh9Ru-oy(E1d=9g0-Xb$Bc^dqBID}7+6@h~ zG*Sm6#h^gY&P4^dU?B843mhVg3Z@C{;p3EO{mYt4WF$M?!{cWCh0d?FmV0s?AjmmsHLh`aw zz;umJTB&-t2k&XvlNBXQpPG%BEC2K-3s%hw%fgk7n7((x;HFLUmdV}9S399{h3t}V zYNCFR9r+0AXtt@#?PqU^cMGTc_F_Q9(K~*3|ygQ%_y*WAq&{{j-(A^dErdIwj$pmZNa`M87Mqal)KtFVWl7(F|K&9e=rqe$Iw5arcXuC~S&4 zGBi{|=uH#C@Rmrou%BU1fA9E~{&40lMO(K<4h>Coos%*B5_Ol&y~Sy?I&v*&ZoYI$ zbBcqpKS4zM&Aq>Q@awM;)8BaGRrk$T*6))&{lnAm0qMU#ckT+An)rGy{TqEqfBVTN zlG7Er2&uPWd?AH#CiW0CbYFEUTEl5?wR#`H>aDG<_n#1`Gg_6KP9h`b=d`pI)b#g% zXUXYb9D4tgmP25AHj|mQwy!?;5E=a&vKb#g@buGz&i33X@_AePH=8Eje*2zl6PGko zXlrZ1p5ENlLh~WCX{2-~r!-vejv#tY0Wmg2i6_A5^x(wM9e!l%jvYxmqEbR5Hw`Y^ zg3Q$3e^+TjFA z^;;XbfHKnrKe^KZ`sK@^cg*ojT#=~(TV5h_1%6oTSr8dHZ?;NU{P3cu#tjv6V?{)A zSM;B<_jGVTPlv0$P}K=hw+-V-XKz(ggj*bwjWlrEG(iI3TX8_mrq30{!5}!67lArP zbR6Yg#JU*U%j!jbi0nAa^)R$PQq~Jr$TGk@b05r2+ag4A0XcxqRpuZX=NGJdwk7~ebqh0Of-wVD7u3^&6}D!U zV9Ds3LR=qK8&b*XB6ZYsV$((A<^~t;GHQA!m~Q0sbzFrXMxd_ibz&CGxfSzb?nb5; zdDC(GKVcQ23ie54eC$RtF4Zx~i0MYDzpkd!=LFR}gRdEgJji_ml9azY%8)q-*@fv} zDCy;uSAJupZ;`pdbBn!2=?qScDo)y>t~Udf+_s=Io78T8l|)C~NOTUTYt^x1$F}V| z_R2PmJ_0<-E4rfT)Q8OV&O7g@x+|+;CuWw@drn7xOaUnC8JkesYb)|BI}6ShV`|}I zm03fF8WQ!Aqq`crXlrQQsH-cWEH)NVoLJK*-s9M92;M9ivPjY zO?XF0O&N}frejf6en~^sZ~!;zLpqGDAcZj=i%EUxzw~J^Ok8SSW)9-%NG{<>#S4@C+YOf@w4!{R#zl=pM3NU-MK>j6dnEkwhLZB=c#P_bk5tE_ zM!Y#y@!dRcu5CK>CEUHYGD`v3F;^QXGOH0P9Q&JoL; z5teYC;C-31ATTVq-sGmsPa+L{by003gf7R+>Xe3tFc;FtalNcA$mL&`WlpzDFCKGm zwlzgnKO!nf#p!A?G)3uPdNPf5U2LFddmAuRwNl9am-N=11029O|JWQlGMl>}k%s1BB@tY?!`> z%2)Fk1vD!K)9dTAN}{&>`7s@>f76jjGB5@qz)-yD)8>&*!~T0edjcpFnhvH5(K!@X zrh9riyKFg;5G8)uIKEXz7nxa< zd2&rQbx>Vt<6t_pdHJ{%8gqVvs6@l)KO?h|h2Q^|m%je`g-_-CYi_H1d3?OPBWmc# zb-De_2qA~)QO#>+3JcFkN@*T{Z7)sV3j##1=ay zBfZ5XK8~++4gSY0Vli z-H7Q>IDOL&bawh`9&T;aWS?^g_^9`0VP0 z7sif$Lds2d_6rr4hohj&^}<_+wF(rCI?*XARJg4+r1Vzua<=m`Riul&aHa8kY!v}KFwXuL#k$P)BQO@n zx)7aDc!8r~bZO|+BA-c>j-x1W=EL7)GLn`fDdOAsiO3yK;s&_Ocq}X1*qo&he z8&a1s{SJQ`8KFkKz4>kR5@*oZ`fWmAj!{91n*IuZ`>?h_Y@xW0BJ57%aOpIwfOJbt z=Mt84t3vep8bjn3vRe(0j6$zFQOe^h$BxD5B=I0#hl==UlFj#I0qO5(pLE!shMoKO ze|&l;4UB?!W|46$N~a}BZ9{xsBfgiau7ED(h*ad4b0B3s4;D{G*lo;jD5r;D)sVx<_aEN!=yd<-KYjFjkItBW_uY3--?iG@ZE_Gj#D*u;q3lxKyt z@66x5C%WZB zEc9I-+(?(vMoLKoy7MuZ$a_LhA(v{%x+6C?dAKi{{TT5L^$iud-MQWM6*2wS3z30kace|eyNfa=eV4iXfT<+q_46fDOXKR`RExVG%> zWTpeBIGE<6<3zo4yJRf!Jhw)5MB*`{G@StDiKS67X@??a`skQS>>|$la&8&iUCtzc zSDVonyMY(0Hcc61r~m&;d!xV9hv$F)apnY0D+rwCvMO-(ve~L4#oDrJwQFs*zC>?O zkUF~g4G^=8E@nA9I6so^*8u!%=ddz~3i=0T5*bxODm7if>9^gAn*K+WZV`J>uKF7V z<&|v0m!6GtIjRJ4{C|XWMEp6cB2%*Wl%mfYOrJpzx{_NqGdhI%>&KZlIQQ^5tN6R9%f80e>6e( z-`|w~x4*ey+15>{>B~^kBU7@#^lA8PO)4`&uN$4{-Es;Gn>auf%XiRQ5(wB-w0Fti z;6LsVre7J^H0VhWA|=gLr+M~+>5<_DIn|ZO={p{O{P@aI4CyZp8d5i?e(o9$3n&~+ z2is3x`^dolZ!fh6pFVl=?W^aH6Ok?$KR@vnttmf^io$Et(lRhkic{UtR+Gsnnm>1` zxxEfG-Bveh)6y+E|Lpk6A6O-%lG78Z=TTwG^6x6W1{OD``M zb;AMom@BAz4T`8>%HY&Ic4#;_z-hF8k8>*w4R5MD#s4!x1qTb7QugkI(=Q+IPwi=I ziVWT2>a=CFrvW(~Qb$j3hB{I9(R~_;BDiwy;7IKHpqf`Ne*E#z-+beZ7v32<_v3Mlb3#myu#CaqM|0QjWqYZ``gd|@Y_!y@yyHvQqxsK3Y@2zMn)z=ohnj= zu&l{U$ZXw?m~K2T_n$Z**Gp@AL;+55jNEBybsaoqww5uyy!&q3sqwZ)+KZZcpzro} zbvdHgKgV|mls+$EQ6^M=_>;q@nwrijJDrIFPoWnzJsmSlae7)h`Zf2PX6)z%afHmH zqX#AgddX((&`MFH^H#h+n6FY&wqSTU9ZgjFxhubVw|C}?FD|0pQE^UMroFUtQWlr3 zg}dXF>;k2yrKPV)$10>6QX_+>R;K!SB~Vs^%Wj%i((>k^)aAHdc#B|V=2Fg-b(+`} z4CDMgSS6%%I0_ZS+l8ByMj+V@W?$~*mE`5;Ys~I*t~VpKSlyQoT$-Z`2Qy@}cl1@f zI-AvgwtcJiXvy^A=V`S!vZQoBJDMEfdf8~?bP${VsB*(tt{3a$Guz^HbGO7f8t1yE zeu8u`ej0unyzIVyUY@)px~SsTvHm?QfUMPM6e(Sley4!+0U+IQ`j15Ba-jq1@}gU< zjD+476zF1@{5pgiNaxOUwZU60>Jo~&&6uvM)Lzu2w#bXZz>{vEU0V8s64QV5qkHbT z_wS6Fj(C3G;>Al9>w=k_I#Sh_N=paUQPpAd*PcX4*Al5O0(YxyR9DIv^CpmPd^FrQ z-gR+01TUC}(go*Q^BQV8winC!0%U{P@VPkwthI}Q#B|1kOD~w%^w&sw@ezTqW2=}F z(kCAF;J4^PYB^t|rCVzIl$34&ed#_NXp-cmrLzSI&%s$Fhl`|h64MtN%gdCUt|p`m zsz`1B$3sFg2oujBsW5~ecZNwAcPAZ1BZ%|OuOp_z(F$ZVkS?Q&QO^bGVss9jM5J4i zy0yZC+!j(>biK{(!h)#XtkIcuXH#nW(PIF5-%nmi{7KAD-WR404zd}>4)dBL;+uiwLp ztUdJ;S){_?dsmoW?EEtSj9ItcxZ>3i$?2prB8?-WL+2ENlHOu`>7sNRjN(KmR~?Y# zCXeBTvHHE=(s?(pDskJf6_4V$|LKgM?%K6$+pc{#t?+Q?D}2wMl*q`)(6GGRuISSW zWTY&%VW1&){kB~{-SyBzuO}YFLJ}Ka*HeM*yCF8VDq!>a#`>P3LV43;A>`7&(tyOo z|JyIzKi?G_9ia4N3MmuGVl0d43+SWM5>1B!uz~m=+va^N`D|==Nls2vT~5=f3Tf+& z$w4s`kmixBK3vrZ`MUR2)q>{17{Z(Q4s3#utLRKb%1v^WOzRcFxsACPW6;reZM*p) z@0bnVcR%{*_x}2p&PQ+AMb1nzzWsyqRYTf7&`omsz`!^cXoMQm*qz)+u_{9ODFl7A znkL-kjeJM8*VT8U^>^pN=zV?3jpgMfDCSkUjmp?Bw-O=A9Z=kGa!0E8#y)FMqy|+8^I@;2c@QF?cT^tq@SBd~?o% zc?jH6&-tOUG_W9h3zioONAaW=1?Lwy%S^s1&?PJ64tJwA$d;}WQZW5iV|o#$-_DSV zjw2m4-CCR#6it7lx&C=rUI6vTBIfVlN0tPNoL^qV~>A(fgArkA3o zyAnDxtt7xb$UOs0R|zPXzB(l@-!-i44n;!}s9u&|5E{5AnlfqB^sZ>1xgo(>->T_B z!t{JKSo#Z?UT#>hYA|%m*1gMC4Gx8F4ckhv9Nu&?N4y*;Y%5e`HIjN$5uFor?3R0` z;=To3w@gD#f7&V{{b+2ke@AsrGn`(XmWGya)6|}tPDtfgU6fkV=~kEO*tOU0w!@yz@P*Bz=i&5^#?p5rt-+koDmC3J z$=9J8F+EP*d4NC|58tzcANkwVkfNm1qXq(_%8!KW!lA;n9QF-H5ysO`EIn;ePhPz| zIXYBaT$B=uu;OKXi~s;207*naR9q0+KUNN;pF2M?A%8lS^!Sm3m?-CGY@Q!GaxS*( z^l1{(UjoxV?H@fy#qJf4eZTqo!>YX8%V#d1o7{PP)5@W(^|i};KauU_-A_~_ikePp zx{_Y-Zxg9J|ez$`H;8UNR8rV*@qgysoecdU#9JTc-2XXn}vcY9bxNkfzaC%)`?KLoc64%Qo z9C|A;q$Kq=la@#*qA9n{DR6Ct(G!%#!o-Hm9HeynR$mv_s9Fk`mxYH-1n0u&UDvK$ z`Qr0WdS|X$5QxFOr6{I!~<(_w<9( zXVT-y!I@O`!b&*ZH&qFY%wN46?5H3me?{(e&97YjriH2xX+a8}b%WFrskt#EoWx{| z37Lsv-1s zfUBn$=9xL9GSWg+(*&LuV!Bm8Y9++b-3T3?r{|;+Q|eCHO2+Uqj}I3Inc8?-Ykk?L zm_qaiAC}3*W@*uSR@o@s zx};kx?M0MM#*6wD8GpLf@Dqc{l=%c_Iv0e}4;oYYJ@-8Pqk9)Gz7N4s0bH$VyS~ zPDV&#%-L5~>{D|i+0zB-;&eoGb87r6guX!PLUMD|f*F?W#lm`XEo+VVZf*d@Z^M(W zv5inhp}ItMOfMZ3!Kmq|<}^MAuyvZBzXwG;Y){snopkqB&%m%OqB|=3*yTvgX?{Kp zw>i~lXy8Q3IwN0Fx-}HS*swbprMk=8>}`jHyWjR_s-q<@m2ZxQTf*rHzT@xcs#Uz{=x28l1w`AqSxofRwXBv=G8V8 zg6Z+`xuvlI7{qfEGyaGe{xTO<*_EzeUn<=^#yudnv7(9@!+L5-(b5$G6GNBS@%lRC zG(4Kw6`*iqW3qcpKwbl#MKOIh5QXlZ+ZbGeX}zK`uRPn$t-Zb*CA*>m_?Ks;K0gmi z?;dW9ErqPs`@1J5mw7Dw-YtLiy+=E5d341?4{hF@7(2f&7A_xeiXX45ZW^ab6!uQ; zE2G;I3tWmX;p>ra+d5_n@v@!|)OVjHBc?l^E0Yn_bH{U|DRosVtojO`N(ZSfIMc_= z%j3)I<4ZTw{3tOo#+{#TW_#nHJKDSV3h!gep~Rk(ND?JG75>xo@|XG4@hGr3kZg!t z+Bsw{HV-6oQJj7Q>iTMD*GOkHc1lN4ql>6K33EkkCkHV*T2=3o(}`pR(;?*B@3!?f zx?4R+Z&&M39j06_v;3pG!1SQp+D+L}*+r2NMPZ2Jp!Odr+E!A#Ytg2XG7qII8gIJP z^dP3<6(ylu9~c&Zm>wcb=UM6=QgVZ{vo?6E(v%LQA-nPLG?XE}S5ZPLH9fdC#pVwU ztqSt?cCSKBul-AS({EU?Y#yMbBeb3!i8o!vYkZB{r@@d6oG;`uH36fJ?D_}8hr;`J z5VO9_fznUL8PxI}IrP1Ov#N{ZB8MVLuRvZ0h&&5cuKa4#SMRg{%s?~0XGffHu}>m6 zqo3wQqenpX^XJacZ1R_9erX{655FH93m$&%)A!DG^rZIhHO`jNm0pi$BPc18(p0w7*bw7TZuFM_}JLwlM>Va z<^Ov5leQg0h13QXs%g_uPfB5Ae`roydw66--N1(Zhq%o*lxEV~iEG)F(9+X<@b%YU zPsC4x0IZ%p9pmk-&?uC?Wwdh0Gpz~JOC?$ISYVn_f02TzFKuaW3J>*cF79pa85*5D zcjcq=&FM*NfiK!b61wM0W1<|BwV@Kl@IvXD^oe(vrnd9*$oinkq#Hshq21VWnyP(s zm`w~36}rVWA|+))X)hBgm6byUyfZlwso|rSnEs5Mn>;_+fc2%Dl=Rqx0q#CapU*f* zl={T+=YH|*TQseCZsoE|a-qL^FIg)ejwjE*hTnx2tSdK#MHR&@THAZ+x2htAp^Fb3 zknIILr`{3S8A?}zI?#?yMCNo_A00S=n0|r-lrA~_k%$8%!`r3$kx5QTe}{UI4q&SP zr0!)rJKG;=b?L#D*g|?bjjR}OI!QW9mL$wXPCvybsJ#x?%QJ6JQa22xvoVRa#Q0+D zC@?2oLhW4==<2y7L0rlQb+(I(gO^L1f-bXbdy>+78U*R5C%Yy_*3-)L-+C7({Qty0V@hf;Sqpr)^4r~i$AS6BYE4w=@QkanvrJOGwnc5$Kk>qhKDP35wcbeB>3&=prX``bJlv1Bu|_R zNiWX6%5RZ1ohh~&*E&0)!?V3KvmqY_GmI%uhSAZ}kAK z7MtURGyT5gYD!3dbg$`WWLaPkz8}12v8?HfFJOA1a@0`yeO5D4*c-eSR6l7n^q)&G zM^@KGnB1Vb$Q+~x-zAZoVNC?+WGda>5V}AeF28S`%rh+NrUGmE(m{0uc8l1}Dj_!8 z!UQsk(;ub@>AKf2p!*2IrKaC0*Gs1fdXe3Q;bZf=0P5cn)2Ariym}+3%bQNv%VUo{ zcAH53Mi^7&qjWi94GR0W!}isCnluzzWilppG`T3JX`Y$KNnW0Qa&yo28A5->G$Pfa z0c!!d`GL~~=?2qPP0C6}CqKY9w^h2j1a}1IDS9_|pu2(5bqkj8(lCx4<9PNEo|oY0 zk8^iUOzhbcwg)nA$l9};WMOC>8GR4H&RN(yCAIZ+@r{J6vvaaGtBY=ertcAYI^9TM zc-$_sd`8i`L?#(C8oKC7{NFX)YwEQuG!` z9bY=zaQaQR&bSFo@5F;HbzPJ`oqQT*6`EWquW}o^6CN_0K6h@-{{5$S@4+{Zo?PGE z*GGFGg|+vgj_0M+CR3gH&}MIc|6}Xd)7hx0hrsTN`rNMg*!A-pOE86&R|OkPpC2$k zcYUetjrvQT&2ggnEHUZBka3wzBguWaNYrpTvU=j#`cvxkNw_YU-o*Y4u$Nng3=@?| z7&_+fiVcYYnAlaBIh@#6LFb^N66_`xqFv4J)n{|Zx(CEw+#>!Q`cS5LB0$V2RJ+z3U5s8iytUC1*x|vv!%R# zJUOvy9KpVxycf24RRsv%NV`(3@XRTU(WQ#}DetDCYCK-_?)B*C>@0|(RJJdd5SUui z73tXY6%S#?_wO4P!YAi4S&F#cwCykX9{hjvvDDoMj|q}C=nbi(O$P?L;zYRt#hf-q zFi$~P5i#jBG=kGz!|KB#mT75KU<%%JQ$lJ?FGf-~nEpf3gYK4^Zqw4CbPLw!3e)Lt zbVqJ&3fA<phW%;Hf=YxnRk3yvyi2*@a-gmgn!v^Q!xm@W_e4L7(3yBkdBAJtz( zO{zyT*|KFx z%?8s=9J*gILy~(b3KWRHPA+`L!?EUP+ufKllgFOwkLs1h0QEt`MMR9hi&6Yd; zw79sQwB zL!tdlQar1B9hN!0eD+w#``qN^w(Vd#`7cAE)u3ZrGJ88?22hc!UE1D#KYn~XdpmTu zqraa5*iqOV4>b)d1?gmlK@HIK4Rs-+60WJ7A7>p3Ygd zIGq$mrHzB}PGvOaoMO=X@85o4yHV4f*zZEiCH8MvhHR6m7T@i5fy>PF)s z@?P3ubmbtDgqW0+kgx=^c5fSXqo=-VKYj9^lU)@9OcaQ;%uT~=Ho!ORn)$K8zJLW{RI+M6CP?dab!|7|hru3*Q2Ge_I?{%hdpt89bn^Q6G z5w@%y0JLl`P;8oGTpBSicwTr>c)i`+Qqy;MEel*CPG8{QY?r<^o!(S@mQ(F1C$Lk~ zPX|)do&6l;N3x@lC;fX>^6N~9xvMHRT@*y)Y(E=BhlF8aFFKbh?IqC5gt;*75v^xB z@%D<(>0G2I;zBTEj<4+NnfQ1zXJh5@@^cQSAFf!Muy(X{sNKot>g;ZJ2%o zYWk0iat@};m`<{y5yOow9YiP4rIV0F#sxrpUCo0RAn^(m8XT6#s}{)i7psj zNKu!ZPUH*T7bBY!tPZe0b02<}lg76Grn%zD*G@k9BxZHp^U`~s!CJ$F04V<>HC=0r zz;665GQL3CFuPSqDr35>xeht_H82WT%_v7S}mP+#6b9v=zbQBiq2qX>l|vLRc?TC~x4rNGb~sVAjLsW6*Twr)zv%B!sf zEHTQ&SA=*3-TK1|-gEc)tmvH4dE@OKv(VCUr<3sljVsv&P-jb$!$=jHSx2`czW2ZP zy%pOCs!UX2EtLMswqvgxWfp?x1u=b=N6^RnKi)Z!Ra^h^!1()Tb>P*$a*=d+vXvXk zs9;S*MebWae{+0%c}q_`*6I4#D7!v4X#H?iY(Nzn_4=b3 z<V&r4~%y-_Vw|6F~(3vN_psbMPp3jaI8!= zeLN()U25y=n@So`@N==QSH$PWByQg3PZ{x1|3r-TOgBh^Z%o|v(`||C`$EjL1al2d zSaa?F2WtBxg!|76f6^_WY(?c1B5V=KC^RQJ-E}rz7-zbeq+~TT>}d$DRdMMwZnrvc z8H>xf_3A)ZDcXOeru%rPKkzMTLyAp>VaiA4dJ(B>+#yW&0Mj=`(cGw@$f)UryZn)w zuB4Ya3ubRA%Fgxin01r>N!&CGO82JQMAvSq=^LpS4GAgRP!(w$FPdnil!ffBaHo9q zrs+4|bTg?iWkjZDY^ci12+1WV9n*^mN#~ZcgWY|6-18`&dFL;prf>AK+Yuh#k31eq zk0S!&1?ucIC+x3?G{!h}JhyYg|KVikf@d$1CiF&2U$$(mO-(1mWC!sbm2rhd*+qq^ zsm-Z=zFwJ2+(?HhI{x8HFMavem(M=?-~RRK!DSTWIlHz#vScl7j*eWh5jtnTClgR; zj^msV7;AZKwEq{7qWo$Ai1OnG+2khMJ2JIZH)0`;4w3{|c(n~^Sdwt*0eWuLxUk-1N zh-hnTiU@UfjcAJ;4Is&2{=o9^=3d`8+}5PH;MJ$Qd|IJ&^R}i!GGEe(;l>+HY&q&{ zTAUku9(sm|l1WVsAL>^}Cu}eM^Y)&=^X}}hq&1C7o}6l5sw4YT$%c$n-Z*WJmKm=w zv47Ynm?&X*fXvX-$u)^U@?g+Fs43;hKVAOu$$#F-^B(F!gk~;KIXW?U^4hgng}Z+= za_(SE&_4F3?^{cV4^a?fq54bVKpIGL~Z@$MnKy(SFg)1iUCNj$UgVLbo{MU%{?YofE+< z&~r!F?%>mxKmPdR$(^G~^u$uLrr-9q6o&4dw{}fhPNADhJHtbXSJy;SdO96OU6}_h zPw%O#qqfwSWCPa-7oZnk_>xr$hnek}v?eLl(N7VFvjK29OuW35Sq_vJ6d;2$n<{W| zU|!|t=ZRSiWX8B8Rhz#e*}j>0VP*1Sx=#lMTW2Ff>Ap;U)0lcNT+Cbz_Y>Lh+If-L zn#o=RJq@)4cEvfv1i`V84+3+QaGEFit(8B0qhG(%4o^QkJeuJlnG@zo1QP|w4zsB& zVNZdY-jbq@m7lxf8ENp8cv8-Ofl~YJJeQ^9huL}^F94Q*Wc)6O>6ox3rGwz6K_;o_ z9G*b)1bfR61MdrZ=6|%T=@zTYML38=hWl1*}{@Tw)=V<8n88uzkN*F)+BtR}J zjIMmrxLb_n#nAe7HC?6`RP)!2HQn5gd@iDMok>jRYPno2Q0MirO$6ynmB)B*jp;&a zAe`8AiRpJfd|{ndn&D#*eyP#aFTm#9(15y8)&=V(@CDxsmLdE^Qqwh{^v62yd<;l` zj8&b4v4iNhNm0MihUs(m?EDlqCk|{UUx2jihr$7_uy9B?%8uryZgLezw@18=AL{0-@wfK`?){Y=lYmaez?pP zvYO8B$wV^Bctu2SP5#zM9URv{U8(6%`V(L}I1YOQ--^gZDdz&V5VcON1#cnOqYB%( zjvz-=X^v|tJDt(d)<8jDT*R(|^}LiEwDUsd4B>?*MNN+@#kjIHs+#IjT6~9NDej`u zr@7v6xFBb_pg3)hXo*yojI!F=kl3c$2}v7MQXNTQH{^uZOJ&fNvg8}(i}&~rZ*dtQ zlo2i6)n&xMaHR5SG$WOP2}TL(61~We^210$=}7WOhRt|2K2^oj@Gj`lDqBW-gF7YM z#&1m+`@`GXPM!LU;#)aF>ZjvRcf@Cfx7P=y?JrwIH2^W-D-!oNx3`xg`PR~KDRE+2 zWi2siV0vXDrk9Ci)hr77K{4pBd$6%iOM()q2PK+Ltp9^uv{$0lQgcHaZ-cuxBz7!X z`*><%#|paaHt<+R8kV+AOx+a7#3YTJm$cke-s*q61(3;AspuWS z!N9TjlFLw(tpH zy7nifsp$&M)rm&wqkWeY1kpbCyX2C>N1XQ zMw7#`f(o`^W=Bmowg#03m124kz!z(MMqE~9c-V*$vUg5;F<@z*?BP*b5RNrQQ`3!+ zYW6o)hngaRF7$TzaO$T?^&E6LpsztQ?2ddkhD{y60f+@CuQxNHN!+`|72a-g@h; zfByNIPdBD_r|*+K^fwRr+d|i0lpscYGqgGy8rss^H!h`L{Fs*V&xIEn+WWeQOtm_A zuk5`zuk-NLtLt~~-kJezUBuinl=Gt8E<=#6H1+KX2?^UbZr`5p>0!b2ONVb9i8!la z`pq3pR`J}^}LlO zI}Vf_Jca9}h7Y^U+)SsE9aya!5#Ez%3Yu%OBuT(L-ez$J&s$mCOW>W}EnrUX#fu+& zaO)v_aLp8w35b9$qlBXxkEvy-C_REN}Q7vLZ+XZK=RDJE!Q zcW`xF-)dgyrFU~Ij_ywQg{mUG7`n3Yf*OtO7-8Q0`qnjSbX#vNI_?LfKm65KYrgLucGuOuaNP`&GSiPhtj9`PoIe~h55#XL)NX=9(rh3D|uexiIE>d zWezl!kedmnJ2}v3GsMTs!P_axZg%>zWz$!-CuNdHv(PItYRice=XagBvHo!9>^hZM zLr+zF?Yi!LI_iXrb4f?6v+s`i39uSZ(dj#`S(uL3&Oiq|M@CSsPFM~d((q`4Y*gccd+-x5(o#%wTb@wq4|cpQaZ?3I4Jo|N zi}msLrzxvlMq#xL(^1ovD_v>nV72nQu&#ybQBl%i?FA1$312EseOQELv~;j+@dMV99RA<1^q`P28C*K9Xi(KG-LiPgh zDw+`zS7a_;7jdWyvkSC~6-I&^$#t>G>0(r;F%kn`i*zIvF1t!i=0i?rL&^r4%B<%}l5w6~AYwWum!HwrNa8PP`^o|K$FHuXGTv6xH8FiF zt#}}E!FA5JNWmlLg=#J91}od>n6UO4bYs+qS42)1pNfX-LfNGqbSc8v;`i#n?X|3* zV6(lvDi#>g*cGaOgVSG;2Lbb01*9XWzbdkNyv>^~MiCkKcpp#h{bd zN?j%`i)#B9r6o3-%ev~za;mp%J#0K|oKik6Nw zC!S(gh2S!M`AivKjy{76<|uOxzj1-7r%rRNtiC-?cbx7oH`b?3Osieww;~Jg^@@r6 zlN+tr5PARrAOJ~3K~yctN@8xn0iM=cR&26>>EVf`iE+s8i4p$@Okd_$nV45eQc7}~ z*g=-05+&YNUbz^8?I_3X0x5Tyb2F>xlBWtXljGXVF-8gkgu<(9({TGQ&T9yYFYU;R z&sy72Ytmb4&AECj*^CylVQS0k!>J=J&kMqu;yZ3_mPeo`QSu_C)8A;RtLqHkiHQ>* z-xQDRjUJxbV763cV{hpPsLN}+%Dc>iX^82@8oH2{k%utYEE(txd4x8W57zXd>koDz z$dxyjHFTtQq{inpG%)4B8BeuqLn5Yl@wg|ZO%zv4JPn*0lDiDd1G*$JGM-9@#JogE zy|S&jwk?g>isR6S+7HW1|NCfvx&_EXM;f0rHn>RV7?WW%=hW9$S8oj`RUEZIDocn? z+!|i5SM{R;>4NBDGT~QLRH?Ld%;_rW1xz13!Br(P+SGKde)Kk`dyX6D7o;#fD2L8Q z7(m=(qN*dm{i1NOs6)D4ktwP`!*oxV;hs=>pkO-Acy2H|qabKW+>#+om!y}x((ua3 zXz4UHmU@@_rwt#6N4>JZBMZ}u=i=}jgWQpWeR!C!pGtbsF#X#~{RVo5?-4 zJvO?x8%z%kh0=9Skq*&CB-VM`BS6wA6MU$PHnnG%Vk;tbb^(a#y6)Mb-T5KBb@S}m&(D5- z^Bv`v`NO{*fBVLVAAAI-Yu$~8Se=HYq?Mm}=`Gasoc2aKAq;lWfD>oCcjxM>S3efI zjE>&ET8!yRNY_j+BB(Pq;!T$V(gYBGJN2Z8j}i28>@b*Ks!=-LbL$RwU8mlu${`YQ z+uJ9gGt|BIRO<2Lw=sRN&uVgt$&Eqz?OS~~e(l;{rFCr+;aYn3G&k?au5u##rpjqs zNy)b2T#KnF*G=*jajDaE9%#}RQKMK)@0y}2H~W?Cv;#dS%}7^Q#1KO7-5DLda?Tug zLN3AjXfhYkY4Nx?i@8Awo~Y?X?$rM&hI7J!MBgAcc1%VUS*pz@=Zb`jDwOfq#d+I+ z^nd;G{V(6SdgJRi8-jF;Laq~Wp6I+NSmtM{15og zYh0OG)f8gGbRqOr!s#mNCD$zp5Ej=9luqP&RTU}fLhSRiGebrZtxj{(g&`G!u=(@z z4^W~ye?IXmM7l8JIn-x7e1q;YdCfIU6WB)}rw8UY7AMKfQBo_t+`JsT^yHn)&!35B z!wowYiH6a}t?O@`FQsy{(9k<`{>rW|rBf3o`vV6Y#&>rIxK)vT=q!XANg9#8@N}eG zMNEvzgxlTUe?EIP;B3>?Po(MIc=e984E77Z_KV z4#cX6ppU)77G_(~)whL-m?At~ECTy%EyqicmcZHT^NMya+{46kQ33_#S-&WIA z-ix1vy-1De?ID{>eiWsP`$g1rRhp~BbZJ9McOwv8JL07gB^^{J1jhD@qElyqf^zuW zHr9uqI1#>H^mN2@XdS!BU~&hx4vZTd5sqK6iRA#g;5lb&cKWUHY#G=&uyf5C#pEj1 zMU&5k!qpOrxh$$Pn-yK5xk7$~bZ#V)^jdN|k_#q!c&zaVlcbp=5<7E*gei}#H6Eoz zD#(#_SrHMXSy_v<+^n+dsPG)3#+IX`*Ow(HCQ?@V4x0HDjMH#BwudMf9Sdr8xMq66 z{$A-jVGnbFJgQ}x2$XvGxsG{~&_!uGs*=)2N|gEpzU$G_$1HG_I7ZotzO+T0Ij`bI z->GzT<}Q%9Qq&cdzw$~dlbL5kNypfub{qUgrZ&t)B2FXr;(0MAFV2ccOKeD8)Y{c< zp~SJUHnFubZPCQmE=^5OPF#`)&ZDNM{Se>H|Ha1`n?i=T$`&Udy{xSx0%tlgE&Ui^ z8ftU>-7G{M;CykwnJ#UDxJ3cx@Jf;}YYTCl#C6byw1LRQ4kE~dvKq>b7GsSm*JP+o zRu1)gb8SIdVR_u5#jTZjsZ{&+X=P;%2|wD8fsTmG~0`>68T^%Ak-7u6NadBmiEjwuLml9GYeBePr$ z?Czv#cOU!wtGAHNXHJ*2atq%0$lf}q=+%Wc&g?#WhK9og)Z8v0wGldyK4eo*pe|A{ z9U=X&2F@SgcjzM{-K*TZJGZay^v^zEERR3xd3>|)GoKBi{6Vw1@8HeB zgEtSB71F@tSFO!uU0wKHh($k$>7~j!N$;G?K7*>vq)cab0!{!yX&McX5_|1dWGZgN zHzdaXVs|NByh6UshadK?++o>)Jz5Rwaj89O2h)>;(oOF8j*(vxU+qXt7e<#L4{8_P ziegOIUWzP4yLWXN=y8;gaP`-S=f}2P`0~r&zW@H^%lmJAjSc3_H{X0p6vEf(H~Pey z(zN}z!f2nmzxCGUM_zyFx!orUP@pJ>{gsW=cb{3cL0mWiU^-e=ZFR=H`9veW{~|q( zRDow>2_>AU=?>XV*Si0I(?Avj&B=?i<{+*~~&j0rkvsct~ zLK3~b>jEf>pfeN)htMfBT*}1l(zCEfuaB-SKXKyu6W0o^8dlDnPhR`w-@VA;GLwz@ zUSN8toxdCPr_T1ex&UwcX!|-%?ABE<`O*2$pNW#rq+$-3F4HZn=ahm<+WFW~`P17m ze2Ku$ZvxQA1Li~(fxRmxUH* zI6G=pq-?|_3sd0COcLhtx)7ajZyz~_l20Udwn#Qxieh6J9r_j{je}0Td+C~uA0VA|l#b4YS@FFv6sRlgRBF1WrE^ye)0OjuCP(U~ z%JVX$qszIfAQe!Dnx7yB^5I$h-HPH(y18(=IMeaGJfa{S37!GbKeYMz=jm|tG>HB@ z-esToS#rvY&TN)lo8L4Vm%H75F zGQg=Ix=><*Q_H}fkUkXOU>AZs#y^!9W zwD6Q}pW$18bdA#2*Ka8tJatNvUUrI>uB5HQ5W0qUJ*U!OKxMyDMi->x zzMjWD!zh;|reTfWz`z8$8nqy#-`6rtp*oIq7vHdPG$@sP7c?`)6y0N+5V%x2Os`stHy?q3E5l@1Scl;O9VNkoaoC) z+d*w*76*si>=cL0+@vZu;JF4ho0yl%~;BG0WpciL*{LvNEkH$a#_}X9LOiylZShRxt8W6rMnRnTNs-Biy+tzRzMctgT z>~FTA|M!8vy#=b7=H-Ovc+8FC7e6GZ2 zBy}%cMkTZQp$13F^a7^ePoH3E6)fKLp%PMLbdA!-`GM&kPij!5n|u7|PN4 z2$?V$Ob_$OO9RsjPZ~*bdxs<_CsD@4+2^8W55MMfCdXji8 zq`a-DIHNdPC)H`=5$+Uo9l8bHYCvANU7;cMHd5%=7FJx zG-1{9Rq6sUFUJmV=j7sh&wnz6;P2k-vldY!?Cu`hxwO zjDrk5x?fp)>uRlZLZ$HKAT=g)ix2Yx$UqFa3NszYg|GZ0IIf(%y#Y?daDRE{GC+;R15{w&Hoyf%JKq zxXS5X6;ss&o=a3fRkjaey2j=L>DtnxL^L99=MvlrrIVtVlq4A}x%y1e)8|j|$!v0i z^Ru%ZQ$if=D6nMh0mO7>0+exr7uYVZks=UI>ru+S^V+gNAU`w zrxATltK6D$dwRxuRYaBD*njQ(wG&%Ty3ahY?TV(PUuF-(wgV{(nec^%I#SAl{*8mn z0k2cEgO68}S5L^JUOmvYgS1bY&z!>B$DiU)?f2?r?-NX+=CWlz(e87|l5sCeA})Q7 z6H`}bC;9bIE2`6DMZ%RL;(Mg1=|1En38xDNdoiVj(nY-n(tSenm!%gOGMpT2y+*09 zrU|Nm`kazEnC5AQOSmJLZV^mR$@WJOmq!Wka&QpWOMvuNBI=Ua96P$~y?qp?=ZAXF z^a=H0b|9RNoKBRBG%)g_t`yr8nm-Lm(b7dfSGE{=Js`WCPG=Wv?@VI|b9Jm;QI73n zS1=vN3&wP4l=@M`bz%owG(r7Ah!U*iDj@R-e!expbX(U^8|PmUFkE%1ah8hHA9&!tCtFm{SLJzOT+WJ}WU0fqh|`z>kp6UyuZM@<l-wD2tpue(nB*%`5cqWC@qLtU;>T<4^Re}=f1!XpO)i$>^#2=jqS9c92_BRvq z($Sw>lWXlNOY3N><@V*x4T$-99UWmEmAr0t2VgWWI~7Rmd;CQ5U5>`5{t8H6v0{I7 zLs}}-K5=3^QSGUz``gkaoc$DM9nIBU|BLB=m%lmnB<$O(&nc|-nw>!>FbP(rvXWK@ zIMONcG@LX`2L#rks#Ec)?CZ-k|GtVKW|DRuy+F~29;pe}3 zU(|GQy4+a3&tZ8r4UGCK&+b0E`|5}P@zIA+I?*c|_uaeu^Ov6cIAOfk95O+sXFKXD zHdN%A+Rv5a*EoCqkToU&OxL(v!*n^ddDPL;HA=_ya_nS+ie!B6+6jT~n{q-ldTvE5 zvyj-;o!dJDLRa4i+w=H}h$S7*$d%8iQw8ZP!Rn|lX@{wkPs((+$3wl%Qk<0Ogcrrh z8FqHlp`GK8p(W@J>kca>eZh1ueROmQyBVqZj3g3<)Oea4(To)Cv|3hQtebZ+|6*uo zaRxy;QUk!m$W&ZxuS_pK0pxH5h;0E(Hx(D*NOps%Owj=*L%ZQpV_mlw_<#5qdmpat zzx@9DzkBiWE$l8o{pp*to|*-z(HSHGtjczTvwd+Wj-{Ze}-0#)E z`1mg_$ESvU^7+p{XTJoTF8S{n2E&!E>Zo4fbh6Wb_uC5?PD&)z1%#egRYh=qOqD}6 ziVP%KmEE*ZbEXTTi<-Vl&i7J7DsuW9LG*c2MJmh-x4Y5eHOYSzt`dh7yx0CdDN{It z#>Ly9_xUO%2Q{6j7i*uzeB=1$H_2*|-1Gz6u&8f4KozS`U1UIAq`e+%Iu3URhVrW<(_u27|K>CZn`yG@{Kz{bZkbUFFhlbke_!VLAN4dt}jd8`x zYvFhZpQ)#=Zn{5eI+dc{{!*-Kuk&VCMzlSy8sYRQPAvK$O)JZceWqybfHO1>r<;oK z%!rx}46}+nO{G#p%b>ErvB=jt?*Q8R2B$9zC^nk>ogC(iH(jO$Rns#mjfK-On0Z6$ zPV77(hM`KXm-a?Hft+~J$<)!&o)Qx3R{1M&7YW{f3NLOfX)ol-@WC7MGaU>Q;Q`4C?Xx8)qBfAUHJ*ZLjvVF#&q6?>MmKV{EfpkfEc@Ss%lY;3S zHB2AEO+oenj?(WQ)|{&h>)Z}|iU#STy36%*7ibpq+bJ)K(nU;%!~t{+CCZzQn*L+) z+la{pP!~73hUlcZFs4r3d_G`~VNoUkd>V<=Cr!ifNVvIzr9h6KCs)O2!$2~<&_v;`0WB}=W z=g!f>?hFE6IF*};Q-o4c4Oum&CD~<&+qp)%AFajpax`r}S%e;8TM9gO?b;RLaUz0O z6cPS0^7$^0^MxnS(Mvr%N=uL6hY8EVumE+}Up0hZMNL0!FjV7R5I|4dpQz6F2kj>S zBuDB;(bMZI$!Wx#-j&>%_ITKY`@%{~Cr>UdC|yH|7j~L8lh;i48<>Wj)OFf4-?hVC z$Y5N`cdW|-k;cZ{-$H!N(P!8eQt&Er`ZG#1m-jI=8)0d(@2gp_0PW0a1l@POI%6pt zMTGe9>tzrxnC`K-pdootJb8?Q>1Fi*aOwYbs7vw5#mho8dRYUpFy*yYqj_t6a$Z_xeR)Ag z5PeiTa3n3piXZ z;)4d0F}^_MgyqDOAQ_)VSEMxROB>qyQ#T>WV|SStAHTmNFm>&sw2p~sav^blD)txR zVTiJ6JJm&_qmH9%Azl3x5ow+{o;3!~hmkTo`3+7`8D zD8`n8)(mrf+T;;bk4hH?cFlq5(_H9xTB$JIa|ulq@TSWX6cuRRbegc4Gr;t}^;qVh z`k*+s$2v#%N=$fCCb;5VLi?Z0=?>(&#kxnE&>=w$_TlRyoukFc9uOQ8P=0#7zU#ulQ}1G0KLepl)6$FSq(pANm%G07+?f}~>)S~i@psh4#P+zkH+Bu8 zrk^F*+^W>{+rAeVU1RoR!1}5LRCdWvXXW9;*we2byL9dO^C0-mzMKEb*}K-<0BU6& zh-ZGs^jqVz8>=llsv=?f1DVsSKyjMKKuyuul0kA^Q4AsI zxw$2HagvgX^xcS>x;k3Yi<%y->n2cPIJFo7i59xl7$;W*W(E|e`PWRV#HD7sW|0hSN5`fcp zU*Ev|th0AzZw+6Yy`98MULZUDONvP8XEX{o%F20}nYpS=A=@8Nugb-?G6d<$>mrD* zjV8S3F-ad#oHE59$Ix^_V~EF*Fv}gN=`|$5 zl)d?HVEUB<8m9}ZH%_1L6X~oY0X)S~v)|<6mEYUbq+gwJHT=Y_^CwW!6T0&c^u2Rg znbLnJkd9ksR0xstZ8&;) z3&A_!*jc7C7&JLOo2uC=>43_QzrR1Ao+$=&XZjtv=aTi3l0tMkfbRP_ErS36AOJ~3 zK~x}~7g5TocA#3pB=3O<4@Mb(pZQAcUzQ)5&%?{Dl=v>W=*Z<<@*xjLuNT!HN|&fe z<_wgOay|dY0gk$&`V2c0Hm3|@QK;=x21bX|p>z?xXFZHS3@y?g6GUgd5|QN^jZ_tN z+Dz6Etd_{gJq6D-%gkKz)dkrF)s;D&6m$uB5sNzIqx=Y^ON`1RWRg=zDr4%bA3v;) zN=%2^$!ppCgfO~@dd3^J03DzN4zpRK+aH8mdE;=|%F; z)p%OryNKzk78MK3x2)-kuN7s>i5%72nmYG&dFKPfrcXU0T}V~@;#4g*{eg!EWQ8B7 zF4y>pmM%X}OvU!1mb9&AJ5^<*v^NrKx^lhHI*Kqx*@3|T($!^&dT9aCN1~|Peop_<)`+G=>_UkCTo{*Sz{lX@BWX z@O%wtauqgp@LW({=(L5~Qy+?Q4zntKS=d#`Tz=FtYWfV#pYEC}a(G&V$CfSUBRKSj zM{u?)Jm)-M9#L9fkhLZvVpm*$sZe@Y1W|hkw!|)mpIi>7<4sQ%`vTf8Wu(cit;v;= zESOv!MbyjksEn=Q)q?d{*2@cydrbbBUuoRr(H6pw|FtGcnVkBIu=#Z()0Q^pI6+~ z+_2(k>WYqLzTq7H0TZRaHLU&BkDp%19<97Iq+-$r|ICQZ<0f*<3I5J4(yO&Q=j9cB z=bG=oxTPGQ%T|NkB;rS6iefWNIMV4Z{;$E^;$!PU9cUU05f7D;q-K` zBIA|_1C$jW2wgf4jq_+N$nqWSQBDDAModKvoknB6 z|6NX+jp;>UIuGRH0;Y>mF0QiBpo6T(7FCum$;%tU^x2L@QH8A$eiMcdAAyYyP)AOu zx$*GHt>HG)OL>l=LMoFd%{H|Tm5`cGW_bPW)%0clXtmNku{|0nbVAt0?vgp(o`pI7 z0rWn{rSBXm-}~rwx}qYv9L*l{SVPnF1LrhN{G$&Kw-*;>EMFe7&nq@#b#Fz+$&7u= z0(zP3B&_P&&G? zJALL%(lWNMk^s0zf2o|)H@_Ru| zr%J#Ht9K`sYHV0B8S+=Z)nM7to{=C`q;KBBX@30cU%&a&r)FU+c;pQ@{p)KVd`Pn8 z#nsz4?Csg^-bF*w{kMJGcD zEI>^bC8vw8dp?+cU?rM5xi*;;TKZ#4M@h$(&KN>-rKXGX1)uuDg>Es{T<=VH7T_gn z&`n>2z8;e#_n$HaMjyo~o^&WF7DZQs>LzHwgI&uEQjbqD;s9|_V7#%77x9?op0N+3$zs43{ zInOR+Ur2E1%sLF)dOS{8lk}Nx4#?MzUJJcY({+(#I;P~OOi7{RsGAd|qW<>LFgkUb zE6HLMPEX-4pVV>zcW>O|qO@~6*ca9n!@Kyuohu})M|d3XH>H{)7Z6FKye6!4&`}=h z9I!0kWH35pI`IB6-GkjWdb7@kybtDe37<>X;rVRObm1%k7j8omUv(CSDgWy!_a5q|6mJj>OJD>2?A7 zj6&liJHysmc0}rIAHPp(a=KP2iI%QL3oF6w2OksU7XB6m_&Wm<$MPa_`rL>A=|M5L zV40CHN3IY^=Sm(#1-5|an%6}UI^+zPPkrQd5xL1*5eGUtI;NK&&m!stm&!v=preZk zTsWN|7g5uXJS|5B>G;&2SNi(%N2nj&MfEf%v?W#PiXx9|ag1>K<|mjK$do`Zo!d%E zqr!J?qsG(RmS&|`YyfH*HYFXd=Wc@Oye)WLHo#nILb@3>ea%!qZs<34L5p}^9#~)l zbnd-b9)cl|F8B7d>FKg8V?a)n=|$9Zi2Pv*z5Jt;t~Ned>i3Ln`AN&&KN+bk>b74L z5hoxpHJWnVh3Wf5>6+3b5c)3ZKq}b2ertF^f7@x069Jh|H6c{!Q{Yn}DOx#~KZ)x< z4UEp1A^kiVnvkxY!mS{!YGnkda{+Ya2LsFuL3a+a$Y4>7Q!XHK6McM$e`3Ql)o>1b)WOHh4h zxS@PWVx`$oy(p+48B8y;6dNj0)63Ed#G77TUEFRIH60-xPEY)YVEWjx{$GV8_@s>0w?{Q)~|V_tS^DvF}8FpNsS;NreLs^ zxO6&!($1(YEpY9OO)fKBCM>B8@|!?cN0;HQ)0U#6-$`#Hx{!|X42-~%KXHZc3j8Q( zX@N_pJ-dhyoV2t`0u{+n?{72LSgKVCsm0h#E=x!1(X_U51b;%@`f8KokERXcFK^(9 zI|2jKDpOaW^{0{c(gvijAlPLEUUk?UV-!5`NYOF-UnH+FaeqT|S;tzu z>!;WaQ|_?L_P_G~;#sgSB?EWgeb=4CbN;N-TRZZuySdR_cLojZOdZ-%!EvnS-gn&{ zHMHt4osW&GHq(eKBbaVQ=|DK%XQL#%M8y;pWpIU9)62tQ`EpvFWyI(lb;g`1bA~Q> z(pWoPM)?vkjAMIIQ7@QY#*H36MpM)8Q<$#NIc^s?T|0*56-3bADBM8#Xsk0xgz4p5 zZ_}ox<2Ki47`6n`-$=aaU^>qvrkBDfFr79_;Y*m!6liLCu$SJvrL{DS+e&V_E8Wth z)Md;Vm&thr9$|S@tw!LrkC8b|`s|E6UM{)mc+;zmBu)OM?ejxiH_8W|awa^&Jz9Fa zqoNlBSrR9K?L{ALBD=+2=VOPOCn1BT*j`gFK^cyArsYlZ4txY`|HmKR{@^N^jCSK= zqP%8TWMp^;*u_Sz4xVi?MBC|>pFHzRH1S`o`n{N4KF4j2p#IX+zj_f{`-?BW{l%^m zyTi|(y8Qm-&(6LJd#~yVr32D-(8(W>_219D_0m_*omthB;0z+V>0@FlDo|Z(l$vhM zmEJ~Z>7>0V8GXq9l5k9nFWM#I(xdI=fe2 z^#IdPo12d+HGOb!@E~oFfcbZCY95()-yO8<=*z9^?2eo>r-ZpoG5IXTvF;>PdJ%y) zp1eMv6#t|hCN~G~$j*w2?cI^llAF%XP(*k{;tMao{4zrCM{j>{rN+8pdyJK^nc@-% z-D2f$jpTawVvC7w@9z^ZJ)q88^3tgaz@Cnd>+U>{mag8|(_+zc4f?*9b3Y*RsQlFnxJclesEf1YSS*$2{KS~I?an^%&N&#J z@&5bGSGLg>meE<4o}S`E#yY> z7WZaj&!eBw^qJUR#-^vx?aRl14*wM1-kGTB>_%a)hYt;mB+#db>%T*vFc9D#==>I@H4N2g=s%vTPN^GJPI5S1 znu0>=VESuEjtIBEA%&!%xwJ3>&RKYben*Jzue}LvllY>X=gON-42+6EX9^%k+pET9BvN6g% z&Oi;_$z@b@A$2)LTV};hVQ_|6)8!n%*Vc$TowZVJ%F3lsElq+JH6+5QOCq)kpKsYx zz!|Rjk58&g>rZZ_+?7>@(E4sr9azM}ay81Z1xyFjGw5DaUe>naS4)=cdDb_rHETtp z>QX9>7p~7~71Ik=iSn|>0CJ&AlhalDWZvBz`IXd)W?A{Nm(b;jc} z$a}e8ET%0ZrxELp)8(ibURa=(R4gxQ(lSHDa`qE2j}eJow$n~1T{eT(q?P`fJX&BO znBLk}T~nP!gzM;n@(_osF=kf^@DfhvYY6S49nHZ*r7w@HyhGE>Bk35K~7-fz!f!$-%`9|Tp z#ZXvSzBS4e8$;IvF}!S{fh~u^YJ)LDZ>KZhfHCN1FT-dOQy({^rb{9t`9YrJMrgt5 zBkvm{YPu58hpg%1eev|j3#ScfV7QUUk|KRj!vp+2uPYw|c+kW%WxAGlyTuDAhIsC-@;Q>)i}9oaDYq@$&iSM7``j`}5C#em-v^uJ(V!`f}^_ubw-7`ts$MUxw1po>}$izU>totn&MO-JuNmO#P_d5kLY zMKFEC_U#)sB&^)6Qzgm$k=zU=wbdC5(3T1a)X0^wjJ&z|=*K3&G*GKQ6zMEpK z*$eFNoKdSGx5Ry;$ED=gF1Qp%v3$#DLi$@ zo^-!q$4g(Ge6HbKP2+U`lA1GTPMQr~={~`;C+(X(`_VIi`tGy+Cy~=b zFLn}@xB*Pxt6};%v4;C+C-Js2{im1sPoGzUSAF_?OebP_>A6kjEI{g-oQ}wj>!m7F zUnMc)xiPpxa*N#D#EdR7y8m>%?s(GKRYL-z1i@sIQLY9Rp;bG`lBu!YtO@wWQfr%E8Fy8jWv&=EDqrVspTxKgcUP_9=bn&9IBPP=+GsfMWES(fCJ32Orc?C6{ zAF!XnJUN!hK&Bgwk&4~f+Y;bhU0WSZI*>Thh@a6oohdb*c%~t8KV^8qEW-=rZxxx} zQQ9KtGOEd8G@1==!Hy{H&d#=v6fs6a>7s)_ETyD$tfz?dNhn+F;;MM^TaFjuRRyhc zL3)Mb-1NbJBJG4Ll$b6$I<=*Y#~xmwm5<7)vb+eRD@mO`q)Jj3*Ndp>kIkY7sTzXq zkDyB{HT{j(j%mI@=FI}#a5@UQU^ozT2m53@(CwHBPMLOTi%NHz{A*9YwoX+e;+`~5ujjJfardw%8@cHH;4 zpWmLT>@VLl;4&hjz{7Q^>)LT+meSJ*Tl$#$mbQTD%DKZ^U>AUDoGQ}}CMQe5abo2) zb)9!5vbww_CMukP=rY(*P;b~0lvtqDbYOgOT3NfvoLrDxUzS#xoR~$@OS^c}D>c&# zpqP5xhW!$g3>tN6gOZNJIRt?Z|2)0fvS~{fj*UeN(dnXCRVTe!hNSy7V`a4o4cMi`hk~=z{7TJUzo&!+-b zHl{+4nqF_BY0@{wH`H`f2AGbKWdw70&&i(S`~oB5TDMe3${qCOrL9y4-{~nk=#owK( zIR_^&ov67??<5+IVuL~d0~F~wD*1AD>dW380WMna9gT(E-X|p{DkgvB6?zj1re7nI z5pq9SF+0Ohm+uV*tPZv_Q&(eLo^bE)e~y9C%dnvHHF9r$5K^a`N6$7m&(t9@2$& z>)Zmcyx7?tFznj1$79R#T6TrXb$y3&h0vF;PFQ{2YOQ^RmG2%rXeCS0VqpgZBZ;^T zayMWz5WOOXz{KKQdihXsORpgO`O!&)n5 zdeag_Ulq<+*NN;-bzn56V{bg^(eCZ0VjLDu`Xp60xN^ETrG9&3tb6xvy}q}r*4$(L zc=z+Kf$2XbhfyH?_18an?!Bw{V19b-y<-(1{f3Pjf#`hjH||qJn3EIU9I12FIoJiz@-fy>Utu&vJK7T*<7}^e#7%mD zp)h^c!~gV8|3pP3r2a5{>|yg+U^-`Fd=XL~&|p&*84rQ!4?L(T=V1EO*Is{Os@z-| zUZl8`#RZQ^4XIdO{A6{ZJbs!<`QJ!nUaJOJ?(T0Z~Hto%8 zcAbbjpI7QPu#?C#KP)}c7JtUydhO)uTLg~>u`+=;E{IX|-HdFh6MnWTBviG+vT`FnmuM$p! zSBHAorFYGEMJQdEyk(~f!C@N1&E#!>?zgvuOg`>h%KLpbOw{zm$}U4~R$6Ov^2GhM zQbJl#UZ$z(6U)uT?WpOMmHRvT_XCzh3Vs6`{$7h?eHuDEQdeLfAwH3im*iTSL}4ZA zNRtjiWYB}LxvI5MpAoG*BCVm2+D-b9nrj=DEM8oihgZF!ATK`RG|fIM`{UyXEGOed z0$$ifkmbkknqH#-jLWkwXz417ajDo7M&2(zUd-s&UKTB?OkR=N)=YMJWdphF%o1qV z+R@QQ+~!0AWC%EKPHv-Q6kiT)kBDHbwJ>YoB`~`I+G}f1Es`AprxJM^Oncz<2Iw63 zISAjDxF5gF{!?vaG4hbin3`*fX=vJ2lUZUeGd5M}^(M4?X|)ig}=f3IJL?RmaM zkAJ`C{syN1Sv9@(ZX1mM38n|%#&pA9wGqK|oaePsv39{(1cR0U03ZNKL_t(KI)h3x zBT>(hnyYg#rL+GmJiHv|8$l^XdUlSrGm=kk98W_e5)-TQq=r@q zM8k9i=^CM{Mf~ewdEs$kV7ifSwxY;bleyj)%!dA+*BVTjWUYs%--zKO#tnBJ=QrGC zf?rmebRiYfi>|P=bTMi=y8$G+u{JMjGNCX?=`?fQ|Q5yl!Q4}MY|xZi`m7VL}+nhsGg&u4~i{Tg1fON zI6IqqqXR-w)4l30YF&!nz6GYI&(=rv1RJ9w^Xmd4jTymqQD*n(c2mU*_wF9T^qZ?z zC2V}*g%=W*_pG|!b_+`X!@s@u(o0{RH6A!{NGN^Psu#Km=IEi@&GgLaGdo{Ui2w6{ zf1v_SC#yQzxhP}hrABUg7EHIU-hiV;JTDrli_c{vYI?%Pji~7xrN0rYwkOyq{n&dE zr{8_|?9JMW5G&w(b4PAuBwDX?WUtQAV%~N9_>yW9zx>rZ#G}q{LoxR1@ zb=!z~dHs$-s~qe)P7l2c|+2tkaFKKc2fQ<$rSJleC00jRI)f!L{6 zMopI{LJs&zmW_hb=LgK09^gHP0DFf_&5Pu2@0DWb=!Vo?B>iD^k@8m%2_nmXizwe5 zpmg+f>3)QnT^G$SHDJ1drh2vQ(ekR;CfRuIv(?raMPV*eh}54dr=*joY@w7eI!b}Gu$3J z$Bg~BN1>*}cwZe22#;Dxw5C0fD44|$& z>9Dvs%8}EBj0MZzcwR^x=^SpCg*U+TBM;4e0-uZM>aRU5nmNbUUV8eam!5y^kstGP zKjsZ6QkVWlVtNrymmZ`%`s=X0M&NvC_{jozZi98j>ReVTx;zXIHXt!MN>LXb9W`C%MJk*T!wV&( zlE--WJtC)n!}NlN9u_8AI)Zu}HJT859%_0XQgz(sodcew*i9fKft?GG($zWva=8UvkmP0zD1Rr^N)f4yookPB!@HL5JSxF2 zJn$Ayy=iDrk5^Dd$oAeYZD8S(^kYMcQuOXrL}n?HMqTn+|W;GI$1Ax&-W)M@81vL6Q-Yxg&j40znD0?5YD=~ zs_}pl;NXzkltOGUu?aSl{G~v#$|4uj6;K~1~ntsRDKa1%p zLzw{J!l?htqFkIyIzJnhZJ9#q44e(>()im~K$yMWfL|1MvLK8IfF)!)(3DxHXF~ zMwb!eM!5P>`%Jf@IJ%I6>37_rtB<1%X#tE+Bc#~s!Z?q~bV71rADm|EV(y90%Z03$ zag+1X!X`(A=j3F}Mob?YoKrg4&(9;TPz9%pH~pK>{@4G0|LR*#@z%8AVoNc;TXCgF z!yQGK(kYI#8&9*8fbn8Vr*f2ThGeE=xyGB}2&V6wIrEaJ>B#9Hh&eq5uWO7sdRczD z8}$T^Q3eT(n-uczzef=l%gg779^ISJjTIwd`J*qaD!BCpoc`hwsS>?6Kje@YrLS*9 z)eY_DfoF#Fbk7_QrX#06cjn#=V7j9{M(v`E-o~0$w9q_rb8iemGAfbL*4t>irlTMG z^i!4u)uD6^(G!H#6HdJH`MYP|y*U`uE&BGq*2G3u#JCejZgO_BlzZ&)?Xa#p_{?u0 za+LO%!-qe;^y#I4`S4$E{Nn4cH?LKkZk33|5<Z6HSN;l=-h|&EwvunQH8H3Um*R%8|N-v zl#FpEOU`(s3B^P(HPLo5z=66_XJ|bwbh9bnb0xnm^NU?p#@8etz)meLW{n(s4i+9I_8e z&mWb&_qxdGXYl{Wn9G{Y#HO<&;{d_wfB5Z}$k+gK6@{dfch2`eP$GSm`Za;{$o%<@S0q4E z{4QUmlpErY;a*}02#lB5G%XB9MasTNr^la$Sg$CzO88sj;!*gXv`c5Ld~C z5LrVOjyTK(w*~nLJLiCL2Xl>dtCeaIlyL(efX2}DDZ!Z1r1F^IRK#D8#Jh-3Mj6jx zb3O6tO#EU4fcqs}oI5 zx54^cly_Od;bB5ygvZ4%^Vq|4pLiXpRe(-yDfli&TrctvTGES_n*Pv3n+4S+>4gJ9 ziDGhjXqGfK66qbR7dahUis;kSZ$@CB`s1k- znu6^Z)UmlgF>5L){?gNLJ^vcB3X%OqrJwubS#Z26A?1{(=E!3|4XF!OD>4^|hSSwS zJ5$pV6&f#B@rDJ{H%qLGACnT*g!CRQ=tb0Y+fh}Js>h^;)b?;1{>y`?U`Do(SYEX8 zB&xcN(IuVn$uT0Qi=d7_9ewF1+AnGn{43dp67~WM$L-=PBjSi8y--@ZXT)&N^F%U+ z=jEN=uMF4X>v%;#S`oV9^cLJ5Ejt505o(9Bm4duLg{X^Kt{u6JKskO9Rw!UsHWv-q z)e1y)a>zCJ%TYioxuCTaHC?@^{;lWx@#So}&MOUzIKP!nemHebZ0XP7>xqpPS|`5RFo^t0(K%lL;aDZD4wosOcHYSCjNoU3Rsrx~s6<(}jxB$>h7J zhDm7i((BZd()h}}H3NPT5uP-}T)Jt+Cf8}ArjztS8l$|SmYu2cM&zfZg{=XmL*tV7 zqBg*tYN|40XS_^01kmp!3Vi9NwJUzLKQZ}=p?qRuWsRYBQ6d>M6Ze}fNnM1L)RqOc zN(pImO*`s30p$SZW%A^oJ^IXF{RRBP-EfpoLwp!?K8UxZHaYK9UfWcVzDeXns=!3Y^7iYzHgjaU-lMd1rk?Qd()^hNj&#FTF>y-s@ zS!-QoCxz>@X*0yPyOgx_k@t(bPGh4M0rjP>k1r``O^ z3pu$mT?EThEm~IFXYM*hunTCeB>v`d`VkQ!NkM7fU>nYQ($cZTQxgiGqqsNlr_t5i zEH;<6_1?p^o?KUq^)8+ z@%W#;h%g=^{2LGY*Dl^x)Bl1uz1C)W8TRMZ^kGqd)yt>gq%|%NOG^gGEc&^kbU2-^ zNA+S&rx9s&PHo}V3`_@+!IRSUIfYw|<7bOj=x7Wl>Sahx$GL{-g*K$9>36f2X1I;g zmDxqSFXDdjoE#TUL8otCR8d7ytaEH^RAJP2FkRbDJUmG+TO<7ZCb*24Fno-k@}`%P zn{Lph<7W4&Pm9C!Vjy!SSZ}DWEDiMYRH^AAq7%r-m`14U@Cm*XeB*+`d?U)Y)@IBe zOORw}Z3NQ4VER@}FJ5=3o=1P}FXz8=yJh}_0b+`#E045Wv7bXrqm1a-q6$eX3AMAM z_YE10_+2E<&P`%2!1`G4lo)f*#^8(FL{9$?0?oa@%tF_{X|gVvi`#LM-ltH*xv zi?9FB*Vm-q(yzaMbB|zpUkQ0A&YgN(KXceq`3FehabHChmWpoBb__5Y939GE?xTQ1KJ*4X~g*qr2|bO z+s=`6Mhr9#beoclKMqYrtDnd^hSm1pym8|{{CJVP`+z=Ii&pQpfs+Ry;fcg zaf#~|3Z=Ux5sf}&J~=q5olgn9kxDWTNY07B14X7t!)|UEt-WP>Lm#UhJ17jOzxB|+ z-MV@OO2_k3vrR>$^LXpl5eC`hX4)G5-1+BEocQ?I>d={u=Wyr{?xNyd8V}5K)_d1c zK1#Qw66-oE1{t4G!E{n00n$6bp9GzNnbVznR&7X#A=w|l3$qy@T^Rign0~#d=h1v9 zedWBBSeo#xxVeR-v!SNUboZVq@ub+o@Vq!PLvs>LCx?aVQJ}pD?H)eXB3JOd2vy^F zX>xNn#i)FJ2c}=q-gVw{+N-PQ<>#|Gs{BcG$*iKk6O=wGJ3G@2bI@!dbis6JUD}XJ zqasn#1=QsfPN#sCy(}^xh>nikT3v0Tzo}0!)b2x)Cy6rd#W1-j`d*lEL~mdoM2%}C zyMBsrre)9-E+Yz?ZFOXTH%=UhwV7`FIuVUR z?s#J$adEaFqQ7wjIG?IqE`sjL4YT4t?>zZ zkUj#b&*GVXtgPv83aJaGW2`}SfBos#c|da21=Qv3slgmUt&nxRBPJgruP%qn*Oi~PS*_TVlqNQr!A?R5d4Cd zMyctlg4BlTcf_F`N1O+MsTt*D&7Qe?ruwb{k9Vz!STlNpUj%K1!sGH9PIo9yr({x9 zl8U1o2xUO3aH~>|p;S@R)fkvDAnt4ioGLegYE=m-pev{=luHz&^gE*WsF>Zg835~# zo)%L=>ypxs#q`pD0yRCZKQ1nO>zaW9&oxEw9J@G&8Edf#*4*dNuse)^&nPtGF50TM4(H3IketT+7XwW7nfX)UneUyt5o`u zn(0hR;!7SznA8cN_)=HAE_Y%|Uy3OmS2}JNk;b@EgUKaLAvy-C{-BOm zR&e=ra#vOj)>v_(QqM``capLhyWPjjEelGKjr#n7B=HX2MuGnw$UctS1zXf-|9 z#YF_||Dl@h$wRdM`QP}Tz2-Ki|0Qp_O-=s`-t=LHKl=>dyrPmBa$X*_$Wde?ihN#( z#YF~PJB=|JMx((fHud`I7DG*ZNz14?ogG^qft((wyy?pI;^|3$BN7?K zOl4EkHB0)CnC|JD7T!u@v$z}+Uuo=Kjw&?M+Y~+fwxq3T>3GQPmm71I`1+0>K76#x z7;dvguo}-7~HoIV$(=gp-#OUE*df?>JEwx+m zrq52FWLKYs`9@RIbHMb!gPKmFwR;i;bH$m{X^H4$UyR&_SV)9jByC|LorTehB+3GZ zt&=@sd%L?+=#--BlP8zAU$VJgzJB{sosZtAPjPfN8rX$tG}%pZD~F`@y2u~ocZ}n zZ_(oZ*u4oA0X{S5pu@&wC`?Crzqx8}@leu>O-`4DmyH{bNfhID@?FSF-@Xyw%0?m{ zH;S76iBS5%n=#u(O@DWXzPme;8pjxuyY&xT#{nY*;M4_Ki`|yL>L=LYQbBLodY?#aYxO;gTm-Y=?LjxBBZ07 zck10%_g?zwBlPqujhz=eSGHgL@WYQjc>9AdKDc%6(#l@gznGp$%twgXp@Nr`Y^m4v zw|Afx(`s_UEYiq4z*3gCX6M6SJ^a<&CnoP|y|Mn}a%)9T#opYi9S7!hU!>>JPv6{q z5=z(1(4yD8CQ2L<@H8qA?$A5fF zvR<$a)$Hg)PUrpb7Mrry0;6TVFesmxEUZL_0Ucst#)CTFRR-F-8$MzzaKCg~MOgFt(h&~2^nmN6{gdT)J@V3i}d#Vr$kFFr&7PE)^yan5s3)IJ4qnALqHvEM(w@l z=hsE!wsFA1xIPoFJ!5R*ZT$#r@Jcl(;KBkS?;h&O6q* zF2gy)U7F=V%|glQc@l^de!5!s&wSQa7owx$RW46@gWS=>WOL?$Z89fw}U!2o1}n1=3)X z02491FL(?!UHM)_*8bxG5C^CQmO*qmYSp8N-m_?Z1i6#(0(FbOg#o6EdwerQjT4JvFS(FsCfe9ZBx?+rfMqs8f-t{x->ZQye-f}>H_;(nmWE0 z+n77IWdT60MhiA|rKjUi2i8^6%Qw{Y+a;uAkgM8Jv8Rg>9Ggig0piH%)R0DGm6C?s zO7G8pD)25#5;%%6lDZPpfonh=FN-?j&L-uBQ?zByfK&Nl$YnWWXeZigvAk#%sS@aj za7@nOE3aaEIl6Y@%gGI`t#PR7yo?k51s`Kc>pvg9)wAWv8Ee9}lunjuM8TH+(g-R` z;|x(<7#?a3hYP@T$P&Zx!P>GdlNZG04eXg(5I)?up!zDN7h0GoHGPYr`f4p1j^)X| zBRuzDclVq;dO#Z!1||$2*fTJEU}Vd1mo*U+Xg=y$ndtHOh-t3(QD)k*bc}jCuO1ED zDQ{>g@9;N*>0Pi&}0O>f)ZcKK-PE0^hY%4Yc{#{8X@M>%(dEh6~PYDP~_?oVr@ z#SsyRHS4M<(G=fHpRvYhG2-1WZ;0zy(h(G&MHi$>$~Vhv3;W}PaPicZ#bs4CM8wly z)nG7(2bF?fB&lbOYoX8RG{#bT8I2T3zl*awp>(pPM+&RE1SaB0YGsg`?z@P97djOI z>kZ|o0GftZ9hUi@#uXuxLyc^Hxuw)rmA5{vSB`=&z=1bm?(Yo z7d`uqdcpMn*{jGIHtc@=Hy`z{Tn-MD?y!szwJ_-Sk9u1e%&=1ZcW$5yk{O1K>Y;0H z1Mv5~fP(OXR@w|>Y9Sl37NZM-x?=T0LnJZjUUW~4)af&FqGG)4>}Dfl+Zl7JX$mw+ z+JEZm@$V^4_hsNs$MpiHD|5OH)5Y&%`;jG2-=OkVFnP&Vx(mYTL z^$Ws`zC_gYkYGCH6ooTQ@C$3jo>yBP1*ZSce$C&vQNO)zia#-PXpDGY$V=y2+l0y5 zSz7jZb$dyY96d+fi^QzXH$Jtc`r-^wh59v9yD4E+?@-pu+aGoZ%%socsE{U;H8wJ` zdwj@jT4j=l;A(N?7ZSF2lC0ghqhzJYSYCFW;PkVo>9P0XOt074Cx0iY%7rn?|F^)_E;_3u)Tcr_D9N*4xXht@6h5183l(vm}JB-Fnhzua1f`n@zGvR^h^s7e3wn^W7Md&fc_k zb@go{FXgwkVodsY;!dX%DVZ#dRoU}XMx_v(?(gsDrl&%+N4Ky^)cPSpSFBF3%wC~) zu2}f!-ll~i*>tC_axY;5h$|gDcTxw9)V1b5(uGs_Tob_Of$3D%*3`5ff9UuJR}HA^ z+b--lDDckPS=UsR?H03K3@>rvCu6qTiQVN7zZJX7`(M%mY5F{#r-WqpDslbKlP4^3 zPx8;6pY88BgUjYs zpE-THkC$5yPW7gk==sYen58J%n>h;hbbFl>=uQ3+b6A=L@o+Q`!j}#|6X+t?;pq>0n3+De!F@N=cU!mHi?MP^+M( z@GLGFn|w}|qG-;_{=%sirw*mVxJpeITe@m%q>4GG-WJn&7{%$BUQpBL!s@J0KA5TS z`5H<`C3F!^*C-v2%JYyl7tqj!;B5|eCA8x_2irmNH>S>dLXuuyqM{VqXAZ!R(7O20 zm6nbS51!*qe@&_B%Js5YXj%YWg!7@Hy+`zPxnj@M2Y>Y76GxtST^uidXyg)`{=hv? zqNZbafzg%kg}aKJ4xVe?bRJMGDOi`l80AqP(0nc}L#Qt2!ssNZyDoUrRn+vKh&Nr5 zUWU|kiT{mYKQrA%>#wdaT)&mEeoI^dD^9MbGxyf5SJ$uKQh@EH;}yDZsyb3wU7%Z8 z)NQ~n7a-IY)(WY@s&X!uY^1JY(;?VtYK;K9Fgkdy3R5pX(?NuaC>$7H)=EiVIi?rX zboe~)#MXYq^tdf2*DP?M5z&_Z$q`H{`nTkjikKc3Ro#U)4*!OqG!`}t4xT!_f3SHl z+;<@F#OOVH!cR=_E5P)En!X%Lrwi#&d!zDl4^?XB>4%ywJq!8T9_{HjFwS$0U(0>2 zsOix9h`_Ss2w$d7BU*MI4J7A9<|pz7*vX)_1{;DIjN)@@QH5+1W zT;;3dT$i>465CDTAG^i_+1xfS0Ay zMlKz*6hx=t>$EZBJc4LMS=O3ZP>{ALFn)=$ri--RR@T>*Jh80{Nu9o;uyA3 z{)YW&i3seqeO+a>HN_E-$OG7%jQ(`oBR5X@O*B|Mg=woclji)5jL& z*!`zZSXB5YH%Z^B0uU?13-W?Wmn>Pr&v%bOfeOSqnNa$jD@!K~T@@zx<4~aclc)H` zih|05g4Wi8@~y@g;up>MTeivp13J~2;%q?>n?1Y2Xw(O%rwbnk7eyIjf)!U!($y}( z6&EIbNCnfShII7sX_EAUt;*%LH(l|$($mL{^DPZ85KOPnfYRagsQMhD-y!8cnM|bX zGBT?3u%zQ$89v50B8yQKtTjvFq17d57dn0_CaPCdqO z7tgpQll@BZxEMoqq}oW*45pWYatu8=2Axb1{B!FYL>|G9;&8T3ttcomA_EgxJj{KGVx91V)>} zbnJyy&q>tF^+!V}T3j~MKYQW6PSu%*M8+3C+Yf}gu{C#PY))e3O>zW3KVvPTgwzJ zOjxemE?_#`e(d6>Cw}uAF#Vu4GRl^Pj~jb9u) zhAe+d!}N=ttFgN5C{C(M0->p)sf-`dedt4l=eIui=-h|r-aZGouUtu;WRqaJy}iFflL^~=arC_D-cB(@ z#=93c@<8+2*Y~e^U8MAfU;pZ*6YCF?2%_Fa3NJr-#_&^xLd1D!LH5jJ+bI!|B=d{G>QktoKfTq;x44 z1*!$o=OC=(Rc|C0heo6f3D+&hoPO;_)HafGaKT(qDU5rY_|9<_Exq)_`V9Z++cYH| z!;5M;O4dJ#=b(A+I!rQh!JEqHl3bGB5vKWD%yuIQK<^bi-iaQytCmCLq%hj({LHG~ z+d#c11c#1K0DB7vzwGI00Omj$zl!!IWqwMqkApL*jB_Xl)l2)TfV%Mnd4kRod8i|q zlTAXU0-`x!?gYroo+mee-2r0>BD!>Bm4FsFT|6|QQ^<|?r=Mt2Zj~h$+l$!KzdKU0 z{iPAnc=l^a06HhKpbASJ=&R)JoavmD={==4Lu@bhk&ZLHrTRNk+%=@i@WQaUU`f|U zI!QuI5&28TSY1?3##p-y6TO*qtaGL)fZ$bk?K5VQB!3H^+oW_=QHp%5>E+1d8nDCg zN=}EzA66`@Fddy)9RgAs~4b0tz@A0d*F5JYjKzwsKFPT&hZ7=`aj4S!Agm4fW3=?LkhNY0)0$kVS& z*vlK()Y0pei-xDOVLDg5h5=?X+)nwZ7Ms3V19L%iG}1|r2&&hw-@5)p_!bboP!?hJ@H|OQKMInPI5ffZ1>5BWO6LL^vQ&x=T`3x~jnG>}TNhD&h|{4_!EUDs zvAZF>VECT!>auF_rqj}T`D!q|zP=3IwLE!+ujgdn$-aT$`eYH`{Ctm3_89FsFnRcW zcef09_zlqD+pnN3N$v>fHD$E>Bv7S>eRs8K9hJ?r zHliU=o_)Ep}ed*r<|!*A$6z?^fjt1NTl4BQI?FODfv|V+M}sQnH#*a zIE@!qMp`=cpEa1uEf$Nhw!Ev7ym?-92X=Jw)afZ|&9z`@Pm@fThEup)_OpMWp^W$% zto7_A=;8rz)O7XHYRZySjP_Jzw3y7b#@rgCF~jYLSJQQO1B3sSfn5DRRMWpVzT~?v zVM)Yy*U*3`7&e|AJUccFN&Rl^hqG@S?;ffkl{T{9x`v?5Axytp-S^HrM{6yB{`7g& znpWg=#PltgP@;0o^j|brR}-XOyQMxxEZ}2tb1xe^)-KjW3?lmZ9d`ulO|iP!+!wQm zU3HvCpm<(XeAqT@6Qxsc>d$PPA7=Hk0O#n)$ht^fC*SSvy#y>v zcNRNxrb${xSO-1e4iX_Sy~-|sr{av_B3vGhQ)cSMzc78}J5obR5$T6H8FgS$W@a}1 z+{q%3G{txcrl*V_zwi2Pj4fwZg=CM%b)G*nJ0*1Wdv8AV#?$m7eerk6UAtfU>YqRV zJ%01E*B@QiyZzpc`}S@8^j~&kOMmI5-Pbqn6HG6v14I#r& z)<1hD{)kBE*S>!5*fG%l;>GP36FQ4t2Gid?*xuRMYad;LYEEpWJ5CoOE2RgGKDr39 zmZHxjDBZG61-yLr<-7lS@WKTQ8)T2H?CtHv(jSv+*)i|pM<0Cg_D6VM(9l2l;KM7I zE?zo^!j7E2(tn{ucaPVBb(y##iei$Y5ryYq-gdGtY2VgZVks(LlwswhmkzA6LCWj_`7;a+C zcBW{y$7?7&eaP|xn}g{+nwXB`B_um!R5sm&youqb>Ooasg6hNx&7n=w9Dnhuvz$4d zabVtb@zwz4e0J~XGt-Fl){Vnm3ezuGFGy7Sx^*!Y=IgC-w@zGboF_{9`(NNnfB${_ zE{Nwy-Gs3VrpvH*q79InlN%L9x!FF%8}euA=0-_oNT^rjs_RxOGH!*n89Ch+1eL_u{(wb0`!QNDrWDqprISIbB>SHV?S$ZDKlG zgs3jQ6Z(ZBtOqzaMJLUvqu@Xa4EPW7NuQFwEPa{JO#eB~MBNZW>7J|Ak$xA`vr`NgyXCDBjM@#R6I!sf@=~(BPPs#j& z8HB00D4-~cj%l=o(}(KpW(NnLLr4IO%)XOspC$JI=BlTW$m%RBxCYW~crKVOg_IA1 z=};z1kIjW%Srm&4$A2@6W+@}Z+ai#T#~d!7 z`VhK1j+a@aG742cq&gZw=nBVaDYRJ@sUek4q|$qo@I_g+(K=_Oq$^A(B7N3e0r00J z&}G)FCjfVi)WLKS)8Badbub-}Mt6VX_19j1<8@-w)c~NuYB?Digf0^E!UkXk`7DpA zJVxb1_nYb`fs~@A&lNNW&RI|2RAKfZrwbRf5>gS?Im&@8Cwe+5j5Atb^_CgpMi*jl z8Q{c~11m_7QRZ|N^zswiFKSKTnl&DAV*galgQSm;jPSe@Br&SCLUa%c&y(PEuu&l0 zrXH)7M8Gx!G!m3gh@cprj-mMqFzw0LnuT4HO1*wg8;gg>RM zIWaX=Iu)f7mo80=s3xr`>&qpk#SCZn;l9D#5=7Vx2{dhHD?OQNL3nc+i7-^4QdCO3 z3x%Suit1_7hLCHI-eX%;!ycR$zxn*hv_9K zs5J^n-Vjw7G1+f49lUG@)f!DGeHtGp!-tP!x+<7X=Weh1JP%dLD!J)=DAl5-f4d3l zU)omx&Fk{*u({R&>bgj9-8qsFamq%CnT{siMR5h~(Ip?lL1}^BRG1o3dEMU2H& z#>OiWg!hL(eDPs@PDb>cVrdGGLzZ3X875NWh<*m^k3dv^&e%;LZ{@ttB zKM$q9w~PKpFTVfI$5JN>cVl{4=heOO1q>>mo{@+b*8blfuSbc`GlA*;F$sGq{R>}_ zc%68X&(B)t^?tLtkycB({nPEokkTcG@$lj8q1}fMcV9fby&IQ0-gKp=51I~N-F6$z zzp=m<8DC~;7)cJVKFsmb>WhajCTw3Fo8fLz4UP^*cXoHyc_-~aGA~AhG)2cqel~Jy z5uIA?3H!5<$w(ckz~;7t2gxiEyT*>jUMPJvQR>l7Nx3U~S6bNWqM=dbho`l8CTAoJJ%jc*~IMGZYFn= z!JW>VvuER0zxa!5@BQKo**Rxlep$>TU%Y?LW_$VVl}7p-Suom=Ng`J1CI^2XcQaz3d}M9frStebv2><_Gvl)7EAA(Z$~L1MoIQ(oaYreS960S$_Kzk_JS& zQ@?@F1(z6RD5ka|r#tBQ2XIt%nrs56q$DPG?1!Rqm7Pif#qH7l-p-kB_RJ|9zRBsx z>dLInCeQXkO%E6^Lc08D4t2*SNp2J&op!iM)920iwixE5&vtao_rd+nEJ6|%ap#CT zo!&*NtOP0DF~DdnGUUMNQFhFu?f3^TBC=BU1ljxBK0NM$%yC;Nzso&XqZd%zNRg
    Vf- z>FWJ+A|aoG$kCSMj}^ zI90P3AsfnEXv1V;1GaGu(m$4lRBu1H+v3!^Z=ahRLOX3pQ&ZQqToPmYsT=D~7TByy z0IpL~gXnh-@xYMoE z?bGdX|8%_cAIRwn)H_~kObD=wGNqZrqYp>(zEScvybPq{FUdmz=PWD!Rmdxq2bRK3 zEB;3@!~oPdUdS?!pso|3j*H9F+XUJMIz?Hhg-1t^khU${xNH&bv*ELv&wTXFQ|79Rw zvRfouMw#G+)+K=PNmTUZ-+AG6eChoB^!4v>k~xJuj6k}$+POP!&9h>#6 zJji!JO&3sq;iv3mAf!+FUO1HJvb+kV#0T;%IQ5s34#T*7@nTAbFJ@MOw8c6!Igu9i82SVG$NIkR-Qy>uxDQ{qspL0=}wj6d~Gz z<{F?Y_7z6gAe}Wgal1@;^f59R9cSS329KpD76x_P=RUYzBS}>E2;E^_#XX zLHgIwT%|H9=ZgmIqNs}j25UMxI^`;Cn4hTW-VU_k(guePv%Otlb8)5j=D_Iw+XULl zdkHNLJy^e<&^)&QoiQyfjX*kB9ke3mBS4IfCrnDU z3lp8mJ{j{;F|ioX5gCHz7Tqz&EC^k1Q^w;M+vZ=^D_G-;@@G5F@q{U_*J55M1e`%->F z+bZPr5|eIGVA|Qn;{gGlgnsA>OFRRkXgh!0(^PF<*VMoB4WBRWMc03E?8#s5`sI^P zE=<+r&h$?AA}7N@X(6v2IotMew6DbY)866SuGI89 z9YaH{GowUm!<6y*H$>Ym+W+H?A=SvrJL{2!0>z5 zi#~ZoFnzr#CBSzqb43zvpQMQVF%f+cSZy(;+Ys`NoX%oR8%rs^1VI`L_}jFMzs(vQch=VJ#nC{w0_9nP#AR^#r5i16$lXwSX;M;PAX$u5BtYqV_hwhDTbkhO z6u2l*XHR8=T?W6Ps&Kk}TwDe~3#G%fsNW}9SD`Z!UK%kTO{(dqZ=B|dz4Q`>dzhR~ ztBCVrMc>P*y)VM-40*!c-QAqsz1K+ECS{|TUU0Ug1I0>J=M5W?#!^y5n$gM0IX?n5 zorbX1c-ZwuqbecQye(g9=cm6sYB}a>72xY>Cfliye?b-?2vCHYF@ei)qWYG97lR?f z-orkfCqxB^E&rATHcEjhg{C$L+L&ROkl1BA>uqR=kQZJVo>p0j8>ddNpR`4|n{>=s z;!5AKXsH*WF@(Tt&62nqtTjBMN@AD$Wv<|aJswWyPOancp?joNhe!C@^F&Q%mFezl z8%%&Z^(6Ex)7uf!C{}jM2b;ol)v9yaGDuNnqYI-;!6E5I=N)J$_p<~Jr zm{blJjmaf8T^&Qveu(Re!T-#jptWXC;il>U*gz-0hy0WCq+KuAI@_VD>YU%TGv_5Y zU0NG4GdOex2p97WAl?&s<_tH+DuSh5du(kJxW69DeV!ZizZ!b=!|A)G?{>+}N#41W z62ZO&IsPt~&0VI?4Vp6_cgof+y|Lh>OU}`wN0|&A{qU{tibG#QZe#`%lNECYEuC$k zd{hcZ>63aU2LB577Xfv$)9bGn_w|Xe99_R9gca=MtJvBh^=*W{Ur|OEK1KQDm2n7} z=Fa6i_;rwL$eIkhwi3-f`Ih2$o|?SCBB;w#jQl$CSpLWU^A6_CB8&0Vxab*0{Z|^u zS%g+=>GYGm&Z{lXl%L_0u&@clB_+MQSY-AZlbPt3@xr3m`ZVd0kfM?_2~2OSr?e_?f2q$6pJk50j1Ja_Ic-lAyf zGs$!*u0LETqdY6pVaAae^CN?#(%5Bdn77YtNB5Qfe*VR^o3=*wFb!~ZZ^l$ZF5jH_ zTg!{_A$7$Jb`4WH+TTFV{czWCA*4=t%P`q4$^8iFwPH)JZAe~#3q96_3m`;ZwK%<$p!j|7uMCE8dacQcXu}#uX)G3t4KqwDN9)vtmkD zm7^-Lg=$a{(;pLCxM|@Y)WyUGq^qk^c7d|U#t&2FW zu{qnX)_uh7A{z&#&k;F&{%kgh#|+_9*41&Y#ls^{jx~UgFfct?-09fU{kJMi$DEGq z1vPzrxY>%N86$eSxe`h@R~i)~2&Kyq{gZEZ9gJm5$~sdF^}b4dBxRn}K_5i>Nlbra zM^aQiVT!EDBd6yRcLJDaK2c=#f=oHNkZAOLI zz9tQiBxmu#9c4EkZ^;nF9jkZ?!oUsuFKLaBH#UO&`%9A=8~4`T+<)nogf(J%DH=f9 zF9FlTDH|=j7#`JH7FA-7GF>#Lq%>Y6M%^>2u&`r1miBnPpX5hx>iy!Ezufimlh5y( zyL;kT$kCk7HnBpwa`~=lN8c=2)oO@xcC&GE(h-`jG9{UC;LvB_E$Sd)m!uayraQ(A zr4glM5uV&X5SJI#I5aXgR!P9&d)L8q4bp%2i{ELO{(E3ubHK=DU;N^OPi~IvdwkVM z5=#OfNEzv;pZ@S?Kl=I4fAE8Ud2__T>z0A@Wb}BTj)e#)ePm%El8(CerE*YjUazA zoj(qGI{tK4Gfvf<&Zqd)_QidBJH`pq)Bv3Y5IF{?XLmoh&x$9Tv?1{LI+evJ-ABow zS-2so&XYt%V|GD7oRf`Bh6*@`%bf~%|JmVq!9vY3I)>7;Rg=(%i%tzIVI4VLo)saJ ztQ9=B7cISQZ(G~m=eqYk2c)+JuEV4*nBFZGU8K*hk9AA}3U>DB^0GHc@!Sfempfs+D`<*#e(rqCt4d**BNk>W=JG>>*KV;p zbL$RAIeF`j=3BXSWe@_4j;zS{V&8_A4$k+9DTcX-tPU{Akk=w|`>ekl>OeiJP82hlWHxwWe6a@#Z5E3xnt$TUhIdYejip1jO(t5%of0VB|_{ z?-<`ZOhx`{;B+z@Nk!kj-4Dfa>)_Vh+G3>i@-X)~GyrIZ@#a&aIyWe2#%5*~HBH0f zch_+P4~e=RrtTfN)9otiF~PVItlD~M~+)5ZECva>22Rk@0E zGZJGuySaQwiA9_V8bP1pdYMV%AiqQpC z9583crYmAcN5_&5s-yQSW|tfq;$cEu$QLD_MxK_8#X%19y`?F#$mzoA?8tnPp4VsGs>FDWs$@As)oBS*72&Q^c zQ95~a3e)2X2oQIU%b=)Ch8s@anVGSx7@th`uO9Io9WuQ|73pS{f?%VOK%_2Y!xToPqRrm z9@Uy6mh@E5vXVxFXPL1vtvP*-&k|3_iSBhS~!ySFTVKRfsGD5 zbLQ;YHT!}L%DHyCyt!&sW0c9H664LrRjo+cBZQcgHDa=7-7k3h1B_$ zI6=py2Zsn_{P8I?ers#N+6r7b`EeeGpV?Z7C{qpBn(kje2drI`cK;qRQHVBnTeI{BG5ZruGbE_67(eQ)j4q}Z7IR^I z82x0ssOj+cX#sVG=@mRh&|T^2^j$?&7f+0G#i&Bk7kQ*?Stwcor!y9M5R~p=jnSpf zns^r}Cw5ND7ffG4;7f*ew^1u0eMif5d5GzM8q?SqWlNl4^m>D7{rYhFnL5eqX06SX zsZ!R9AdZ}lAzYTLXd|Y#76*$|n&MjLKT0N9*0e>5iBZhp@4=xCrYN;>$u!C-a3M9_XCE7q)uppQXhTmUn08I6JdB z-PdD7fW32cb)iX56ivd89SPzw%A@pz&=)6tUN&!eXT6i<(?F@|M0&&N(_mb{TvOD= zf+1dR{&GO|U!G9M|(V zY+evw9-Es>oo7r~qBI3vaug6>&`aZ^=eNG-0YVJmaCZoQ@$T`40PrVFcI zhSuS6K8DG3Irkgxd>ePFU5WE~R-&a-EXyl7`ThELJOtBC?f7153cLCn`k0d-_4jWo zZYVdc^GdLZ%g(RxswplmtU*w(#R_98tT9tRS~y%AKbRbw>%YLIIcR&(8cgQ`;B+D# z?8-09S#xBDJ7PB)B%zBl-Rn)s)Q>htI;udJHSwl;??{K{$i?s%V=-Bb&rF#cs%y~ntn&EsVR}xH z2ib*bz6+l^eGTb%6x)Z}g)?bh)F0o_5Q;NB9>WW73fhz6Q7;;g#%50tBOOQwp!Tl6 z#q{#$F`Xcot$*pC)imY57}LL=^ztp9!k22g>CatThmW>PoDQa2)O0dg=E!a5Vw54VQE|Gc+8U)VS>n1R zXZ^vgeqo!^aFS4fnL_VBFdgfN`jt{my87|`i8(#T6-)=a9i-fKHeQu&IZ{6gq08h# zIbSFw6=7Z3T^z;lG95<@`%*#5e1cd~+K{@-WODM!u_Q3x71xW{Uc{KLK06e!_loi5 zAiW|B!=v36>C#Lk=;@TQno3BBAbGMm#O^Zm8&L2>5(-{lF_Iyr9*wLoc9AS`BH7idm0$n1a z@YWh6y#i#=DRJFs%+@2cqouFdOB&<-&xO)OP46(Jb#(8=u#r95xI*Lfv@&C1|E)fF zlBz?|(l0-#A#l6Q5P_avS6Wa&;z@U7iLufgx4(rj#~YU}J$S(NK2~b&g9i^zwX91$ zE(5R2anIweD72oQqsKi*T6F=(4K(c}xYCz}JHd2Mt2+Bi;#TmVY+HHs*t4o}xX6af zcK5vS;nj~0vO9e6t(70X_0i#rZ?0-(M6IF$Jx^%iS{%|UHvQep9gX6f9vI6U8!H{U zId)IXE+Dtmihle74j0BRJ{Cfkp-#O=V*1DLU4Ngf#tliq(ni!{j5wH2nK69&&;RYe z|F{44j~~5+D*W7Y1e-9ESz(=**G60iEGO+N$s!3JF?8%**M8~*UwZPLaG7rmzB9%N zT`Y);%O)WbPX~q(67ACsz@1aYx^-Or^5t8H-oE@}G8^~4$m=p1IJ$4&zHZtH4Q)6{ z)XRGVI|4?k3)hFcr6hQuiLXe{C+4M=_VPe0aOlJ)kTW7loDw9DlUk?mz~+*jO#{^y zrJUnHC)EDLi7R)QX}$WYK>DS-`!jWAL(y{iuO6ISH)=>q8cI37miD87`vX{-X~Rj0 zSbrp7bhIqHLgge%6iWrPT9Hu^SCN7FMVfZna9#m`j+##0Xv=VQ^{@!*QbJlIo)_Wp z=i1gKBvd5WQbH;Qn04$>*0Vc0)^Qo6uE9E1m~Pq@8F`s-)(~!Dm*E69YgRAus7Fz1 z88Kij2)rV_AhRHYEc}OT{tZXSoFp!v7$hSme%pw`G<|ru$y~8x1L^T^&V9brGiW8n%SS?FCbUoD}Tgn?#b6E?^N&pk~dRwUi=nrWSGBSDbU6HUD+g_#&dS1-3Q|oiZpb zv9~9;(HFnlLVJYtg1B_w4Z*&t!SrWMiy%FH2bAuCjy{l2KqH0XVl<-t7tNk5AHvHP ziyc}E3&a54v%5!Rb@IklM*_j+V6{4>nP!*&{6{WvkHL)A6rn!+Q>B{oLzVfDP2K7nLiv`t@(go7-y!1RK z{B0SE&?gmhMd|X~Rmh9F24{V_!+j|ODcvU${`PU5AnwjVEG`qXsT%dEns9WuP~}SU zw>wI@E4hf%aedO3^o$GkX$_NQUw9ep7SL8wwsu5_Szui_9XVaj)b`}?S#^^0pOLe* z0rblb4H-FHZg_?~yunC^b5$_9SYD{w6yY3tWvB;6b!Mi3`P@&=7fRRex05597A>^9 zC-Fr5_0M|0aGyUh0j96?`=U3xx~O`6ZcNw~;5aO18!Voj>>pp=_eJs-y`gXM!Tn+A z!S8PRZm4)fp>!_1X2JAZWF}JFLk;O5VT@T6p?Pi*$=1> zUQMQp5*j&?Fbcr=s1EtJ}@cTInspID9{QIlvkIY+Y zYHA-xVUsC8o6MIcb8SO^KMhDt!>Wk1hO$h$Afat< zo(`W!HU~-C%aNcXG06?i`LX0FqNhVp$EF8upE;wraKRDaCCGtn_3c4^MbYIHm(HG{ zffxj{3v)VRde4$gpaNZ$Ooi3ufPAC_2KJdVxA*v!*VY%)rm=iw7JvU4T!0-$l3pCC zP{sAKv$vQc(XPIoxORYa>^lt$Vh5Xd4)*n9J@0B6?t9~WUrvlay_?E0r}y@Q>gB~M zt+6J*Ml9?^!_?Fi7M0uV(Ee5avVALa8i_1_is_5=X~xN*mPKLswf|U6|LVnGKAfl7 z{O~qubGgx1)bvHBlrOJ{9od+sTlCd4IG(4MGZy8U|LB^3a;1Oo^oNdg0rh95Af^kWOTx<>2dYJ}qA&5LHd%^DVR1)LSh8N|2Qg`SnLXc; zn@ZHnl)2O8+AzAP~Lk1J35*^P{pMYXn)CGN?ofCN*lpDURDiq+Dj zQZW7fPsY}ty%+jnRn^3VBVXT7^}qnTS@*8OV#*iq?u`dN{4nROg9pF+(Y=coFPch> z=7P24&S*_YZ+Dd07_93gHyt;JFgo#yLg??o=A(H=|Mvg>AOG{EQQ^rKyY+(Undu~}U?8V04h<~Dnm$tJ zTTx+Wh--Nu3OS6fz8X$-oLslCAkIDy`s8C6OGQLFwq@V70k%%-)`9haI#3m-zDFwV5rSy?;G=L!dzt8TBc_9wfbF+LM}IUte7qo~8mB3G9~nm>{~4 zI)8ATp0=wU9Tjmj8vR5yt9q5c+nopeF@SXbC^Uy9!Y5*MWT^BKoKE%cIy>K_q=4fo zONG)uejpwk>R1KSH>4gPE$h}}#}_{5N9-)Pf|5|vJ%rO&$P59qJWdxwT3J+KTDZYC zB58wfoz9naFzGuwE5Xa!K92C4^f;sRmSXNMt8S-8dwM&Wf%P1MbgN!X}f#K z_!eqpZ@1EUAL6f6V2WJ*yil-Evrsphy0!zr6%{}Ev|OUmJ7)mXSX(6Eq++F589Tt~gz^_vb}S7ZII&bWzfkK?OV)Jsn6#P5;SvR{z857k=`?4}b8(*Oxyv zjgJS6>7u6}SiKuHU9+ZZqz1$oUSlkHe1z? z$~9>2_z=^dnG9rfpNQn+Ya^du1p3mB6kc~lN za!u6qm_f0q_no2C6Z;FLq-^1$4=0;l))^%aqMQVjjG!)_k7mEuwDgBC!Sf>9V; zK6b_H0;DTUzsB>S1CyYv4Oipp#^_QTUrcE!#iYZvO@&RSVNBlrMTNDoK0(rebj=$4EJuQZ znyaNZtYh5F0x}ZC!0(wBi*5G3C)v6HFHqY@up8{-daSs zj1f$yK$XZwdOA8dZl5`2dscldgzl0ULVG9&`mxWLu?A{VV*B=)K|v0FvBmN6Me*lj zyBZ*K>R)Sy30!>Rd`ut0dKWgBH}>q@IheSGzitsxjLbv2isNewVf!NdKBU~lca0B_ zu~}Wd@Gt)h1oS#c$)tDMA7gr&%S_IF)F)i-F-rMB9I_ZX?GN=w7f=4}bpCVXuI3+< z+bjxIJwYjG&I*+)=vOYDnm2jPM;@tOg490s(IvHCp0%jnXKL6ZkEHf4=7KD@FE99( z$G(o~f0dd(&sClTW5%EDLMmSF`7rR8IBtRHy_)0HET_cCueCYG*#IMap01peMyxO}yBK1KZKP9?RuwzZ00W?s@X3mBkD5gyJu+PW+ zVhy+8PNyFyw%v3jcT~DEp*M}wNuZMje3+7S7ZKVG7$p#!Bcy?5wlpC9^}7~KKYhBu z%$Yci3r3Aj5d-^6>++2qji+n-_(TN2A#l|6Q`t13r?4fzw3Ku_9=D>M?hLY;Mc9dU zE!ElR(%r7u+~V7}$19u~_w8$KZES2DZQa+}xC-+MGI(R-s&_mk?gH>q%yAeT?Bzki*} zZZMfJ7S(IkLi zigweQ&@%@UkF+gnI$19iV^&lY!0C4{F;@~cXT18c9Kr3 zlXcd<$M*%CR4FeH+6B{3XIGHWxM72?tkKC1I9C%v#ptp}1`7j9ho+tLPp)Wh5ub}v z(+eMZ(51ea);i>T;=>r|ae zGP=}`KFzI!?L`eI4My8>HPHR3CzgFl={&GBGCKAe9S+1~!~d(4p{hsX(Ky6JqoF$U zgw+bn9W^oCQLHcW|BS+}S?Sf>L0M_UFC)Hp<$1yMqUq_%M9v=7qMDda(dT!*^TJPF z|G^J_@Zk^1V|=3Oq3Pv?jS_1PrX!~_exo$?FV%F5IbH5i*#9S0vIGCgd3lVc>S|aR z{7Vv_w(R96XvM_+s*sn5gsutd&saXTQPU$GCtRywak08oc~4AWba7qo<1;a5qt6m| z&Q`7NsUQ_sCEsgH!V+T!VNN7p$wEZ(6JDrC-N1q`T@dEdY^v?Mb5+j3)H`0)Z3hp& z#mME;I`nW3Dtk_HP7Z|H0HyaaT^PI-dj$_Uhw%25Ghq8*!x<#@!Si?Ghe28T(VL2; z=oD{y7;-(vbY$~8lHW*YB$hAXbjG`2x+Tw2szp0FOFmwO=r7CVT#DU(`*z8b`7cn@ zA4#YmACK?bykJYBck>#*LA?AiTL&9(ch}fdEL>-9sx6X&(Ha~gDyUKAG2&A%#ye6R zAG)RaNYIq+Q<@j-5iLD(4IMq33b!1=dLB7@4GrAksYe}hYPU8!Zr@JE`u0bIk_*kn zen8K3$C;D{D%0*Rm5%M0#f-}A+#xnn6Upk4GiZV2DD7&qY719-N7CL1v&;Nu_cbs+ zg1RFn14qgQgB*5B*=tu{AI26kBgcnpG6sgb8e$go^^^O;Z{JR)A2FLZW1MH1KuTn5 z!So`+8d(tGpsS0dm?oZa@n7yukDfDie!Vd~YwDwD-w(a%i~Og~&#li9>fW~K5i6LE zV>6+;AVu1LeDNezg-)5W_3-+f$EHs8K~c{Mnj@eux7qf{qV-ESJ~e9cs%}fBI_8E~ z`-AE}7VsC0p9-euO_yr|$(A*=$(#JghyR-}U6vKp`146GP%d=qCMA%P>@~*Pm)fgG?tT;m#t!$(?DI^ zFXB+g`EqbmXm03weSjG>zZkxL{o(rB!?o}vk~(lMcy5YjC0@nA;ER#EQXzKpVHfeu zf2pPiEY;z1z%+{-hn$`bU)XwCk6{4FM@=X0PZQG%>=7R6qi7!m2+%i(=s)(rb&!MP zW)kg~3fS8l#PF)e^o!~WrT==8(trEw(-o!W#tte1_ZPH{8l5Q#EzLK-)X`no(1#GA zG8P{^xKzWfxM@?9*~kVPoANVGV(iGvmYPVRbR^o3IlNS}e_;Kl(DL~44rAl0#>WNI zDKu>b(i>a%@ym~#2f(-LOgVnXj=gnu)SN!n^8Oz_0Ml!YWh2K&T1!eUmXwry^x zx7DnZv&Jt9oXCdqJ&AI+dIBk`sw(8QZ7Z)fpaq>dRFo!kevc${&EO)bi;U|ZT>oUO zGHTzxvGlq+?CR97BIl1-d4by-HZ08)kG0sWlag9j{m*~=Zy3`5>C;ao8U_V^$UyqH z(HTrnSeSvBj?PIrFoAsHB(fUuwPMM_GbLcdiXo~uZy>14@15P#3+vmU`QO z^!&^fD?IX}qrvq0YL;gN(`}iJVScfK2AwF5l+HO$2>00;OeRV*Z?@b$!Jp(+hWJ|) zr1K05@a>nDM&OR8j`Zzc-QB;UEbx`Uq#M8bgEXqzt6_Sl=;wjLZTk{VPAh z&u}PjG*H^PV6DX3h=fkBR#rgeCFFQ}P4+rEkaoYgu7WAt{sOOc33MQBYfESY&l4p0 zWzvohsSB(F>I^^~N0xB09g~4{1aDq6Sw)h14tpDGmXT~c2yGOrIAJdxLg@<2|77p< zOO1`j5_29YiKLq|D@qLrFH5VA!gQu5z(veom|2)<=$(x=q^j5^*xDf2(C+RhB{xbV37xCX_OFP8<$5cjx29s*}+{- zkc>1Zl}Zskl%CBCmX3Li|4v_>hp(*=xrc|9?S|AHsj2+qN2l2v>_~E4nuO49?aRgy zrei^VXM4*Bzd}O+L@`J&-o0ztGB|XX(7AA94-&5k++Pl1VR{WAR*R2BKpp(X{-Pvx z1Z&kg6zv*)TX^d~p&*0gM~!aNV%Ke7qjOHmG*)_&V7l!Mgw$Eo!fDm2jMc2(H;0#hSDd8M(HT|5+n(pGdmE^3>zuF z`4?bx!E}DO zNL2|bNiRyFS9`$va_McPg6ou6E=szlrpv3&>&}wF6T26ysS;}%!s&wO0`kvHvtat7 ziO7vT65-;r+|>uwd`T5uNzv11vqXsRvkE0j8P$E3RPlAlW!_6%ysOTH2{l{1CkoZY zkAj5#$6Ov6xmsg#$z<#lhGxhWWjr=h9a#1{)#dN9-^rbTs9-wXBm1vjyLN`(Yll#l zd!}$1nBS=+bmdJ)Y?iCby>dtD2p0;QYl90pezpAS_pcJM7#f;;HQ9S}-#FPHwO6vl zTHbe!3CG|yF)a7{CvM$TPadO0rXQ|9+G>8wI0=k)iBl76NCN?+fVL4p-;;VNgQ zas?$FJ^nm#FJ}%V9=hGtzaY7&rn-UTn3aRnpAPybi%70CbWr`=86}i!UKa^-0meI7 zm$-8#5`sUWEQrv&i0*PA;WgX$oIms*qtyTQYorFlt^I?W6E`RN?KvM4JGe73(LcGN zkXq5Wj9If12w$wJmhADa+S+kE=|yBRqC*pIh#@>VHq2cGr#mKYNqmFA#Wm*>lWU4Z z33oU`-^OD^z08~vw6%Eao@U3O$mZteJ;{YlK)YC09JdRQk@ONIYWf`atcF5khpEX( zPO#Bb?ix9LM)Uj`1Tj9^lenoqD-s$aqj7%o{772ZNQY9fs5{7A1YPK54$;Mm0MY3+ zg~KM&TWX82+Q&A;_xCk4#KzLbh+1M?FI35vL+MG;b+eH_~`~IbB zdh|0>T@>YQ5;A>==^<17YaIKEbLmL0m^zyZf<;p7`4KhNDkH|gw$Qh6Ha?DD$ zXkLzwV&6P<_9Ktz9HzP}H%wH})Txe&({(dK#3K`Co;x!uXPW?iuI0+#`rsQdy_(`g z3KZFs19em#Po>mSoz~8>TyDA2B&JU{;UiJwn>GQ!6-iq3bFqYQpazsK37u+?{v&S? zbv}nd(|x3<2J9w62*sSmn8nkjP!qje7@fr%DKT}O&je7U_9-*x%$Lh1Azj=r5W7ox zeYwk$t?Ql0O=r;}z>P>o+Ifnw9>7&gd zrF%ebZ)mvQ5FK7v%}?#&!*Dvs5Y(el*h_$PE?}@4A8tyEiZY5L#(dCQW({9r`i1~s znonZbb+U8Hu#3yXwd=LRS5lAe~GQD%xl_n*{*OZodx?r#FfyYCmTM2wJz zML)iAqoSkm{^uRzoS!YyC)I5p;QY`?WyCN@caT6tPk#3)OfR>`P4M~S zt&g`-Xu3~`T~09eJ^py(Qw@BR~|iDRpm2L#Xc*_XmA4VXo<_7LgM3#=G?hAaJGN&nM9+bqrXQ7BTVP- z-Th?$%})l#hLT9sXl&Fqrj?YGjnF`Hbi{2P^?z=G2`hvyCG$M9S$ zLkn8};O5O0-7f~Z>7FAian?f6No9sZX-UD7eOc#AqfcE*uT+-*<{ii z6kvuv#e`x9gQ^*aLCqTDGL{OUYn=Yj^wM&YzO;zu23NnAu$>`MPWOi;t zO%DXxF{u-z4x+2ktw5a!bvDr2hF3WQP8ZJ$T{&go<)V9&Ip5xfX1s8)=;tmkcQ#&r2#db}LKc-<7F0qWFe@9YX1|Y@K-hQP45G%LIm2 zWX?usrUdfG@g<|3zdxDm^okYN3!Kha!RnWXM=%yW9O*Qzs!lU_L>D?!>Fp7bFQJqo z$_u9B&2e_NeE5oh3o|NA-$e&Z5sTReMv>ID%EpH>de25t)%h=>F{oJ7HAQ_j&@E&v zZWc*9B=itS-$h2t6Zlx3;CkXTmn=k-^kYx%5)-*%^{26%bIYeEL~ch*S7SG=gN`m= zym9vgJr8#6n*Q{}E|JoCNHL%*D-Bntnw0-fL3T}R2h<-LURWTb5t2NLqDm!l;3xP0j11E#y8rn@e|@*>}81c+7n zEb-YDs-oC{;F zUb)(T_26f3g(9dAcJ7I}a*gm6^$QUbA#>--wZT3bPQH<)x^suVB`Ik2IiblRTQ_gn zO8F@9CE|MNQ@$54{o0}PdssohqfT+MxKbt3u5uK4-1jx(BDzMMRoU0K$6|&p0?)+8G z=x<`6Z-3s70Gf8j_MtT|*zC7+upie?GI(2KlaZgXZmrEaBn^@cYw@}uK^IH?WnmY7 z7xEb!%9CR@dmouY6yucb4r?|iuGxO%jh%im#e-`i#fpvyNn+yS?Nb)JH28-la_7nY zcxg_Y#@88ZlTX?9pV<XOL2o4Y#&;Dp#0)~|P2*j7>G7LmIA5?pwDf-ViuxN8 z2Xp$_;^dsc9M%VF#rINF)WxC*iRq-Lqoqd==i2;*n68^Ub-LxhOWfy^nBF@zMEeT_ zfYDQ<<@i@I{mY9*09O}3@<{R2sp0BIsp4j-mZLcwQ8X?m1b!`;PLbwgdO7crN76Xg zqMOfK&vEadZ7A`Nn0Yt{b%noR@9UU8lX~+nN0xR}4z#0|Gye3nJSiD-rQPusese7w z`$yZNQLAP}S0t|Oi4ZPf`Y7rG+8Uz+?($Y~oJ~@Tm{-7b-aA6>4wB5NZ+ zalHuUKf_wh;u&&n&G4d*h_W8idpI;~N!TXpw?sn^&>^QwuA$h}#qpvN2}Mk=&LtyV zLa^M?(s8kn8$&J@Opa!)@vu12IVJl_P?vK#txh-s_A+T8mj+BH;6;1F(qMIt;|zED zA&ZbMTDr*TLh0H8sGeIKnwyimDOy)nxW1Z#QWCHa*VlvU>#HwTUkn#sufDimDeMC4 zqOmi~(K)lV$FRK4^HMkX600a|M6fff^!83R0XuA|;Pb$tZqMqta;AeWTmvl~V+-QB zrl!{cx`^s^$mxa%h#Kl)~z6$vtr#W)pLlD7#X)NzkT`h_O(fC*RD0a zPt;4br)OGq?M0$q>e8tpwGnfAVSRnLEWN*TA>5>Jr7ORYtktu?c zO?F0`R{|YQkw_rLCD#z$pN<$`^?AnN$j)*UEx}tOzZX_s)WJU@r3Cp+6@UV6g zPDf6EN5gZ={{5G_M_(BoZ8W;kZzzF@6p)^h5?q;9z24wUlOr9WON+X$Y2`VXj3Ci>n=xiDHhpDj_*hp7=rvqA}fTyBpooHe45r@@>?`!k z3C(UUXT#|ll7rUDYL1abQWk~Wfn_?3J`cI?dKmzJUj06gw*`EEULJ-ALd)O9M8I*{ zu4z>+8+Xxjl-g01^|Bk|y4jyu;X^zzX=6cb@bj9kTrY{ppr?u%^ZMw8flhP+S{h>EKa-(CU zXy;Y4mt)~%#qXF;Rh2}f`%H)z#@nYV1Vndn;aG_GoM)y@-^F(l@i16U5Yz!miCte-fPtf%qufMp@h(TtpILCLuP^qC-d^$%2hW@*Pz5!d=ot8z7DbF} zXNXw5(w}@TCOP*i?L!ZiUo8(U_Ak%P+7h;9%Ql=Z*N8hobI0y-1yg$8om)gkp4)Q< zMIB5()CcNQPKx-S97{``WN(r!5z}MBToTWyAW1F;#o1kk!X+*J+`EYD=h$v(G%AFy zK3BO+QGDk)HjWpURfWzy=l_Uf{!S-+%agD4_b*tm#eYG}pnoj35x};%#wMX6V_`NH zmzo+JB7}?&*WShugloM#d2maESiF-Hz1K(*I$cQTObI%&rkM)T{=UIjzvd$#b>tC| z6Q_ey+x>FoX2m!o;p6he$mx+pDUy|q*9D_49p9H^ZR;(r#{zF6>BYIt#vCfi>+{9i z;y7hWPe^fSR%DO^`g-Jy=Gn^eLWv$81JUZYKNIAg92=Y5H<-Aff4FH}3PQ_=tBZ=k z^yG%FqFUM<)zp+HZ%*!)l$VCVL@YgpMg3Q?sNXJUMuPAzy^o5>?P<`>`^z{TwS2wh z7Eyqy1=ID9O`ZI3T*5x~)@o3!Hu%S`=C-RWP)bh*R-4Z}5Ua%;bGs66RGK|Nw~(SGFfO=w*9 zwIN55&1J}$K{L<~D0wHPN@_@@EYlIu`YWy%O~9URNlu@l`X33VD_R%19X)-?%6jQ{ zR-8x9i&E2lY3E7k3odn%iBZCUAjEW*r^`cTPgk@(9|)g5!`(-7ri*6ILI95*qzXp` z)wO}LF2cH8o3$Uno)slk@5+LJM$p3d+|XgRPe|BS=|QRp-2&;vj&6nA>Cl$DawVF& zNuMToj^U-Yw!WUyQcxW;HBNO>kFXxE7bgtI0rhAk_If-ovQ0sgukwxrnyf@fs56L8 z%M)TBmd*?IRcByYwf4Z7-cCGY22!oTK0nHux<=%5alIhr%ATiZ-H7i98E^=Edh0rm zArHEfcGMuIzdNa=|MuNqfBvE!6{ln5re`{pbvwslVs3Hn(Bo1$*e8@ufB6<&Ym~8_ z`oNlwLb4ojznIO)vT%B3jX0ri-Rdg7*x12xnm&J^bU#isFug<6bS0saNdD$aa(r^^ zdu7!}t6GhRw=KDF?6b42sYB7x;!VGMv#@b=q^z>i;7RM55zkfIo?7<8;gUx37o(!6 z-zzD@#^2azE(yOVye>NXhevjT3lYPK>u3b<8q+Z7Q-mvWdPX z8B;hnqaeGfWqkNj*WH?y>Vd&5$EN7G$|8y z_eGVBGOe#KH0NRHK-O)OzDBs-@mTZs7fctAjlp{1iiK;}b$8q+pjV*zE^0Sx9&9p2 zkoY%Hta9*R$-~-{rJ3};^`K2H_A1K{ZWIxD83ugz zcFuNQYV#p}(bPpv&*a%i7G^tU7G^w~@B;#DN}B|CdBf;wyh0d_{5ItSz<;&ujhrQU|s;yIZq+ra!4U@*=nn`ct;k7o&BO;CoiV(Uo z(bK}q@@eo8)5Uwiuf(VW%VO=2`cd}8uI>m&?&{gd!D37)j9t`sTAVMto|pchVlS7d zLj-JzRa6Q%UUS%5x(!Jf%gbo&%7PBS6ScVO<>x{5=RtOm{|U@C%XTj&0F^*$zjg+A ze`eaQWrU|rEL;4WE zRhYi}1!+Mlwsd|TrZU3nBBpDx>6$nF^(yL8Upw#uFXFDn4(?NE%k}-{!f~POX z*9pEoB;W;$`h46kV7ZiwhR`st%Evn^jITl;A3`*y zO<#F*!m&p*ZH4D&-i3&I$L?K1TiM!(q813V089Ap7dZ zk>?Z9uFv}+qzk2U$DN0+F*Q)yJ=9LvjL6VuxbWI<6wr#I52N?UhN&SNhJ`-y*4x)_ z{qA?YU+}$0Xbe)0P_+=TxW$E=IeF&Fwf-wHgI62+ua=izy?r(LO1Xb*@z%|ow*u;e z(o1x3@RoR96sO~OIe+NTd9lk}X}Ch3y5!KDkGYb(AQpa&UE&v}YDfpe&LmqNfQQ3% zuAO+72futF@5HgM<3lTK`#J%OlSVY#eL_iHFA_OE*MBn+F8F*S;TlJb$#bS-I6k^ECv?+cm6_gzLE@Asgv>9B8z&+nvMwm-CEH(XpB>I|>#h!Ws3FzzrS4Z$&g#V}Dc;sP!>hgadrrZC- z(<#)&n9;@Qe>8yd(Q>DY-leU>=mvAAPaZ=BsLC=ir(2mS(xo9`jsi+b*U6WIIOEi$ zlwleiS$-Hv?IW1JrKV?cI!mRh>s*zwd@=!f(qR<%qNysT`)@HFP9HyYQpiet>56*!R!84r zCBI~4m1NJDK|EtkUU9*C@SNxuaNS%1)oFkPs3WO!UTHM;)t37uJCNrPr;ohb+fd$| z^7uDyv#AVCYC1>Cb>N-~K4=4_(yJ~P_cKTFS;rQPcy9RILFtCmCF;3H12L8 zk=%Fv;`tFJ-4v1DI9XhLHln?~es5~AyJsF235eY*Gw0l*cgT7Xr@z}y1Y%!3$?9;r z9Zg*x_4>v}ubeLW`B13%ey81D$Fj_PH?rCzzRaFKe0=!&IisMXoF>R|D6}u~3z=R%ZjXHYsk414DLbpHV^XHfdHmCLtK=MC z6??|m@b#0EL)0V})LcgGiP>q7Jo8z}haa}K&U@mmkH~MqiT*K!zW(DcU)>qg71349 zaf+SAh;$#7QQ8Q)(}{J*CE6BU?QCq!^f>3? z;oOi}2dC@jLR}ySJ`zZd?L3Yfh^qKHq6tfbsMTDus*xadq8XJF(+Q^s`NyKBe^eei zJEvgv!GdM1LUF6JXI_pCRT$F?m`+y!p9XSKh}IUQ=O?6*Ea*OpiH*DeD%A3(>p0!1 zOU)?F%yB=S<;3^l9+S&5wvk-)qU~mo8b9eyy=-_lb<%^dQQ(=blwk(fyp! zCJ_B>Qb}`nFJicd{61 zM+8(Gy0+m`Q~Octz@GVC#m1xg4RG#-nx13xbP3L*<BW?g8V%jZ=z+9n z8e#OcYfocIfA6^$pL_eomw#y%m(AVvz*>hj9Za{Z=`=Tz(}f%uYgl5s)rM5fjVy1v z)buiXBCUO%`Ho~If%=_N)B$ocgybBa;2^?%sOfh@>Q4adBaE&~*0p|6_k*@Wv^PRc zA5yg_?X^*&d@-Vz%`6M|_6{jqsX%pa%a=ZO`t&D;-VXO|9gVsT3IprLqi(KqQ=HA2 zNZT5>!n#5D=+@g?@4ovk?j1ea;ep|Lv(|2IU9O7}Y!86blTUSYXxnB=aB46KpNXkj zm9Yhsl{e(T0FVvt3eaUrKgIeZyQW9>zW(|j81MgK+P_VUj~~2BCsCkWXl`U}a|veC zSM-$1Nhw%OI?zFb(b~4S>=^S7 zjQP4DPRE`8x9CE8n@34Y;c(lr89*)Odr8iqYh`XwP+dZry|9Jk#kMT$+tiU(7A8|& zO4MOomasdkYDGwr@7CLu^g;_#Gpca7Cnr%(ieUwQdY*E=d0Qt})kGD{=Pe3XR120B zna(k;pr<1_>hS-6EmW_lyEwP4!0r49*)?!C*%i6dpxnl-` zI+fA9V5~b86@|lLA{t()uKrd$;h1#{bN%!|VvdtAd(%R}Q> z@Mm27@5A&zHDN$smLc7k(hXHlzT5D+_*!lk9cmGyOKG1cTM6wo`Ls;JNWxz(K0qqe zoQTa^bPlImkZxQrRwUzOFnuD17>VgZba`K7PIuIhW~GpuPRPr$*`6*-X*|lev8B5M z={Zlq8|Bv&!? zEKXO|DGweyDJ-0n7pdu16H*E5n-^|gsG8EF*+eyx&p3Z|PE7gw^+b^xDV;N}-qh5k zs~<#Vhud+(td3m05YLO5K#csXw>kCEs4zFzi2uV!J+qty1UXy+$)FLL|T&8 zdDX%1kW*d^F%^jCp~m%MwDi!k7}P_joOKV5zVyqr(pbeJbdV`xd$Jga{nlqEf68``tN)cJr1B9^|1E)otI8FHh8#i@E{_Qxe+3(I6W7C5-@wb^Vsp@ z?{>CyHwm+GQXuJ{0Msu@Q>QD^rN$G%DTSYW^3Ao-WyOjIS~_bDPM9SgRPB1^*<;CL z%yA2LadvO;EcW!wj7osg*>VDy&hZD*Azd>23z&!TlW8o?2x>UT@r-jvc1MxUV>ET2 zb5ZR!J_UOTSN{jROkXRzkzPj%Og~ZD@F1b>BY?MVE6XA{JM&S{QBGzDC~Q|^h_m}B;=;9!T_VUad%VRZt@v# z)zc-Xqo+5ZydObOPfbft!=w#Kd%7u%G%v?TnmW~^o~cke!I+L_qz2MYKK^9ho^y}B z1fcuqyP?6OVe#T+Yp5uHY3WOImX1m(@2d{ZiNT5!N!sm`<_;Erg)QAJhcF*!Req|=0d)}C z&=lqc9x+}y^l`;j@0Lm!WU#-JXRup@e{8wEJT`(7*V+D~ko(K+qk{8R$2vRPmdN&k zMM_++cN4y^NV$XvUDkex=YPu2A z9gObqr6&8O>>JQ)L5NUz*3A8tw z8AwGGK1=>-%`6MSi|!p35Q3IYah37Alm++>?Q0Hf!4qT=4zj$l6t5AywN?c^`;FNY`?)^(hSN zr>tkeqAtt^YJpozM{njC%h635n>Uk3h&laA$H3Kr0Ukv>7F2%r` z^p@}LE^i}`Brt3x1*8PM5Qok{w#VCYUYM@asRM)82fR5PKn3Y}Y3OE$pm)6(_NDoh z*+H&t-FnC9dq)1j{`D@GEtV@pfhd*PSn`wU1w^;eiaPpH1Z8A)7xZK6CLz73tqscU z*tjuib6a+N2^r(Har@$C%-9Z~kDf?(Bjj`<8DHPNqAGdg3XwQ{LP_B#7<=;cfJ%?b zl~umJ(P-$=`&O(7n7LxyJ}8ImIx6h~yq}ptU^J!}^mMPNI(ubX2Up)bur9Y}xpZkQK>C!5B z4bPO`Vg8nJW&#Yjc=W6%6tLS=daH84kPLXPA9)|c8(98QiZ&z zF`yzEh*CjIUtKfbo5U8J>82!f>{LweP%w;bcF8IoRRt-ZW0r6iA5jL1ItP5%PcCGC zaZox(j`T_xT6f$ejQd+CBh}E9j&`IBQ$mXA<>;0zB)()n9qXC5di~QDoLhSOO-h&H z#WJl+VaIx16gI}ZUEiwdYmnw_b?r7P_-I`2M3{uDyZ^ROcMkuSM=>-203ZNKL_t)$ zVS46fX{J{ujqEwlP8*nN)I!x>hFT{sKy)SdRZkh!5S1B~DoiJ?#q=JPjDC~VuRpm5 ziL;`jE~?lwA=gsV>)Z39c3vMg-t^zU|IwG1ckW21(3F^VFRa{%>J|0Zo9yj7u6-g* z@67wZpNdFL$i>&5PU=Z_V&d_E;esb``q97hBx*YGjK6#8%o!P9C=We&@STG79Wy6A z^!BS~s6@q^{y+cui_4F{gPPulO~EO)+KC{>O{XE*<6W=k7-#VUAyV>W^kya6yIjJY-?lp5k-l z?ztx9XIAug50|vH9cQ#eo;maE3orcql{a5}@wpEcJ#}smeUrK{eC)XVm zIBn{>yBq8Kk00-^ujsF=o8!SwF^yWVpn3_~d}AYVj#tiiHkO9&y!OpUpL}_CnbSM; zH=4C=P5O={{?3%_#(0tP0;M|xjPATF`QDkS`8nldeDPlsd^VH>n9PF8ekus~=~UDa z1?d^JXU`Et>ReLacT`ge>6WvTdfLl72zvq36`20}-@j{$M^B`kXds@YG-FmqI(eUd zbOl96M^Nt)G9sp1+(?b2n_FhkJ+m@OgVMz5e97~oyhoW{GFD|Y*5x+VWtIk=SaM>) zUXJN{sKJwKYHkAFoCc;l8#ZJT&Pa;-Zp-xYq{E(W4C(LQ=4+1JoW) zQ7L&oDC%@4P2J(=8Wpvu2}b`woPK>z6e9XdKIh!|8EtUiz*obDIct{A=B7q)Y;1aH z%E8LK*)C4A;p$wkV0w+YVa0LA>f*APa2Kjam7j>?MQS>bZbi~_L6agV9qgvORIS5O zV%_snM$t~~Hu5t$&f(^T{Ov|_143yac3K;eHH9rn^82V!ZYgBch|=j?;Y_+yeA54o+8Jx=>k>>JqLoxUdD{U_{RMA$kka)dm!u-M}4ox6U@7CtJpNV5GEjVvB4WA)Pu? zbbA)T=?|^lzkjZIcAcT-Gf_ZIH<(_gbILnqNjI$i+Ub`qNdMW}FaGke?|+y3*J5*d zf(lYhFW&OKAgxng+e{16PYHo>*k0sJ7o%I0uBaE|OP4nt*9#Bg5Qxd@pFtr+VTJP`9Z^STxQIK?JN6 z7@n5r=jpl78fJIc8J1L4y?&+k*tBWKuDt#_nX&+}TqZp5ir5%PW)oFB1ZXxTp$87c zaXNK?s?uqNg_KSzkuf=|cHkHubXtyHVWx0(uwy`NNVS;*ai@}az?D;j^tPmNPI*OQ z$O;G`FeE(OJA}MOtz%xO#p1v?W3c~1oOZv5JrJZz-?wHQTFRH%G*c4Zr$6GDzs`+& z7o(H+V`wQ%q`tDPMcx*BoxOqxh@hZSl3gxP`AHN^9CyaU=`-3YD@%%sis*$zscCKa zcrq3bkGUOx`qsnySZn*n+G!zUCgOQnF=++9TwtrUsywr#YT_8eTB64s_6-S(^A1E9 z2WTJ~3hickhf_8;f4wlhDKEA%JKR^5qS0f~(lNbE-#Rs`AbZky5FK5Us2BNOB&JKJ zgzx6<+rBw@8m^uA+IY zx&BAq^!cn2V-}D3qje8*YpnH96!{S~y^^H`|6zmw?+gCAYC0W@9CjD!=lpTwjFVD2 z;dEiT1+^CY;`cVtOUTM}fLR`NZflisOoil5H>MXYr*hMn(^1p!o{phhn66a}rb|=z z&R$&-9%R0S&p8(jZEw@C)Z>B*yQWZ11r$m;>8DH@wcA(^P^oyEK)c zW~Rwq;%^NIUiWBL!BWjFbW6twI5P09ny&SUP7m{5i5DF!x`|jcQ3c z|6qz|ECRZ0FW6fwP#2U}GK)Y#=lh^B!$9imvoI=}*}}Y$AM>`<6dT!#Za5GqoI{Yq z{yJ)Ds5`;TIeGHHrg@~H4ATS!h|8tPWwpHMp=Xz#T^1TDSU*b@9gL1$-KU``iky*Z z8)CYns}Ynw!s$1zpKPk=@9!)iOBFK=>E+<7Sk+0eBS)IJ53Cre zaC*95bv2-#-q_e~yLA5i;D@bS_kYuFYlw=Z1rQzy4_--AlSf7a#evdAA+O??2&ahD zbadYCmg8-Nfnh)yh=2RV7hd?m58iz9mG|D+d6{&NJxz;Zm}n4d_{BHB{Z;~Yjbkvy$)6G`sHiKu3#{4Z1kXw(@XSm>WVlU?1Uuk z#QY_JW)S@xZ#e!5Z*4_otb2qo-M#b#))#u2cG)UA$!9!&DI>J&OR4GAx4BbiTz~~S zeQ&yda1?nUcGZunQ9Zfcsy4_`-%g0uEg{d#!-ZHz&nT~^0tnsSM5Adt2ULTckg_4~ zQjW-^augtaN8gUVzOJtHy_aNE5~cso-+$dt@#x9jrKsr{8JU?U?pYO-mY+(grkkrD zZk=kyl3kK} zBq(|kROFYRx@uL%VkljpJ|_dkoA>pP2DclI9HECOZIn{e)6$*N#P?3l{NT+;J`d9i zCU2?yPRQxlUJRvkEXap`Sw3?{iOJ8M+dzmWWAebAtbW;I{GF)NBt9vD z$$Uv84LNZBWp$$?8mUL-%= zD7)*dC2RbNTeU5q06?U!M>_r*K!_HVn{yD|P&%Fyu1uzRy~JIHl=TOugU<}vU7&R? zbh-)Y;%$lP@}Wbsa;w124@zzS{&x|x!DgYhL1|^Z$Zu}4&3Paz;|md%<44B^BG1bM z6L;~n>*TY!??H-B+4?%cx%}wj^@pB+X!(%IevzWiQ)^bBy&>I2Uy6T3O<${wb&J{+ zn@*s+$xWxX+1er0^0{jRIcJKKEyuocSF2@B z2hv|O-WN+vw~Q~A-^D@d&^lY#PZjKRVLJcK9Bvm~$cxTV3(FkDR_PIg=SADU^R7D# zsvE`q;Sq1TZ#2e%afF)9oEhdF5)$Iwu`(p2$~z7*dnUILnC}UR+||rutfxZEcThX)R#o*@ zC1sIXax|NQB*m<5}%DFyFfBA9@7A4cd0!i_n(c7% z38lGBm9-tXy4y%IjO(Z^i4RXorkb=ZJ}x)8V>XLx*mb#AP1wQ9Q3(Ij6A12Ll>$s5k+T=J2NZaCT={eO> zmtRm4A3rTCE(GNizkOD1c2@1C?I9bpYAF$J%i^F(N6BzvTM5TaWXI=)cO=CnZH$`{ z@A(&12T0&{_)Yj*c+>QP;l$$g5nR&cx0wDX?-r4NtB^Y$_(y8G*09ucg4ORpjByNQ zy-c^R--77}S^9sBn*O|fWM^-=l;K>;gBabqE?74~iVu&z(=3_J=R@+d&J3sX5kQ{C z@688c=BfNN zj!gsUbW!(=qIpoH!QX7}F@y`r@uKJVonYcxU}537)N>$wJTpzvv4+vhjip7=jQVU_ zlui#-K;04bV$^gjbgO14CIU zK`#J%jia`d#o<$pUeAt=yvy6Fb5qHBp=BXxl7?hQ2E?dkOWg^eApXKjl#V++lg39W z_C6b7Z|LWub8|vUucp0`+R9glo^?Oh;FY_ht1IT@$tN8;`Us>j>xQJ7A!-yhz;R-f+`1Er_d*>Q7ZW-7C>^Z5I};ciMyo6dbFB7#;+ z>3dJ4W149}OdoDKV$^hFds*}(m6^YL>d<%2yh>m?jYuD_ardzgCshTOeYxnJoyCtE zO#k@u&R4&)^VP1tS6_|T8F}{5XJxw{JpK62$74vmCVtW@50i&6M5NnnU4E$P35_T6 zGEdSZsHb)7uf8duitxy}h9iVc(GChnh%>ESiz!8&GUd=YM0#5n-ju!R$k~ieA`pi! zoPOgC82!yRU;GT`&5j*;QTRkq)9GbYz4zmfe*MpMFZJ|z6im0qxpN+Pnfau-P*uq5 z?aPhX*~N5-1okzT%iq6p_3Qc*xe-c!?U))QkCkX)5zDfhpp>bR_N=|RA zf0zG1#_^J$u{dM5|AtJHmA=@cG)S0E_DQCPTLQr`tAc{Khkiy(d9a~3_!~|~OgBT) zIysH!0QJlS8jc!0-IX6VobH*MlII!`lP7F&&*G&R zUe2+3YjY}CeTl1c<}AKvL2P-flY2_8i+i5SEPp3kJH|NmbJhGlbnz%3-W;X8SYocBs$&_tUE3{?IiP4bY905Jj5}A)Oyd43mJ+U}w`;3{Ib7 z%dth#IXJJ5^iupTZvM`(c`23n@lsM$hw4eiDu21~>_w$`&RM!R&$h;&Ca?-mXLcev zouK*=H66uVU~VAYNa_}q-}S_FNPV)&A7RO4BGsX2@EK?x84pqb3Z+}L?f~{(kL;3~ zZirczj$y3fj|kSy0*vZt+S0YNqT8DT~H_U)YD~%zwZIsg~GUGz)(H9{JXR| zz=@);bkR1T{`}mzL(3n*{xWwtYC5&5lIjhl8||J|iEr8O5cBms#`0n?9Xx;e4dn7N z0G-gqwQsz^Q7<#zd+)`cyta0^Sbi;1IBs;Sf>fNoe~5b82X;wJ7o?8_r_1_c)O6|T ze987=tS@9Tz9BuH*#{-07NuLIqSDfZp1>w zw~lEYKW1nqF7%ZvyPJi8q;8%Ef+!eYXwQx{2Hny@TIbfU&)&brtCq?@L@Np^?6@xQm zdEu#|S6(mS2_@#AXX#azYPY!LZe2Cg32vTh-r73y|MjnUd9S~{X?H&g9Y z;>M)fmKm=f9xr$Lq!scXY@NP!UrFVKDnscsPzp;5j|*!C!l54xMQ8+st=zQvLKbl_ z*;$)b2J(rB9s`Dv>M}JNCJHPmC<>TpLer^B#R&tY3!lb~8T~L_PJL&TFh6)bj$Fxj zTrb@e#3psHXk|cEU16aRMmz5R*7Wix@6O_Wd1L-)h|FC^mKZhN>>W#Q zNpbPymIKUg!E_1z|L3Ub_K_EH%Oz0GA2dryH^lBx(?=UM9X2*> zAl>w$9g)*5yShYkzU1hWIUV>%l^<_my6$lp)B^)U&Z0~XS%k??s`N#QARmH1id9k?Moa>;F;bRJ79i%QX-Eg|Je;MrcmwN=$ z^}0mcI2cY)BoMLcyW06{P20uy1T!BcsOxj z+OcCTot?uh9XL;gs4+);@^1fLoEEl(gmyX{MR^uSHC>{!kr|gxB6 z@9aAC>Y_#8to_j=&w%N+QPklP5?_bTnwD0o4)(TGD80+Iu`$ODHU0dDTU+-Zt-$6% zv0xn(Xwmd(I)GTgvQ)Voy|CVI8U|y>e{1?Znb_k^ORc z&E9v(75loeac=}V`Jss7KD2wO-Nf9t=eAcA)YtXb)h7zmE9zroog#u?Iy)!mM8<+8 z`hkV!_kS(RjK|WhFGza%vg@|lk?*Wt?X+gwk{#*(E>Q(F2MbcLPpdf&?jJ83ZfN+G zLo7r-=D06*S-iN3(jda^vDA1F*|>O=SAtvm0!V$wf*>FFhA9oSspTj^L_~Xi{Uyup z0;Yehy5J)xcQ>BgoqH#*cjjMeF^q&a0zPnn@#>cQ1cwj3vScMMRTo=o9_og!Q#2uSBc=N>~_u^bL| zVNi1p@^kfa_A0M)wX1AA)+b^P`LUyXqMT;WW-2gh4z_y^kyR7^Se=@issm@{=j-I` z_?s*2RKHPcNH^DMGACN%o?>_dBf)&x<*$E~GJS`UW`&3AJ--8eBe`vYb`vLh~ zzKfN`qI60}mG~k)=L<-O){WN%HJzSihRcES$G-dB?~z~rkWv}p_J>S&BRy8O^zXg# z@@eCJnY(uX8*ASfQPL%)^O(8J9Kdv?v^@C0Ts$wI67=GI`mJ^M@lIiaA?L+1y;!7f z82uH_jqycAq~^qiUMt(bcI+++I+=LzW;*CxTDtin?uNGtOUzx=kCJu60ff8I(oxe5 zq#ICo{Gf(l?&zUF@0kH%;Q%^bgRqdWz_8w#zR|7Yh3LD+bL63Q*VuLAhlad|CQls7 z{*?QWf+1$PTzY!Fh0X}zGNl`1x&ib%9AW7IId{^OWIE8MAcuLvurU(|bp*$IdH{78 zoF+OQr>f%OE_i!at%%+i0JyCTU%7H)c-*w@_`4Ng8_X4VYwx0?|HpwVAUbe;^(xNtt60lV;akC^!pwlRZAHKc51nqnRYhC6HHD`U%x!Y7Px9Wy>U z%)28j8Gt3vzQg^hx36Ftw!v$t0?G;26Q`5?fc0$b?2pbX=16ig5wS z0k_|A`_{wrREg6DeKBbc`($&RHuuU`7q57o^qbslH6=CNzWSs?wv^{M`=|HM2dj zr6j&>BeM+B(<_Tg+OVF-*Cx-b3JF;e(2=!iA#VDtj*t*C(~ow9#mxZEvuY`Xtxd$7 zUQ}4nLLPond~HX_roXTYX)-Ll@FscQ#B>=>{sVG`Vcai{^^KZN=TSP0-ifu`A*V~swq|wmzCh*7(#%9n3504qgq-d$ zy)ZLGP9I~cPnD@Jb2g=>)UyNs6{dMJe5vDsHs(FWaUOkRh zG88*cC*#euB$Wlmp{y%DUE}EdgRwP0`uwLsbu+jEu*2%s7y1&8= zc4`-2%K&rn;^6t?oUR^kIX>JrJdE0L9BrKi7YDHV!Rf#Gjq+Y9 zASk!|gj|AS_7or5(|8h#Gnwf$p5NOZVavfVQ%9>ySn!LY#DU|T*PD>gm6*N=E#0W; zhZfO|wD?fW&XkCV6z9x}+TN-F?=N3{($gpE)oYkuKEAx;@uv=n(=VUxI<)i5+jD>P zy=NX@v@;^Y3*Uy97f~{KUYTB`+a#p=MO1g4jo7_AX7>%Fra$q$f2**ev@UQCCiliE z$5!kvTqeYZ8d`s+1TQ*Bp$-ctJ6nz)@5J$vc;S^F{@~|7{lQP4{rfXCVOn&kI07dT z?KAVM72UG;<3D`#(Z^j+5k_L<^bJ@jkkhGA`!(O|Fa zSFZi_>jjxuN{EQ}M0#J4y2EBeYbGm)xRta8`JOqA^>U^Ym#*GNmrm?%Y9gN!Oy4a` zmrl;bti>)K=R8w`f`g=^Tc=Vuol`;@4MsCdPwd7_L)s6R{%&_C)^uJ}9o*d@(}@qH zyy2XthA7|2=?2s3tdyVOe59#~`{rPnuTw#(m>Q@aIoGvwN9fs=dSXF3Jx76be$q@+ z>GP!)MfB1or9~r;Lr5_C^(PL)73@@q>m4MDM5(cLL03ZNKL_t*96q3`q#E~vrx-+X8 z+Y9V1$2sAz$mu}8Umu(v?C0)eCBf*AP%yhk@JkLeW)5ySaoo$5AXTT}AZFQ4u65i@`vVH%}9B?fpi)NL*~#q zh8Mi)cwEruC7gfvAz`|n#XQw=Z2~_Goc-65VPAy*y*2bv*ma@v2KsfALeI(?^CO_0uG+Gk$`KZmH>Pi_rAR1in)pJNgo);0aNPR>&=fCp^rJF_O|848t z{KptSZ_MGt6DKya39&a~y1XgP&2ivzNKafx$l%7Lq@+!oRwAWtmUoykKMZrFpdvg9pt3Na5-GfNwPanYwRXG zdSHO2Mf)fsMJzYCHb1fC8=?p)TtZx@8WHOu;_NYk89S~F_OdrUrv|Q~!4I@`B=w#; z-rY9iXkmFGNf4-FWppClM0EP8xDL|Qdp!5XF$lGeO@rrcR z7AdU}%Xe*oo#sG<7se%Z%x~Kiwte&FeWOQjJzRD8^<#;N8|Tfdnidy5?=T%liDV>< zW8U3cHx)D#g%Hum0_J2K&1oJ7#S?>0g`Q+bq)If>DiDe!7^XcuifYku<4{I%X-$gD zF3IvHH(g67a1y1<_A+kj#M>v6*dAU}m^>}Eb{blGMIFaE5{X$XN)A~O5|bHzIIex`wejRuxb?_eF#RA) z%Wv7=+i+E|8vRJQE4>pUXrVH9t zMrt}mNm1VnsBd<3BQ;s-#+#1$CA;LE@*0dVeDTczCtc%AuwEo(T{f7a_4C8Wf$2Em zIgPx_+tvgJFL7(f^@6>b+-3DdiEyW(labTu&cXq8SzhvN&M4=A0d904U9b+QyX!c7 zF6E}S7%&}f3trOI<#Y0b8+cq80`-d*&zmb;5-|JqRpJ6wdOt8cFpRf+fYVjJA#sVX z@4tVk-X3+%)mB$m>bVDZc}#-L6O1ch`sK?zV)E>DnF+Z&`nq;hd~)>o`Of~PMT_?E zWd^K%h&*z>x*{S*om~=Y^Xrc9-M3=qj91V4cr+a8`{JK}^Uv2V?~QsY^fGNor7#~l z^Y%jzuFVFX-QDyDt%I@#xG?uqM#8dA@u#yT(5^aE1Uzp~TFXGdxmA@UIs#W}@$ zo;r7E&!Xb9qui^Pr0>3;Y`zFr73} zM0);G>C&^8KRNozm+fno+7GU-%w4l>P4$9c=RAUGh`h~H?JDkYrYI&E5nHsEr-#ep z;#iti!07$z5=+QSLn$xT2ft4QKmERl;MoYlIM)*vEXa4w#HB)aBV6gfq508?-Me=; zC7d{Ma`#E4F=m`VC5O`an&aV_<|ltUnJd!LF{=}4P7I4Pc;1LJy%e}7D7^wo@5cOs z=bqBg4S2&F=A3)<+~28vD^Tj{L9U_)l~U>Xd+AA<;d!J9*9+!!4=Q{c#OWiDE-BsI zz_kRYr!UB7a+;biMV~}S%Bhv_L(e0A+tJcV{mBE;vAk?>_nAG5=B^~X;7WG@KdnuD z5cL`S>@tE@`6FWIMVDUi+myH8@@n(~X?2IQ6xkedo+`a;kvoxL*vU z|Gg|Pue|aaok(BXZ#K`>{rjJP&;-4hE~I78Kgipp)O3r|jrB#r>B>&GINec3DluKK z{@PlMGP{`Jpr_x;=myexuj%qc!`59KwYdAPJBL0UYTd=GNE$knZe85;rVkB8PZ}Bu zAaF6nJA{6IGs6O-TkpKPb#g2JRwSj589PK)Ll%8GaI>GFU9f zi>0F*y9>&>c->?zejB(*$5C32-i;$!|IkpC<{_mAmLaFhoe~}0TZQpFx~ey%*SmL1 zRS1B-aC1164yF^qfwnDrJrBGpTSZR@)`HzECB0A$OIaeeH70KXv2eU6nyvnW2>41b z*@*-b+sZL?5L{3^>To!#|udwRCjr{FIJZ{PorJd-0}YdFk(`wP=Y-NrzkT zr&l!O78Ddz_-7D9o>+^Io51moxDu!qv6?et8fin?f&V3IQ&!Q+dAAeva(L^C+QOn^ zE4I!{!kpf0D4jHx=+>>RS(z?{A!DXiO==DZNm{uwDP&UgK3`u@9mO19fYBYtM?+rG z646o834|d4k2+G{eO#Rs5;8&XPE{#H2E?5^Ud9p!10^IN9HVNI`VX=`aK zsw_;zcs^rO5_a^>aY+FIJZF+VUii~XI9N~=PhD(Fft_9}b@sxx#*1GpNC zWdSmy;C^}qaa5Ou`o5okNjLZQ+bc%4M@W~GWb$Owanx`+j&id25yJVNEM;0zDhAW7 z3oI}?6k~?W-}A=vVVHWeQk0`D6qU-H&J(bOvFe6&6Vr{dJ}D%-rX+kOQ7@ww&t5h= z)RS)F64HrI$cc%PF`e?!^^kD(7E)d`HPA#7!@KdOOEb6jnk%T+0&WY;#q0ddGqkQt z>y-)9w=x@10HuTB`E$z_CXVqXlrh{f(9^}~TV^PkQDvn@OXn=>Xwm9|`A4z87(90@ z7PO}gfRWe*Y&icXXNrU zSVxvzUh>5;VpKZ&8&42Wo}ZA};CT)Y$f3(jA-b?er=M80q^o*KERnEPfni5q4V{yp zSz7-tNiQFNvGe+)5sUC@YaEJQIHoo5>EalVQrMDbMNCh~A>uA7&*s%<^TTYi`%+^Q zK`-aeH@8mqUH>?V-e6n~y^t8iK%zU&bl#d#p{{wUC&1-QkJ5ZRFD=JA>-(YfH~-O4 z`k6&dggX`&N1#D_VXCQXul93uBJAawmT{q?&M&OmgZGY$GDvsCUe5&kstkC~Tn(TX#R9>D`?z zjQ)gts#~2FELb9!g^x3sP7P_N^KAFNFF(SZzGP_>?XO}(w-NraDhSid`kI5~dB*dC zmC4Dk%c-jm?Vl!?84Ve`uNRP&UQu_wz)sDmOArAtsR?=QUQi=e3}+l2o>7!Jx~8V) zBY$7|8cJ6i(n}{6GegMS-2|)C8dOR;MWh+`%$hZ8+r6_?OPUrGl$OAe9O_At)l*#) zTPLx^l$hSx-_oyS#>Ud!g6<>daEJfhqvzn~4XRqj4blG6yXHyrUq`44jD*+l56e1>TtU<-E7i{i&is%A`HpUu6x zxao1`jS%#l#fx3|nKYQ{RI?F)|K`}R0dssqK_!S>85`=HTr=1L?|Ecj32=if^p^ z2??$oi170#{ZY;&=RCJyFP_{j#f~@Km5#!0p3J#}{DXtm`1=RB_$9ce;95UeR30(g zl^#q>QaM_p_d9`ONRB_b@`FR>Rs2Cn(pFQ{7vwSOtQSv%yKUZOlbNBCmjck|iL*=JWKZECm8#0%a88w~EbmgWy z^mGI1LUri;rZZiEFJ*Hd!NkJ}HQo4JB#=AQ^tyD%7mUN8>#g6Ud~{}a8q z$1%HHJ437?z=1(?c~x7W#}TdOJjwX9gVq&A-tuwZ4i3{uTrpeJM-WJ63 z58?ElXxVnMBFo#Fh2#d%c_oe)r=90@a6UM!mw@Y~^-tl|8-lBK|)xi^0ZSsl_xTMNIE5KzDB=C&hbXQB5F}e*5UH zTVHR3>65l@O{(3v@9;j%D=U!0$4uPX8gKV3kBc6=&v!)t#`L)Gq$-Mr2|uStkpf?k z$pIm?7=?(`6bYqtysDk2(s2~q3|D1USMO5!XuxwJI@X4stZrYf%l4CZwb2?_kd2dhZC@N(CnRO%LWrd@~Lt+MbW#4va&XDz;62bAO-zhnrCbeT!stKv zfz}eyv(vJwkDp5IwB&TL`X;mrLes5kQY-bvRFdlI`pDH>7pXIK&{Bppbs&8`?iWyf z{(Ss*?1!cTx2Wl>{Q9t|68u0FpP!#cnrA|er}ON4mX30n<0C;)l%5x*#BAVPI9hF8 zIU8Za5c{y-&qPRyLPlUo;bmrp{uKA-fS#X!=#RO#TOb!qrG2+d(MRWyMmo_yv zHFjc6$8zZXPE3ML)|M!P+!1u?^dO)zRHx9?JXd7$JYhP!)N;JLqW{8+uNW=;zx`i} z7Bw9zj=?+RsZ4O^wA}W+e(uG7guQ(7>pxJ=dFaqNV!mmeIp^;PWjqJ;d3Yos_|nrp zKee%xCQ5znF#U1LZU6h(R9mXD!ohT>h%P$msO@QbDd{qaP|bwgou_2j|);I<72_QCB7ZYFDQ& zH>WO}t(p*Xmkf{0hD_zV*g39>-zAgUPq&2Bg!a@vY8w&TJs?avsCwaMhx{;<8!;V9 zNB`c?khvQvA2FYALJ}FM>9ZEEy62v4_sm)qv>4;AY?<{*n>RrpSzWMsIMqi^BsHB^GhiqWhEhXM#kdB(E0{B z$Q=VvKgrc|k5V7Ne=lN4ooRHW5?0q>rx-$R)aZy`asqZDLh*R*c@j#eXh4+i+<>pk zY@99Z=JY6Y1&t%j2{NNf`L9TezFZe3a^h~7+TFz;vkRIz35xQOVJJsV=Uj_~=3M$n zU$@kCEm1Y8fZQKSzjxbgCtL6uj(8Cs;}T5cQFjlf)x2F8ToMxeR{4YBB<8sIJ2`tf zd!)oxR>pEjES7k5B`vz;(inCDt|VuFKQ${OBCTdMx%i%I*7z^M)}+^Mqx3kz@y8b& zCV3G&$MK@BMrtx7A~!7FO6&^4Hk>INidiOTmes{#b#72QYTcn)NHZLgy7JDA{e?3v z2S}}cpv1h0(`7%As*cDFWfP0eF!Zmi7oH8#9^Z+g(@Ax_@B8rlLv!~-=?^_*2;D&X ze$Fj5-4HmS&UVG+EC>FC3P= zL#z&@&)vT^aR2`0yVkvIVqP$_yoE6Szypt*zEw?k_+CDhGabtdknZri7}pC;Nas?c zJAE?lbDZfGqB|fR%ZnhLN?D99V)u1r>%j9nEERo3OTTl(^x`|zjG8_v%zI{bR(LBu z7wjze(8-RZbV~p-vN7oyFE_Jz`(}NL`Wf1?BuybhKHIK1Q&5uT15q zstA^>g3yuWo7omda{1FwWyKGcBr0K0pdO$2japMCCKJKkHZ4A}tu}rT)5{eyVGgh| ziHyC2)Ry*kko}h&pEV<7>crNu6UxeFF5E(BPFPs4_o?P)(40L-dLJxfp5Z(Hor22a z>>C5ii(`+?3(^bJ{v0^Qi^Iv&{I~F?--DVyT-lk3)qEhHIC!M=CPL9`6DyqYeiEBb zw0I=~dr=FQEk(2qDiq3NeCd}9e8tM_qlZa(A&~KKQb}8UGQRYx+K$7>9`} ze(Suf0uOug)aVKOe2oD;Ze_r}=&8|0I)}}rjYlJzLtf12CNzWM`?zg7j*cC(58nYu z?(4e`doT!3s3_hU6T3Hc45)Ya)Ofm!)+Vip>xessrv>33%Zp$=J|twu#*me9aY-}i zotj*-IjJgOWe1_~{k+)Pf>Pze7ZlP>wIeR6cRQ{g`lK%Yi`4Ynf=6VeL+GEn+ZbqW)}wB@-G@isFHE-@9dS!HEHz!a{moTx+kD3z z#v#Khw_y5zN=;`Ie>_sYRn!0Yj@xcg)0bLz&7Q$tnGyN#*8S5rRamK$WlOg(d4F z57O=E7J;3=nlQUDzlhQ2mt+xws@*Vq<#@yI-L}m?x82DPb2_qdqha(c`T#Pl_P_b4(tn0^vh?*}KZ zUq6XA;`);}NM^ivqoTgOjyUwFyxcyJx^HI;xQm0LUzq;>Z{B_P{VM?ZrTY5Zy^Z;4 zImMJ&MrC#$_y?9=+baWjYJNf;g{8$2YRK758=vFd2}EHKpOQ|c9R~!um?*4SvOv|D zOF~1tb{-Acx1x8T0#^gJkoNj(mYV)fv2#1N8j?VG@(cXe`sz^Ep)RU0aW?0A<-20H zCsRWs0o!wFqX(s|=Vduux6mHrMT&J)PO*o2)Nmqf!-DisiU(6m={H2yUuxrm`j*7* z$Db6XGoC%Oh02u}yosR~r+ zOln$wX&S0|9}SM)rDN;)&aN(cQhFgHYWmgA(m5`DUw-__C)cW%dPc4;k9EIyji1eLiBpuF&vj&;vkVsWwzTzO ze6d9Yk6P@JM+`2b0wukvDJo+zwV9p?sJiWb9Ni!phQdhP6-sbaSz;RaIS`n@1~hJgDBYC7h0$>|N}GVAhOO9>6lObg=2eqwKauBt{KJ(783w;^iyxv61; zPlM6EC8lfW66d-X&xsSBBvNLmYV_kq1gX1MN)&mkOwp=C*MzFIER;_5tbc>EM@EKP zCs{*3E3>gj*|ad-o=HEC%7T=3`nbB2!|35N%HJKkkRsDTZ}$i{qAm@ggXk`j(oG{# zf%*uf2LtJhU}xlR+85kUcO!pymsO#(x-vtqJARztHNBy1xo$yARt2vL4x*=$i+_|C z-F*vcD!trtW9_so;#V>+*D2UJNPUJAaPzo1yV=X_K2epiDeh~Qp{5g_&SwWoAHnno zCO>gsD{?L>I*^WnElk%*YP$R`nA5>#>PMBE?zm4%x2Rpkq&LrX`{uaM8kB*;=PWf6 zyOea@zyQM)cv(YU6gXXKx*2McWcGl`0A6!zdO&HY6!VAH;&~CSb3uj+h82gNZd7vo zF|fZmLrq`)2&=*AYf0YRC8VcMuU%(qN99a6 z+PEZjo%jONdBspVVmghF?z(G8<)fC_#l*d^m=&!*+xJ7?&#MpV)S>Y3nNPGr=o5y< zwzlqy)|E+RzT6r+#J{n!No8Trc#mB-XV7#Dg{NzMoS0VQI2JL zF^GN_(!2)dby;H=guS#zPih@Iskx^N6`Y7g0KEzw9Zc^{>TRy-fX$0aP>Bqs(=?Ly zpOVgvI1Zy5ST`UGTJyYY9G5u3FFnn0vk;v-MY^WJCks%`4dV-Xt$THU9EG6xcBmNb z>18R~XCa<-x*PTObkrsm7J=yk;(<-5001BWNklp$KgtSTK%BL66vbaIm-M^8?Y% z;e@9(At?#dwR2_%&&xt%uCo+jpTbzZK*#^rzvjigi)mrhKg>abX&rF`i8Qyc*Y)E= zFRHA=3MT=*vLAG>94;&zE-Yy)8ZJpJ8m^=zX$zEIl1u=|oVSo5b?QXpwruX$;@tzAkBL4kHpg%dW(m6X3D^mU z5r^wGAwl~n4y2xx#1{fy_~tI%8!f>U*9?~C=@Ucdmu#9gZN>Iui5=6ZX^lUY+?L!M z5JLTE)%LjU+dJZuw};R)wx}R6d0JdjTw7sf8-}K$iVPa1*A?n2oF0-C7ss)IESJ9w z)ANL-z7~(?Oh@CkB=q~oYWc*cU2eNAX7e3m%|h;#)?R~5{-^G~ZT3VxW~Hdy9_T1c zl^y*c>rWE23)AzgPlkLhce`8HXHUOlyaSY_*pEyF4zkK>OXjxL`%j(URMW>gp84ih zmSs=o85pCp90wr2Rnz}G6<-pwQPB;?3ej~k+Vf}(>ekoY)0L#eKv9>Hu2ND-(iW$y z?GS9NcAxYjoume(MokCPtr}8Ca{5h9m#{8W4`07JD{STbC=BVdmo9U++hf3VS+R{V z9mmW35|d-TWfJoNVLH}yLfXM#GuR!=?BcjBKnBxI38~=RXzl3b4ocSxHH$|cY&tiw zWa790xzovH+_GhpQPPdw#U!coSJ4DBT9Gd`1?v^jND7SH>iWLP?1t5|w@hN=($aMr z`6gv>4#e)DlbshK0Q&*d1Q=UXkhti2i|*sf<7v$DF{pFcw-+c4uKmWnc z-}|z!y}q;*NJG5L<84mR6d;#(&20w?`6s{rx8HtoxvMzl5~HH+PH3sPL1 zQ)0{4$9lQtxjK2$kCe}brZ-4s>?KE$>;#LVROd? zH?X|uUD9z3Bc|g!de~t|7o=ODe&zI*Ht?K;+tZ5=-};dx?Rpz|TR zcLX8}m(k_u`61seKh7SSICCgF%e!m>IIXfxxzfeu!pUYJ9Igb_Zy9&C(p(AXH|ub( z;q`#9@zH=kXipBh)b!@VRCMA^M^$e=g@|3a{^)wr&p_o8q;$k|z*^}ih~5a|Lhl}B zwXiu%B(2SosYT{mfxD5#b(`zz=4olu4t6*6j^(Ad7w561gjZoPXS+nsU}6E^PlfeX z5zV(gk+^h;=!r!~kBZhypmcD2;8?se`>xR8Xz(iOG^f}~5;xk~;^Kh8_!&vQW8MmX zhT**hRm@vb@r4e(@@8fQnw#`CN0%);xW1&npnsV8M~_A6y3o$*CFms%Xu6SJTrhb0{a9b{*bwkgGQ!Wf`#>)4GYGeWkr z@5#r=eP>cdhoyaE@T^vC2i3Qe>rxvR5V$e9t+KloPTxcYL`N36lNEUt-Ib)pGw~?O zisLiVQCpk5*<;oS;{17+V&^-?A|KyhW3Y8|fsxMh6m8D98-4puyV+DAH)q&O?#|)X zpSb(B+vs|vF@D0lJMI`~k-rv=UmZCqTw4g|#%i;v+wK*=TeE|Ex7_it-CBBE4od@W zS>xL>Q^yK_@x`~8p7QS=`ybTwd;elJ-N?+wg>DJy7PaG3!JIxa9-gdRa)atz>PtQs zV|$SuMVJm88#&!KkPiyojf^X5!kCGoe>OCEj4`_i&ZVS_(ff2$wI+0wQPZ)yoNRh>52b}Uo&x7{PpTp5ji$?&5A9L? zVSXvbkhrDl8z%1x&yGn5SXP-Uy-g`fO_Q$_CbLI@d&iR+RJVg7YuCA1%6;(-zbqll$jLW}O z(#sdGMy4%jPic3heW+*7o|?ILtvglGgnYkuFKv0c$bV5Hc^`J4JRC5Mbxn0_Hk(M_ z)}goad|+6AIg3pRpghL@1b8q#h_Ko6@(^{Urn@;O*kXVD-qSyO;io_U>CfMMaegH; zkG=U_e$_Op$#vy`g%@R#q^{%chtoenPA8PHD@MGxp+Su;A5{f!f)_?_u-C~g4YYUL z0j3{E4L^UWS`!?+HJG+Z82Fe4ZBNsmr{3NLet4iht~Jj*WsDj zfOai4T`d0S2A_-uf9HH+-AmIbrOn^FH=nteYDRIoumY?c0 zI$FVpmjf0k=}wrunMUPBL=e^z;a+_<6iTO=*OZsYNpW?ikza0IooBC_T13g=VIB)BTA{m+8eFzltlVKxD{xQlAZ{(|k`g&(lALdGIikUKujl2 z2ItCs)PkC6fLTd*Vt#?3fnrC?Qmq8Tt2L6Q1)_8~T}BlniX)FxZp!!f=6-L#oZo9L zclt=mi+ScutJWxii3sO3I`p_;?=65+#(~;6&l%|fu9Vz|g&yDBB@}^t1m)BH6S~eH< zmZQbtcM-E&r-x}k$^ir3Qh8oX-%%M|l*WiP-EyZJYIppgVDV_^9P7FM(a7(zYbY>m zh{JsZFe0Ou%?v4<84x%G&ObB%?dR7`n(+3*u)wKP@qrs_IsmHC^SN|%NF5I6>=sZT zxf&f!*(l%%dB$xC3@mHz2?;SU0Hs#rkqh&QbfYl@#6=2Ak_yL#>EyHYCb1nh zW?n>Z+~*x}^dwC#!Nq~7uOULOJ$e*iZzJr5ke6E7a0U_MuMEZ=7&vyIcR)6Ef(()e zkCDC|?mIs4(}h`EK2?euM;^SrXOMJRCFNh3-mBS7&xLo^7tvmmwmnxJqCXRm^TKn@ zD)dcHCo6;I)X4wWzvAV+v%H!rhUqhki$}5P6cSZ5CDauZ6c$o6Q&C94B|Bf?h5w~3 zE-9;RQ(Q+I?-&N}{(|AGqyPl-Fr!DfOInFv7>VpTMNF0eVARatCP+MinEl4qsD0LTLpf>=BVo8 z_I&{SSP}iWiKD4J9KW)5bJDch_}JvhdxK*2k@0dRt!D9n)jYy37;= z^0!;Je8zBn+=v~=vBF<|vGbGHgwrke&wlOJYlN=~=nT%c|!of=Z2Uc#~> ziF_bCeH37-ZY63zO3KSY%-)FUa-eMSR%*JQeHu3lb>W_F>+`QrPRjk3k$kd{8; zzNY19L<%D|B_*m|*@%F;S0*ixU>))%5PZAN&T**ejZL<`%a_wBL#*z)+y$mnS9-nc z^5yU3QSgz5ewt6e_qrzJ=f{idkJGU7>ev03>fbf7jK|--ws&uW7i<4tKYOFO=gRMK z#Nc7?@4V4}V|e%j!qzn|oWD4D@wvC(d+~+$bo$v>?=f`7_n9+?&K~M34qvgNqotiD zMQ1OEUOs!-sOevP@y?EPJSVmV&aN0}4wl`uE2*h2%_+T0l-_mdGObQyC?T!Oqz!6a zMFG#0{Z$$N#3p_94sV1%Zw}KKfjR)C5OtMtk`)Q2Be;U;ISKw=tAG6V+pl1E`RPyJ zeDOJgBgN^}V0tykM4XPN2Yx|3H3>BA?EB)AKm3|1(yoX-a5^SvwIjux?&Fc5zCxre z3L+B{Y+aYXFhMVkXZvi3kIPo z?DU)l)S=zQ8FM^5G8UVv1uqyKDcuo30;BVuc<}O4$#GoLUQplO-BQ26uB9f-}Q zjPxXw&LH}wlrBZHW@VV3qL|cGN}9k2X-EE!)Sy-OEJjNgr<)4W`p)CWj$b>mqh62? zdrM3Q(|vfaFtY^RgJmW+KggNn7LAM`7K_fU3>L2JKBBxARg>Q15Wo#xZ*V`tWXU5< z(@Z8qyvH08a>pnV!Ot@|G#E%XluqV2&XHBLH^nUvrElN}OcPEX_OF3yfSzDC+vWK( z76+v2nE6_oN}g4Jb+&%xX8 z9>gOca*9Z$rf>6i@#E+QH~Eoh6*m(fNk1|-Y*YTTf?b_*D{Jg7ClV-}?&2IRxI`LP4B_Sp3Z{Gm&#*Ql67%6ytvuH&zPQeGyD)J^V)xZ4a% zPRHvat=DMkQhlkQ6gmsKxq_sw)gX1qTt# zh}l~oSjTOprjwg4NH?HvvHFPf1=|az7Z{!HNNd;0w_?Vf2G1>K=c?6J%0Rj(T|&A; zLw8)TzLr1i_(4%Z$`}i&k1=-ip$X#yPlxZCEJP11<75W6hQmhm4h zq_+%{HN+{M_(Oy20(CR~9iyo5dT%*-&pR(c1_44JW#02|FnJ|v|^ zd5q1?3m<={aQNvOdqK+uJoZ+TBXd9ilIO)}mkEpKm;o>NZ=j~%J3F(25JN01wNQG0 zWhEZG?z&R`gH@uL7ZeWLNrEYCq3?G=Nm5k@jf1j^$b-T4Qc$@$#C!Y385{SFz5@xJ ztaK_w<7ix!T$|WY6@9phD&;^VPT#Q23*!RFZSnOD2%oW~V`YFZjE(!;DCwAf1>{rr zNkqrkf~pReV|!7oi@MS@qnqPu-v_5pm_%JFTDoy2j~zdK^z_lUk6)Rb#iyvPDr6c{ zs}6oBRj*fVC)1rHA=79qTAP^6fsdr^oM_<0Vq7t`q}kM!QZz-zO-WlzVRCO0M@^_W zo#yhF`b6%n!Og-LzxuWbciiC}IYLODj(EbU_K_t=S!;5Q$hr=-+YY3O(dh#bSg+q<_mUkqbkUhZWvu^H076w+~Rb!b$D4Nr4wX& zF~e{=4UQ}e&Gc~!RX1K2qp0gfK-R(e;bEIA@w(7^aA}M^FOOsoswV9!A6<`%4W$#j zvN=3ZPbV+@80qD5ql?FlbS~xEXyWF=+->gDVi4V;boSw4^CE@mt#YIY(*^bt*d?dS z^Rw2Ianzx5Cqg5&I<>E_eP>@Wk>Ka@Z0$;O zxq7}+aofKk*F~kI{p}Ie)jNLn=D)nrgU$K5MEq1ALA+EJY@jUPUjZcknc`R>H_4z4U)-a2~d?Jv(RjhMYgv3Nez zj=DP&6OJn`4~285@fhT#m8K<-5|iVR_w?H@zWkckZN$^!FcOds+0IN1=489%*$Mjr(mwCo3H^I*j%S&2mdquaxUfL21xvcD`Pqedh1c0BL;E8v`-7~XJ!Reh% zo*7;3AAgc~ZO8q~QdURSL@nJGDqzEb#QTAv2VGZ!It`8Hc#@^gA9g6cu&~LwVX;Sp zi-$t~25M(A4j_XR&iaUZ$oRt4LIonohx~dK;ZM(cgKkUv7I2ZS3BFkZq~yc+=-R ziZ$JtBGl5l1ma`VKDIOnDSi(0tg2C?rqg+7H%*Q({N#h`#xrA4`Z15@Kfj`wP zfxe@>&m^YjQCqw$I3hyPqf*qTOrbk%@G9rD{ESuXnnE*=9FdZqDOz{v>bs2(o^+ag zdwEKEtiRjhr8#r>oN(-k;!ZUB95*Kl&?yw)cSM{nR9E_TT(&xb1&qY+X%UKNgHEU0#K^0(EjPjSgv9qT^Z)1I@~ zeH$^Ud2V1oaW#24WIM_MBXd+vZt(2bgEjL#b7Bj;XqP}WiYIUPz3PvVJ@jLxtwc!=S5^(DRUK5$%(jttuyx|Rj~LBbjhr{CNfjuTy% zt}a&B5QAFEC_qwU>c(%kP3K{Y6Sg(aulHmtKZ6e)^5Mk37gz zAf}V1_~0{^H{Dy&ics~C@w@=$($a6L=|Xg)r<*F$Z$s1Zyg=IGZDF{CbYZ)pbZSSL z@^HL@p?hyRS)EAD>fd7e&=7i)>O>8!6Z_Iy7QSVCD>aa1Wq|<@`SZ^|A2^9F>_ao( z3Yhsx0!)DG5>kaGaRaOhW7v%8}q7~(Vu{fRcZ$n;ak|aWBuqK=iTYtWAOZewF z9kzhw8r(;_P_%TN_io=lEx9BfR97WmywR3LuH>~q;qrnbrB|J*s!9^yo9#(T7muTZ z<8j{_{W^U@ue@&IuEF$ER(DV7@xplQ@JRVkd`HL1-T(~g*lv)ydwYAR_YB9t0-K-Tr{6sGd2e?ecNsS z;cl&zlD%c&`VsCnkFp<>OU4YMQ%0`pGNxqVmaG~FBj0+5M_50^fuGZ+{)6uwR%n0GRG%3LIA~qMLYe+I@uZ+NMN$gr` zcwJY(baS9UfNri>uhUTaEowTC7#9MhtEffJ7psaiSw;2YaHFRi-CWvvjeUI<0>8!S z=7Lp@W|`oZg<*2+>-pKOTasSvslk+_`M0;@dBL3?M0C0h?G1qS@}!CscdoQ_nO=xs zjEN~Yx_Q1mT00_V001BWNkl-)KJPGUW*k~_5Ar$Iwt%n0zL0Sb+EguR84&vaVyn`3s{>dvu zF~0e;&pxPBoK0Q&4$T4kt!8uZwpY9h?9MN_8&1{ zXowQ02dTo3H`YCvPZMZNzX*U>4)@Hwx?C?OegdWtv#x@kMisGq6;#B^ zkL1dmtIF75pDAbQlA0#d%hv@Bi&tH~7XQhYU^-DR2UA?AA@xg#FJtIZSqyFaEOvJa z<*0$n;yL!pf~GusH;PN8o!!Pc%>e{YcW0dk`-CdDgo^aeTh-F2WHzl!qOEIcQzdnNX9P>VDj6My{8H-nC1Z6mrMH5x(%yon3m|mdtBPUsvOLX)( zLDYAuE>-YuN=UK2ctk0rJ-A z{h!Eekb!4|wr)H;Z2sg)CG@ahLqmptP(o}$Y;G_|D11C+9130>$_FFIi$1-o_BEXD zX1X4M=y+c6mSGvOk;oP6{fKVu%DpDt#n{M#l=TIs_s*f$ziPBx1 z=?j8q1=~_wQwsAuXWPr8T$avu2@YLs=Gch$IXUWGs@_N(<8UQU)=7`gOL0$$tc*-u z;=d%wvc06GI{xMg5;44>lS>wdat&)cE?5Fb3g9gT-83L_i0LE~DnOA4MSLj_0^}ox za=|xWMo8Cn#|C%p`q6z4g6_8rvHF8QdeC&@6tUCDlyr5qGZl1eJi<4!IO;g4jhb#Q z0d9F;7;D%5iJJ+%m3*MR$VtZN>H7H`byp!#>`{^afFK9i9C3tZ{XKBv-A z+%34$L3LRBwKw+9l@gDkrmSqaRY7Xh^taYAN!j(hEa~cwBt{=eWR#pP9iA_%g!J@J zQ2L2YA9_IeP28db&>?i|>#ir}v5!y4awLqulQncQ9Y`Ivbo0nN?^joS1)|InTv;@_I@q__B=w{l_4(PwaS!0D#~dO}(S>e#K3 zw434QW{8|?MpNf(Jl`x?XDx-%Me@zf;o)Uffiu17FFClW7eo5itx(w;o457$ zt@~CS-nSw!WFx^UNgc_x9lg=}Rxt3Z;EM4LT!AH_%GbL#Yg3rvZUWIkE3r3JrE3#l zaVhBg2wkMnC_4Hilz7GLNl7=3baENlhLz_*k>KRJDIwjrFtLQTqH!U|5|34Z>WSns zlCBs(4HHW@ZTpyHF#D*Bttg03uFS2gtZnNqAf}gY2s}<70)p_?@%kR&#)~!7F zNArwZAM{7pWqN_piA)D%@6?T(Y>VebfPE*{7m9?nj>85nWnJ~7&^iJ)oUS1_#RY|& zZn799sPl0eH_-y+(RcIdGoWq|ozJ0~9O1*7;T=97uZug!z1?NU&P#dRWHHK^j^za( z%BF=2XUsHnf-yRmX~i%&J0o0|er?7r@Xqadge{UV37(r5#0-R?$p~ye;(9Tj8O!z} zIo-l^)8l9cL!!B4a@C7kL(D#ZHTHD&$TTW7mKpPkgaggj`3zU`El6h? zL#I+VS6Y|4;%Jr|m~O2LQmfC#?2Nhobol3Qyz6ahhf$L>X4poRmcm$^s)Z)gQeb^FnZk5})BBd)9}~H{CdFr2Xtm#t*qU-XX8mG?31X;r_Vmp3q%g9{j!D0u zvI$Au!@ogNx?2=mqAMwp-*Q$<4TjPqJeda&Jm{1fadyw+hhADbC#Ac6NmuBy*%{gp zuZjS5r`dqD56lCOKFip{uZarvw3D~P77^%O z==r3qBJw41CD8)O2~Rx6DaRGZfm$QgtLUei!3!;kwjxar)Zt?LYnUYec_ba)Ia(jVWsEb(<|-I{%}~0GG|N%qWlg7obh*TInbS}2e-Jg@ zk(w@7x&d|g97g|~&_+OggwsvVi%c(TALO0A6Gj(?Tcob@JEP2vu^Czb2Gz|);LMpb0|U2YA6!U+ zNmy9fsW2eY$k1U}%HicxGIRi;4)2TD+{oyym|f(9iN^6#Mq8tv&%Jvl`Eskb%zMU# zg_}ZThJez^PnWuW`0)0P(~v{saVS9BB5aUVU*cf`WuWs@2MALK__sEL;hZ>^9E}ME z3A*<{V$1QtxGPY74+Wxfsbhn|yDkV;S~^x_+%CxS3Ti>j*HiZ<*ItMV>7^egHfu9V z6vrq|FDl9|DvF=By|yKh{FRQY#|E^yQ@!eybgBcBI{4kw(S|OLtR5EvHLQF7`7#pT zkhfOy{v}PV@@)?JoW1LzyV0o++0*%}v%Guh&@?a%{SGIq8|l@n!B4kjli_pa!uB_;*6x)y3L z;n)D#>6K00H3fyq;bAN2Z#4bz;qiwto5XFWQxN}hH&R5p4{*ZjGHD#FjXv({8<(Ah zci&v~r4H0WZmwCOjELl@?E8Gh;**f#@uctbZN^$$<%=%wOI_(y2#b3W=BJLGi0^pv zXy1~WqU4T^Roh#-YYD(lZ0UGCDWqyzVoAr!+U~qu1oO7|w#vG~M2bZV>niAj)KZx^ zjK_+pNn+w~UK7oY+6u{0kB=iBCd^e?-~ToK8t;JE)gp6oI^RZ57v73&ElFL`=^|V) zFAQo<@}(QQIN^+@MJRzPmYnX(fj~jJ!E_=SwLw6C{4EWR(A2TO1WxiUI+*3Xa=zU& zf`YD5C{TE^alFvjsAhc;fSff$mhpwjGr};xOUqZ$r;)2Ivq~%bB=Xj<;N7~(IV)N( z%hJ(rF}(=yb!32{$Cv{N6Q|CUl5V+P)ZIwkNX6+#-?k8Zgw(UM*Ox~YiPJf4rcVPl zcG+IcSUG_$wob(HBJa(_kssf-*mnP5TQ0$Re!(gtO(Vb~FPB_8Ivd8g(-kLJd4pY~ zq|y+A_0%;|8BTbkq1q26oZ&{p8p& zL=a&*o|vl_E@Zu}@!b6R&prKP{;R%?rSxYn{@{l{{6~TMFAja@sY8bjJ;m9X%V)lM z_E{V-zk2O0?+XRjn+WQ`uT=iY?>~9J<@osRn z_`;_|roZsqnVoypGwH~YJ$r0jw!Q>1>izIDK=ouQ*L zuySuGj>?Pj@^F^m3A({s#dPtkzh+s}BVuxMBJdvP(j*pEXO=_`JB5%z*f&zs(9RbG z`QxB>_QVszbRsvOEA%|2Yy0%=xG9#RdcjiTa&r-RuHs#RY%Zoht%+k#K z%!EeuK-HGn2@Rc77)xcVs#9r=$~49!$33qyr98?bS8N^Z2UO!YkARdB)ZIPYyrSIT zbOAMLI+tp3WP;jJ^EpJK$^|!Pm6;06XT#~s)&y7khx$3ONCtOzN=S6T%iqO`bEn91 z4(Ak?mn)Bn9j2PsT|OGQYl`{PrH#Pp5mZD(aLgyiV|GqKOl+)e!GdKAaHspFdhwBQ za{M(wMmKgA<-6>nHx6(M>kLiZEVvIf9oGxrN`n!pbC<)> z!bU{p#;GoQ3*$!?rjID>ED@yBnpALZPYHyUjx#g{RKk0r1aF(v|aK z_*-Tdu5sMLqIKSLGwHD`FmlCM>v2vdqgfZa=k#sT%iO7xNOjpYW@so7n+tvxb*moR zI)SD~ESXsb#1r=dmU9XV2}s&9f1$1^54?FiT)c8H3>BTx`*{`Vh@iTPNQLO%p5u05 zAv(J_zNg1KtgNhu83EKDQs%wz0`72d`G1UHdUVzH?Hi9xo0fcRAijf`MgD|B;znG? z)WXaF0lQ-W_=d1g4IE&j==eSK58@mW2f;fNkM-_rmWu{c3=Z_(16L5LL0(y2dara~ zgOCUgtylE~AguRR?dz=_s67?Z3&DqF88pZEVv^GdPp7Bf(M>A@rp4F7=}LHEZ*(xS z196`QN!-FbKU}E9^&3SUHC%0HAa1f+CaolDUQ@!U(UW|~;Tg6tUKM{Jmm(PDerXok)6_i>U%Eg( zBqU%G%svUJo$c(C3prqtI=62fJ^J>5w#v#{j5bM$72VUO#X;M$p>ND4RFl0+ENbaa zq&I0{A$oayTVXd1R9mp@RM17XmZJf&r3po~wM8Xy+v7T>W!1)Q{7;x(MwsZoF8{K3 zKwK-KS<<;R9BR5zqTzJ>>2kgR=+h@ZJo-)%Fmy|cA!*z5fb_9eMx)G6xKb!Ro`mN` zjwxI(Q>TuZXE=HE!}F%{k<&>@FV^r4D>+ya?tPRRQvPSp_DP8(CfptirQ_~Y$_rM# zl`FR_T(~*RQqv{b%lFOG8y>exKn3Zy4C9E=isJNdA$`PxFU~iZjxuiqcq6Be(cfUg zUU0q`m(4;rohLR`qC#|IYT=Tc^rFbf`M7ZypgN$g^^gasVV^lxT0cWGiJNNrZEFf* z7cB8=CxJvUZwSJv4}v^kQhZQ;JS{A#Ct z(W_t1|LU2yt{|shfzyxaipKBXrz-_g7G(b8&p!L?ombDidgjOTUwrY!H{bjznEu0G z{_s~{y$7oQj`7q}PrW2m{{@ozS6`hzo&C-`pCPgH5K;)=KW^yzQf3nlaof(FJ74|k zp&xzknQs`iwa4g@%5d;Gq)wigxp9?$Wz82}UG#X&p)Q(k0!tnq$ey;`c49KjF$IKe zSJ%wk94LL!na}1^=K2AS*E2CpJL(&o?AQ0C#Mn~hSHNZ*jAI0f%5-&Jke+Ibit01r z>HqfYkG}c%izT5{KzfMbqin8ZVq;1s&6{?o)vHdBS9yg)4sKmh#dH@^?6oXP2`b?A zb52vdmiBi$DS88y9bcg7l{rhgH7e{kf%)sYd) zW_Pu>SA1Dn8JQ9_<($tsszKf7WVo>31?1{96@clnb}x6=99It{TVq`pX|j^$acZ69 z<8#jaoC<5*gE<7V`k?)tgO$0fwk;8*rv>@X+D3aI@>Vi3gy{q%ipy6K-g4p|ByieO zaBdcnr>-bQNdCmhMm#U|mzd0TzuVGMpT5A8)~rbA8ziH1)qt|-dnC!6%iX5R6n^Gj z_?$Xbm>;s9W36qN8j3#xR72HAWKK`xNCfV5I(%`EhzojGMdWu$%-IXyyiK4u7>nk|sq59wwE>jp=(Aly9<_ag_=}%H-*OptF3{1 zY++<LJ<4aPPXs?6cQ9T3lKHzuAEjW^O$lnJDw>c<>cVp(BMS%xO|`9JUXI5- zf%aF9Kg;r^>*Ppa5g&`B9a6ewelbuDd&`@ybBTeeCwv8>QiN(q$SRM=#h2mHY%Ts z@x9RPX#eTgjGAtdIzqf&0_Jp{lT8WJ4WzR=RitY_Oi0PK=g+8QIkRqoK zJ%ES~YBQknJMVg8{1Z~s`J&+wpl+buy4zCIttdvr=`6TYk8}K>)Mpf1I*1;IeqI(( zHgkyo3}ag{!uYa)-1I;px?yzKoI|nm7kX>J={>Czn|lY72QT0u5rLPTYVKJHgc?k@ z5?{CqpEpxQ+PoG-FYDpFtT)7$o=QC--jk%LW5mqLItEMk{Ez1U!G;c3y{^JO910yI zt4Jh2RfWJzMmd}3mU0S_#}ClDl;wk`qQP@!38HlFKLDMbO2pYhO)3d4*kG=75a@#X z&7<(9fa#QtVmy`#4-&)AS{5BXxUeH@aK?q&toSww=!GRmRYWRC=WKm)$kCEbI5!3e zh`cgz1$|%nF?e8P#6kS-9ZVcxGd)SYRa+<1uJ!r1co#2ZmtN$12vV%%fAf1WH0U9k0qQ5iM`O84(f63bSx?sp3 zPHZcpM;!urKLu8G3Gl?4nn`+51yB-4&DmW@w`|yq)5md&*IL>6p`|= zkTpu2Zp>8UC?e%>3z3XtrJvs$kqd-P5y#T{YY-A+%o+69VH%Z_& zm~JXpC4Os~U_rTzCDw3IySZ0Oj7+X8;`E2j%Tj8MUYxm``^_+0(xQ12r-p<><~$!y zxY?p_gmOf36OnGR)0Lpkg6#E?m6}30C|x{{@D8T0#PcFRw=6FcM@%obZ7Ybi1=(nD zWW#|1EG87nu1W4cK$vgeX%n9`0q%+P;*cr(+} zsd~wRhTX{N|MX8EJh?kRDvGW`1Td!WXn*qJKYjS&Kb;>wPC=y^@3w&Hb-C?z%m=*M zTZnpj|9Iq&-}}|CzW3Pv*A1O>M#PK3^!Kk^87O)Bv(LVKhrzCpyYuS7&)$3Sl{Ym6 z>Tmq;&0qfH#rNJ5k^c@+{m}1zcLqJ3|D$hz_8A4G-#q)}XWtzA{nrke{NxR#I~J_| z^67tj=!x&|+up&!Ol&R=Le~Y2=5UBmq}qAo#*MJn*5z-%y2zdvaVP?dv6_#1x~37b zlAo4P*RHpXQ0>yFygi4$^Sd+eEu8;B|M2zU4=N zI$e5rsJb(^-OJ796p^A-MwO99;OvN^veYvN*rrMR5-LftEObp-)%Y$2r0;*-n6|Sx z$I~OnOb zJPV)A(Qi^hmxab2jC{xQ{$)-nv9X1fHIu;+k7evm(#BO}J*^oEAT zbT&G1Vh8z=;&TJ(WWTU5!+2Ow(;@XH>{9ie7+&i8E9&#}(;GaPKv;|}VBc`g2XlH< zlT_^^_|+ffN&{hu6qzb{C1V5jp?fkEXO4<4rWc(bLHm~SedN(28#c)F0;c;pF*!}h zb;HF(oj84B&8urT7e!aAJXZ1Wqz5Z8^)#i*JQB5G!#M}%3-uW|c^uo;%{e}KgwmzB zxVhQ@X>!eRytrbifx(HZ%;E5cs|V@m6p+gILT^&3={e-ItJ0Ik1?cIvTtYGBav@_~ zk&N56g&JXAMi>?M^8UL(<4axatL?!N)N|V--Q6SHXU}o>EQZasL59S7Q>uz=Z(1wm zxMP+l<;5M(OM7{FY_%;lc!?`T%B~}(7aZny-32jQYPz^u^0_4S@#`j9(zljr+-EU5 z=dz?j?WP72dpVYK<9Pwr9b?3UZW-1M=4-Q-ur3ANF~0xcBf5d2uD+xU$lS=_Vs*2C zMbJHGh~cQ=gfa4EjOmu3PT-3&8NVwZI}hM{IcHRmiqH|>DL;k%mp}Af9{0VUsFe}N z;H-p~_g;Q&t)QG(NA)$5$EEDFS;9k&31%ed#YDZ74N>m7Yc4!)ARRGXz8AyjpF24H z6{Dm(~!>HmKPr%$yOy*qhJ=wx_T{YiQ)9egFU<07*naR6i+9xr+*4q}ym&_`-G5C(-hr+(qBOnISW2rOB6f_(J(5w`4Cg z-t@9C?;b*~lM8VQT<8gehbblP2^kD*R)-@iMIA;*LRX=uH6*p`c3E#=bo8VU?;iBg z9=tOl-W>~P5RnM%_a3e~j7)xj(3Ln`#kCTbQLklq5mjTd!LY4rRLSQD#Mq>~oI-Rq z)t91NjN)-s2;HyuUSVuMp4fIgiB6#cd~Jfew;WyQ9awcriaGo}sMm2|xL`1l+x%A;JTTA?+|Ku&k!>IDpb{4)U6|fG zcmP)q)uyd~12z3Nm!h@{xL%CY96ZNZm|@48UQw4@L2(h*?Zl$CX}G;RTDm(9ujn|I zOqhB%af}$*)r+(+IV4~#(dpB-*G}6`FnI?JTwAc2Cf0^TkE`NSHFZ+>N(1B*e5+Pw zZ4U6QG9F^M8+!{wE(C!)q&`;GbkoZSE#2H-CBUClH36xV@=@R&PG_5wd=Jmtx^?{4 ztz&A}*Vgic-QAhp(~@dAE)!onEv^>!E=lYzN$Ne;ru&$JZQLHOpadEkC91D#QCkU3 zn#fK^Oy?&(Eq>Fq+Dd!*4Cnvyy!;u2{l8=tICeBDf`oKSPnZ4-RU5dqXk8X{INm_7 zm{x9ZFr656$L;jo_nCaN3rj_&7+h31NN zNPx+OUc#O1hvV@MPInZeDx`5t;7V#oF}|1@Qpg)Si^I=ytD4RqtD|uG`lHD+pm>>H z6ybASfBp5l zo!zU?ocT^3&5%w4*tpH>uG@e7)yqKo&wmQ2zxjh72-bi2!#CfA)!+M!zMsGQ#hLfs zd;6=GU*=g)s=vG|Siow(iUO&7pizL`>>TZduv^TQn6EQqydHpYJX zqg`V^eP>ZqQ_fj;cuK;k8$H|e^Ce#ACS+#jDwi^|ZqIkloO$o%m*?Yc?QKLvhx=I56aMUE(;j}3_24N|Ki zx8Q2O)UTO~bT*RkEj7LHi|S>ej~|STEWUr4U;7vJUkcNs+-Vx*IS0gpfGY^8ue3MJ z333hc=LhX%qZBeHLJ&yWjXOc<7NrZ;5#h}(m(WrCP-CK^>=kJz(oO^c!ucF=@n5sb zIfzI^zQ*m8*Uf`-~fkH;I?>y9m?~zxg;wVt0xl4u%PDDoK}4 zFglShq^{30tw^2xC`iS7N67%wFPYgrJba=e%k6nFF77;?%WS4e?!{3Q(wLA(eiUq< zqJiMxDf|jchmW9|RG&Q_o)=qFSe{~UPYv>?mnl&jyL<80|Bom-&(2$aqVwia1)g3`Zl zp41eM>JEkj;Ss|nq8l0g7EV`-BYD#Sa8GFBPe0MS9xMaSU$Mk=<9m7K zkJNNyPnYH8^c#G?HdorYDE&@ooM8dE7SWV+GMm!^tujLL#_~cZDN}fAOzk(-^htPI zqQ_5~iBdijM*-qf>)1f=@u=xzhsa3?R526xiPE<$+`?7ww-J}4``k#%gX0qc5|4J9DQ3Z7o)4g>K3K5Sdb1de;$Utqq#RAuqP}eq>SYuD>o%) z;X#o%U1uFvfas+7qFUG*ytOPZ;I+DzVg)hUxg~`oWK)$XySmy3u_@|755yg-y>jJv zTidj0$37v&BaU=))O2k{+aQh+wLJ-7r(*O}2$qWp6W9f0R*BzItkej#B&hW0psedQQEEG1Qg13HOT93$BspXZs`lM? zkKZ>bV0%a0#*Smun9APguJjJXV!n@gV0iN8nZAluoH}ljB3ulm`w{_z z{%Ho3g&OKRiGvdI%79nCRVaITP7(E4o|qKK&a=CGCvVIqd66A!V@A?4z~P&c8im=D+ZeBu#^gk@)QdvA{tMIp zTAw{5rHjJF($bxU>4Y${L?;G>i?>`dx)|3Wxg|i0kmc|oN!>VGMvunzLbD@28_4Na zQS!K{bU2ctedpa1r~Z+cj@N3EYDhQJht$r$Z3?}jA`2oN#&o5;P(EtJZ4BxmV~MWO z)366dLr1n2pR0=0_*=Mcak+Lkg9t}Q0 zK}(jT=QrJun*L88oNT(jD6em4)E+y*>3;{gGtOV6Ql9RVo$tQe-Cf^K;0s?7#a&;} zfb<`F-}==LAN%2BzxvfTg`d3t5C8B!t&V>G```R`+LP|xyQ42<=b}T!#V{`cdkG0n z?lFtLIQnnD`bv#HX(IGf+I=Fczw$%AFvGk^NF#|aKlusy3rcBx@2iEUPj?I;rXTpw z!RcVR%0y9h2rb}`F9gpL{stcqvJanUGJ!4o@y8DxidgjaW8Z&7n7%vetnxaLsOi0$ z2Hxf7<4td*IZs_?f=6cFlV?7A;pLxv`t&eSG5y`cEfo=G4;?xiQEGbL)(ESE%L~bCePq%)bw0WG}KjV{0a8+m~ysjN2e(L zzc)7S>?#KNa%^r(mIV7L!y_}zH8TOfgjYg(@PY+0a72&??}>8-v&)nX*flczDN>wL z-L<##3QbH;He{?>@-h95UJczg`|;KG)lsua{cDen?fw!>Kj;2Zail#bN?Gal>l_tm zqCF6bGjln2HRvhMDUNU_GhR?W2RWSvK%C7%Ro9JCp`&sm%gft?Gwnnm=HoLzl9ryn zVAYygYm7ggY(^X}(#=Y~W<0$VVR!(=BTnT2^T6E81?b*h^vv`lciQPaiJ?({x# zcXD#KDSQ*>IneI!KZ;C7f0s~tk!}lhbsI(4i`u=8@|m;PGlv3!6nmcio$|=al$;c7 z>0*7nP)wq9q=PC_v+>|5cwTsxQRMLe>CQ@l;a>Lw1pmF2?ZK&jOZ=ETj$r!3w4Q9W zT-}DK9cN(m_+1mNuAW8*mz*w7y0N^#=%l}>*UtkC8s6W^>7sN_guf8~BEJ82lQO($ zD9}YG3#rl3Ey5O&OH4P5M;0ldg?JWy3(}>b-=d}~?S&-<)5YTsNXPXeyNmI%ulp_- zFH^eg=x6>OQvU@hjBmgE+Apo(bx?i({xY>ng3_rYea!^DkoxlJX@Xu%1*rk`=hcJs zk<(UYy5&u`0vV;HfBFh`7e~yCWqC0(VT!?3FxP>0YBq_AR&(&7Kz-te7%;lQ;~BIk zGebD+z<<##n-(6;-jX$=Z5X$U1{pDfwHG>u3l0Qy=)VI8UIzyTN(u_zDatC4>4iNM zz9ZDL9gYw*|4r0%=PXETzuJ|8xosu26pKzAef!pNlo?dbh@*-WA1H5LTT5ItwioD}gEVO3GN^lZga;_Z zMMm{NUn0_pO5Z1IIvtB}rjL_nL7tc@rMxsxn1B^sa=ZL7+#~OTx{`7^bvl%O`_}PT zY)Y6?b!_BEcWhc>MSeNcwPd2v!Se#jNjo|azL3%Fg@nHpb(h3*Xh5m>NpYKNyS4wd zwJb@VmYmpKSy)pWkoRAhKEinayDulJK2&KgmgU95bRjL@*hC%{=!({Htr+~3a1Pfx zWbAop>A2G;0>nl!r-*cnalKf^blG0;Yb!=(^yqox6XdF0q5Lfu4!)_Lob1Y1IB&N zB0ZRl7gInw@utsx-dI{33AY96Tu34xDGycDi_GbcX@*N)?r`o;)b#92bsN3F4?)}ww74`2KzPB*UGn=toA2}To6;(D>h#q-CHV>adt zj|T;phYoe^+(B*Q`&a((&|@(ASMR;^cwb#5PC`sCzj^;Rv?T3{s7_BO874O!{ThQW zks0Yb_U`@SqhJ5qzkUU%i`0Mq^EZ*wC9GTHAAkPyfBeCVFMdic%-e|RpAPCzE?Tf~dK~>8+sn>Fi}rL?rye;1fO=BD8_F9yDrmuyCH*MjSHHe= zqVMuq8XHNQr^7uqhMWYYgGhz7De5oSg~%D3P5bDILmkbTsB;(ppd|~^(@*px$e-`e zuU@jIy5^fth=5%7lKo)h!N*@(wkAEjy}g`}0Ok=J8m=SB6i_^x*JLkmA|&0}$uB*X zoEmVG=ow($&rhT&EnQX@&bZKk4kPGy4@&Wz^SKw6s)IRJ7D(IyYqEagomj z9i5DoBaf2aas+>Q!x4kvP&%B>O%_o)I%m#q4=gqHd+YPbU%?SGGH}BfOxOBHnxepT zKWEpJykL5G5%8kV`;>EM=bSqSj!P$(pnjwQP}gq;(;+?q9;COAY)!TomBt!{UJG%( z%<;*I#Zywgx{v<8tNepfsTIK1&!F~}W?1Hpg3Y;3$|-_;b5}QvH%`Q+ z%QWK`JWKX;{|F~29f{q=-zO)^hqB`+`@vWzrpoJMJ?S*MILMjaw(67Y=H!lx-Gz)y z_?#zjG3FOd2vF96bT;qlRGzYUN$-T7a{|-hapQHdK>c}h9n1Rj$m~Wnr<y2)iJll4WAUiR8A33^$+_L-NTIlcdp2j-5b>8Iz)^D=b$<6~t=>4dxp%=t$Z7}&g)i<#ih(8P&Q`UK+9HALv)7NbM#E1zB%{!F-cSy@%b z{7qpUiFA>vjl0khh8#T@(tK)Wb69k9INgJ0VyupCeFP&m#W)T*U0H-i9LIajAJIY5 z5l?yd%&eN!6Btqzptg_1A|`FW(((E!HKeIZO0K16=mGpKBb*M#_9BOKp&=rcWt~e< z-Yfyrn`ulld<+Qh?LEdoSM7lGjhJpQo}CF93@0!hQYW^NHk4cFP1#dL(P>CWN7jtZ zSy{CuMPl@}?6#~ya9YiV;tog=&Q3hqc5G0-MxKzxfVvI~AmyX2-`vTNQ(>pVRwAUc zEnK2m^J_0~v{icg;K1O8fi`sN5Ivm#BBZ@Q?!yHI9M3A0)UFNTs38TOZ<$_3{=fbe zFYk4lLAxKa70F<T)Td zl}Ari+jk4oA#(5>=Q_AO);G{3?CQ`C4HgQvO5#^*M==^Q9S;-v>+Y0hHXwXtr)RIky(!yAh z8;@@H{4a0%U+c3cHC>^L(wZ5Z4(fKBVqGIR&fBSFc7-Htk1I zsaNvXkH(3ULn3_nDFq!#ot`i7r?4d=mjmPsOxShy_>Hx86ZN7f#=2Nx zY;i<{J1|KiOf{V+6OZ$^jS|v-`rv~b_Dm8@+)~@?_vSWTC+kIn*z@D>ch(QL9ly5s z@{%rFdml=1{ktj|J@wYF{`G~Y-!WV4D>!}yyZZ0nfB(|nB@t&M7J%t{+Z*@Rx95w~ zOF^*uFFyYDzyA7P`TFXsfBg9iKNp_U_7hzla#st`pTGGp7ccUBgM>H^UNp9r4?iS` z{a?iCH#PMGlnH$}sIE!F!#57TbG^d8C@PAy$$ZiQ-J+sm78Oq^{;~JE2ljtBr!O^qu1wg>{`+ zaO!Sjh&;!=A=fkQE^VoO>3&ofp3C{-_ zHH$dkxa0EKF88zq+T6P(xVe(q=;TSsA?9c3*-vEV?Cgna0s~BYpDPV8DQa|a2?}0t zf&}tQ?_Rz7erIFpk|j$bYL0^GYnHvVsPcN{^(jl&ELpOn{aQ^om`<8W69rNnNqDEp z(=*D$4ePsWTKbN3FrDKpfI9MU#1gy|YI*PAb7O>&YkhW1Y(#l%WqB^yD9GZVdIQG~ zW^G&JhnarWte~{01{^Q+A5ABQ9P`TwsQlzfFg;`OvTgS(Fz2^TDPvvHM~0_nU3W+Y@X`|#wkY{HT2h|4Ae z0pCiPVWWV$XCz8@Wn^EqpWBjEtI`P0BnnZUck^~x@7O3yPG_4Nk} zB&h2QMmL%|TDf8u8KAm+=|)VKyW9eJF}lh|ttiIF44>-^Qs2*o!EvLeL)Zd#Q97K? z9e7_J`sItyop}x&U9R+B5EUgUT_vLoIwZ+h{+e1F@g=wVT4K}ZzVYeHi0lvUT07!- zDI0o_czLMZM7%g`FEXebdpZ}8IzcZ0x)5Eb)5~|^W-(viUYLSX7+ojCbJLggiSMs_ zen0&%pYeW%XqD$3?sbdPZ>s5mLqp9%K--0Z%3*vr+8@O9tAnRHhLLkt+t*Xrs<{St5XydFkT`nw_HW=# z-{z8BGTdJQr}M*Y>#l1e!6kM$k$!jGvE3~)p%=8M_Y}Smg)z2Ze2OokMQLS$Jri25 zBzZn-Q^3U0TlXa=uh_R;jb68Rbns47$FQ*qv3yb$Sj2Z=0D*_$aUlVL+_2I(KqgZ| z>S!w}w!(RiYhmAnsfg|j0@QWnhavQeChn4qMg-Hz4{yZ}KPHaesbt*ag-0__%qEj2 zHnk#oI|g+Q0nl7k7sK7%Ek*6IiAmFrmBdeLBQ3qKZBVbJpsuc3MONwvrSqYqFGR?~)!E)53oB#DHFNifiL9vA2D@&x@|kuX#EdHC=K#584E%hfP%hDbUZEME-A+UY6PqmZt>! z<)$uxOZit%wqKC59{@;tixY>_-A6@Ck?Vz8PpUoXgkHPxXe?TK9_=^DVvR*k2hyhi z=~F_ht5ahs#%@859u}uxym))%C8zxsafv~SKV`p!#JBC6f}BHFtZ^MW<~(up*B0Fh$CJfTtgwbb-9^4IrX25hbI zuOI#EH}C!9S1=E@ih8Ldqhp)Uizw(AcZ2CJnNLPe?1hYm|o>y9FYC^78ACcz-iFgpW zSd0xJ)kcfSVBjh9@{TV)`RETHee~t!vk_5VWWi)+dgZ{5Pl5ue zyUtR}NUjXo_JqL@=aQ3`OLTjmlONUwh|JxYDHb|?ZXQk~wC+&^j#Ze~fB*m>07*na zRKVzsmo9Y@8Fs#NchKb}ONxz}etFqTM=E3AdFLFJo(t02W4p`kURbdy9PKY?db}wz zrD4uu7dMjG>C!284xb4?9ZE;8Cv3z;(*ixEiF)ziFv09)que7RR`-?DLW$~4eBews z$UXF*wT8a4sX=R21z|#2e9tP}D0@Ze^f21pXgVHkKuo{?9z`Z9F#Y7E#uL1Q{d_j^ z>$~eRXb07B&V2(BI9AvSpv@9UdJfJP3#moOBV*2^8|EzLUE9l((9;O0w!XmghSE&> z9${a{qJo;9pPuUB#-yujRJDQhb7!BT5LOa8tFlR{>6w%Z6L`rqg?B!Wi3g7rq#u#h zMl9bz$%Ga{>5rZ}H>aT~*3(wrSG{bBTN*-lCK-!(oJ8p^O0dNF&Q)PEC)ImS3HJ0N z=Nu(nw2qCP3%S!rt>R~2?LRBje|E5w>$1>MyyH&rzh~6?gC4Wp%gg=RV{@EGtqNMe zCy|3HP98X)a>z>OPzQ!|De8I>av!KVju)hKtI!nhw2DgaGfCpsw+)KV6FY_eJA?xya3(QkItR@*z(67`ko0+H{AaG zT+&|@=ORwmw<<>gb#9pcqp!V;l1{V>l>QmEm(Nr>3Z?&Yt)-<4wTo6zm}gGK4YVDjAJH+h7L;zdS~-m~ zY0nfwu_?GrqshTA($hD__3qnOmE@hYg<8Xw?0DkN5(h&pYNp@lRalfFNHQ4@oa&IF zk!|vV*dn#0W{30w_01W{jx&;v#&4dHl{}-PqjvB@8-X~-^it{5QPOsOcx5s-*lRY# zrUpueD-YU>ls}_NR8nLH2bgqF7<(%EZvct+yA%~w(#EK=2(x}$GU7f1%-etA>{?9OS95pbR$rT z`nY{~V{pr$myVx)_f|?s=WQ=3sKhXzd@QM>TPixrc|~qf()QYt+M~5ab*7II&6+An zm@Ka)pdS}HF*ODK%1Ljd{*~927+XR2ko>k9mEHBdYH3>0~6-gTxxjDBmefmV-FrLhWGAiyxhVvN!xhh`19ptEk>kDUO zJ-vE9c`z$6yO#)$b?g$q_Po^mSUfMNw9ZbXahu2qS6j-? z2uv^Twv8R-j(?#hrz0{Gol1D5Cu8eA0tDmioXs2qD7M|c0_H@PvO-+0Erbfib z0CD}|APtTvEd}47wjZgyIDj{~UHyzq;hazH71!GexJ~36KS1(<{ z9PLJ(A5rZfazdI%g!?(e>2&Y>=%0W6&;Kk`r~2~CZ~pbS@cNhZH~Pg3Z~pYBRF#U; z|7d*pIfDDoU!c(RbBzlZ&)>Ll{raLkPufok7aP(N+S~IX#Ky*Y{(9x?S#aJTi%);hUwNa6 z0?7LQ{%%wOvdBGh^1L!hSqGkNScKe3N6abaeG8>3GtW&OrM$YTFT?3{Ir_4_-QJYh zhZVt%Y(q7dN^4kkLY5c#%KP^Ab@`>0xP~DNPUra$)S*s6I?6irjkHC|DUZ3|eSJZBth2;)Z0(9j z%*@Qd<+5r4n2zmb@jU>vJTE~Q)3LamG^gDe_sqHHUc_`BViMCEPh9Hk?(aXINWgw> z>0)@?!~I+ihZwNp967T4h#_(~o#d4U(YMBa4(b7TYIT-{#?#(YHRh^rTafDzN zJBTfye)PzmCeO6=d?#0CG{sDb^k%{8FHPAKh2_O4<1(;Ed6p8~2&OBa9wQWCFV+^H z)JElcp=s(7M=GNdXXc!>5#Z69a)`Dq_|y(gu$IX9U{NWm{`U`_ab!eGs!PhlaA==B6LIQrj(R3 zvrz@Tj11L~QZb6(#i6Df{ap4JB{S-VXqyBVL+_$=>FKEH0`QRTE-n4-msujqi{$jvYspbx z{>WMs@%>bg?t0|(+l~s-GOX!OtSkHUb12=!F%l>xEgeobr0(E!OH5ZBm%Rm|>!8IGlP9CNo35k==|_@Yh(#wZ5pQ}K z6{K^UeTRH~X=6kIlZ10`#2g2t1MQ43zMsx|Mi}qCvbJOz$>Jr2w4O|Ciwj6>y` z)p4N(?KCm5}r{V&F>u;~~!OAdQ@M@^Rb4!U6-B5X2?VNKWqP-AE#L z5tb0R6`t)i01RLQ>Zh(sQa7M1N(OEDHpC1fL-Aep9RSTo5+!8Z?L1M>+EQEDUQxNJ0 z1`~%59xN!j&_N8m<}=u7uAb5xcdB{o-#|^j&AFtF40L;C?dDos=Z%?lO%*Lgg^8H9 zNi(RZ%csLpAuWOuk4=+6p4bMhUns&61KNYUsOkkpwMFq&TPFrojbY})&-NJosCfCw zi3N#C`^JUDZQe+{iwYtF=_o~*5Y8up&!KdN@uG{;tr}AK)6v}ld2u>m9*vBSUm4nL0@r8+n6^R>PPfBEG;}e-*a3}y{dN;=k zT9R>9wH>P^Ih{-!ni~~W*o(-6sU*;b7n>ZvY2)^!M?g|BvCw!ri7di&tGkgtO%sS@)V)Nm<9Z2z&CMsy zB6VNyBBEYa77_JAP=Z%v&HD9d>C}%BqC)v7fBfKO@35JeUWDmJ_O{N1>1ODPMd@0i zvQgc^&X_YHx(*F6OW=j*owHe^!cQNEoX*_9F}S(~HJwECZy{ZRI+zZ+ zCui4GW}~E|z616c*~2EVJ%&=<9jB3>;nK*}GN-51rKZ|*gA(L#!07BOYdY>`$_3p? zO)qYbO{o*7=eFBx!?ROzX>ODvr+OZ-A5%t+3JrFz4(>u3Zs)L6OLu4IaOW_X{!bS_ zxKUTXBi)@|Hy));{TBzZg$vX#UihHt#=t=T-gd91OP7B0^>1WMfB(wW&PE$f^+UzX z0lezkcXWTEaIUMJO^qir6Z~wnIZtWA6>o!MaFXOxR@(lB8NUV8|M~Le%U^u_(QiNc z_@i&meDlJaKfs#)^B?^1U;e!leGp84;pZ=q4)f-lB%5Dv>TlY84guTlrLvpSAVhmn zI^p9{DT@|8d4~9N3Q~Wv_OZvl`@OHuEIJee`Qdv3Q?Vz+MCH|GHbV4KPd@h??EjBn zz4+BPH3gN!orJ~j-3z9-v{mNuCemprFE^#Vk1jK?wc19xp9R9PjW|Qox$OxF5fNR? zI{uAR#!q6=^y%Naqq=$x&U7D--5KfiGNxa>(%IhLm!D8ddWw@%L_{^sN$FWhCJ4!p zw7OXmis=LbbfM~$>_jJmS@I$x&W>8MYWJni|E}^_%AYzLH>53D;&-I*n@>Laq&;}) zk?WO}2b*TCq4HP9M=+O=@4{d1ih{g`IX-jTF}4T0qSU6Q`(e-FW1#}$)YNL;0AlsA zZdiIcsxW1YF0&(6+qcb*ERRJ($8N4JMY~~jF#R5ZI>XsT#`INuomgdpU$D5C&ZHYQ z!0D2vd5E#RoM@yE7N4h<3Mx?vK7Z7wfy!GBOi=NV8ATd8m7(b9fH&hDHJ%MJz!0{A z1xAS7kda@fp?o468&JceG8d%pPyqhUzUt6wSzdfNJ4eWiDE-kR zY(^{bYXGG{TEAh$bU@uBlV|5nYilRXDm<6kCN=N~x!}(|IwvP**0yc8-Mh>mU%o#b zkI=XYoM#>*LN^IH4w8nQO>`nUI<6Qeg3%QSgD-_vq`@w0NObh~U$c1jw)@xk)A=ZP z@v_NUOb#** zCAWv%qTu9CU!*lU1A!~SGq>1X4dQqRZK`=151FH;)1&upPxZV%ziVML``P>d+Rtn6 zJv00M@84Rib*@R1-#)iWyE zk2a=~(+!{_qw6g)-gM?sbZeq_l2^#=kbo(P!-h^t>@SOqyX)J4yk~JbIprqZT*eo} z)FAs4B6ao;lI&u%bW=f!BOPjg@lLS10dSpV4dZ%|oc?oA-Nocw*KqwEHQi-R$NnPM zi?O;u)xukP8Nz`ke|=f1sN! z3{PN97g`I`%|Q>NOG=mP7oqpmP_0Le4`gjGr5*{Y3ju4t)aP>JL5n+Bq<85x^Eo3#I7}xzrsK;{4<0Lb9q5 z1%`=|k&q5$!_1rmH%n+Y!$A5L!{Kth>_3a_u6&tsl}(sl8nL`1%74YR;cXrd%5Hm* z70{@5r2hNkme7FbETxZep^x<4GAPcO6~B1lB4;F8JF8=I!6V<_?o=xbBynaAmY8nc zy{t20d0o?l&F}!?&VqTti^ycma&}{S$-?kK+zEB9)o00*$uDs>*-Oqk&WY18xSTtS zZa1m~U(9|J=SWbbb4%s^N?x_Uhd2E(x2)+} z99w9Qk8g}`!u~>o)+X>5lZ?_O`C}7H{(S$wPrZ(G{yNj0#%`(vx*crUpsP@5(893k zLH!<}kLZ9(w%SZ*Y8HyJY0T$}Mu*lhDagqpF&(=CR|_RHof=Zk2F*ER5ZN$N(!sEG zgF**9NL3+)f$JOuyEHLxY$WWZP1!tTq*uok6$Lkx1P9y8n%h(bOJ;h04ch}27d2ws zDIo-&uB6wo$5a$F;e26(K|%bYqG?6brcDbCwh#M1YI+aj{jWYYnC=2`ib=s+xK`S^ z#picGU5xwCgT3$RWBlPJa9oCN*|9~(jHkuL(%buJ>SsJJk7%>ZBW!ii#Xq_CK~sJV zrb|wjo{sBf?)L zO7FpR5xT-^fb}2bblF~z)6vuor)!P$P#xeh8_IBK`W!7*=%SI+Emk+K7lY|klWts< zB}8`(CK5>WKQKB=J#XD)GA8rgs&bkG#?<7vspWkdQnowC;xL<6j17^|mYsr>&Mqex z)63i%S{;$km=m3w-JjMrgf>>uD^o?L&E*YEjr15L8XemUK>l5Q?Xu+7P0`1EHV>|= zyYAw2QeeKje(rP^ZPv^8wkUE@Jbvxk-rBs*)=gK6b82epeDczo?VnvEMtAR}ef!Gm zaypl%yg-n5F2Rx64`PB=bUijl@-+ue`2mb`4 z|I=@N^Rr2C`sH){y!7O|oO}CC#xLId@MrIAdw1e50m-^d>>9RgU&Qw2g&4 zCgwf_av?fKmPzkVnl$O>!{6IBc6Dyv9@1F`D-N5UF%-yVX4cizpWL_Tl#{Ysu!a#a;#`ati^r7LT1fY=|M{wDTH^Rl$MI(+VKwpJUPFQTFnGD!|` zi}FKOB^v}NQ#UR|QiN7K6twDTjY!5lq5@gA)t>%lFE4t!rKW#&;i`N1=JJZ~PTuZC zNoPIT?-YF2^CD+3QOJ+Rp5f6y(Z?gv-Iv+LGV)4TC7Jrj=>Y*zZc(XTbh#9!Go-5H zd6}F&D`Qx%p?ar;kZbbEAABh8LUJ6Jk2W20K^pgt*OZC?m++=_NHi zH9a+526gIUcXD$xq^GZZ)_Np*Fx-fcZyNU%d;2%+-|cc4}I+6$sRs# ze12Tt1`1@fyexpanhm*xZ(J%bKJhq#F1wz1oFqoF)s^xhIUVI3!wY_Od1d5+5!lP! zZnizInh(<9cbtLi>XR=R92REwgf%aX3XMhbdyiR-eZlkXyHIxR>wpmAyG zPq^rRaL|bJYSyH|tH*1pn8v#w0_E?zGr0Cr>z&$ie%_$- z;|8Fm4>*4wzYCI)eibxWh(tHnNfwcF@VZ0}K}}x*q)*ryN@g9-&G`lMp&NTcmeWrA z8sMm+WWu2b$L$}ja(eK5jw?C+yb+rr>kVkd@V0^(p;}lQDWz&&chevJhw^9QA7CiG9=Gp7Pfayu+ns_?Fjz!fa4(Hi!$2o`NY_;QD ze9}3L?~Zd7C8N(ajVeK3KS%u)BK_H>`LpJiFga1SBu}-H7N@xDvF-HzdqAQ$Z)16R z!S(sLxoJaMpV3u7m`fY{ig&v_PlpxMj>X53-hvl~Oca90QK=iy-sy!za=HZdxXP!V z8aItfV03qRkJuLBbQWR*ml<8Y6^?=;r%zX9LXaz05t-aoDk`B9Oz(3KF)k1lWu^oA zZNV3#bJqp2?S~*nQqx02{iiSVAMm(f?)k^p?as|;ayDIWIM--ziVwCI#y1u;Eex)X zuP(C($H%7TRA8+qIIWHR_rkfsMGNB=VOqz$qo=_ZkSr!91;lUy>Fa`$LMuaq7LQ7F z{j2nV&i^_7U-k-EQ7*id2FL}nvZbS=Tl%vu5a@D8uYXH_JM<7IdVEf=fo%%z-~1G|$95c*~p4x!gv2HxJ#Qx+WUj zj2T9sA=;Gb8hjm_%$LRVE|T*_X|FCd9WkB7QDv`%@#rl1J#v6#d0rGI46KmDzrgg2 zS+mNbh>aT)n3JR0Q4NKrL!opyFOITddhvE^jzwwBm72bLbbKuB8fn-_!~0^K&s=(ldAd8IRlu0NTjuySh$88U8O_>|x*T1*8})CrcE;Z6@($_r>vPaI%+^IoIHlRo*) z>F=2H_$DX2AKPgE?81fE!HFyD`EI`LK4wo1Ximo`Q957oKsF6EvweI#=xmRJ*;7Ur z5M4 z)9Fk)BN!|6S~mjx?V(w)e{blG$$Td1pTXe%9Dnh1j*JH{u@&ojXft30Kg zeml{+#oG(WG|%*LC((v_S+sP)GM1IiKAAae9Ke}w@iymbVZj3TQW;cqyUjau{l=u{ zQC(nb?(9`n)oUQr4g5&QvT?5H`eyw*Go#6Q5eTR2?epX$y-0O&&oFCSu#+S1!8l>U zeR9&5QvCVwlthAZz-2;rAaCpaF>@LrG_M#vNCog*MyF6ODoF9Wcu9JP(j};e%*H)4 zMJvzJF;V3HWy~-C}LyO{f2;kWo?TR=kV)jsogJbs*hXUQpGg zrDI*k`eK+}pl&QPRxzoGd=aCwgXKZ;M=e{rX+7$~^gEOer_1MJk-A`A(z+$5L+4ms zbfDHolO~NAFHWB{{_xv7&M=YQLF($OhsVqM!r92^1gZ}=ysrL7!!gE~3`QC${OahJ z{A0g_q)zFmT9I-SwKG!WB90d6>WWP#F5MVkIL5m!!Ts?1C!d(ZHB1XqIvruZw>&TS zUW_*#K=0YHV1YV%x*+}V!4)IPMgI#&=!v`UHIz=I zI#+r6r@ET1+@q%d2u7#9(Ro@po*zfU^+=R-$>)a6>3B2*iqen8Xd)OnA5iyy?d*gl z6E03)5fty(UAX((Rjb75lo3`JRus%_Dr~B#aJ2W`;_tNNbinzCVR88Q6P@6C5vhP=nRFBA{ROxS=Bhf!C_H7{5o#j^OY8zL+C7s(-G3Gf>K#UfZXSy z`7Q13TgJ7wk9)n{**-1_%-+!0D7QCVjevNm@`C}Kg$PgT(%F%OZ-^?{6=IaqKZ*YFag{n~{DE1xZ*|Iw-}!4H-IwIX%7JBLAYcnKMf<4r)0t) z1%5pA{8LY@EAgw5$-IdkMr^=PcPjkpOfU+{3mx|6^qPi}Cc7Rzf_X_Wf_c%x;CQAF zj_#6b7~RRs4x~H6ib5-=HHH-(2`zHY4g5P)2mCJs;eYHETQn<6h%|J;Hfp*S4Yxnd z5r1Y+`y=FZWtUs6jfi!T=Y_&fi-Wl_aV~TsRfi)e9X*{bFMaqxsrQlS|6U5`P1K9T zbRZo}?>Bn>Tz~qIMx&Z$q>NqlnsK~LP|AxoCmKwj9?67}c>ySG1--!444pJ+&N5ic zU7It_Y{7V5xL9{v^d}?6ukLwY4`|PF<>P zk(&Pd@Aj=-R^^=<<>#A_Q(L>25*rt%|LIS-#=rWCz{P97-v9BD?Z>x%{mOyXs%2L? zTWvWtfL&fr=YemJj~ux@t7{*9NIBgaR+Z{QkA|2-Kl-(COx@5p>H$enYLZ%RpFH`yqtutZ@x~i({^kR-il6=LH`Jz{c<24+e*W@`>-9eF0rdGK z1qSa6WA*BZM^A41#fJp9|MNfphc}KMI9ZYZ%C}=}fqUwjJL}3xPsat6!j=iTyK=L< z($YM7&U;05Af_kx0@AU~H0Q0|vn;RFw|HR3)o)csdf{gCm2_dcOc*{h>$+O-rGK-x zF8xYtDz8mVCNn5ZG99gK?nub=O7Ov15mKeZK9Ec|!8Fe{5nRr0UU_+JurNY8oDcbS zeYbDt>|~!~74{2Y`m&jusU^6bUr+oy;VxabyKa}unodij&BMY8cPD*aU3NS|##CwY z#ya_cqzcrT+I3R45!j2n!>8ZBSH!^V*s;F-Gs^OP6D6kOc0noUo#anb3o3F4OGqCx zV@7g%`s|@Ymkyobfl-AkDeFa&`pTWMrdug5mm09Vl$R5kgCdUSg{*X@W@2Mk+pFBpu-GDXSi0Y%q zpr+H{sI!^!3N{>d^zTnH|AIRhZfq}bIcmCGKX7^`oW9d#dl8cFe0HZ<8_K+HWpVmu z-<-VJOUY7P8qOT1zXvERNLN=V1~sHWGYoB|n?uy{t@HE{)TOCYo(s8$m{z3BzT6|0 z687>KD+AJ(&R#ktr6Sfle3)the200v2M+dP`WKMqNpqxZuLMt;jk03;2Mg8Zb}`Tn zts~hprRHB7gH%X>Tj1o!9((xVMCtLaZv#_53TbP+h|>L>L3NQeB>p0Ru00TGsp$|p zqPeLcec8~v)crMv*?M5kN67jS#(R5*Rb;q_Jp>A|gvP@hM^EY@^PFUF28 zP&Xkj=A;l^oNjVnEH#~yQyE-(b}Y;CVkli(7J zdoEUhOJm%j*DJf@2}ei6b#y!7Xf$tjSYg0;$~-s3?LUP3WeYKk(+{mUL>MG#BijY{kd5MqgK&Ap z@OL*9R9v@L=&JeGxlKWdl8g#0E-eY=|)x`PYK%M0Tx3WDRy%geC16gIRG{Vsz&d5vuaO^%{zNeknMR44nN ztpeS2HFA!|$wPR4JT{r6rud?uq=i}49{&f^|5l$pKo*#_xEvn0c-ov4e7lCrt^VVO zEplp$mUb(ZCN5yRhgZ*Lc-_vqBPLy;f=W@mKQ_i+@l$K9H2SpTC%zezjf5J8|^mcE#PP-L6katyj9 zSAL^~sIDGPKm7^ufFz^uKlJ+R+mCYqQDH1go}^71;2 zCaKY@>oZcC*UFQQKfT!3cB~W!H6DJ8W2_bc+Hhm9IH!pAEmz1KpavGJhnilyC+%2Ahiosu{p_>PucW6ZdkpNq zrsJ)F0j0Gqq~Lt@FLh(Cv{sdt*3t14r5s~=s}0!lOz_MGyO7dDz=wq`==x?WIm2k@ zhWdA!P)42c(zD^=Gt=|N%pSV*{)c;Er$;Imr-$(GzFRY1Dt z0Jh8N{8QHe(_N*!~tVnL+3L9a_RBN;nL(Wxd_gsyvx<0I?^6Y7oW4^p48FE2DXRib#8oIO-7+~{c&h5x(r5sXgI%UxQ~aCy^zM0QK)ia`Q$6(CLbPcm{$92U&T(G#+8qeJBU zP{{qVVo<;1{!1pjl7;&vXhmevsQJ4Kj&EHOmNgel$L`y}j%@0}LNI-uL%|?tw+#41 z*7RLlJ`ueh+HzSsw3KlGch@fD@4p<*4bE#$JnHd?*to~zk}5;Vf1&PB0yDP(UtYr}%d(qr5tohI@;p+y7THCf>n>4K)3|Ch@}{Ju#`x}bCB+cwXp$NY-*XU3EF&OJ z_8}dUXs$&1VqAN>vCM>K%{}WRxBQS8PO&V=@fcpt85!M}TPR%Rev`UU{MB&D=^X8x z9y*RNn$Z0vxqfAZCEwb~7g>zkxk(^M=nUF3;gycFicmRQa+Xe?*j}1wrgOG%%zJrl_*6lDSHJ$><_Jy__aSAUegDm{zKrn3OrE zRpJ+Ms1qr%C^YP3^C`ZU!t4ADR4{MLN(xPCe|_9K5_^i;8+l75a3>|j#XG7?3QCIZ z30)lK98DzxfQ~p$G-D7lrEKSlfI-`Y*$GTnJt+eFI<+BHG6&0Bl#*Tv+DnUfloXzw zJ`SFHyf04W-oX{I4F%nfZWMB-vnIW~I=(C49$(N#Y9tLs3kwKLqvvS6gSM2Tv)6;7or$t>Xr^|1*uE5hJ{(pgR-MbN4HpA$GBcBl7CRH7k#Gq zq^W8dOplyfvLtl$C`=wH8L?yMmyk_9!DV>~)pkXFNk;Y?(1#dE7pKcxVhUFU#u@^3 zc9PQ{dfv=BT%fKwhj}uZcIcUKQs~aJFhI?kbZllDlGq>bJ0Mbsj!Gg)9W`Cv^e~s4 zZZvgceo+klNwtxr}MnK(0`^=h@=3E@+B|GV2OmsKrW){I*PVYjyYyK_C9j+l-s{q$*MmwD@<^fT{X-E;-lOQ$Ux z(@Ra=vd-26CqDRK(g!Cp>T9t|EF+qn$F+?7^kvI%@OqQ?lD=nIdPfJC{@Yuh=Y03w z>FZx@*kAea$J0Lk;Gn_mcMPT1-_E~%-^7WxFHuKHf6*@_m1Bv4zB}H!a^T9Q<;$19 za>m58yz|bh{{+EXLsh09{sKgwC=<*VhoAZR)PpDQ+te}8=9!Z>21ZAMp7`#W9dFWI z2`&Af!StiIZ~yL#ZLeIp(zM|3szt?!V2hvL3 zFFVt>)DzxcwrtO`Jzi@%HYvR3x1W7}b!}>Z_puJZz1NJjsNqUzNv2<`2l<7be)x~| z=Gbfj-kzQbUL>)kx(}|Bm06~Z{yuJAewn3tG*n9Sgm^D8b1{%UbEbFwr7k$#Gc|hR z#@!b#e14<3zNV`jO6MD$uj||Oht&4~>d7+_-Q9dP z1I-J>=axZTUKt=A%S&4=ftKj$dj`)`i72L*=x8c&*=j>HBqOh$%tVG7L8%!mt|G1g zs1wbyGkox#ytQ?5ri1AgQ3L8?bvS*d?oph*U}rQkd3q^odP+_efkkYI=pP-8V}?Rd z>-rqR^E`A<{z1lw(+#GtG=Va@d)G>hrjMMyz?`=^ap>Um^cj?qPPyMZ+qXX(I}pbe zx0p>ODUeRtsOD4pGu{*|Lmu8fHXoZCiZ?KA4c&^FSd>>UY%d7uG$eg&SQQ1pvNw72 z25pAuJt!b1M>RE#Ntu$Z^gy~fwqjrCbHuHC2H7PKVtzNg zuJzrqrZX8Z%}A|!Q6(=z=#tjO>_$vC-gKGFfpjPx2il~m<6lKg-$t+DH-5#&FHrr= zj`5QWe2>5sBMfJZpEGI1t0#^^=kFf<64%SW;(0mx%G>Kljxg1lNa*na=_`FV(e1}cktVf6{xs{=zmA%IWIp@+*wQ|2w&zribay7Pe-KpjU zX5gBsOzLiuR3CTFe%4t%p?%yVTLx85uc*)MVu(3g~?m$A!NF)twN1wT$DPdol>Qvn;@9X-FVf6L>cGNE_n6CZCcL{`Vj za=p6xdObyXdoVKZYw4neqJ4+SSk(H5)D#yJ(?)7z* zp^e>SZgw{^YjWb{35zcY3ksUfCrqFYD-D6T`IrsDp74l;;{ZA21UvCJjZQ`!LFTCJ zW=T!w_!I37ORm=L*OHV$%~;-VTP)-F2&bAMZ^HBb;s(BC|x%Fd}J=$brB?#%G#%C=kYgAa|^to)=${0H~f4(Ta$MRy4GNI(510Eo)-8EzOJ=oms5q`T%G*16n_b;z4;c-=e$ZqK=o;6e0{EHZn1hf9`F zK^jIdqXxiknP231k@02j+`^3&6Zj5~9MaEvcrG3b5sN+M-fo zu=k{-!0AzLm|dt|i>R`NbP(%I7zX)^)Q;wOp$($bVXF@5-kv?R-IR06oqqbXLeWp3{?qR-e{%V9 z*om*t96h>;o;OiMM}vB#xVN@$y7}ixAH4te$rKZ@p0G1IH!78NtzDazMnZ*`&Bwho zdf$DUu3SY;zfik(FX~C?wAZ(P{PFjrUc1PT`S=~b+xOjfUAHrCkG=1{ll9MjXE?p$ z=oyk=e)b=c*Veo>@r6wt%MTnq)8lZFqg~^j4|n|PS5%O0J9^)Jt5+{iS^dJrNzV=c z;LL&hHf`$grpVUKEjs1}m5wS@2E)sLc=PKsXI}ea+u0pwj(&ONO8TBX^(0f$>b`An zi@hPgrZbA#PmCX>38fgTONpn4uM<4oebBwJyW@MwJhrK${oh(M zFmP?T#Prjbl4oD(wBgv88K5La>?hRw8aFa*2Db;m(Gi5L^dIJpKA$PkelYRsDAO3z zxq025nK<2zoSs4R%Gbwakp@Svw zIcP}2JA!sjO=mNYfi9@}Fp$|u6Z&2QZG3)m%L?){-F^I|o?~^XMqE|4i)Z3rr!Y(bTzeeXUv=VRo^f>T2t%n^~HP=iI32nZCZ+?K`ePK61~NSgm_3Z!^be;hfKbpVKRMIWQkA3+r88UO#=t+H1)yVnyw;JL+9p5i)5Z#YWmdS z!@>0TRWph}K7P&!i2Z|C-~MoiU|qXkyhDV#uv^2@)JM#D|Lrqh(8uV@e?6-GyRR^n zK5=;DNJRAGSi(m9}1`zUK@Qsn5an!r$BP4}Wf|M0H4;3eppX(znv8 zh#sWt4W;j(59!;NEeV|?>@Gb)FQRngdwI_kkjk3=^c^<8L+MY$;AVf<)BHj}>FiyQ z4w_?BSF2Y^@dnj<0vTyzG(=(z!yNW(XN{xr-ID2}w@zm#DIHu#PQn5cc5?0ndDMq2 zEc|}%%?bEkjxQcXQ}r7K^KZ~WzM+lU!fK~_e^!?`gN(KfQXks#2{oiE_Food8&apv zQ>6Qe$$bISH|#f{PM!*}AdYSf#$>0XsK>QOQt~PE-f~E>;@n;X@f@t?+~--hrLv3B zS+%*GhVTW2bMY-V4XSj;<2be_CF!O2CUckOn-?&@RAZp&?k0Ggtqdhih53b9OR}8jpmOzHg%Quroxd?28*)Sd6{if(jfyZw4$#dQql#1~fNXU@!MpaQ|p%(zf!<8cga1`GvvLio$}6Dqnwo+&X72<<#fke#lnv`}pfhQsN) z#I^uC8*k#`?Oipo84Zh^i?XU6aY+QdFGBiv#FrEd`#&Y5f2+@)2$lh&tJKmgxcnMas92%D#Ei5)6FRCFG8gn@a&*cw2-WM}EY;FRB6dGhgK26q(Zr@kdDs7=r zWFvoku)=Vn`Olq|0i};En@<}dlbCMR>!^%#^pfeJ{T@+hx;R}$nwV6`XmL?HN7e(9 z1;$W%52Wj9SsK5!J-~R>rL*h$%4D%Lb!2d}Y&gC50L@)p-_CsbnxvP-=;D)YKs)}qO~#ZEIj_yowqPN?{PTkns(n4`)OSh^>fA_oF z`vlgV#BjR<^R?HV`-xroG`5?N^(|fzP&S9gKgHR8m`3uJFF)|+2a_g! zaC6ggoG$5UzN^9X^tH8n($R|5(Wli1SMy7@D_3Ps|GcH~7Iv5IA0NN<{e`ycXD^SK z^WN`o-^SHZAN|7ZO`DER46pl6a{6~0-#CMs{^2iI_=X-*@zl-xxgq;AbEF z<~P52=baC?{o+^u`qIB1-3D_{B!REKCi;a@A(0D z8`ICg=_hvVII-=(@++Oo(s8Ea+JMt}Db!W1vy{f1NS>HR5W7ps75DQaLBx!_JnTDZ z(Z_79v7cY~1Kmi!y|KKL`9Qe0Czh9MU!A_RcJ`G`9m4d)h+g=DU^CXCr*D2mZbm*GG(ml$7-e^X?8NDkX2DAanI&vk$;pwR-kBOQJ21ot#of1mqHlj& z%Gmzixl}LJ(?JMEuU}ceFOwbk4WSF6qt&>!7MYnbCe=N0c48nY>Y92OP?zClW$B)} zTDAa`->9o&n`~Qo+RU`l&AtSqBc}ArcWwXxAOJ~3K~zVx3O}jZN?l2)U%A-=>3TNQ zC@hi+Q(P<{Jpqt=mQg#Pm=_I88|TWx^wP{4lg$F8b4IkEUjKv~(s-bB?}7b+|2vi! z3)IEw(e=1dD5*wHcT4l};koSWZ_?Qf%o|EC&2%3;GZ5uJeDmO$i22L%){eoc^6+E5 zY@SlU6_3dT7;Rmzt8jdv2ZU~-5>-N~A@evFdBD}gB%;4Zc_oKnB=;a*Ooo?XLwk8f zrB(%Sbts)_lRB3A`Ki1WJC0^4)b#fcL+L*oKYq@fNyDF;G#piZ z()gcIXR>3*n`ho8k4ZV`rWdIN>vIlcO2?P>#g~F~v~-MZ7sroSPcI?4T`quQJ$Ce2gyzsvyUKv{XJ#39G>?CJxDDzeZ_gibgb!^UNEJbI7W-pP0EX< zr(1p(7pRZ0dWpIubium**jvS+_|`25cO6+LbO@loX#6s+v+j1WhhcNqFM*WvBze+9 zIhT+;e{3-RoO%4XT9PiYwDlz$=U((jOZOjL5;lL;gcILh^xwK0GXaAGToG!-j>n*Z zj6NsbJ^^gB@XHV_`xT({7UXE~To>@CA?FKzZzHK=QonYt8}Caaq#n00smK`@Ixg-U zWW9gfIO*pG(?N6HT75&GKh%!T1TPC~wQ!xqIH$9OQCO1YaE7u5OyVM9iTSEqtwg`) zepMDa9U}~2&aJVl!|1U3hW%XGnY5+%xPDtgL)%9yiSgW5KstBN)PU>i##;!f!Bs=_ zdSf@bIL;S385NZH_oXf7imZ(2jO^@AVukIy3+ES>u;HPR?F=~g@kJBLjwQsI1*D&I zoMSrDO|E)%;l`ATEFA3J=YqL+V-j&V?bX4-cYa_0b_@5<%&*92o>hIl+F5Nc$j`@g z?$XF{!HlwxvhS`gXp3EC2iBG165rHS-qt1&9q)HTO(~g(O>O0lX>l|es(gLiQ%4|l zQ9ATX9#8|`apo&U)5v86F{TfZ^MH>TpT6mf7yA=tjlM1qjO;M|jPYgMG{Jc#A&mVv zv+@Cy^+7=dITHBNM~FuCXz#wShuZB9ejXbr5@n{)RfC54(Gb+WAOIZt%j6Il+>qWko0i#D{`TI|pA3HXGZ2rmlql__KiRt<_6s9j;GJVJZ zJSB#%)i}t2uz3vfyD%Pl=y}Z?G+i*H&e5I0^h3`^&(R!kfib;kEy8N)--h|E)j#+M zpK;fBGxx6YQA6lUXg8`I19H!rp!oFNDE}pes|d>_=7rU12H{$*PW_;!KSqC>RkLD4 zLZUiDY%#Q0@dOpf2@L5#TqK#BDn(myc8s4FB$Jcv=OsWuW9`*{U|@1!2v|GY6KVp{Mzfzn+}{=~IYFl(iSdq-mM^ z_U%a)ro-vqe}DXA#*tf%r-*KsXmjEu)$aBAFHC%4?50fzUO2W-@!_YhSA1~>HT`Eh zw%xv6fBWR>V=-TDdIPJ=KYe%xbNU-+&b+x}+poTS>B}!)I!bNY(HE#&%=62c_{!nu zem?wzZTGENGjPqO)oWgOcN=SY^_>s@W=<3r&_Lk1ZK~;vZ=Kr9HJdMdrCwHYsjes``z)VyZN}gyV?zT2sH`itE2Ri3e57F zoMlqeH(+d^F`Gc}1>T86F^>q-PwX!Itl(-h_KdpxjMcFf%{w<{gpb{r(m&g)*RWw& zXVf**;GmGOzh+~Ww(gGcB!T33>W01C@Vt;T;^C1vY;v!dv12nb@-tS>oQaZ7Or_-W zee^a$WnP)NGZTW2rld0=FM+mJdxj``MQ z3(|%2I~V8>yGu?Bf#i}qP+x`NSZc)F8fS_*QB zqD)J5PxB_i3{DPF8d6MD zjzUa%MMcm;XYGM7{tc-h zm5s*BEiDz-OB$5!tC)4#Ac@Kq@uGX+kE;>*2&0n$(~FK;@=OJ=b7A`IWY0Q4_$q`%9-8-V)FGb=`7!r8uJ1%f+@`&7j$u7KE8 zN(!fAO;?0E-Hv2P2joq6BbJ_gf-73xjRwu5j#k!mV@Wp$!gQo|SHz17NL`*6S<}~_ zf8wqlA>ESEU8*`KAoRZw%YOiL!|15#cN0XW>*#>tdZS5PC2d9rJD7Zm-2D?>i6@!79-j5B$8y?z! z8Pm(ST`({;np+NC-meTsp}CdRB2^kj2a?G`C-bFS<`-ohQdfyf9eczg%m?k5oTYXj zI`kC?F3Pv|mE2m1F7UQF3lBUZJFMP5J&qqRe$|}*?f!Upg7|r5IMtNM+&#yvqCIp= zkP1J|%{gs`NFJ~Hp&^xzjN64UzGDB1EgNu>rvNjPf5hU`SAC*4SLXnBwA?Vw^99Oj=4PM=hjtCv%s=_%NrVqHsc%!$EavcRY2g z=j`XgoQ1QZS51(99p9*c^(Fwan{5*DjjlK9Z+WydF{8ZgIxcRzGtx=NP8vyP5cLAL zWAR2Qw`=B6KotT$`(Vhpx|6Nlm9RdC(A0efr|8xr;(oCpxX4dLIeP<#$0tC)lN*>4qee z0c2U5n&^h znOH(JMFxI!Ty+JJ3lxN#E70qx}-{u&vkB5tW^ma|Owo6qt01K>u*- z_{Sf7{PAx;{_U;C3#Tq!+WXZfs6k(>-h^>E7Sq!0y3FVoCe{-mE>1uBhH6M(-S)fN z`D0($v}rYEWjpY>{OZd!i0((<{r1e6SB`%9%eU4X-S+j@HxINHcQ&Wy#GJecrcXU_ zbj_MI%4;-smk&RD=fgLD@vEaRpzv31dKbh$!<-^_WhVBV^xEcT%=onb+`G4-t30JO z6VryRgJH||L!Xx~1bcf<9+idBzE#Opm?`S%>U8DmXTSaax1U{Ier0)w&9@6m|LF9; z%uGg1???=%gOE7A%8M7u1gJBW!v8}gCRTBi^x_qefI^}-z}~R8tGT)MwBpkD+z+O2 z-sin^O8B$KqB>vr;sk2?=e1rwiT9`F-_CfUtgPaTjK{oZrLg^EHZ7~XH$`Xrz<3gS zCI0%TXD0EHKKW+eT^`s%b8w#irP^?y}XY4QS@<~ z-{A|QnP22a`+33XLiMQ3o;>tpnP7Uln}T4X>j~(eNeDdsNB2lemt<}YIbC3N)bu)$ zweXu7(w+E@z;r*iULg^LTBxnfqtEIxIDN{LDYL6mC8v8)??KeQpLd`LTWUI96tman3aDH{ zxCC{jtV>(RmmV@ZIV8Yic0^zVoIYh~q8m*_XD_Ae5$_1^2K-GgGIb%vjgz3hMuU;d zMfl9DT=#&Oj+Kp8T-k)Nlg#7cja>=56h5h{8C1C{iQV;W(3A86$D(=D$A}#O{)0Tu z2{0Swn~ZY{xXt0C)^&QkFuK0c+evqMQlPGw7s>8~rdwPOm%GM!>lkjg3@##cJT92i zIm4LK#pxzBed^TVlSbfqc^f_b@cZKcG+$gWo?`TKvI5~Xt%Y>ta`LYRN3 zzY|tJgc7yHfB$Id;oK3oHHtpiT{);7*cPI5jtnmh69Ll>;E(Imd)GMsbN+{th>Ijy zjCMoqjlpCya-X^vU72_q_Nd3_7LE=Zz2xll^Jv3C@%e1+^0Touxih6~)$aM?^b#sC z3wPTK=~+KFe?H}=CDmEoS?3zr0hf+ZWihKLE^X?LmlYm%6tXw8{9Q2p{zOvGnOQiR z&L$~rk@g+1IqJWRF0p0wIV!;oGS^;F5Fba}OLdd1?4?jTc`A*LhVqIgiZ$&trY#Cx z7}s98?)7nfk6eq3bH=v>CnYsCIE&&OXxI+o(|My7DMbTL@Ap8zA^xMorek{<@Bpeg zF^oDGfb#|0FimBY!YGZMIGCVCqbl-ejhc>>PQbLKq`n@9ULH?$%Q;L=ZEZ;WG!$)U zpjOH>Wg>}@X@xT$j+afRF{z!L$fkydZXQ=-Tw_5wYS+vfyTjh#sGN?C#}OP99PA8p zEOPk#dsEXNEA0EzyZXiUfZIRNv8nqsKr1X~0g?r%1?y7MEi=qrE`v80i-{T1&}DH^ z&Wo|a(A`L=(x*55jwk>Homu5Wy(On>NJtl`_Y2xRYSEC$td02_DxL64PO2HTjI}caO<=K{Mx$EnkVK{God}hfq)*urq^eSe$O|j){e)8XWKp^c?g= zt(6F*C3;(f&$HG;_KR_+7xjR;(3~O3fp2FPfOKW1%R6Sq-1)0UEgnQn*+0e9#<& z|J!1g+XiA!x5dQdVS}i{X@PXkK+a`ffBU81sg+TAPK}>>Viw!7-SYO-9ypM)w)WFc zKXMKlvHqaqU_SX1RgR7E1qX_~px64`7bY(6j9OcZT%7aenGYuYZ2Z?ZV{7XCd^fEI z(=zMILHYW6KezPsD|;|o*VU5s^4a%){&?gEAK$ul>!XjpIfVkvSMn#&z{`ZzoX-=j^!`i_kVx*-g_T@ao?upo30$) zgnb34{KPNU9R2pppWnUGL11ILE&2trUY>k;{TD#`O9Z;@c;}yJX!_xfUtn>+ucr3W zp4lDLsJ-#V(JQvPx_!~nOf=A8FadqDckija4GlLtH~aY5Hnk#(+hS1DB{nCpZJ^l? zv-2_Ejw(FmnM9~3C(}%ocBJ3lyt;gOc1^=Ilk&2sgM4@bMEduSNCeX(+)EW&nVIJ1 z-9bX48;wD!V0xNI7ZCxb+m=oae|AA?RLmC_0nZP$URS+8Au=_t%`Ee z1`i&LrVgmnYHH8QIzBvflL<(w?tg>Jy zm`)ZroDMI$561isrc-)K^5PF;CknbzzU56f%ue+wa=I5fct);!1TilI2X0;+Ev{$1 zMoov)F`w^z_83Vsu(P`@K+*S}#+{A}-dg>!op@sWe9}sDO4FKi_Kbni*XA)xm@$L2 zmnrg;N8qKO5#r_-l}$l|7aJ*jU}(#d&Vo_Y-Eq0_YI}r`t>cxO?Sp>_+1oQ>N?=up z$IxN!A=qAqE}i0*?Uoz?X>%h6MInSPxw)k!onFA zooT%30J@+YAcvzh-hcJ5oG`Ha_z_$}LsG_^@#7Dlk>6z-f9#RdDIGnrex#CX?wPk8 zN>?V#+s5#sz!%i?6-G^;gYyM39T^;8pGwRN^nP#!K`#nc*Y4o?mx1RITfufKFMNZ{4WT-M>_}6CAB|o%1;gG{{^O-9|39U zq42oGbq?qY^w<0Km^O_xunV#zHreZz)Ez#K{s3l46q zZX`rS#uyF5)E1h{;(~gvgvKq3dvOgsEtqSpt;LathWL{ra-Qi0St5s$SOF$@Yl!ZL zwEK^~Jema*c-dXxeeU5Pn=FdD~D==73UC_RSRbWDs_YwRj)^6GZkR(4}IsxI#I*tW3I(}6{M zH(EN589J4g%*ri**0E#2=~x>Z?JWpZ6leY&C~BxXKuc+B5K!(hg3Pk{3xkT_^oAN7>7{HfxK55bCU1Nu1qF+b5b|;)sWG@{+*7YtRxV89 z6Vt%UM;$G4b+rRUJ1$A3qY4+2G5vuDs3jdTXiL9-TQI!<=@?w_x=e$j0CoV~gr&># z(vL8X=#>0X{*OP6l-m16EHAIG8$hsPSlmKf=ITJ&L|kOB(_RvfWv77tsM<8Zc}%FV z+^B?<`Bozd$23uNQm~BWrDpJq!2D`wMfJjk)dl$#&P8$5m{wN@kIw%0hUxtyfAZ6x z{&?;`pzTEz>k`pHS;^2pP%Vqv3v#WU7*{mR!H)@7C+x>cO}7XcQtxZ3N99gORF^MZ zm=37-R%oMc&=)(pij;dW9ZsJ>4QV7_Y^xZf<}%ke`h_T6MVwUHhxRkpZ{hVF#I|7E z0(8!_FrCM0h@A^56XG$O=Vmdwo|ZYOYm3nZ>4@pOtgshLn&(U-r|Z5=(xTDx=|#GD z@nR|I%6w5Qqhem;fvaz*H-EL8c6At4>! z#ZfWK>4ajV9Vz*Lgm9-(v*|?_^Ngob|xzLrb}g>(qX+6p7_3`H$5MPE zpa1#K^1FO|>(|$QeeD|G-1NUVH1~zoF-XuIy&|SW1VZYH->yeY|LT>Sue|v+HKQN? zYRxadybq=A-8X)Ly8h0uR`Vr|x_^CqD#VBdOfu?;l63PZuIoM<;BGl zQQ?n%$z$@)tjpxr096xtIn&Rxs-v|t3e$IeDH?2Tn;lN4j`Z^zmrkj9=r{G7XJ$v+ zhJ|n5?7g6W_&}adM2Nd*0`H73Aw9l=Wg6a7IsiVWE~{zl>MHN*#`MyK_mGLnN8emp z$)gMRNvNNBzk3yrbImJfzWw&I8!5}u1DE#7omG~b68l>2zz~WPXD3&Up|X>E!IdHF zw1%jU;ai+Zkh%}zvlntUqBgawZtgyA9*G{gW6Q=aw|VEr)>BGZPYxqeI*bmm%Ti83 zYO!xNjuem0ew>4Q91rhA#Y1`>>PDoH5wf zXD1F9eBY&jI*mw`HsiMsel}wP7L+t!cW+NG&rEFjr88JfJy9-yf#?EnW06sF(!@JD z`7yM99%Ow+v@g%N*n0u}az*Jo?+EEG@5=%v8MuJVe8>%hNoHnrbf$Osv1h}dr7ad( zx+k$Zd1GcE;xAiUTf1y#UQOoAK>95uK1Q$4p&5w%IMdL>D|p^>0=DnPnsy5@$!@B=Ml@; zciyfSA5sIO9`-h&i=2ePv75gPWE)hMuFkmvb3^B@15PL_-Ly6`kZx*8pM3N$Wq3=G zH){dZQMU!-pgU+T!5*)=A@zAKOn+wTNE(MudIrM_K`!vP;c}SzeT&xx=<6*?mnj`a z$LC@aUfy_xjbvwD9XWj7ygu_@-@bj`yz|7W&$)<{K4Ro{d0z0Q8!$&YpF_qAluq8u z9CQR$PfFv|yGK}R`sj-*=3($L)^y+;XS(sF!|xWv%kX0DSjRhP@}_`Pa`+EUm%myv zsyUQyxZU!$KWhFG8-B0o7A)(^X*#qJJV0+$iB( z7bPC_7cxWYng+N?U8^4?*pu&+P1=JhAL!dJXh`UgpvrdQ6fw^jOh-cBKRRy7S^AHz z;MTgmrKYQnlt+nM=1}i-l|^_p;;waHi%YsjwI{3^hdj)zfMJa6nAqb8iAm!8vlv62 zD~LB)vbZppA}dl9d~H!NzFs*Q6_k=fjGa+s1%>ueh4$DAJTGy=^`^l^A1NL9>Z#TSkbz5L7_!R)$1x>r;iZobz?ksaK$o` zWWx(atJgRJ(}O}~`Sp*C)VpQU7TF#_I-`02P|}s{GN3Yuj-V*%k32xe%jlB)=#-6f zM?doPT@O9@BI+UiDA$FCl@t);j+2E~kxEsEGdLJ)O;e!}(ueEg#6UjN=O-9woE zbjd#;ri;W)hKscT$s(W|ZZ|5qJlznk0bCc13)Fvn*H3`nyQEB87a2WXq3Nb})Rz2Kc}!+O<``@A%sE_B4E1a>a=LD2fx3Zf1*gkeZsGe=58g9K z+nV@7p3c`aYCiud6pk)|)7i5qNS`}by;5C@dRXKma<>~m2i7I38*Kjp)5H5mkEOwp zcSMK{R3E0T@Z_QMvmQgaTQ=}RK!u7F6F?MFC9-WHghrsOc6i0)WP9i50$JN)Utzg-WCMm0BgE<=dTsjsiSbczB}aQfW2Z-nWn zF&|xPxe(h~yeYZ{%RuwmJgc7LdT=vSDw?FuL ze!05!l$W=iYPj(2Zw;m2y7uc0_}wdyOq)ic?vmG{iA*i9QstJtvM$rdXY(a6 zz5Cmn-4XU&7;esXt(K^nZ5e9 zvR=l&y@R?@InqD;@Sm}}yfkqlRvbF_ghYV9n_8E*My0uz;%32~+-9dGtLkZu@uh3| zft#;`FRPg_VJDr|zS)l`L&7Eh*n-m>PK^S@Qz%O7ss_~;t-qg|!$ znbFys@gp<5eFjFLr_ZJ{s3##WUN+3=o<0F!dX%415(A=Y$w%2k(oR=hZFyVQHy=q& zpEjb#C|e-vIkwv3Kdv&I6EsmWu;pl)+F;o+)4 z!1KZYF1qbVrR zC?@pWYjdEFupQAGxqUE+FSC=A@o;c3!#xf4dnVp{+LMe%7s1Q) z0%Pmp5j{E3`lg!D?L@Yi%1_2KoD&dm!7tDEJ)A>=5!i?;!9 zih*TJ;a@OH-9kM=0zKTkLJ|pKe|V@zA|)ZNI7ZxOaJr@rDoZxGL2hGkr_1!hq?@7< zy=Pp9;maL^Mbs7PIcxNw~Xi`6ZPw~*bUbc5)MgQ3ll4tuIeL39<68d5jL^k-1h0dw5%5c_%L zbv+V`(_M$?=~F2%orHVc)xAi~iy-sySXBsU8NYtKiD4W${_w>&n0`w~=Z_G^cVBt; zi;E+MKev5&A3|q@>GRI3b`(nI_Urp0zmvm=HJz|@`O`(|$msH`lgG%pQ=eFWae@)k z{pZZvb@$7{boC$Ap+)LFt{0b{?y4T87IpoLf32UZa?~(6*sWs_-C(#`W{Gi^*_(_P za|Tzih70=CKqGRyNM(_C~Y18FuxZQHtr6a zPF&r>`1r8GS4M4oVeZx}I+0>VXOs!h4Y5-|iU(o86Eb&ExR4w*y&c<&S=#l}ErRZL z5)jYrC$@!to-q5hbL#Y|U_=h$7A|yDH#(i@*g!gaP~4ReBd(@?l!ive<^rdK>oB`; zyK>8*Ln~mu?JiV*pbsi-5Q1!F`!(<$K)+@xNb#UAaW0tGG06 zeYONmcdW{d$<5B?pM{^lY~QGW+%l}ujsmY4shwp7b9c`zt3X|M1f%2Pj;0AIp(=&3 z8S|y4V@gL)mt(pmzNN7t{_mltKkP@Q`C>xOlN=RFZK-Ig&WeYrorU=snK@Hy`YPtP2vul5XlLhtPT!~3wpg$+4pR3ID$L9J*m-ogwxZAv2Uk& zkY3Cm677_}2f2iPBZV9@lif?2T{69TBQc zG7f!^%G)Zs{1Ph2QEOUc&&W*6Y_rD)6WAEHDDK~%>1F;sKfX68eabbZJC&L&Gix7M)8Tmzf>y+O_ahUsE(H8Qt)@Do8ctPS<*W@=zZs z>3qbbr>j-zBmMm6X88{pJ!<}{`Guphz;v^5kqu;$F2HpENH86b4LcGST{LZ-mRVho zNn~!pxe(lXEat)MLG}#m85xu}db%O?zx1ZdoQ@#go9uM@^orA6lrGx~>FFfAgvs%; z8%7^B>a|f+kfN-IjgB0kG)BR>`Xt@q^@r|Y`uzlCkKI@{HhaoIw<4mEIv&$D6lnkGqf_O1NSk<*NpM`&nm|^nd-oCw_U~>SAA? z!GqmH27>8VI$ArTyj0M)hsg%kjoLae{n8~8QNv7hHGFN9qxnfJ?? zt{3c-tW)JR^_v&e)8K-3*ZjuZu7`TT^bA%T9lbKzaJZOy0Uw&oOg1B=Qr)R!cIo*B z$}KXtpqoRTBstLsx;C7C?Ac?R5xl7d#gfA-s|KXU!nqRsf9IywLO5!A3PL^_cPf-l z*(uute0`7MO0Q?u;Zy3FmXd;R6Ia?D zZRVxaYii_l4xndII&UE_CtFB(S)(Xw<&X_l6p<2$@8j;FRF)}2hXvBg3iAq&7W=w4 zQ#1O_GEwuyN#vL5Y&iPKXH+06S^bG8p8WaG*~^mN zqoZp9P=8WgNrmPXp1T$}q5YGVluiPp3Odho0IeHX#}&i5Mp=J`AajZCGRh2>ab@Jx zktR@m1Q{F%@g!I3*r>p&_%k*MW(@hyF zq3IAf)^Y>i7NqxpI*_g%Qo4Bk2i08H<#iOYTNwYe&bgzelZ;MXsM+ybz}Sj@w4xuj zbQ}o&{)=~KE%D!a@$89%{wql1;PMG{A)Q{7R8-X1xVvKhD;r-pF(GSIA>L&e9ZILu z5pudJO6Av%QdS!OgQ<54RITk?6Ltq zrvwqnnf5`lyRa%L=DQ4wOV1uh^C7Xh>PC&Kz6(mfz*#HKYsn%wOj0OHD05X zwH-BUf|JIjhlUUVFa3Q(clEi-Lvb6(gK>^NH^Eur#5d}{c$Hd)pr*64dHcrXhPdaJ zl{oUfa-%#`J1a_d=a;D`J+Uv1rbXxVrlzwc85xCH@c?_bicuRWc&u)WZzMvDa-1>UJrM zGnno`WTg}pO?!PB+4q%2MZxVvrymJ!YCIC`JW?4KUsQxiC{9}-lHhb_=zw)WVex0@ zo*ivEZ85=G5jv!D5YsBAk8ryD=mw_X^#=w7jV_r#t88P5|2>;g;kTP1CyU61C!U2%pbO8kn~cB(WQ|jM&iE&>KHmR%4;$+$`dln z^ZjZZq16@Tx#eZ~Z8T!44qFuI`|nLn|52}5yGv4f6qWyZADjR2HHlu0f{r(YWgY66 z-P2~lQqwupf^lK6;N0Ab8*0gdbaN)A5o1Odr{8nl1ictiSBoQE?I*Zi^aUYKH<(T= z`{zO3S9}n=qZ*a@Qu)MY161zgu@jh;7WGOboJW|iewiRYxMV_g5!fBw%DiM@T|#Hek*KYMWp z87<@{Px@f%l3Q`N_%1e#zWw7PzfNkug|M^X+BIj^+}AeVzMX-?hEZJHnM!CiHWND2 z)IsSjqi)_L&P8D_46N@zd;k4+-ucD0H%=DgxA(TmDYN?M%{N{-^TxMlZf+{h_ChUn z_lcf3@#3VPKR5o>cV2zJB>kBCh){t$O>Tk9s1jN_INK-kCH8rnSBFYP%6 zrjv@u$X``BYSf9jU!$kvI)};Kg=g-A18kib)~l*Qq|w$5PK#oz!f`RrMb_bZ{$jddJwg-`mMePo9nCA$)mR?AWp7Appm5I^>=~V1Oev${0!G7+B{QrZ$$c0uz=$tFvM?cSxQVwick3cnC`KhNc=`jXS>TL+c9p|!BRK@ z>wXzB!VvtzC>;!^&xX@ebD9$d6Ou9$NT+_Z?M4e5Hfg(rAf9nuUG&--Dhj(+uA~+f zCygBCbUUJbDY(6oYEV{I@0YqPFEyQHMebMn`p%UiZT5J}+4YPC3lcYH=1`9csQ>a= zI-4%=_VI?AH{(L-uLh)d!Wg-&A@rAYQ^H@^C_s2ReSvuH%)+pzXYVXt8I2l`d0yG~ zX=BF7@?ttw<(0ZKUn$+3nCRo1C^>y7RiCq||L`I~QSKR~G3r%yO@L@OYUW%3dUg($ zBAX|EC~xd6**P%*v>&2}RA2Dc*cHp`VM8IWOyibVw%P*Ut7j+>WAx!Uw9bIa=j(S`#3VN~P7!9gh4MRLH~m$Q+>j$-C^G^oPKNJ_Y3W1t7g5jF)Qn}RfUGl#pf>bOBv=D zDAY-lPc&yr@NtMpF?V6Qibi*#i??5HKXmSpQC~~2=ESEe`H?2?aVv| zobM;7KeVB;QYQ2*?N*5@#+vw&rn6_0+BYP9)y{kr|v{3?8O?ZQVF zF0@>r29gFN6P7p$kcm9hZfz!L-yhc=*SV+Bg1gD&HkQom|BK2ZS$2jzN zQq%7l7lcgibY_*r9=|M=6BgcE5jN{ zpd=!OEkf0fg+YEjg!Av`cv#sBJ%Y+V)RPiw8|LQFMd&VS=K|5Wh7MUYc62EB2kSQ% zSdgwZqwF7gsINROf^_zll1|bKzNtr^5+mRB1@jh+dVoca`&i0QMv5)cAPX|ey=&BMivLv93iHg`cX_SGPfvwk(_kwE*R2xj~Z22_!cBdy=Y4)`vv2?0S^2YKhV}BYRne!2exuYP;$#3wylGxeK%C@sY_o`VXtva;X>0nx zULl?sld;6afcKQCf$7KCvQCmqb58V5`pBoIR(XU(BY^*oyccU=e<7gpPrv{D?}h1V zLW(8*n{Q5&`l4}(CP?+S_tocs>CG?P{>~Jasuhwjoz5jVP~U&=z41b8P6FyjK0f~a z$CA>Iv-|!?(Y0>!+RN)V&U)bm2>Rr0{3x3?5mZx5$svTEndxIN{d9>i{fs)1n(oK{#>|)zn2H1am=d=^NfSk4OwPwpa5uaA zdii?7gc8&7y^!0EGd?76=rF&sS!1L7BOhnhuiPg+-Dh)ju{Tle0|~bo$PwFIh$qQL zOJ`&P>VBDfB&U-#GQ-U;l_>Q+^dyoqy|(tosfMQO8A@EQuR!l9&nYKgOu3G5@lMzp zm|pNKIKEP)puqgf==!{6=}f*6q9-~8$ zyU&9D3z$QM_aEp}e9Wi6;QlYvbc@n4?f4eMyKbpQP0!0r!`qXcDaXua-1V1!;qSeobFA)ezupK>n>EsOM`i8>0>0j_k8(7+q<4bOW!qb96OF*egezO-C*ex zEXwpkCsG6HG$}Ql4rP<5E>5?0aJoVDC!hRFP`4cFa;Y0mH&&NNe_(W$jF>J$e_5)$ zye^jU9STQOA2ess9Ku^L!hq`d)cMm@fOTvz!-4jxBSsE?2AJ3WePnc*UChAlf};NJ zwyzJ5*gg_Jx}51i`u2I}k8j;-Z0Qp2@udsWsTIZZvL4y|ZF$|{b#!}tFA8R)2kD8e zF#5%Vq^95f#FI)*H?DNc^I{p)djc7)oEKo9v0{WuKn3GHL%c3=U1#b1A9mI?U~*j~ zF&7e11e_NdySM=HFa6rQNAh7cRsVB`q{Rn2Vf?<020Qu_Cd) zM1E})Xy@eq>1RU^tr$JpG1f08H_8-pV0+;o6#;?()m&!QzP^|XQ#%WG#}kGFh&R}= zp<^#`QgvE50oO~sNEZ`KV=xwVmG1u?yy=hS^nP$l61|neO0a0d(M!~ClwkNpaf_=f zVk-(u3d*4L*qVZplCtuQ=5l3{H^xKrNa=PsxS=7xFlpWM4`S{o+3-mF>#wiF@ZxM~ zigUKm=qRbt-qhWgBr!d%C@#$5j3nD7Xmr+DvhIP7*XEa;9UUq$9i5YWmm!3|un(1% z898ATJ*37-jQlai^uAC!sNOd;t2(Q`BEP)BnZ$G=9z8uQX<=c*qN2qz?)WKB(q3)H zyi?s&qOPeX_L3LA5o3CFcVSm~P2SAX8mwC-N$Y}~c8I?szd&)5cye<8-KpshZ@gzv zb`Q7xBOP0Cj)4BOc-=b1f(y_&Ul$lsm+CGU7Zri*Q7N=`y7Y)7f*9 zdeR5_JS9s0$z6~4rs=I>`i`NizH|bvdN7@8odIToDAimR z7Xi8stYc($JsNYib*3ns!DBL{u89VF{prc*BJ0YsxG;>EP9dqtniXJO>1)a9ieq%; zFT&^GIfisN-FRK3rx$|h(+Ax{-zAq7-K@@aU^uw0^lyHmghxO+<$^kQSaZ?s?M+Rn8(*a5I( zL{&xf_eD;BNxl~ss6*+D@4)m=Kl)0neyyF}JKt#OkEd>|U7KBB|I+Q3GU{*NzHK1= zPo`t(?{~a6XEzZ{DY7G%<$Yh)}{{64d@Z(Q6($1)5t+oztF{roAmm1FI9AXh| z;FTxQ*>&Y@EiJh4jW?b7!(KMlwUq(tyHC7w^S}#e%E+9=?ga+ol<8;%z5@qm=J+M# z_@$;VBV_W%X9D#L7iyEo9Lvp!#+2?6-al~|4W}XoMzA>}V(4rf5WE3A!fZce1^lQ7D$Y!7YqsJbb{MN9Pvaw|^ z44e|88Cq&GJ{h@w_ng2?%kc>5r!yO0dUdkFgbFJrapk zq|SHW%KDX=$D)g2b6!Wo=vZ!Kl`b`2@Ool0F{)4&%^HB9Wx*tl%^itb)N`{xN zwtP(CD@*GOXu;8}?zTLw`tq*)jA+U>%>dI)U<-meI8T&&TAm+n7(?kUP`4QUj@x{} zv;8-RyZhw^1op?TB2W(xA2z!eAu{3Nz3}4q-;7JgTDb-5W*KRoB!8wY#ku4jG16#U znnnbEbhc7#EGaz|F?|o5PM|#7322Cgk>0P~XXZ@5(m*AiPYJZiROTB+^nW(47Z;&h zayrDW|1xm_b=jWo{4a8Xj}iYyF`it8+8!9#OU;sodf;loQ%*3Z+QiDk;*Kp%HN>7w zpYY?S(W<}z03ZNKL_t*eB`~R0N+y!J-b8OxwyMX?I=usX5uL6!r6C?{kkJ}7T;B%j zZiJeSD;@94E_EX%c@TfPRYPiQ>Bf_8k-D_>J90WeX$IU5J4;r7?ztx)bxG<^iqL=l zs5z8HT^hQ4F4$kpP7=BX8aaBp?CGWflImH{pFfX~PODHvR^vf|#CryJ@(jioY3n1W z>ZaiO`)_~o<$b>*-i5*c=(|k6={xrJ;T2Shj+B^=+ePF2@fGVwPL-U#UcxOg2r|AEl8#NG(!PqToSuFghAP1nJTg7iC>ZXyI^dt5?CyXiyl zru)m@LNg#zkkv6(ce1?;=>jeEnIjj_{hRl1yov%+C9GlYBOdR zM05t}={kj3qPpE5o!k)ixkKajZ=s4*;Epzq{tdJHBY$HAKevTupHxl~Zy5I#8RcCVP5xb+(OEK_fVqj= zUcoQ%iaGsOT=ow_{zd|?29VosFo_p|!{RqCfaeq>-MV${BVuds;5k>gaq7m6OE+$u zxuSUp<)mZK;eK9X6J}Au-v}WT$6)75lQGlBRw* zKbfHW+KTyiY@T0mGZy!ABTx%fif^;>GYS#an{ajmy$#iJrvvJZe~;Yshdosqiqzdy zLHbM<5_HK~=k!qI^~G6s8kCk5U~($R&yB^Sp5IntZzzD`k;#J{aqYn*GVk{r8bdf`^olE$^ubu@?~+_Q5bj_W5YR_z{5 zQ8VvdKjd_@P9#tN3D|~%1_A5+q=h0~{`AL$F}|phz;%v--3zO$8}hHm$8}TL+F&nf z3~MU1FDfFN{(4(xLQN*zU0+_nW*^L0Li6}wUTAH$i0{VzQqk6x1LNaGA6FS1R#KkP zM%GQ`v?6r=qUfG4wI0&>-~M>A)0)0%7=Y(P!W2%JE;ZdHryF721UJIWCR-iDi`v@aOy^)gWY*##gGOh~#poS2 zVKJCa^*LGwo)-)-p)|_H*e>{%+RcF#k=}ET&bM~f(GL$s>NyY6>~x?9D^54plM!8< zP6VUeDi)>7`~K8}eeYqSs%@PLVv&7p0|6L zk8gxeY{ka0*#u?}i^yrFeax7_0d8rkl;f+)*TyDv=)u!1O&(b4NqyDroTf+Wcf^)? zx9nUSam>9!{9>?g=R%lKImm@JIK3()&}X&bbov}wLzWl$UcmHUZ`eSGqpvEDe1*qc zV){2%mn|!f-e>f87uF-CpZ@N(G{ZpXHs4M45zb5RQkw|f%Na$ea2T& zeMZI$6E~fl_|~TTCbEOpX%@OXrWn(98by71o|ZSgyX@voJmPQecyq@uzIYeyZ8^@B zO%s<#1tcsRoa!a>aR2@Tq4X=um#1J7CetJ*w|T$nUpmNe4huP%I8tO+0qT76OAYbJ^e^2*`Xan#j06Ys9t+*V>x1MREJxC zkHB82@uwfBw&j{(| zF>Kh-VG#(gYyhFg)ic#d+^Mw$*Q*GV@>NhBXZq<4A6=?*_gx*GYnw6~PG34KoWz}* zuaU?Y+d2g`eX=d)0IdN!ru0$^o}4i=utIxNQ3*=oc|q-!@Jph&FR|%9`V{ct2ndi7 zD!@I!+s(&2Ft?(@=lIFOFc%N=z+uD!U)fVhs_fMJ4hV#@L|HC0#ez@ z;q*N-0|{dsI`n>t=^D%|YHLx#YBTF`owFL!w;F2K*0m`GzTrCM{X3y_!_t*{xocJ5rgbMJO{aGO4PyE1z}tarop$#heWT_MM@&xj^ zwDhesI(qr;m#4zOAi7B164J%!7N`G^^CC=F0jZ&GDE#ibe{NX&MXcyAiq`*{(t9A? z3Vngh*>a&9S+~*Qym>D6uzr3H961W>1yPc4EBMx!SC8KczHzwY%sS&&SS6>0b<8Y&k(zz4`8*V2W zQFOjbu zPyhH4z7|}8EPiuA+WDt0JcrMi}&vE&@$ zPY({R#-r|l(&6q((s}R|HrV6T)hMp1tpN4Bh-5|uH+C1n{=^{KX+gx)gslizVI0n+ zg$qNI;*iQoXB_Q>)K|^Qr%ww8gF&G|gCawf^wKYAIv>f<2l~Yhh$kwPuD*1=O)polBmJeQtF;ZKc|1MOu?_omj>~e2*0kCGyWR0V3~(BjzG< zA647C3Y?)l{&fqn_vB|(lsHMMsSGMw$Z_H3iLVKlD%qoi+Hmp~~ z?9`gnfHbvQOjC`Z)O24W+$e6NsSC}>mHmcltL^6$w?*M#4+x>y4M-0OA%G(~*E3+u zm{h3IHw0F7s|xYnycz=mf;tv;mp2_w-}l|=KYserhL1k_^wY1d9ZBkLAtdpuYb}@Z zGWWeiji^!HA$0b?|L(heb+vm>wRB&mlJsZqz4!k558(9Qe)ic1lSYm_KJxqTe@o}l zTOWV_SwU=b^b03XuEr~l&b?{k>iZZI`CGlZm?o-ldR=Lnd)+>%>8HW;t8d(V7eoir zC*B8fQ^6VIhvg-Gj9Z##HjQI^ilOvPt*xoet)0tKn``o8bF*WLU&tEq+!If(Kf_&2 zoVeUJWAK>d>j_5uf8*Rd86^s=|qowp~`W6IJQ$?g#9 zTWdBQ_?AS*n^z(poATD=fwq)cV>d2m3XsE8gKAFZT|FcTOdcCXk+FlJZ?}F8lvX#(i>Owi-B1|xn)8%(@?Inx5)OMq}TQ#Im zINVLHB0C25l;?hK82#rg84X>xqt%hjE(X$}bo!f05;sGcFWO;l;ZJ54sQf(KkCPmS zi>0R%oTz~!K52w98t3dlMSu5;fBmH;rK__M?Tx;EbvFc+@2#iY`XFLINKltK9Nahc{I1ew(&y9laI)Kv6Fzo)c==?$Q*&ovW zDcy{dchvNSidGB`TfES}$e*e~y52>qg?oG$U1y5uVuS|C_B234R9(N8#R~0E#eJJi+`Us+=S#q=k>;O1TwI49&J_NfH(oKevP`*Rp)s-lX@ppr4<*@F{5i>4lH}_(zUz ze0mB>o{xBZ(%>}BH+J}>s>95B6k{@7k#fI9RW9KSoBUP0A`V^c7_pj^`{ zsJx&Al;!0s`8%oUf%AD+?FHqTIT@I=>-m|fXj;Tr?5Lg_793VsP*}kfjknz%R^7%` ztBYvQDjyWqaQiv>9Tir`6@@yQO6&!81;!kqgtVRD^tfw^nY7z6;5WtNOs9@ig~D>D z`zIx}Zy|hfP^kZ+2_VP>EH221p`l9_M`C`#l};EQTlE2&dw=><1%Ja?4?WdKiP(=| zUoUbv?S2jsJG8iSV zmz0ctz=-f>J^!_Xo)7KhY)_A2xn;8|QX+a4+dLAQDMD0chPWfu2Q?3)tcN=_YN+d8 z;E4Qs*}iVRM5>dTog3xOc6_$W5A-JNg*Youde3mapRdi^trJ-}#FrRF83@V+kVkb87U6xy&$^jb|gQ#29W;j&bqqVOM6?s>OQyR^2Hth z`SRt1-~aZvza=RBgXe~?|Ni^MM~-}d&G-uiv9+=M7}B`m`l?Zdvtl}y$8>mm`nb;|D5lC32L|}% zdcxhFB#A6HE!!=fD!G6qN|N<73bBPAy{Ha|bt zhv38v=v$P&aJc1L!{D3kM>iohdssb?Fo;0AgJ%lUYisw`m3Q4Z z)mB@6s!csccdlGeUszMa1+@(gr)b$k+otQ$P&#V5AX;>8>O@UwBI$~N_~y<1;nXw| zT|jnlUUc3cK7Tem{8;r+t{6O(7pzMqqfaIk&zf@91T*c?*Klg7y(6gIz*8>U^)n z$x~cEX|f_9pW{ha38_3MNa-(2Qx~Q89GG53E^oS3Mk*BiFO; z^WL2C9PL0!|K*oo{EGTfGmgG-lrChit{?F}7;cU2!^wErPGRcydHB>di5R(lg`so< z=}71&cD!u@Uk;;#j%=WT@kM1K7Z;wmKL4M9*EZ!pm$S3`t;p*aRtD9m->$i-f4045OX7D zNUk>uNDp%aFC-yvVUoWN;})avE?zVpWKTli4B{7xpQ!1h7Y7I5id%SVQT(cSw!JP| z2x|ua-4H6i90l4+#{8Pg4(A$gW+?k1k0dvsJrb#!-b{`jg23%M?S|L`Kfjn1n4(D z{eyvYSzHX5TZsM_pw7g^Na^P1(Glhxz2Cq6avbuxF}tu;z=-Rihen^x8iksk8%5Y_ zb~M)XVqf243@Td}t-rC6eR%=|K&%`+;B9;Ne3b_XvEraNg$#;7dZ;Bmp#_Wale zH7qS?*ljP_-ShkUw>y6LVGkxX6|wa`H2``(n{BVFfv11c^f)%U2QPLIQ$vrV!otFW zRn>DbxKvap7163FDIPIfF7;|V8wwUKM9PMV>>0MUF+t>*~*BZ;DHz%5`@|;=emge{5Bsez||U&(nYZJsC(h3=W4| zinCQSPkXzgtLSu>DPpODhpl*@4p>zq(5WSJybv2wZx{7hH!|{#=4ExLU(p#7=Jzavjx+ya>jU|3jLotjx%!=%->%0Cq z`Y%V%n=sTXDrAaRnK7s5E_chxO@PMJsF_Sna|`ga!DV=3QR|}8NVovgk<+n3Yg=GQ z0F5vGD4E0vLl^Q8Z%@ADq&DKhpe<6BjqfuG45Kq%K%m^G@sdGwq}K1g+VICuKmF!k zKK+}r`y!w^9q9a3%7}MFD-4YLI|zR$xGlV<<#V+bmlg9#xC!?viwTt)#li%F#3(y z=FTXh9XnRP=09)OlUt8YT+{IueK`jwv-Kb*dlRBdK-!ozFdZ96lwXXW`;5VRO84wp zTUT4Rwr*`FRial4=HtF6)V!gh>${4I>m~CK*g9;sY(JT_)sZFyR1b*C_44R%STCix z>dMs%pP{IKe)YiBn>UxYLb?OrV)P1U%LmAd=OJ-6?rw}HR1Ki>dPM~&ErkY9wdEJ= zG=i%Amyb3erq|5~^eJ6AGx7eA?Bz1-ulbS=PG1w8{_TMd1$_)F9y{yg$&_Kk+%foI zdI==QPb6tEBrIvvbv36~t1CVq%m>C0oF3pd1B8s_S0Oi=g33&)e(J#V`pkWqDVE`06`o4q)R&wsO;@ zr~5E7a#vBQR~iRtB+byF)Ym6Ex1NW=I(P|a*_0SK*yH}k?w>Lxpp*X-tSG#&zCJ)Y zFRrFqB6YpMA>M3SSD6Pdk_WvBw9%c!2~m28J3jNk5O)vcbVAqxbKZKybma1o!BmBM zW&LyE6HQf}9irm5U!}J;*F^O0gDe7u+G-4_(N$0$Gg33`UMtTt46p_mB zGKc!mA259+`ne1*nAEoq$3!ykyr~dHF*j!P!#G|P$v6kQiZU5TKJyG6N!JtZG8IZk zOn)0|I%>K+F9y=3rCYWa9g@c=LhmuBo8CqTxB4INgTVzzH;fK>-wTI7G*6gr5Z$75 z!FbPL>BXmBd`Ogz&cr1Tam^R8B)x3CQ4a$y!3!zoBMM!@dKhL0ha+rJ5!Q``ML|JD zNsAWB7m4DI0pnI<@Ipt0BW&>^|0Sd5hAoaS*7KC zqJN_D&n^3tD#uj<=Il4Lf3juVCtD6Vq4W*@ht7r4?*=PcK{v&t1ecrY%tQMtk;m2A z2rZqy7)bDtJ;PLzVt$eTMJE-YKJHL^<)Nf@_Wt|hrdRfBk8@Ppv7hJPh%LL(cEb*y z$A8p#t??FsZU#&aoPTQI{1gg0r}<)Fh|( zVb!~NVGHLL)YMc6<;xo87OX;ecO(@}3vE=uIzcO#!mDWqnzSg)Asm*yrKs}tc6i-+ z#M#ssU+pAZz1!Z67;-ZPDS7mE61a=`{nY2Q7ML{1-KoW-=J!4*sb zA4>X9^oMWZp*{~B_n#g*sNd`UB@RdE7AjWl6$MR6(~^Q0E^2Bk>ndQAKz&YWW<`V2 z8tFxqlvG*71Hqa@B#ph1T3vfvO^@H191NU$A-0y*6f0Gu{b=d(o5HZXxusnL>K$w`ZmxF0Lur{Bd=Q& zZDG0`>heZWFZ#ee7NzT!t^o`qTbocAT`S1nzu$mJHoqTH~AYHI+z?~zC{!+=f z001BWNkllwMZBx%?0+qbh`-EC^x_W%0Vq`M%df3&yD{=xd=4(#dTbV0h& z(Iun<>3i0;wr*NY`1*IJzdHB((`UJq-R{pnzxr=~{@`bmMhrr$2`&15esl8dh>qp= zO`Q1Ul`p~ciDOTWJ$ceNUPS4%Nw-xYdgi5}rW;IeD2we}&d7k$>+4JNmMu%&lUG+; z(@Yp;O-)XxTR>EE+0Cokm0i7YlU-SJXLDyv6r3FWT0iW&Cr)ls68S)HUJsrU<+EgJ zr>06xS3HNGmph3mgJ;s1C#N|tFSRN;qV+)8)!63RSUUIY?aJ@^E`NUE{1<44M1(pK z;+qFUb0LArAyJ*#h^W~+$>a8_!k_;61#B;$UHJU!l`B^|TO*hnz?s8_y@m0m19?=O z9_a2a!88YF4}(ZURbmpzc#0gz7Bw-g+cT_J06y@UGrfH`ZGzF?z4-=|E;)Vv)tJdY znldG1Ij)znlP7z463G}yl!(9_WHf58g7VFP(s5^Nn~Jg@70BuCf#0SqHYL9z1NR6% z5DjBzSxI_1If;Ime!hVEz=7EB!F2%C9oqLjCX1B09;nWkNyy8dI!JwQOB>pGSNR@X zCyagd*YmN#v|+gKy2P*X-j)Kw)PeLnoNfXW)rN>cQ7Gl09>naV&qNo8)5&mArzQ~H zI9$S!&(YfvpFP42?JF||;^$VIi)jF$DpzkFnK&ICow0f|^A#SyiL5bZRe95m?FEaz z;%@X(Fl$kuy8b~Fuus^`vs$wx{lSSdajW1gSsD>QGpkli$TE92KoogRGKL*SA4mOHO|V4c+XXQP_(?b^I?=weY0;;wJyx zaJtp4=uwxD{uh$E{OUh{0$2Laal4S94yyy}maBZ;GtapMbt2SV#&mgJ(ApWs_dB`JSArtK)+hU8^OH(ELibRpew5mo(}Cx_Gb=FOQgT0!)`RoeEOb zlNuo%NT-5SYPzW%6`|i@bjnAGh}nJ|qxjay?a#ePKUbHQei!6zTrc8uqo)5Lri<3u zJ%mj_(9Xd_>^KKb=k<5JQ4U#I1nN2>n2_#`@s5Rf7#zX=p(+X_x^5w19F4)Zu0iVT z%62d2w_?Kl!rd_aLQy(Hlx{j48N&+#YXL1OAG;g|@4{)0 zWPS+sypquLIH;+h34If@i}TPqe}%16qS<(zuB2Go;dGO?zWBV`r zsoJ@}k{ChU=LJZ>1Y)<@ZxmiAjE`3>=BHXVR#FdOHqXjAYic3vL zO!vk10-YCQIeftzJw0XqSWbiOHd|-avd-A@g81EIQ$~el%|(BXFKk}cxwbjBt*oNZ zzWeW>rvK>S#4`C@D!TG%I$BUdprL9;vlcB3n`3~CO(9Gds&14dP5j|aG(U=ObY4q3(%yJ2X&My>PEs4OxdfAN!&Pvp;~uZ54x-^} z<+{EP_8vEFz_g$N(@0AP*69n`r_X@%NS%Etj|0(v{Nta>@uI`KFeLX4Iv%=YiT~(@ z{X!jK_{yizO{u9dbX`$(H6Q5e0(n{5YHIRom_NjYhQ?vcDH=yCWRbGnG2f8M*x1xo z!}ILoVCy1dgAx0hKcl9T1cdX29T_hJ2HewIpCeJT zZlwxT%Wv`^qpz-d&jX>6IINaXKZf&=M zh&YfDhSp$xj0$hv^uKo4gXv3WLmIZ&SrtSw+EQXtqj0&p5wk~Z2uI+9pF-T|kC>1~ zU8&&^0$)5yyhun$1;=yz+}xvb-O%@Xg+#^VV2JVYq!3ZzDqh(lIX8FT+!X36-Fy|~ zmz_(xc5Fk^{$HzTl+n^X`umY1lN#xA#6U+ErHj$K>i6s+WbewA*5x}%Q2*0uS=B}9 zfBI9~)vN#Z`Jex3($A)j;OpNxKX$o|3P%~zCm#LMsObczlgPMf4Wxcd=JeuLwhVCh zZuq8UPHz}n)_kS8xtWx9SaDBYauqpxwRB!uo*V6#=~-2ky0-I1{?(ML%~!8pjn)2U zb7!Zmsw1SMc=gGP{a$|J{D}i^y>)CLxJjuWo)dYr#cQNqQ^QASA^4Qc28W!Q+B}-x zq*ryavhv!iG?J&yW>-CW`t`z+*Tyc#)K0iSw&zTb!R~{rA|k5T(kd;dKDu;F`m$xo zS1ur@fB)I%pA*q|j175s^3q}1Cr@rX+5fS`sDK%RQPTqr zmRr6I>Alb-Mhss+a!A-(!bA=_rIiwijIm{9tNb2w8#~q~&<8!8L2mj!p*jKTV(@w# z*DlV5)_dXa5cDHvqoYerr$MbsNx^h%FLak{*?XhBwsdCZW=Z5b>u*3^ArE=d2SN=pH3j~Qde%peqJvxIXE50CKh1rWM;94E|zW4_#VVj@?N zBrgNav1h~kV?pK7;reGWI{F25VLIj=F3RU&i_J~OVs>%> z(T+em8oI(=Xp}T`SmH2KoZ8FvZ2+Yc_JT28UKa!EQq+a#aI%U;@u+~)W`NjmqtH=V zjAj_Oi_9;k+EjwNnjAg%b1Fs!^oN5q$>JxJaH+)-( zjN4!2`I*=k;M^7Vq6G`pk<+E88_$b;FYC|udE|J}bVz+WW^_;+eH`Y#mp|O*9J(l- zvt590ko-ksU^hy-E-)9}{SaF;tT*c6I9N&9iotP|aK^X9qcU-INhRRi)Pv$3^0D ztc=_BKoE^AX;q~BLX})nLc0IZ<+%1O)3=NZ?Y1{`wOm&xqjMWB$6Y>zVV$O+EqkwH zOgB+6AUQX+6m(hC%@F+$7`Ll$Wf*NHOA1%XqQNFJYHC{0&Hvc=(I4@j6Gi(ewd5eV z*&B-sLb~NbXU2ZXq`62$H^V9$dseaU zB+u-p6DgVC`<*4#^Ji@=iz$xD^`-kZU%~j&QPPoLY`$Y(%fNnCobuXOHZOA?^&-@I z;DsDJe{5_?SQz*}YIh+riCbzXLOZdCe-}(2Mi--shH6CR`kD&14pcN0=I0ld;7kW$ zs{wWRy@qV@e6|?J7Q`0~TIdW7aXd9YI@^yBR9;!c zL1Q&xj7Ro2Vut~jsr78jZ*ac;{38pUMdO}-{`se#8YjE?It6d=*Zai>AAGUzgOC3h z6TF3`j78@=*M^Ur3Dv}FpGCD!jSXGy2?S*DwD#BrcGNIADl!sWSiYdI%Ih! z5$IuYN$sJ*xYFCF5#XMLFQQ? zAzIh4mgGw}(9Tr^=R$TM7;XH{2?4la>3gjnwZ_!KRF6QHM<@X0B6(1_io|TWO_Z*J z+XPJ=QT?7lY`qCWvxbKWphZlN^w*M_H4h-l(M91>!F6+k${bp1 zy6F5Te*x)w3S3v77acNG{b_hx4@+m8uorAE_`s~d84_nktIH94<5X8s>0<2k|L?ld zzlQamw`S>5I3u8QR#`>tuwKPc0bb2fZk}o{$S8=-R&$`gdMgt=$ zs(!9aMljtL)oIAWE1@%oXbHH1Zt`3`DmOKtYOsjLi(Zw*o0=Prd`y1UAK86$t+Mic zwn4{Pn0{J$jmYTx$mh=K>|C~t{jy~_(fi0yx0G~odco&^`26!f|7Oyp;e#+rwq?W= zN7tLA^od^{_;M3+`WjQUxaO@jsv|{Ck0~ZekCa4DTbiY&?=34!Nnf@$r><*XeSMuL zxhiYXaBCA}Gw{nyOHPKV3_L`%=I&+2) zN;lNu1{5n)tbFS!(#4IZ-LEZ%utPLba?f5t!3^d5|SJ(0gFG zH)=Zj8eO$?CR+gZP=nA`+jXODZ~30VnJdGgae5ThU$5w*h}5EVK>fOl(q(hGGk*E( zFX3V!{aNMV1kRvFG*N(VTrNZ{`Wy?#;&RLz@47^8dYNXhars_BR9k7VzhZGl$Gle7&tp3aP}|*=sK8! zj4u9{3x*zLu5SaN{0G;IF~ETBvZ&7+asD}yT_isvdq4Wbhn>@408>fEkHh1y-Lr{27D&F8DVhx=Ccze1Kt49hg2pQuU*Z zNw{7{&}bA)AHN=J`ulUnzqdot=skWHVEqj(e{te{<)Jg=Jzo!~k6%w6>H4kfk54_X zr$mmrIDN$WeyR}#)TO0cm81s`UzGdhurk`Y{faqLt>#8Zu<8<1j+s+XT0r7D-cxhMP)YN#*+1S#892(pR(Zt8^ z{Jr6WA_p z=bSB{V1H2ssdK-4EJ@YZ3-&hb?WVbqB=#i2)b~5DkuSCPx=iU@hp2RJ2BsU+i|RGW zKp#X-y8ndgl2x%8vGl=gCM1Q&jQd=DiBuq}vQTRWoy&p_d4t`CydiW!I*~6{<|2^p zGP-EN5V~~$(o=C7EJ~m7J zo5%h=O8p*AoNsTU37Wx8}*b6Zu#^x7hIUFS=j^Gkf#-y|7)Z}N>Byjd3<%=g( zS7cxV?mf&6@DXU{9~M6Ymn&UYXR?kc79XiI5de9Vx>4f_5Do+=S>|)c41` z280%^d$8|Q&;MAc{`~WgKQA@$#fQ`l=EnxmqC&tAE(fE|=Pr}*T8sZ(@h2?cM6?O+6t~jO+$mMZ3Zv^Icds}H;S3?_{GI)TF zc%@+yAjwnCXFCQJ1BBQ+oQoED{_pQiAC|jn!jOBOy4Or|G}Y-DKYsk4L5p9D?NL{H zSnlt247Q5SEj7Id(C^~?H^ZWHh+KHfj`LX*aa%Nu=|wuZOC%R98%*!p+ZbAukZxjH zKxol1JH|smvGAO#2Xow)zMq5c>C;cDHJpyoRy{5ZO`DUi{_x~L1U5m34La z+)uaAGc$QiZLQSw@{G>b*5>BgI+9>~u!=`#CR8QQn6a$(28fP=eHB{2df>*Ds@bHm zL=+!5dGd=Hn+IcJY^4B|64dl%DD}9- z`J+cAJ2<_o?K@dt=8t;q0Dkw5&SG0;CR-*_ZIFFbOf(X^SKivZJ*AnxwpRIG{vc4l zaP{hyR)7)HOZc#ew<0D-L?EUPc6aw7w+}HrAxeb>0c*><_MSTZ%~#lnMCspL+GC>@ zHUdiD?86JR?aYohe?fPqO;-+FKu?cto$c-$IJti`n0~VVP!IY$=l&np@XND)v|Nn?fmOZYfiQ7)sOGq z?zVdH{jZ0S(HBrEN)9@@_<}$sxnN_FhTcEASSD^Dz5jx6Vqj3z(bZRGVjG{inMzR= zH$O|ID5ayeff2@;L%t?O2fVM4xqL9z;7qo7tLac$YALyk%1(Ew>H3%Oq3jnkk0vpx zndtC$FrD_XiGzLmCq7Ikp{3qYK8YycIR8x(Qj5?*brMcR2I%SX8eu1w14a*l6W-o9 z)0KIi?S?#_sDPFLP@W8Xy*tFMGw5xkzDAlDYdctohoYCf2g(Z1f<_>nj0~j9kWPxb zZpQk^bEF(1%Jpp^C0!~ydsOv#yZRbQ{biGf2r_HH>5r2AO}3%}UtIO2aJf41`~{?Q zN@_Zku0X~|1?qUDmRmjVlFTbRG6u%4DzU|fbO(eQS>g(TUr?K@QV!C-E1ilE< z&yU!y)bu$Aq4aGR$xT1J;=P0Ky}gZ8M)dkQbEeK&@&1ZAPri%;9Z26wb0fSfmNi|5 z7hEsK@**u=#ut~C-lL|kKmXK={E!$>KNxv@d*2tu-w%nq?{d|LiqUbW>ny|R92ieJ z*U%MZP1i7I-${C*$&Z{Yh@9AR7hQ`ZGOy9GsQpM1=e0BjU&EZx(&P}NH?^RHmdr&> z|6bO}g8T})-6U;E!h#+zi+Y8e>FDTXaQZ4)UfMXg-Y85*PB$Sf6z9do;Z;Ak0qkZE zkRPJ==%I0Ri^R@Oxky7d)^zM6Sk2+y?(2Km<8~3FL-kJe9^GQbAxtJ4z^yKVNN7}# zfNpQOK(nF?raBZNSC9+4Q^wumB6Lyurvmd+H>9THP3McipgO|2wG*maY|f$Ncg7!C z2g-c>gb62@pdZrAJK%#btXz zO!v+n`&w+w##OPX=}e~8`N-Eu?F2t{#?IP3D|S@;sH}y%bG^LSG8*NJ?qcitkLvlE z{aYMA>>idh-Ja3lj9WwoV|+;=?Oc9(^8oqt*wBB%-_!TrB{w>x4&FdNvZW)a%NN`yGIIMpL0MU$uirDSH&O2k$(q5c zf=eFn^*D)=Bs!ov8~Xo&)gtU70mqa^7IWVcJO+BU=ubUe0we zPeqb_y3LPcToMQ0ZUf-{zEv`fmaFR!dMGsjWL8%Pit?TWv<{N zb@xsFI$rV<8j7Y=m9wI3POuXmq8 z7XG53!|9;0fIVms&UQR6f^jN5b*uvyn_CO!gxK2xb@Na-Fo>=vap#Gd=V=(88(M0* z^nC;in0hS9CC{*$T;QD-r0c zXM2w&i6jbjHqb360X+a+fb0;z=qTFec%t1ACgCeb1%fZ^O&KXAl=KV{&7BG03n2FE1ZAvM|_zcVN0grPI?pb8I04Qwl?m+#=lNn{Ph)b^DQPubmv_ ze}rzNr@z^|xBl4$KACB$V=&^xEGMBQb8}{TdU93vOTu)E(mxsX`M-Vs`O$ZOLnPzz zb?t>O+_y=ZIe!eLCX<=|(oy^`2PSs7x*VxlsIM(8(+zKWoy;{Yq_WN!v#h4PzP{^r zMlM?_JC&xGCJiMMH%~el*lS~NAfy{b{YLE711Ri7CPqZ1tbXC<$=BAu{CFS#S5ka& z+t_@)a&qbbbsRpns46#nKcs2n&+l9Yq?3P+kWN+!f6LPMBx}AhCaQ0lU<^UvC)is)qM8ZlpBL38qUhlRH@J!E`uti0M zxToZYMC8P#c=bwjmk}L7-Nz%5E=TZp-9Gvp@dvg>V<;KeLD{SLQIhe3ffCbq;&`d2 zWoKPp9b$Udsq*quM82<`N#&)oQshZlKqFH0blfhNYEe;|+V(Aw+eN6Z!v&DIQtrLI zk*LMx(0SnC!82GSXVG`TF~Sj5BMP3&-eL{;)0wp(sB_wM9HoO%w6+ITQKnlJ!ea%} zEkI{}p+T)XuD-?zcxgK z#CWgl9M`u2cs|aebU0mzJ`eMYk)8=d1a76B!_IiomB)w~M&TnS+6ArG6iGtr>`l8; z!|8ITo03!FVP57Y+zg*O>oB#YVs(l^v9GYFn<(~lDduva1MwVlr&wT~n@8g#*BFk8 zWyEkWT@Lc`lSaI^O;+?CHT^!JI$HV{U%!uVz8+tCkLQK7m&1p*9$vAYCP(wIykJrv zE;)Vbi1mY@bjn1}Y{O2YYaKp#aoe_w@2QUT;$f-jhey2pj4)l+bebF8eYZR>c+!nC z-GI7bbve_;>N;Yuo)yQReDSH?Prd%)gO6-KetfI{!Q=BD7javlZoxNHE@%2r#pqJf z1>_Wu8a6jqw8V5>`R==Wyy?}|jUsYdr(<|YDmucl>@G68iFl2r001BWNklfMF2c25|M@uM)mA`6T0x^`qqJjmZtHj3Q^G{4yfu$M_$M@?@y zM~({>pqJaX?AjHyq`HeZbOpcAk95Ph{pTVNQTQ2Gxyu>fl;2g3SEZ%l+PQO3`sK*> z{YmGpb$7S4HN;V&iE#$)ynO(wb<+Mw(${Gm(M9D67q?u%e141FghKDYO$SNoY&<{J94(yP&2Q6NCzkn>a?Bx9`|dDKYa$&5C_3-zE=? zcHUCe+1%C{TauFOmQrSSjH;2dlXMt`pJw;`zWxo5mwM6ev#Ef1!qA1nZ+oE~MZM55 zy=Zz^d_0T!H3IcgA9{P1#204dHz`Q6sjz|~eS18w2Te=ksD;%Tu~Oo>!~Lhj6$27*fZMuGDFh zmkqt&+xL+HL;OSgMNV)Oy-v4AdJ(Zs|MsAT@lKKyWj{wlr_HEx>B02&P(G$8{Fu_& z0ECF%)=V}uMB<9WGfz@R}i5QSesXx+l#bq}OlC@-4F^Ahw(?*WmL(y_eIgA_x! z<$f_@I#ENSYOBOkE3pRaGu+Op9v$6v%zYW-i-B}A(XeJ4I@Dzb>A9J**EM9o*(FRj z@;DdJiInhk7pF%utR@hP!xr-p&1@oU$q?orJS5%zzcpN69}nYA&+$y`A3JMSSqcO- z1~+vS*qM`qwyPfGY6Xvfwin_st;`{BMruMrUfSS@D!SmPx3V9c z;*}tetkgwvsENLaUfY>om7ZGV=H;8>OO4*DqRJyJmv9k{lb#zAjkt6sS_U`Sf z&)n?e89-=wRcj}hzH^^r?X#!=~u73K^M~X+bi489uTE}slPRw zzMOcJg7?YK}QgK@**WT-U8|?EB5c^mhRS%T2 zhJ>8vni@KRCMUZm$a&%8hC#g+J^haYb$l;ZT3aI)B+i_Hv14+?F9(ME__W%5DMHOm zON+`|M(HR$jlgr)_?Js{djhe%Z0eYOf1+>9eMet8L(^4aY9>$lQET&!-SHQ0)Lva1 z+d1s9ff>}0j_p4s(95qTCvZkcG9jCibG-=8`7q7#T6$Ik`e3${1PmUEDn5A_ zUKm&&-@G?lyl}Yy+fms#(#_8;0?>_|t_7WgwvDlhx_g1`p;_VS56#O#cWq~>Pz4hRTzC6DO^)t@>l5~4 z_(dUas78N8L6?}WZlsvhrKEEn^@QzsRlss(n;)9qlwUvxBTkRo!g;DL9al-EXy3Rd zk~YfG(y_fb>36it8G0zLa(`oYw>`hByS@Ef)445M+LLH08Be}QY)x}535x(azLt*~ zKf1-vQqD!-j6ayY5yM&Rak$8VE+)Tl>ti}HD>?lZ;{r0e1?m>o>-GZl{{){4(z(j7 zKc=BZV|5s{idz?dF9SK8?kFjs7B39{k0UILSEiaA%dq&y_BeY_;qlNl8UQEG$fVdVYOo zc|JLdDC5-IK6_9MhBtkM=FyV8{6CAa?DiDBQzo9QwOLQ6~zS?VR9Mwdga1J z&iIlrnjMXMUA7mII-Dk%RGjYW4D(Z29wbmcGCgcDw&4kjXyE?(x@n=p^y#!SJyKK@ z)Sk4^K`=X^==Or^=;pL~mF>K+DQ;mk56>CjP@b2MKT2;LGrkJ^^A7cd)#qGQ)9Mfa z^e2TDEt;G755TWI@67+_<6&jfAGfS7_dYOv?yOwzVZ$a*=I2Ab4f{uzjT$}RaRcf< zc_^sR`~UOW|7YI-mgUX1RA(JoL~hOzoeOPUl+Kd*7>LY4T|yQ6^xXv_n{$on1i+O} zuCPV$djKWLvb;!i*9|NU{3*%kCgg>yP-RNN@&iK#DeYwmXf8}wG^jA0B{|dk$}nz# z*ht{8wL)49q{G|RP7laT1q_9=r01kZZXUl`w4Mpi#R7F}Ej@rOFIbD+s z1L}G_Quj%GSu8D`;3)?kQ-gZ{|8~5v>Ylf1=?u5rD3AWRt2UO!hImIIlQuUK;DUBX z|Ds%+u4+4Ka1EirlWqITeFMYkfdkbi2g0q$2f4Y~A-$^T>JyVgKSZ!1LD4XtfSd15 zpJTq!Ia;w>0Kz($?&EVZsj{-AcF(2SmLngx?*+mNl8#)X`Nu z+?VMa)p{klb>(-zw=6H8eDeEmRZiLQ#;cQl_QA)~4mnQ(<_tic07ey&F$C(g6`i;S zNS8Z(d9lq68gxr5EzOka;aifH&D3CoMJ0?0B z143Tjp0yN3E~~}3gWE;O4trOnBRKo`kdmHqlU7GOW4rz4f!0l(%WH^4VH-sPyq|-W zKRJ1@54e}P*7@l8M}p4H@bi=H%k zz`eU)PAQ#5vA8JLMdld`)g^IT126jKQa?pIy3RmNua725u{G6=2TG}MFALJ;&LK;Z z7tpBbOkpXokSiTX*I?4BKWXXOlhMd|G(+Wq%kr-2K={n?nI4IQJ%&vo`f?bFNFF|z z$S4aPOvs8F`|=NimX3ah8J^7z{cXNcl&TV5i6ZVz-D)-*&2%72TQCBWXHS{(@X|y% zV>H6OnM~6wQ5mRi3WyQD%j@FND=~upqy2j&_DbXiDjJoNPRVEp?yOW>Kr6EhZp!~D zkKgreaL1Z%SpA8YNq&LSF{i&Q!Zu!!C+CrK4y2!-*Js{~ePMNh`VW*Yi#q-nQ&sA! zAqB^wbmGxpoQIVDBFAQD;kpim=Tgf}cB6vOVRkrONUoMf=ckU?PVPFVX*kLb?R(^i z@hTpDf5$d9o^9Kqr1Uk?(OLfD%ZXp?P`e^oTqpvSP`-XVoc{Giq88VWv;f_tGNQMS z7)g7hIsHg>fzscTLN7>v`@Od>(-4V*(y7nPS-)ca!Kp8+oe`LRamDs0X>LSnI>T6A zT)r36gVbepaUC5#9J&5{Zx|hTK~L{PSk43I?-8a0-C(yC7@#?j&W=SRq+4RTi_mpV zu84x8qaIBEQLv-Y0WLX$zjrtmEe;Ewo-`T^B`GgSkba>>esx?6(2U0JlC0hHcQ2Vx z0*sxbWReU*gzbhVWidkLvc1TnUREIM3+D8;hHfyOJw}yX;|4hjaD^zi1*>{Hh8H5! z$$kl~9One-@vSs;w>31LbH;7i)!yFM+3rM4FDNf>h$r5<0yA+zc`ZBQ&+QkapMTUy zMUpX~t3K4?baP}t+Y;07AUf`I7o>lLZM{*dJ3@LJ-AHS1+)>ZvZvoCl=(l?K{MWaR z969pwk^hIfe*vrVzSDm3Pyz;wu0&7-R74IDf*LiFg5e}Y!a#(u1q4qVM3AEg5Rqy) z$xza8#Y48|jaTL3jmby@gHk2N2(Q{{|1WAytj7JmookATjg3ZkF0sr_RxpPl0SyH-W$?DWj>FJ83ObuDRI+qYj zCNNB4=r!L9oKpE2zC1mhJOp-Z87`ktS=+XnK*0hV{5(2 z^XCVb=PwyOC2QNrEI%3~#fQY>Z}&^~%S!G|ZJ}`zdjfc}ZZgw(wl3;PTL$`5$)E{n z>4+n&u{*#N6tL+X-66dR#`Y2tP|lVlV{a!bh6;_`8sGo#lvw_IzXNIMYvvdV|IU>8 z&4v8iuvRc}qW6M_9+H=5>QwjTx&D^e{@rOi7yf$y#y~m0pWv^2e+$w@wJ`d9AlGGK zu3=rl`@MrK-~2&)QpxBrw9&GKz5p{)x{NI9LppLa?rtbufu2U~HfP{A7;jHvpwr!vgX1#9Shn9y}eFUrg@;B@mE z?vc7R;WU#5ZP`6ezpts=F`XVqUIKMlUo7tnoX*sN?F>OPSTjkx3BGv@e^S#^$Vzv2 zDByL=~3bnJ(v-+G?eZ}#iUrp z7Dvd>;6oP`u*G<066JR>f;yPqqijY*!NTl9M8MD2G`8Km{n0Me^u__&iTT!}0Ue== z^dnp-q=f7x9Azu2ay=p3nUPIRs_=xZt(=$t`GLX-H(z@0?_d1cxyJo-@5t~XNXP90 zri;?C!GP(TpSP|&{ycKJFdh3itbSgYeyp#)wa1rY8U->IqoE#0Bz1Sm$xO^d&t_JE zV`aluC|y;g>EtpV&pUox<#~=y5!JDf`pfgZUV6#v!g?kEg^neOn@Y%BCxa5xN)cV2 zV5Us!Mges>(goUr^gKA-Eru5I?uCxW2kYt#rr+uaFL-D3V0uoX%neK=N)qu5HAP1H zB2UBViLG0=rjYWYz!#dY{z@;t>39&~CEh9_wb@*mAe3O(afyg75~c&`uNg!?rtFlX zM>o0Ci0Mq|bl*K^9zXrV&n{g$z5CTS-ay)2w=QMFJN)0fM%-lejI_y7QBgaKohLd| zVL)MF3bE|+yjXKICnw}wR{^@=bc@!Tob%QN)iq}qW~aM5yA>m&Lwsno(Z$({;6zS` z)9G`BP+e^k=sMuYwmFmb!)}7-d2Kk^_XI9m7DyQ8(W8_Foj>y4c_uX_)LfE{!Yd@0 z#r>??AtZ9#Nw<=2-D)6?v6_@~M0V572+*Fjz#OJ8aB_=*(HXG6v$7De%`D@<0QQB= zcH7HY02)lEdR21z+q#Knqh}Af6&6!X%@^5rCTMby9oTFRDk41-6cIBh$B){O zvM(m%xR0x`b-9oQk2T%JjXt34W^i=LiP@rOUG;Zto@_YGBb;2EW{8w$xH~zxInQt; zx&=Hp#&T)pd}a93D3USAjj(i5=qV^=5VeH$3zny5w@JG*!1S?c6Vn9Za?f~s>v1UQ z{NBkvL%NIBAxf94-Q9Zu*B31UeTe=>GYL&6I~_tdL*5u{E+78n5EiBYQ*$YLoYr0)R0osUpIofBy~yY+=@G0Lb^31r=O~AAGJ}OuCa0CsP>^z zqc+Zgw&`%k;hwSO46TUf0X1EiZXRa;pz;$|m#$7&O(Y{p!E2W2w0C|BC8Vk# z#f^@Vo^%8RZQ;<_(wU#z`Eu^u`S~Aso(QA(6E*!r^5u>e3Fmcnbs%~jin`qCb~(MF z8w>fnCq6J0q+vA;eMy%;Ku@P6lxoluA1oo1@yfuw#?*u)3Gf}==a2Madf9*YMA$%T zasVBVZo}p39m?pt-H~*Sz!g&=YU0mL_fYY<8Jt-Kqo$Lnb=f#wB$o4II9)~;8+W>xJT5#vJv@JT6s8yBdJ&8( z2F5X#W%E0m^$Uo|Ug!wAQ(P*@AO8RPEuK$wnVSkN(`|_=(3%=@(OXhi$NSUl$}c3J z{TV3d9W}HVO`vKtF|$6qsJ^a@{mI!m_4EPlZK&++sIN>8Ndoc7bUa^~&{dIyJ6&Nx zN0NH!H`|qjl-`9grk5!q=pNiZfTSMZTiJp?9J>r@iK%o%+BRn1__cG!uZ6@OhS3j? zfpSFZhYzoP?C_j1e&yv$LQ*{^ZOhuWjl4RN()kk8&orT{O8bLIb*UO?X-Fa(o#Idq zIL=!FlKqmog)cPw2Rf3t7lo!}=WBXb2QbxQ!jN1=yMTVb{^ashlHW@SbxD=Z-h-mnX~9|F%;SN#yq=bVIY?I!DGm zHQij}#HiwA=kx6tKXUXGW$TYrjE&scLS7@K%g4e{4W`wY$dI(|K<4?A#*41o89ba7 zjP~-IG-}GUCFO?F!;B%^0(MzmXl*3V3=ikW?oPK>Xi#0CZbxi1aPKH*Six&|-k zp0aM2)AhIqFF>$u%~rb>)!M9>H%}N?)vDx;oe98&;R^#?~NPR-$YFR{kd)X!!FWk z6i$C$o)=s%5c@wo{`~3n@0^Z$=W)F0A9E{edNo2ijfXg`H<(TlQ>$;WG+pW*DUPL~ zrb}jyOO9)zM^7=LX@+b!8<4IMuW$6+>4DNCG}CZ&v^5n*H80=2^TVM>SJsBFKVxG` zgHy(X(8&l#c0@=Qb$4@&T)bF}j_gCs3y>~G&r5NDz4yeRx*Ycze5biWayoi?L0l|} zI89AtzPK=v$mEGA0}NCSxd$=sTaTus+}NtXmtQh|r3Ce+GjEU+7>YX2`@EI@s+suW zBZ_kDV)}o7|0CQkk$LO#mTlVPQ5|u{clt87-T(0T!O#BN52194>HKD|%S*X&`-^Lx zx1;W)JESe#EZ2+s!Uc|rEEB65aflcQr3_KCPq*SLn} zC`V^!?TEm5Ln~CEGY(A8R*1_cD4ps|8hlcpDNe_it*FDovpF%;39}Pm+4NE~7Mq(%g`D)ip4>XpmI~tmvcGsc&zMSJ`&7*j(((v)q4b&%ktM;siM{ z?0*d`lMAQwKyqVvQClO}9Y`mo5m2`@^`Rl+1;=dM_~c9I>D&eVT!0UF57Rp5R)-@< z{rd*Z@2Tk6UpBrVMO~CGue&(iDC$O2mxKR^;n2t4_7i(G5jhcS1h}4vj(sQ)77EZV0I@vBt3`0$4w2dAb zwUV4VFkQm9QOAv(&WT-2pJ0sX=)AbPh2UXLVOHa|SO6Qu`02*hg z9W~~XE}7B=>0L+g0idSS(_V0zn_Dn{?rI>4?xDX%6(@)AGDUZk-NEM->O!hM$rxYo zyf8YF@UD=ti09?-{<$>`=WnH&3Q~1D+W*?G@xsvJXx{#o-h2!aRGe0j$k@$7=cwmz;f8tZ=GC_b*pZ-Dp4GN?EeYJ+n1Zw;AwT!Z{M7ky zB>Gin3l8;sfy1F~OE-_oPhX#( zPpRlmIbC$bpvH9C=9-S0zMS4if^_$2H|}rXKEi$Y|LeDSzRsmw-vK1(mTuA)D+v;7 zNi8SMr7C$f1(+2L1f#>bz4MdmiS-RGQE%D6S@;f1Pvfk1(h4{?-Ha-<_?G_ps_J)-r9M> zbR(xehTrAkM^Mt&N_($bQcfSPF#l~{S$=-#-Ra+lalB*+N*Y>JZHCjFUoak zsjTno7KdXw4@hVUDDA4KXbDh-DS?eivZZ(DmseEYWMZr*lb#8k_v2kA&WM^n+DPhC!fk&`i;skI0k|E`EkL)x z)&TCXZA74}yUI`U$b|7EqMPu}DWd^z)r8s+eat8*UCI0Y)1YtJ%8k%1BIW{=j&EHu zya-((prc2P^Y@=JY7#}7mgB{=!}S~vVHZ+LKt}f(`0FN1nfG+Op{UddvI99PS?$OyE&d!t1Hm`2nhTm;~E@xeR zF&@!Aw=av*-#=Dg1jOwtZY?I}Ww1!yZaR*27;oZ{%b&jgnlZloKkt9J<&{f6eeq|X zeRiO6zvuPc-!s-0)O51a5zw)^Jpan$ChO%N5CRGNAOHX$07*naRN3WCf2BHNQ^_XB z2&N4=riS#(Tjz0LyS46q^C!gmrn?Tfzh#O zqdgXHu8T@v|8ltJ%BL2cycjVV`@TP>LPvajjt?Hspg>k)`ls*z_m4h0dNf7#kghq(-U(VZ z*4b_M?jK+JZNF8iY;=>8OszQ?;oYGqNNFK<(|yMv4`-jjvtkoYp` z@{B|7XIbLSZExsyY33|EduWd{YC4|xJ+ivYTDE5s0hG#xl$?(1W!0hklrG~qkiU$s zN@FcOog1ZlJA>OEF)EzZhH4lo9XZ{o>E021QzIet%*Bv8a=H>r@pa|!wU8zar33Fi ziz72#a3SR!$~gq5FJMOi8{zEc=sbO0+SrLR3f+;yZ8%=|-SObdhNmT##$c}WCm{G# znLYZwA$i|sx`@gI>nIaD`!S*ueNs|b%fyKboh7Ba;XQX|e-?T=sg0s^FrBVPxLp+P zxBx%AlytD3Y!|9bZO#kW|H3{WCWVOp{4NuIq$UaWzXo^cpNE|At}#*o4n1?iI0 zUk}H4&YETu!bn4-nQeGzFsAD%hGs+QuU~i_y9@XI$%n6BkgHr>NI(2=#iH3%f^M%} zVO5ZRc+&G^J3UAbTb>uWUM}!sIn&=%^P}1o{p+dnAccUOm$+pUh2NT#Y`20ce9B_%Wk zoFYCC3JpmWrNim-=cA_2?LCn^FhI{u#jTvU42@SJv06j5qv+|frZf6(^)`~of){<> zylEfQ5WxLGFD0bPSfn*6mi5ClCEdTj`wIEic-uQ}^}ZYb0o_M?t9rZZ&kMTord%_d za!mrd9m@@)4_AqzlMm-B64FA93o(q>u9fy*#dwYbT?5UWeQO9Ew{PE}V^CdOLGqHy zxHx*(Ma9)$LpHy9xBu?l(wjFgAL;rOoa{>K0>>M-wT)cTk{@2vN!49ac#ZnPprY$- zXvxo~%rL2wm4W9*oQ2i{JfV5+#xu|ZB97lkbSIIxD}uV9ygDvFJ3GH-c~s?cOHG$& z-JNcv?zV`{%fr)gz(lxGbt;7&P}k|-0@Ek@=7Z(ExxjAA6=Kun-KI!%NmW>KImzjG z&RbUZE(uO1?kBsfl{!*tO3yRTqKQy%(k=4R8|aSI-J6Q#1rxh+7pX;t%#&|Ye9+fB zP(>YSd=;_$0a)M@0;<4fAU(C0I*HWYr1}ckZRi==Lb=4eG4s~0JvKzc-{eBz1|OpS1Mk^74R$gx>hztgK*)0|Jo7ySr(g)I~*T3z;r(dUr=z zUrlL$V--dg8hN!OwA9eID*;n|*{0S?{PvZV3CY2w1f`cJ2ZT`HD!7-~2Q~eFOF7-U z*-O1zf%HG}oZCVSk&mx@Kwy7pMpVcsDe809WE+`%nCiaW^I<+8Mq1AAQLUvwKXQKw z1grt2kDJ6n1JH)d!jK>k$~#`LR6dmW3 ziu#q$c}c55PM4w{=I1qszj|5`e~cf;@pIX&7ZFUZl^ zA-!&AL%JxD{!!4p%6@`tn# zO}j*-J;Gto;4v>}5D-W)X`x3VNpq&GrZ74pI(^W=*y%{9aNq?v4^LWOF*1jW0_!~@=z^z-CX_;{%%%rD(`FE$^eDTGf-TC2H zS@VLgzw!zObWEzRQa}2!1oT(`fxhr>;7#BChOxjr|H|_*)tmMv5^Rprz0WeIH|)!F zT2P#gLW^`y;b@`_J46!pnGmF^4&2@Jw?%cUk$Dx^~rOY$j9o_JcM`y%FL>26e zx_)xwOGEilHr^8TyixW^5O1EV&CyLR1yWZqWgf-&VjM3(dc+wt&^A=i-noA9gi4yRBFufpL}8ks2fhdK{UM0jRr{3 z$6ayrG(`~6j^*VeLKuG`DShwJWqFekfeDx_bPFOnWl#0vr%n0j?%m#$qfEv1GJSg9 zRw(_>)(t%rkv^1`zB6ihlr7Df=$hh;Ciaw&-3{--%oLGgVkUu+-7G2~&2U7#&j?Dd zD2|ScDqa_g-`vBACYUJdP`a(jagbVK^GdL{Fc8zpNpdA$ zI^#^}@lduqjYg_$x-AB~2s1F8NtubR%;6r@hS?rTZggLu~(9x+> z&B>10v}eIGXJ0yqrmdUqgq%*AIhCVKfcag)`NEq;N(lB&tgnR@5cBdDP5QFzr46; z1wBWN#pOr$#Pr8c|M=kP)0f`->2uQH7cFWhl^sfdZaewvr!KsF>A-fF8!ODvMl3I= z>4@pHS<)J}uc)P9RE8JCbhPw0)jz2gOb6EKrF0VLp1pFB-Sfi5Cm(&*cwXdsvAfd& zbybg^Jb7+*`|L@xhX{u`8HO``+(x3L?W3)&eae(}-m@`}PLQDfh)n7Chpg!kIt%f_ zJSskydTyk2-APx>GW!QLfBu>SOAdsDd_@y#h4E^jr;E=Sc)+j0pk0IzCeX^cuyX($5)O`<p-1dD879CL47XrEP8b>CLNG*F~+5iuxQ(@4kAq zA0Iw1mugxnSU(sD{-EYcZ|)lZaid1B2@kKVgwZPtID^#bJ_L!^fN(X?d#3_W2s<(M zbTVJ&mZk=TbduRv*Id^Vw>UahsY|LAfzyrkWqtnoxcutdeViBDLjTdZ$-$m;RZ*H$0mKJy z8_4aThP0uqGO3}yjN$)khm}L^@(hc(Woj>1wnVJWj>2SAPE&X)Z#hlJ= z53Zn=cXwB`mMP)CCNdAHP!rYX?mGj*f|F3p5RyD_D5fww1SZ% zMvQrK#3TOce{hRK-P|#7{bSRb@5}6eaEEWONK8MMJJ;~Aj@IQGr{OL_Eas{q^ePiO9 zm&ZA#MMmbypdM({ba0!0YtLNUTMdT;%)BS(HgPn%<3etC=h0{U@&K;p~){ZIcF#`Mol-}x$QfAEgy52;R6 z-gJaw!{zd(pLt`qiF#2cqeZ2pac{^u(-GfJ}oR*zIpfa`Ry;g;8{?OJsj6N zapQy0whV+yM^*GuVhgA9--ej<4O_{h%qViLMt;FU;zk?zXqq1_Txcu1b-w;f_9@>w zatpow%<(2$CUDytTdjN%@*h+5u0x(Vn@ZsH8@GRX7l*o~r{6fUJHn0n(da=WU82{I zM{L-;_ahn_-K6X2(Y>2I9Pw2+?-6Nx2NH02X!q&U|JP^#=jo4kqwp?7OrM%IHgD^l zYc<#67B?M_OAnoz7Q1};^0F9&TG!(A=tv)I%=(W5SOci43YJU4f^=-nL5_|N(FJtH zifeFRM?8$Hv~_s*&mbr$#%&M%IQL~k=@B**=`+Nqh`qsfxs6(jmMvJiY}wMI zTU8N8LJbi$=Qr$H9GDRlq?mQ}_pvQZo8|3BEh&+TIK8PIRpcUL>QpiM9yj()AhnCW z_qY|txF33jlt=E0^L%gXUet709axXSgK}s%Ze3bBL+Uw@4y&({>4oS-JTyeIEQqOg zJL|T4l@MJsi?kbt(rH3!^LA%H06rvn>Nzb;gwdH7Xn45hBpOQ3jAYjbWyr|s9_%d0 z*|diYdGd>9E$|H;J8|9gb<=0KQj;CzM8>H~IH@2-Rxgew^b{>!=_@Q#6*j+hZccmT zKqoO>6(7+aih3bzNYUvNXP7ibTrcWl#4v4&P}9-aMe4pN?q;l82%>Xc2l8Q<{9ueh zPp4uU@E54_TRx2GmeIw4x}si)9MR=5;5g@iI+$+MbSdgXpt@1b4UtO;$HBq^GoCO- zqy#tGwe+WGU}`DqAUe5@aJo+Ic6Af_!sCf!RPy3Xm5N$J*^KDlVEW8w2}xh^Q{r6& z>GGft>*&Ui&Xv;#Unfi*aU9ir`|NYioTEwU_Mg&PbjQI9Cs|6l=rdT;8Ro=5I-tIy z7GJuwbi{ON<4`)PIGBE_b_KHdsgv7J4p|kXGP4Zv0*y6Yesoc~$z$X)885Zlx3_yy z?%F=ozWvQ`3quS(&UpZ>y#;4$J%ieMy)6F85T1OH51arK953V!p zf3`ndbKt<5`MJ2R)q0v1o8ok!yp!TlL3$UuBQ_6XcoC-OcJ2hzQwPXJl$I`9zuetY z(QyY%*N?Hhfaj*36dMb<*#q&fHSRx5bE9yUcHnw>_XMqts4V?}RWu^C$FqvdG=MnP z*LUP*@6DS7ZKUen?RxJQM+~3~(M>_9Fnm}-x9sR55!+N5!Rb} zC3ilJbEZsL4W<_qREAen6yV4X7qP>mNUsHz70uwQazR2?_pa%ki~A*)s;=NA0jbb? zenngl|J3*w=4veF`i}*Ar-x_1lOG;Me0q@F=lZK?aJ{fNDm|*RIjYcRWOT8+xrwvk z|F7TT`8t=>kX|ClLFw*XKK+(lwC5VcW*D}!1+~08KDj)(F{`u&tvsnBsj@!1Ly3$v z_`xaKRA;0F@Eqa2qZ>&(p}T7!prfPv@{!AUnvlr{8nXcP?h01Z*dL#Y1%>SNQnJfa zyGmjFmc~ZKt7Bdt$ZD(_s4DF(rDaiam0xiDT#UJRQsN18XPIBtywTgd{F0&kfP~5< zCSZO}eho=-wpXI%jV6`33(7+#|#p`6udhR{+`Sy9)JACQ%m+W&%?B=-l)NC3Eu?ie2*Xh;aq^PyT`J#oS^m z2s00=iTGQ+U|<#`x723?w)cn}rj?)DLR;%Tx*xuDY3Wligcvzp-WQA0jifGP`e-l9 z@gnsbYUb1!R|t7gRO26DIzaCwF`WUXPxJFfw+=%~4-1CUm6>j->BE`nW{tvgJD{^Q z_MvU(xxjVfd0~64jo0S$gV{x=IuXa4HBgi)C%O>ZDCxs;I<>0GdKopv;&fG!YWPnf zDV=C_s$zk9m|ishC;8mIaQM&1y5eGD=J;nH)eyJbea2GXr76X&NQP3`C}?!05gVQs zUn>6`oE>pcqv?s!8JJl3bHts%QslmvVt3Q$ys#K_5Asc+>nJyw9r3^et=MtR#JWbO zN5d30@0f;~7OHtF>RnTOg243SaW_wp@qO%kM$_WOAeNNKnAX0AW5?b<^68OJZ{51} z&;N`*@YT-`^peZ?fB)$J2d3Y-ar$SC!u0RO7&-m%)4T1I{wnQ_p5M*StAxME1_P(J z?(>M8!)mBN6Wdi8YHk!s&|xONu=Z zl?hG}rvpn4aBDcV0SqE#*Kfu zW(B_d${5t?5EMiEqutf25slbTLKjbkrN6gpZ%HJsW0FkpiP$E)xh-2TcF);Y5YzwL z4?o#`X7aMJW0meSV*!?zq%ZomrZnOFJf4;on%%s7dG@S@wnE}&BAa}DeF_WR+-EVh z-~+@Y;fj8Y>dU9i{sU>aF6nWxuGw)up^n%tGTj8KDlt_G3_E0s@SwY$tv*{VEq!tX zFOOZu$~PxqoLu?hoWSYJrZ1()b=NNTc^`RCaS-)AflHknBfRNTs`AMQckdZ9(9>;X zpabZu(9zYM$gsNa0&k~1vw-xoqVz*&T?_G_DCjZf5XKieLxJcV7c6zcTtl`c=_{+a zBjfD%I63rps}R#s-8X5eY%v&XmQm5_ekkUw+bh^!^cnC8q-ln6=8Rs5fSkPpOa(}( z!COz=DYd72Fyn~anFz91hTSR|i)DF|??p&Ydn4)g3l=P$K7Bfgh-pqSF39OYjvhrZ zxXz_!8#G5t=Pl--UnyD5F9?aH3vZb z@S{&XNsjunD~I6bdqW{CL&)HCFtTFJO*JU$xyJWFaKIcsr&yGO31u{wUU~v8{lNjC zOG@YLSt~Xj2l`4`)Q5u^C9#X%XRmnfxu3py33JPj)xyXO4C+6;bcq={Qo1^u&VI%; zG@32P%WNop`-OuCA?EGq>$B-)x^km@>1~MhQq$#pUqQwTCKm!`R!AQI2|~Ihrn3Mo z9aOKKN!L-;hblGwrALWlWY~ptyX!@*M|qZW+t0Pn9=8Zm-+r$49442IZQ^vCFTnar zWPB3ak<%FpLD#sC;TDxkO4reXa?U0^`k2wzt$RLZ|FeDWz=izIFJA5>WDzx3j4t2kc_H&!%tWpf;Ac;B6lO7$QWuY>BG z0_xph_(0>l!}~)pOHjOd3)hPpiJsVRR&nBHFUPJULhJY5JMxPz2>q>J+`RS+*qj5R zxs-Erqb_hTLl^M6SX#QhIFvhm^3f;wTW;^_A#|p$E)MTWdpquycbdof$3?}3g_Xs{ z<(AgW30|H$KRs@J)W!7|%i@x%ZeHu)P?W0Gxg}~$m6_im{ zKR%+)pszEUd4kGLz}!EWACe$y=X&~2nlxw5q~K1(^yY%PL7!^=)?<4_PM1WE zUQ}F=9tEby?Z~!CFOQ(5H94v5BaTg9PkWl$u5Wv4Wm#Q9Fc$Z!;8I#7DGH{$p@N-64c)1! zoqt_5J#FEi8h>T``^2a)94wFd{juMLU;4CyF(cOQNb_DZVuXLT{g1%#+0^vhQAqG( za{m@}%i4%xdbN0*QxlDXHZ8uj4;WXVE54=0)fh}IZ1vHp{)@? zir}t+Xjm99wk$8Ac&X^}yi5_$`%f9|PvD^xbSy7c=TBK)2xFvxlr@O)tse`nt!rkH z{RymR5u+Of=Q+)m0_4`Kv!6Zk$iqq)6|f8QrKm&NmU{*I<_LvbTg`I0UW}aXMKLV1 z2X+sbI2gm=%5N0of8(%!#uL+uTCtZqrue2WkCHi^ti7IeBvb8Ycgoa%@x(%RCx{4< z&W7q2TZE{`e|b)bxd150xX`_wu!L|QUz=+&QiKuskPMYP$ALC0sHisgVq|Jpnw3Tb z`MR{0#r4p1J|(niSs+L{*xmoyk@s&MBbkpu#LK?7&(i?t%Oh%~dHMZY|9q?apTj%n zfB0(?_aaLF;m0>lf7Q6Zb_WnH4Sn~=?W{b*xDfBRF6i>4Fq$kk~BIqGjj3q4Na)viwR;0+|;^{ zyzpxB184D8h^Sngyxr5I;peWwtCgph;X;J_N=|DD{+11N zTe|j3>FGcJm;YA@>eT=vf%ario{7Mi{?YH=r=!ua^LtA&T&aPI*_X3r(^>RWf<|VY zef;_Bmp;3MnEuABvCC#b>1lb9J-2JFb;NBjm>xmWU(E8I%PAstpwghoXK9LW5PG&g zIOKHplt}8u`2y9cY%#(;J=@jUF|@cWHV;fkP3P-E*Pjd@e9y-@aVZ4T(b45znGtFm zj7^W_-`Ck{UcZ}@Zy?$GN0*Jom@fM%rK5dHW8B4_oJbyEk8J0)74l%o=WonOl}{5xiCEk z)4QTzkl?}X#7%C8h>DDPIzZk z)I_|iy!iT$@9F6WFOZgg@XhT2`g3x&P<{%NqithLfAiA8 zFHXYi?Q}aGA~a^^#+7PnG;^imV`kG*>69EV*w@A6ufyvkw5+gX^jbK*mZc}RKf7`` z=w&;YZjWQUC#D;7Ix&tXYhm+R9O!U5HMSu8x%Re=SM8(@vCnKjcYxB{jZY2L`m0Hj zaNH!PTdZyxlxmS7a{gcFz~u=KYVYbvwFf@x~i&5&yCBcLv)Sb=+3yhs5mdr zhJqcF!WyFDLe|8kKDoLxKPn2_OWDP!vhJ!5&-yqdVDsV$3T*r z3|bS(SW%e@b7LCsN;4^545$7X-f{MYNUvis!o#BF{>cQ zcV9+*=Vl4|pgZ-Xegn)H;;8_oEHs4jP`}2k;L`HsZT|RFkkV62Nl$nF)2Q|D*@qM@_kh>O;%Y|?`objt~H-s1yxG|LQ2ca<$6gV zZH8t?+;R0^wF{|3bHSe+e^oF}TRsU&pD;J>PuR@e=RP)Kn)^dj%f^ftA0GNg->QkW z0)O+!*gv}ATe>O$AEt3G8Od2582d$Y;W5}<==)uy=))tYsCpD7-9WmL)P?Dm>tz(l zEmOw%O&d2FyUH*`gTmrrjOlWv8|(Torvvok$W14fTnf60KSW69NEjnx`bguMu}j~Q z(1qwiZ2P%ZY?g2~JYaPljj;Z2K%L+h$?Zb)2PxgC<5*tgX(6VaoA9)#jVh)W6_ILK z6OTVA8vV;K{h{gZ>9jL)4a$qITi%fEt^!ixUesC<`+^JLg_eis1x?Qud`4dDS@s<8B0@w zXzjUaSrb6?&g!Zocs~?gGOLiIF^nLXxuQ|LBRSyk9mY^}Y*|rEUv3f8fD0;Bacu$Ipi`2-d zC=p9ST*1zZQP_tGqqP7H;V2Io^~u(U#qC@nXyyGi*#WN>Y63F>9>pw8Eq> zkuy5FFjDd>eX5+@k5lvgM5XTE~LCzYC1uMKGY^~XVni^vkRIu%KU$OshT7 z@q6d&MBga9uzK5pcMYFVf%v-V4w^eVIPpHAlRHrI%NyoQJiFcQf*~EHosd+jeWP)q z@owTi3*yN9IhsaIP&!W}7n_Iu?>W(n;&kjTmYmLoM<8_&UFD*W%G6?9D9?&>4Y9A3 zha4yQOi?-~D)M}R#-mT8r-SN{xE>@-rwfwMoFV!B2|Ja`l&)ctY?Hsh>Xm*$*V1Z&y+1Yz*QIi_#BLRQen$H|dKw($y+y zITwHt5Ja5f^=g}ml<74Aax_Vn|s?oC~WZCJuifZm{>tf>8RJ*I9)bmo3)spFWri4=d6LAuIYH;o0I0#Wg|4jga)FYsG~{zEA3YFeaagqst@NQjGx zarx+zj}%kO44pbrCKWXy?P1LY=hjxn)zCC9J<7kp%WHXd*>bN@!Jfg}mPFOXrLHck z+dtl~g`gLLW24H-YO0duJZJlvThP@s;Rs}yN-N4LudGR_bSt`6Q3;synq+$kry=JT z=H6H(D*MOzhxxyBc&N5^XsGtUhqcqZyhe?mGP=!cNyYMj{IXaNX*E<^$(}A2kElzp zu4~5hl5U_KF+~3Db2GIgb3{)!|zrqz9j7qB}&c^c0e8l$rt``vsG& zLgy<|(?ekP#*uTzG^$l;UnSY(4Q1WQ1F7AqAarF;*)7l=&v!_2Z%sFKoynz_yL$W1 zleKpKSjEkOc%on~$M?6*Y0Tf3#Za>u}u9_UiM;?1}q+Lljh8IZPz`D`XL2v`%lcr6ZG>W)$ zA+&f{vNNZ2_C!awa9(1%?mY>^x5RW&ItsceASL@y`^vl~k;XU&&y2CC*x6iYt#w+E zO>&I*U!-mh!f%7%I%S&`Orv4FxZ%l&5!%fvc+^@Whog*x=n~Tp8$Ufauzbu&S@0Pq zKi!K2cf;s*P?wti4TEXP{q{yq*+r4jju}DjM7=~s`+(^gWO`^q~DQi1eC5g5B-~0;s=e37;1OU{V=~)lam4);${~%m><+wI33!nF0_TR$B_JW z-;~I$kx1zdlO6UhYYI&}v-#yU`ANX|`ye{G<_O-p^8S(cFTel(r#icJ%ac% z|Af+if|z~@SIeD%{rkgqyz+|j(Vyp_7NiVm=urCZGq1j3JTHo5d<94+x$%4ZUX3tn z`uX$fZ{$N53I24-4Y6UkMh~i6X#|MwFay^GjE=Y-0si1hcXOw{6ihG4DJu48Eq0H| z-nTw`=at$qFHPE!?HZd-|4|=WvS#9a!M#py2Zo`d;=u@F7Mtkoni#kz2WX|uk0ogG zW(4A_W_ogF^YXHK%ssbm(WoyXA~uG6NVgnUSDK9)IUP}V@?^r?$wu$lu%YP&5sF4n z$Dw|^hi*cy5!G_ftr-{9!S|(-m zFLHHrVn*f`)vz3EdbDpI-De>_=u~1lUk80R2=sJu(v(d_2HKH=Iu*;bVvn(=Bc-=u z-9L($PLb`dz0}$sp$+u;l8j8Ah3N}&I?k!k$w5fL3jZEUhWgpbXVKE7d+UT8#w~RC z1doYp+;eCj?=2saN$Qt`jU5~f+nYek;*!M~nTh%?!|DonwEB*M*dp^)Tc}H2b?9wE zX~1-+oRU^5Pxs6^gh5GSdMMU(J|oOD+#9mDLpqYWVBNaL=Ex2YtRLDUt2!H@_ac)w zfr+jHgi!rAc@!B=U$Aa$+PWFu-T<_tE4!Vz3rJ3Gx;y2f_{tE@sZw^-jnS^KwVJ^4 zjySrx;5REO)*hRnJiIe$>(ZPxi9$m+O1cjP+@Uk3FH~Bi$#$8#ZlSYH^Ch-|f@N2B zX%RuBUrd?V-4zDOudkk)3KIKY^f4=+9;S4wd=z`Sj4zK)cE=CKuBKi2z3I=_I@GgE_sncJ|XR;ao>ef0_zXV|uAw#2a9&>A$u} z{Q}l>{OqbBrG#|*0l2(<6hS!cLmOANhaLFpD;7K>K^;tI$#%@@8`0yp&qu>QuzltC z#ov#v{jMPW(Y5fnQPOpOFR@XXFOQkKnOp52RPBM2p0)U0a#IEBqI8*FIy;oE($#rQ z!6uzo@^L3~K?Zd&y)zjZHNNY$o9G@lPtb-msj?Ykh&2d$k&s^5VS14&^5vHDTM}~1 zd&4Ul>TV0u=|y>>aozwn^j|>fzqpA9U1guYLOPc|Zi(fJIS0^nFraRaa{=Ff^&6Zp zEJHsx1BY8>?)>nb?}SeqS-bPPXF*h4YTKQ-{MzucsPMU54lk=)-sTyX9@W33E-pJh zH@mEIOj}J{9HyA4xTrduE|mp4&^QI^9TnHQJG!vjS0;6y+cvr_04mojqq$N=#WmSp zO#LVgevs2UYQ~RWIgU?g=o}>$v-MuitsN2oZ1Wo3S&>_lt}X_}vFZzqnhtZ@E~eYC zp=TE;)J1B!%zNfcNiVU;IfD6N*Sg{KZ;g@eKhZ+>xdXwC)KY@z>`Nhng)B7yI5;@9 zvL(JWc-uTL3?{+x$ihpjQDP&n4n(MKt1SA1iCqe9%6G;vzRS#aaK+9Wn@ zfKpO6$iHo#Uvfw}q+aFUpH+%SJ()UCGGkInbYzOqLgT;l9Y+W&QXOmu`8_QieHAUB zd;ltaa&oX5Qne)2c{mkU%$1rRk{VxCnu@B=<}m3%P|xjk`zt2Bq>si_@~6g=%~S8c z|Nps5QG=n)Tn5dL+yctqKW5Gl)Xn)3 z7Tvo1?$e8Y!gx{RXJ5Sh@{T)m8~4Av!(wwV{bThYB{`k({PU*?XT+K=eO)!ACR=^? zFjp2D4%t~Z5-IBw2+Y!PQBN5rIZ!J))jf)8-| ztN1e3#g)oY-nM;Yynvg#O4LbJQu=MoE=O-4>3gq_#zy3wsLm0Y7yu2jO@>z!U7dVq zdE2UOXD8!%F|HNsL}a`rW*>b%dV&-5m zKUNsF#Be&vl&Ig@D+Q-}xGl>B)0YMYQbU?HafYps$Q9&tp)#p1(In~XHPb{484q^% zX_9^1oqbXE$u3DdBsIn==#)KQc{06B=Y7JDj*_l0bazMR84}qw(#9^->BJe%L@#DU z6Cb3ECI$B(zuVB@o#;2L=hki!e$DT-Hv+;w@6*uIf?0L z*z&wv9(c7=lHq0M%oksL?)8H}`s=SB6sXhH=wn>zpJ8`FO8@C|2;#zYGlb~MUH>Tw zFCVf5I@ea3c1fxp9hx}`&yGT47Cm>8)}+SqLWd({b>%PWX9aobD;B-9as@3&&&_^f zyPuc{#RcFZpuiA*K?6`?Ra$GM-7+r`UBw;Y0074iYV@!BuYN>x#au@w1doOprMie%{iq*{YG^zu0 zQPlA*R4SE`UZiz(Dkmio4|_L%n`B^r?+60=TW{T@hp1HXVf`Eh9Se&ga0BMUh%PDp z567+>CcTCDmWrf+QVK73_>G#o6PtNMaAQSF?#1k=`Evrwy~3KK-dS?)t7)U>(rs<% zz&jUTo>sdvJG|CEcYR#=SCw(M>u8*GyZ&}de?U^lEy^9OK?h^?mQM=r^q(}!E0?0t z%4^tOj4wv9E?*>dRwjKx1SJxDXhkN?+@MzTa;nGpi-UiA4ElNlyPTez?xW#hNyBEbd zKE5=WoEWG`{yrQbX~+2JHOZNiC@F9p@VodQ(5Z?cI_b zU)cg&3yf)7h2f>+R>zUv{sEAmwxdMS&uPnQOzz)CU35Gxjk@ByI$AEn((KS+7md6w zH*rgKUrz42+{J_d*L!L*&x~6g{T+xdl@q5?^`jI#msjCgK?SExS3hx$xXTse(tDZO zh+{lGVMLrNvxt650m)fy*lAKLQ-gVu(o{alxT3Neb{J5dT1w?CO-gCQ+ekVi^|2kf zZqxr1@BW9D&6tbK{inyIf2(Z&ho0i0hqC>7k~!gj!tlZh-R6!M5vDyf6Qf3rnDD3W zG_`Owoc^7#zuNZvJ6?ueWFD5&?L2Fk)?7BM``CoT!ebM}ILUyzOfQz!EMT`N-3a94 zriJ;BCPf|Zh#_it)nKnIFY=|!^dd}`oR023ZsZig7>Q!EEHC(7rqSUDGq}F})baYg15AdUM_KVqfYbgNj=D z=S`?HwW7sDiQ`r9puu}FSuKtcI9)SHi6E1Yj_E#`w54Q3s?$pjNgHl>V{Ld|gmwTP zo^<^Lc{{-9Xw;JnV||y-@e%0gP&>M#Ly(g@ zmh>2Du|=(knVVu-mB8l#q%)dpM?N}~8)vgM`9x&k{lO7~;a(PER}+O(XhmvAM>9Pk zxe-PW0;$l8-E4bo#{Yv`BqO__dFQQTeYZ$?+#GEqbbC|D-qxHQNj`qRifpMCq^5AnNUp_P$L3A$5-XwrtwOMmtSUoBZm> zr+@hRrI%0Npot}n{sy9J-Y0hmOxv{~y}6?h^EL^joFDpeIA=wxA|5I4QpM zNN28>BS_E2P@;FT9=D5(>E}C=j`V#*57Lf~dRjTTq8{_I#jKd%nf9@lBQY`4Me_oT zQ>q{}N;Zsa1ney;(OiHtoU|d8O7O+hGbaj{2~l_6gCMRl&!tPT$}9uZ-I+PElZP)vXap`Ap7akNXsrVw-L9!?gZ_@ZNCWD8Th!<& z!;zSI7spK0eW#_FN0&|)rUTPy-gsOT^`c=)NZl!h(7cx9Qi*d-G|GyO2nr>X6TcCO zm}*5Jl^so8zpJ5e`nu2{=NU7cXOQtCf!tS=uH)3P)R5v#A3HHEC_3YKh79fEbmoQn zEHS;{XAe@*uj*IX07oZZ`(Fb?=^}FDegV~Gf3Xr@(8f2)4r3(srzNMOlfSSMFN&4Q zBDcw+7oUC6PU%wD35xi3Bc`*4?doY%yXfhasOhI_7d-`;L*dBfE1x)Q ztm#HXw@97Gas1Gz>8c?;_e}egQTF1|wzhNUs=o64N+$I=V0t^qKE$OV+AUpr9aR79 zz|YRj+^Ct*FqPk9^IX?tr0{aJbE({a=n$EDW`K!xUuMSzm4}D_3>iViH zpeup)Jt*wz=3@p7-R?WF-# zy@ACTyK$5tZuSwF_&XHzUx4Hmqnp%o1L%Tu8O>49jfv$C=$vINW%S&xxLwiFm2^9< zqUx)P@HW4?s7|l&sGVhHaWz?CtDDP~N6j7CS(!St=ADAD&WeIb<0_-V$N7gxg^a7p zZ3xe;saQ_-OC0OC)^+pl-GICO0XWYY2(C1gM+UCI3sG6wIcZW`JLVT-aY-_oI+)Ic zgC#PjcYIMosPK5=d*;oIG&B^TPa-UVysSnwriX>9KsV$~OkY_TnDj{UD z5RI6H`=v3glz^L%(vbYzUcB8&1gBT_E-7s|Pkdr(H__<{v1ZM|&`{`Bws>D#{f z_5EjW9Tu5|umV{_vv$rkOIRjJe7u59{ygJ`Hmnez;9{7v2jg)TWbgn!pFU*`V3Ynye)Yx7o(PxR9wU5B!c->8$ z{>PYZ2;MB5Gk*A^ndnAqm6V{RzM;j<7k6f-L}o;$c%;*alLMg64txFZr>Yo^#jZk% zi6aUf)@uj^g)+m3jxLdri%Xmk`~U&B8Qz7}_WqS>l4ulkf@Bhxi^jq)Oq*gs+7@d>t z?c1{Y`_J|7e|KOfmUAc_Q;WoO#>cPz!>f4HcVkaSPL~0O!z+(}{4tpR_V-?S^=&Bq z(_?*QNXRKZh|Y8(&ECh~RyGm!dd3VX>Cw?LsRzxN5k$KR;$2AMgVWKoONtZ;lO4CO zl?Rr6UUp^Z@OaOcUD4s2NT4jjoRZ;#mJS&44#J~uo7`|P;GMzj?&BMpLL@c?gwBdd z1V$r3@0?7h^gEE$4$uGqAOJ~3K~#4N2(vlgP*CtrHS#f?NcZmAiyDk*?;7a4bZHYR zC^B>o4t4zL8+P4RN7A4F=I8(GlcSN_tuAvMT4$zAan!ZlQ)U(`owD zGsH@NcInc~H_oKxt$Rpn`hw{j5an-wvUo#WWpiD6&tfn=+KJvfQ5P>polRTlni*NN zmHs_G;4*MbT>&);9_~(#ZWuAxKj0kGyrUr7*}2XZ>P%^Zj8O7<-~xxzk0T*xa*&yt zu$+h(N{6$vTZ^Uf#~eaYFU-Ngvo#VeeQP~Ujn2QC ztsbtKMP%=@knW=r(~XL4=vZ?49^iTb;W=(pLZahmL{cBX6!I*TE(eO68*U*mU92vr zIMbIy!@PYD((%WzBAT5B1}>dGcG)uL98CX~HT}jLp=YWk!P_YvZ#tVm)cWvBgzH?k zUxn1qlAx)V=*I7g5!C5>l<1KeNCoN9K(hKJd8aw>79ytu$+*Pn5Jt9*178Q`L$n&_ z_bg*DI$G_*NCd*HqDfJqEGka4nNkz2z;zR+PMnU8?(F94KyT3nc@X+K`jbwbn6_}n z0$(saZQ;ZP?qvBhX;jP6;%Fw%aJr7pHYW$FfSDnv!4h*vC;MLm5jy($VOow#R)^Ec zL|2PZEhOw^Bd~5j{Rv6x8jDb+k*O_J-GI6T_3yvPcUa9mTBE0`(yxUrbM<=YDVjQ#u}(f5Mu6`k&N%RHhePFV{Z< z(r3;F)cJX)U05zqKlRfO4_^Q52dA_QG2N_lHY=4=XC?)(FRh$CG*fqe&WP!?KRJoz zMdhN~(b8#X1f|bj^z@KwNNb;cS{0;Fx@Y^-8!c=4eRKK)YWe|cNL4qw5;0vC){Si# z(go_C2bQ!0=Oc&C9oSBZ>70!#PlD(NrKijMatcznOX>Gu9Wk9&NBXhwoJ+^If;=>cTz8t(ouHo?j4LUKiK1x~(%V*FU^0y{;jup?p$)SyWW^k|}rMD#xv9 zo*Q;2Jt=tG>KZIP-M2eBZui~pdkW671kK2@T#hXB&2PQW$Al6kfh&b*fzI^6&%9t9!f4NJZ&Q zsAy1H3!&u1vczNi?oI8WV-epZ!prfTbhTXW>gvai-e1+W_Tf2W=J{3iw~g$oFX`(d z>AZ^sbyLFIm=$oj>t;MtL15Xky!3W=_Y%#5lAe{N?nuPQg!E#Z59x)@tFnkwu18MJoHHe^Ir;CZ1`iG4h~^tGg0Y`{Q&X>t}G_wJ7PdD{jm`;xkI39O;1QGXVC zIu7@&=g(z3gZjDbk&dg zQ>uxm4yUVrlmb%h?V@yx)U8vk)+p9y=8kk-Hap~!1psw?8U<~sT^Kup7t|%Bu>i0>Ui+_yi(%G$r_c48XD0G=I zn30!P7)95264dji`}FhxMy{?oZgTVzfx^fs_P}h5f*y%_P6tNF#|JvMM#|!h4Vkhl zpcu=uCt(mi-=l8lNQ9Fo2RX<$K@K-N5FJ?JyHo)vU^)*7&1(XW=`E?2MYHFI|MRUH zWORg_TZrnH$x}Du@~2??SLc5J`xl>ij$Pd6&h=OIXEio9&I`Un3?t1)aiL30*YTBC zUp@2c8OlhxWw*(CF&euNUN-f=LwJ7w*scx7^Vaz~#S~Yg@a~Io-{VYQcpc6lgfkBz zu*C;PLOP~s76(wGiyJ}M9>x1|Vmu&w(7yQdhKA1zJjXmbbY(XYj2RSuPZJW z3iFDPcwN<;rZBpgvQiSoF?e$Xw?HMghzR<%x)RM>z5dRf(>1p!m~Ghc^2O&P+)!!s zM0<1g?rZgM@d*mTFXTX-W?~}ojwwfP+!z+r31-}|ch^UZ|1QVN`^Vni^0qaOZlMKd z^{mNfNl1Bh_m5w`^!jHnpMLdB9xR8LzHS|q-ucDt4JqjjJ9lC}WxbI_P3zV?*qPe!DZlQX$AZr%>GJn|?~oJ&v;!nU&m^`kM_4Rysf-%z04SfGsEMW7sw z)5Bc^s`>`KY}&f^v|`$U)lsQmA#nxun^n?DHVg7bef%pFkO zHTE6a$3JeK(A7=FpP7M?N0p$zYis7xv12EWT|kHn`wK9#XcW6@He}2`4vzR@P3v)! zaE|GPMUw=^qrxcN7M6YEFG&BsBAQdM45GIp`ql( z_}F}6AoA#90#kWkZBFWeV5EHFq19kmdu;4~$nm!50HPZu-EzPf30=4@lREYnYDr~& zd4lM3(XXNtWdo1ig^QSUZ~?3PW>0Wc;C=E;XG*#*^eRK7;3FRNKZ;{FuD-IV0QJC8A?{p<3|( zoIYyI#yPX;c6#B$C1ZWLz#L#mS?UbvoMA_D&Z*wT0wYqlmVVdzpe7zT*M4sPj?N|H zCxPc7M7@CNUzK-t(zcxzo0!r0!S6EvE4uc`_o4xpA+?i%O(f%q6CWhxBbK9?g64e? zyKo4skPvI9D2z044Par18STNa;Nr*B=odlQ=k(54OV>gwy0{7bK!aMX0KZR0`^ z&rPsPQe{Uo-t-QxBB!(L3)J+QiV#Y=yv7X;c}<$|-Itg^)}Hj7fAYh8I!k+bZSz{w z84{kZK^Owm&F^DWy1P-+iv{HNqdBY2US6q)7eP8<>Oi_h?0<_A(y1|}y{iSt7(k4c zPO{3pwe!eW2}lk@damr9mP|@~LdcR*SQunZO=S{utCA>2YDwp&CRGv!gJVWjr!AFT zSXX+JySk4h5xAZdkUG$o)$fU6MrI0CUX8&6_>+YPytikvb~5JnEz~qNwwNIgZkD zOFtLIn`gIQ)pl50^S}ijJaXjlXGWX%qMqo%=oDY~?43Ky+j%G?#9+>U}tHXE1f^Y5VNwhefbaVlg5R1w;iFZ&sZgj-ZAe)0X z)>~-ZH*YDqCGuIg!6A`8V7m9&>gO;0?8WCk-1&L-=jYF#Z*7e`cI+bxNpAjvDDay{ zJ{6|te)ZXBKmY72{`DvXR{>G)Hp=w!{Am@BevEoE2xhxGxlxX& zICmhuUd>DQWq*!A{mRfIhv%=4i7o0GEJDRKcq)z5(Gd%`A`F2c$(Dc?1+_GhR4pcD ze>9acBwJX#xqA0Ir|;~@MNj|o`h^{*H}B>>q=~1;zSezvk?uX*n!sDE;*5AAW(De)^p= zZ>-B(H+A9IsneT2>A3dA?VgmBp5;4tHaFLiBC{cbc}w2r<>aB+)=lTBiXu~Ji%HJA zG+1{gA#5*=X`Mp(Yzw1`9c=089y5G_aP(a~=^DeR?j~b8gLHM?JSKLDMHpIm?=Tm| zoGo;Zp(0?}vZL%X=<9fo{hKtS?yD~<$#i2PSDaqxrdbR?$@`#xlH{Pc(~Y(8tQ(BJ zN|B6)kgZcLu5xozjRXcPHh_^yWd;8?89bY&O}dFm1IBecNW2OHVeISR(WX5qc&@}4 zt#Vml$=1b3w|eZEJS+5gUfvlSmX|%|xel49{eu%0J-AetwP?#BJV$3Ssqb;mbaRpa zC35lBU2rFXBo?ZR;Gwtg-4wW& z;C_}mJ28WzEwHf?ow5HlFgfYMbXm|}dP-Ju`VNa(r zlGP0pzqkloUL;KaKBc4(zm@bNFR|VeMS%Eyp;p7` zoRFK1m`;4U>PRK7sy?slwZ;L$(^Zy-AsukVRxCvwT^&wO!u5jhMV@sO$%>BmIwYh6 z=!Vf%ENZY_c+TOY_avN~0Z#YPJ5&jaWT3<6=i{I(2)!<$(5NA= zm50akrJSG{RPBM>9l8F9bYUc2Hb?E;xig9k+1OYxyiAymnvUsZn9?PsgXh^h!%bgO zMZcJ^7sai+R}U9u5C5C}HqNK!c+OptTvbXzW<1f1o)nL68#AVgZv}&yO1U5AqPg)Q za~u6i=eOh%Pu@T?&x-DZn(pM__?F7^4S2ipv{#jrx^AU2#`ktmXBt5NBAnsd{IW{> zx8Y9T*67!tmE1uHKz2*Nx`PsHjuAb%m*N1VbdEGGBn5qd_!dIc{RV<%X91)+jV~>4 zsi?!Bl%KG=D$BoWb$3Wr6{0wEE=8`3^1Cs+V~OuOPx)#BZAfW&1b!!A<{^hMwUn%w zmhQ``-AMk>I>s5wQt7Z1LIo*tGA$KYCtLZ({nao%eatsv`jg@R`Oh{j3c>!d)!tvX zCY$Go5%%iPw5Ty79{U=epBNJcr+d|XjVAwfYyVF#mqkSBg%+k8--`vln6t-?Iy}MT zjFYJXrb}QJwu;S-if%tKV!9F9ajihKvW8g5Z1`0Vw(3Sr?WmmTtY-AcaqRt?f=NaN zq(r8prTYuhjWJzmjI{bRYte~y!L%VYSp4A0FrQ0jw>I6XCAB1V%f%x~m;FUYxzjPH zo4cF!2)ySUzAvP6)oALpI3ko$FOqmkQ92ZFAl^Rr(BsTJ#ICOk`0X2Ja&3k`n;DLS zq?By!acy!hZrE8?>>HF36dB#>80acG7pQ0AV92CJj0bYM+{Z}iB^f1D>cyU z^QS+1@tF@V%B`_?@8XnAobIJ^iS9;6E+0Gc>HD{ibawvBC;F?8m%Jo$Z{N*+8WPvu zK}25e(*S1Jazj?Xh&YjIpw8=zG|D1A5 z_5cLo38t%OaSvs*fT#3h6n+V{(d-(q)rTDP+u{SHis>JzTpJBV!Sm znJFKGU`nzxJP04fk`GhpNM9rmM)O9JlI<6($?%9ynl+J&n zf{M5eOk>xJ8Xg#p$kYWVx@8DU=^2C+Fz0qkBt^lJ9cl z$b0qlAl;gY1s&fsoL)>`JMuD(rtp2LeA#e%p*zMD^mITShx#hvvZU+3!{6fKh|fq* zBw-&jxJyP3UqdFEv^)aS4aD=YSXqY|E;*Vk7~FoFwnkh~jtgB*&7x(?igs;X8kp!# z4o}+gP}2ogin|cpK1AYNytl-0IKX zKpjZuHS+z#ZR4Ak=8*T0Z*iOl1<(rf_aI(Qf$hwmF}*M+aASS^PEs>6d9wYl0b;o& zrsGEkp~t_pk-E{1Psr^eP@iA~bvvp*$@QlcpAM-@8Hd!Rs#^_2fo6rjeE$X1^hZ@U zYJNy%l&OUW2++*{&3TZK)9q_wUCMjJ^S<&0Y3a|=&q#cJ>Ggx+bMphBs}t#GrngX=F*L8_n^tm!X3y0TVzjQ=)}k=x%qiOAhPr5z@>#B@+y ziu%Sm<)800I!p5QPT8**2fa@n0Jw>34T}%hdE%980{vf359`+9^ z75ZNDRj%i__5(|>r7P(rgsc}@YbGG3qduak*Vrpajg*cL#3QL+FOs9f$c<54LdUJsZV5E@WBr-}_r`tos@c-9u@q8j`dO1ny0JEvu zBr~1zQ7kOIA;kKG1kW2aI(W5b@RCycf~K};K17?N?#k|#?q0uvUS03z@$sqX+99Me z($rHuMRAst;-jhBM(rs6l72bFllvR9ssj2-0!xyzvhb?l43BTzR@H_3h&-6&UW!fo zO?*05n)s^Vcc~qX59kdce@0cM;c=~H6$K46nW|DQBlj;aB}Sc=sYywxObIZ#5QKle zj4wkA;(Ag-Ii?rf@^tN@zY!TS3B;qTAR*y$DiZ=U{w@-Jx>4hqP!Ka&)Vis@p={4z zDd{C`&DYkCTKMk&pHD$7^n7^4BVomVS|jHhR6J$GBWvutJkz}}r+*#Lr&EXe$da#L z(SOai5wL~Qm0hTFqdpt%rA6n+NnTUNgYkr>%kcqoo9J_aD`ajM-EMb5O4lW?U`j#_ zqz_}YsP(Z4M39@pQBJt0QPa`Xz5K_iy^%aGmNOktw@0Q+Odn|i%rfU)+zl-cI=Aw0fvp%slj4l9w!1cmHTrf;bc%h?}FZqC) zuIFcC^uT+VZfA76&~6BS_yb$#Sk%+AA-ZQUBS_6{;+!0dv3z7_IARAzK9_(_9JY&- z4{~}Uso-)SBd2o)GGK5h$yl5c8R--0i$<76Cv<1Q04lmc0YDwfQ)D`4)WVVYkzUN1 zn@{A1T~gDjIQ0!092`6oLA%P`AAk1Zi*LUCdCZo*`@r-}VfwDVBT)L0BVal|EuHUd z$UunQLUH7#P3Ld*_Ge8B1Jj}O(@5&ClJX)KI;I!=E-32n;CZn(CjA&S-D-X`tfud} zkr$fg@8 zD(>EW`qF1tZr%F)){f7^cTnKMd{zu$zEFaM35TK{N*%F8bA9C)Y%QCPfc65aN*Rkc^hv3GU?jw z8%=ogqdwo++z_`oWkZio(;!BP%~5sB;~duI`9xAqNp~t|)pWWc@Ar7PCVCXRfOy`{ z3!S4HqGEhztefFuywZYn4#HvUyOEfQ=UHMp9i#Z3xVn~PBo?<8yVr!;-HXhenTUXnZ68jLbs}0EWj&f;M*JFby|}yVIjhulr82I9%}qL@v6x_4 zBFF_w&)_@BcE}>{XbdhiQI!C#SVHjKT?7j<`>2@pP>h|qEj3-F4qVgGl=SoxB}Eck zM76^4h_f;Gm3NUj$8Q?u9*5BA5A8WbR=c}PCRX`K$~U&|+PZl0QK~q=bU1wmk~S_e z^KIc9A(2}{zd3TEaLLImQc#jD!Zm`apD-Oq6|JRwMd!%rY17lt)z?j=Ty*-31(;~~ z{^>rB^c~Gxmll*=*Bs~Q#4LyXIt)#ISQ|3{VjP(xt3ukrn`k5ZUjq}qh~edFM0BAw z2jfTIc=(Bp8zJ~dpOp9I4~OMaM*s)ZhdCWe2Z^7-uYyI!DDz~d3(KG0C|~$X)*9rY zdFn7w4rf2R=;=j6vxi2ld`Us+Fgk6LW`gN2p1O4K`VSSBj^~9_C|yTs>IZ+Y0?!Hu zyIS5p8&C(yXP>%s`rw;Cql}c=(RLEksTGyOrB>G9QfwBbK{0aj#oNky8(WQ>Thn}DAS9{P8W+ajEp`3E!`ly zmOP@9$Lt?e$boZ8Sv)YRJ($4Y18Y`8=@gOXhS2f8MhT29=AiQgesZC7ae7y3LRUPF zm&V2umbeFIb|0W*0v5&P_8L)1=)-!tMd?^vAa!)} zzI+t%xVp-UxQf26+t;pjB;3|@5S<-#%>Cn*khgdzE~;jV=f#FA<7&!kJUv5dI+JeS z?vWmU4e>l6nKH#Joab0ujB(co=u$SPUerI5Xn!Wi%|R$Vh+hIC%rJWCO3ZGcx3Rf0L}J*l&`=ro!i`<=uQw&-dL* z>MbStB`b?u8X08tWll(tRjQSi;`M(u)64P+-zcWzRrya>knQ%e=-Vh>WdP~?faHeCO|Z*%o*eCk^@J!!3)8vR1mUNt zBQ=;l4C$OBk&pAjYd&TSe=?<|8&n2n^&q?>W>{zFAX8xVailsC^CC(&V!D^i>C=L( z`cX?v*M>>>Y~xn?P@w_dYeWLe`4!=qRGr&ykRiI z*H+fByv*GZ9?R${VNbo22gP`aE)bAUMxaj#bXY=#B;Cp*$+n{xryGfKMS~ej^VUr# z$r;0~xFM(-9T~BXP-mj?5HyW9eX_(t2WJAb(_>W?SVU`!4U3^bH=Co&1~@&|ZO@rk zZ~X9QaR{lMi!+~M`{X8jp;={H@HW}tcr4ql)z!PtoH>2xvkT!BUzQc%Pr36> zELrH)?rt7Auq`tMC|{7wow;5d4dQOvkYYL1@BZ>P1Tg&K7ij5w-~Jp#H){HpJ!dhy zTt9fwFgk{p=Xr`W!WhRc1nD-^(W&qbmX{Qp+bh{S3mSSB=S2=irbMUYtvepYzg2f$ zLSQ6i2oyScJ3-FTG0YA;s48|LqQvHg;+QT z_d*Qi)YH1VowXsT@1YIpD$`v^ZHmZN$q}0}A<`+7&WwQzXkCceTFO<7>k^tBeIVw= zlv?D#>5x8bzUo2f2K!g-2_%4KYe}Mqn|G+UD4n}VBmbjeE#UP2Epi;`$R=^;J#Kq& z_vE-FmJl{W8OMeVSYDPM-4sZ>CS2q}B&=u}C zBdCkGt$|B?#rE0HK1~}^tSvI01L>rwKcQq3b?mW*nv^~*e>=2}&W@Ws z;`P_xd>ueHkS<*R5r|Gy`s+Uxh6}+ZmxEX<0B_mNPrVGKpLz}^=jLaypL4nhmpQic z+7%SIst4%{&tPU*#Q7q$^c5%HeEq{85TA}o9Z-kUvAvwyKJ@gn?LhnXMK77O#RCHN zmtJa@mOf1BI#)F&8AQ8%EbM`=9OhZSBo3hhOMCH;yJso}`hjS%ao7 z*9$D#)kz!DBsDhbOvtavhtzYCAtk1B+B?vHBL1}#1D7i+^TD3pt`E8{C*1;Kalg>l z27$ez0gFmqgKX&(k6J^V{=m3*4G#>AE^A9%LqTUnXJ=eoQswPCFgNsl_p6HA1e`Bl zPFec$sJM5kvc8C8&2?958~s+-l*N_x)$1ve;Pd2ugXUM;Zg%xw&C0sk);J96_iQe| zxsU0;6|P@x8;DP$gFO6JiAN`@lMwh$yy>~qCcW!P!U;jzP<#jZE{d_iBZ-<0)PF&M zdgqe1Iex*Drg@FSpFU>DYv?dLNk05=?#cP;QswFCf0$(l=7;BB$ltMZJ!(4bjogV* zkD}o;{YSCkF_AWBg|X?)JKVX4RCWY)TU2vYb~^2s>W2Tnev9W5o$1brVMW=ARDx2c z38<6mqIN*>{`2On9qG3u%(KdCTb4fwE3`6dscFe2V!gZ9WH#bf&u!^wsY;fCytk&K zr4;9QS4$seB(=!OnlmS>ZTvQ-09e7}yNFR_cTDNXwQGrTfYS&1>1u@fPK(m4s@|%s z#(~DF%iZxHd~)yr+rbtQ!-xgOvo~M1Dq6&r`}vh(ccCq*#CE(h@d@bX>wjN*e^&aPE%aX4o;^T=)Z0H&0$*IrR2_fB*eo9Qopt(1-G-&hkF%eaP5YVki^MbOkRr5q+LGh!>kaMJ{yd!8(DM zjxtIrOg8jn))L?E>G~>U>_j32zdmnvt>=+p@2GX}sM!IFytLXE1UCekHqdxVJX=x8F zoVsw~^u=-XHM-q%V{u-P_vEwdFE-a@E9oUArKu@&T`2!qqtcz%EeMJ%>hYl1l|3Se z>899G(+=ALhr+nJ=7#Lp;-EAicja%RWZN;FJuM}ROO9HYp28rPl6g! z!Y%0$x(Q?YRwx~Bdi}2Ref3*Qh@2-r91lMNv&|JnJ-xUnR;Cbjx=qycQ+tX%-Nu1v z7Afi$ID_di63R8${R5K>q5cSL_T7wiu+*X)-yZQ$PK+AQK31?q)xdWqaF zG+soeUneeG#+KQi++osbJGco0t5&gc$W!A(mL}xlbs$>$j%sEi&Sy;U(m@2 zr;DA_XDlFXhgxKI(=Z_f%uG21LGQsNx#>NXYWpotBOHT?D>tf)@>sy z)qD6q1OWbsh23c1M*fxru8a88@x2Jpjh@a0AaWSkAC>(aCy7!NQPeF;r=oNP`G{|x zTtS;4<+!{=0^<_^{}W~%_hotH_U}JUHoE-ia=hR~q37t#XJ)?e9H#UiU;p9jZ(fp) zZaDo%7hZq;I*~7ze(=nT&*_N}%Q;909pVV5U$}n#(gFPGvkk=~ual2%N=RY(**M}~ z;8|v#+kWcYGvNBnMZ~0^eDea7j+m}KM2@{!Bs7lirESW{k>lBQ%P^#lFC96(7B!t#rR^(4@Z(2~YG2uorjIN7)Rc{e z%cYkO4?C)>sPrDEbJ_ksv})SuDPiIH;V1oTYo|#|S~7R;8cIpQ^l-UeFvWBx87}Wk zZ6QUS9Cd*@YC0}~ffK}W$R+@&;UvBcsDE%-5+w$Qgs!AIyx}l9MiSgBstIMtiq7#K zo`dY_XY||OT)PIOV{IuT@UgQpgv*^3M4L-Zzm2hOc^##p7cVwk#9G&RuC2WCPMw(m z)DwN)ckKv#ey=dpDiJ+#vwvP&);1%jn14E-ot#EDM^0DgQCn=> z@@89XPy}sDV>iR+s`M$?(V3h3?}wfL>?0;lbt5lDSgUrPbPCE%#iCBRXh_KFHOW7}4FKE5}=zOJ4=*dnKMNDx8Gr=;^*=*Zq6m(6kwJH2hPCny(LI99G#U zfCgUgk{ru3#PWi~4gK0bSWGmO_rWE-n3j^{9o^TDd*sMJ$iu zMM;c$2=$}mP}GTbsS3mMf-l{IbV%J_0Wvt#Ekb8*AXt~1oFVKtXBMrCw7D(?-L9f@ zFT6V(IQ_294X8h&gqIOURmYxgmRV~tD*(6W5Mv`X-F{T)yC@tyM;B-60mMsAXJ{H? zfw~^6%jUlKPj$OmIgPrfrcVdZdj?bJHI(O@-q2i!Io%^V2ppHy1=-vOLWj{gCML4y z9$R{%qZ1D7L>KQ_X=sAR7Q1fj^aWG3Cx7C^pr8mi397^;LgAWP9tBOF3~->|IV_-t zGzKA7n7(-NRxZV5r}qpV&*+J3Ev|n4%*Vff@n`?z`se%hdJGP3*b6Q9?24nx=?K-^ z9TZ3&>5Idb?L%|WGsn*yk8qDZ^V#oz_OnZ$oPNg`(Wx30lFOX_>MPH$R}JYqGQHT{ z>DC!{IJ5;d9cliZ8=*lHXLz4EyJsKn^z7oC9BIIeM0`M$k&2;-ZlNg-{X@}!?WXi% zN;?y&tmTzelhHDNh?=|Fmp4ZbQbp@V7a3nPQo)q!NDEP;L3RXnFcHYo^aiU-F_|eI z$mvi!&wypRFn0IjH{>CIx$et`f-m57JSw{*)ME)gmCGd~(*yfU4u*InW!l-pn2reQ zpHNBq|Ni_}*KQv>|IwFJkRs%6k>%wqP9O`>p_|i>;{e({nZ~1JF{Z6c>8ZGubS;jg z9S3>_?TPvPVzx(64wV`OB>QOXudN|5_Y5-B*QGb_kQqfJ#cWSUtSbE0By-dln* zeJ@fvh)w|3KqG!&|qU{035$$epZfES(Zg4qdEH&VNu(lZwOWO9F;FI(t6sx_FE!PpwOUUp$n zIa*T0+Z+R?vkdMw=xtrpz07!Ev98-!@V0el(<$}PD)zzT5DLlf&aPc}X_gYkLJ{w} zsmSRBt^ng=bBXGlGo!FIvGLfVsx4ut(!r%3-zE( z=7JW45*=fVG2}J|ZKlC&K|^*_8M6UuRrvzychXh1bgi3}>Oe9(;=TP}i6xbT;~N#n zC{Q=XmzOY=tCm!iqoQ~K-6+1C1M5Z@r^=LiQYD_t!omQ$m7)Rz!@(;Sy?|u?G_6OU ze&PvMX4z@X>Xi5R)c0SQIr~L9W)S3Mc_E9P2=*TwypGj{1E!bj($RlR0qG^s{hzLX zxZ;`TWUPVDalOz`6cC5U5y&r`K79d5$CfVBx=KiOv)LkJu6cSTrulY7x(s1}UpX7T zCgp|5bhRSIiT)EPoy{gtof(4{HkcJFtqM|OO@B(NtA;Yu8J3i8ot}IXb2^ER)R4Ao zk1TpRwse$qBz0Ub%6mC?%Bbo3%e``A8$iEu3LAK?9Y+y(KEVJv7p!-8f|lu`S!|Zw zQ`6gmlP3-3Ucca38#b*LNcWrzrq5rkuypiu7`+BoUmbuArbSY^EH9}lEKNudnD@q? zz=~`tE4zX8-d=tP!R@915Mx0Dju)9;kjZuYLpT?otK;Zze)}68fAbcYzFg{YT-5TA z@VYy3b=Rb(gXvv;w=0mj>+rc>Y#9$b>M_V_5QV22d*|6KsWcZ6Z>0tuTnya`JA~0{~mC{lfPI|S(=-4B{+Cq zqu+_%&CEYO`4A_fP0HS*6KDgE%!q;X?D44-@93Y>o7%E^}w z&zp8~{+h5453IRxA^+v&o1?3jua8DDkE)abCPMA0DHFw&NLcUs<{j0-^W_xchldk^ zxrUG9z?zUh3uk}*JFJWG!r~1)!_grD@oQ3h=VEUO4#N~4*66iu?Y!VzlJ@5YXVGpb zn9RoV)$x9fe({99#3wLiBkH^+iQYp4<@E3@=OI~HrQmZyDou#0mXx-w9Yg0)auoq? z!W5}SPJofYa&++I{sBzvm%9eCvijMNfyUi7fXTc&L48M)lRsEZ!=>b^d2CEb4ReRm z{QTr;Rl$BsLPD_8hsF1jGSkpO10yCEm|l`Xm?*IGM|ta2OgKRAj)vCO3Y;%+dc&qo zWmHX&1k{3#PRJvn`5hfC{P4+k=ht+^mDJal)yKdhfAL#9)z(aduv{vx|M+MAs9_lY zhVzkY{=_4-rh>w+#pwsOtpHoil&`nEJoJzQS?T`6lKsNwF(V$y|Jn(_R8^x+*pc>^ zzxW5XxcSPLd)e{J_Ie#R{t!0SR zf$wpC(v1DBB^mxi)-^>g9^8tOx-`$Xux@7q zS=bqoOCwRuG1ZcZet!@J80mw~98I?L0^bGGVU4NS(Y4Q=VnSz8`qZ?E4nc$&Mxz;n z1TJnl>>#8{EyzLO!3k~&v3YAxD?Z(#?1svQ?Be3%gFQX&Z7c zemtY7br4N`@RK^Em-=1DE~BO&slRdK_;KtTXW(?i<}+XXkDvYiWyQMOdFKXLE=mW| zalPz*MK*ObWaCYL9xYuhkTgDi{Q0-3A^kEcKVKt$Aq11~-G=+OMA&FP7b(-&ZF!Sw42 z;KNIxI_WM7-%ww8m{Y4mNO$E&x4XO2x0B(9ucNpcbNy#ueDQL_u`dhqxq$qQ@g*X{ zjYvq3qKv@IqE_Yydit|&P7r3!p*`+R7+?P7SHJrCZ-0L6+Od6K((!&-U?8@1EHBR+ zO8+6=^cx?)@y71wH%H9CBJt4FSyRbk{Nh^WCn^oFRlgGR3UMgZ5;!&GE%k|v_Q^|& zz)!k7E^Xn0jH2Ry&|q~brs4i!Nsx_ z8_Rh-EF`usW|HUPLslh-%*#Yir-qbPq-Fay1tO$F^z~4B-!8QxEs0Dd@)8h*&!e&V z(A9~F4ZAVqdyz+oW}f?Uc=%aL9~Ak5@nsm)5!dMvn2R1A-tO+UtC5g?v8^tpXQx$>8?TPF1mvw`+C?{;V2>9 z)CH6CNtr6gh+*-?p7f$*m#6USGORcjq;xW0SZFFq#p;ICIk69+`csFWT{*N;c`6KP zg-^|XR@N63b*e}av|o_G{`3>y=O9Xd@ww-odvUfNB{d#n`inoHWb{YS zIY02ZrKNL~3SXjox;%}sp+z*Z$Ef?$D7;bblHv*25u*E21D$jeBk#+~XSaX&I%4{p($W#qNlr&oCq(@uC8WX-`C_pWCAqt=N{|JXj`r_3A+5evL6}8?T;t3tS&)YkPNKt;BT(6o2(CBdt?l ziq+ys$29_BNQ9wsv9F^BPzy<_sM+5b_O55|Kv;eyEmXrRlRB?4At97e=5%9E|3Y1k zNHQ^!8-)Jk_-+1^=7xW`<_eydD;N9@kF2c?n|pGJXKlM@{)O;@D5IutCh28ITr7l+ z2}YxEbNc$IxTu28<{dkj8qE(`b71b8HS_Ze?nK3{-#q;P^;TVtP5+cvq@iD(L6D`Ms2jb|n$XSXI>sHseTF zC#@C?>WzK_$ya(?u*bvpS!A*V^fEV?ROOi!T+S@AoVH8;>;gzG@1~-HB%*)-GFy^* z*?y`EN|g-*u#>Y$98p3ii{_iz>?+4fOUv?Q<71>(DK>A^X>^Y;xO&J52PnZCiqo*6heeB6mQ%1p}JOub2 zIYv739Kui}j!*JOOGkE=#Hmex6xZa7^+I(d%9#m)skKkP4)f;}xt$Lu1z3zTj! zouW-*UaU*pb^!n^~gz2c`@4UUY zq^XH)5KQwW$LXrlys6^m{jaTTgM(#f?u5G7iX4-hx^mQrM5Y}$H#Z#0@6)_91DvS!U$zj zx+j}{5I{~wisB5>(>*d_bhVD6w+!S8!17G&csRcMlhc=8-cfMt{H=oUFD~GFK~HBm zxljm@=~I$Oq@fYh-Q9WZ?lF7z2pWV|u8Nuyk*op_t7H=^yiX*Q zj)Klp^D*c$l&*$c_GltF9p4MiA$F3u@3~LhhOJl4V)M|`k1h*bwdc?wtIg=JIo-PN zy+_=;phw!_+&VKAu3GwcfVzrFj|S3%^eAyaOG#s-{}63NofqVVT4Fl240v5s9$JL+ z9M=zeH~m7@GZbQXaK@p}jK~!emXEV<-i$Q6;br2wh1}b6SZM~u)P}NT3U^&?L5`t8 z>C3ZaSITzrbxthS)RFl!wikKOsO#1YfJk)ki9ekFM$f)z zIQ==o)=}XXy*QihM5yS-i4La=)qiyTM=Zkpa{bMp8nvAJ;bw=zNlceJou8jxf9K$v zN^ntWDQ8A+ht#>M1RCk|FFZ@c%l7RvS0bj9xG2I_z&edfCH*Ul5zh+;RCMJr(u-6* zNTs=BO@C_RIWYZ!0@4TMbj0)n!1_td=Sq8_6Y0p2sOf7r;!Q_R$LBI~<;r&E2kJ;V zXTrv{8^3>bX4}lGgut|I1jU8p8kUp}lp9dLca_ELx_Hd`pdPy1)mz$|zaw9Cj@N}e z#`*I(%k9j?;IPK?oZq>y)dZ%C%qbI8iaJq^x{C9+D?WaJ#*_J-1<*`)stEnH%a>nE zevMcT#8YYpo9Pc@C>^7VA{Yr{{LTL|b(}^+|Lt$y`Yi`*NKL0TQC)LqXGmpu%^ji? z$y2%6{Btgq2w+0Xmi3~mpnD#~ka{N|RFZdNyNRggYga{AR1Ck9@7x3O`52fNjoY?@2hO_pVa90E)NUI4?sJwtPH2f z6fVb`Esehy~2j()gA~Nn!V-% zWu)n`QR%4Z5pe}kv2>@7O;5*hk9uBE5Wal#PW1CNYYs3!+R?l`Jsn#NARjTjf6D%O zeJf`ZUGRY83g1>053RGipf|Tyayr9r+oUmbf<49Fo=d8x`6aI|_oQWG^6K7F`W_`z z+)7}Y)>6?;&!FCca*Qc{1KWbJps$XPFE1|-E)9uCgKt~g7?8ZpufH^)G#UE}qB*UU zXe`w$R||CBIDq%1i%A}?m8yY&-hsA$=p1GI3Xb*QHi`>Tk#c#TUdJFxRjPJ}X{Igqu@qEOj?5{JM>)~WD-V1tp=%H+X z(iy+u`&Aq^V#LGwe~FC$XE*IHyo1HlK(58P$lqh&a%teS5(R;c|K&+z9-+t4DA?T` zgy|-EalC|MD4l{(L+N&Iw(e%FZPduohUHDNx?mkZpXN21B2s!8$?^i7TbvH16Pb?h z9Y?&uZ*yw-S=heemFfagJ*NzC+uC%U@*}GYM{@wjIYQ=YZ)7gvD$+tZVkE}11`EYy zJ~xgQ1-=-;+z#P-is86M?qiHE_UC3J7`lVS>Gq54i(q2HyE6OPKr)L)vUsB)G(;C;ZrY5^MU6{VBwWm1! zo!zJZ$IpKD*=gcbN;Yi8>VYhOoIX2@)(+Z{UcS}WbEE0_ncc^aMKaSMkAZk>f)O1V-B}>Ms0Sa zcys}UfsSwwtDxVgqFhi*omijz8!k?PP5`=VBE^)fN5VRjpG2BQ;d_z0aq!0JJ9iq6 z(Tz0xLio#Y`WZT*+K{PrHxte%1CG0`si`T#t?*FJmYl6yH(-4E6}gPRq*+nME<$Mb z()j+B>jy7l42!Tx04 zcy>KlI~~AIE~}}NE57!eL{-zelQT{`O>b}9FT?h98O-s((0COW3oW^@pi?P|)5Vdv z7i4*D9NRBYXDjV$`r^zCRTmVR{St>Bplwz*cGaemU1i}nmsv{B89lr2P{Tzc7m`EZE z9Bn6c2W(U9(qNY4n`hz|h3RS2rCR-hV0$UlqnKMV$Khik#nUw^F2X%-c{-*c z?cibZ!xYHFl_`LOH;sZFSZf4j&au(MDbMKSB5(uZ64TMUR~pq@%C}uv7sl%@3~A~N za~boC0m+S+)Rl|A5=1urK!0-T6h|nR=0TKoE>f3L!2AWmTo{nHGF|9e`r?Z};qW4A z`?HHyym|2Y!Al1*y8!1Ly?K$LhoG+s`j)KSU$>~tLIQ^M( z*j+Zxd357<(bL-vsH3c}<=unG&5zD3S_jmvW!C#VfiwG`?e3N%0adx-`S~d5h~~NW z5pp1ys1l|KBgc&PUjnp4<}EE0k#a6QUD%HOH+}%Evol}OCJt@1eZCg672`l?H2Rl1Q$E+>+Gs1efIvJ%-i2~b>L=K_l{pr3jW~T{k^ZDqOZN$ zc(ZX{ReVT77oK*NoF+?Pm#)rX0A5e%Adj!6rg7dpB2LH|S?yPzM1Kvr(^lX`%`X?=J>S7Q-#K6E`3}@{avP&IgXiqs)k$@9M78TTIE{z@^ZvEZCsIOM zS{0ntZ!*iX8vPrWtO=e32Ky5%zHMIC$TsTp{5(sS_-||UELD9dt%Y)XLG{#x@_Lsd{Z4NV)f+WeRT5c-I!UPbq#j=qj~8cikK zj6XpHOmbJBA_0=(8&y*pkHgAjo%dGxHzp?#oxVD$hR{%^5Prez4$l|1&j2ZK!sz=45;`GNJL!tnd^+RQ)94-jQ zNaPa7t*%A_XG{4u{0!h4SBzzPkuTlst5pBdakMv*n9g+1WTvZn)S~oB==$M2%8HYtqCc^QG4E@sy&;TG17B2EpdULQlY7K7;c z)Oo>j)7Uj~UIl{_yEEOOxq08j=jOimIh}Pf#{tssnO-KYa|O^B4{q2Hlo#rqy|cNj zSY?hF(S3XZ1Ih5GYzft0{2i z=mRd~WV#?u7dqmw_4QWji+t&@Zgy)c`uSFmxR$y3aXsmqA$FD&6|dh+aysVpn0@uT zdIm9`!1IGeJ*|6-it3LYyG7tjeNRRcR*>QxwAf9pac6%2`~UI#JGi<(IsNes4$m9k z%UMh>kFQ5yKdll{D>z+srIzXC@yE|@`I4TUm%A!%`Cu|s*YDj?U-Nt-Ibop2cv`B7D7xSLeUUD z4d@&rKk~W|9ah5Bk3i3{6_s9Djfl(;I632vPG_oHb0T)%c;{k6!0Z0rxi?x)4%xnS3m#dzkG5dWADE6^lCc${Phd3 zfA+(V&%ALaHfPJSJ$sfdz>}0l9%EWs6VVE4Kk5_YXsiCbnPdVFZ)_wng+VEaiP6!L z)6>aji1MDgz}LrjdR__}=;#x{i=mp95blQNbX%H3aXO`>Ksvh=6jrXv#!NGr>HyL^ zpmaFBW0!Wvkeu$0#O;DpJrNHIMX{TfO+R{+`cX2|8M{!fTd};9B+4MgdhiO#>%tdL zE)Jw((*l}Fx|Gt=00l{Vz;7N0QOa+vCvZp?+bGRlavmm6ZS&hkT@M? z2j5LLqbx6&Ua-BmCc4p>G>4DbT||xOjgY=z)!13fa$2#=Bd0GjaWckp{s4iC!cB~$ zE(pf0qq!zNx9-Zqdwv0-CM{Mrh65u_XE3$nZ9bP4LCS7N-h^mL^2_H!F)dPGwt zqo!|^n!d4Z=J&5|gw*H2;|A32cy2)5G&ho8eS((ShrNV!-LY##N~Z$Gxu!5wKG@EX zHJ-ukqo(+e8#km4Xb%pN^Ccla7nm_77|Zoy>P7<+AXRQuznIHJsh@ZaMn6Fh%HCc8 z3F`{1eeIe+9Cyoa?rZ0UrR`kJa&+};x9jkxE5L=aa?%&6J*@!GyAnum>6cSQqph*O zv8`<$a_rScaXNVYU^%FLh2r!!oay`bAD)BHrN67?%CCoheP#CkcN^!m4ao1(Kd*Ml zTm;sxo5PrHR)3YX_TRl5Kv5%aM`PB={Yx%)x8%>y^2C^qcwTv}q7qa`MW=`qIlbG+ z=`A&tOR^@-8#Q_!6|1GU`@Whs&1XgFo9dlguAV}S#iR%dJWiL(UGX=2iB!a{LY&Y*V^(r^ z$K}+^sqDL9UN}&SH>S}KX*{8_W_57elXK>I!RV9bWqAb;lww5BZ&^(sBT4S@Nq~7} zx7wA`whASOXqN_hZ)sxC8&I0i*HBqW^TT?2GlA&m>p5wm22~O|CDP=uBkk8@w=VpP zO)pdH{t^TFe~jZF4*zqTu>&Q4O7=H>?o-j*pRBoOb8(;h@Q9J$^nl{vhmq62X^ns7 z+XTWQYuHsP^dls*O!1qhymX1eD&%Cq+z_trDE*nA@d|4h55ICBQxA%kZh%#Obn6j3 zgpyMQ6Cy2hL_?pVymjRCadOC@r~~PuboS36r$314i1x#L4s`R(Jh%PX%^A1KR4&Vk zHhy?WcGrtA2Rtu466IVejL^9x^@kZ+Wb}0VtC3L!J~uMCoavUBZcyCJ1oVno2*WGt zMdu8?2iAKbN*C+f4|<3_fO5+4Cl#7elz}}xC1u^Zg|lMHns;V*$6nQl3h1-h#e zj<66nZ;$lsbYXgS>(35#@z}viGu&A{N7%tki zw{=%*U&pccKmGI=fgtpfbj=}@v1D&iT=gX|{nCvyyGeREedBTCPJjM;&#Q!#IV(Flx;VOip0$zNgGGfv_Rw`{gUV2gnZ;)uM2Dm33^VU? zBnjOk+Q})sGQ8En$=y9|fqS$|q0!QtFhkpXaG&q3$Ln%_*RJy)omV|UPG+R`tGLsm zhb~X{bVgFlv6~y5ZprC@I(vu~ zEBha{9dDM86P>5_dF%txNn$?)N(U~RwE#EFUi9>>NB2Pg8pGgiOg8sq@;{(+b3Z%1 zo2dgEWCpI8L(C#_a!8OV+RMvLbPWnkqxh31&_S+T4#gG~H zwXwZ8csp|^zCq4btdf-UJn~)mHCzysUKi))%bpwfTZIsO+gJe~2RSkh(GgKQvkS8; z>pXnBCMgQrXpV>mH^X-nP_qSo<(#pQNG#=ql}0+@gks>c;&d zVcjsg^mMzlE>sueKRrZJIfa?0PW_Y<^$^0BBCIAmh0C~4q^G~Q=*2}eK@z1~Q^7F`5!mgl}=TVi=W%u5cGHUE{g!ZytR45|nPI^LAr`nSHN* zln3F%!BBJR!yiEDv}J0SHGMW6hH$!2J&Klofw_cn=pd}CyV0{N&Oz_$L5fE1d2%)d zwL=oqt*CU1)1{`r$vNEu<6({)(cMx=|H8?99&k`-Pf41?EceDh^gU+za>7IW43metW9^jMo>Ith2 zTcVpf6VT0xPM71wE~nF!y(=F#NYWQAspy~>Xa?Y_*FbbMQiRg@)D8+rZ+GAQjj^BK zhv+}NWU1^&ZWG^F&*3&Z(mIZGb=|$G_!i?o=fuMCt5@HhH*Y_U>*s;hjaTOh**PDs z4870nSJ$qkqVw?KwQCXHdzZXBd;g04`xos$yjJULyxTah_SZ{(4X0B;dNtmf1@K^{ zH!}Kv(RCM7Hr|@HWY8@kAUIX_bPO)+ATUucGN*SUxP$9lNGPaWGHDWT+Z2@f+ZCn# z=eCU=MQZxUFy1_jEcjT|<_Ph;lFD2e|0xaqDtCU^IifY^ubF=!Bz*JW`W?${c1Rbl z%kRQTb@cH6*KhHBs{5MWa@^u4;`?PgFAetdY)qa@AJA=nrB$To;CLaU1-*S6N;&Fv za(QY3SupT9S~<)fPs=O0RN|=wZS>oQ>jfn}c}aX}l^+jcj{}`W{iqQQi0=xh!hN0) zQYvQ(&lu2sSz(OoAbR;kef@fLVj$*zvUogYLbl-8HGf+sN}6xouL` zq-{J+{M_Dz(u9i2fYO!<#P(9Aj)a4vjVJUKwU#wdn^u;D>l~|kGD$@Q{uAv}R$mgQ zUR)htYEVk7408av;LB5UYZ{uJ{~RCR`(!5W9Qhw(@W0?u-wFRFHw&9!LmU6j z{BN|VOwA>)vEZKGZVP#A#A8wSw*KE`G12g=HEW#Ket5KYtgMtBPJt#jFYN6idC8)La$pl-#yn9Uo;W1dC$Z2j18)E$hO#he;e zH)6Vx(~a{5YL_+L%t*A~zRm=;N*?_yw`MF}ip4rGFD)-E#U?MY)bygnoJ}a0G*!Wu4*0q`6UK+dI~~Yv zr5!;_e#qR^d}JNUxTT&`MY{VlA{l@9yaLlRjwiP6B@)s!Bdzbab>vfFdPydo-U%ZF z(-#k>dqe3zyQ46}PfnA{Xhpq9H7Dr>K1WG^-uTs(#%MSlOU%cw8q>@BpLW!xH~CJV z5gHVOk}gQEZ{6D}j}Cul3#Hn^=-6FM<*2$DA%Vl1RN)mCk_6Mbt7vNpfjBNv&HL70 z89F?=Gm7|=!or?ny?R&eh2Vm#Yzij$1vMQN-lMfBrwB-A0+UHN39RU|m@pKYcLqh+ zY_3I#o1BWv%06#sX!v|b?v)+dml{NSphQyKi!uln_rTmw#~-&daC*~Xd@%cR7N^`e zPU6cifB8%F^cy!)B4f^;ef)7b(|5lS8k$M&A=8`;0?{9uI^&IndB*bc$%ZBbX>VK1 z#hvt-h%1a(<-N+A58BBmD5xp#p&*o_ix<7eBBw_#Z6d!O@z z*a~AE3w;z~V}|n zbpE}L^Rm3incj-h9^n=NH)F3ZF2aqUiQNU(b_z5~Fz*}_rDB*H>6z|7gb+G;6Z?Xl z1X{L;80niZbmVqE0etpO?yg)Gsk=!|2hrIOak^=ML?a}XT`(2!F}qCIX%dr@SyHsi zbUQ$h!ux~gm!8hgmQ~CdNO;r78e<>i=ELisjCDVcMOwdrpn4oUzbK*vdt-U zhI4vZb6s6Jp8>5#+53QbMh^GFXdhb>u9u+d>{$1x=H+D`z8Q%nbl=L@7LLZmcWr2ec?*6(5ZvoHRHrlZ$?_@f^Y?_xK+7(kcriP{v3F&yKn}nw_|s~y)J8wN?V_ux&2K#5XqFj5nnvy z4yI#q*)Gcqm!ze$Z6G_w7lPdBe1su=#fNVmAi^bVh?$E&CVMO7#pvmV&cX9v^CO$O zDI%qYlp#HP)F`W36d*@lXKElyXM)h)j+#CJco(EY>FfqZHs3fN|N8x6QX{DwP&b$C z@NWO0=%L<`MA!!4osYMLk(%r052O?GIQKwUZSCwKDpuFz=VCVROh7otlx`qh=X72V zfK&nangr?wb1|oPH8#@IX3c7HKB)Bz!1Yq!ak=Y=OfFw1e9N5v+uz*1cD}5ELQZVr zzqor>ybUjN3vG$+!MCoXhtE4a56gK!7vc5&9C4lN&O&-=`EQ*S3^Ww8&$%b(KR8sYiNJ21DPpNFiO>xuV# zeka~@(j_=qcK%_;7qK~V_FD+w)0A^m>H^9b&cvR`9qS3*qyyq*<6eFRbF0bTKUPLglJ z>1t<`%rt@Mpc6DXg3n1lPmccpN|(e>zB=BQd?MvF2Q%IZ|3EGZQ*;=ycd`nA3Wp_X+vw`^XmKJ<31Wr;`ip*XCte4f-H#8(+Str5~ zPrV*m9*1vZo(J| zDrZXoX=}@5#nEMh=2|o?px;}dg$$#mn^P5#8rO?)xnOreO;_BD@x7Q^csb_bcF&6- z{qQ|d=Yn*42B^;cZa(v~->5INsWAaL=2L0FL7vibGAGIxD+j zXPMh{pA2722pJiHc0Pv-XkWBWIdbf)pB|Lq66Bk*G{~ojSjCj3DfDg0SR7db2e7J% zY2*w7O0@cE6^>#?R`bI>Zm#Y)fsxXSV`TZLPYOsbU9!Y8d2X`jfuwptZ+dI}zOyeA z_43&}F?&B+w&8dY%}ApO?c2Mz=zPbKTkpU2>5=-qtOQQqbae6JrsFrfzkt)f*nGp} znY{DPbxG)qvyZ=uFn?sCUOQ&wl7hIwm_o;5d<%3f zRhSF(T38sZ06gVzV0ACT%R!B5rs?kLmYGOg4CepE8OME&`!u=PCLb>>;>G3^rtd7c zb*0y{)-(6zf_Hd3T{EM5*kM7=4u1Zg<3SO7_MoTVNLjphUu$Mi)A6R`GN^;;;`AG{ zUVY_zk6(ZN(xq3^LNoRrMY%3vGNl62g|il>e3JCbYqtlRB51zq9poMpRo8GkJ=%@% zcyH%G-=$0QQhacyZ*HbH>DdL-gA$`7Ba1dfTdK>ZhXC5#a5d-pYQAeZ@IywWP>GMqtp=1#UTRs}5~B zB=s5`R<-7yLmt?IT-I;qQytmy?Ls z#npKMiRZK;WiFAkhZW27!cjxljAG7{>G||yKjR{S^$OO>`E?0_FbtWdx>N~1Q@^m15 zx>|_h2lAk)OkHtZojw<;e3gz9NGSxfMDk!)oyUnRb@u2} zFX2yz)8$Y%TDrk%FW4C>hK7M-G5_};6w`n5j|UIlCv=O`v8F@nr+;+tvr`ym=rxLO z1X72@b(M?Drr$Y9bGvRa+(z#&Q(r2!G;)$nLuAJTeY%P_o zYzXl#Zyr3k0zg+8DcgpRo*LK{{@YKgf)tV5^JMMQWK*jodv~~LjC69S0^>#?YI*^N=J3n}u*C?-XBZtCdG>m@hu0^1L*15QBe&$>zbR{7a0}zA7-Ba_yebU zQ|Z}=zvyZs>E(1AO72bSC3~f+aoe`6fo*MVW42Y51_Z3GswyolFX!KH71&M4dl|4<&qo%6({>u^^eIS3SEGooY2|bk%~=b4&ImUj*5hMRCEBn zH@@rg<>V9QimvzfpTH*Gbvd~)K4c(^*Sh#z|SE&t&;c^KZIjw0+l&!-^c{~K!h!+%CipAkX<>DXq(nFkQI&Hg!mw-jd4 zG@`c9mLnc*4gNGrOqaqeN=JP6Qe?V6&U7d}Ox=vIy-ZVfI+Tv!4y6n8HO#4jbZO<< z1p6|>?PiIdRzr8-o}3v*H~w>8m0pCm~elf!};)2Ac3Mi-%?FHP~msIoXkR^JUpTQfj1C&A#lQ2M)L#70d= zF3wbE8dn$RAiB0wJ*W~=Wa(Cqo(k=a{a|iyZfDK>3aROvd+?T2tHIHw(=i|I-8(qg zN;gsu({(flXZn#(U;FgdJ{KRlOSsTxe(~ZnH+F}9rV`TUiAee6W2L>UR|V;Abn{mq z|K9rN6`X#0*!1%F_l!CH74&POpdy4Q%xZ4Q(pQ-n&egUY|q%7mS5qI+kTY zdN$#Kvb>;LE2uHkDKXI_y;w2kKxxrY3=AGQ*=5-~*Bst>Zbz(lM6pW`rWY3<7b3=K z*lBY|ohMF%H1HUY=omFGm63yRK{;MPSG*ZM$3==kK5kCO&s66yGg;;x`|=e}Fa9~b zMB~CcWD6+4ok&JHOr@u%4+b?wtg?mP$V*{rw6C?$y{YN=;u{+_pr`-*=l_B~{f)`Y zRDSgO1=Mth#o#b4b@aKUk(s{G`$omJYki+=*icyQ4er`(#dXbf>C|LWW-3mfp67GC zDQ#-R&h=5vF}`Vm(M3LsH$du~J(E6%XY}}SD2=jZWP$o{^qor8>+$q{8!h1$+Gl@K{4Ha?9!_3TZ@?nPzfzM#N&1Q3OaBzwsslM3$ z*Fd$QI`X5`7D?o=wgu`YnVh;zhLrVZt*FMQ2w0Z@&xv^;cs{`##p!e(wJhpbNQO8p zGN5i$a5V+3g@!Hri(O5B?jJ85L`COdj)u|?UV8l?$&9BDB75_YbHtJlwU3j<`(DD! zqGzZ$z4WGq=U_V*P|~r+!0Tp)A>mwG{S3l6TKb}uPrUTh6D#S3^ehXYbTo829N|jm zni12nuBLsmtK0*#4+Ae(@ktThz`X|O_!j~#dFBmLqp?cTX8SQ z<=9>nz&LWFlyrVJg72d?J~{#Yylvz6jp>D0mxn1hWwe z0ZlxiqmrsS1ai6;&G(!ehNv`ZR7lvg@jUL)!{f&U!!C9{$A>Od*Dg_5W2(B7vYsAfxS|x-|tpd;+ z$MEpvtgLPQRnpf}OZ(@|+15xuqNJ)u09xMkE-;-Rd8a<$gnHzzUPyfaIHy%;Z*mq! zoB*CLK;bUI$xA$!1bca95zFJ3oZna084%Etuv)r)3!&|76zMJ%n*v*tD3u^QQ{I|V z0vKt!)F0nXHceRtO>>hP$||~*2}4mUk4!F4N{a8L79+QJP3~Wg=~I{g*O^}aoSI(j z_3((tzEK*-7ej^Xxcl?Iv;sUWx!-7$F>Ou1y&XDs!j)VuaAiQT##7FILP^dtW<#Qf z)!4`YF{f&CWc2ennAB-hL^n7Ct6G^>A_C@4hSE(SqvZlIls`^{OeM=jap+@-by?u#g4`OJ0+(;-*@}#w5=gK( z!5JAPxR+Itm+0s_ks`$zSh2Bt;KMF*4RmsXz>11oT@nfG!1UqKnoc9%?0uhqo*lRA zc1?MHS?jLP_wCxcbueyyHZtGo*I)em-=DtGx_4KP?BMA=w7zML&HnQJ_mg_#KRv%M z5gMcyJq4th>T&eL-~S(Y(-G5O=I0$K{a&5uBr75Kkl+?Z(vI3@f&+KA*W|&bKBGWYuM@=_&7JG8txws4adQse!l4aXQOBXsj%TJGj%yW##e!j&cHfd8V zE^2zOs@an&N!7hx)M^a`UB#rxo=#g+kO{(cPiU>>Khw6d9;^is(N}mzNu+eJR!)4s z#PrCW2a;kVS1v|^ru7o>jJFmq-?(@;a{9mh=HEX5{1$D&U0MhBDq30EoiR|R~?84PmB$PPCJNr`qO6(!>w9F&`Z~p%7`3{RGp74q_{ZULlXLn2ZLyXduYoFYDM22 zL-Mh68=7Nh(e%JvVrj*Smy5Shf&jNbNWaQcKt@MRKe*!MgyMtG7(NHnnG58?;py>o zcl8bT!=KJH82gIjA}s38WW|%)$#0JK#8kMdGik_T$B@MYVd)}AJ`qN4 zj=i5}m6JzuTv6+43{$a=kyN50kMq8;^PS!BNnGpbSdr~+S44GRk)1nln|k2JdpIXm z#Ntk;!4Z>7ufF7_6sD~=IL?<_-K7pk*I7Bf0Uq(*BOhU0mW>%~R>bP(M- zQb1~aFRaXwVf&zrI35<522Hn-kAdwag(Sv+CKRQp=$NP{`Cl;k$w@QD*M!mHNCtJ3 zbL#-8OIkO%Cxo3emLfM}DyO~8bwXpnH<&9hgGk2izT3BdY2$2Ta52kTLP@v8bT}Mb zZU+H}GSSin>sra2!09${H}?a{<#|cOl)|DoeQH2Qk5SXf@%z)doI5MG(^1CQby}n%BzN4_UycKHi&APWXh8D6>7iR|W(RCr#xpa-A&39MVc>kH@ zN4&$zlaricL$)-Q5q+C zW+3&WnWnLj771?&4D56h>Nn(t;zy?lwJ#$h4X=A1S7xHZ4}s}48KRpl{&ac`VR;$2 z4W?fskzdXm|KUD->8a@Zm|!S=ATyHoO8%h*Yhoy5_0O9c+TtHppOHp~BeZe>x{_J~ zf%CL9oGs+^WMl+3ga)Q%!QyH4f$c4U^=(<*a-^rxHMNayNo3jhvsoH8VQAM_OKQBw zUv2sb-Z6&hk9pU|=wO{d$N%N=7u59NRy;3LE57?nk}#g`Mq^3}naaswUS5B`4XL(e z`kH=cddzn};(zj18|bP;RQ036Qy3OOUGa+YrDIV?2B+^R5mf373bcZvh|0h!#gY@H zjU#^xQ4Jzn^vhcGKr)83(^1kxiAo34r;@tvkMYHb>EkIzHJj3g z45J$oXL0PDMFZl7)OA6(*wzKVHQfN!5zR&88iv&ks9RS(Axn&f_~x|;(k%k#jG;>+ zalKOg=v|R3hWK=KKhn(x$p!G-u9vPKqs%j_ahX1Gs<;2l(6LW~|NiP__y{S^k+gxQ zVx!1m)>G^8xX9=NqE88)^3+n2o{4f<0E{nKzIZ`?^$0CuKuZIpIx}|PbSJ;1aC&$M zCIbhm1?jK}uU5x{=_-CK#%t_ZX^iP$`m0qVyZajnWF(t$*Z$qNvbVl^Vbl4@tyf=o z;lKa%793Zl0!b2Rst&aV z|It@p!t(LG3(z?_`fG2#_S$)i(!Y0DnEpEgUk+?4e)kfX{?Xw(TeocAvUugv!2_Pi z*sBj$B_t(n$o9mOZW@jnTRO#~#n^YM^9eFhrXBQM4CE22$Vji=RqWwY^vb@y7q^w& zJiTcX{^?5T$G*B9DBBdjNk-rhU=v1nK+k<>J*Qr9$z`)yqGY?ty?#REM8E}oPgGxvAA9qROf$w_ZPqZH+miY z2IC86{mWOc{*L6z1-w^5E9H2>iK-5MzTj@r}=mwXnU$| z6hWEqOFU{ivlcURVMj~_knZTf3dQ8eh~T_s#gz*N21S4k7MD z1Gy^%6z7V)M?A6Ta>MvVE)H27xzcfwq;v*#A+Gk!o2qFBOhvDQy<@mT-0HX_=OjO) zjXTnH&C^UK5b*8r>r(P`I3 zwdB)kX@s$5&KyI(hSAN^*ojS1H*4u`92qlg@r+}&rECsTM_%63h0Kj*#T*3C-m3ye zaeqrwfB*gGUijG?1Ten-v*&(H5aa7Vm7b18U6rJlx%!RwfbCIr0wQIcv6%q!Jx8GE zJ@Z!m{PHW8e+;zGGa>5AUX))QYq~-h)uq%D)iI{O_ujnO&!cFU(PgP@PSed*^9g?8 zDXgLoDaLffbEsYM>B?iAKgu=KjYg<~6wiyS>D~mWTOlu2cDfbAXeeCkmWsxKbPZNA9wO_KPHi6) z-A2*H*Yp9{pBy{hhl`~orL>k^z%yrNm4;sI?7A2=U2$l6p$#=*L^jI2o@H@5Ru6=A zg%r|~vn~T`L0$Kb9o_X9*tJd|DSbkwlgIn69slKhZ;N4V%;?rRXSO9}vrOzH&YV2H zp`p~fPsRZ=Rn9zJ`v=`8Usr_Q#3=6GIKbu^uA z`T9nCViODR|F5&}6ZL|2{`S{39f>iupY?QPX6k;Hm@Y71XED02)Zi*^qpMWsn(O`@ zi4z-Y8p7(k?<(!ZXzF!$>UJQ1BdnM9u8l#D3&^{e*VPpjb@5`8SHO&CCvBcF`N_GP z-DYfd+w3+vadhI;yRDJib^GMFA$UbrDHx-rs^BCN@pfj*?e62L@}>;qV(Cn5$s7jK@uzp@LBZ`VLp5u% zFq5<$3sey(?43b-t6^#rI>}wf-mZ8>-nr1!Oo~SvYWk4U{f9E8rBfB564b!70W4B* zcUm7BeBZI-Z3DN#_1hR-22yWd%Q#NAEX4HTfn%ho=OvN`L))X!me871vfU|S<*g5G z@Sm#GnLzgG(4&aRML3&U(*bt*Fl*paDYHAWF5!e@`QIW<{ky&C;Yw@| z`%Y#2kw>yY`I!%Wp_cFm`+hv*pZtOa@5M^vKlWGsPpTC5z*xV zks=MUPntM$CZ6%Bl#Pnh4Ht`44UwXNn`lPE)Pi5Lz^N%OmE*;@UgUWhKb^(#hSF^@ zFKTF{EnAo_O1J7qt;evQnn)Pxwhk7O>lus4t+SG3bW3VCtMl?DrrWaHEn!{nA~#OL2Lz=@MU8z-Q^;17 z=VfJN4#|JcMLTw^b~b4)1`D2A`V`H`7x@J_1d-&DL+PaNg2fARHs<7Pgu!5D2%YS2 z83?ElbanvKrz~}JS9YJhTrY}&Qyz*ZJro(a&TuR-i&aH`I9%1=|7By%^*Mmg<;URMYC>VI_>GN0r z_`?tGP&^8y6Ug|Q5z{fg0P2Y72fim`x)IZ5hT%#KFT}sZCLBVY|LCJjt%DASP}4EF zV~gilRFsf_qiaj~7G3L-7JGN7@&m5mOy0H;`?Bik8iR!a*D!XssyDo09gWG`Wy=5S5bB zG+MR|T)!C|x3!Ai)E*VtNzQZ$^~)LAkd5<$@E64W1kVaE-99~kd*8iZ|N8UaeEgfc zpJPxz_tn*_=UzKMxL{-T7E@wCW22=jwc3x1001BWNklZ1hACI7#zK8NH*Q=I9()0xWpZ5q%Jqw>I@l>^2-Ad0`^BDxJCb7;xw?is zdhmL3;dHurIyn*7XwR3yH-A?K?364UqZUcP+R&MLx&V=#r zB%zEXzF&9-SBbhC9UTK?wDp5zz8p?C_{>4f<!%>qi0PEj@=^07P}FBF4adh~$lIR2qYiu^W~T%e9}lMrXGJtFj-RiW}+8%WQ>awP*k`z@PT|FY838VU%_kR4=8>r~eIq@!+QPEjI zOji*p(doZ^>9S}QPqsv6m{{rARXC#kHr46aib`*yh60Hl4Bbam9Qq!p+ zWf1i8?2}xF^gfrMMg!$WMA!A^@?`$Q7<9LNP`F%5dehbhrYZdtOlOpo7O)H0J77&z z!^O^V6EBV{o7gq6%iBA&prCebN|y3qI6+G<#hcz&T3`Q3V>h5qzeZTUZpV(c(#Gr3 zH}NX3jR|Y4%eZ#!mj=^K+s`pPw`DVqLAr6BC%U*1$emiq&hgWS( zMAIoe@NC5}xsA%j=4P048^L!rq;!mqcgYK_>8)=)d8hSG-5pNL$!*E1smTnzNN%^k z*P5t_0qmT)7ygIOlnqI4IunCbDxaA!65CV5Ng%t8 z()!em3Nw9PX9G6$w)*YcGg50X!cf#oEDicQ_lp^b8TOxwwbuTkv1F$0J1)#ZLO} z!qmUCiT}jyhH}Bs9$8!_n=(pEPZy=a>FCar*e3;zqk500>yQzS1-DT8B%pihbQj3h zpt8wXvF@iXNdUTWyhu)0C?n0CF}u(QNtPFq7^6h#Y*z*m)O0!|LFqWtt&JHo`h8Fq zfdkgYNN?EL#^&aXRiCw87N8sFiwNB?y2a+AbYpnYMd7=)CQ#Q4vJK0B&ILp2dQIG@ zXP`+3J|Cl~TkGl->lSmnc%6$9(>d~{O!W2-_44u>`xKs5A+|RzUzp`467h`To7vONBpck6Kb3vvJfDIwk?~z~vMO+1=!t z+_RFkN&0XH(sP|EF}?Kfsye*kaCZOx{>GSSFrDPPjkmz`Y3B!*-n#R_3;%R=Va_3E z60i>!RpxJ8yx`?a@BI7me@*SXdvezyCxqSHd?ey6IkB5gpa0_rAN=uOY>6(v1IWo@ zv<)gqH=NsWZr{1@*%BGCrvL6WIGweN)rRz=kG5}(3_5f|4gz}={X@9ZMdgZSgwava zNlHKLNncB{-zga-1cc~v#9ZfMpqs!&`n0B3=N9A9j*X40E!!5bH!0S+nv4=AF6t&z zRmuJX(yK8ahuF(w?VwhiW&pTAI;IObrls>bdE}A=;_i@eB|2tw(vv-1Ddksw8+|>c z3HTYkc)5H-(xy#GNmbd-kljk>UD*kW?_;8bJeuGUOP8dL8^7%PnhMg-KmPbP3Q+(2 zF5QiOcYfz$$P>@YQYP%{7vCZ>z5Yv4I>_eaTsaaS-!DohP7%@iRUaaM^0k}9F?dPR zmAInj~FW5-Xi!ZBDRLr~NoSx5jO^t)9P5;sTvVR}iUA=rUc{UYE6=dt9^%67>JUY;K zhj2@>998p3VFQVgjt+$Uc<|Pxo49sm)%bwof?zbgm$cmt8y)B-3QCtS5e?hpCl4TfeNiDEnTO!zXmqu7Hq@m7JqM36eGk7 zrvvEb#~5EM_lxowE!7=LH)t-Kx zT?VRy=1A+5m>N)*=S6q_`DMA+_spj8QrVoc+1n!a967UWKH=_2=r?72m*qtrNYA_n zY%A!69;8i8%TzTgH63gE(>80m0d*^t(Ihd7(K%Q_FI}@qc_4|}=U|pPUC8t}am$5*`QUU^jP5i{&AEKu#aIqxC zd;CoLz;~@%H`is-^ov~=>D3bxI=QDVPg1KnO=t9K8t)T_XZk^wk({ChpEK6M0u}YZU@vFpj zk3XI`P%?~x<;IP^53#qOqW2IR!Drrq>m^j)^qxm0tXr){S#5Z@2ZOX*OlGqUdv9D@6yUH7a$5PWU+QCcu?6XWW4Y;qSi_G~M19fW|jPGnuy&e-Y z5XMe}9rfj{swK_3N8x1X#i5H01u=nP%vl<<)^@G)zj(3hNXq4uGhMVbq9MyTB{fsG z=H@m!lYf;dCFT3}M$^Bkv1HAfv^eU6_U%h4q3uz5Tx@n6zV*^LF*^BRo1Bw26~&>f zCuNWQfBgrZPf4I@5R;`LT2_46txQCghle`Y+0lnrqygtk!vK~N>PTyb@X``-QyQ4JKc z)?}_BJBE=ufUYki4JH~H-kCrsg%K&ezCKKL8D^10x~FEP4m8sC2!uC!eoYLv^_b8o z-P-Pk@h3Dhv}I<+U#+H3xo>)zQT`CyFZ~Co>2cE^e|-F(o6;@usVIsoTKY)b6OTVy z;98YJ;zj`@rZz04moMLrxNMK`KLhM`QCQv^|AI>YH~VVBs$eZX~TkFJec+cS-qm@yb;)|G-}L(pbLotQ_rT@tJt&x_ed zfS_*FbW2#5@5MM`xP!L9bi)iAn_Cw|>gF+Qk1un&)u`0AuFZ?DCt`-yW^gN>7jJy` z)X0o|AD;@s&4DWy2CpP3&N+FGA8H#_&?&k)@y-IQ#%nw0@gj_>9J|U zzRROe&cD9FH3Vl&I&Tm+V{yoJAdbXgfs((|D=489o9kc}Y=|qqRm3DCp}43#C1BjP zo^eg3`B```Vu#ZHoTwhD}>HB=LJWYt~avMV^3h&c?x=J7t0ANxJ6`?*8&# zVBeQ&b@Va5m(M@{`07_bJ$K-IKA$Werlm`Oy<5qj{5s=K|Hi=_8iU%~k7O6o`8B(L z#GX_@`-%h)pOEEnI+dxpi-LWc3$vS7r>~@aRX;c{OSdC|A#p|V*~tkZQ(UXCQq!8r zycDUxOgH#y?7~V&B;)bpbwu-IoMgws0%0+)TbaVnu~?>LOwT_d%gf12y9qtqPZdJ0 zpI@XaJ+>=ci3=z2o4^v(Wg_U~h371JxO0Pp550&yoE4PA%cl_&n10a19WnhNkp2VJ zYaUL3l|{!t;7TdmsxQ?wFJ7=B)kVo_Zp8OkrY-gnAgeQ@WXA}Uo?p$k7}@`Vr1;{X z6UgbiX_xwd(}m^V96XXWOuP$=dTeVIo1>lU=q`1TeKK2|@W}Ic{H|czadHS@&P4(D zQU~oPaI~+eWJiJrZXb3Pc!UuDg5xEJ6F?o9U%H4^NNQI~YG+P`2Uvuc*MD?vcHtyso*h2k`#9Oj)U1?vugw z$wa?wLsE}e<-H0}_g>{4L2e+Feg@0Q>lz5?G#?eML+H}dC8g7K6y^rCN3n?DcDVtn z&%SZ-9*2t`T>RkjE3e-~OD}tVGx0B~E44r!HJuPKloilh#v(~XIEm-#@r#B{9bJrQ_bY<-PP%nNF|5!4N( zi`3sb)3i*1>0OY%Zi_=|$rWL&6@tK?O$sz{YSy{u)aQi-#+XM6 z(?iFjnNbC6#p#xw-c~AFCpx_MUJcHVdOAJU*R__GUaw8bN*P##C|Mhpnk7n?nm&B0 z1>!y4*KQfl$0&WwqE22*$NZlE)gd5kNs+|V^V#*N8*g{qxB)GyIpokViHT=BTADt? z%aZr@jh=OKz|8LmNVL4^Z+En`G_`d2llwx`qT%+@h>kP3&xbmD5?8G{`~KNg0cV?9 zhCuNf!yTjk9T5RDhjF++pmGb+bvxJTpcAxqg#9dp?{X#}St)B`8ls{aq6%sX?(t6W z-eurVH;3AZop{o_&Ir>3x|*5-rjL3v!#tsw!gR{(*6LW3)A8iZi`Gk`+{kOtJ^!_bhPL|?B+VjXx_eqboop!UPDS}?`HQYKI!31;2VEACYQb} zbnniVw6=!8x{QVfyfk$u`&b_!Pdj<3u8l;N%$9}$S!U9XwcXBafXva(uib7zNAErk zsGquxZ@ulEjA0z};{4QszSK-wnF7*zc{OV|3FW!eWCr#H;+qK^VBb0)T<7rxi>aX@XiXDM)$4~Sx z$lBXnoOkaIU2azBzazBRe#oCtq^{k%+`{B)uhS9k!GmMVrWbCpoSuD=8BIJdc>)U^Fw32T0A0?xQ@NO7)`6j};fgBI)UjN#iX__Zl<3OqoS&b^m_$_%F||&Rx97 zJ-K;Dvi*7p-EVOSO^!yC=|Yw0Mq!NF7y-!?4GPR?n`koaOtPI)?Q)ze@G{#g{F=~lbZNx&?WHl-|4^j#lF#p)9;AK!%E9xezxv@1|M?E? zha_ZeIDK&N{2@Fq$5R_VxqIi!Lp-E?&H{Oe?FSFsLQSXO^mj^OeC+^AIc)xtak&_$ zi&Z^pA{to%o&7a9{j~$XSiq0w1?;zjW!+r|*7x_|hfCG9ErmWF+B# z@GrHbs(i##PnT2*M$yFO8&IJm78atwx8%B4xmFeKYh2aSQyZ7$iZ09k16)4pbnh1w zVxqa7)2W}u@xTvY|Im=4OAfqyh2lsO4)196n%>jn;*FHPfqK@2goRi3-t5BpGG~w1 z<$W7AY)JAT-8`t+bIX?8ocO_?%>A(5-{pGJesq5c3LRL5-G|t({bT(qrG@=whL~D1S#f*)+7cX#f z4_=ZTm(0jnxpF73CMU$fDJ0Ujc}HD+TvdpNLpU-mlxTTIpmYw}qmq4+|H~P)A#FQO z9wU9Eu}I;Amy^Udb}-hW^g|m@EZ7aCt9}$Q{Y3Sy>dKr*V&m=31C=0p2#FeWfqrRxRPgU<-krKXd4X!%SiCh`9wj1F+YyvjoRCC8SO`k35dPnsBt(^TcvZD)w8L{{Oom_(nw6c-XFv zcK-4f9*yb14~|+X=~~5tbk;{tf96G%kJ`j^_MXTpRgn>+vf_5$E{9|!>+_Ept6cL(^W;J)J(`kgz3M+J;e5B9Ne}gxLCUS z14>uiOT@BO5rDc{5;0_gF{mz&I)nS#v#p%GD#}Fv@a1dmgPt z=Z&hUbk9Y!bmMt}(<3;}e(v(s%kN2EXV<{!GAKP_&*hsWw^Js%>b=s}-y)Hb)JPO{ zE}9xr6ZEp@%&Kjp53K1#Gg^@T26#S(=xFFhMz>LV#JtYgdUn_-@Us|j6~$T{|vma}JvPr==`AeW(z9u;}YbUqY1(6erCPvXt% zncNDd<9EJ3@DuQzaK*D70Zoac9mK*U_P8a!Pa66v@La0F+mon6)BzpBG*??ztF=+x1UQKkeu5AnDe*16$x+hr{qHN7CF;4^h7 z^p5f>xR=#Sgd&Bb^^iC5=|nOT$|wvk2)NkQ6jggU#jELzS8d8#@End$Nr@>Sk+G?u zX|$_0C5l4Px~!Ttz0GyW*(2px(=YGc6jxYL6}LAzX3cG>9G}Y(J6ml zF#3~QU+?MNfGMPf>d{PmhwpU%>#5s7I<^(2P(!qo;yqcXsLG)l+I42I3x)DgQXAXQ z(ZTeS#|GNh%_Z&pb`}Mnnd(~F(3#kt7f1wsUw0o7EOp1=@xDMp9S1T_?%I;U<0!#V z^`m{)R496!CF1t^N~#U@u|CW%1E+X^fgxgI(B~Tzr--tSO@#pVtgO()JTe$DAmME3 zOGB1d@cEk1;Wae_VY0M@Vt{GL^e3Mtki14h-t*R=st2~M;gLiAGyR7PNT8e=T2m0( zLKUf`_V&b38nJSrNcrQBPYCn*bFESzdv?-9uikyM27g#t-^Yf%D<0bN-*Zu@ z3b0Og1Cg!pbG0~vZLP3$V0H$fi?k#H)n$5-%BjE#1p&Oif=7q~b!@ePY20g3^~eC%3lJ3}vN5j&D$qAA)y3SuXkcyWw=Y z`LMS=K3y&itim41q=@QB>zLCy8e1>ll_lZfIB1D=!C(xeJ0KlaR!Uq4aqV+G@w`;_ zC-3hk+$DckTTJwZS2s;NfBw$hyL9HsUu^g0xywH!k}-Q%_ST~9+rhZX!SkyjY8nxL z^6OvM?XK3NqIoXJ^^M(hz^Lgzy#=Q)#EfnWOE=>Afdj8mKl;4`mNQ)%`{9LB)3Ll9 z7%V;{N+;@N_n||dZol-78HYdp_d}Q7HI%NNqn_YeaRnLN6&`AVDT{qI9+Tp9yc1}< zD)Vzf6iqKq-cd!R|8KqK^qkq3O^Ao_-qX6(G04%u!IyGD?n&J#Yr7jj=Y4|Jh3o7U zkV?%XBvc(vD7u1_-qSOAQowbjbh`8;9DcRv%7#B&KGQYl>1{t+cJq}hS2p=nxE~}m zWecwGof}6Ol~m`x`|itww?6+(->=g?-#EtUAOG>ESO58^2L=}}1_Twwh%x=kPd@o1 zZsSfxbH{?|$<1}m*_BC^gr3LKrXIXo&JGhkmgTkVCK5it|EI8)QE*gy=qlL3hO%i<|Nm3^A{f-g+J05Uh7XLQ+LWVZHv_O^MkSR z%3}PKuhV{HnUgZ6?>}^6fAxu7{UMNPtZPVYY!wEOMRtDbhQ*!?#PbAkC1NuJXHJ!~ zJKl6W{^@kuB>BbB@fkWZ!NJd##_!6oLKY>I1AJbr(+hfAf4*n zK?32KQqpqBP`WRNK>uNPFQl5+a=v?_CM?>`Q z{@~r046Gm3GuyHyoxmB{o0!~U=?}u>!g7d&^7VLBz;wd()q^m6gr) zjTwdgj_cPu0`-pJeu8jHveTW_mI;H5<9f%c4U~sDeDH6K$bZZz; zH;a%uv@1~m(VXv_JKlG{$OR*#yI@_2Zi(!O^`oP!_Q2_;>(Q8$Zn#`{4x?jH|1n*T z@Vi{zLtCPG7ZtWb&8Wy6TRO&cg!FkAKe%`GE^ZaHc8<@_!_8vk^m$#7eVNhH<#y2^ z3+6KAqk5{_=5r>9zj-s_`T5HtR=vk<)QTdSlgJ39Hz_xL&z@z3z;Jjvf;dL6GhTbj zwmn_OItJ8D{ix0LB01f-UJ&6C(;@S&8~5(rxW_a?pg!HIA(iP|wik|=TZn#v#R2fK z!Lkw?VRwtsZGdi}Ij8G5XgoRD_Cb|0@VQ{yNbBo6-u+=)UmuHEDPbiIGaJTDEufEP z3|5`8o}RKEH(G~;dSw=@RW>7_ZYUjP9aOv5&|7nl+R^$}G~?2go3*vIpJjd)6Z4t> zaO1ImJ@tDqeYhnckwgY!S$gOk`gTia2f}zu3%!XtI&iHI4gfo*uWR%p0VWBu_2}WGGS){Ur7JJqa5|!TSWJP}kt0nvOKzTtQqv+5 z83U**fDuN!E(TnTi5fRCrPjZWx1nVtueS`<+z!Nt)Y6Gq-a^+W zFulH8ZCb_5W9$vTZnr} zO;yVzoalr((p-slxCA>&Bww4^LTqCLrL7G$xMkWqvBoq6Fa>E3r8^T%mxe<#y@shq zmAl28POF(}6c429dk)*2c!QV2yxJ5-58GTxrTM6X_ z4=Z=c_bQ4PqB-eZlF;o^uhf0V?R1B zv}9jJ_54s{$nAny zY$9@CPnsTDn!Gw?qU;|ceFMx|WQ=7oN=8Rizdy!%dt*!=AD|#cg{Bhjf^9~W&Z#Xk z-E7XFI2*DRj_OI;aNKCv7OLx!#N)P`td)3+SuodHSuZv=mzd6?E*aAcOXj6pmU8jA z1>ZJM*9G%XVs$9}KFFKkMy+ljo)a{83P&eN%BEXG9;;_m7ik3SuH-&IxAnp{-4;mY;VZC#~tNtG1HdeW_v+o&2P=a08Q zeSIA8<~yO)<|57Gt!6nLGrz?2q-;7qB^+KIT^lfte^4zk^{er2V1X%0@OW|4s~BHy z65hP+`=b#@Ub&KVAt9lt3g|;kAK5rEI7p)U;Xk}vNgLAN{Nfj%?B58duaxoSk01XO zHGSdvl~`V;Jo9GoBkOm5{>dkIzwGCea&~ZawI|z=EXL$)CKTWt)ug_@i%Hwu$WDU= z3)1b^2UoSGT)f}ND$5*7)etKkn+iT#DQ&OMiXIjS)Q)DIH&@*>GBV7g^Md701eWu$b(bh69e zHJC1W8%{rX6l0MSu5L5KRMRFxB{`|`MBtXh&HRrt0Y-5J;&(dzjrf+HIC0QwZv=#M zyf3M1@dq&Yi&PbCk;TTk-7>w{94{|%4^|=SMN>4mTsxsup|Hit*`2npj*AquM1Bi; zdMxpnRh7;mG%~{R65_aY{mPLY(HX7DzKf)yQ&YVkGsWMFpOFU$6Xc&K`+Zz5$rySH66=~*O>@Z=?Fo(vAKxNA3oT!Ud}W{U`?NQW!BLj?f@fsV8jnkifb^_PVFg|okO}B*fZ%XO9Wc#yy3?I2Mz95aa zwS7p&xi}pwK(F^ie>eYHa=*_U@uC-L#AumYqCc(r3XGawB2rf-qxm8II7Np0-cny2S#P}B+JNA=d)btzl0v+Avk{GcJqe@~Y_>J1#LGdR!EuF*Ea?)J1 zCvmhVk#0jnc~f0nP|B}gx4h}c>Z66}KWXWB8>SzH#J!Pr@uv6SYoR#7T)J^1lcblX zRhV9AAv)C1k(b!>cuz;_+iW?}I{=tx&x=(;dZVQbvy^v)QPUroZ_JYLU%-B!)Zz5b z_L-xJ=w9a~G=AB9GWjIDe>dgcJ*2PV;Oy!DB+pI>Ir(Sk78cDCd0R}gHu^5Y6gO90{gmGZ?C636JZ@M3?M#` zc`aiAitoHlAJSngDBKrWotctbChVM-daMo?IyIzufhW5IsV7Z6cBxou`alDXW&7H$ zWzZmN_%^sLI_D?#l!{43>3S-eq|7w*W!7|WuSYi@NX44Y{GgK=S&P~#rCm$wBfGz^ z4M83}AFfGV6I#YN%%oMc{uKl1|BIb(LAxoXrf9c^THF}yyNkja_D zhZ^CSY-^s z;T1b-r_#8{HgH$S?L9us?vX|?y(GM1uXg>A^)x17M}0?=KL3Lge+A&iUWNjw(%J(scO^$T62ma1~d6Mwd|op&2YC?Hh9k~G2*$p8^P#mManj?zX;Wl)Y;mDjorua z`wNEG%?hl>YhqyZ;V?Gz6wSM#+q9_n#cjHL>8eEVDj569ouJ^4-KO0q;gQ^+<>5qs z>_}d|G{}BIkiCN~bhUF7q3dXkoZM=AqO|QONM14v18tSFUyw6C zZ5$w2*~tWVqD0QYfwXb-bZO~u-1g`!M0EVrUw!c0ybpTg@O@mk@LL)jeYL@HaB%Cc zL)Fyqo!`3SqmQoD-0SQ6#odqhlb;eFKT?^$D>?b}=|L;$1tMQ~;kEMubCLN5MKKcd zVmvTncNX|Ls;C!oUJjg3+HNXHKl>GoqvDl5N$oPvx^d{;70u< zP{l~cBM%yI;`gBd*3*gp^o|a$A?_-0gvg7Fvv;hf`P{zfh@P_AEAa@^p7A;IE`a*% zQy@VE5TsrcJGBRa>@+r_oR%_FXFNd8mDyFXAqffDaXYTpHW5HE*=^?a`ac{lei?z5 zc*ujUo7`W$^2%P}3IsITbo~|n2^3+-pgm8{$jG1~TZ)VS{SWWbh4kNk@tfa#PIsQ= zk>(Bk>Z_~&{4WdNT)A@ntl%YYE_r0}=U?9aUL28d!%ky%wm3raiB-|w4Ydv8JHX4# zajwqULIa;eoNOU!9vrqZfSlrU24hEJm(M~>KXhWFO-v`@2hUM1eL0;y6UZQph2;rl zq+%2mSaps{Ou(A~p_9Fc?;4`yZ7jxX1n^QzN$iV>#u;;=7yx%pXJ#oqny+uH?;t^!p2YF%>9S`a-HAvV<95m|u0FBROeeQ! zhl%0hES1+WGNyg3}Sx?b!_yYfpQs zxaRVTNaeOrLJFXZ)a@Jr^$Kc0vs;W>*~hp7-8* z{W6Z1tFOQQ-$dyat1IY5ssFEBy}4%|A%gF47e07<_&99E!y9cg+u;&9P z9b0Jf7ksopf7=0=FDXPTyxnl8`F&9}x}>6R~jEIi#rsGoUnDqxN& z=NFJVGl_X!(^1non7YwPN@Il5WqRTN5}1y=#f-^d`sB@Gb$@8v?=ALVkEuJ%pC7FK6K5R0^-xtNQZ&X zIbeIyA<)ZfZ7*h!HNDZLSN2{%gN`2aS<`0)1))>}o*I4|HT~4}>+dI)bv2z`MinRy z6#$(EPogb$pf*dV_96m|nj4zb=0UP@$%CXX-yY+VQ5Z zo0|xxljqXmEsY%0OH)(FsCUy@Fg>$Hm_Fh0#LOFC54TWqjGEpN5FkqpqeHc-9P+-! z=oYAdlhNUI+8YIoCVF>F^=^u(ZA(E;$M90$N)japEed+FYQw0<+naLn2s;x}qDS4z zaJ@o6ZZsqx?ef3qALG^JeWccVZEwt)jOOI#liQn5)PNH7 z34Eb+v|>|SYk5l8UW>i{i}>@Oy!%srG^>KeGjAWieQJmZMo|6sDP_G7!zk;ESUnK8 zOCzx=ne;3I;mKJC-5Z8e`%unX@U{;P1;Xg~#ECkGq>0fFZ0O8@%@vN{kXM76&UJnD zCwJ{Snbk1dK)+Hf=YY1%x+KkxsZgDdhQ<%o=(X5#iXP3>TOiuS`~BS`9w-05W^}tTHr87IDhe74E{#a%l*|KE+L%}6KD7B?M(@; zDj_QIyT^B{>B+$KbXilTgcn86oMB1ivWQF%h>9s`EGLiOH8{BR@y92ZgcEhmK|99r zD}>vr7fW1Wd1*>as5d?m%OvyIMhgjuO;@qR!mHNX}p><)dDOOYEAX$bJzZi=YklN_aMwmoY-Oyf1EU{8mo)CexAr zqtxMq67pjDk4j4yrCar*wgh%IA~rU|wqzvov7i?N>b6@sGyZfzy2a;~OpSIA-kI zc;ZVO3Vo3J$xHntY%d+5qgt}-EMF(zpmcTH)WFFLq=V^_&PC-?1$AIps7^dwZgs9x zg|m-b&`TYiJ*z4m{G70g^h=&a26S*w_e4x~_QVy^zyEU%5~Ay^no}3_`^Sb zaPH054!rv6n+IMyf8fBY3twG$TE-U09VkDi6AhE6uAoL?da;$qi0ef|iaNe@P@UyN z#VFfJusMx&)JBx)hG(vagP((QB|a0ZJ7jme)4d%fGQOg}3J(mgbO#Y#SAN^n(-YOY zNxK%%d&TLvHcSkTeXcW>7x13qM557cRgqN*p3d==^u$Q2h}(NTCZLDDggw)}+IAeK zr_Re;4trv*@u1ax(uOPNuAnPM%%O4n=#lID{!n#+4LdnuOwS+8A-=Ep-FJ6E=D#tR zzVXD$H{ZN<_r~lGzWQep8AIUOu7%mp1k?SBP?2z=1nF)>Lwdw#I34uV zo)wG8^K3=7{02|V{mssP?4EQ6f9>9NGXkm{JuG>2+r-e<*8Ch#svQ3sEKVqh6v z8%i&xq!Y9HL3DK+E9=$^1UF)QNl>aLz)wESPTyE49Y+$>%U%yYIjQLq>?!L_#|x&N z1NSjqbgmx_bI#+fP_?QuUTl<(UFj%~X_M16cTnmKyOY>7gLj0tEw{S3nDzvV92Ck3 zrrS})3yR0mTNS#F^jjZ1E5s9DdOzwN5%&(R@t$j<{VBpQo2<12rMuhEO)xCnsiK2w*@)kR<{kq?}pYbeiy`lfBves2w{BV zXFq%6pP}^okSF+#X20;l?9I<(cj=;q(I|TZMrX?|gT3WB<*NT2Dwmy}5%J!th}qa==Ix1ie$KM@ zF8}t-nfDE)!{?~tMop&&sR?@7GpFq4O<>nbO~)7`Q~G@w-2!&&B8C@^5mbzlLIb9M zed8BaGo~(+oerm?rjx}8vAdz0&wY}AB2vfkr98C7F8SVweR|ML3&Kn*(R^1sDYAew@>}@m$%=}yng+rS5(wZ*-{dz zB2DaB_J2fl&~ykiA4aQ%ismPdqN#p8bYt#>x$9geZ3~DQCP4A+p-(cRuTwUP+rp^n zi2+Txl7;DR^E=S_WlooAr3G6GKt5IOcA@~=iKBhIM>chQHf5t7t5!{26~eF=0ybrFgXZqY6<8F^$Kew?nP~m)P7VEmW-^m zGiR=ijxKL4iCRm?qRY`K zkH++pln@t99Vy)|wzig(7P7Z0sjx96r9Al`mRUXae_X8RSJ#MTWoWqXxVjImTSwz4 zG;pjgYHma)QVcH~pmTmY=eC2usOgGz&ZV$wh4yMbj z!fKR{c3;W>+y{=G+_fDuJD+EJB2F3pIm6}0j>(gb8~yfxJTKIfrk+AjCk&FA07a`q zxXqF7@t|i8DRG7g-0(o^vD9J3u3yU{Zr#AVY%ptZnAfD5&RGrQz|_~{f$<*-4W%cl zB=(k2QXQj!`l!&%R4=cVsR8=lB>H24$!vF-n;4q8=08(Hdf%HqA*TGnsIR>*mXB++ zKF_7D*`RT2Tv0{1f%fq7zt{rlJJoarz4)^$Gq@t!-m@zJ(pd^}90M~G07tMnN zmq6U5OTx2@$Vg63F3L`*aJ92`6>xiSqz7q3jccQ(x|yf@=){t2S#!A4gnv|nBN{YN zv?&^=Z;#Q{jRXzW3T_ddB@-(EMvN||7oY;-;9LHs(7xI|#yo`zIMo~9+(AG7~%i`qzf|eDFKK6)u)oAJ8;B<3OR$x^F_-+#e z(9*p?bVkA0ulMpx-Cus#{h=x8>yKYx7n@wz+B`xAqi2riE)&3LKwU8yV7j4nL+Xam zL8UQd7mTq3-8GzciR%|BGo1iJA{k}sUa;H`qqcK8QYD;TSy`ptqWgChy}I>t(dEAp ztN6hSKYZcm^!)zqxw~Ke5ZBA;bDtl$g|E4KOMLPdU;OJDuX}x;kO#hT3*tOxY2TeW z*{8P--uh=a{inCk(33#(^9L4gJ#b*_xvfOJNKjWrsYU7N=<>XP=`X!{;C!rVQW^i- z7boBORK}Wjbwp7A6il}diKUwmL%sqBNH8}D{oE0zBU}T8oV*bz9RMQO4!1oq+fK== zSMU47zR${fBKB@oCJNFy8Gk62vB=4}*wdX+Xo)=+xKk`j;Gcd7yGbC#E4i?|Bx<@_ z4_2%IudIyK1h^kQRJ@C}NyR`qzmcx5GU8sj>=oe#-E`fIzVhlONYc4dfsE{@0Mid2 z-u?N<|MrVt{O02?Z=G2FCS|x-0ABd&jemJ_snqm0nSn3<{FA$%G~e1NW#82|);WFz z&kJ2Xn#p;gvAi#ku9TORvzE_VzF;}|E`CeG`J0rCQkxwg8B&pri0@ANc3hRu(plJ= zA{}{e1L^uY;E}=!!#9L>Pw_cBsmR2Oen^&=FA>rec6frG zLc(;49bBoG%npeK&nrlt1k-uDaKfk>(iQf^%E3E`$wNCMc-wQqYDKgF-3LAJy};>U zI3P~(=nC@EF}^&b8dAh`dB!ccCh1P&)4hkY1f$?6Bx5 z!chHYk;*t_X{4)jNO&X=F0V=?`7eH+MHrG6EFS3}$%!XasG^GE0Tr71LF@c3;rEI6 z+(g``U3~IB{;Frk(QOpBi+QIkR97-%h-*bcJnx%RxNCD36K@9izUOeJY=-)-b{%*N>HB_*|u^=Z_A#`NBdit^gi zbkS|DOJ^u@Bw9LfUSg@~GQH3`CNOkuV{bv!k+o4Nm&<>9^Gxl{U)?-QQ=zDs>rmED ze*b$aMiWPynqp!~0-Das6F!ue2wqcM@W1e*V?iHkK~=|`-b2zNJgCNkG*vR5^BcDV zYrUFIouwDi+q5rYJ7+uE={wq!=$1IYM;@2}1-QJO*a@W5ijWSaV0uS;;#{|$M-y+b zxe4@QUdDRf9sXRzTb&5o6WEwXKqP?v`~Lx{|B?gGlOes`*wO{*YIu~F=QZ;)@6oB` z569G|TqkpqJRD>BA&wHO4;7?gQBhgZRO3dcP&-;%8y$T)x}>(YAS&P@;W%DL3iy9n z8`Bh%663YDAgez4Wb*belTS9EEbl#%axeOHVH|%K>*LH`zoewXl9bl19@+a!(9$<; z8vFnH4?KTrQC;@{ES}j%#5nxT?gW@!ln$qN!sS$vwy%41-Gs*{Omdk!S0)#?#D)Q4 z$!o}8Ne#S~g%I9wDwF=90|WS3h6AsiJc*AbvojTqoA8&uQ>oo2kHgY^8QUwj*R4(q zh0^J68n9-~011uklRrLy(FX5}#;@o|DsMVrGq~kX4KSS^SFG- zdR$KUz^MF0RG07*naR9V%M(pi$9MF_83*dHJzUB+}}>~PUCy_hmtZGZ9vY3XW9 zq#;Ou0P5z&nVA7^j=B9?C)Co~C|;I*_D7JPi{phxxcn8r--Yx9AtxH>oA460gRRYY zT~|62R?@!$<~jfoJbP$pSH3!@*ewm7vOe4a$4IW9uO|dX8`2zA zQ<9E?2I?S#cNLtzyZ`V@8#eX-=IdYlf?dQPeDFgx41ezDKZe*DKfZhQkLR|=4#s;P z+Ev&6(XTGvyW4$f5KPDHJ(4p>!=3)qTk*6D@Xwt;7nk(vfm;jDpQbzK`3-lrEm%uCzzT^|y6Wsc?U`xk53q0H z%3jm%sAt=%S6+Q}(bUF#4_p_nj^Utsqysxk*u?-ZJ0Z}UJuS@Da`S0cONlF`r5aq# zI}qZVQ<<}T)`CL@(`iJ0X&2Gy+p)jw-`!75gOk0xyK_-eW%7uRkDZ+doQ}&=`HXNY z^0G-8RL`FHqzZR-%cuYs`Ci&L9)5a@By3XPiy~j(W{NqnycAnz6qw!Mvtec}y?D@M zz6iom&3S_KcGYZ?p>H#13Ngy}rGOZR%NMd^#y%Cg)LK$DQbrup^o&>kpX2W&pYxlsC3yxHNiG_PGB38t@fj0}&A zj9eK`vr*5YY$v?vej&b8XQOyiDQB&IIZU_xHSFF45b z(nU!tsBXDl@KGqug;!*G)A>&UdBfhYx(Y`(yOp_F^AcT>#;!Bnt`br+xXSh~wy%$- zjg9pt@1-}bw72cU4?p~$v^m1KT9UOR%bz?uaxpGWqEE);xt*Pp){qch5=KuR)4fzh zr0{BERzX&2Yu3fCwJBX*CBJRG?xpI{rT}_>X3_;RbC?p+8|1C96&&6%pLKw~IL6P8 zb}UNb?HzD59+(?L$mAO6Wp3+K+c}gO8r4J!Bawh_51s9B8|NJ`eXdA) zQsTCrMEYBKTQQ3Wy%R@!$`U*CzE+89qT$L;qDdz7JjsfyRuQ#txIb^AFuj9IsOc7( z8yOvD2ikAE{d*2(@EGg#Ipo#Eq@-NG-gy0b%CG3$6txzMP;`A`TDKa|H-haYQ4MRO z%NrH1*yWXSpO;wxpD;n2ZyLVH0Ny^@Ab_4#+S?Dis@F~aow#>XC!clOjP=HIg{reG(s7d+IT|eKLy!vyrsx31=DZyLOBe^nr%VHqz9uLD1OL zTkw!$Y8g%?3ZE#KlZUFe@3_>M8Jb6a2eB=o!&ws3<%XBt<=VgY{pwWe?Vq#^pSmqb zM@^SSKJzvTJDfg{+AvTvgzE+1AK+nims1$x)e9-LCM}CjM%1d(Y>9Xny!2UFYcdIL zObZO7O({z?EinB+Olat^szryrCr#>1^vC*wNd^gC!RuLTQ`flvM)3XI^gj*U z@pp`Gsp;XZF=6{6=?Jb)CQHlR9)G+xd`d+D zLipr>l6^!ge#2U`w4ybvHakUXdT{f&88Oj~Gxcc9CT6&Jd-WEMnH9|oS!(AI7wzTp z#N&@mEnNCY>!Xi9Mwp|z8q&(9syC)I=^LB2z4pJ!nVjU3(GA?fyaHJWT^&0aVqqIJ zOD?u7+Q!_WcA;)_fmGdJ2wNWHsEe<<^&Yi>HTMDo-5aBVqub_lcZaH1v!(Gl>4cnr>_^@V)IOQTlXm!bFXbPJ3kkfU(c##FyR2Km1Vk^z91X z3$Yt%ZZ1q-Y42GXpT3I_5R4yENhOp@7d4~~=yBxILkB0;(Z7DjC8&d#)9EJZ7i905 z&WhN&gNP@jyAcf-bIJF^@Ugpk%h8vPzIy9pDE$||0Jf3PUqDfR!L~?v`d4>OpFXg4 z`^hi9xb~BaU$v61eru2*$IAGTLEoJt$y*1{-#Yil|Ng-r=|XxsY14s)w+@`%df@!v zhPdtOgA3R?yH62n1%MWc?urs$fcV|WAp+ihowjZi= za7cF^+!;$C3T=OKD=UkG91qn5#+kfaNiRd&F)c_q?dcI>yCaS-p>r8Kp9$mu;TmHp-r^FTU7uiNyBp zyU3NndR&3&g$zeOgnN>3-aLO`!*5G(2F$0&%4PN)ByEakCk5?zWYO3u|I6+#KmPUC zzyA8;FBk7Tzhvv(i$D6&b2m@(J4)+H+$tlcesmFGGB-64Xexd?z@s)ROLe>Ob-XgmE^aF2RZPiARHdD zwJ;rK*A@Jv=kmp&$rJUGrpDAazB*s&hKT9gjhN2zuKlzR>fgPKl~DK{s~;=URZ(bMkX@vAie9oqpoP#$ClUQG&c> zt1-jc7@H$#@vzxESF_~{M~Un?NcpMORvqihoWA@r*`7{JQ#IJWZ|)Y_*RGfarav|1 zsmMiqM0gXixO}dxzoTdsX1wN_B03Dm1=hvUuO0R$)G;A zi{7|fbYdN?b78s&8}S*Lk`Q2x9vAcjrB@nb{26C&8( ze*;Upav1-cIW-GX)2%p0>OGOt%W#1}w5BuXI7OXP`$^&Gp7$VpDE+-X7mrBGKJwm? zAOHBRGe17V@yBP5pqZP5n)%DhBFdhhKYP{X*RTG34}mYlFcK&!?~MA3$^*lbJ#+bW z;$5g8#h6Yqq|QKpaGd_6q(#!)=!_~zo1#XyZQi!Zvb%it7KCmces=TbXNK)nLaJ=_ z&7C(sFa@N>n+~I^id2+7P6012lOzt6@v`_c&L3`}w|HD9&ptV0n~F;n)d;4W8w{aq z@yYw;rcc}cY#%?~m)6#pK}buf@)b*ZuO0vJe|~aYwwIEu^13t}0z+K_v`OnGySc4f z=U)@Hmgb^sQ&RB02+>UyX;yDt!P=<2&Zw@a-jve4H;Hg;3c%fRD&|*>^%(=HLgB}&YPR)=0=F)D(|W7#&X`#K6N6cp5AEW4MRxgl7ZKC-e{jYm#WpC zIit%Wrsko#qo=pKjjAmvYC2N7MdY?qF#YYfZ~y-5-xKu?v)|?+c?O-SUe{B+LR)0^ zJR21{P}-;(Qd+N?vuLI%QDIb)Mn~fZ>hii->vgj34L4&N8$Ho+w>3rueeZXRD-u_Qcs>VwCc zJbf+Aj~*UVs6+K)V^JQDG=uBxQOIUrQFMjt+R2YiPSLdD?=n!)727hyhQQL&1++$U zwgA}DoDHz*guj2ZE}A~w1rc8SYN4_)T}MH`akxAzrRxfIxzPv-uMG90Fgopw45O<9 zsg2SN_p=3UP$!1U4I}FsBaWMMbIJC=*0S{stvl#cnEr&Zy%;oC0VzkR>H>8G>E=xL z({t7^5Ux{e$y{XFyeji34_|NHs{aHU=<&LOjF%`X_}8*S592+rYV7k`v7emllOJXr zKUuwe0sV!-M=-lKhxo>O=H^t24?r;J!q69eC&3JoR!sVfQ6CL^82+FX5br{T&yry6 zv&Wkd%z(n|+!$*b{;Ur0>{%yGUjUSN4P zw2npn?w!K!FEYNk7V333dH*4jO$Z=FPOlt{PtJzY51jksKjBS3aC$>*EJ%OrG~q8J zTk*9UH67c_eb)<)7v-wI^y*7^W6p2E_42<_LHf>i%+Z7A?Q?dXj~%hE7N+m23<@gt z7(7of2}ym*lH3wRxv0CNb0rpLI_`*iJVfbsR5bF6P>SQ-i(3B>_rIU%+2&oCgzH6W zx)Lj0V-+m#Od5FA)}pw5<$I%})h;8tXuI--+Rc$n=e~5O|-;-@SYBN{3B+l1qG?vkRLE-OeuBS6*0j(8uSQV6f29-qnvl zpINhl2=d8QH6qoc>UBjX_U64@k~ecrB)fN zh0(syI@K7=zzABeq(Sb96I-ZBea7eDL2C=Pt(Y^W0z8n}_z#Zqh}?x|lTcNRS^Z@^ zH)#2abFXqHos?nJbcb9heTyI+N}n<-au!@3ynZE8xZ}#$r<7rnE>`?gb-1nCCNb&i;Rb&Sx>)mPv8ImzZ?Rw!Niv#BF3 zdmdEB|MmGPpG7e%O( z81vR1(p~oG$?l1mfAjL0rd97_W_b%*7p2RZE;T)3&ZsifN4Fgjr3=7&%9`%u`I#|N zzxmeBG*htZN6+lp{N#->$BTm9C8p1V(`Qdt6r;?y&6SjlZ_FI zw7#ZhO#vc}7dj2ieaK`Kre~#b^~AOQc@sm|P&^rpLxr+Vf869=Q3LfSkM(8#5;Yw= z-ntn*k5B0Fx_P$YHtM=thZnPx&px~PnO7#wK|6ZpQ?nN}OlurFjVr&9Kc z zdPyzUlCmIUdNQnT)b!fk?DF~@s|$NEr`zKqtjewkNk)+`iKC*l3WEEGkEe>)nA*$+ zlF8diKBNkhw@TlFAyODqPu3w)r#2+6!%UPolr<0v#{0LpwEJgfk>#J7hyD!=>@0%ujJoZsaroEx=Y{4?n&38m(mJ=i)V5;-=PW4@*)zT@6=p?=vO3$P`C3_|_1Gi+U>5ajKQ(F=B!@2NaObCnp#^$-OGAbZyq6b&J9|H9*aY5zsBV z)=Fcym}h7BUNSms>+A^~nQn;81?ZC1ZSxNmmnzLhugJWp`wXsy`xmr$|CNvVVp!q+ zU`ZwwqD?zL|Ml0#^MZKk2O}fTZPq2l zlt;vLN=V5Fq)Zf~qsxy&@#=l6uY^(Y6rJqs>f}VDOlOl>iF-p8sY%&!duy8lMwLT` z4-+RQamGD8B-3H)8W$DTShr*KrPYVuJ#_fp;w`+3u{p6+1<>?{7E?ivk#=_B)80IP z{yd>CH&>NCjRtsn!=@3O8TmQ!v9SkYZ`~SPu;pDcYT)!=sI$?>ckbM~h)edBNcOE! zAHK5xV_9Byk7Os27U@*MR4K_bzG5p(80#AA7m2ZABbJwqyYp9~@h&GVGk@h`UwaSN zB}BPWG}9ax7ne}9uW%D}=7g{>4aeAQzkC+b`*J_#a=8w^fVvajeefA6-NYJ7H)cro z##oY`OJq6)nYhzW(l&9s8XM&=&)>MazuK2ZrAl5wH}(u7lF)HhB!QO|Rdieh(~;1j zcDrdl(?X_An`Rg5Tt(3U!wPIivo|wGm4gzbu65mgOp5w5mbxuiKlt*?2MtNva9TF= zqgJz{Vo&z%ROjn?@+H^Mw&~QAPvcy08(ExQq-sXGMgH^$!+2kg{@@3Ee;&U6#e+wy zFf?&T9#_?+D^@(UV#OBnfS9(T*NfH3sY%}wMAIqTSfpO0OP4NL?`XHw8I$>rYON%2l{_Hj2gkn-x>P8(^YwEK!zOa7v&XtjlKCrqgp)uI3 z7*M+?-Oiry%8;t;s<>pI3O;q}Dk>9v<#2a$=XReloyDT+Z&13Jox=;Dw+coD>SA)s zqAqBcs;;6^tFV+S4A>h*okgv$=A}sP97XHz|7;A>C8is{3m%pSMWlqXJWrgWF>wph z$8}vKWHEw*P(Yh0#Hu%7Z5ofN3KWwI^7;OFprqf8YwDhvV8R7I#-udu2_H;Ns zx_)g<&Ctc6hI`1tS$GAI(!>0{XL?0l1k~?^8BPb(iGNuW8rs!fFf$;m^tu;XddKLQ zfu^Q{vtD1&%BGJdq(hyL^{iVr88yA>v#1)(Z0nF7V$T&iLlBvB=*c7$KO1+Jh^BlZ$l;DHkv3k{p}lx<0p=eQih6} z{`T8|`qyuh$Iktws!!@fdB+cu$o=E;Uy*@MjGizGb zb*82@W~An2rXio70;f+65X65nV;~bLdm!*9sbIRC>#0)Nf%ZN&lGT<$C1)r_2;MG} zAGPLY?U>y0v7?N`Mkcu)S^c&r3UpOO@1v$jl(DM=}*^)~gMk3TlOh{p)ud%x85KW^k( zYWh-9_TOH zG_MQz7H=EoHXyFQ^tx&6^uaCnIbCa8O1#@de<&R_h1?<&GkIT4pYl}o$!pz*_jez! z+rNB;1G#X%*@gR>vmN~q>e7kEvvK+us0(8tFrA2O2wD`Jaa1)W*E>7=DY+ut1M6&1 zP*6Tz^8V~f-w22ebIKL>F(C8bek_OK2+=k_E+{}n3j5e2et>(Pap6&aOc2*TUSme zCBO*!O1JMi zq{+odQv67Q=dMaLN560i7!k+;bA0Al)0GeCAvyV*>K&s;j% zySu9=-KK=9q=XHtU%5^zJApaj%VwA}qUpBvjK*A#{$lkdx+*apfEw8(nJAd!b9RO- zCa@g#b#Pqd<1_7<3)2p~dT#H{RnPxu_NpUPnq-fR`0fHj88 z{nz(I7QG`oS1w(-e&yho)Q{5oXk;XoY!pfZh-%NyW>0PQRxJ1-LGhI%K>Egw`P7?| z^-|qmxse#g5V{A2PgxS_5r->1ZbJgu+aNj(F_*3nXWxjuFJXeS*5k~u4_2PF1ONaa z07*naR0<05<&)Rv52bVDyPzo@!H-VFPJ-#xCssh{_(%3P<9WGs=mgce%NOU<42qId z)j8z&`Z-rQ`8n*$#vY~iqDk2mc6N%?q48?0kKHs!ARQlvJ@X58=!^|@)!Hiqrjw0ajb5EF66iMZMTFeHZzYyvJjdE>7n~Fh|YLaW1Yf zK6mC9N_$zM`&*j;(qA+#^`pq_%6qg8m8*j2G?dl!fB~dG_0*y*G_TbgqF)=D*E$ua z=W?}fVoX{8RQOZtr;v`6o$XBEWpm+3_=^HvZxuP8@Ou(%}IFOM%O+)?4Py1u-~)s@6_ zSJZlnXH^mHX#H;pR&2V36|&sy55=>@t(Bw=eW}Y|j%<^fWcKG^pTno!is^9OsO)QqzaMK5I!NAq0$Gr#eNqPATeC zih|kWM@N@+ESuO)YD-zqHkYzFQqwypJfRnYPCkj%(A`I;M|3PBY7xiz*Kgnc`ZlMs zu*f%aqx}Z{4VSrO#c+WN$eu)8@mM&%t)}xtjhZe-hugpYy>Yz^H56RuB_*~{2YYtd zE48FI<8DU%T_cy@?X3xoNh2r+*GoqEUflV$wMR-y)~*c<>uckxy87ORP(onn`&1j{ zl~vdLWnCSAx}fy!tEHybqNcaj??}erZkhITSnPTdBw zQNOPdVtx%g7e{AuVsKjw)AV5XXvUo4DRZ@a7al(+|`0!^_|FrUxtAB_KJtXkY8T zgejJqzGR9xpU6k%1K%9MRVm{hn`BHc(M#i8qAI3feR;6)C#FV^xfSoavZmA6i0V-{ z^)oe(YSeS2?gtn2I0{&_uCX4?T87Ydtw3EOI?HC_AhBGt4#Vi2N=R2FsTK{vn;Xsc zcwv?|UGIV6ZgZwZUa~lyZR=EU&N`;SkuC7WP`ZphlcxJqvhF2D=jF)A<3H2(2~Bwl zHNE=~YI^sfprA^CdRkRs>*_cMM|DiS=OUI23zeq|q2PL3D9b847B(07l5Gu`1 z9OCTk2y-l1g!)X+n4sl3{kyXJE1i88ge>;;q?ZmMeZJ0Mdd|iZaJn;9p(Zzd-V4HV zIn#goFCYByhaY_P$}3k<%74@q2BxP)9l5g=pGQ)>=V51OA`s)_lTWLJ6mL2fcFIN1 z$8K7vpqJANNkyUC5t6wA8DIO}LOESf(#IGb?+a@?rysI189%*rY0J*R*ag*t=LajR z5A6rj324NjzJ1p&&-kq)Tay%^UPXKz(q@H+gS#`mcOWE3AHrW8F{isbq}vBMc@|d{ z;c5x!Df8YJ8(ZNjUkr7SNn48wak?PJjO*bO>T!{f4uOo0PHbxOx)~GU_GFLOK8)4H z?-n0=nQ$0A7FKpd{8&Y=L@uU)5R$?R?s|bj(rM>kTlmV&J@bDwXIsRP(tX*ak=x^8 zPZ%6@bw7OR58FL=-unF4zxc)1_rAV&_g)lg`n@|}_K%Eg-1vFjC!aKLT)cSav}w#V z2!l_kq60mm>7au$8z@pv|g}hKI zLG-!7br_!t2!iC}<3oHf=E(V?d`5+{FfJf%Q&tLMTL;q2p=}H*Wkjl9G1gg32Zw)Jb@#xX*2=y;&d!~=k4_>A~6$1`UOi|LG z(m`r^HI!bFE}@>cBbN;Rbcf{@q%V4E(Nj|vEux%*Ceg`B&e=O!lSh0bBPr^Lr#M)1 zLWQF<1BrF2kd+*!=AE!)ax!693~`N&3=fIh5w~+Bex<8#q$4kbdthB>Ro0|AX{0))xjAkySU8=hP-K;ASo#QH2djACj=~RurF_!CM$?0?*{h7H5OA1YjaJiU( zaVWj4Ymb+bR}84D*b^!J=AP$dSpl}Y_Q=`-spDK%-=cY=v%4ZF+Ek)U#9Mpz+U1`U^;D5f%MHcjGQiSy0X)yr@N>~ltNN8a}ArA z{_L|)fa3Vo@xRS5(KeHxoMA-u%_4L`x(>Ew+Xr?06D%%5Nu#DyLQ2?T21Q24kEc-( zSzBM87MOMqI=>gVrUu!xrY3An9{LQN-W28KRkMa(@vU{yrGcT|q2y%*_^(YVEur4C z!yD1Or787P7J_p3HL2jl;f8tRb=!``EDhkuvL2DjS z26H2fe~lAftxaWv5v7xx-br9gqO^5D+yZiOIYW2gN6NZx`1+K=bet3^0f`;npBZZR3IA@!-o0TLQPWdiL0o4AGwSP03;exm!%}WW6)>l% zqwu|3f_neKwI<%O-~ar`Y!+CheyGl$Ur5>>_W9Cc9PV!sMSmZpfLb_#@uy}Q8Emu4<9?(eGCSt@#*c< zp;On6pHzf8_rFanBxZM0J$n08Ca?~>A2S;S*pK0PVI4iw21->^$z+#7Ju@qH$e(9d zlh#PH)U|18L%8W18Zg4-;j~G_%@f+fF)_3)wLLMEr1h*cULH}6d3gi%8Cdka-2ZA! zf6#^W0RoRLO(@4{vZNRD30*z+x`ON)!NGQg#w7k2O+p{}t`gL5sp(UKlS@iXMXELv zZh6xmaa_yxA9M5CTNO^d=ffksDmtaAL~8ny=5ddEr_|b9^iMoGDIle_;u|XmFL5ml zn~3WFgnv=+Bdd)!-E3>hBf+laCFOrYu7CKU{tL@^)4}s608s@i@{3IYsUcZI!O$;| z%1t6!!R%z>OrUh>%(_M7{HOt0PPh?X1B96$CdhI6)bSAe_^J3o#_C5WPMmJU zblfkd9@X-?+mPD=ZyrPZt?T4AH-R#?E4a=)t_fbWU1#hrJR$MA!En7Ai_s0G8%K{Z z!HCqghS`c^cPixL{>EKh--Fo^{n#E*;R@47gzva4533B8j=OM3=beLdkV>5 z9Yg6DDjXJJtql+NsC0I!&RI~oYga#B7cf1@H=ZSX-;kVmkJucfTR1(Q_A$gPetu8E z=|DO<`d6<5?En2L`Q}739?3lZ(edLbMsZt{Mz(GxeH!mcRe${A!9nafOO^D3nvNgj zf-L7WIC|~PXJ}}2;I%goEIgo=qYQ9eeT~eJu+EwuFRwWC>GA*h(MSKjdbQ)u*p<1| zj1E@jQr;*%U7&twe}9hs2%f_bcc)_KMSc#PLpqe(Ik_XHOHC&huL3tdUY=qn_rp8l z4#zb;yKS_bou9E4KAR{RO**}g0H^7rEhsktW)wxeD&2w95a-zQ zv4;;+etKdt%}75+O27N--g{l0n}@Ox(LcHK<(IS{{bcv8m66y+)Ik+uUPNa#UeIvI)dqeaqnw08=z3-<|Lk`PyTg=bup4W~~bnMBzni)dfv zG;4jNXBBu3rek{{$;WVdy3L!eh<2_`uf|V>&E?RE-N^`2AF}W%KPU2Ypmgzdj`Plt zoxnDpX+MzP6|*~dP7x`Jv1_cWTJ;cK;xkQdYmbCVquZ;&ll<^T`xd7AlC0?L0Gj%| z==!4T!T+}?9hW+QZc)08tifzWnsW&|jJlHMnhqFIg}AxX_~1Z6h2W>;qCL{b?-$d6M3Vz)DYLYbKwbyX4WCcuT(tgB z(#t2u((0wAYhYl3(~tEX|4?P5y(zt|xX-g{?giGY30zB1HEV=*Q47OC6qe?+u*5^kQ?iDexD7EOE| z;gda2^g!ugI`$YSy@S~ynEs$J)NuN3namN`O*Fa@*N1N8wRC{(w?*T|?eaf31I+QI z-w>bMhH_t|$7jZX=@VPdk_Yb<&@rl0veY$> zB1Xc_YZ%BF2yAOh<6i0@N)qGkf#cwI8x^Ibrwa}BS%oDl?Fw!8V^Mrnqse)H#67sBP8QH#XAavNjVW4sK$&ygq^I0u(+Z+5-+iLuw z_fEGwV}e0Y4{XbHaT`u;32h^=Ca^7wsF%QFX*CTES&mcwT2B8i%nnUpE6rHQF^x1Y zd1#AM)SBq=#~+niUhy5NjNeq#`8E)TJ~oyp>18b z-)I4OoB;7a4!`db;^&n%o#_XpLvQF zokQ;ec>P#D7p-FH=tfM}GlS7hW{qTYEX!e-qI6F6SmyPKxrOQm!z~`?)ZApA zgn3x4#4vKYwa6)}LFv<(fatY&YwrM>3OhdU=cYfktM2&8?U%Zbckkb_;7~GO64$uG z!W{`z>&53((!1RF0np4vT-E{JK!u|tO+|&e04bJG2P96euJnkUwIqDjl8_3goXYf^ zY6R1G&k;C^0>MgY=@1ZnpML^Q-`J1Ri<*A=tBYf5`U@Xi{rL}n_|>_E7m^lkJ>7ln zqvIcSH*Xyo41vPWZ>m5C#;#FG&iCNpfk9J3diC6S+8ZU9p!Dy3?*g5S7M}YZeiti} z5iSSPePx@gro=3{D%Y%vrHQX)m-UMNZ#!Na}2Cj=g(v zm1j^;E=($L@}#iS$I%^ieG!FExRMLUWT;!<3C%2MtmB_(axx*_h$E3aHW z5|P+5xn~mlVkU;xHtuNMab@)%Ru>&E+E7(hv?1Zu4g2=(i*rSo4-%&rJCnlb?1=$B zJ~m{h;#YRY##hBBAk8x;kkerr4)ui_uIxRsXFkExW!^E-I}Ve(NAs5sr!c=CPGr_M=wbr2~pyP@>`PH zSL`h>AC+v*bw|zp>7gX|3y}VjZL9QFVtNrE$U{mhR->w`i8l z@&cyw*?JTeQL5XToE)Fr%0K*(5PPO)G!Mm_&aa#k6~76UNdzmpVq@`fuc%C-Z>WY3 z`x&MYhqJ_EpR;Q=9}n5;_S)Hi(LX-km1oUEBRK)WE*@uKzv=-TghZH4yxF%Fo z0r0ZFJKZcMp_&hP*??xX{xGSNc4J^owG2 zi_=LpKhxB-2lG0#uCZC5P8I3Aw{Xxz(1lb2|1z}nH{Lj-C%0!_+4EpJ{&#L6?Qhj8 z{4zXpMm# zNz%U+n+}Ahm0rG#@x{pLSk=QC8%cEOZA-%g!_^@Bnu34;g@Id~Ua*E+>jBb?wQIxH zkTx9}Q&NK9Jla8lsQ1|z><82Wrv0B_`drlXX9+NerRO4x4`XjgoXDPrv#XlUMxk|Q zHg)to=`xN$MuJ}E(#yky{Ym{+9=a+%J0yN1ic=J->QLpuOq#)eKUS1Pej`zGI$1G^ zQq#rR@HfbRx~2s6yfLdjy7yiK`SOj8diye>Gw`OPrpJ(*-b&wJWOF2S@I5-_V!*{CGedbh z!F06r?(Q#FQ$*U_+8aaCOI%@ZSYi3v+S1Z!ENAs4F(rkuNh7qNi3X$oMg;Vq+00Y9 zd7&uff$9pxn@s;sd?PKSGfGlNLnr>Qjkz4Kj^?eOn$&@|y1rCo^-MWWt{s;HrSIAo z#5QDP978*A!3#sPBT73{16x|!8#3zB+RAs-XGOKs>o(ENr9IT&Wt~h8kFNvMw`}Lm z*9J~y{sebAZWe+6z-=^gMDuF~`EL(r5};0DDPnqehQed|cz6_c6R)nb)V?&F@XD6S z8feH1&1~GYJ&SDi&>^>V7}GP`YT9{mZY0*=d%^vJ$KIdGMrP;$+3JB=giE&3g9-dE zY4iK5x%4|sFHe+4B6|A^$fpW^9~!|`=4v3rQ<F;chYCp;W4SKMx+bDQVIT){*H zN)HgFW93l}JW9H%No{ZPlv$TDj;Sxfv12E*JW34lPMnUr(> zqpNmwY&d(SJM$mDg33Lr+yHgwYNuS9m~*AGBan{k#o4&X$zmswQEr#`boSkg+w7^% z+nArfkxuN}cW>Ny>(GJbfHOLgu)l%aXEKRI{E{n3m0DFlH$`D2VUEB;pLY< zRVd>-*|8xN6}joIJI}`_#V-iTJ+x~(S~?LhG|S8lTHxz|len04a6o+*8Sv~Z03#)( z`_MoVp9fJdIa;M?$LiI8Xl$DBWLL^7`(D`_O=>_BdFYrhdlJ2RuSX3~B)a`@(cxXY z4l6hvrwUEm6E+dk!hQ;BZ5<@I=JHOnw}4VexNfK zZ?2k8+x4D++UV80(yM(g9LAac?#n9{EY?1TTel)_oxZnuUFW?tK{})NlP~-8eO+Cr zJ@eu;yJ;jmlBq4~jdhOQ6hBfG@4FlwedXenI|p~F<*dPUn$A{MhD6%iFPRelX7G|{ z5Y+eWC@f4)uwz~xjIrsdDZz_e9V)W3J(ezwbgzIU)xaJ~$B&{68r630^mXL}PnR*h zdjE+aV|k&m(V^{#>HFy?Yo=|iwKIMMO6MgLL1G``5QIc*7lNFQxf)xCL3Cx8$OfWz zJV?#vODQp(uag7cDfwUU>ias-gNe`=_k*OU6ZxWHPI-$w%q7I{caH+sFuQIcMEzY7 zUrZ}0BF`(R^_0BN9H2OX4FKOq4X5wlUwwjfMTp$uboks1V^Oyl9el_0LNFxQ>*ydY zov~;|ZaOu!>~Nqlt*5>(^b;UYhZ{I9TD0hyMT?w^Ru{!OB_-fY&+gC8&Soade3y=^ zr2Q!B(iuO#T;vLFA(@5UAI^M5wBLa7j3#j8;S}wyZ*I;`a(2bW?whj{uf8vnNqx%n zLvr=3bar0gknUQs!y~+^xxBSV?<4!e?DeGF9c=qUgN>T5wnoP4V$LjOU9@g9oWBqB zN>isWlm!?VL7hdZ=`4W0X0Vd*SZj#T4WwWFZ;0s}WO>oKj8(7+TK6|jd7)t*>0q)B{bkua9Q^*hazo-25RcH3tf?l@KK1pJF*PI#Ku%?@& z7YavQb<;7M$ zs!57P>3S1Lgn4>~Y%j*ZE?ytQbkLl#(P-@DZS*ZlYopImbZJPd0(=J6jOps656Vmf(s65y$%%*ZNeAl!~_NY|UD z;^Xca4Gn0C!5mCu$uy&;(;yWydE(Sj0?lFN7Mh4ol$_3JXn6bU%%(X{_dGc+aR@bi z?j)*jo}N2tU83HH&Pn48rzhr#osETs`@`F^u!E5dyy=vXmSH)kLsI9EL34@Z|3irW zKphvci_)>f!0b42Y?!X?T7&t7F|?0e9yXYMqoJ|1qi6bA|FdU58^BOKb!Nd@S{e23 z?TrbI=`F91hQ(tYaRN=V62a&OlfsGTB{B8np_6HSUv&2ozu0%| zi+3=|pw6EHz;CC@JcC9)Fp&BaLS4|%PomeHJa$T5PYG4O-G>0Li9_ZPmxhOV(9lp^ z@C4C>oh-_7qu`;%rIVBw{~G0Ww$QYx0nZE1fLKZ6Sx?P6)?MF5FM+se(;xmiG*5s0@tH>QURo6$J8o)J3=yd`39ksAQfeBC1`{QLFP^Af_Mxh^NH){Oy`^CVGbg&(^4uSr;4-r` z+fvzk!Ss~-g8Rb{`nO+J&I{a)M%*Lqc*5i!7q=cExFKKRsRilSKR{GB0$JRwPN9Ng zL&aLzKsp;zYONVqT{sw9x}51K@OauM%J72i#h61(4^kSC%JQPdMkd}-D!4W$+P0p8 z;cgW2v0-S|LFpS;e<;$w2UA$3FK zvaOpbiFq`O(Je&3FR4T6E>Jo?7sM3)PE$c7Mz4*j9s96WoIG}nav=`gmo_dBa!0sK zxYD|#$bCsgl{2n{9L0b`>4KLBa=O6?tgMc` z7T8x&MM?x9Vkd))LVJQDiDhgorJ{ETWc+`frjyaDhhO_1mY3Ho?R?=mAYJ{9 zjNwI6`tP{q)t4+xhtpp@`tG~h_!mW6D?%J|x42TanG_GZ237Amv>!PgxtFTJ>f-9+ zLo@}gK2*J>au=#OsAbf2M<07fC;D*WQlS$mg`Y*McU&nduO(@0GzyPr7oy(Nv_y9s zo#~Yly?S-s>V(6)ieU8g;>ul~yVT5-Hjo|(Rb=EjIR`EB!wAirSj>EgH_%Wz1(QDN z<*vd(s4vI?CvoJ`C0J@=x1N3_`mI$IW%Vp;O4*wn?~zb+_z&d7yzA~tB4y;Ql`C(Z zKB8UlpGZvq_)Es=-6Qb{2^TKB8hd`{dDHub7YoFlXU-E(W_k{s4yNafjP&jWQAP{(c&4D!zvl{MeD~kyz&u=a9%n%t`Fs zk<-!9D=Id5$YBkrTd2+(hRq7wKUOQe-XJ>LhpTl&P0v{nf}Bq0D5>HX$UR3>_c6jZ zg{1CB55m==>oLNX3kC!G(F;c8KdiD zZeft)0`p5s9~(Tx!GmPY_#Jd`r>~MQ{YCd;Pj^Z=RJNf4Vd@Xu7a4xXmwphQFRpN} zAe_Fa!Xex#xw(S!(HxR~v^w2Fd7%!j>c51MTuy!72PQ<+(8k+q7sE5ElbA-Ss9kUc zvE!VUi;*vmJO1hjcZ@lr|&r!9Psq?4+wbM}g>@JKfsPgdhnfGoYw?paTcJtE&Ph%$M zATb_$(I73Pdj+c35KPsEO`T5PyKVKHHr)d?c z`5w^RoM=02kAhPLz3hqD)^vm`&JdqY&dZT8$BXf~NJKZFZbAB6O(^IesCX31%WP@s z!t~j)z0B?^8!u}*2ehFw{-2?nn?0eV3t&u_P!5|<(zP6jPTwZ~%Uqk9{`6$<+$N?! z!1R>MDJdyobnC&ni%p=9KKCV;jhg<>@ifSN4QL*?c1=x#7h-CA=OmZT>8iX6ok^i& zOhHVTAe}y@Y#=&qZB0QzLv63T>GX3<4Cn|b$OOz9YHt4$^9UvHlP60|AMJ3#n?9Vl zE^%(V_bM=b)!ERmhi+v0(}Hv|wV~44I|GR5q4w8B7M0F*Zj|9fbQqN!0}GH1Me7!$ zth2gcUTS*hcpT?gYM^g%_5(G2jJgraA$;B4c-OVo1Blm3-&WH#A3#kX3M^I9OULvU zuYsmhUNgP@3kt%R;1tZPDaC}23!S%thDOnQ*LDHkwb7;J&B?9x8K~)X+#F4?`b9dC zuI;VQXv_Gdn-nttvmU_^nI)?5IBdQ2jl_A*p#MhL^==6?HrcnZ%0AuA9QOz+2k3TjuVT_o@&ZjIX0jnRIipF8*#VUVte5acJh*HoedRQA=>QPt{HGYQC z#LcE2n=l!THOwwJnn^-Qcv2(H$!Jhkk`l%@E^4Ot#PKdzJZxkSl+PF+TC%UgM&`jW z+^O-e-k~t|n*Q&dKS5u?YP>sKcw4FWpkoCmW}@0A0*1 zh@Wd|>B?*wbEo5Xq3Yg6Y(L3mI%SoLOgC&Uf5@1aP8uTyb{csa@Q2Cy>uM?F3VKn* zi>Taov=O>_ej<6nxgm4r759Va^kRkrnysQcEx>> zlXFP^E-czIyC{mo0(Qgf_>G;N5$hNs#sEXl78G?vPWtlLFOqjT+>w;@N|+BYCqq%i zqjJ13kkoVY7v~e7q2#~CEA#tD;y2+KmmB4K-#d4eoR_N$i|HG*<dS- z3<}ypsob0Ar%j8TcHS=Xywb!Y&)@nNF#V4(`KuRHFiHX=TDgw6Uf9+Ff?jlBAg1GZ z0o1vY%2F`hGQG66#5tgQBCd66QV~QC1N`QGBoF4Pq3x) z;`Na`lSX1=>6Ao<`up?e^lTe#N_i!&h@hCm@4kEVg3q+b$U%HBr|(|u+|NB4&RV`;cmHnm zX;L9qvWxA_U{HNYY|(1$P=#?@rxEnHWXV#}8J7h6xK4A8O{#KOG7HPJ5xH~i?e!Y@ z&e-P+lJ)2mbb>~&yHDirzSRBY$?d!O;K@&~&fVQ#NvdSXPT$zbom-Q)jwEF#xrW>O zIQ#p5xO&vVegB4yc0+@bEo12 z&kG*zv^shQR@b0C5vYFj@KJMV?8JClAa!?j4rR@Q#h!T8RRjx7A3bPpmQw!WiXhou zcCA=(R8%h6oS`~V7RLsj^_P!c0MmWIa_24XD;7yk55hBrlFswXWm1<*h^JG~tf$tm z$CJKjg`>N>XHi^oQBhGc9bR3ti{hRATpfhr1iWA>Lr-T9MLfGH*wNrf|5xTLAs)C;Qk&|3zT_bBk(gW<(M zx;ZnZb4dM+k=MC?8PPA>HkXYqn@#G=nLT>?^XJH3|GtFy7iiG5XI{kf-!Gf}{N~Ni z)BGsn%zGfZwk1KGJQy&Y;Pj@5`P)Xha&(*JeQzr3d3rR)Qqzr?Zt3YpN7sptIMXkx zeDsEq(r-u!$DD3ekt*p0NC#i7tQV>249p~E0O6u@i_)2-xZ!!3VQJ~Q5;hm5V|o#= z+y0N)PhX(j7Dt0vBY-SYVD~1+S>>G)uEzz8gfN_af$%lqo z66ekxr)HpZe^NF}UrW!Ebh8w4uUj|WiyC=er=_OTo~W#2Sw|<{bQ@F))MYk@qEW;R zvfp@Hm8UmIzixrHwVvd3)-(2W;W*dvJiz-gGB-N=*acQ*u!5EDVqG+*7w$0>b=@l< zGqjx?$JEbahP|S^XI_jta>Q$<*MRACWXeSwd%^TtZ?BsLH|c9p*W6s!typzHJvz*5 z=FB5AFBZtZE_*s!I-K6z+=`l>Lefh?O?mm+=*Hgi^3t%{`ncxux^j9^B#nfO#Qom` zp8wLlNP5XilUS`zpM<=?&XimZ;R&e`EE8BBm^ok?77a8E4>zP9%Q%)r0^%?shb`be z&KB8G-dWv!40@)OP#`gmp=$zZXshh~_DPv_^)>!AC2fsu1r(6dQz(;OLP|Lwph7jX zt*-9aHDLKyY$=n}mx0vVZKS*)r4J7^NV?C!@P94y)Uo5K!-3s(jd;*A2l|e6UmMQU zla^!t6ykbb3stTI89aqh;?P4|pzy@b2A)3qg9w<(%Oh$CVV!t&a^Fd`q3sb)pVWas ztm*73$V!zepUS1&zuuev=X28wU}&EJsCh>8pZI91{d@V%B@j#p~U-muE(7)X}o_7wsyPwS@AOJ z%q<_=^56L!)5~1R;KFn$`H2aWruutNbTdJSHb^%Vt{PHNI@1f0Ekp1u$z1>~n3b%I zBi%MYcGzDNfEmQRjAMD+)Bp=+P0EWYwiK&dV!HZ|8qbTR&>NXv527Iyx6U~gQk%!+ zD#O@34I7qfSJdiq)Cd03amb)^wt^sa(a$E`6Rw*wW#SQPAtw}zIY=%;!y!Vo`=+bckU`Bq<0VCJ{Z}u9l;w+ z$A^xuWDDkW1oiVozF>kOHJ#jaqo&`&hW_f&g-Getoyz;N@W4WhFt2e~_`R2ac*~kD zn3tRm&9lnUm!+nERDLDdV^NUjw0QeXNh54A(zmku#35oCsU$uA#qr}`$f^EL_i_D+ z-d?$j&W%;^?o{L<=T;)5dsY(Mn9l3>EZXI{x^>4FVI6KglUx#sEGww3y}tKK(L#A# z5}^6YL+RCrQ0KQ)D_5N93`9vQNl$0Lpv8VTiMdjpg3!!8q^6^jD$zrND$#oGw3=d~ z6S6o&Hl&^QgCkov{Pz0Ih-Gu0e}49!tomdq{qRc{roHAmZLz|0?%tcXx$|D~t$sND z%g+hF+_Pkp8%H<={wv{O(=-c+*eh_wTCA z=b@^gal~{E!NJdLN|vA=m%KH0Fo`NzAA!0fKKJZRw76Vk=U_Npf;w`#=3~4bPI0Cy z<)wQ2N&e4adD*`md42Kn1vwklP}Ytb-kp@PCdDJ{LzJX>vxh@2Y`ywTuEY(hl2VRq z-f=oi(e;TP8DKh7MZTFZG2cf@Es3yP5JI8m25b$dV<-1H=w3`nBTqiP3TL`3FE5G9Uw(N7rk(vKw!FMT>&pj&D1TVy^@qmM z3mypx9v%moMDXQs3R;9}zG#I9&pDUwyE3H*En;_7&>|px*7~P>7Wue)dQ=r9*X{5K zsmN|lX7|w&N8UBQ3%podDb%8B<^xT~hB!vza^b+-O)h*-XJ1!G(&gFTfSj(8P2_rW zRfY3{m6h=eWUkMlUK^_z_n;|Kh(ml;Wo1>86KRb!JF0N4O0IIP1khcboU1&YY?v-@ zy2ithZm3*>`h#J)TL5>-=zzMMEpRlM=tf=_x|^e=rN96Fj}^9PdKhtv@5QpdTvZt< zv@T!z&wl%r_1poHCoa*`HE#_5%@|X=5_74D07O1)qCE9u1!#* zSR3_QGCGczWqZz0ExKnOucXX$Sz2`yWBOa~FC!s_v_=vfH~$DqpCe2+YI>98^Z@lU zGR|~1v@L?i7@aRaP1Bh@)TNp@Mj6;GDmSNeRG&1mbo|NuV>6N z_H;}yikReI*=9GB^zx+sa0}A~;Ig;K2xIC;H#5;U!un)G>8vzH=>WU!&-Uf(rPoVJ zO2PDQnnY%0iP5o{6K01!J+M!y*7S?#S!~unK9}*G6Q_oT_0okMCB2OXNDN3l4bMkf z7A+_VZA>YdNp#_8j~j)gO=l@M1k+`Dp}Uax^wFLsZt29E-qMkX>t(vPyy-2WH?Xqg zO)|a*3%6O5YI&D-uo^XeQW*g*#&bRf)e^*i`SmYDZ0(P>_xQBeh<6T8;pV&}b99ci87UNF6+94SrO z+uK-P-djkY=HA+v*5rN7t>tw)TI=cBy!G#vQ9bs5`#+vfnc~4WK`DwDTQGP_nQqV1 z-jt!#z#32)X+4mM+(1?z^xl9iTwyNP(i%uYgpW;6Qq1DrUz|MN2Q>!Y7fs(6+45mV$xnoUME8(YY?%2+C&;(5Gl1wNKfKINDVaS|d9;H}GJAsY-H0 z*2i$u{SJtpLl32J z6d@g#J&vBv7HnF)y3DlhGyq*5dzham%!HKo$ke_}j3!(}RkC41?Gu>^n4{gJ@haIaGa#fbTf!dXBbR3r__(C zSrQu+Jfn^4$0Bh(kRC-&7(?nhrFzu5RS&GoMtDbcXEk$oal6o+VXo7OVRW5x9jCg= z{OA>0uM#FVT)xi0Ic%;4e)I;gj#*8Vet#G-9W~u$9G-jiY@))yK#;CuD030p2RdaI z`FnCWoT%Q7j2e`Xv}xKi8)&XpMO*Ua%lp%v0S5+3cn;>MpMopL@D zNC(G|MXspn_#wjGo$Z4tAdRn1w~Xo7XGpg;CSvFO{Kd44*+_)Og5^QZbV70$XGu?A zc;zip8P6R+RUWC{{?74tj$i5@9E`<_;u)_h((|X|PH)|0H@J21{1Vz58E^Xe1Fv0p zRi&Z8IYXN{ty7s`&KWV?p!%ycA(gOhjxVoJf1@u}d!Svrds1_Un*>a^GnkG!U7QZ6 z6YqU#`~FMEk7M88en>4)!E|@>UZ5NJ+?YFZaj@@NT~xFh|9Ra&Xv^7xuG7N3^br~^#naCk7sdH$J7fJ;F4!3FiwtYGGd_ES z*uH8;KI!Q>i+B3QXG={NsV{jm_>pjT3F?J~cjE4xJ{=dA6dt@}NpQFiQ!HpOe5oDC zoQ^}o0ZiAvlbw8N2>DU)INve)j}nxi#zy;3u1ec zv}k=ra*?}hRZ(ksf?q{Za>Al;$0;i*o^`6!9xQgXVDIs$;0uR+MNNENJp}2lKECl} z9WgcGd&uL_5m#dx?Vuc!4D9>HBc=P&YL*!tb|L0`7_7{$h8rM{5|pJ;ElXzwyr$ zjgrDBJ>7D>sF5gnFQ(Da)i-|5cpotx=Q!q*Q3P?c^fIHSV}2P|HfJ;FjbsjnF9Xye zYKh-_DE2fppEzHzs3^K+zI^G+mYuo#`dfQ=9`kX)V0u}0hN9KCF2Bb$%a%R;{bkF( z|NLe(G@YXgQZ#hNDsMPl4=$s6Q^cG(U2L&z*%2UJaf~y{nvUEwIWKP+Cp>0!nO=Z& zNFBS4$xNST)6ylSue-4h*9-lPILh`i4&#fWUUXpBtSKQKQ`4V)R(vkEI_WL|`y|Rv ztaL`5j;ZO0>eAC~f3~A(K3Ym!nzUne^=(9@3$zV;_kDQ$fA$3il4%#}Z_*E@YpTHh zRH{VDY9v6N$U#Hs*j`H8N|l~YL(^g?GMdX$ctSqx6!hwZn&{w0Ae z+>fYq3P1sM>vmE1Lu$IYC^h|trKa1oc55@bVB`3Qz3gurOvhZ)5R=k$J%t819aGPS zepWkB+dH$XYvz%FCNE+E+vs%E4XJ0yn_eqSze(+VJ>i zM#JfZr`OfB)~Cdz9EnceTeq6ZQ3UkpwQHlZlWEx8Tz99gzPz;=kJQ z5xmb9bNC-Hc*b7Pm&}yMANTqX&UAgQ<=pgG!IDR&#QjNz*7h2|>+=sM&;0SyZ#~f| zOYBHuTfMKmG$kg=KgI5mLNGnXHEtp-DE5?4D{h@S(`#)>bZc`_lB?ar88qer3n^;# z{trH#?|Lr(h1*2exW}cX8+awS#ciVZIAJ;14F6*5 znUg0$gQF>n?9tfMaZt#WP6%V=h=5v`6!!!tci6Q$-Km1e^WO^7 z?<}MT=t$0fDoBsN(?3E3qC>kp6Q~=F-*kHGVC>+|t#Mn=pC6U;-T7A! zZ@}iFexyk9x4w7l9F%_U^!E-d-0+e(-6Xwy@1+AqO*gLfqc0zpn*PpVcfUV>9)mcfORIp1**3Ks7<>oA^;~dUAF}EDm@)FKkh*lw6&YM&ccU za&mF#@2Vt(WhJrgmEr3}>2GqfgyBP7dFvg+>38C`E(s>{J9vqmk4LP#Px$(9JHHSo zQY!KE_)^}vlcySA?TfMdQ1yug`!98${P2=6o$}m`8<%gaUJ&H#I~Z?Ipv~5;@#m4$ zLY67bOiO6 z4{pKsvcDK1{=T(c>yNE*L1FD!=fQMR6dCdSE-W{kzQ_SkPp?i-&&BN`L|;E^5uuZq z`Byhr**UFFF4_@C=uQIt24+oJ?|=h}uNba=XrJ<7ULzN%t>wj$)lap*2M#H$S3Cwq z$UGdAI;G*@LQlf17Kgc|ase~CocR8#N+-GcamVBg0ABXqQMeCoC#%Q|{F?5-1Id$Htn3F-#cZ4MaIb5#2I zk7078b2(qe?CEd(7?quyFr`2DbII8{k^f{BzKL;Vz-{L|^ysoKhy5XbqpMMwdM7>q zeYEt=aJszeKsk3ddb+`XiS-0La%DtW#F#bxX<5@%DXONVhSYTlHQn$!ls?K+qjuDU zzOUPS0~5&HbyCxzbnOz*PJvN%INIz&qzj=g=5P4@E~HPAy+}VJi`I!|w5jRF21Ck= zBzFXLJTK3Vsp%%+1u3$ZT*XEjkpkXoY;?JoCP)9X9%Ko_n!Z+DNBPSig+>z7xi`9(=n{F;Ig8FfDb5PZT3hPn)zndj2_2;>5i07;%aiG)gB+Gbo;?n9l3s>e zIy&&2k5hNiRc8g(Min$i4zoW%c-j*^wBFml&(w-zYPuG*YyjPCOi%Q|%{+#&rr)>`SRQ?S?{$!_#p~?M z;h9ZdaL=f>S3pzLsbQ~QwPD22TXHuey1cgQ3CGNP_Dg9w=V){NeQhBb6TYK$)L zjhY$O$cjczM@_FQO{uM|O^GgTrHZe-yf8W}rj+`Uxa7j-Iv~Eao^Baq|6l)s=d%uC zZW(}hvrNGzp7YLiDCu&B3^fc<6D&mT3%o|eiY)4FKr_-irttylLvb?!-k8)$UA!ia zPp!$DyUrzaZ4F644Qo>y=FT^*~eB8W@(A(KwLV*OofO)FCx<2y+XVK0Hh;Olqos2Tz9( znRRaMp;=i>HHd2O>?E)~&lqjc%ZD2>u%l;X1|B;`6k{5Mu2-eq1&H`-Ql0au&_6l8TTKsEaC+3kD)`vfB{+Efl5qb2dALq_ zWc38H6=U7YqoW%e+26x7a3A@fqG#qE%HZQ2Sjv+1?jd0>ndwCi_@{YjFCE+K2DYwnO!)5=>-K|%toe8 zW%6PB{HCm5Ow)Nrbw1I4Iev7L@p-0Vb!*}3iXd4bD*HoJ7l^kO_lu>a!$g3)rz$R8 zG0h6)st8@IY70?TjW@l&KOI?Byatj=UuDrbCqIAI%9SSTrMj|s7rHcx z{)sK_?y(CG{Pu$%zVOw#4GAM7gHE4*f$;=2{rt{c&qKSaMzX86ZpuEriOX?uTL-tE zK7HtKA4J~%R^Ulfr*j42CbtOTa%Gq56zz_jbja4Px zIj5+ue#hbMU+kba(&0;oi>s>WeTmkIxax{CnbkF!amaNLQp(vvSUFxGBGQSxr1fij zRW|k@ZiYAMUK;BoeimTiRshuKbA&jmiI5WlHP-%W?v15q;T2><=%oxYx%*QcD8s!= zZu$qapP%>2`K9X@?=JkLxADu}`S~2Hd9Kcz2o14kww_FWUsWt#e~K3Kb9OGL+z^X7 zLbekfc!DZ-6=8)J+QmmI*~Rjw2M0g3WR}m?xVX5}cg}GD)0Zv{UQcc-Q6mIM&04xN z+>saODJh-7yQMJ31+u*CrT~KGAT%~YOW!?06WZ#^YTB2wA0aX_K0A5qG&|SGa1VP5 z8!G@%S38Nv+|bD_I*&$a=4taqF5hY zy43acPZ9Dm%g@m>nXr}S=87dAI|{Sok}2qP3V&+pED#=tioG};13sOooGHR(`XOsN zKa}Yb5JXKwe0&vC6ow~pLFnluFNTL?Hy4e>CnwwYdoETuWqN$2CvPLarFP=<5C>mc z8HIT8`|Z(Ol}sNcSHBQvw0dV>=84u{gWzr31nNdi*NJ3vouHxHmUO{L?P7Ezty{Ji z<-NQw9o@+4vb`91m*3^Ty>XT1ML&E)IWI;~w?G|rU1B;nt@`=TS3UO})^uQ*Ex^so z45U*(+J!xxzCfGjZ2nQ%^J3l2s?46#Q#MK|DRfO7I(K?cp7K4+7)VZ^Grw$}q4Wsh z_9*K_oKY6ze5C>w?X9!8$i6w%acXLzhiV_;%G;YThCn7^czF%9i1+djGEp-)b-nBuiVDOVj%nW z+nGdj4?*~}BZ9!!aVJ7tT3}|2x#csbl+=*5PNdcgsLjyz_i>(Ev^)mlQ24t0E1Fwu zYmTkJeZPLN-M4>fHhUwlA^Li0ef_bl)ZyB*Ue{B-J0{MY*){Xb)R|3Z&t{$i>|{9y z%Z-{IbL0p+DWG(?op|-$g3y@Ky7Kzcy?e`}3#P7V)GY$_?mALkYHKOxD=n;~6DiR# zdqj9#YaS}gV`iJn*Hy`9Fhnj&kn6#0sRj&zY53OsVinL(}j|eI`d2SiUj~zdG zvTwK#y9-RK)6k5rHZ08$PNw5B8VOD`ZW-~VQ5WBV_h32 zEn0?B^NC@lMi}0bd7DS3q%`wvUVEaMIIJU$k$F~P=Rhj1mxfg445=+OZEZ5RSoxA| z8CjXBX>Fw0^c_1+lOxSKh8os5{0+S6b6eSyT=E3w@4erWysdXWdoF6aFx|s6JNi?g z{+-_RN8-lQH3|RwcaEYNk3SYwK`wGQhow3MPx+H@{$MMrX`N8|rvU!JI)A$*<5MAK z#iCpEXoKOC4X(ql3@eBb+NRD^0y0!?LuY}tVO&{WTwJIfHKn6sbtqjTJu3P*Qe3!I z!Quf{7>eb1u@rShrjNtY&Sr(xLTsalYr`CQAnW0{)-2jC>ddSvtzD3=+aIXuX4wYg zqH`Ht%n7TQNJb0btyzin3J}yEsOQGD=cB7T!4xuH$}LXhIkPbCbwOK`Dvq0(PGljXC|& zC6Dl(>FGOTaa{=0T@%tBat~2JYH|9fguX!O9|G##`zd>*P%&Q44qCpee`Qea0vs&4 zbXl$3zWUPk?SwfVK78nKaq+I=bW;9`K}PKQddu|A$#JX$wqu#wG1@r$I>p<2K z)jx9h>Z@Ph{rKv=A3eWk;hRgBu3X%I2R*%+7NazMCC9{FrWy|-WU}K{CvRdl0H!ZS zOkW;?YF$MqC68hUqFQ*o{wn4MRb;p?MV8>NmHMN>>A_3FV^8CG;c#bb+|N(+jBiU<-41w4`f78HS?Hj0E#3Q<%J3WP$G zs6n(*5W^5#S@Ezw511uun&nPn%N`Bth&{2@SK^!O1^T7CCziTdR<>9 zZXDW{=Gipo;|oTtcnIzf3^16Nm?)4m&aN5m9~3~*vwsOwqpql3W@O3@6k`TqQp#DF;4#vO! z{Hz~8KY7;MN=0N4oSG)b} z^b#w>!xLH)ke>{rCl$rP(`qkk55nqR6XbBjIhaE+>>;5*I*uA9iTVQR+rY1(r-`Wy z`RFM@gN~x2ocd^we-gW0@+hqh3!{XT$qwJ60GutwwM-f@dC^t2ts^t5KGPFmr#WeK zbdG=z@r<*DOhbLuf=gqa!4on#V^@-^!nDLHZ~t+$)v~)h9d#ppzS~@OZkB zNo8ElW@h9kczPJqg=V7I?oS3yh?AO zSC7wy+f_wM1*uozwy4Q6>7R!-@1wC zAnx{YI6(j51F)}k;P@}EuL%I^e)1eO(=PQ@mFgiqX=f9A~9b!h2#sNsBHQR>QDQSki>`+?-b-S3~jx@*^~SFV!6 zPF&Esb@Qjw*YheV>?%8be}2L)rN>O2T8JWl_VnM7ridzUWOc*m^Wkt&I__}*m_TR0 zWy}EW>u|?VLvbE|%A(U(uPnioMM2f(bxWoeo;Xd*CAynZOmQ4Johs7h803-nP4OtP zLSu-2;kMDIk<=Rt7jlZ!FLw(rbWV4lIYEBSLTvU*oLr=rbQ;M$q4B$$UcR{t>8TF> z=k=ndKk@a|m>#SpkAzd%^NpDP?P~f%S&5k2SO0-8$M!MAHa<}7KslH_`P=W~2LH#m ze)~Fqyjy8RgrF`?23p0&UQjnsEJmGxC_!!wzI3#7L+KVWTLjHL#ISfjj49om%JsrV zRX-|&50s9iK8{FPVY;ar^;%xQSy8$&)0qtj)8%&uxGh}Q87)rD;Au%e*B?~tx;Zy= z&b{Dtb7yM=f~_s zFfa6e38{cx)k9Na+39I2M-8OML`=aQ#48);`;dyT21`!|)H~g^{6{bHOG(aZYisRv zWYoD=5XRe) zwhz3eMD+zEs*eniUG8=4>2DtyD|7mVf4yPfShO;(lECp~qV1?!41<>U0qT^Fp1pAR zqn#h^#P{;EvnMWekyOZD0hfevEYh7}B1b`U6xrz|we=UJrPCRy>s)hQTpW^ac?r!Y zi=|JK>f%qAPL*!LSuVjA344xq>LYE@DNc;kHPAR>Jynr76P$FdF_g~7VPkfJG8#q~ zN}6m21eJu4c-UML5@2u2elhdKy)V9(c4_vUm!Ep~x4-+#Um&Od?iZh9dU<#8;!6uK zlM}Ppw^=<%x1grWaZMFKO&C@jY!(Eo_%ShQuPhj(kk?^v@_1@O_^fFVR1N`#x*%qp zN{&i6T{{qw)R!)uICkPgMbz%z`wan_Zw;g@#l#_we@KQpq9c=&laf;4d$Jsf@5T?m zYGs`f(+M*pO6XkIjjnSUE1>kj;*z{BLiJMu+_*aZQm7v#(#1jVq5y|KqOq(Tc=S27 zW$|o^`6}fxnUilG-@DRJP}%j~hDc23UMf08f3C5GvXGn^W4r;=!^%rSN>I&@e&1An z%Gt7NRX&)0jQu!y%|`=D43bMfUp0%H;%H5J>~-XI<8GmP)DqR7U$rs=OMM*uVhMP8 z{dJX}g77f<+oqI&=2L#`8eq}|JX0IYjuMzYX%z|SW5=#s6<4x~^RcvUjgHPEp0q5} zo!nI4>IkG;S4}dtpxDNf@;z?`YuRHtGqO;^8Q#&K6py z2!LsxN6|oz=#&)POYJ$WWpVz|EBSt664I^(tV0-P?EdsJMd)`M=X{7gr_~c(Q{7r0 zhM*o@>2URV{~Ex*K2A4OZrI!cbOd!Ts&k8mj4#Fn1C$HTVeOGI@A~X#)y@by2g`rK z0p$zK0Y>L&)6QoEu(8C+`8z0bEGEiofhzDY7)24y9{g-Db>LtcQiC zWq+Z(RN0O5<{dcsquYS@fi*)aN1ffW=jJbNzxf*A{#4I0EHTTfoIx?&!d%7zK8>IkiRs3e&ME?RV@rqU zpYUROJhCqmI{70QUv6O|fX#n)_RMY;vfyVYNP7X

    +AxRVu0`rM(Lm$yg1U($)w> zM@~0-`dT_}?ylJOL3nC<%<$;oh}86kiiU*7b?Z(W_@)u)9sJ{0=`F+&PzRa7^x;== zvpi7r2`br<;sKU)tf)xT)nOEi-ntUtZ%y4dat$h(0l4kx4Lz8N5|R? z?68=gJ6(OFT84%QTJNECY2p74)63Yf1QG47#`%A@8~X{kzHt6|%;QA9tb=c-uETqB z;)V)DVRjXh{vE+Ce0gx8tRuGN>VBi9gZD5m;p0nyWfEZKub)3(A?AvDq=69WFpUs2 z3F?r4Aw{EX?hfUn#I&HQH(q5!3^=-R*OmQOiGtzsc@7v-sGk7ml?_ukHKDO^Q6Zt9 zQ+bLfHcjP;H^$IZbk~ye^RK*m<^23-_V2p7u5s5h?7Z0(eibA7{;BJBEyr=Qh$qV~ z8>SPOYAA^%gmE3S4s}Jk!-GsEpA@S-wX>ZgsV6?v`KI%4E+JJ`O1$zIpIG~~cXmJR zRny($zD`NkvTs+@Q>Ig&T7dxeZKDQ9O~gnZ3{6oJAD{C3Dehm|LN#ujh?*}g`V(G} zrQ95q^8x`&#x~?F8WxxuIel(0Er`_CNYrc!H8~eE3)7)kljtZFU3hM=Uwud!i0~NG zVOj7TN>>D-s_7t* zQPUwK2moac<<#GSBZfGOyxJQ7fWVaeY8y;)Rhbn z8u->=|68A=Z2!%XflvP5nA3mp$&t6R!Sn^!J{j2lRzLKJL4Cnn+XpN){d-4%a}4TM zB%=};h3R_-W_={r%Y_>ODMd-==0Mpr_|KJsUJ_8k{KS~h{X?B#dW{pCHElm# zp(Jk2 zvJ;2B22980Q;<@Sx1u0A%5HOK)o?SCI~(U2+uSacZl}R?{#xlUaV!RxrA0*pZ~aiF zm$x$A4q|=AVshdyO_5)yeaJ^9A3a3xzod^Xm@%9(f9u+m63JPr(D^&mn zbV=z@G177XrV~4IGlXnhFq$J!qf0c55!5B7zb*3$1I|WGCnS^jprGcwS`u4kiMiqQ zqw>7yl6);MJ-_OupOl9jo%Q`6fB)^b^H;LR=^VR)Xm4Nja;X$myX)lws4xirG<3*wX0M zww$0qTWu89bAG}2IPAEd_?|%V>G~A_03ZNKL_t*AWZPu9Y#&Inhb} z(McJ#ZtpH#V|p9D!+yr7^fFkM%E zByLAjH`h-B>B4k#M-eiRF4#vRA9@N#$DKZtzCf_K02bzbs%q;FeB0x<61@U!KPlxO z#T*?RbIVK| z)}tFWea-A0^RV8m*)jW4IFx<>OkYOJQ9-!|r&!i~lKRO#m%0xiroVvT|Dh%iMoq`^ z@&c8ia;F77$vrM83S~-!+2<^L1T>KP7 zzg4|y(dTERrK6(*?2EQhOS-KWV`OabnBkt(?uLro4TTGDE&4Uc{I`E~2ks_CQ9+6V z@2hkaW$cQGU49>(#o-(+V+sx!L+Q{x2ZPUE#at@+12~NaZg|?FaVhBD8-LAZNPT2{ zWkr@hsGaNThY#rMRHgDnFx`B(E3u(vSHw?u?TUCc_dK?j^DVpZrH2ns8gBV%%in

    zH&+4H{D19k2nW)8hPt^#+T#$i{99jZlK2y%5}V%WpAZvcyd&q;;d4nL*73sm>mc`p z`GvjP(7!=*l=i8Ot9H~%h@x3w-BSrRdjQB94-gMmz>9w(g?C+O{a!b z1)htx$z?;qDY(CG$(5MK(krAX&PVV+v1rK^G9w#zA*Z9HU&Z_KH^;|3(};P6YKP@l z6M*+EbV;%-=8{_j;XvX9{uzk9+5}6(zwL-oj-wZ?m{}Z zntys7sOh6hzxJb3b?L+5OCO3a`=%1oKcJ?^S7V!ruz&5weG4brX`VFheogYygWRX$ zYfD;vckydrf-rrl@9LlW964AAh#FKD1A9#^g41a#trWZx(*mWlhG?3=bO71lvIW(G zSAf;xeQiryG%7umj^zbO9sjmCU6d|P#}i^E>Z1-|JwV zYmxWIEYQ>8g6=MBx^J1ma86`$p=eYRIu|W(I;R@2y7hVuiAysVt@C<$p?cZAQ!U~_ z&08Ws_gP-#^igNkRFm(bJp4)H9%t_Woc<+DZ;x`g2K`eiqfAKlM#Ryge0%+&)*Syz z|Gt%RlmIgo(TC30&&>e>6&Z^>i);oc^fYhUw67w(?DP}V6c zGVX6D35Ed~Dd@0o^@HgU`H@eqvG(u&^2mbB7mvJwcuvEk1zHZjFM!n-umJxyTDpD| z^CC4J^UJR=vQK_ql>YPoao4f2vM2>Hon#fb5EgQ@*TS>}5z~BZ21~YW0=l_u`j`i z)0jHj=xAeC$6_3voNous16;gM_=e29B_MEBG(LwYg85W%>)JO+SUPbigDzU|&^Gg> z_I9R4&CN$Wowfb_>_+%v=F2k=ysJj8zy0022i~Qx%i@=3-~M>PK;_1bDXpKA%D8XK zisqw7OUi=?Ou?Ak>Iqe&B=(2c?I{IO%$z_>l2Mc`5~ALyA=v9{9R*QpPg)6rTfgb# z;WOfk`rmr%-fytJ-0R4!S!&8y;xWD?lamqxr&mTtQ<;D*C9n2elG=}&#zq%6A*4%8 z=hNS}0{fE#lBP55;PyfH_LO#eNM+svLJxbOKh_0cP$6`~@GTlqL%kxLOY7ckriyI51t8!GU1d>#*Zw*aT zCp(yGFgsx~iH=POzAY?@V9O-qPM3}z7o8s+7#I?2_q4h_Hou%hIoVlMA=pExTVP_5 z7nBtp*}8diTN#-=R3cCSOC>QQP!$T`I#VXu(U}C`HdEm?qC0^>yhysprc^rY@%Gj3 zP=820C>lprPzgJ8D57N>e5RT<6mxH;KkRM@^s{?v!m2}p!UB_{qgPgDUp zO@DA$+PUByJ$>W`F}rc68;c9R7g`%xK`$yQC4>>5iMSjU-FpPq;d9HFj+Xw~n|rRm zgDc&zxiPzl(Y=^Xtc#rKm|k#-1P5=$mMsJ(M1A~@5ixzvoW*mH|99*l+hq;T^qDi~ zEq?a)&6|WQnp)J^Ewif*C@}rCo0o}VB=Ti()v`G=77s5b0EUB3s%A&9vV7^WUO8Q+ zmmTw1(&Mcl9jbb4#{r4y*j;?6E=;ad`2x99#2CGHVVtWwX z2h}pQ_%54U!E_(Cf9W=P*jd3lp!YBFJa^$%pD&%2xc1@ST5|+*7bsum_$!I8HnhAt zX;;ioTYj4RL22%JI-|5Cw1iKZ{p#>fQ^Q*(y&6N99ftCQ2OAPErFW;_>`hZZha~c&v#D+gefd7oLac8cinmdJ5Q5U2;1JcK{4lr z!#i)B;NnG~nv}-l&s@2~>W#?j>UD%?9fh0<(DUmWX>x=(e}31JMQ!Z5nZK(Mv-v_? z@C3V@zPm{|>#WJ~G>MRqI_Zduc0=nbB3-B)7oN%P(}jfmFOl&ayGlBZaYr9-#9_Xx z(G;AfmoA}X^@Zh)?EBb%wQ=qX&s=$*yDp)z5!aVoje*I}Gtm&5pFV%}3O<`V>*ljJ zVCTi%3WCIpqx#YFSMSIRbAI8r=%lZCi@tWzH)Hw}YcZFU;Z1*Z($^Wtm*#TI6BX2M z9m1FL_2b*s^oJzFPgwo!GYY>{4D9tIl6&$tx}SdgX5DyRrXBkBt$yuW@$XwGH65;& z@-0pKfdhZzC=FFO_*^KRkQZ-aI(+Mu+zmrhKMJJF^de4ISh~(kXga=aEH9Fr)yc?f zcrhwE7;7BdKrN3w*Er)Pa9d$B(#S19_d>h4+(+tKqyfk4#QPk)*SMd-Z=JF+vq=%U z!d)zrx z;AMJ&o@x>1P+rKCKM`o*^fxA$je_G3cN{Nyix_wKvD{p5RP@4blg)=%c8zrk?AtL5K*{5 z4UeoLNY^F09#Kh}dDn1yXY|;lq7>wPyPcv!G=3M3jeRRJ4$~R>?1`O+5AVeIVged> zc7f@dTp&&I<06b=b{Yl69|+ zD1g%)hD1Ghu#?EjgEeh=>~_ej3y6*jh>KoD-zf59a0wwC%Py3MrJY=HT9T?&W~iEX zmV|||r(%$l^iO{I+jn~w&wT3HXWxD2+2_b;e0ed)Im=o~)5@ZjE_L5pM0onSEo6c> zgO5R;`nHbMWr+HIlkF*f&}C&oN@WK5Aucps5SP6LI*R1mvY3I=oD>Kk;rYn5k`r!W@^Zj~DD2}NBGAVJWEDId$aGG5BD`Ug-2 zVagl`64WFJk4X@-ING{GvN%9AY&fZK3TcK2$KyW{y<<;_q&F$RO+n}}8XA$2&i;|Q z70s`c_d>f+7K9v)HmT~;*Ad-kJ>OjZy80sNI=44>c41yIO8WO9`^ck4N{6L+8wYqN z+u85KWRfoglpJO&wu(qsQAH|HPtFevt8dK;DC7TrTT^DMhn-PycPKAH9kap$1MAba zZO-Xqf>TU8Upz#H(y_eIhZXxe-ymLSPymK=cEs3h%mr$eu8@|`yuN)3VI^YQ_E6QlU!tlKFHWddTZ}`3k5@I2WXw z@tk4x5yy*A{rWuAbc5>xbpz@0yO?3z=$Kus`q7ah(%0TRX&{~AQEBPYvPI~U(w`M% zV^~2=H;1h#&_+$CO0#Dkls8EA@>(bcy7XY10O_wwM=_kA&6n=)?yH9+&=nRf@goG24(?7kq8I7G<(pzUQ z5P^XMMwo68UEK?FalrH{rUaV@af8x~A@R>8sG}ewyHgTLpC9rh)>h=^mXBb@B%t5NU zcgyB>3)A&@8fGiLE7l^p)kijkVlOrQIHs3zw+VyaziZb|V{xXZr~b4h0c0g+srWApsw32;AbjEas&hFnKb945zwa(*{9 zD=J0lWwhi9yng=7LfkXz56Y@^LItuxb2=ui2g;8xDa1_E2;NVhzApUAasn7%IDVC` zqF1g`IlAjAxi8pg8h7n)WDbD6Wj8gi$mw)wqGI*^MVrqmIED$wCNh&L9%Hh4XZ{r? z1yiqHSyvdH|G+!*trz3lz6r9Qn2ylxgn1tw|8?f{8foa`$vux3Ie+c=18Vw1fepA` zHZU3ZmQj@c=%b?#jbOSTDUPGsMy`I%9pl&XbYi}4V(~RA{}C49O|eWbUQU;Y&R;hp z9UDqjsQS1`N@I~p-H@?iVo|cuqA{jhQo1B`;FT>(N*DVFPf=qdVAjHPD<<7|T_mQ< znC`0|HFzyS92$RGCzg87BLL_=P2I=jmISVA2GaR6YhC6}aJqi94Q)-bxuJ5C?_#Vk zbU2c(&SG<$c@=uKlFY3WT`*+Mo`e@p`Ihs>h~`aKBXw<3fbHWEWV|Ti#p)~@JVwG4 z&U9JRA1EPp_>-U#g|}4>32{0smRwWc)>d+N zo$O3L`!gcG874&iLRVKGJ(`4!WHIL1*qvYt%dT}1kpq?0W_FgnpTh{v_K+bC63#p1LI6E2U8nOaG*^H zvb;Qt84@c;IYCo&dfOJm=)|P|^1uCme)rVOmtUUoG6PN`?aU|wNGxxlg@9A5Sb4iOqZO#3U7LT0G}(rR;^_o zd{s0=3ANLj2xXgZh`t@=6pV(1mXQ&WZQ`xxMK zOg&74d5u9)_Ne5E(Myw|ag6@NxA0~ePd@d?Y^NqmS@S`P(1Fn@MGb=HTU$dy%35>6 z;CKHF>u)t`x>ZCv$8-gS>rfRq#Dbafo1%_yvnjxN<5_luNsEa~PZh#iVImX`@n2;`r5Y{n@h zbrHMwpX%;~3vaDqX&KcSx!5pT4#Xa4iHPVSSZ_0& zP8}qyzHRrJ&q-t?zvT1Hn>#u>4s{$%tH^CA4IdgxY)MR5_eJ9sc-ZGwF?h`N5i5%H z?mJ?07XJFL=s5HMH?!!4`!$^p_{=f0aNEc*qPy=A44Qjy{VJw^iRXd%`#yDRTioqK z-*#AHnQlsv%OP%Jh;VnJmTGIar^z(1s#6(v@Y2&21gcuUovMZtR%x;wM-19hLVwR+)udPU5 zvW`%f(^IcZCFo`T>9dR8r{3~?`i0^Xf#)0XrsF!9dJ(q9pYnIqkpjvK3lm~?t(U8u z3>Ug-UEI0z#Cf`3twT=-o2Q$<&=LC_7cN%V)@jCh0^Pl_C7U+l=l~S?)xbs<>|`+vjhu_Tr~7Y<$0c8xKQ49 zHc7WrLf`rF>x-|s#>Jf%&zw1X0yX__meBST5x%i8?>kSFzFAFwG!{#E@^k=vR5-x? zl@Xr?Vm~?#98ONh{qptW+huPoH8@y;A26PO|{phsJuUT(o zQBC3_k3RBe%XxX|A#l^URSa3H$B?w~5l#n7RU?@gLCOp8YEiQxTP_=8Iyo?kUN+s_E7>-!i~nh;I0s*D6unV7W+rQjXWH_ z7*C*N{{N%9yOi_-W(pMub>kY!aXCg=Y3-yxk3~(_Dujj9)@4u^Nd%0|xL%5Dqbe&2 zq=>^pW1>267KdPR4+$xWY9Hu#ddgn;;k$qF?k~t=tm&-#h}8587chF$8mP9@LmSP! zuDp^c93|?T6BUZVV&JcT_wN7ex7Wx@=b$F0*3on}TCm_(17P|CLoJYW^#?M*3`G9K zsOdM#snT-}5-REL%nB=4YK^O}Z{N8aXR&ym_~`KAeWa6UzHp)IaP7Y0{uS-bVdS_3 z1c)btP;BLyrc`u$ZSBq*cWjUr<9WBtVVWvFDENf8Br`{ zh8Bofocx&NB+N~uyzJ}3_CjMLy!~~DJG(N@9q!Akts~_o%HgE_PVHby{~$3hgQnCr zC@31I4C*QNT$wcc=NlY1lnOZ>6S!MP0t?q*OmCJ(qwHoousJxP7Q4yjvi7h)ML%ZpBB zMn_RsLsAY3VHAd6_ky~Vbd`>B_04zQl=FqC^y|;!cah`efDzGskdB^x{kiLs)ejta z3RC)V;{Q3p&TULD!&N==W`M9e9-~v~3_x9kerg7kK8Fd!;%8s`#m&pl&3sCXP7NrV zUN#%o%Vk|yR<*T?ke4TC9-y(&;t@4n#&%0a*Heg8UYhfXP~8HPTwjiodIEQodTts1O1xJ0X1DPPEtBMfGtXY zj6dQt#OC9@2+w71n`X)BY-Pp-m|wEG57W;`PN!eYqEG4NauzXtAzI@ZYC?CD+H(5N z&n^-PzMDYxirk@bRl~@;EiJLb{0DeEeNhLF_7gPW`TR_pQo}dhLoy~(aC&KYBJ|o5 zF%%mc-Y|UwVb>4XP%MMVuRr@|3)3x{_8QVf%3OrhNA&E^i5>AWg4?bAC?O=8Fp^nv=t*bNNTfO?w4-K5-X-UwkL$NW5rAWj0g_Pt{P2wWK zj6Vt>S+&M7CfzrEUV^eQ8Af|)qsV%WRBh2(?yx>Ymjaja*;_+QE zn9K_+a+efVlqT$oSyH-=ocHvYa2(*IAu2=tj@k~*2iwnIfoc_^c=Z|GbN zS@iySG7(Y3cg-cwT&2io7Hy&*(wVl+L@4gZ_Coj}NPLAPmibc~34dYiCiHW+X*e_; zSVmhX!5t0$%xRqMBo6IfL|7>H@x~f9A}Iv+tidyJ)wu=rCn?|NTNNFSzo-^n@^L z2k>`z`@gw_^wD6_QYK~!z~^rMJ^k7vnSIm-9>Ej)^^8t|Y1;4I?aR-oCI)-^w-FL6`>;)8bn*Gp%{5a)s?--_h#AG5 z1?l2*!{vs@&BYf^nT0I%-fU(mu)JI_ylKHxNP-umrzXZkjFWfAP`Yv5o7XlH$XEn5 zR#uX?+}avew6Umi^x$%17_K=K@ekpBJZDg<+z?`VUq*wbJ zHN7UxktEa0(ntWc7=s99kOp(mSWoka3+_Tu+s zP5;XUdqZty=Pum+7jj;TgGw@*^TJTm(MQX>aBFK611v%1O`lxD^g`6jD*!p+=@QiO zwQ!lS;MxMCq+6W+1D#pWZfZ#v9C`jFVfuw*B>@5Uc47~4+bgfoLkvglzCPJB@TTuP zOlfP^PEoo5ytco%y`7>%WijIEVNU^ctKdHhL@|qZVvf;T744d6avqCUwD)gm zvblVa{!hRBr(gc^H;f;CUhzThKYZ~2t-kl0?f1IpoSJ?6gG<9(ryZ!s`OUpspMToN zevQ21EyR74wepVzcY1cVGg8HeD`i6(B=ymOJPXva<0C4HA_7H1rldr-yPSs8y_lXK zI17&plwQP08E`A_p!Gd>Xfjc*0`-aL=mAb5(36r@j$KLXPKoKp^3vHwFVc*CN>!x6 zQ;^ev1!&McSeer9=y#=Hp27kYgy)BET$qg+4wRl;luW_uQj*!Vk7wf85 zCbQ+(>m;9}uM9|EX`*^T@)lcQvAz;vdYS8m^|7%Vb-7Wc&zCdNpu3EdnsLr zE=AoE(ycb6MnLDpih7}n(}H(V`g709mj32D*Y}{Di_IC*(mDN4>N`s4%Vna{p9RPv zVudgwpF`|o_BGF5=g5KPpt#eI&os7|9%@LXrAtnKY8X7H&Jr8|*ev0;_Phm2zI-r*_Pwh#0oy0TZO^*f7EqA)1bgb!B z3TK={b0c|PcsE+C#B{3zsfFkFPZ86xyl9{XzCdESWqEnoi|JKZ)2AS#TeMEv%j2N9 zOfUM`O4K6W7=m7?9#zPTIXuQ?IbKZt=+nsPf^;LikErQno>Ll%Kb@vAyKiCqMP3)9 zV@U5sO+WkTiCYU%1QF^T*sV8zPH&@z#-Z4u zME+eQ4yC6j#te<`!~`^tHV& z0XD1ouIv7+XC?%?>|1W#jTJ}aa&2t{;;r>nayl|e;DQNmf8k2(Q0}DRSEsx>>D89h z1Pq|14Y?nD0Gn5T+;Ql=*7x26&R2IF{9JnxDE&+vitTxPs3#&Ok#{3CA~ifcja-+G zYW=z7J{oD;(rE4`(H-r*`rukj?7g|Y4Y?JiEvc7Mfpm`P-4v9z{ORH7_aC8YN>5D8 z{^h$ylYGo9Z-D%#mqwnn84LdI>yt{kX+-FE&JfHBw!vOPc%>);nriv3;T=k?CQ`fCKuecR#CeZrS z-K4GH#5%LP@bAd*->tw#L~tZ@j^xfDf}cOVkX_W=0H?2;#P3VORQxe#7VX9b)3}_d ze(C8LZ}8eIp(W|nt9NL?bY2~s*a(^H3u%-@&1&K4_ji-+&f~%F3*VQAehGQ&OhE21 z9pDo6&8YQxe}vrhM;}guj{PX%Bogtfl6PddOzYFi;P8%ba?SjKE~I>f@!Lp?ndJHX z5A*(#__k>{;7Mn8k-^2;qIF?9a4P4=+~CwS zk0)&sbSnMa(z!up!^@JFPnj*4j2EM(TY>4m$n^0T+o#C#!jR`h^`qFf5!1btZo(L0 zYA;-i!u8N*NK^M2S;XB8-ELOl7ViaCHQtvI!;2BrC8?{Ckxn@HP#sFgmTo*R=0w}l zYc)eJSr_@?A{VT*7jwxh(j}v%L*#UlrF2vcMlUIxxgMprI314jJT)+cw&_Cm9X!?>F&K_0!{|^t*A~3>V&*^oV z(;K~iiV$b_gi>)7?xJ}{9(y@>JNa-*Ors-aivG@mK&pf%&x$;1M^S(N?IvjZ`y{E0 z*CU?~X~KF=<);iraJsbeS&XAr-Kkj<*9$2zvaZj<@q(6aDm;<9RdY*mu!DKPWIu#^ z;8~8BVmvQ#fO;HFN2%gm-3CM3lWIIUIUe>n1R`>)`I6T~&g|Dz?)n9lxidCa21N1V z0w^4X(fP*EOH_=`9EN=>E;yZiS2zSD!sR{Hg4-^B9r=3jv1;&dH2Vox_irK9gyC=Qq#N*A9SN*A}UF_aFuBc}uD zkU3Uwub9pi8jVt8Y0>%C88iZ#ftr452ic1A4&X~y?X=k!Fb{*w>}3ZoU%E;AF9OpE zYaAAs(_nPY;(4g)RG&V{b-d|vqUJR#C!}Ve)9fOQQU(7*H7Z_dt z+qjO7&fu2E^kak{?+0ZWTDEOQKR>f}t-6td=SppX&DWCSaZ%=U4CmeBsA`1L(_13g zwMN)t_vVgGn_64%U98^LJAHjAw&jGzFE&)rqKC}y)I?0_JuyA0x#{8S8b53#=|!Z@ zu+((O*}7^i<2LWjUV=A^b@JJV$44%UsD1b1`~muAG4$W-ZHL+pt$uIydu?qW)1MSLH~%3g_4FL* ziKSs{VnZ)&N>gbtl1@w3o`woEb8)&E9Ub>nQwrAO-pBQyn_H1fFbonqlz*Fw(!}uF z4HY*V(l4d93=fa|fAxM~e~z>G!3k5A(2i)ymE{By&ZpR5`uX%FcwQo2RU`7m)P(T) zOZHQrIrTIRimuS(h$>L#cjDy6^$VxsG(k7twrJ|EF>{|;^8S+Ji0RyZb?(D+8|giY zynkp8Ox_BPho!G|t>*iyF!Owytod_1hbk<_O z5BRPOn3(;eM^iz1W>Xuv=UC8V_wQfcc;)z*E5xhA-B<72dH>Fm^PsqFESPVQ<~802 z)-k>;Bz@HCp~{5dJUx+=Y_kOQ9SMK_RSIcQ)5m_-_k7|v7l1yRE{FFvSy~=W|1wM4 zE96IiBppiklP%`!#~)PFAIeq{>Dm!X%hx>V__EPFj@@@l4zmWeRQjf|w3?=>kAHPi z@l9+0F_z1*0+@TF6b0I z8Z9x6jgZ$LmzZv0It**sUVLJ@1bFekv7Z~aineN@v*4S@G6-&+n^SXLQoiqCal1@1 zKB%{d9=%+ex%W(bZjLMzvs<%|DleH}=BqPl@~)sOPRjr~Ozysub2jWE3McOx~1 zx>5Y~Dw(%(3Mm5wNyUZ=e0%cSq|CPu_70yKKDhVC3o3ec>=^o@_w!qu ze$(E*rFhF0Fg?r-rnh<`ot|vyGAg>DxX-m>us9>Cgswm)c7)F~+ZI?!Dx{xZfuo(> zEhMK)O$U}|kp>f(PaF`G&dJi`kgWRF_fXVdbiN^`2B~4j6sMi?$yLqh=Us=1Nx;$A zb$BN!F9j?5I`f!(2p_ZE{V6sm&ar4+M!B0$v1TNYra^_0>twXcQB2PRNpI$um?ka_IK>2EL4jtms_0Sw=>CPyAc zR3}mqP$#tI?a#ALoGB>na8e;-aKa2>6k_nD8D#;Hev zbSD-hTuaXO$pl=6gw!xg(2OA?4ktYY!K?CXLvvcQJ2uyQY>pszeHrSt2R04~1k?Er zlm|8Q>%(_J9++rHZH}ubDcav(NsNJlbkmO3uB%w~^R!Eg87~HY$`^3o$El`-4AqSj zHzw2eBEXi@R?n|6^$qkxWx`EbPC#Tpkn-fqYi#)Rk^7b5pB)yO*|xfj?*f*kNb4<* zH=Tp5v=?6)>4+O$pzdXIOH7yV#k4wt-leO{@IqGlbt9)6CikK_XK3i4`Y+UvRFIBp zE-<&O>ALg|+B#=qbPl3s>FHJ~BVdl2Y$@vKAPHCA^$8t&Mz~e)-ZRj&i0$+cW`K7pPmD{-skH(1 zA-(tP=`){R1eLZ;51%rcvc~Ri_6lJ1$W5z0*s*E%=Zh8=uBWcBF??P62IJ}2tX`X| ze>i<8b$UhV5QG|@zK&3h&&1&t16!wG&R;PkZElB_sVu#}rorzA)pXx&e~UN8ciE7& zME4QT3u!IhZ3x*P;Q7zUTl{e3Mx&%Zuodp32UO=#Hl>6Y%rsX&Yy528!q3wV9z1yW zP}_TWI1dq|s3gUT-1LN&*jHa2H?C*Wa8FN9VoSt0GWsK!&!m>F?IsJRl+LYkn8$|q z9>lT_ofGwdYd=+X0AdSQ-@DYJLUVc_2)d# zet6P`wT0`*OH7~xQN`vn=fjtjl8TrRu`4EKzH$wfaR|jP-@lxMLqRh^=$i{mm#k}C zw*jVJ4&R0w+xYQaQ?Ks7iWpw8d;apd`{%1)DDX{i%)DeM;xg-+h8R;7VV3z7dpPbQYi|E^+>naI(-78qY5xb?D5Q z&AS`-A3q+mem&4n$0G7tAoLUGckROFB0eV{9RTMNIWj!%RO&|;on44UooZLbyWn@3 z-*|^Uq)X<@nocjSU5)=1)5|x-DJn08|8vRIaAI$X$s94BJXGY7WKEc&Furw)E`I&^ z1KxDW>D=+bSoGij#yBTE`ewip`` z9Kx2UPK=2%Uks9-qIxu@;?UZNX?R{}O$q=Tvx!JukgmQ)7TU}0;yrjfkdBt+1%LV^ zMZ8F3o)qiFbRgZ>x3Rp)XEQ;3{e&*F4*(X3$%F97*CT9495j#fsz z1~p)nD}5Y{uGcz_6iU|deKJMSIjt^#cXf`xKWLWX@2PddWsaQIw$@fxfea9R)cZvd z0JuO$zgvx5ZU&wgOtLs#p#dn>#z`LaqwG{iPWJ>QVS7kU4h*#sxK|riOdbWo9r27F zo6F5y057eBNx;F(?CtDM%yg4T``-3Udb?%5cxcO7<(-}G!FHtd z-~2{|ZXg{cy|1s28r!g}Eaw}O2L`rmDHu$PI5qsi-uO2b+#L7V_?|CLf4(Va%a-;P zTl%CuyXz0NWoD5gSd)$KNLey{TTG-3osID6gesfcMqT7&>K9WOm8Ab{G%b$c#66#**S$0G-el0tlm%Nn{tMTbv%h@gZb-DeCbX>03d1`%)f* zd-yqm9DW$LXsM*g6TYxS)zb}$c%V9cOhL42!hY>)4{X82nV4(Nw7OD)OlH+CA?gJ^CS^2&%X28eZz}*UEPgLk0X@ycb)~wVR4Jg1>_iB z%<(#lIK1=DJKU;BMG5MVI+VV31~3k(qmlP4mRSV9i5>1%HP;`V{3o?1*z z27~g@dCRU}T66pMvro~UvqOH;A_Ha32-(A(m^H*K?VUK2l9IFy=R zm|GeyojC2_=35IN@TOb%3_1HiS^~R>+l$Lwd=RUNS-Ec(XBFRV4_wq1Mc?;t^KBjI z*LvP9n@6_1>Gw_SBadr6uMaGbicjyqp`L?wc6%Fa( ziF6K`f>(Xgq*wLNFn0Eo;o(Hotl^%amed9aJUus@oW}6(bU-~FJ3nDAO2LtEu2CVI zdbc8Bpz-eR)JutpJw2)HvuFuERh39+x>mwpMCseSRsZyAI>Xd~Ey2moL9c4YGn7*RH4MY)s6$_2~dQmlBqbIgWD% zKg;>u>q%cf4?EMwl!9dg+-E*Gza$}iDrR+@Ea#_^wtjxmiA|eNv*h&dZFe`*Q)$V< z6N{#vCn6o&%f+2%<|CsQE}Vb05aWvi&X+V!-L|%H`jY*}NuybGx2?W@=c0tsVEQ`R zEbS+n9j^<1miNz-^+Fk}vfd$e8ZNCnZ(tqhKdnMi6E(At9!sRioQC9S+jNK7!u46hVI*&xMqO*xh`jX;tNk$-&sF5Pv~R=M7IQ<+ zVp2dA)DE5!5i*$TBS@-|BVU+~-9>&EDufKB z^Jd(~^o`lA^`x`4p`Mq)JAtlZQoZS2sfu^E1Bi3L+Mof%1D`7fL<466<$HL5UD&ko z$XYi8@17chv-AD({p{#{@O3STZ=wFqoNRxW!%^RXKu>_9^F=a3+?hc7pu6MV;E^K~ z%aa&_-nii7-x2ll?rWdF_u@ZNw|Vx);Vpe=%tWiWf{N?9WSqDGo)dhiareUAGmFx? ze|zn%Yll8Q^xlG3_L8}Xq;4qvdo&>Z)hp1trKTH9*NK?@?Y(=QlV`moOux{zii%c0 z2#D8-{+Z_{`T`4n*D)#SjGP?n;ix9<+twmg)2%7-IZClwyYg%HhIoA;8`bebUX zM%k!F40ZTfwg{`0JY0z51?D0SoG@&FI8U{=Fr;Ktdkv6YOwu6lD>2`y0 zo^+N@n%+at_uVeUyI4v(lul`8Ee!AR_!HgT-oB#1)sZ-UN5hM6#LvpS*|T+Y%on}Y zpAPoz1LyH_)3`Dx(@j$x%nq(W?WSNRltF`4YFb0e6LwO{JDX)BGt*TG?EOqyAji&I_B`T6flU-B4)G zz7_p_PRKY@x2rW)e$5rYZCE82-eIff%GV6yI;GXgV&|q8k#Ca z9)12LDE;W$Sy@>M-Z4Izx9zhc-=6ixSauF@#3W;I9#A)9RaRN(^JeM=rZYbXv1QTg z6HZ6dj~rm`!@G(--ql{YG1@;aDZiwwETnaHHjTyWJNQk*W6sx$&sU!Dz!1DBB|)Jy z$|^3Qz%z`}&ioWljw>lC8ppXNAO1~BXVDi1*9%sB8x}2g7~sdZ>2*h^Bx&-3p04c% zF~M|ivL)H;H??`V9$kdJDmsvR<9w%B0u^0lBKm@}=OMbto>kWNUVU3;h<6uiyeY?& z^97nUa=Ovdy`T<@OFx&%MR=~kRo}JeB&8d>%bU->qbgD}{*x>(MoHHhb{Fg{hQf`4 zZhDZ)mVVjG=kFLuhtmbk;&eKZK1IzZS?NZkUJR!ru9NkG-(?4GZb)68mwB^q-n@B< zKBTl5t+Jl}vdgzGzlP)GDQZz?F2gLd?B-33>2x0DXh0pBM>n5Mv8nOB7&%>%`n)Oy zz08>%ehIK&w&N6@7Zr{^23@=7Xhrj2drDJs&9v%*+ zjF;y}001BWNkla^1)~s!xGcI+q3?= z#!F3SkVgWb6RAkG=*_g=MQd+~*2zaF9i2dQv}5u457W|aV(&=Bat(>ECDwoUgs zHm9*NSudo$(1^2obKw`$3wysH27GN=1<~MFtUyK!gw3hU;XdHj0)aF?a-MMZ09Jp= z%<>@Ye|a^wB~G{0bV>K0F$pj}mM^cT2W3T{H=X20!{t1z?)>3jUHREZP0Jzf%T&dmm7@t?*-^rXg4N~B0OCU#u#l;J7ElVV#qMDU+7wHrAcRa|dW zT17)DyB*{$@BW}6HoRphyn8yGp(w?bj&2<6;obBaWzvNLRyDfnR8?$lMS4q2Pi#aB zo|o?1i0N#O&)|=VLEm*-?kAoYA0rm0B6L^dy7}v;uAiR})3~m1eeC{(^;p%{EkWHz z@4oU3!H4S>Qp>P@ePM6Bj6V`37Pl*TOIzaK8A3n{?7JDiTAjk}g#X{1*u z3OTAc7|t>ZId@Zj3ODaMe)Y_ziwZ73z3|MLZD-_4A!KGDHu0%b8>e2pxNs_VnB7Wn zhpts;N(B3f&D*BOjGi`r7s7jeb930DgyYAb8MA*0EmL<*r7ZOBiT6+c-BiLMPn>w4 ztrk+Kdiw}Gy{^)omo)>+KXXXzDoSRQpfiaUZzvV+-n)}G3k847p zkxbg++>URg@c1&yS)Y)l{?9jr=|&M3pWoT7mLSr zn-qAniUE9UfkA!Yx;7{<_x(WW20r8{bTFM63Cqn(dPKUi zYijKj3`VtfASkx3&Z(jBusRb$&l%j_+R^&fTh-MR+rL%c_WG=Azd%o)dElMfH`ks) zO+O5#cOK5`>a0aW@1z^Ug?|;F{~V?LEJ`?>e)euc>OIWtnTLM(@d9iwhQxIOo#Rmd z)%UJRLI>Zy!xWHyZ*NxUz~nAPGLo}MZ5>){t-G(Yw$DZ4&34cBS`T`C*D*bA-{7%h z$mH;M*WoQda684Fv~40rgcsc`yRR(Ieoj|ymk-l%!4Pjwf{Vd9uZP*X>;UBGEr|*n zV#}l25TO?<1P1XyxtYnZv<1o6E|x;wm3_UKi%~xzkHnMZtsDI%Ripo8ApMh1j%>%! z?NLKb+KYC>K+L`=LE5vvltGmKT@45&y=E6~m9s?fIhj9*oY=6d(u*zXq!YNi;l0 zt!vAQ6)WKM5->fKpl!knvuo(rV|Uso`?a_G7ZhZ~`9K{)UTV)~*M`f#vIql8a$r89 zchRhx7c&ptd+**oI>4f{C#n5u{wj8O;7mtMzqoT>-C<#R-(eN2)|FGXTa)FVozq8r zpu3h9s8L`kQ6{_>K~ZSw{&v4g)7Vtr7R?m`9kwV(N}SRxX`Yp&+i=0-SZC%yXDYp` zrks})@C-N|(+eJ==717vf_aZA*Oijap!U=;;P9jKYGnb9eO86wH-G8*(9o=`a=yjt zlv^7`Rj57G)XAFpz^v!#dSsfIKL7gjuLtIr9}Dq|Jc=AY*)f^tjEjhgnm=!AjgwwS z$m!(e2Ua?w+MSj1;@Da@=d|V2WUqDy<#f7Tai$=F9VK*-V!}oYzDY?cA-10OQue@* zz~lgryK*BrITVtDRUXtEGrt~+7VFc9QRNo@hbQJaf#Hmry#pou4Q8Kw4F5tRxxro}= zsH9X2If&CQbAQ9>m*I4E4+XN9Rqa4i-&zHy8*};u3GAny+=?@O#*8^=={H|fGz^%I zJk8Uex9q@csvf1~(o@T-p6VH%x$O4MOS283vzlO?-bS=L>QPjCgy@_>BIBAh5ws?i zHGPdy(}#D=parSV>0+JB?4qbf950uNd3ns6^df`0!St73Hk57{`{}LxMV2!iL0xB< zUdXMX;V9LjkL?()VpqT^SzcaXZA*U_nJa@)f{$5djOo_KMv`87kXKE)O&DK z8r_h(3%iFdwM>dp!roVC84~wdR(vq+)4Xx1JP7axzkLfH*veN{Gitg;-~aqqe-EhN zA}+=pxUcW-&^TiG2+zair;*H0(_rbdB~(D3J$sADc=_$IPuwC>o1Uu;8`9}1aq=pcmuSbK|_ufCNnLuxw$PwqkoWlAh)3wjxl_UQ@Dy@hP@Ttl#b@2sFS5~8=0Mz!&_R0eE(nnoadg$=RQ28 zkg#;oa}2mXb=`X9y!38c5|glQ{q*zm3*SF+k>t+#q_@N%te@Goa6@`}YQpm6qhptp zHpVQOUbsHSxWp9+Gk^Y>%~PKl(>QfqW6YIx7+jFCv8eyul3mdLrnW_LpUnT8E4!`$ z)@Rr*k^S3nsH4{xLg)!fkZD}EZQ;7pn<*)!-4WR`cZivxcy;PpgnlYkUl=|AMBC2h zRh~slc3n}B`nq*`*!k~ox^d!tY32(FL#NwP<1_548hy3!3|AK}L_MERr=zL!&n#Ma z9^oFb9fcmv9zp%g3HjvbHx@3+&;PD({kH@%qLGiw(LbBaSPRS_6wMzA-pr2Ohdklm zn8x@Wl3sX{fr)_i2KzTY-HAm9A11inOXiW&VRqH6e*K7?&J#_j`T86GL`x~Nfu=RY z>AnGyJ~3hL7&$uBeCXkaC#d(R&+%e>FJfCPFXD19-W$m04uWq~^eJOVTt`gT5T`RN zuZs*XMoZU<>TG0GZ_NQLwO$fATes5EN5pf<>FlF4%e_xzWOXi>%Q^wt*_4Kn(S4wP zUriq|rt5Y~ke8TlY%cIPOm1MEi#qqYUJR#$>b#`K^)jTR8%Fn0x?Z0kotGv~hv0pm zSaOlg?a68L_!VJo4Yd(;VyhjDqUj7_AUU>v|Mrw9WMHd(b5?1MI^KQ%YRl(G zj=cEddmrEXM`5~UPd8AmT2h~y4yYTIT{WcN+xvD?2&VJe>1vNcJK5=o+5q5o!X+MM=RSq$*ofeH=dYu+jbs<;b8fuPA=~ z*guwe`YV;dC`i}9lK#mjgMFQy_%$SfhlYAO^D^S%GDtOXY;PDpZBk}Dm_GTf?kP`? zUjD_V!7atSzA!2nYp5eMs&6Q1kT5N!rFo=C78i%oUzP1-)zn0$B*WYx{fmu5ozlNJPhTf&yHGrBk=e=u;O_qR>HFmxp-@neeI}m6#5K!@_p<%mCp8 zq|-YnE;>5jFA&>0x3b2>cs$uu<~sPgss4dEji!)vK;kPILYk#0o!7}83qM-TQrkMf zhm}%US&)%YK#6Ba`O%}V^OD0T`V1@9?u@uu#KAm(>G`j5qet`o!=m%4 z8;z7I?}zsb72f6`@)38sT9UHQ#2ye>RLQ)J2p@M@82K(8_3oN7SAJ!ZgSi)zS6-(l zlv)MkbSAUpCIh=fLQp;_TQQ}^`7-J= zik3#(_3*rpXynmBt!=K#C>x2FDH|QUl@8rAB*b7k+442DF8yk=M(B)y0z2(bo;O6Ki;V4{7PLydbFKKi_jwi2j->Bh>{i zUdGxYD1UY~-gIyrtBYwuDmZ^fq|Op~UM}z1v*)q_^%i7qN$L#xk8a&TSbEjW;i_Pi zbQI`QkUGJP9Coa^dGq!=RF6XNW)P8n;P%OrCy7gciY5X*1jNj~ee?Eg`CY28o-YH` zX+ig3OIUogjGXNY&v8HGRU|$4*h!dTK}2lf48CyGM z7f^n4n$+}dX$wnB*LL)7_@cM)^Ylbm6)wB-pbic!OE0&u+(0@87%!W1)u6c7WNzh_ zk6h7hKC8?F#Lo5rbm-fM<2pBp{?EVuHS4qL$gsTbcf{@hI=cBnf^0D{F*#KzygU3xor`lay1mX@BFq141+I#R*q`gweK+;Ddb&|lguhfBpx3^3`b;kioE ziETkj2iP0JV}~E8{qp^v{WF|Ttf4Lw8#!*2_4Aj^FFc=qzO*rR`SS3EbRcaEpO3bV z9qKMXefsM0xx20;teei)gdHbC`ybz*z_%r#G&gsBDoqg+V&<<)prz1;Gwb({iCMBP zVOJwyY29V&@VI>E*w8`oO*Bbbw5{;`hIP{y&Ly09 z@pR$TE6a~xl{01S)P()V$BfyJtz}c^s?J4A5*izikKYg3gZ}5=ztKt3+FiPvo<6hr z#F_KUNrET15xIWRqKg;nFP=F)72sF=j2tn|8~?3p zIJ497>koR*qfDM6dVu8m#9r z&To2EOFP)sn2vAu#C+2o|5uiiMC)Vo2RL0tq|%LzbsSz5_sabZB@34=4ca88`zYNo zy7=5n=~Koji*fW6!|1|S>mWquXo>0Ehop7`)Y?8=E>btZ%p;md(&OopMdVtfRp5HF zRLi;5EYrDeGLSAg-4fD)a$ORen}`>4!ScIss#j%(LGlrE`h8X($$F8Rj%lBH34b6Y zqicS`(JQ4}h;HI*45jO4-^Y?1g z4hWHxu0b0_IX^HMsK69L!kwOsi#R?x5DP3CVUFA1>CSB1+~IN9-EAGUE>FkiLx(bR zewgXZb{|^pc5TnRM`dZw_U+qS?;dN$IdSi|@}$oE;LOk8N9sP@MTap0R4%mP4+qOR zn0Q2q>KbQ%ekM2V+P#kVvW^V=n95Mgn!dnd@>gDYh4NA(vHSFNqo(iuUP#=)KxNm@ z0rd-aYgfgk5aNx&r#-5&-AU0Nedj|Wks$FJ*d30La;fPzK00<7n|?d8IR$*+wK%;z zk9cof+yjmQ|7Hu*JG-#F>hCLi<*%$Z*85E5iew6KaV&znD5lf@1VX7KcqcJ`SFv zL#A{8s0^amqgT?9GbA#3=~9%8i2!E2CWR>uefMPPP-G}O2|C#?L3#=W046S+aPkml zNKRyT`+%dMpq=JWTgY{f1HRdZz=R3-EmnHGDhil<$aQbVSY^Y&>GT|pJQ@;E8RuV6 z83*)pnCze5qG-66Y=24(?8jrt(i!DeSJsuYP&sBW^sS^R?)7Pm?WNw z%qXEeONv|x93|q0uN~hGza+(?ZsbAuBwS8ody!d6jh&bt<{_xl5!gRYDUA5^m4IoN zK8~2qZ!4a3S5Q*Q#uOJ0sLB*dYn2fb5*mr?rN*EAW!78fpd(Bg{I0eP!dFdtwW*H*-GO`+nmB*-I+8eFG^#Y^|)?@jhc61r1 z^QzFwTMo=-^S-V|UP&FN3y5yK>9i`90uE#wM1Mi8N4IW$`Q@iyw(Kg#wF0Iq>;DjomW@)t|i=M(Kd;~ zKkT4u(dXMLayP6;l%yd~czSolP>-}4cHlNt^=|vqkkr}^;TtRipSqGbIe7KyB zMjt8_d|~Mo+J%G*y_u9dgN|t(fYU~i* zk0NB~4{nJ)6+GM%lZwM-c*;1EV6-m+4sXbX?M+)(uC2Y0I!#VxRH(=l&S6a9}AwB)4!1|KuOO}t`AKMs%Hyz2EdtyLg1~7H% z^yyRAPo0XUjsIl+d~|!1?S;EHFWNxM(({Et_mbty8`nvbzY;^V3(b&vuPjIBzH(e2 z&(x_4=O-*DSLXCW3^1J~H+FN6gyW<4H?Esb=HlrShmX+^?*tu^C>cdN-*tTXd_;B9 z8_(>fPu|WG^isXD>nhczN@ax23o)iInYs{sXVZ)5d3146K+<=9>kp0o5?O!c$|LDD zY$-l_ZR&%o%}uN*1BT=6y<@(z{+F(P2X8t)mRuC@7^(JOKPHj}Gs+kB;*NOqk%qvp zU-6;%GGbt!$o*zz{u}Q1zqVNHX@U9!ln!j;XBmxaMJ{zq+a5K_K(S$I$W}HGN$`lt z@_mTUxiVT^jdTRWwZKHCTafPM^C>X8H;d7T>1-XkRtqC*`~02slC!0zo9j9eQ0pdK z=&-r)oNLz6x-v>P>XuR3o+YMR=f?X2pL4|dV$Q|z+{kKd!n{JAXxwLY%k0AIG%+xm zxXd-X4{!nTf-wUb(Og|erKEd>^v6wSRYURK4`yPKd$qg9olP@(x}M-755uk8*EhJO zF9$n{yTCa}w;!772*)2#(?#U+5yR=o>?Zpps7{=&{qpvFBJ+xp?GT79XVdB+&!N?s zIjb{W4p$DnByy-XR^drCe$u;l-8Xwz;wMaNWK^ z90NhwHI(~d95*f5=@=vX!$72?x$7siE4{H3n|KWhcR7)Q*kSGq>Rf`-RniwJV>)JN zPp1bNSE(jU2hdJk{z|{Zz=9Yb3U)bNV7fq^C>NEDqNJN_mtVg1o9&4#U;^&MWZYGp}WiL!#)*>RDx zub^NhE){%4SaD?9#+okVbkI?WV$>9=!8q3oR>;ywRn~#*$5|}UT#J-+M`Z!cpft$iaYXV+;%qro;Qu( zMV!7zp^WJ1DCk&NWK%zR$(YhfOXmi~yii8UWn*=bsxF}&Ru`)8xlEu6r`Xmdudlg$ z;PPe6FD(a#vAt~FD$@&@ii(ZI+hST9%~|u>&D&(W%wz>tnK2E^%R47ezJ|Vz@f^ns zDUOTx9K6|L*nAm9qsF0*n$BTa59=snodc-eLWufs)iTU4G&iDvv}Jh5DN0En9H{9q zI!d}o{lFZ-vo!?i7+|O#^$OnxyTN#hNM&|W)(hv4n?|H_w@xESvT7K8f7y?0%+O*ZJ9S5s7S67omf@vdn`WLWyc=$RI z>FH>@1ewfE#ixzcy7zO^PO!9BpekcU@1;w;Kz&{8)NN^-KJU%VMH)_xNlZ+Pg?oW# zpAK$7`hHocuIe@~r9XJl+$2o*4lo@n3&SV6`)<(rSJZT&Ig38TgS3X?w*@suq=aJhPENM(2u?1&KdTL8z zD#?jAf%6I~NvZwhfN);QjTDMvM5pO$#Bfh)LupITm{Y+m5o0cq1~VMnGCZkgTw-cs zOKPdAMrAnX?iJiA9CjZX?&)Fb1Ep6Pz`#*zsp;LR*x$$X{I7w}zw6!;{nw`_JTp3B z{q915ykgPr_46b4Crn*W*vs_k>*ueNR1K!n7wCNBGcSPYOEzpsPaV24v^*lBbbWY2 zcquzzcxf9B_NEd%zH1kZPgN=Yn1n0%U8YhhO2q@-_YKphPF>HQ3&jCZzR6taH0(_S zq7#eO?|OW>@)eDm&K#<7$*%omzBEofvvB$7B@0jQKYr!TX#yb6H^%HbzJKA)HsHUr ztF7=V*)-1_U!E|(aQB(_&s;dR^TgdnJk3U8TgXjsyfR;IorSc?gUJ`|+(dx;{{0x{ z&z#tO9&-$eI=Vhm`{{M-cqY5aj-39-NqP};Kay@dCQGxbHzWolRzEr|I3hjGZT@K1 z3;o|{v=C5&uPfs z)_|@J4VSw%9t@AE41 zwAGXCfi0FgJYt+}wVvYk!4(8>v~Ft4NogN++XiXWVsPB&O$Rg}ax5*tdz4%+%6joH z31X=o>Im{f;(Msb;i@UN^|f_)vfHZNff#g^lTB2!d(h@~Z%2A0J>BW_ker=YTsH`J zy0C+XW%nOhu;9HP-dyt!@BjRLbaMpse*xE_X@w$wbmN#z<9P~tImQ8d`GxnZGq=B3 zUw`PmxA3MP*}K3BUNq{tTrc0dCcnChOU?Mf|Bti1NAl|WKS@#4%l|lgqj}XzIh-*p z7vRcoPf=jUWFk{^Od)hHB%s`=>0PuNB_Z9G?ZPaA7#>QNUTA1jjP`}{001BWNklG5sjJ=)o^cu!f^`OaZT8R zf*h6YKq3}pbusEHS9nN!|DYKC6Hz*hZaNvs?()eeP8WXkuAh`Qm$bA@rPmSWfWlo1qi&3<3 zr)R{ib%JzbHq0bTr9^f_aiK_wfm6FvDTjPY6wvSPe~`pvd^56bLs&psw8% z7>78ku`zqWG)^udf^rr?Do)JflOxH9acC#PiWPO9^6~(cm|`u;K-DLY99j+tVJ888 z8V>QZXv({E7G=LAYX%-IsLUA5FqFI-R_sd{)LbLd(GtRjzj%T zt(nfUj*ie-L|8`Fu(yUF8}XYbI_P{k#gNSr8kQn>nDgIw{GzsR?b6vqp$7o(>uJzb2>Ft!(|>LZl?Kk;v? zsgWh6zqtoWH*z|V4yD89d*1mA=$x8SiRtgYgQ|^Cjf{?>{wzNVT@-{H6o=9;U-wb^ zo0m?)=zA`)%%D1_hKLXJK;}f9i_@#NQYpIiNz;UM#~d6lREo}=2d3|sMt9O3bEKv3 zdF`F2z;ygAv#XXZK5+0ym*h*w<377*8EQJ4nNtPy)27tWIYK(5u4G2Ec0Jb}%7tNa zFk{D>`_6QEU1UkusiE{?3#w^03PGc&Q#vY2*V4yEJw3|E;ZJXc(Ur*PRnvv+qot-# zo3R6ZA7y`rlyoz!JHYqC^a;XutT2zAvTm1M{b}!?Z4}|OgR65^ryazk-dnK&*c?h7 zA`(!UBn!`ex@jTtFKgF^H>^$V=|LdA-OwVT7Yy%S|HTGH2&y&`WqqNEhWTRod@Sy1 z9o2*qR%}R&ZHbt&Jm!kB&wU&&rpEE2q{NZ&fHwZXMQ*lANUc@>`EP&y*{^T?+A_62 z0QRi**&WgR-*_uQt-?^Wb9^ngPTx9v>jYsfpQ<2~q<83iI)?McD~S9E=3qD{Mm#rn zF!#Ol*^(=tUA^)d!fzu2`%rjkH^=nUSRCfv7{_l~kuB)v7}Zl-!eb+3H4m;Dvt#_| z9phsgx>IB6*g7dOb~ruvgNAe{U$vmQ;X^Iv{UZ5gC;~rv`0$u9TgUJbjvi`A%T4VG z9uqt~x@sJq%mH}B_J-70;vHjs|6l*S=i0%jA2bdfzdCTpX_2wYnM)5n#7D-YW8}eE?z=%dNGFb^SDkkQ<`!<%pKr6sdr_-d_wn7= zd(J{Vp1GMtzCo3e^(5Hi%XYjEZEZno|DhrB{njxmX0>sg6h*oZRWn!Hd?<%@erz^A zC;bml`gc;(A6nW$L(^%!-x!9Tymr*1Q!>p9OHO;@(J`$fZ||31TWABa{FIJww$FTd z^*`1%@Kf~Z^S)@>%8NHG?SgpRD0#}i|lyt9}E;(J`t}~Ox$SvN+ zM)IV4Aswa_+RD0(m~N%K@EA|S)l2~_EgV@~m(5Zx8}`-;URR9f3l_TTE;8b9uA`zD z4R#xue8lx4$s8mH&ei8=L{0Y^UyLYkN=`Q|Pqa%OF|{DNGI|TT>*}2L6x$#Yuc;xG zn(iIqby&RwJFHI0KEVJ&wz}bX8ulb9W!n#6xBI(0GF_R~Djm&q+oQt<``oT5yHk&a zPZ)Ot6>W6d^j{Ix?!p9Ko|i|LqXi4DeSG=S2k%oSN-I*Mpu@ixe)7>rAC+U7aJdGH zU0Ymuz)60&aQFR9+XtGmj{W0{3-%s)+iQ9O#liJoy#l8L>I?!Iy*-X}?MM?*fP-B| zP5=3gyr`0tRz^N_(k$g?#yo+b!g zyxoN7gdY#7Bfzc`jg{cR_2d=W7e;JaP9y8zyJCNuPk`6tTv#ew!HahXvp(cwdKHD zZ@qPopUhTV9&H!(F7V+%>8*VwT{~}dtva`l+!qvkT-bTh1uF)5;_Y;5Dn>1*^wGtB zg}jgg}(_nEi-#$cha%zZ+!3VED@?`Z-O!ni0 z(_RH~CP_)unf4k;LJv8rtjU_JEGA$aqy3^+65&qAC`yyV$RE$sZUib%ZFC1k509kE zch=a69LA0X()oXoJPZ8B2*qTIoej+BB=S1~<8VMpO2_hI3w8RZkVNW-cg2q9ySg{#T){t%+X-6YCNe7)?YcgEHB%8z*8;C!8jX zK47GU@?8of`~|MY9fUpKwPC zTPbw)49dVhC=4K z@=>8WIWBwfq|2U8w2MJ?nu_9g0m`jZbV=$)Pq!3xV@Q`z{krg+O^M9md^laGZpHx| zC=$`P?hsp>JVh!>X+8?2-~Pp=XJ^h_ytryHRi&C@%$tob9ZFyJ)a+$w>{YX0e(Hxm z>c)=_q*o0yw=kX;*00(+qNcBb(nabpyRoJZ?`T0yC-3F4Dq4_Q1Fs7Uy@bxwLT$%Z z?i(a3GSpNQL6#&RI31^pS4|&AO(!~CoNl#cs#-QjVKKV<1l@xl0sbg90-@u1 z@!~or^#|1Sj@9qA9y++TfwncoxAc&8p4yX|N|z$c9S2V@+<9W*86seMbJKp<&_Id_ z#|9|1yIVGOqD>H)yK{Rhz9`H^P+z-kLqciA=55=0t5@IrBDJDBCXq1T<;$-eM-hJz z)1hw~9^D_@=DXQkL<#qrRwRiNUT#)}){V&>$NAsi`jY9zvYe|GkvuNgj888*i`Ai{ zZBy$edM(`Bw0U#y>8YO~#>PhU$aWGlBs~AD(L(d7pMCbX96nPqDbW7eXX>eW>(+@| zw?04pMdMHmzI=8qw4_on+Cr^oDb$Wloib3ym>uIR_PcED|Jm!rw|#SNx)C7NvcLZ0v*)sv@oOW$(?k9dR}y|&f;y}&(6)x?+e%Lt zFN4oOuwdN_(2|!eAzhr#U5uP=?h2-letcZ8jOhvzH&VJ{7&Q#q`bZW^M@$E^h2U21 zB9|a-ufh#G^Prj_7%I2e{o$v%F7P%_gj>xzT-9cD!kGYFJZ{$Gg0}@Jmkh64kuTQG z*2c}G07w^`YXSn4n;*{10&bC%u6Ihi2pHB2v0jv3mvYm!5Zk)hQJ^`> zh#Y8`{wRIL{;odT%7T^A^d0YLZ6($XZW`=UZ%1QD_ksEYypFQ~;ZoEL@7m;g35qV# z_nC4@h^4i9yQgDy7(FICT@Jz~`98^e*+I@3qxushN>a zG#8A6<9J>mbzSs9y5&vZ>+J8(KHT+@$$D}3hpwW7BSflW|3JH+lQA&RKY*5v=_I3= zoD$seH*Or;*;N}>cC73eYVG#y>?ZoAQg2z)R1?~iC6d4Jb3py0uI6TJ3NG!#qKa~U#P#*<_Ia1K}olZYzTGiaD+$Iw$IQh`v%IwXMF@6Ijz)=9f>`)`?@W zItAf5DYj+s`uJ{yHJO>9vSDzkOGHQXCd!4`7EPw|$8Jp8n3NQV#y@Dw5Lx4i;V}z% z;3$V56BA)NYmkwHEeK3ksR6IqX?J>D6oKSWo}J@Q@hzq;O%@&OC8Jd<&C67J5JnSV z=DL~yPzVs3T;%)1PO~5={bkFYjv>Q4ENA+CuM1*2O-D`7(aV^?f%KDmOzkL%i_coI zj9|7H{WW-7aBj48OH7xj?v>JYCR;j)ZXjL7qm1i&C(d??NQv0 zcYUjhM^V#<@uvgn3VVUm@$8`dFB_h-6+ZXcU99ct&bm8yp1?u;E<}I8n|^R@ZhC5B zVnkwiI*#JR)ZX6iNi-+wP5XT9&EB(TK3#O0*v0CD2dha}OuN*Qo_jM~#*c=o(LE8= z3HIKcj=YTUj`uMn^Sau?$gXulP zvEikuJ*Q4>l?-nF2L_LeO`jCe6FVFmE1FNo>eJGo?xMN$f(jRHN5o!2V;?hq!UP2N z)Wj*H1?uqlr0{XU6p{{4>1kM7fdEg63_mfkEitL4g7kJnYR~Yb;c>qIum5rWfBZY} z2i0^id_qihs0Hf2mlJPaT`C96w~z0prau&)mHvdvNPW9CeGlS2pXiQ#^x<3?(&KAl z9v$@!sW7IP^@-fjuiW`hf0eivVLC!FQnAmaE`=OJiUDQOucU5Mn`y9E+|C^=ql-?( zq?QaX(4R{dBbFC(Vw5Bwjf=P zthIGCOT_6MtOeXzq^>mt>BjW}n(ML(NcCe~u`cRfDl0XRE-76!&VB+xx`tO*AGyw( zbV}JZ;P?ooYx-e&JC%X@|ZZB)~fFJZNwMA8GpFfSu zk<*=Q!A^o)SZK3^VPyQ`y1H}C$I6erJ+R>2nafJ=*6-|u@1XOpmtJZPE9XjiIjVh> zGpZljCrEu?&fN&HCv6PeR5 zxVHxd#03O6vqk0ou(8wCl-=aQlaoCtpsCI4I(*F1(|2~3ccP|4+S%EIN1B?NvYZ5w z2f;gGG%LMu;s4_22AEDPHv1B!a|+S}En3Is0H)K?CNxC-Wr#yGl+67xaLfYWfqvyG z($&>gSC`SwL-(uUsB&GD?xJXyqJgHS8md=|F)rg#j#|O9DO>K5r>!Cx4Ri0@2t>)+FlXG8di-Xe*rE^k8Og;E4 zIbDOj2?F($l`GEeI~Tq5$A2wK|IvT`-YZ$2ot?E9SY9fBDeLt}Bib*Od7`MYV4s{W zcW>O?w5jdlT`Vts1uOCP@7#F|POpd+C0s}2Yoxfr6bVWs=Mo-V? zM(+rfnvR%`ecwhQ0do4=_K-LSCj368md)&n$S8Kf>A2OY9}Nt|fgTyc^ecqIQKao; zrVKn8Ts2rF3M>NfARk@0<#u3OK8N%L^J@q)!-ECzxnXRFLS)Tl& zq@`mwF3k^A=BFxlWy>K?XF!-vM^vS+bAdKSvZ<>k81T;z96K?|uQn&AmV4nj$0UQT zJh~vTAUdUh1{?H*#q*M%5*Vef!GL;5DCtBb_^|s*@r~MPl9Nr^r8AJJj-O&9Ydy75 z*!Ov|*&aQJB4nbXob0q=^-SxpK|CFUA$`xA?>zh5^*v-UzDXG4p1;8Ga#GyB22tE_I;=h$j5h}<>pstmN=K!f!{nE) z?=g5TPRFs%*$AdzUNd`{S`sNn5kY;2en?`xeG*Dv{3NRR;yLscC7kin$&)uv5*0=1 zsK&fGH?Q4XLvH$k*)wHUH`aO+$T(-~V(LjrWRx?V0#XF^*#O2sIlpU$QPWY;hfM`3 zo|jm!n2yOs2`_4Dw8l7IaHj8oq>;fbA>D8^UKIw5M~SgT+gygzdw_G9UW`4R%XlUT zey4vb^9Y|e9T>NUf%H*m>f9Gff5NmjGO#{kdXdD7yLtnG-f7jniKS_4!$|ayhy_t0$m!0hKH+KBA`*)*u$Qw!99tI-5a{`WmEr1A>{Pjn`>`&4`JG7Z6aeZ zy%1GWinN?SCWj@5i_p!$@$vw*|MRc^_Sb*KQRAO+v-s3=t{RzK*LBdj%0mHn9iVxV z&N00F?dhMLxOMTqd5N*S2+)^E zem_fh<;{z3Em}Bz9rcdmdU~ex9DjVu{-N&hp`KwFJl%NAd&Z2f!uQi+yeJ6W8l<>% zljoAlBnCLgxZXf7(&3(}svQw6V`O?s-!Yte3SQVTCU{I$EJAzFIButHQA_$z1m&cO zl%-bCsTAAHl*bX|WAU)(ri<@sLOMKpIN109^*_%4kADaLK+=oF;g5``ljaBk$46%N zCXT^j@(0Iv@uu?*#h0ay`W8;NZ+PU<#2T1N;gNF>F8#Xq)Sf#RhkL1VY5vT^Dh35X zH7rbryNP(Q3@-v_3)F?nf@9(FglYVK8Be-paxtfnDQwCqiRlv9gQ=`EYP!$z;)PqU zEku@=X;#dm_}U2LqVlf{OD-3zi|835aq~2|YzW9%q>2K zw`krxp3FU9x_8{KBEDYxxxnQM zh)uutJzOtGezn(#>4w#HY46^F_JQ`Ub0#_cUovyt%^`ICac@7;-!!=0-IrYhp}U+M z(5GGOOUUcQUL!pnH$0hzK_PJg?I3K*z~spGf_C&uN-c%y{{p3xu>MlBQdBT7ppn{z z=`z0Hd*K?ThEO^}F9CXX`qhx`5)|c6`$>Dd6ViJ9C$FQa+mM;JoTD%o&0h(O|Bb>? zG5RN;plv&|v$Am^iTI+Bp7YoTQBKpF073hpdk`OmW1uNJJF|Dk*5HaJQTiL(8>+_l z9Bgvd)a1NKWpG>l(N+0SdQx(95NdD$h`&OhevThhdU>xa3o84;^nO7)m|k#h%i%i5 z8*dm)|Ih#Vdq0lM>g=pLN95v5FTIYFWHR}P%1W;!iRD~z=T5}*`ua_GiDPK1Ct+q4 z8R}iU+dGeuX&JXFpqbUkc-gW7VH{~Zs@-Is1L+hytbja20~Iw$+9U6@@H#rkRl6bs zHC;0Q3bJ4f=!W`BOn0D_2ha=&n-xRtkPzXWS)Q6~WOP|zIN@7}MSVyb6B*Y849^mKPepFHlff+oq13V%-Uc3L8#|!W)xPsqJAYomdnNq=VnwZs$!1 zCG4JkG+1xg$zZpax&1t=iBI3NF(5M)sD*Y zvL<%fj%8r_j02a3$d}nMgTR;j!w2e@FRxJyOx1+1s_A&tA!{u~43~99mnb5YJw2HC zMbWxBpr*s=Gj>qkN+VJqpR+D^eBdBTm-)q~rjKAcHI0fcNfV}HKToF<=JbZ?4HX9u z9qOpQb>S8U5~9^B!V?q6O&Nw+TN=Rc+uf;ntvTW(WQx_dX2 zE=;G5W%~34OfN=Ff3SoUz<%KBumAq<{}xjJ^{@XKC(Pe}Nq4ur>0TM#@|+9NQNE>p zQxp2L6LcnSWjfzhy{VdHzx70dfak=3AfFqV{6m2_W9k>{Ft8+|i>pylqKXku@4iL< zN&4rU{(>w)+%OSf@$fUGt?&+0*f~V5V$ZUwmT};AZugks*x}*F@#lluI8&$_1&K`328V8{y3(Xo=Fic%n(}CubkecMvmS~T17|>tUoO^ z-glWxf^@TCqojLLU7Y@)ny$xWEoV&qRu_H)cm_uWMWPRi=_TC3h?=PB zlG8mU^hU(%EEhmvN)kSShaOsrSGdMmcCZ!USV0%AfQ^-v#cmM68X-hv1eBC{Y~?sv zYCTvchyg!*tgEc)l~3M%_og$ijMW;Bn58}r5>!;36 zF({#m9zlcTX-AdR!RN=s>78A1_P97|8ZoY8k-_LpPBy0V$&Nnbdb#i~XIaTp4iMru zjz&iJQM%=Op&evsITetKTPKfCZU){z$_Nq82R&KG;Phizw*F7rx9mGi%T85}Lg^-d zu`=b8f&QWtXLb|O*JQM4w*;iFM3Zt_$m@EoCz~wAfyu7y?b$yZH-2ksrg6ROT{~{V zaIYH&eRhqfzPha}FllUlG_@FKhX=QTE42xbk%s}M=U$l&v^1Zf0wO@bVu)Id=3sh&p~cwdt3O~5LB zKKW#5??cdGs8SbM0;Ugy;)LM~&4eVcWCg8q>*5p@xo-s){5S_wD=1xQl{iyK^FenG ziC#)N`_frtKrZD|S9nUasmw%EH|n=NIwjfecH3QtD8g8MsD5=>N?@BOg!ykxXtZCF zq5M#r10#EJ6b+Q9!LPSUuzDDI3)g{nZxRo z8CR0QxRElcjmgm%S#17!Omv8k;dK#c!#u?4!m@AoOZIcwv)wc=a{5sjPKR5*%uE1W zJZ((rvd}1j)Zb|%xyb3v@nQO7mYlwW)bu$z8aaJLO`k1JzdrAOg0;{#o^%jhwWH=| z&-Le?dqp{HCR#@39=|m|c{f z{*IB;iGQ&~by8YnS3ywcbWYWQlQ>>@dO$iU=!|)y^xLmpdWxZ@NQ`-xKK{`q>F5Vq zjFv9ni)DJ5W7KpON>NAXH=Ird=`fcbGdV9kJ7%D&Yj|VQO~^~jbxTd}F*3NK81D}u zItNhO;%!{&VsFd#A}PJc%js2H$I!3|u2df5D3IQ_4P#8VNL}`Hj;QG-=tUcP+WLw= zq|TVAz`at>8xk9c18=DAI8;qRDXe|=;#vAJ65vun31!3(#%vngbDZ8CJ|%cuLV9lR z255D|O`tsYgWKJgFWtnuzNmMRJRc3I1UgO+Pl$z?=fc(x4s>y3@sXjzP)PmPe-Elt zA^L#O4w;*@7P0wX-N8G4dcL%8Sz9iCinC=?+olslz87v-7k(ush6w>ic%zdWGXIQ( zmn+;KT-Wi+l|-yP>7*x;mlzSVZu<-e{@gyxZ#Em za?{~)E18u{}ax>y}i+W{-%(A+d(cK1>7!%PzE&xJh@izs zl$>r)BoZd%Yu?qG=_+Q8aevKCfAU2lWZ|hHb;U3mnH-(lkn+=lUje#-bW6|14Kj^M zF-?ukLHCgB#WyG)Rr^ti>Bg8Y&x?UtVY)0LUcH%*!k3xurF39hPep<`Nbb#mF)+^Z z5d~cfG_bW>YPxZ{XeI%6gXkiEnOh8zTOVLd(O-10;l_E0V|@=j!Zp zb<)Hgb9&oqk0T0#A~{{n4@-P}{opy_)WY=Ix~LK|o%2BV0EZG8u?j2=l=Z+<1{{Wk z;IDAkk|Gz^*T*C2;qvk@$du=GdTR1`3VBGuI4%xjVcvC5OTR_N?(~_D~SsUQs#{!w-pqK+Kb5FMMdNdJl5yp zqF2UcWVH9E;6NeEg_u4>|H*dGMdNy*b?SvH?3%3j z6JMAe#9N6BYl~{P4c0nSm@+t9LOmH>}2R@9)gY!Not;i0MhR z>In+aCt+gou`JQFiKr9EmR$vt>D3AHqo-r@Sh4SLU-l8y^uH9Szw*W#v+6nzpKESz zF8>L+OS@CK}lB!RsSf=*I;^bDEnZbPQnP;RUo^3LBW<41;rFfV4LCt;>#7v zn+jC3?*i)!{ZP#)qT^9MI(n#5>Pb!^=fn=C*JJ_w0P)*RSv6Ubmuq2MveIqE8F9sZ zeZ?!xBSf#n@*+y-!&kIDX^A|8=;Vn@k<*usomf#(HWYgVuVR@5ufAd z>1fLiT)im=;Xc3}Lh=kBH6btY)S@PZ)P_1#i%l0T8&)2v=scInG_X~@vL7!Z8~X}h zhA47^YC`JUS~s^jqTPKY#<$~zv4t8zUBpkD*CI+s5#Ol-!7T)CGx@-tp3SQwdC2AT z^Gk8KJ?@-reDAnk= zQ938a_+sRA!@Y2>G8h$bu7DT0UQp8Icfpkooxk?xf6*zfbRZoVhtDDPONP_Eqzh%;x|ft$BaKD%t@;yDU&QElnW zWos10cycyk`pn^(;`Di!KmPdgvYBA`rAr9vtTG$<9Zr8zFA#6KNo15c9Z?-zkC-zL zF@1QR$$63Yz0_d3ye?Q?aK7lkQDVB$xecU0@`!YBWOH-sI~k>g4Cs36)+waDz>ykw zUV_PfA1z3)+B!`uU~ypx(YePc9Us*hV}kCEGktCrYY|&|&HTL42jvbDOiH*pW>zbgK1_a`9iQ#0tOs9r)`dX61$+D#J6S_RD zk?_3;(@mDPf?nh=e*nJ4=MSjqSY51abhRV8_0J<~vd}aQz4MtO74O_4vxUf(Hl%aP zLl;q~nmgUJ^^AyEzMLbb7L4ZNb4zW%f+Ob2hkteTvn#|g-eI~?Nabh?o|W(xba8Mw zcARz)1Lgc!qs4cD^PV9Tat1Y{6oYCIzd{a9ON<0{)*Qbh7|Z$A;Bl$L!Bd7YtB+CJ z(TL#j)3%b69z2|w+7n^a^p+MZ=#!Ar8AB~Gu>>#vNqFKvJ0{@DYMd|vr@u9gz z=p&p?`_ae8$Qz!;ZCvEdwLR@U;9cYtFeNReuCFNH zj=7`8V-KX`Ca#y-zOrJf-ulYI@Wup{+b}76kb=WpK_PkNLAJi^K{_kp7(Z5aMHmnf8?>JiijA z5qSY|=#D`|K*H$)^{$c%W}6d!e&jj&z5A zNtg{|HSY*N_|#F?N&5@H;A7~LC~irppdzFfWP80lL=7U_nS9jK1 zdu(skD{suo%7#|KbgEYU?M|Ch4u@=_8EcryfPfg8vuUxT0$BUfrnH`E!?{OfPLE%Z zdTMKGnp@S15Oh`u(s%yK{K{yiBD|qy@agjbQW|Ru354=k)i2slYC7JY%E}d64tLfZ zdE=Uq(?5RY$8RLp?d#lkZq=%n%3pte*3pn!nOe-?y!o6xgdX(On>V#dQ}5{5bfT@T z9&`FjFOdj;>{zElHS6H{xRtA#@rKv!tL?;SwSu|`TsQ5-j_8ewERU|K)m|8zGQ*=Q z3sy==-?wiCtjqfaq@$PHNMwl&BxObBmH_$!O;ln(U2y4xtJD{)M(pe0MZ@uYVf^K1 zp&3+msKA#ZO6E3LK}s?dMM!RXUY%VOvicBlh>?NOH8%FhP<4hQt>W8I&D{(o-xtj zmru5S#pVP4HmXR;ZfE!<+o@t*UFJ}dzMalT`i7BusX;ejPmtG~jz!(V@jcfGdjZTXcRDv3R_ERjztnJyF3T?8 zJh|rp2K0GPlG*}uFMjI48l|r9K_91p6bJjVd5aHxeC?gZi0M%J0qc&l>6L_e229^N zr)pSQIzMbwYI^LN**mzpX5KPk`s}J1Rmyhps_8yLH>kcw<)vV=Pf8bFbJPh^x;PuU z)(YNJak_P&m=sQ@=@F1VhM0Fzx;1o1-B0%yrE7aoy0sOvp%FD5%Z54{>A03|MTqDX zH-+pK8%j5EWpjxzm}F5WIMsS2&C_pUlO% zJH`)3q^8COZyi5o8f-p#nA^isgGX2K#DY z)E{YsBb)i|YWlx})4#Ktj-Fnv{z(&Z(6Y^s9d3$kMSIuRGz8Js<*L}dQi!3vX zDH+x6hS+uDyKW{X)+6%bH8(I3lNP1(%8l*COY15pHSdPydXd*hlMS%k=;pi;z*M-bkD+FDO%EhvPj4ge9$N3sV*92Xem zplb`ZnL(Gc&&bwcWPktmFP{6|wFO6-!tx|-qcsi=^fztqhuVSytTr&A_T=)l-McZp zWM*&2FLGqyd#}80A-VT-!T0DvYS4VagA%(g6D{uaUpdw?r~m84oS*|Tg^q0}POkN6HMfZjLE7|}(IKz+CojE(^QGVu z+8NcB;m)@LUes_DPx_Ipy~k$FdVViW?DHK&(^ESMdy+YrolW>UZzs*}H>)o2dal_tLqp&Yhiy@eh%$-g&tEoKU?EN?);} zo#6JU0&tt6%Se*x;Z|aZ?D!>v#kzQ3u$Qp&BQU=*KMB2= z=0F=M!L$$^>Dta4#*h(-)p_5zj+cpDC6H?^Vme;=l~6ji7dRbEch$lt=%qX-YD5vU9rQ8Mqzg$sdL{F)=#-?)4o{QY9=f{Tl}w-4`WjL<`LQt%3-Q}H zaqQBG`2mikXcxa)m{fR5A;h}yWOzpU9w73EBHQD{;n&JPq$D&yFghteEQ~cbMtOL- z4!`J1W09wFRGpmcQS67|*G|?a(3?UC+&y}kp-zS4`1vJA=BzGrMz*dlv-<_vDb)^e z6f=p&mrjEvB4^-s>@T(10e*H~U6%K+0TJCJa=LVMpPFs}T{1QSF9_+Bj>?m6EH6mv z62)=97+oDshtbj3vAn32C|WvrZc#esbQE(=jm(Z8hBdsUqXKZE(`8Jzh}}5V0d-03 z=J2Lub`5YJZG72mRN%`8X3hlD$wNnAhud#oMoho7hA2k4&o#4{{iBah&IIMDE4>Vz zYh1pxh8uPeyKdBUK{~^d(+PUnv23_y_Kr1R`hkc!(h<|w65*1H0p#)F z(Wwo?h}aD+<3~?QSTY?YK9_!z(ta;py7}>s@Vu;DL^sp5Yj1A|@9o_{pPTT;b;?aw zl%jV~2>KOFm+Rb6Is*EK>P2+t^qtf6pgZv?XnwI{)2*~#B3q`WmwLN|LjKDW8mVw!8y_8t=>C+{hlT_1!Up)4i;AdKbs~WKEQxiIFQt&DMPi`Fz<0lS}K~Kkd z6l>BGTYB*9r%Eg*MR6QRJ_)tFC-;NgOToh}h~;DWQKcKlapcWJ3_qS2PPu3Uxs8l& zDsj_wSxu!ZZ+gS+^w_HLJI3$u{eS(B^FPKrkeo(l;;26nrcXTd2XfQ@9dz!y%fCTQ zC-eQ#6wEXe!gFx9e07ATKm6$EgB4FaI&IrmZ;g-KJdVeEqVyYb8o#=!Kl*hqA&Y~B zq;jYGC>?%72v&SZH(bG9fQ(zcXz6Nh5>){E&T=0(01 zk-B*f$l%k)OdcMRf|)XyAx<}cPAyH{``okv7Mq!b@Z3_3)4jIJw^)UBcUhh=%; z9b{_Z`>e)>1cj8Bgy3!lNr>M@Pp@;i=>BLM%xP^s)aojztzAJY6nYtz7&K=+(K<&< zOb_8dK4P%i$w>4g!46yT(j;1#3sr&wFudSE$K=h(=}Rh(UeQTAq%aBwc|0DmBmjSJ zEy_AAkNS)E(ZQx9+oO~*R(nwzO3^knfkm^QGHL`MUe$zxGX<7f4zuKoGh zZJFCMUo6XfOYMyW=wA6;7qPosTX4-<@&mjsFuNcf)62jSXG)S~PDf5}b%ePp)o!)6 zu68Gdsv#xVa7t)2gq1qX+3$3QApm!h|80yfJ0aAJAVOi9YO-pPf;&4s_;n70=^xRE zi9*v=svV`VJBf?n7$9d*-9g%AZEaA%s=!sEOVo6~K*Idw$S$$v9s5anULWa;1)ppg ztaTNL(v|Oml>W&PrwxfcG&%Wb*6Xuo&3gT9C!y^%9w$|j$lqW(wiP}%<_d$fUh*5T zJDX}ElRXVncElbWc!)-%ldEH=ZB6Z9pF<9PE+O=l1Tt0z6x(nz@lo;>!1@##8is)E z3Cqf+pmi3`Y02s-sOkM=GXluP_Q`Mj_{Tqf`ty3`ZrX9iNmRLgtABV-LQd=t}f%r0y+!s&AFc8tV4I&IWWR`@ec+02j&Cm zW7WnpnG#vMRBN^E(#{w5e8?Qa9oZ;Y58u*q*A<0@X@!Jz+AnR3Gwr9HrLNK)La}ymS3I^)tfovPbo! zgr;+1I*4Ak5d9s5^p@+A(-GC-bV=yGP)5ky($O)Zb9hH~7hT{Kp9=!J*99XVjBuT+ zmt|SMe);6h*Y?b&tC5*Y7+=ns+j|b+On(-`%Ts9S^dDWejF1-vzO2DpeqfFE2h0TT zFO&ZA#15sj{5A`uOgre*JIJ!=g68qM;%BH%-(Toc6W=C(v2rwYWj85bzTM+ z5z`^?5ixz#)~9-ARxP$j9ZVNe>xXw#)Q#=MoAiQ`J{m~pFxsMY@wYrL94%6}a9y8- z8D>LfMxZTvKPW071*H|!!xOvLrU_6%Ql%=c?VVam`RF3FbWATKHcr6+8azI=JD4Q! zhQz8VF$t*Yh2V2TD(yJKTd=&`ym@mi*7Qa6>71S(4(z8dNnb*PAhkF0)`6N!U%_

    &atX|F?C%y87)^xj9ESehOd*a1;Ly}MACfG@I|Wnh^{+5 zm2%g@sT&&7*U=4>BF_WZ%ki00TB|wLfpCoG!NakWF3}(L)Nmquy?ch(MbI-elnR{R zzWu>%UOQ$JUP^dkY-%?r`X@eqLU7^~NL-L`B%6E*3VJg5j)rFLQok;8^;iU)BoFY;hlB$QPOgr7-JYs5#=pKJO zP(RL_o1WehJf02u{=fdm`5)mO=$K0&_@j^hi7@>;>4Z&1_W^!h}+E2AO~ zhW?(Q9)F05$_o!8rhC5fhWh0+@a{Y^{%ckEudMs0xhl%lfkDh7#i2f1x>rrdP{Jj6 zog*|XRy8>8<8lkoja5dZ{`j~lqrGCfDIcYJ6y@27&t4VUpsW;Uq3kG2v^T7LYCLdH zqXg}A6m_5UEPtEJ_SyGP)fJB8qM5#-rU(deNM~*vzSZX5Jtpv@1;?X0`HF+ zd7WiiZ0@IRkLc-ao2MlxKc#64ZWldIGf~hi#$dYHAE1}v#dC9}t0v(^F_R|1W|Z#( z!}Jm&=q?FDLB^WSzkPfF(G;`Us3GlWb4R%bGgc7ESR6zoqgO!(T^QCCodO)SB)Rz0 zm_;Z-i5sEZ5TA`rL-1h%bc07s@9V5Zv|O2yAv(9^??g9(;+^E%WewJ1{5WjXbb9$Jtr*?AnJQS8tUeM^6T zO7g6?v%Wv;``>??)IBAc)X0yVokeLuKpfgV*qKcr&SVFXgrSkip=)EORaIm|>2Jip z*syhcPsQqchjN^vbTEBvQgjJ^53iD5BBU&@f!6VRcs$unlr}n{S{ep92b+r9X??V1 zU!K3;Qd*J9?LKj15+R9wbw~4`&!2U)Ij`&RjgNe4`nlSj@7=q%`n`Lr@uOa>&-t_! zMsJgxewV|I`Wx6^u(H#nRH)uX$JMwvIbZ5%UbF)5OM!a#j7<&b4FCWj07*naRHXNFlrx8pNf7qZv6YUDf~a;* z^o59w^rL=m`F_ zBjaTh`?oWL;|)-y18)YW)TQ#1>=)|E4#~`^sqqWc1co=Qm`A|oLTC&rt86AIEUYrn zo#QF1Z}a{&fGADY3+{9*FP4@*XWl89!8PVdNxy9A=JKW+(frwWR7|R)Nql*Y;1~QZ z2d3xx_UnT`i7)ZA0CFx9lzN?2!QmVP5_hoyd?bD~!2xNd!+6j3M{S zdtUp|YnSk)&zwmusR~`^EZcMP@|tH)c0W7wsj8>&fIn45W769nzxFK89m~t@lb12o zL+rCJoxC)Av09oMHJw*w)O2&QCSo=sJgMpOyd3E9dR}015xVz)&aOblHC5Dg0@xO) zKQ?N{Q$sViE;gW!rjC?8O3*FD7O2DEk709x)Qv6O*s6)9nKok@nd#aJt7~O*5S;rU z{SQ`apdT#=;}sY9tf`u8>_ zHT`ki)D5W-i3zEV)5Y+@^mJkgZxd!h|wJHNI2)`=6J)|1-O+DZiE!qbJ|y$-~-TxncF>vpbl(OVB{QF>}ORGv=T z)W*^;wC+&s@(5swld85#9k3e`6rz_x=c*`kGBl%>0AxjsER;?!CvuX}<^D zU-Jw`7R9^MNmYDwd_$|RmBq+SjtVnX3GVo^Gd@561;yTp@AFa!xZWvvZZn)muOK>hAH&Cu~T{J_Qx_NwNDAUNaK``e>Y|e>=>Oyoa z*Lz^iKV-e}eUz4(9-0?~?<7Fke7Fi~`yA+WYH&pSGRA=Dg4({Y;u4TMpv1ynN z>E_IM(*pvNv}0b`e945EfFW$v77)_u3CyeQB=IDG+;jRx5{IkK0c)PTAhsv*6wv(?>K>?kg) z&8y9Ty6d!K0g+h|=18j9&Zg}y8*Orm;m ztu5~j#6Pq&e)7Sgtxtv@{NbTiY&g7q`74uFl5wJJA3&Wc6P~9UrWDca0fGEIxMl{( zMnSGdd`5C!QBY8FxU<#)p)=I-dE-ig$7=&t%^I6e8EDtekIoq}owK^m`g`x)%e=R` zHK((SxSBd_+dfVN*7n$V%>Z=HV;lu4D`K7D&a3?jhTk5uKiONVq3tyVA zK3RyslFn_+@<8}XqFCtfQ-A~BUIZqS@zEI*P=Nm)zoVm|98cBY`iH(z!-M zBO$usbDhZca=k^&E>h<h8?NmAJl9DveiE~A%G)x6ouE`R(BB=mWr^xHQt&BGtVt2lYv!t^{!!sU`@;HIXi~cchp-s3Z_d&=jXts0|$(lKH*_YO^2!% zcOQ89<(IcE-a51ADI|6DbU1yKD4iqFjhsG{CP!*>1b&J^=MeR>b;4s4CUBdzs@{E8 z zBK4fq7IIsZ+R}>kyqe8*;{=T{aQ@jBS3bneBBME;mJdHv#v-~oSuYD|Kva5VC^dm@ zL$P>Fh7uAYdiW2_e=CYNhbPS*9>(*pF@=o9DdQp%QWJYr7D|WDo4L~)a!ci=C*mAv zP8DkpKQsKylo)!1jz2{T^KfZ+;uO5+Rn&D>k=WA1+tLt=vPS8s32Z?e9|xz$R#7ZE zt|fTum|%QBL$SefnBz-ti6zek`98Mc<_GDMVlG91=TxHNc1Jf?AR`u{2>dn7Zh8Q5 zBenP7z99{U%*LJ;id7qKlOsbcd*XkTkoo}Qk93{}z5a>R^oO!E2l&&BDfR!h*B@WA zR>qfyr&MGHe&wDu8|FUx$m3~#4=zr2r^P7YWkTxeFD-v?oj?8MN96l3tjmdos+NI7 z5d5@`I8%(Cj%v;A2GT|3Um8-=$IP7@JY`%kXJa1sDe1DNtH6>rof6Z{p9`Zoqc|Ih zTCt1TtZ}pRTbe+$Q~LCZwCc9iZPjV|Q@QP6Z~7$aNiCv>(ygPwoM)^dB-V3(LVrk1 zd<-wiu(^q1G^`G;L+92(CUtYsz`fZ=pr_zHjGW<7w`xaEd6Qq%iBvle6mug_y7yqN zh|yI$>fIT^mLGY<_u);%@qphO7Qz}!mNdKF^ZGobHTyflhr0V~TW zpe*J_EEk?IXZzsc!?ktJ{v$_Txpv^WcR#=8Ar<6UUY)H@n7(RdWeRD5adFM7;*OSt zII(v0UhX{$rW4j^f03jYbs-&bp_>Z|O}9)hBWn5&ScTgtBOOSI+o?XJKfh6*Gw3L= z^|>;lR%Z0oflC@Vb<7~$aC?n|w*X4VgH13DsQ#%W@BUBvokyDX?tSHzSKfH#jklkF ziGE3V(~p&B*=%{`bzLQ}xqm>7EiMrEeOMUvxr)PS#*ZHmATV>JM1zA&enQJb)K|#{ zr{_TEQqpC3;UW6=bhS2qT*Fix~;^N!{VYRtYJT zer`+7>eX=iy;e8T>gT%l?d$5J5mI^QG2$3+!0D~PI-2@1K2ks(P5l^(I?f?-*fXT4 zOHJQ6Hadi_q^#E}Bn7iwd0TLgQ$=b_BgoNc{dOGxk%6R4!rZ*!wh|^Dc(aPJ8Lh;g zQba5$IyP;RXcFpj3SI;GAYAMfDh~?HlMf$%H#z2d_sDT)mVm#1CAJzKNu57cb|G_C zIc3W>M1AH3ez?;aNlWQ1M2wG_511Lj(m+p6rrVF|PNMQ@H$*%P%?OxG7&(2Z_76n4 zilYlMaI+I3iHT}wPG?_Vj@yQDM@l$P4I54n-9u(DvAjewdEspV(m7>`UsG9Ts~d?wTTMu5UxsT;-WO+7WwOKJ z??}$C#Z=?2uT6Gu_Wm_Muw|%-bj}Pb>qU%iwDkXJq;yc(LUghDWguOybQ7FTTDpo! zNlt{)rKU5CE#1(%7+u4N>1&92VI6PtBBi|u*A1u()dlHBMn^k0oQ{gFf>L&#-YB3Gn$yjt~qt-(wbOEe8=omm5@qJR|uniEHRxmXBfJEScomG zp83Ur885#)TEE0s0vCa_+T7H(-@lxVt(%T)zV;?v zR5w&~Qv&+x@H3}ibArrUs4~OcLMxOhF=I|m8^3k@coNJ_F#Xo5o}uBPmYxXAE0mD7 zjIKI0Z3jI_6%`i@d#A=yaN5EYNBa|m-$RoqQXN)~;<%m`AY4A0m=^r4SX#^t^o^y8 zl;pOGB8k%JVM^ao+K-|* zPwA1APW+-M-6Wx?E0Cu2`elS?4b8HxQzW?v(#HhzYaIimV|Yp5KAmy zdMmY&XW|aYbz#zW<1-3(aj4osBW0tYI0!`!IdtL{vfgvxF($%|C!HqEYl@ z#G~z@#4P7fE0K&Dv?fJbj0ynei0?DmAW)r1-N<=LW8}U-dJ+jQXntt9&JaB3WSWGj zL1rF>n9xpM3C)T6$lwF-DBdHj8$zO?B=Z71E#>7|+5Q={nW?k&ANl0Sk$b4=zkSO? zE(lrPq=TOuJ9ed`y}h4sNV*&$apF`T$ol+?Z9hM|@ZMXQhYlUO_R8M9dq?DQE?{zj z(&>6+$>~49663vD?)AM?k*2Kb`p95LD3sON$Dp(U4@o!3``DO^%KHR~>Ys!V`{q6m~`Q_)o{QSTF(=VwV1=0ty z!!W}X*S-Dv+lcn|q{{X!?Uj}7Aps!)Dg-UcSADGqCrwx_hIW^&-R{hG(sT*)bI7c$ z>eMk?yI%yXmoA-raCmD~_`!R`BZlF6F%r0~80oeoh}|S5&^nw8y+@<7LY9=Kn%Y!Z z-)kv@b!NM3c>`)4QmGm7V0w{XpW72Ki(=H3N@rvU(pPSAXTs=jW!}rIT>+(cVc9=i zOHw+Al4E7Z>W!e@hPHn328~QDO}$)3b>%bG?c0*EQr2=!Ncd6}$6@CeOBW;E%l1Oe zC%zVin+I@I<07M`6M91A=f!2J2lgemPaYX5q12Cr~CLZ*L(lPZ1 z6!Wq?ka6BVstgd*Gl1y~2eSboKkrIVGZ4@EIArXI)fi4viZ(7)mQfPnRz$gn-qfk+{Uvw1n zR({iXVm!N$$b1qWSJ$`NRTYbCrYKN-RI_;+d~>K#rV{~gkUn)&NXr~Vp*C>(EI-Nf z($lkRT00KqwAL^KP_-#tN11&yDl17JO|EpbR@Zx4JL=oKx#4I>JHR!+K1*G1kI(JlWc;)ys7E+lgE!tpPtA7 z&l_l;dYj0`t*>pRz!U>I>{zm6N5hUCuf2BiwXIF3n{u4($nEc$1a{2s2=GYknV;wG zDL8U`;>eKZHi9kfNmX*vnQ)UmNBzKy8ij15D5CeVCgZ)|MX7>$AEQc%)U0AW~t zfhMU$9@2tHZJXNXu+Nisj>tVW+R%^}jw-%)A%R#%q8u`N7nVJ?mUQK?h17^n+~9k2 zYIeH z5;tAm;PAix|Mv6p%7zq83LZ&mA8h>seP=oB4>(>NeGRc|33v%v>pWp!{Ril3wD^_` zrTc|xfLF|`Qyn(5WTbT=u>je~$vzp~FuGq-ht)X(}SB1-i8zClITlCJejxBV;p5-RGaGPw>av zE@0<1OG;<*peaDiS|hKU?xRdSI2t{jH)=8&7tbx0=dR|Tv_ zRAS3>7^4ds`h!FNwgl<=D6+M9+6UEiv~UIAh01*a5KB^rpC@hh#7g>*4i*n2(nX!x zw{%NQ_Y?Y}oQ|1;R+h;XD+qW&z@(><((x1@gGOJE(u;B!ok)g^6!l3Q2KjB^xhmg$ z?bGv1Md>vCu~oI58XBJUoW+|iHT}QbJR3bE6F82KDr_30t4z%vBeRiskZK2*Zu@LB z_sZSZ_FXT2`|VH9&X@vH*;>pnosMWkdiLgrgfgO^!|9Zig6J%N_~={W^u{hrO|LsK zOZ#^Zy?q+XCa1{mMtF47fZdUePXd3oJzHsdL&J#1!^1-#41My+`=2S#9Fq2rMyfxL z9ixWy%H8=9hl4Kk!^73-VEW-5$BX6eNtCUnin$8Z7ZewC&V}#_v?WS-chnaa7Ik;? zSUjqlj+zIb8Ypdn@-S8x5@cA|TD`roj4+r+!bpO*2UA8{o=o2!8)-Bo=YX?ScpB(z zl#~t0IqEk!jy5eUOC6*|=%v-=1v#`Vzx|!TGkrGVP}Zeamy(k%XSxJ+3Q$W+tJ2Yi zsfjF0bc1uVt=-Y3Ou)P?G}WmH=pY$$cCxZc<((^~&(rTSd$zLD6B*2%ju}c9sbAeS zS%5Je&r3n^vGl73(%EQjSM#qj30Sdxcm2qI#))~{FVoZW`@O?28vBbtos7nzmZ~yr zBr6WBOJ?RsM(9tAE|f$6kos@4W(bB7XU zu4G0tDjEZ@f(Two9|ifzdq>?TrJi(rcI`wXmzOekoNeQ}#M#-ZfdT#oJT&V_P7;TWo)rJ(AzqK$ZIoPp(-{HQ#$}AW? zYddue1W)2Ya@YgpZpp?Kq>e>ZxbfM05(mUb;fQ|0G z=;=0ha$_+4Z_)l+f})v0*3}j7FR1hVlb4{2I~_S4J)H(emXN-4i(z!?M2#UGQU=X$ zZQKZIqiLHEF0@`Qi-&>6l!2Sb$yip%T&QUMfGj zjy{`L1OpL*sOH!ptuYn#^ZgtRw4 z_vS{d>d)Y6xqX>BQW*WIE$Ue+Os9%;CyM$45$X#Io1ppytmzx)Hbw~3DLn<$rK8J} zeydl?I+mC)v~=`sNc~SA7N&pwyQ5!+%O$7_)lFB_Z?6}h`%ElsSmIrvbfkWy^f2oP zr~3iiP`YGy4m_e6Ph%oVL$_^vZPnAnDE{b2;5byS!(7^&vt~3e z^MxGevt$4J*k9LtzGDKHd~Op4@0_{Vg}n>mVI&%&8IjVGlbNs(o<>r6d)jzf?B4JM ztTM4^*zo!&wr_S3sI{tIi4%7UOpoJyZ$ety7-p9{QIu@1L4fZ~=v`o9kQpA)xt!qh zl+3+r!}rDzwlWs83<`+A&>tU@&>I_ttUVf=MnK{iz7*M0aFgRdHwJaAF!UZ}nxcVI zo^n!(K}mYaiApFbx$Wduv@Jqo2h~y8xh5?w=RHy!dt-a$dlA($7rNaraa*SiY&f>? z9f}0lvBBj`QnzWaO`Qy30G8l$Rnwz9bbU?#T)%kTd;f}23f`D3NzG+ zAKZn-!cOBki6_u}5z-&T^v4)Xx|fGT=_un+x*}eL>A<;>(dB!wq-RVqW`4x<2(UI$ zL7JJk&| zJS=8BUXu-3TLkE4!S7CAM0F#qTaytUQUeq>G_DitxHz3tM5A>BUk$0=$^D_J0bAp~ z;YE&@heP~o`jVB{o7tTognyMT?4eagyC&HM3u|KK;GV(5nA7QKPjb2xIawqi`Ug=R zvy3g&Md>K^f_3HP+cCV5+l`veu^vM@nBLl2on9^1OMaWzt7qV`1wvJxSxpVnSvyi+ zZ!4@MX9ekXmW=dE-9LNgncv);Y4)~wWCGu{i%h=knW?FP{9SFs-mb1{sp)~azd3T{ z%8q;8-9?2*iDO(0PB)y6bbj{3mp}UOQKP2I^kT^UTOXR_m$#mLbY^DVIZI8SR9p5$ z0#*hZ6KS6_6*vXb&{o}%6^9==2_H$ofCux5IDO~?zO_F2y^>&d{3w7J#m6HX5-jV=VjM+)Iv zJn6rZ-R0N6zWLEd$H+Kri|+2|a7W?`q13WE`B1i-K1bzb-IQg=-(3!P!3r%&`1yVjw9r?*9GCxw2OP`dJc zTB;fWX=);ANKcJn2dXu-uC%#K$2)CzyJr&9+XAVJ9SA-N>k9w?AOJ~3K~$ZM4#ieY-gjcvBovKhML91fHqux{>_L2h zvFIa+<9AUNG~SoCDtjQ==Gl!>x(}@*N?jdsl>dsxEF|rs=E}Y^ z1!O4-D2Vdq!pL(-@~wmWiz$K$sxW_5%`QUNgV587XVh)&p&lw=ZG42XvCXItDKV3> z;6vy{YD!KIpv6($p1#(AAQOW_v}IsoaAS6&&DGf2$0LLA#m#KL?Y{r$!gRn=zLy?y z(~X*LUC=5^l#vE0kp;C zCQ04Exg6)lcrJ6g|AKUM$Q@ocD!xiezx(FJi@!iSCsjs~F%sZ!y>Z*hffT&+u(Uve z)Gz+s`Hh=MblLQ^jdyPURCzBD_{Q(vdG4t{5vDUx(@mU+=~pT>9iz;qg@uiKNqLdy zWqc!QI%aeurn75+B@S;w>BjP+{-b!)wY{DiP2W~8)b;doUEjH>v$N9=>fAgyVAVKC2W4Fnrcx8(>C>vA;Ou<#gA zwVEFZ)n#1q5xbF*wJL?aM#6L&8$sx%36MqUvc_R~G4p+i-3GNGZGk!(0OjRCdONAC z86`*<4Y2v?eKMvq?Pr|Whe0r9Ehw&|@!&{77qpAkO==`!I*H~{^gT@>9&#;L5$mEE zi1EEhPuB&>={ktuxmpCT2SH8ugSlW`NN%08sG|gOi_$4{W#6Bfa){E|2n=g82+~dU zEl&-kL+K%lA0SmBDmnuHFBq;PINplHZgaKv?IY`DGI4UUth6pYsFc#hP%^&>sWVPs z-BdjqNfn_}yDAGSvXbSafS0he5Yqtzkt(jC0#cODT{uVDPUYtldXkvvl4?)u%w2d| zJVbRA6&Du+O&<3Y4w6SNfBl)C-Fx|Ey7%D9i3|-|cc^h-W*|Rt)?G~_%VGD-6m3bj z{V!MUUitB7*ZT(d{oPH(bW2Z{E8Q2rXw>w@D=e8^r`Xf6!<^kytFFN-QA6W#2%OQQe@V;+AeI?SIJzIw8Rl_%HLAuDG#|0e=7ytRD6E& z+iTaZ{bcyX;o+(QlDK!3?aOP}UtfQ&x-@-eW`IF^qGN4sl+D_LH{fRf$txq>vy$XL z7NkSzzxtJ>($5Se+E9JfV<*tXz7CZOWL4PRGmY5+kUBw+USPBSTzz4Ep(7GIlBZ?% zSQX~>*#TN*4g}ga#J$}+zPI;nkUFb8`#W=ZHgES8cm@uwTTvUN!1N&fmKf?$@2N^} zB=rv)O|t{NILPCnOFaT?s3RCOblZxXU0K<)vx#MZ?~+S1Bs2cy%N>QS@~Qyi{4ivC zp{#7r8G;}Ciib{Jt!0CGt)#^&DoK^SXlyR@mFlOa6qEmc%1Wsyt*42pDoUv*tyPfE z3ex3UpyMiXf(jjR4qhnM@l(f+QRJD3Kph>eKA{XE$f0Mut)s|O%4e4;hwmg*dE&>a z8Ub}hv(V(Nd;^`0_$*Z=nz<52D<+Sn#7c4>Qzk)$a~n}FlwqKGQ=P#_kt$QBD~e^0 z=8wb`EK!@v-R%`CmvAtxb}0}(R8~4!=k*jH*>M;zIYEudDBt{D5I{ryDla537+HTc z?i*KaGW(V$>BY+E-*#Z4xYAo0mxY^M#h*!b!L__OnC^qKHWc+0wVpX$mz5RW8b>Qp z=2ZO3)E_BOX^{NQG9$JtHbw>)CflL-eSED}H6yVnZ+GvntQ^r;T@u-TaYeMokP#wozE@oMNI#G?9OFWlFI0E142hfmn+=@b^0C|w6^$~?e*<% zkTUZeu9t5=wR7V)Hh%pnG<8YqB5e&QecAeN!{=i=$$CLb-;1XiN|)=!S3)YKoZDFk z9@30)ejgIk|I|>rW&}%pzo;EsC)%BJc_k;e(#VJkQuOBrl=G9Xy^jl%IL58dKcAM0 zntt+^e#dgX>9=|q? zi1V2EWiiXbBOvljY5g!gwWD~($#%hvk_q(3jE6-;rE$l(_Fkp{eA|t$rJj`Yl-{VZ z_S+?+;S_h`X-TcA!I(d)ve``9gyN=YXc{GRk-PTrQkUb5=jDcv#onmtC8QDB=2Z&I z7Y9PQD4hGIrRE@;-?pw1t20Bo-R?AE`kfNgbSeeD@}@5W#($rM|DmQA^Adqw{a3e+ zIye90b@BeNuC~_c3g4C1nY@Xtv2J6|@89wN?9!ot6HeLA84o`cPli!L6YB83)5ja~ zGM7L02vw#UkEDGGARSECkTXO?E-VFq4cv-=HBhcKU|C~Kx1jXFQ*b>(W{_}PYpBX$ z0J>U_n&B%Ny-&7b5s&#vSPy6{BvGj~2b6s!Lgzmr2EN=QM@}Ef%{`K<)24=;ln6>l zd4=M8Fj&&QKpi#Q$o@;0#>;9GOCD50LQ42!GO}ALx&d^9wwX?hJ*(Ai)OVV<)N_N=I%kH+x;IfEOI> z46NsZyi$DAg&e$eHY&}p-c?QR9^GVIba@FhCis@beC!O-rv0XEcCrN>bAYJsOY}GT z{?~tY{?SM43LS-@Xls4)_N)Lmq~UHpH~f>4`i>bI6uq_Ym+#*F<-vQi-6Nl#xM@MS z7~PD;g`1DQY@*Z`SLkXP*Izz+ZlL(LBr?8x?Stt_x6Ruh7v(v$3!R)lE- zPWH&I(xIXLdBwc+e=`40|0k2DOd1Qax6#u@*PuG2{_A(HT~XM}PloHOrj89wR(9vM zm+T+W`)?uGkz_?W-XA-43h|c+#1~)r<~JRcVs!4Qhx*mu{))#GwX@?O&_-=3wsVi9 z@+x~G8fvzSHlvtYf*@5ng~aG}%w(84F(;x*_t@lhEbhqk?!XO~MoJ!!*_k_oIem5Z z(UPe3dq)TN*s>2DN=^rX5uRm(;5QW*iW`TnLXC~Y-N!lVS6O^3?+4-f9y(>+T7{wc0GHRNpz%HNfk zpPygV)^ci6o*{0(LdByaBPRGoVT~vD&wGcd5hkXQ(-rGhq_?2Fm+Hg86t5X?O6f5$ zeUdH5=O!o;P%k9ylPM$i9;_%dpz=g}*rcWG=LxK)Mzq?^-l1cOyUK*5P`b2;@(qAG zpV=yMeA?>0)bdu>mwK5EAf~hJ;P)yvU@bd+NMk8W)C@-9>ik*QiCav>n69o>Y8{$o zsybJ%#Pm{;JRqIFc#`0jrUS?8TB%=37G9|xGu42V}yQRYf6wLIyQ)Q@gE zaI(0yvd)I798OOPNSa9^2$Nqf&w&9wpt+!^qw;7+2QIQ;szt0|7yZqJ($`jXr>daU z3qnk%c35$Xd{{z>(M&=~rvcM;*PcFluVx?03XTh;vlV}}lri%w#0@l6aHMiI9aV#p zvBUWO8~9*RO-M})qfycUY?$0&Ibu3EPUWclF1~|7XGCsD+>+AO(o;t>%-Jn0FJ=wB ziEzANc#%N`mp7J`HwkhPfL|7uOHW5*mz-|FxslJgU~WPkDMNQAQig`7-z6`G`NCz? z^*1iw_ES2%e(~b1i+?3!x-k7~d%v~`O2@Fikpj}^aHvyAN z`hqY$O>vAHX>o+-h0t_^<}$qa4n|C8E~8B)Fr(am({PEV;ue|fll?zvBN!pOH z>WQrvF1&WU>Et#jed`N(`)Fd?bQ~GGWC9;2c&?D)Gkfk0a>Yc$j#V`|&!!=lBb!6% z*juo)%>D2DkhDnF;^(U}cHnMlsELi5iv^w+_AboHrZTqN#7!<&DB(g%S}(!ln9)f! zoFkpZ=*=bcKW!+1>BZ)RuAo?tnH>u;F`eUMQGAcBT^2D`1EsTR;+Jt}=se?g1Ihx8)khTT4rz<+?V}k`w!$7cH83u5TzeXz?>t4b6ZFzs z0~5gKI9|+;egU^jYVMGFNeQVu>b_spAN(w9U(K4D$0pH`fpdh=U`4|-jO6-mK0$g(dxHjUHs>49?iKmYjR5V ze8ItS|4FTfFFMX`+K;=fOTN?AiJHus+^qdj=>sLC%}sfkISs{MxaA+&g{;2z_(PgyP zq=gBTjqVMiYr%qa1I6a0KEmUqQ1yZ*p2>p2bokq-=4jh+vrk4h^14ygjSYs2nw>~a z*EHllr5jea<`ZVE-oN2?VS0-3y!dog9;>6(m7M zkCd1$9&n{osaH41fA7A@Do=iTOKBT;&UJKqglkYPp>z<6`Zc<~l!HO5vuKZq2v6-O zm@dYH(@CFhtydUhtG5(3gwc0lt#DON+NwN8O_$$-dB7|sp+w7h@@vb2#pyF2{^t9C z^8MfZ-G|*TISLCMZxu#vuqT~8T2Kg{6Q({gf_?q$+3wu`&)sXk{QNr~&D6j6sVNV& z2;Dk`#4({i`Qgp8i>7r*-G8*ybl1mM{-fmd;cLZ{vz7fpRZ|0#LzEy2_-x&?V0sdD zhjFd_`)O_T$^0~oK98q*h(1KHwNM?r{4qop+GaM~3NdQ@S6O>NEcD zQ`@!eMB6d+)lgJnfb*DVDiOnZT=2k@lysw_|N1{moJW%X`1(hUl%`I30z;`Et;f<& zM5ZUP46B1HE6YWXQ3u(OC!d-q0aW&HIZ0FAu4@C@zOg2HoSE@ZMD4IV?nJ( z+bnxOlKQ$8ySs)*kke0`xTak7Y4X(TucE16MNZ!>n@n|eOD(7#UC)NXlA`GLW4p*= z;lqi;oUaH~P6qSY&4$xai$(OzC-`hiR#yZHyE8OE#)e=bTS`l@ua|a}wy|Xm ztjnO@V#6*YN?%u&o}A7PiG>=0pfA&u=)i#N?WzwA&L--`l+j8&S-F}Xq?AOn8)(wI z|K!2r#g(Bh3Ef2P6e9S$L-|bery!&J5@h{sYClTVg0Iv@?OEbiOd@az#+T z{vu_>55}Gol-*pEO?463G+E5s_ycF!!PJF`%b^PQV6n?pmE6c5pv(8q9T)@`$I;TQ zD8`+b(go=z&qboPBychqNo4$~C8NX7GN`L((KkSGspjB0KO%E2aVk|^V!An~cJ$)q z8$6Dh6d6Cd&vq{1T#~wA9Z1(AkM2{`{l%+BMkk_OE|>4V`Hg3u)5E=?AG#}D=FAe- z&;Pr>x%k{uPks9->y2o~z|M_dM^48M^UOx2G;Y~~g&fxloW2EkHk7_|ud$|YRA~Cf z@t%cVszpt-ixAzXsnhppV-Gw{GYboyA?mN+xcH_XapSFvcP@XI_eu%tQ(s%ZUaB}= zbt&slk>WTfN+*QIbT~pv59^G8)BPo++V&Qx-xt$)8V&sGTF|wcZZa|^^5$~xlw@qh zWq$H?tSg@%oY?mMg?BDoIX;m)ap99~Pe1*_3r`<-;ozoFuu@oC&&bMX3nX95M`g4^a2_K&wnJ-IYN3)&F9bKJpY{7 z_0Ly*{yeQh*O2l;LOEdy8y|lz3M8I0y0`)sQx>FRQ_)4EPMEd<^`Aw=Y|_iIh4hB^ z#*W9Y9p4CQ5AUVQ zbd57FZ6PI+}G#voANnlLttr?4jmPaFEdwGPt6nrW`F<~qrGcC{zqxMWFAf{YUJ`Tzx_nsAeLEiYM8M~ll4_mT## zeYnKbFNTCXmMMl`S&+J!RPF=|uUDR48xp2FKGMW>c@{Pf!p&tPZ~183VUWqNUT%+G@Tar>qgCKAxkrJ9t(-jV7>J`taapsJQ6O1 zO|a$?y5%3?D6c&242%CAIOko5JpAw@5t&WJ52U{QLEpUy-IrAevMLw-G1~r$O3g*X z?aa6}Kx++Q>HUEzeJu`iqSB2qopWjFmMz^7x)Gjzoqvo$M8+5ezgS2u`%ILxM1`V8 zP8XyfM@L6X=cFNTO z_c_t6Gv8|CgF$H5V;NA_dp3BkQ?u+lmzpk;mzu74ckDY>sk?70Sf+Fn1J8@$`Ir?z z>G#!i6AmHg001t;(Ljj|N+bxR@XX-g;S-fr^kxK<5)mpn(k4-@8KDJbajRQ0Mvf@Cllkk$b# zrI#fO(_jAR=H+Le`Sai0yngfO%_rZ!`S#75r_Z0h{fpCocaw{6zkT!XzVn^)pWVLm z<6quA{`tKbck77Nfz&AG7K!_b{rb%hUw)J#(%&73=`Wv4u6$o=`rQwv`zmKAz4`DY z*?Xfg|Lqlg zFD>pQNB!VI+G3B6;%t2S>21f#UU{+bMZlZQ>!vK$UD!M|rH8P*F8|qNFj{^WK%3r4 zDqxf`x}{~3c$+{P>d@r1BDj^TZ7Ne++PVOBwr+hPA&U6ZWod9RGr|m%%}DCNrCjhI z_Vz3wr{ioZe>d_5S(k6U=-7^%L{`UX*re?N__HT2z40MO0^GWPN0P%dxAqwO4nw z9i!PQZG(`G-7Y{BXNTff0#Kio3#y?~3BojSog;uZ5>yUr2Q*qAQMST%7u-$7Z6qeH zdYV=N?J9L9ZU>)B3(lW)>cHhn%tug9&gRbaiN*QiU`Gb6N3o`u+!cf9IynTUm(3Eb zSn8SF-*n(eoi`dz53&=sLjF7gH%&jOKj5##V0xLYB|X1?zt=l|gnB#zuD2aNoZIKX z!@{dXN>57KfJiPU4<#Ovac;Yt+?+alc2*WfbQ2IspCVi@((C25CwmboJ`N>bYC01y zCYRK$BBvv^V`d4UA5vC1DXE7lg1JR2hI{sh7)(EuJzFs8^0c^!xZLIYFE17pTKd#< z*+hJlE-_vH@SjS*{&Pg_H~w6lE>T^Oj`iF>K=NC1rW;DXWtm=BrANZ?BC5ugPMQns z@2eCQjAMKO&XLp&q+6tJsNL|nk<%rn%hzIxReuiazd>}m#B|x>nKoF#kaEAgasF@q z{`|!^o_j`~7c$g$3fAR%F1<@tv$S*>TGoI628~Neuv~caGVYgWFx0^Rdp8+-xdrM^eI4WbnK0MmIB{XqYZ7hZd9)qw*~thzFN<((@hUqkjjka1w^;rIE}Nld@;+O|H} z{9Ye;juV})w~~WcO6GFr#+=U7G}6NvM2@E=JUch{!V9AF&r2F`#M8aBriK8f=!uP8Sdicio-1zrzGVb~8ncSCHww@BIGN@oj5n0@M&*o=Hp#bE z{J7==;hm4+cIk;78;?=_XHHre7deb$DJRkV4)z$TKAG7hpn=2TkiFb6I$&4NNrTLB znkzvufl5(bXT0g{1gPim+?0)?mpe&iX(!tp!%b#vR4`~F&J{$q*Yt8*?lMXUC02CZnj7fIW8P`vlqC}2oHfq8KPWdXK6&xdm?AEemxP35 zXk{IYXE2@R2Kdjs%rh34I}}YG5)!_o*nqeoow0IBLC8{{YQ4H9#2L9{Noy=O(>


    B-qj|~iKIsz2V(>n?x1gUrQ!2Qz(s4WTf)Z9EaA?MLd8d^7eh!JGG~=}@Kd zkI0AuIjgo4IyLDj${&;s8`HPqT+CQJGYe2U7IT%4#zYX04k=sdi@KYBtOOQ4ggOHu zut$+5B|myjYLp&1Ji$4k|6}~QT3R}gPQ)zp>zWiQPVv#nfi4rev7{SHhpvs{Z^8RG zPqEzC;iJ&HV{{#s7-{92gwT0ZGZFJvEk}=~rGwPm!td_!(Ybis;JOjhjr4C;X{8Bd zWVeCe@uJFE%aksnmz1uj^NmGs`fAGJAcNqbU?Zo~;ar2xM3j*xcDy}^o?hIN4`pFU zfwnN5Gq{DiKGHNLnQ)gZwAuq{|ikm5p%n(CHaJPw&H zRiJQwH6{b%NkVyWnwY!YW$sy?lTJXc?3qiKKK$%A&ph+9fAgDPn8WQ~T>i#0&ph+f zpI!b1gB{#IV|@Mlb9r}PKUs3``t>uP?tk*-MbTVDzSxHJ$(u5$v&N6`T7uf2gwx~7 zKEC(9Vf3zl<&{_J-%?7=l)I?N+{rSx zOOsWl8hZc$AOJ~3K~z^?BUUNkamo!Nmv#kpVbCCAMV1bV3xk4!S7ea_BCezh({LMR z4H&&pyB>pF_H;nr9yrr6#XKiFz+L!O+*_wJ$7yk-OvXzEPB0;3HoKycm`DuSZ2r&( z8t4ebjBWE&V%_(YC0BX-ThCqk%fCPW>Z|{+S6}^`zr6HT zscLF{kbZUO+J$R}=T%B7a|Hvk6WzRH+siksU64TX0iLAnOo~bO|h4DoX z$>Rp$dtoZTMZ3!+ya>-L%9UrndS%u?az4cyL}Q#dvg3&+4812Rx08w=hn&vKAo|_a zsMnBe`j<8al9<%e@9jUaYSr_r4m^F};DG}NwpE6j=fa$hnlAFDOKn^ra}h^CVPEml z%DPq}71hp&LEvO`OEZc+AdhS=;avrz6v#GfPgWvzBh7?QGI8Oh2iddO-N0MtOD)Ug zP(!4|d<)VmDzeL3J&pOq+LRshf7dPbsp&oAa4oKMCA_Fi(~`Kw=tfBwMO$JzY>dE; zkgg##7o7h<9&}Za?i8h)RVd7&^q-=^U%YrjEk~`87Co{N(+#K_@!UM5c?L^Pw{D^& zNR;)o1`7%Wpil<*9FP*-PT$g2?$# z(9)Hoe&e#_bhui{>6Vr*m0Qjiy^RHW8_|w*88wcG>Ai0*0y+!q8i?K5qpf5aRajWI zY}3Y#Th!EaJ)!I0kom>T4mS0CZGERtPDf0C^ZS|+&{ETYx^cZoPnVi*Fx^6afx0G2 z3=7`{>eAAALUx5NV)_f2u{k(2R=xK6l?(5`z6}xlz)9>a9A7_~d-DBN|Le&M+tAn# zbBLMwjC|z$q+lMIqu?`bq5Zw~G+KsI(|Tt#vv<^hD=_Qi5yo`u z@R%{|RLbA*kfUlA*`Y%}0a{U@=CF=4S|_*P_8p+}JlLOa(+gfC=f zDzwEp+M5#*zjm*2)6fx|XhmK&9+UQ(-pqyYgt3KiZ07V54TJ27O~mwq1Wt-Faz1Yd z7T0LFeGtK%iqA|6SWR`Pwb}^de8-oJ&dqUCq$*Kao!fC)86O?hf(L3fSz~>%R}HlQzlGO>^KrPWKIS;u{=Hd7CZr?quvkG+fR&GjlPjS>F;(GHp3 zSI1TEIl>%}x(c!eOD2w-srzD}`XBt=8?dz8)R;j8tuQy4E!eMx)u`U82E}e}G8Tbx zf6b(<9y$orC66nL5lpATa?!cXZOt&Xqw=TAuTGt(7@bJ;_Pq9*%&0KgXA;_T>9fY4 zFy?gS^Z@Pb!lPZ;W8!mzz{csasHJZf6zj(v6!T)0b{cn03~D;>#E0eP&Eb0CBG4{0 zH%p6WvfZnU$P94X?{eYXf^<$TIbAyx9^)PQDP8Yem7@mmnMClE<~gOMGd1x4ZdV5r z;HH4LWP7M~t3v{Cc=Y6C>ttzSiFq5baNhTnX4^X(IN z|L*7)C|xXWY%otgdUH`pzYpqt+1!N(#^h* zmXZ3u{L8D67p|0x=~R`c<6H#4iV zyWAbKB-@0#dHa%=l|)ZfCAE^YQsu<1q(XSsh2}m`)`+2;ntUaYXKh!mJPvSUo>4(6 zyM;_vP9S-q=*_js1L=tAvb`jublU@6d=604$+=MkBke%5wo@yy0#ZN34vfTOmD>&+ zSaslun!JNG2X>s0ah&KCY5qv*JkS7X^o`nYd?>lfmP~hm;%SofPG%g)*h*&J;bIK! zAhj@EX^NzE+5-c%%fN2$D6;R_H+Z4|mpi{_(}_y0#Daiu-Wb*vg;J{RXcBwF*k7gc zZtjN*#vbGfN+%O0l)B?X)I(J?2D2(T*r%melm#>nsB$f&5b8r`Q`@EZy70_0#86(&T~ocS_0C=>Y{RU?jv=Dyxe-zNa-l)&*?#VB+M8++dz`~JqB@ttV~&>y69sQvo@ zyxB~fExZP(pP~^`4^^W*l#p(DX5%w@bk=-Lu5=k*u)ln5=iJUso#^Pq6N=Mic@d?P z^ny8ETOAPhi|IV1v9tr{i0J^jH6*4l_5IsUO`SvS&Dil8#&fLa4H-{A@%oi3l*L^6 zB@K>#{MWBtxNzh+5_#U!uWh?_;mEdqbWEVN8KvF#_8mEVVJoJW7xCyYX50<2PLVnH|GYtdZYbL4e2wIycNa5 z)hf;$8#7C7-?{RJ8>gNEu_TGk*$uoMOiXq^!x0Ug(VFQpQ=)nbc{AiamQYR)0}~D z4n50S&eylmzabt`I>*#rr>^A43ql#^=XL{HJLHX?-u|90awjA?YEet1qw{cV7Th;; zy_uNp&A!sn(L9bfa?snQ(<9l}uo?W{uYb_<)G`drXnolA^*#WV6F9UYIRBoK6^8;$r!(k{}KOK&uQ$A-eMb7H1``{G!xO?gzPLBN4}W{K;oit z-!Qa}_lI2yVs-yoFkSCZdjQM^xUZyJS~?HQ(8+_Qm(^(L>^8S+7ddKMq;g&;DQuaf z$}`_lcZPJX6UBsH?3$d-Ck$~wM)H>EA~2m@^-zlsd&r!y*$~qm;&gm5vil+dL%X;# z?uwHDdja9sD~Y~nx}E?tU9Uw--QFaC>xaSPRd z_Om~ig8t`1_h-!F&%W{f(O=%Zd%Wbcn`a9?J@GAr>4wA~^tX_k{-mX*Ke+bM58r~* zU!F<+=-0n`-(Y(Geu6|e&SK4B5D?iq>(0)0C8uBQ$MEvW(9kJD^iJj121jpF*z z7|omLzOpia9YKBIm~pUx-k)5-^>Sst9|!$QFCFc^_xX-uDk&reWb31_a!dD85 ziWVW==;$AReD6#_rDJ5|m65u_NOBd~CqZ&!S7}RIRX#19*zDEG>(*@#4nEgB(#lMs zc6a{Ow)}ihdqAQue(1=+NO&~T;Xc~kfv0}PxL)GU^hR`Mo|##Fsr-7wTu*0sUUwFm z-iW+RkJvS`$myjXTNR*Qi@trejTpr?xVWmV+Qx2^NMzW+z~=7Cz~ua^XyM-!rfXn& zxwPF^JSqjf?!<}1%w$-!j4&SzgXvP!1E&(*yoW$}ZL|lVtqY}`sPqw2P%87w)h@DM zm<&x5s7|xe>APNJ_IWSn7ko0&$nRZkr|`VUv(D>r+dA9>0RwJPdXb7e;dE6};($S0 zR{#oiuQIPo4(A$sP$C7m$&JL9^MPG?Xf@MHnZ4|$OK2hBi&E`j7Fk7%{bVUM&Umkk z!i}c|PN%{ecX`%2RgQw`E7k=-|H<18u_q^14J3NEW$ef}c<_mXJ9cDDoZvpe_H%KX zGw}ixjZX_Ax*}mtZ*(QrCKEu~U)*0jef+@IzGCnGVsC3=EruGwHV6J5L2X%kY>wtQ zd-LGn{(}8<8^g^bPUp1-LEzR*06|^vkH24ZbugU?Td1e7nZy`&FQCaM)1=Hp{i@Z1 ziF=hLH)^IqY7&ze`tHt_?ix5Y`?2q9Zz(`X;o>rMVZ`)}v7P~F3(Un`sbo) zLA2a1CZ17{E<87pEUA)|lSs#`do7S&){_K}Y{t+H+|O zbS+wjmhOXVkh*j4*Lq;|9z~{8ma6&6&ZjnU(cres={(ooO`Sc6>5#fO{rA;$(f9*e zy3};(Gdfxx8zZJK^>Na(sY*dCIf&=w{R>x`8Zr*70@5+PTp{@7$A9+3H8356rZlC) z)6;#$bQ^p74Ebawqj`8(C<1-@`OoPfq(lT0a-KV(Tt<>#_6?p!Os`QgqVv5un0sz) zIVG73QqK|2q2RqgV3AOq*f}dNrRhCq-g|dS;9jKjl(4;XoDpGzD2DZ9A#E?Mg%+Uc zF}`BQ79yw%4WoP$(+e~Y$dk$v(SzM3MfMru6~`9HU(D$ZU%ytC7c~(ITcG=BrUY(c z&as!P2@*A;v1Brs0CY~!)HON4S#txQIU={l9mD1*-`o`hw~!mL4dQO6g%Oh!@@1r% zqoAXgPfUDvJ9pytM1xqIyYrS9GPQv3JW9zZ_n~@Ju{IC_i>dhEsX8?#nmaW)X!ks| z3^Dj_#>T!BFg55?sCh9?3)7wV)$}Du=SEHE+6j1f(P<(ezmLBG57k)jW##gR7mepq z-v?Qp#X^*IwV2(aYyaiNbHsH2gELK7oB({`NsG9`x_cZ;))O%a@V`JaA+RugFytYB zA*wWX-vnUs$^M8JR>uW=Dc>DTiSTPF&W2|(sMEgyP`B_r7CdJNu+@Qx=vFR7S=zZE z9W@zJwm(-Dx9Z*=+;?WMk8Vd*v!{0DA5+x%WUB`Rau5b>K@Ta6_9Dvc>@KY7 zjzD||3>%rw;)-VAJi1h|)GdLbG#@3LoN`2Ek|+#DYB~x#7&BYsDJt@~ZGri&Y+N{) z(=l$`JpY@YaWE%Z`0Ou!ar-yF`G1SnfAgE){KaSAIeqt+cYk^OJ2$VN{q)4!50sGl zSlwE4_QNM{5}1{)(#PdU^cD0?tgWSf>gvelGt-LG`smYAaz`WFcm6dnI!E%=M;)n9i{?I7L)m5J<9#Urk3zW^!U{yIQ+@9Z~19;P(?? z-$rL2XfaZ@@2ZZXW_xn&E|T0GFMo($$@mtSo+T(Zqbqvq$*$de?9ZVCk|Y z&USk!>kLh&+ZEv|$m(1(j00vd`h}9x{{Fl3*k4BW-(`~1HFCFK1iu?i-P<+X#ms>O z_EJTd+d2Z>N!i4^kkIcb^pH%BzDz`lB`*WVKr1mT>?8tXL0JM){2Dx$_!hf)j(gWzFgsrNoiu9bRW5vGz{=)R7P`bS7 zq@g^6heJe-^ld@91aKYA4@|7&79XJ-8h`Ew7P3R<3&x;s@jIc6($8-oZwvZOFeB2p z5zEafO1UKU8z|{F5XsTgt%D{5W0)!ErBgGC3*GmEgzj&=@x#A+_5ArC z3eh?K;^Hkj8EwL!ZpAh{qNR9AbWO`F(ua=%;dbWyqi_88TV5`?0( z5y|ON(@oTih5W|v;`6*1TRVUbq#HTiy6yor9i4l${onyGox|202cBQ``UTACSFTV` z`e#2rJb(Bw!HRF+D=?qSBNLyGj?O6}d~R+oXU&hEz5>M`86?vMj&Bm4Q%ZW~9`TG& zDtRo#m7t{WERk6qPES$lIkI^Q(Tcs9nR96ECC8gix6k#`(TCWRF$lGRs!HeB!dT}+ zontvUV^L|y?+LL{X}wVi6mA0EC%@XStlA2ENdJp*QE3c$uKPnE@Qe1SiO$8XmPy94wvdx< z1atr$Jm-EK`BOBbhCxa?K0O*g988VCNRkqpnVM>7K9vz0wH!aXk+1<^xn4xU#yf8= zn$AYzcAuQS^bzcJnjOgc&dZ_=sil}pQP&Z2Ht@{bGv0JdO84E{7o6^w%&qf9Ko^GV zrI=e8*NgRLjon3UZFQYqiS-Op(=}v!@qe&a2dJ|OB$6CVn7L(5S2W$Er>wRyuJBXD zbUGQ*nQ_W=#&3iX*a{0-#-Q9)#ckfdEdGyIA&mP5JA`t%_R_Ee}XUTdojQ$0o{X<1EemLU- z(|;v3{qB5m@u_21%TAq|qB0Y21)+aM?ty`_>R}=nKj|O3ntzJUktFXS`A51y;2A_( zWOaZY$B8^BSLu?uiyXq@PcB^f?Yr;(cAgHKU6aKZK7Va`vVZ?b;VaGLkvKY<`>qS- z$zQY}{j+;F?~z+m_!B>;drK*+jii3Ex{I#&a5~lmPn!~S(9-MAovR=5b`gkjwRU({ zZEab8K3aMr7MWljskd|#wic21&h!CP%!=EW88M#r9XE1%($Tzy_~j*)a?}JShH8Ff zu^KI=^ed@S5(@^O3(8u)@XmC<7f!FYMdGIktu8Gr?65_qr-RC^MUTGx@BjV3|JI`~ zU%C{RT({qra3$0~eCsQ76D-GPfZndQ8+OpdG$w~t2PaeqiwzhgJ z5%-PjMVOu#NYsl2f63`eaBob`FC)OQrKOIfm#xK2Uf_pHo=~ zHg!J^OHc=&DaFL$VTKfB5S>a<2>l0QV(IEWm7RMkX5C2XZ@&3clXiaVxi?M93pzQp z4w$P-RIV3`&xvg@ON$c%U|n3UVo|hogmj($Tn$Ojzp9H&9k}uhk{W;US1>wi`uQK8 z=LA&$?v`)&P(ixWWTk%_v3twLH?gGy)iS5|NKxOb_(^2+TQ?{M#n_UzvuFLnMnmSk z8x5YLsB@8@aAa@XC->F#^__Gw5~QnltA*>F%G!?^-CstEAWm5*&UA9q<#`DYGZmyh zZ@QFp9@MDmvZXV|mkH5D>Ed)z`WMvn=WAfb_Vx@~66zVEXJOzP-TSlH*B z4HKg|C3l>i3pr8C=bUTCqV}eY#nS4>$@d}>{OKb&K*8sl9Q@?!B;-tkYJp|Gedhq| zsIeRjA(^Tqg@Q?7fxt7v)94)<>+B6*wsvnUSbrM_I{7T`k#L?y@S}4{WK zvbft5_C}~+wTB6ed@@W9oC^_Ql+9UxP=DalW?^i`0}|}Ye@0C|&h0EnHm`WK2>Og! zTp7OH_a-EMTl|1{$}j?X+|orC%V3C4cK_WsEqOfCw^I5y<{C4;_@w0pmcOM!KyEPo z2n&m^T|RWf?5mkw_+AFj&3IsX;d|ge(zDe~@iD$B)0gWV8o!HbEM=$GFUQa@wUThU zd@90pA-4XY!0SAIbk5&;TEcReSVk8aT;yZ-8QCq9j8V~3p?g1|ODi{b);|IM8>yR7 z#=-V9Gb2Es=MflqR&dh^e&rU&>ms)c8oC)vC8o0^QQb1Z2;U!iD4zTkAEz^6Q09vK zJC>`(i0TiUu0~o^HlvVTh|jt1t_PJl-8u-$d1}1^>FMe~3X5;%Hd>=Oi8x)sl$Mfi zQMv``JiKo@AQO@A7rkA}- zd3OMUVl|x3Y=EdiLS8&Af^jr%oWJ(&zojfy$a?D3g;lT3kMxg-(}{Yqxu;Aj%-l6$k!x9C)Mk zE?sgI29t~;B;Q>d*;@DZ+jY_TT)?v5*m!IxzbqX>^#n$`T>!OvAZfs!Kf*jrj{J%l0k5%0+K>vvCFn}*kihet+m;k*c`zqp%;km_66M}c~d?;Jq4 zQPB+2HnYpdG!v4~M8j}8k~U$Q&};w`P^Kbo^mJFic2zvni%SWOS;{|TYp~ac1HPBQ z#>PZU`uNFR$;7=d0m@F^o}Da6H!i1s-1IsL>m)R`1f?_2z>0(IzEHnv zO>x;f)od>;C~~yc71y<7CtDdcL9TSgG0JnV=*1xU(|I3~(@Cw7n%>NWHwnRAw`QRhqUyIZ%9nHK>ZizFW%bpl$m!Z zES>0=Ej{Smc*oaM^~ss>y=>VzPMjh-`{g%pe3z8;h4o;1?8aE$!gFaz>cDy|Cuz^^ zG-5iN2~IcoyiAY|rCX40oyw37{!3E#b2{5Kz7r{(I7TpCF)zNLm$mU$5vienBbo#0 z64TY&NSw~I7)-ZN-S>;yu>*U>XkN{0uM5+6?AXyTarneE{+8+Dqi<6rdST+V7f_U* zefG~x%6Z1;M3dy?khM5A=XCB6+pAd$5ibf<=lc%l%V%bJ)R{I$lwxoD#OPS3b0G|A zJZCJYghEOjF}ksHE-E~#CMO1$N)(=!*o5!}FujD1o;gk$ho&$kpxbB~1)8zgw=-$w z84k8DglEztkjl-p2<{2dHuTo?rp3p1#*7nmPGPFP#IdcA#NvdVv7=BC8bz3coGeZn z69M1krUTG-l&5mrB&^774$K>uIJ!RH*<5c-D#~qXHzlMXHuR3T4x&%UWe(U=CL2f=l5aL#ZXD?rn)|hL#C5pZQo=1rx5RWS%$!Msm6|TWTo^7fU0S-2 z)3t^l(}PrxXdcHxaACNA@M@8uO+|Qm8fKDPi1kpXCNDf!_gavUP=Ga*2z{vMBMhIY~^3$ z+bZlVmK-Ko&755V+m|L7pH<)xQiQqT)H zE&<(Qa+8}*7b8qB)|y2*odwkNmr&DZj*)nd^i2(EvFV!$U>+j_yDc)*(NWYrP*!`j z{~fwz4()0iVn!iQpXG$tl*G#nvM?P=C%GgL)SiOG>ndkwr?269`Rz5?w1>8>S~ZOs z`P0He8jcovjF7&VzIg9DZ@)D1WZ_$93sKnB(rD@!lY};EEphb2=p=X#;Hu6?P_IHN z58nOFbFUPR)Dc!lOV3?b^K0n`l@GX;vd^N6o|^srs=JIXbhvT7bkJ8mxNu)@%y{f~ zlCZs8I_m6@T6EZC(|DzC)zVI~Op%%=dS7v46$E{*mfx za=?oUJ%qkr-F0l%JyQ`^SGOUcs3`bQJ^_YTakV?xBU0!NNahxeG+J$(DxNLFz%-EL zZgvnD=w{;J&Mwb(Phl%BBU_*S1iaBIrRjHFP4DVbhf=h2PL#tl zaJnRQ>@Ve6P(2ndKKq(cWYZ|Lma1VZ>4lrS0%a~g37;FiI5ApOrp z*~XQ=QH&1sTbb#4I8!Yuw+kZuqTNN%t)t{~L+h57PLI(yaHGqi&Q%i41?9qaE;24( zJpWfLDw4;L@qzD)A@4GKt? z_29pT(j}qCQdj!@H2HU)qkdHJ3%es4M+YgwTWqMcVF`Fh^%T`|OWQ5297S#Ie5Z`I^rU=FB;%w?YR_>n%CFjrwJDbI?^)qqwqZMT*OX zI?=IA=U563aU^E!B%`AZxf7#vnKca)8AP@aBoBqsQ!j_6eonOXuqZl^3ZuzEp{z19 zfdun0B_7Y^P~nLXo)SBT-k#Z;5CgLda3l7vT^2s)gpzwH{G_iC^0>aVrI3wsCmw|# zWH*pq9fwTjI`Av59_{5z{*IOmkBikyco4!PGg10S^H9@4br{}v6M59{l)&ZeB!JN; zXinI08yxS=(Z(a6g;&hoc?~dtN@>-lloPK9c2oD^ZK}sD{sdYgPK0spaNH6fgF(+QScr>6(?X=-<9aX<*UM)p}C5Zm>A| z(n7*>16Xa;^v6O%)-GQ4HfxQVj*%yp|J+>h;LBLN-5>EnMM+5fmlM+=N`vSkOGB4H zr_|<0sLKo|i(Hm;DdHk*I9bVpfjOWKoBM*(1@7kVhT=u)MlCl6b-o?A;Cne@b#u^6L8~p-i!r79 zv~;}~O$8YK6W_exVgJW@WwxY8#JOYw>c9`SD{dE1u7#h8hRkn&l6uuU_Jpcv#s6u z(zDBFNWF961Ev>`$0Laz2SY#-MUSqTvH%J))l*3FAnIUS^%Pt;MX#Tk0n}ma??jDH zxf6rP9Gn{H8omZ$_n&?A?4vKe@{-?vE=E^OxbNcUqI=4{?>B}>-pS=J6 z6{PQX?-m#LtD|OZe$^>v7G1dQJBk9z^4t2aeWJ2Rsh*V(`l-p;$>PdN^zZDM;2@OV zt2nH+!@$mKI!l4*OWhrwp=)sZm1`e-Fbt+Y|JuCQ+frBA{gc9Gni+j;+%85-M@rv! zX5^KhymBtm-Du@HPJJ|ctg1OWQh|x;{Dh??Jvew^R}~U#AeQ)Z^^R9w^p4={#-T!0 zCHp*F=|Q1hx(ZDzi{|k3@YSw*st5zJk|?os1w<0|vJ5#LOkYx-%VO&3O2qU;sj0}R za;4+SHllj%?(`uZ16w+ye~1FmuJj=0Mtmj^_8rYd%|$fFDWlJjXJFmBme$0gqNMDA z*)nEuWsRQ7f`X$(N%q;6V*_Q~1>IA##n(I3AS&BaS6P%b<7RtN+B#FzJ?myV#^-@L zV)m!B(GQh&NCY)TvmsT%y4y5EA(rCw?51aipTyq8;q!;VtJ6RJj9Dt@-?7P&ZRe zs1^Tupun}r<3LAmtgUqs$e8Y`t!TvWjj>y17a|xBRjkXlbaW6pw7CVNO>o7bb%)js zRFzdlqmCcXJ5tw*oL(7iAe|ORK(|zUin4L&xEclZhsr!v>8`3`K2Jwho$RM4>8Z&f zZ$EN6e}#6tt*Du@PYMNqb$ehUWw7>SyQ6i#XMZ%^W0_Kw^7bf2a79ue;+8XANiY1l z1P4$Au1XLat0_#d!|U4B5aelP+R(V2f>+hBN=+|UGpy(;a^e|G@N9{`{|3hNvRSk# zPTy%5T@i+Il#8MvbWUOGpWdRAr{!tc35!GHl8yzkx(Kg})H&lEyuBsu`@2%oL39Lq z1}Tp!9+jj_A{>#8Qz;f;&Z z(k}w?7cai*2lex}-ymKRP$xqDPxfL|XP~3wdNE_u_+F#6KX>`Is!nfT{O*nKFZ3)U z#*qWLFGf<=yLb+(I#eo;W@gsBfjKnK!~>^n^``sdV!K07uy`uq<17?GcT zl76GtuDo-2V(SjdLUT}~U}7hAkE>qWdUApaQ@B;4ymO2%C)I6<(rH2jtBy8Ie4cX~ z-!;y2$>|dfDVxV5dUH=V^v17GYdT$$lbRZqLfbY*ZeBZ%ZuV#QMj)LV7SCzNUV|g1 zCrTBey|JC+1S|IFdys4vDo>dq$RY!j1LH<9$7`O~?&La&*$CTw73&*ajLo>C6K-r| zaO;w2{0>o!650^Cds8)6@R?g~zlU-zn>o1MgxQ>iLrt7>nFl1^B`4>GrU696=+1N? z#cXb#i)VH6a=6_M!fI6O8y>N+rsQC6TEYT0SrY{p{x}ZSnDOy(zSAFHgLMZ6p>v^% zT#cH}o&??nB>ANn0pe}OBR;3ezo4dn0n-(=*v>nMd-$OLeL(zvyNZ96&hxmXd?zJ~ zvb&;Me8bwQARCKMlP7j@(HbLV{lOHEl}SzP{6vG>s{1r>4uk{hB|9`J&Pi2?XlkmD z=hqkuJ7CXWs3oJfA81#q3s}z?j&vwpN;+|j3E_{4eF1AJ*1}_r&3MZN&zpUkI{G=6 z%n+@ch!?X)FP3|m?XEmy~W%y2)(k8vfm{mEFZxI=b0Bio|ps{U_Qvp*qi~CA=We7gu`F%x7i>lCu+MJp+jb(QSbP_V8@mY6>G{}R(nEu)i)BbfSEKn7F^9NqBqnMhq!StE#>)r0|>mBr2>Mky@yNf!q zXS$1Kj$S8+rZIaUkj}HD)C>%$V6r-BHyM*ezj(dg-POCj(-P17?|SDCV;8zG|DwF= z{U_!@_!0Sw1nLZea7dNcfKIECku^LzN03GcPs9{LC1so|kxhqjCy;kMfG69Xi1Wpm zScoZ9fkk;%Hrh0Tx1!b)YcZzlkld(JP4doBq9sKiI<(!z2U-W_P=SD?x8`jFQxc0YJ?y*M)1Z`iJ97rOMX-Dd4ZdEs0_7$+#0E_wz?=(HI zN>dbKyG-s&p$$=2I9D5ctq!Y_-fn@`C zwKahBZ$Q{^`kz};I(V%-6yJc+fpOq`=gxod!8v%2j($s8y4A!K4O|`>$>`LisvGGo zwKmej-Fov4JTIKT0kNAZQkYzAj7;95fp3`If^egvi_}4MolqZ&`COE4u0c$c>xR+jeBz>$%4#Mq`}^sd;oJ^pZYKji~UvhT_n%6vU&k%qUoVP6d)VIT`fW z&Yh?s`n;W$n9tFPsU&r_k3ANV)3mS2nf6#p!|4VmQRZu-1kaG~D9J5wc}|+?8p^lO zV^O>yV-HD)T}aCzMiD&?B4$swv38Gw%y6_Fw$4{Kb5~-|E8-Vr_us?xB|Ph6Mni}G zBYeWX^`!SPeRT;Uy2QT<9#Cq!N=X+nWyzxHMa=J$=D+w#{`fCB8gjps?_7QtV@-!M zK}+$gj>1bJ$#X zZ-)N3Wl9IqbJCV8;aqNW!{)~2?ent;vo%cds0G7Ifp)RA?+9X>+gPs>>kYZ=R^uVe zD3Z~6FPd?fa}l&}m4KRetj95H`0uRe=V(CP#Ju?D3j%XQ00Z)aSVT@I1|~SDi+4E10hdZODSy8o$aCL3=NR$UVbb2+MY?%FH#)}~{0ne6MkP6OKR0(N$wki+Pn>qp(hLC(yScVA~S@KbdC zZ1#+!qprZ+(cOKCM0edx`8n=D4^}7M>HvZ@ww3hKdbISB;jWgp(yLwG>fKj|r>BRn zO^*zZygog0;sXAc*I(}^7skBrE^2cLi6PZdol2>HfH%!xmjmU>)GfDEf$GgP@}xN0 z#j=ApVLbTQiac&&QsM&EDX3`m3P7FCN5mBoenNUmpeMO39Y#;bk?smMrWQ;u@{C~P za(GG!oUi5&Bq%-57F|sdhO!PDY5(PFE8dSc9r&*F)>TH!nT{=%~fM8=1Lsn16b51?DCJ2rW#jCToM2@t{mcaDnb&ZFXP{j(RudJZO zQ(*Nhw+M8Ujq#m-0Ela+&3hrYk>rHiRo`L{I+!EqTiC|MR6}!ULbRe&t-Wru`Y=DKWFXF zIdCmR{X>~sG>pP7E!`N^wc-}c?sL5m`*Qx)pIH8u9vM;SY=r9t-;2fRyjS^NZlR+q z!VygWJ_d9=FF<+%f;xdOyb;yMCiuj3CNuGyAH!1)ryKR$C!6ccNa?tStW{hZ?-b1o zwkaXqO9?3_{6vrpx}aH8IhteTu&}pU-@4?fV<9o7l9JxJ8~|E$uJ2q4-!g>j zYDJkFZQB^b%{9GPO4=zy^?6>nfmV-_f`|XZxqW6r${1l1Aa>@OwB->%IlH?f!V)m6m!uK;9y1;mmO}NYGc_uT+~zcP z($_qn_rlXpKh2Ej$FJ?!y7lDAi4u0%lk^gscc%%P3^NP#`LU?pMalR}0FQf?L$*H4 z$bYMvZjx2VF^{>wTL9cQ9+uyIM>#xpE4MevFS;^7j&W-gST`<5(_fC{-nTX+K3f~^mJkTqMUAly2xC{7yrTH^vyh*FrKxFptLBRmD+e3)~4g(aSmC~{`+b= zrWe{Rk`iG!y($r7dfTaE^lPj;v**m2x`I8Gbn{t#DJkhvRu=x0q-@d{t=^;3DVvcO zQO%>PT$o_XD^{#NR8fIoxvqSBvXss?ybZWwW&;t;#or9fE>%Kv8_{^SDpmZ~+9O_7dmZNuInc}~38F}%X{p=q_GOt~jE*iXogba~ z+mJr`@`v)kJTNR=$D97>%V#I)+-KDE|9E%*{%K+tkD;8yPF_G4M@M4Y{Pa8X{YakP zNyvS&_{0V5--w^Zl^ru#0l|?~o+)S({|;_)G+Ww>&d`muXliP<|JrY_T)8_xy#Mgw z;>lyCbY&)(b?{!gfD)2V*dyoMf3BI<%6kg@ndEFZ7`Dn03ZNKL_t(j$7bzx zFs-T@NGGITGCD?MHWLe>k%(z%=3O-$7JqSVrUSzb;JUq$*KqVuP> zzfM^+OnY2eS!Ab=_w*LvdRbk5^bYNgatjISGkJ`nbVKU+G7=LbtGm31w@nXyu(M=Kf_b>jS+2egr%w?x;;C|z`3|qs6)T87qmsz$+c;FGlbb{5*Wq&~ zP7IICgXq`xj||^^{qBg@OF^kMaQ)OPO}(BBb_Sm^Ml|t3)m4~aqFX1)`p2am$^4To zXYD1T6jyG1Av2bexa94m6GGW5{K2Bx8ZzMdu zEW0eIvLA2yab|w{Z0V;u9bueazH||-qGp%O7C!d2=D6f6M{z-&t$FZxUudu`I!F^< zSzFY`3AY$@j+(BKHIy3x{&qOQtO)O2OLh|$r`{h+?c>po~#R=P|t7k@4(U3{)3Er9NC zT$WK?^bWtv_F`3$zWPJl>EGbZFuu0_YdBvFsDD9C-?U}p4H#XNe*XM_fYL27UHy&_ z(J3XB>4lI<#B^gpLFQKbP>d%wLS6NN0c5fJhwod`cX;g z3S>k~M@{!3xgHHCyK$v26{9~Q!k5mjfn*ip`$a*&bFryoQDbxuC11svk>fl(efaRU zjIFs%xm#aS+k!@aSX%Tr4R2TPo(W1xF`4jn;;lF5Kqu z-W{$7eUa32dfRJQ!>y&2%dUg=UXzDShLJ;Yr)B^~DwoL|-5iU|9Znfkhvso*US3XY zEJ}CU*v44mAydM`mdl94d?htAHicG(rj`v%ztf(EsbwK0try2RcgxF*r5pL0nkVv} zuX(}w^wUqQ+VNV$>#rYgI^IBKYbrJuHV&JRJLWlW)UZj=m%juf%Whu8%3MAFCxwf$&52TZ=la%=0bFA5*g=*4JnB{tX^nTA8}`k&yU@9*#Qg zk38pEN%)ITx(}J(Fz8BQy43U~c+>Ac{h~L$nYH)l4ojBgEI!18Pxwc;yt1%8CHA=4 zDe)zHca|SrbO~6RqYUbzbrG_pYK-5O^F@`Usw1Urow9et0ksX~oVKB+B{I}5xm~9k zSkaBeMSt)NPIl;2rK1^nHEUwSP`x!35UE>FX6Ssg1>sy_LS1}BZgII@l77revt+b% zGeei}#SC>HdTboyi-dGvQo5yY8%X#2)497C-6zQ#2wwzsSY3E-A-Y*I&ui8gNY|Bm z5rT4S8lagDgGaaIbguIMrdQ$2ws`C6ydLUZDe9{)rN|P$yp7oEwq3_4 zvc%@l>TMgIzpGhHV}MJ%R7#b@=@7-TL97yF()+&=0>TSbq^vM^YzTo)U)Y zHc#{<@Jh#1JpjmFTGa--my*X4iAx&=TyIj^GKQF4rKA)R7PEaFIW@RJfOQ$w(bTiz z+yVMj@?p#_KZMG@V#SJe+qYxwZd`XLnO`vvuLL6=iqB#xd<^*>sz?rK3}`86I=HRQ zTSt+G9eLZ1Iv!-Vbu{zKwQ1_$X|d6<){I71V>-KKrnenNO{a*I!;r#Wh+E<>fL$s4 z#ZV>E>3p+Y|{|#V4Q6at;sln=TMB*ZfxYguHiaNN8 zD_uMeiSPUe5jj6!I8`2_SqrK^M-C&dbo6sP>57dJsGEMImYObFCy9|nMjx=NU{spA ztS>4em2l4C=lIe&=Q2DFozvgQr={!C&$-OHAO4+*Vg%2BfhR^D7zFiK&%X-1-;$bc zFkNRBr~A}&#Pm%)Tl|(6)buyO^l>6t=MvHl zsdF~21ofV;LGR0!^>iASxiG!+zL?&LoF1{aCqkANlk{SNI=9!bHJ_3lw=ap}u2hXTb3=eok5@Zu6L^%ow_a=8P%p zxKmE_PD(`aWw)b__m0I1Sh1O7WFa{XIb9&lcQQj>bEGl8Zy|8Fyf;m%xd5Frb3&R5 zC=G8*7nci0KLoPeey`nl(oy(x?jVcjk)8MViyt;XoW}y9B3ZCTzw4*d0&&6x+XOxR!J|tN_%%Y zGf>M%5&9a4O=qusEL{!1_iXA5tA6~%6RR|yCmBQ)Crzy zC@~InRf?*^sO51%OBbC>L*K!fq;)JaIkEU%KwUW9K(|i00HPby3n*^z*|^XRj{7lP z*XUr_o?DaLt{rLCB;7~pichDI6!bS3ZDF&RTyqamw6$y)U0OO1qr63)U9U)@xgm2O zs7qFtIL~V_=5;IhWwTzD^>Er?J~f>sxzf#HF_3Y|>TGhqsY6rC!sI~YM_Lr|<&OSc zx~nX)$kws{%-bi<)Ya`N4pn6*_#x9Ry7wg@T?QE9EF4&?t8JmdRH>~LsN>;vyRr?E zNP>g}J*`EwKO)vTJ0K~E%tg_;Yal>G9+2HgH_xPi03aj4j%8hIfpjokgP6iff(k2} zIjO5_8IE?l6T60o>qFgBSTsm_IWZ#H{7FOU7KdBX`L|wDktpLV-gN5tB)p z|LEC~yUJv-Fn#~@v^RTz*gsFJXTaS-q~T2Eemam^lul`2Ys=ulgBQSb#w6|+Tc8IK z7_pxh<)(zOv>HeU)5$h$!Fxh3!YI`kwHSJM7loBl7T}IIQ)jIn&^+nx88c?9C$h+|HoD0K_ct1eV{#~ zri1Bp3%~NqUtW3r_32Q;`jTcmsNs%R27AZ1+_|2F=OL@3VPXBk?e3(k?LqZ41jWm2 z@D+Y#k40j7%Y`e`!~Itf(m%McZGIS~nnp;xR8<$N?o<_#Hexl|I1spn>er=^&t7Nu zLQ&;R5|mzNKl=93vo9T;xpbC5`0LlZ3$DA9Fr^>e1KD?6FYeAB=X3R+HD#sV{qy^~cF+HEgif%=rq0}F`r3*97kzo^yNP{it7p5Xr>C>c z#p^skB2AE5SftObt))50)l3Dc+1#3uFoMVd^;GE-zn!?4sv!L7s=8oQRAf;iq0e6c zy7S8N6{}aSNXC*w*+zQfq1r@j=}75p3pE5Fc%EuhnbTJsVqcW4?(p#w6d_bQT=IsW zi-enL;MyTydZ=l>>ItlEJj9Ss8>1nh~R<;l?Gdo4b zQlqh}t;kBZ@exZe3!*EQJTqg)|#h{ScJzU;(;E+riW{u|IakMa#!)8$UTh1taj>TgO_M@;9;v>`Qe`UBxE zP(BBpLh8bFEl5R|m~Khw($iV@^Ix3*3!|?C=ZNaY_kuh9RY3jx`8Q=w7pi|vhI9%_ zw>+q(_iWjC=i+-lG5yXhH1i%Ho#Rde>TbMs#+v^V27$Yol9Yx=&m;ju++xSdq*CPyCp^k7&WB z32HkfAETAG<5-#4x^?2X3QH%r5()YHV`JYZn?y0@QDbR%&#`axVk{Z0NrNg;&et^E zE7+GqUSiF@J-Io{=TgUN_7$)M{2Mi$&=c$&^d2QWk_Q=MDP}CSGa)B4mVTjtZ`#;g zDgZxP1A5DJf{J`YR`bz2=-I5p4`LF}`D!(GbKslt9%l`A#x!lXEp^-v>hhleSe5ZS-k0YOJa2Z**I>S>ktGkY@i|lo$P>hyNub zN{$uM;=hA+Zk}|}5D$DOSnK6Y7pAY=$HJmUFHAq98?4k@c*y6bSyGW0?I}B zMDq=*!%d4La}hnAn}O!C??_ZP`v-Jc?^VRkTJgI0TTkI*baA>FW)k7QpcldoIkDE5 ziz>I(!!4@mX1fX4&1~nsnyx@b!|BR;2}Df~#l=EBAtj$xNZu|tEfCKP?yu|{EKE2yhk9X*E*_g{t5!E|eEJKTaxIe->G zLCNPfjI{6VK~7(?q_I5f%v?-o?_fto`S$AiE)3n(U@OgMAz1bXqz?h-LmynY^3GLG z=1EB`txmMqR>G{1k4$%77LknI-C5a5*WFXyhSEKi-5$HGGBA?8AC>0{>*_i>p2YNW zb_zB9Xu;8$@*;v@Xph=)y|R0DAb^ZQb_2AM2S_%H4W~3oiomB0$X0JD;(-W%sYcB2 z>e}74e_Q{HsOrPROdRfFI=XvpWEf4|xL>Y9>ceeaU2r-mY+*Y0R;DHLKT(a%L8K8$ zSJvRI=txk1i;bBn{_~(vbH{wp8#XTNcnvSKNy+XLh;B=SWO*b$KPqF1_hf+Ge6Jff|lisGL zMw9(eI{BYo7QChD>DXS3JKfWat0gd!OmxHguEOHF;PU3aK3f*Of_V*k6UKW_+N4Vj zoQ#sriBxo&7*Hfa{kE#R8N{pFW+y$gEIU?4hogWM<&<}?BNsAVHL_}!>Z|HnZD`QQ z>2hlr*%{jlqPS7R>Ej8u1MYq|I&wM7w8gPDeSu1KrMzBZ0T>H#GC3-Q96~F zK)S5yw{DmsQq_^ll&(-l1*eO|<$f_hZk=BKIgqZ)elgupx*%O$j4u8hWM{l_@fY+t z62BX-%X#$lTU-#QQ%d@aH=fyIIDHf0iGCG*eGh@>5eD0L{)aodpFA(OZ^-k~v!ITl zKsunlk>d}P`(ng&GmTNPe*9yPb>cf$E{*|mBc;puV%#or4H@Ca7=4ES9(=B5< zh_0BI2+Byujhe1fQ9Tq}eXY6uBgXf_Dl^Qlh5y?eeP7Ole5*B$#;QqZZ0sDBi+pt% zlM7u$d*^6oG&jZ@Sm3-jm5NbF6Fs=3VRUZHiB23oHb;cIv*~*AzR{F~x%M-APLD$T znRCbKM0ybGdQRSLsp-x!T;`pWkuE3N98o?kDr_t*3P%TtFaRk-J%ZA5WG_KYm%T&^ z_#NqFa;7M`g|tQtD|bj}z#h&upgETIhW3SpUR^Rbhsp0C`x{d_W*I!}nK#smNR2_s zVblxCxJ}=nsNS?x#B=IKdvllr2+nzeHKq$WF)Ye=OiKuVoUKesOGLz+W(r~BicZ9F zzJ?H&SnYX-<~gK%FAeX?kAJ+i3Gd3uCj9$(}9S5IJeRjKCiEda+j2cNdvlLM+#ewZ??TBv^F5Z>hhpDA%Echs66Q1ipJec((7K z?m?s{ZS~&{hs#6OlW}Y1xfd-d2i-$bvaDN>!x(bJEXwr~@({jxhCTM-#YeDi_s4sh zbx>;hzcd^AL%nyO_$xse;553hgmsHR4aTA^V^PQXVl3(^6jdoHiaKh8^mKvx>D(jq zLLSUDy$uYhXK1p%L)D@(xoD9yDeUCC$dqo>bK$N4-#{S0gmG&C!agJy60^wAsabmP zB3DA%AxqKHWpwfV2+|+qbluY=*BF*Io^*rIEWzhOb=^QuVuoaNUxOp`baRxh&LE-D zdOh3$n&(Haj=O3~!?rS8%b>ZrAT6C2cfW*mwQAiIFHMWfAY#d(bVw$UjPuE=e9u6c ztFmv;i8E)4D+kGGAsvnwxM0~{z-WSBQ0CUfVS5RU3?dQ(Ug7(nXld-~cql|9FbQp0 zqUl})GbY(Vbm}s*WkN@=Bp;nrm+b5*mIDHk=_Nw|jIceaY=#qVYK9T;K@fXuWocKH zeZbyDd(S}kRFzTFh3SO0eCsVNEEbp>5;vN;oG&k*6{d4)g}rbSbE_x6^@?Eq(FfG@ zcc;Dc^QE=5jjk?lYt>YC*??CKNa;W-(bL;nynlb)z5@p@?C;+XUD2PWZqid#U*85Y z;Z30?lPqv~UUo?iu5Y3K@&j@i-?{e5DM9*w;qckVAAf`^{Ucg(lG*~5wy4cLdNQ^b zAib0xN%h3GM0@LlYLm+_A`v#O)-?=%J*1=9?AX)EdZAmV*Mt{V!}X>3v%QD=+xq9{ zKR^fn;KDoehqqnuh6)$mf!nvAi+d~gx$(VsipndpmQ);_z@1)l9fQaA7jWZg_CXb-m5sUt06rUWU>#97Xw%K0G)*po$VDBjiKbBC|NTU%Slyj zay3VI8G#mSeA1eC&g2kUL{JmhH^kjP~lYqxuntu&{oK9)kL#*sT{lc5)#JYZz@c;CzFkdc5aIf zLpqLi7ERDB&XYPr}Nfi!cm5LVy*rp z2)gm4=TG*Nn2z5?Cn)QarQ9{0-6nK6V)o>5knqE$?Qu$8Y^E-vvhU1^y2yY?rUyI$ z#h;kdi9eNyE;-#&)9u*jZ9FBD6M6$T%RIx=SEc7u3c%}|Dl231rkwZ%@VlXUNvDaZ}7UeY@&kHIA44jFP-9ajV&8>&x;rT9h`pW))s8# zFuH~z^@W{cbSQnNai%YYxWV*JAiYyejjshBw_sh?biui7FUF}(XpT%TI>xWZxXr=z zAvIAiR?y3O%bOmrZN99NN5Gn{|MkmE|D^j`x)t@}`$Z{`aWswOK$1~? z84K%N-br~VQZ=IX?WWw*`${r%YT79QEopL=+^LD(+nbp}wt1|+C{I@oX3&5rFL&_F z1YUPcDb6(X=7q;1@TNE1K^afQGJb5yh<4dTubbz@yzUYq-aIti%xW9u$vRC$D#I4nw(9;yf>u zNdSmX9V>tinlt#4rwx+{Tc*KMLPFHzq?rQ&#JToF6 z_`RikM=>j3SrF3z^~Gmd>Ejcu?)x3eD`4FhEcSL`bI8M)4Y?)DL*gCxZ!Uy3kA8pE z7nagcfte(NWBX1NSeUQtzwo3aHHKuO^E+}LVJTrr9}}HHmO>H?yjRMo&a2VqUv`|3 zkeK%4P0ok@#pnIPi}=6)g<@w|O38!srZ3A|vZP=6UW|KG!Wn(F zq?pK1)M0O|=?aI1(fQjteWLHok=&Alni8X$1L%g*1?he*oxjDroP;oW(iy^J3EF1C zI*~MOF6(+?SN-^xFxWRke6%MKARYRnG$Im0 z5KrEoUV5rcklqzp9m(7za#(Wum3QvRk*)!ypZy3Mi@UJ3u&@yBMUs`t7;V;uQ=9>r ziq@;sYYFaVAA>87cg{Q|(oX-WsYFkx;~b%kyI)i&3fA=9=;5$^HEQ~N|1=>j!t{5p z5z{gqT}`02-5!`;o4nzhZ|C)N-Z(RZsbgh8K~869@4lq+?d2?d}H&ZxVuwhejFoZ|wrnUMt$wkgLBY2`t77v>$83kjRgi1h79-YhD*S`)Qc z5FLv3TfLn~#6-uhZebSE0;lt4N2m}WLcRZPfBo>?YyA?}58v%aOXmsIyp)1cP`zbX z*)P~&+Fa?FvY86-dm-e|hv(*u&>@dUVTM#-lB@!@2GHWxv0(#IIOVICSgH`Vbm}aF zw{HmMH-Z>0@(y0Pj(|i8H^JjjTcnFv(se5;wzCt7kyu)lPkT{*YiunK;pWKUk)+2E z_5!l=9!s^pN>(sxNVD-pwaGSRlyo?~*xN=DB!thO0e3+MXI>WUQW+|CFFfc)eJARu z(`Zh%+gb=~WX1uk^GX~N(%G!Cy|5IdmS70#(a7mRHVpXsXxb8!%Mx2Wy9U%8HaR%1 zoE-(cWLiMM>2bju0(^>&-$43v7~2){Vh)^Wg+Lvt-3RLu)S+_`yT$49rVGe@r!0!rO^Uj5)6v!y>Vo(U ztjqBNW6Orl3eGqH>0)@ZPMpr=H*WE|H+|a_k}Bc_GYWX#Nn-k@ak?AfOvm$rmVW*{ z#B@9_a!QN?={m^y0;TV?#B{0Y@tZrT)t8#yxgNSU{uZIR^|KyRx+SKI+DUK((xsJm zTBeu11iplk^AbVIOH9w&PPMqu4h(Jv(F5t!jgprxPJd8Kw<<{erk942iITKTl&BiK z>G7StX_=T`a#F%lV&_J4OZe71eH-&jMos2isxvPwJU*qN;54*5nii$>mW74bxj8)4 zxfAUTmKdC)ZbcEDyd}h>y$fT`2}(#o8)`W5j7z^Z!;;ehc2d@X*j^b` ztgvz*og;=5%3DR&JTc(Q)nK{8%yrg2m#KRhTg!V*xoG_e_{TB9&^8o}oQ5Ze`4Z?+ z(+PwG)!TCx#?oTdGl`ev%*#x`joCg~~?1R+BqNLaCXgaxL$7`#845gnu*>n;zSd*6aXR)c6Ule~HOGNYykWxtVW#0qRpi z?pt8|H-6xJjsH$C2&%r{xABE1HAo&)lNJ)?(Cb?JP%#fcMk7;+jKRUYhe3TN7~v9= zSIe~S8?nB5>jTgBN4vPXxuDo@PyAB7NpZRG61X&kDbQr!pM{#jO#{vX^%x8$guc*e zl;)z4y3eDoLU-nHxm45)0-MJhObw|(UBe{3XaO-@d+>5hQo04(B3^;=;((;3ZnMV6 z&AQH7v~FfCTc_yZYn7L73P*jEZi(p_)tT$#PDixNL{_eYd#l`dcuU>V})-y$EEIT#-4&|61Af`)BZ{5?Nc%bL=orN|aD zCs321`cU9_h}iVkjcbO-*!KFi3;i_5R89|}Al0P3K}p>@-a$7%4(k(lxSKKVb(51pI3Zhs0WV*YPB9(YC54oRcwS( z%0RKsGllTBAgS+WUPATg@I2j{MlQ_v-<=;BnchZB<6R|C@+vT^4|gdxQ=r~5EGPzM zJ+{_XL~M$0aV6=1xtf?>FM;0HJC1Y`ea*`a$5ArbS~l)=0@p`WKWgE^yc88%DT9$EC)H8 zL8^ZZ#A-&!dZDM8nhx3?h}EU5Gmr4FUxeS0Da$2z6Wu+LIj}fg&h*A?K0oCv*#)5Z z8mv?_bjn`m`>)Uc2MyUT;wd9Fm@f6)N9e}%Vi{l1%K>!bc+rxfb7|}{#+Xi|rYe-M zbo}UYx^UpkI9^ysQ&X$Gk@R$gbYoLz0b*C=i{x}2I11KH-r{$E?$g$-i$2SXG;ovk z@)x3XEy3hEh|+&?-qesvPQUmK-UQxsOfSauB92B&mzut5{if$GD~r)!`o)bB(|e4T zZsc?%^_@F~>cVv6Okc{zA$D-B94noVNdjLqr&|iT-|)g*z;q?m=H!U!1<#8F^}WWL z-q|BiU%z%el&(HT8r%h^y8gv8xRc+OZhkEy6W=ci%Zrn~L(Z`U8fW5dA%~@%bn%Ao z?4uY9tH?w{&fG$0=Z~VEePKsKSo|3NmNP(W``iKwH|U9mH42&oz}yvU3u!GW5u~(` ze-bq|hhE;$R3aYd2bo@)H+nWjnb@v{*LSqWHzcjI*h{`5jX`f4Dc#_@yyN7s$oRsY z^&q!t1Gqpu))ucHD(~PCyORoXbCvqp831Ja2 zG0WF996y=y^#8i%uN8p)G&kly`+>YQ38c9=o$bsU?xf~4kg&)MqoLvS>3u*1ud@m5 z985=0Z#sG8cy3dMGnLTvyu1wdG2{u@wUKxL&1$|B_$Wj7!+B@w2BSh!d@^jS#A-&< zk|j$ya~3RFQn*jR91@bc?~4YKBflHKxVkdJ+z`=4n=En3bI5Kp_8$#+Twl_50h~&?e9cTME<# z?M4jNDlT)Tqon4wRBM`cM+v5oM4&E7ovarr>c`pfmOFT2&tQ|}bgJb2!xGbFNmuoV zkijb7qj8e-z_nvP-JBRCI&Z zdMkQ+JO-DImM`x14V8%MVB~b4rfzVZl^T8?Hw&}}*4AQs8EV%hZA9ORx#-{6* zs4zX4{p&IaqtvC_0u$*ZP9kE}vA)5AzC8tfQ^kG7v-wnhW@AvdV^fzs-84B`QJ%GK zdsZWQ`gWH9f$oXe7wB#nZJNUnxL%PJFe4X)?qd;t0JKgy=?s{Jln%FtR(kTmbTVLY zz2HxGWzXm~)*yKUkBz&sGP)GQf=7f(H_1TE-$auaTBaA-&5b~ALArJNB%YTK!StJF zEk<9|+qEE^hx3e@u0Et!?p>eUf1-c5#dB<`n=V6>pIo~}7$c>bqI7TZk>mTeO&oZB zYwnRFhb4rvwv9-bHn=^z>a#wzP<$Y=CH*uxUlD62| z;;1J8olccO>g$6ag8uJps}>KvC!-gS8KVY`sW2y+#HrTv4Hn!9mzq zUaWs{q<)0Wa4vawdK)5gTmLla?)^h_Co+S~^HSvWI9GO}*Aetq;pv>79%n)M27DX= zZ_mXqn>#(TAuA5YOcxGysp+H(62~|X?N3i%o1T7$168R*OdYC7PoY>rI|xEKnh{AJ zVH;NXp{s_?hlpzjmn}*k9-2SZ)<%9KU9!m2Cm}|Y58hyDG);j5t3hwfEJ*1x(l8|q zr46P;Uri9DrZXX+wzV`!&x{|4tj78-Mf=GbV;vgV&JKqENUsD@Kw?}`Q=kgGY32!twj{(V%uRy%?ukkDK2RPH4xf6 zBuqD?o|O!WJ8XrM*l$2|x!i+S9I`hT6;Zeu#H1{%JRmNp6z@O&bR_j!vQ(0*+~nX? z@tJ6=s`4~P#^L0`&(8Z}RFkCGLW?6sJT7UhT~}-5bX@6tmfA?7PfsLkk0YzvYf5A-y6iI60uXH8PoWA@kl4&08g=^RYAj802)R={6Vpyl}oSUvAYc zDV0qROsq|&J?ySs1Bvm-S*G-Dv7k)6L<#=;;D?4RdNB{paT~rqh$uSYG~

    - Overview of LaMAria + Overview of LaMAria
    + Figure 1: Overview of the LaMAria dataset and benchmark.

    -

    Figure 1: Overview of the LaMAria dataset and benchmark.

    ## Table of Contents - [Installation](#installation) From 3d212d6f37d3ea761f88ab6ea3a2fe2b49e786a0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 10:04:57 +0200 Subject: [PATCH 510/665] quickstart shell --- quickstart.sh | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 quickstart.sh diff --git a/quickstart.sh b/quickstart.sh new file mode 100644 index 0000000..e69de29 From 93279f672d7ad956fb20929df3660aa0cfa20c19 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 10:40:58 +0200 Subject: [PATCH 511/665] req.txt --- requirements.txt | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/requirements.txt b/requirements.txt index a32dc68..8765486 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,5 +1,10 @@ +--find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pyceres/ +--find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pycolmap/ + projectaria_tools omegaconf scipy +pyceres==2.6 ; python_version >= "3.9" and python_version < "3.15" +pycolmap==3.13.0.dev0 ; python_version >= "3.9" and python_version < "3.15" -e git+https://github.com/cvg/Hierarchical-Localization.git@1252817#egg=hloc From b50c539c083def15dc0126d9b10acf17b0df7427 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 10:41:48 +0200 Subject: [PATCH 512/665] proj aria tools --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 8765486..dfd948d 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,7 +1,7 @@ --find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pyceres/ --find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pycolmap/ -projectaria_tools +projectaria-tools'[all]' omegaconf scipy pyceres==2.6 ; python_version >= "3.9" and python_version < "3.15" From abad621021859b239b51142d60cd99dbade1a98a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 12:15:43 +0200 Subject: [PATCH 513/665] pgt nd traj association --- evaluate_wrt_pgt.py | 60 +++++++++++++++++++++++ lamaria/eval/pgt_evaluation.py | 49 +++++++++++++++++++ lamaria/structs/trajectory.py | 88 ++++++++++++++++++++++++++++++++++ 3 files changed, 197 insertions(+) create mode 100644 evaluate_wrt_pgt.py create mode 100644 lamaria/eval/pgt_evaluation.py diff --git a/evaluate_wrt_pgt.py b/evaluate_wrt_pgt.py new file mode 100644 index 0000000..b2b2b07 --- /dev/null +++ b/evaluate_wrt_pgt.py @@ -0,0 +1,60 @@ +from pathlib import Path +import pycolmap + +from lamaria import logger +from lamaria.structs.trajectory import Trajectory +from lamaria.structs.sparse_eval import SparseEvalResult +from lamaria.eval.pgt_evaluation import evaluate_wrt_pgt + + +def run( + estimate: Path, + gt_estimate: Path, + sparse_npy_path: Path, + output_path: Path, +) -> bool: + """Evaluate an estimated trajectory with respect to a pseudo + ground-truth trajectory that observes control points. + + Args: + estimate (Path): Path to the pose estimate file. + gt_estimate (Path): Path to the pGT pose estimate file. + sparse_npy_path (Path): Path to the .npy file containing + SparseEvalResult data. This file is generated by + `evaluate_wrt_control_points`, and is needed to + transform the estimated trajectory to the pGT. + Returns: + bool: True if the evaluation was successful, False otherwise. + """ + + est_traj = Trajectory.load_from_file( + estimate, invert_poses=False) + if not est_traj.is_loaded(): + logger.error("Estimate could not be loaded") + return False + + gt_traj = Trajectory.load_from_file( + gt_estimate, invert_poses=False) + if not gt_traj.is_loaded(): + logger.error("pGT Estimate could not be loaded") + return False + + sparse_eval_result = SparseEvalResult.load_from_npy(sparse_npy_path) + if sparse_eval_result is None: + logger.error("SparseEvalResult could not be loaded") + return False + + sim3d = sparse_eval_result.alignment.optimized_sim3d + if not isinstance(sim3d, pycolmap.Sim3d): + logger.error("No valid Sim3d found in SparseEvalResult") + return False + + error_file = evaluate_wrt_pgt( + est_traj, gt_traj, sim3d, output_path + ) + + # TODO: Add metic calc here? + + + + \ No newline at end of file diff --git a/lamaria/eval/pgt_evaluation.py b/lamaria/eval/pgt_evaluation.py new file mode 100644 index 0000000..2c8a29e --- /dev/null +++ b/lamaria/eval/pgt_evaluation.py @@ -0,0 +1,49 @@ + +from pathlib import Path +import numpy as np +import csv +import pycolmap + +from .. import logger +from ..structs.trajectory import Trajectory, associate_trajectories + + +def evaluate_wrt_pgt( + est_traj: Trajectory, + gt_traj: Trajectory, + sim3d: pycolmap.Sim3d, + output_path: Path, +) -> None: + """ + Evaluate an estimated trajectory with respect to a pseudo + ground-truth trajectory that observes control points. + Important: + This function assumes that invert_poses=False for both trajectories. + Args: + est_traj (Trajectory): Estimated trajectory. + gt_traj (Trajectory): Pseudo ground-truth trajectory. + sim3d (pycolmap.Sim3d): Similarity transformation from the + estimated trajectory to the control points obtained from + sparse evaluation. + output_path (Path): Path to save the evaluation results. + """ + + est_traj.transform(sim3d) + est_traj, gt_traj = associate_trajectories(est_traj, gt_traj) + if est_traj is None or gt_traj is None: + logger.error("Trajectory association failed.") + return None + + E = est_traj.positions - gt_traj.positions + error = np.array([np.linalg.norm(e[:2]) for e in E]) + + error_file = output_path / "error_per_kf.txt" + with open(error_file, mode="w", newline="") as f: + writer = csv.writer(f) + writer.writerow(["timestamp", "error_m"]) + for ts, e in zip(est_traj.timestamps, error): + writer.writerow([ts, e]) + + logger.info("pGT evaluation completed successfully!") + return error_file + diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 8d98be5..fc91d75 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -12,6 +12,7 @@ ) from ..utils.timestamps import ( find_closest_timestamp, + matching_time_indices, ) @@ -88,6 +89,36 @@ def add_estimate_poses_to_reconstruction( reconstruction.write(recon_path.as_posix()) return recon_path + + def filter_from_indices( + self, + ids: np.ndarray, + ) -> None: + """ + From evo package. + Edits the trajectory based on the provided indices. + """ + self._ensure_loaded() + self._timestamps = [self._timestamps[i] for i in ids] + self._poses = [self._poses[i] for i in ids] + + def transform(self, tgt_from_src: pycolmap.Sim3d) -> None: + """Apply a similarity transformation to all poses in the trajectory.""" + self._ensure_loaded() + _tmp_poses = self._poses.copy() if self.invert_poses \ + else [p.inverse() for p in self._poses] + + # tmp_poses are in rig_from_world format + for i, p in enumerate(_tmp_poses): + rig_from_new_world = pycolmap.Sim3d( + 1, p.rotation, p.translation + ) * tgt_from_src.inverse() + new_p = pycolmap.Rigid3d( + rig_from_new_world.rotation, + rig_from_new_world.translation * tgt_from_src.scale + ) + self._poses[i] = new_p if self.invert_poses \ + else new_p.inverse() @property def timestamps(self) -> list[int]: @@ -98,6 +129,24 @@ def timestamps(self) -> list[int]: def poses(self) -> list[pycolmap.Rigid3d]: self._ensure_loaded() return self._poses + + @property + def positions(self) -> np.ndarray: + """Returns Nx3 numpy array of positions.""" + self._ensure_loaded() + if not self.invert_poses: + return np.array([p.translation for p in self._poses]) + else: + return np.array([p.inverse().translation for p in self._poses]) + + @property + def orientations(self) -> np.ndarray: + """Returns Nx4 numpy array of quaternions (x, y, z, w).""" + self._ensure_loaded() + if not self.invert_poses: + return np.array([p.rotation.quat for p in self._poses]) + else: + return np.array([p.inverse().rotation.quat for p in self._poses]) def as_tuples(self) -> list[tuple[int, pycolmap.Rigid3d]]: """Return a list of (timestamp, pose) tuples.""" @@ -251,3 +300,42 @@ def _add_images_to_reconstruction( reconstruction.add_image(im) return reconstruction + + +def associate_trajectories( + traj1: Trajectory, + traj2: Trajectory, +) -> tuple[Trajectory, Trajectory]: + """ + From evo package. + Associate two trajectories based on their timestamps. + Args: + traj1 (Trajectory): First trajectory. + traj2 (Trajectory): Second trajectory. + Returns: + tuple[Trajectory, Trajectory]: Associated trajectories. + """ + if not traj1.is_loaded() or not traj2.is_loaded(): + logger.error("Trajectories must be loaded before association.") + return None, None + + first_longer = len(traj1) >= len(traj2) + longer_traj = traj1 if first_longer else traj2 + shorter_traj = traj2 if first_longer else traj1 + + short_idx, long_idx = matching_time_indices( + shorter_traj.timestamps, + longer_traj.timestamps, + ) + num_matches = len(long_idx) + if num_matches == 0: + logger.error("No matching timestamps found between trajectories.") + return None, None + + longer_traj.filter_from_indices(long_idx) + shorter_traj.filter_from_indices(short_idx) + + traj1 = traj1 if first_longer else traj2 + traj2 = traj2 if first_longer else traj1 + + return traj1, traj2 \ No newline at end of file From 38f8469f6bd095fdb4b3fc8c0583f4cb167be93b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 12:15:54 +0200 Subject: [PATCH 514/665] ts --- lamaria/utils/timestamps.py | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/lamaria/utils/timestamps.py b/lamaria/utils/timestamps.py index 6503180..82fd940 100644 --- a/lamaria/utils/timestamps.py +++ b/lamaria/utils/timestamps.py @@ -1,6 +1,7 @@ import json from bisect import bisect_left from pathlib import Path +import numpy as np from .constants import ( LEFT_CAMERA_STREAM_LABEL, @@ -8,6 +9,27 @@ ) +def matching_time_indices( + stamps_1: np.ndarray, + stamps_2: np.ndarray, + max_diff: float = 1e6 # 1 ms in ns +) -> tuple[list, list]: + """ + From evo package. + Searches for the best matching timestamps of two lists of timestamps + and returns the list indices of the best matches. + """ + matching_indices_1 = [] + matching_indices_2 = [] + for index_1, stamp_1 in enumerate(stamps_1): + diffs = np.abs(stamps_2 - stamp_1) + index_2 = int(np.argmin(diffs)) + if diffs[index_2] <= max_diff: + matching_indices_1.append(index_1) + matching_indices_2.append(index_2) + return matching_indices_1, matching_indices_2 + + def get_timestamp_to_images_from_json( json_file: str | Path, ): From e739267fc833c06cad770ce8a34c433d3e7c0c8f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 12:16:44 +0200 Subject: [PATCH 515/665] ruff --- evaluate_wrt_pgt.py | 31 ++++++++++++------------------ lamaria/eval/pgt_evaluation.py | 13 ++++++------- lamaria/structs/trajectory.py | 35 ++++++++++++++++++---------------- lamaria/utils/timestamps.py | 3 ++- 4 files changed, 39 insertions(+), 43 deletions(-) diff --git a/evaluate_wrt_pgt.py b/evaluate_wrt_pgt.py index b2b2b07..b2437ff 100644 --- a/evaluate_wrt_pgt.py +++ b/evaluate_wrt_pgt.py @@ -1,10 +1,11 @@ from pathlib import Path + import pycolmap from lamaria import logger -from lamaria.structs.trajectory import Trajectory -from lamaria.structs.sparse_eval import SparseEvalResult from lamaria.eval.pgt_evaluation import evaluate_wrt_pgt +from lamaria.structs.sparse_eval import SparseEvalResult +from lamaria.structs.trajectory import Trajectory def run( @@ -13,7 +14,7 @@ def run( sparse_npy_path: Path, output_path: Path, ) -> bool: - """Evaluate an estimated trajectory with respect to a pseudo + """Evaluate an estimated trajectory with respect to a pseudo ground-truth trajectory that observes control points. Args: @@ -21,40 +22,32 @@ def run( gt_estimate (Path): Path to the pGT pose estimate file. sparse_npy_path (Path): Path to the .npy file containing SparseEvalResult data. This file is generated by - `evaluate_wrt_control_points`, and is needed to + `evaluate_wrt_control_points`, and is needed to transform the estimated trajectory to the pGT. Returns: bool: True if the evaluation was successful, False otherwise. """ - est_traj = Trajectory.load_from_file( - estimate, invert_poses=False) + est_traj = Trajectory.load_from_file(estimate, invert_poses=False) if not est_traj.is_loaded(): logger.error("Estimate could not be loaded") return False - - gt_traj = Trajectory.load_from_file( - gt_estimate, invert_poses=False) + + gt_traj = Trajectory.load_from_file(gt_estimate, invert_poses=False) if not gt_traj.is_loaded(): logger.error("pGT Estimate could not be loaded") return False - + sparse_eval_result = SparseEvalResult.load_from_npy(sparse_npy_path) if sparse_eval_result is None: logger.error("SparseEvalResult could not be loaded") return False - + sim3d = sparse_eval_result.alignment.optimized_sim3d if not isinstance(sim3d, pycolmap.Sim3d): logger.error("No valid Sim3d found in SparseEvalResult") return False - - error_file = evaluate_wrt_pgt( - est_traj, gt_traj, sim3d, output_path - ) - # TODO: Add metic calc here? - + _ = evaluate_wrt_pgt(est_traj, gt_traj, sim3d, output_path) - - \ No newline at end of file + # TODO: Add metic calc here? diff --git a/lamaria/eval/pgt_evaluation.py b/lamaria/eval/pgt_evaluation.py index 2c8a29e..4ed3b1d 100644 --- a/lamaria/eval/pgt_evaluation.py +++ b/lamaria/eval/pgt_evaluation.py @@ -1,7 +1,7 @@ - +import csv from pathlib import Path + import numpy as np -import csv import pycolmap from .. import logger @@ -15,7 +15,7 @@ def evaluate_wrt_pgt( output_path: Path, ) -> None: """ - Evaluate an estimated trajectory with respect to a pseudo + Evaluate an estimated trajectory with respect to a pseudo ground-truth trajectory that observes control points. Important: This function assumes that invert_poses=False for both trajectories. @@ -23,17 +23,17 @@ def evaluate_wrt_pgt( est_traj (Trajectory): Estimated trajectory. gt_traj (Trajectory): Pseudo ground-truth trajectory. sim3d (pycolmap.Sim3d): Similarity transformation from the - estimated trajectory to the control points obtained from + estimated trajectory to the control points obtained from sparse evaluation. output_path (Path): Path to save the evaluation results. """ - + est_traj.transform(sim3d) est_traj, gt_traj = associate_trajectories(est_traj, gt_traj) if est_traj is None or gt_traj is None: logger.error("Trajectory association failed.") return None - + E = est_traj.positions - gt_traj.positions error = np.array([np.linalg.norm(e[:2]) for e in E]) @@ -46,4 +46,3 @@ def evaluate_wrt_pgt( logger.info("pGT evaluation completed successfully!") return error_file - diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index fc91d75..67c17b3 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -89,7 +89,7 @@ def add_estimate_poses_to_reconstruction( reconstruction.write(recon_path.as_posix()) return recon_path - + def filter_from_indices( self, ids: np.ndarray, @@ -101,24 +101,27 @@ def filter_from_indices( self._ensure_loaded() self._timestamps = [self._timestamps[i] for i in ids] self._poses = [self._poses[i] for i in ids] - + def transform(self, tgt_from_src: pycolmap.Sim3d) -> None: """Apply a similarity transformation to all poses in the trajectory.""" self._ensure_loaded() - _tmp_poses = self._poses.copy() if self.invert_poses \ - else [p.inverse() for p in self._poses] - + _tmp_poses = ( + self._poses.copy() + if self.invert_poses + else [p.inverse() for p in self._poses] + ) + # tmp_poses are in rig_from_world format for i, p in enumerate(_tmp_poses): - rig_from_new_world = pycolmap.Sim3d( - 1, p.rotation, p.translation - ) * tgt_from_src.inverse() + rig_from_new_world = ( + pycolmap.Sim3d(1, p.rotation, p.translation) + * tgt_from_src.inverse() + ) new_p = pycolmap.Rigid3d( rig_from_new_world.rotation, - rig_from_new_world.translation * tgt_from_src.scale + rig_from_new_world.translation * tgt_from_src.scale, ) - self._poses[i] = new_p if self.invert_poses \ - else new_p.inverse() + self._poses[i] = new_p if self.invert_poses else new_p.inverse() @property def timestamps(self) -> list[int]: @@ -129,7 +132,7 @@ def timestamps(self) -> list[int]: def poses(self) -> list[pycolmap.Rigid3d]: self._ensure_loaded() return self._poses - + @property def positions(self) -> np.ndarray: """Returns Nx3 numpy array of positions.""" @@ -138,7 +141,7 @@ def positions(self) -> np.ndarray: return np.array([p.translation for p in self._poses]) else: return np.array([p.inverse().translation for p in self._poses]) - + @property def orientations(self) -> np.ndarray: """Returns Nx4 numpy array of quaternions (x, y, z, w).""" @@ -318,7 +321,7 @@ def associate_trajectories( if not traj1.is_loaded() or not traj2.is_loaded(): logger.error("Trajectories must be loaded before association.") return None, None - + first_longer = len(traj1) >= len(traj2) longer_traj = traj1 if first_longer else traj2 shorter_traj = traj2 if first_longer else traj1 @@ -331,11 +334,11 @@ def associate_trajectories( if num_matches == 0: logger.error("No matching timestamps found between trajectories.") return None, None - + longer_traj.filter_from_indices(long_idx) shorter_traj.filter_from_indices(short_idx) traj1 = traj1 if first_longer else traj2 traj2 = traj2 if first_longer else traj1 - return traj1, traj2 \ No newline at end of file + return traj1, traj2 diff --git a/lamaria/utils/timestamps.py b/lamaria/utils/timestamps.py index 82fd940..b797390 100644 --- a/lamaria/utils/timestamps.py +++ b/lamaria/utils/timestamps.py @@ -1,6 +1,7 @@ import json from bisect import bisect_left from pathlib import Path + import numpy as np from .constants import ( @@ -12,7 +13,7 @@ def matching_time_indices( stamps_1: np.ndarray, stamps_2: np.ndarray, - max_diff: float = 1e6 # 1 ms in ns + max_diff: float = 1e6, # 1 ms in ns ) -> tuple[list, list]: """ From evo package. From 7de41da0f75e8e099a0016010cd3ee622350cbed Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 12:31:40 +0200 Subject: [PATCH 516/665] argparser --- evaluate_wrt_pgt.py | 45 ++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 44 insertions(+), 1 deletion(-) diff --git a/evaluate_wrt_pgt.py b/evaluate_wrt_pgt.py index b2437ff..ceba304 100644 --- a/evaluate_wrt_pgt.py +++ b/evaluate_wrt_pgt.py @@ -1,3 +1,4 @@ +import argparse from pathlib import Path import pycolmap @@ -48,6 +49,48 @@ def run( logger.error("No valid Sim3d found in SparseEvalResult") return False - _ = evaluate_wrt_pgt(est_traj, gt_traj, sim3d, output_path) + error_file = evaluate_wrt_pgt(est_traj, gt_traj, sim3d, output_path) + if not error_file.exists(): + logger.error("pGT evaluation failed.") + return False # TODO: Add metic calc here? + + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description="Evaluate an estimated trajectory with respect to pGT." + " Requires a SparseEvalResult .npy file." + ) + parser.add_argument( + "--estimate", + type=Path, + required=True, + help="Path to the pose estimate file.", + ) + parser.add_argument( + "--gt_estimate", + type=Path, + required=True, + help="Path to the pGT pose estimate file.", + ) + parser.add_argument( + "--sparse_npy_path", + type=Path, + required=True, + help="Path to the .npy file containing SparseEvalResult data." + "Result of `evaluate_wrt_control_points`.", + ) + parser.add_argument( + "--output_path", + type=Path, + required=True, + help="Path to save the evaluation results.", + ) + args = parser.parse_args() + _ = run( + args.estimate, + args.gt_estimate, + args.sparse_npy_path, + args.output_path, + ) From 5ae75827b4754cb6b445cc2efc92d42ef467b597 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 12:52:04 +0200 Subject: [PATCH 517/665] req --- requirements.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/requirements.txt b/requirements.txt index dfd948d..9ef0018 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,4 +1,7 @@ +# commit hash: 33c134e633ddc8193f4b547d905bf1df5799df63 --find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pyceres/ +# https://github.com/B1ueber2y/colmap/tree/features/imu +# commit hash: 2633d1c4c3d4ae0f17a462faa3e334d9345a9c2b --find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pycolmap/ projectaria-tools'[all]' From 77dca6a6f17b2c3e2ad535858c76b0e86b685405 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 12:57:32 +0200 Subject: [PATCH 518/665] pr --- requirements.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 9ef0018..2c3df3d 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,6 +1,7 @@ # commit hash: 33c134e633ddc8193f4b547d905bf1df5799df63 --find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pyceres/ -# https://github.com/B1ueber2y/colmap/tree/features/imu + +# https://github.com/colmap/colmap/pull/2625 # commit hash: 2633d1c4c3d4ae0f17a462faa3e334d9345a9c2b --find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pycolmap/ From 4579c20c273214bf655a94c4a0987a4b48b3eaf3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 13:21:24 +0200 Subject: [PATCH 519/665] op path desc --- evaluate_wrt_pgt.py | 1 + 1 file changed, 1 insertion(+) diff --git a/evaluate_wrt_pgt.py b/evaluate_wrt_pgt.py index ceba304..6482803 100644 --- a/evaluate_wrt_pgt.py +++ b/evaluate_wrt_pgt.py @@ -25,6 +25,7 @@ def run( SparseEvalResult data. This file is generated by `evaluate_wrt_control_points`, and is needed to transform the estimated trajectory to the pGT. + output_path (Path): Path to save the evaluation results. Returns: bool: True if the evaluation was successful, False otherwise. """ From b557af6266b11ec32b09418a1c6ba452ae1d5fc7 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 13:38:00 +0200 Subject: [PATCH 520/665] fix requirements.txt --- requirements.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/requirements.txt b/requirements.txt index 2c3df3d..caa96d1 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,7 +5,7 @@ # commit hash: 2633d1c4c3d4ae0f17a462faa3e334d9345a9c2b --find-links https://cvg-data.inf.ethz.ch/lamaria/packages/pycolmap/ -projectaria-tools'[all]' +projectaria-tools[all] omegaconf scipy pyceres==2.6 ; python_version >= "3.9" and python_version < "3.15" From a16b097906d37be824887ec19a90cc0da2026294 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 13:56:54 +0200 Subject: [PATCH 521/665] useless str in sensoroptions --- lamaria/config/options.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 43f7931..154d23b 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -33,9 +33,6 @@ def load(cls, cfg: OmegaConf | None = None) -> MPSOptions: @dataclass(slots=True) class SensorOptions: - left_cam_stream_id: str = "1201-1" - right_cam_stream_id: str = "1201-2" - right_imu_stream_id: str = "1202-1" camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" has_slam_drops: bool = ( False # check vrs json metadata file for each sequence From ae305f5222d7a22a881d2f3c4ebd8d80a48eb64d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 13:57:14 +0200 Subject: [PATCH 522/665] aria upd --- lamaria/utils/aria.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 339015d..dd59234 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -6,6 +6,7 @@ import numpy as np import pycolmap from projectaria_tools.core import data_provider, mps +from projectaria_tools.core.stream_id import StreamId from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration from projectaria_tools.core.mps.utils import get_nearest_pose from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions @@ -409,11 +410,11 @@ def get_imu_data_from_vrs( from MPS folder. Otherwise, use device calibration from VRS file.""" imu_timestamps = sorted( vrs_provider.get_timestamps_ns( - RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME + StreamId(RIGHT_IMU_STREAM_ID), TimeDomain.DEVICE_TIME ) ) imu_stream_label = vrs_provider.get_label_from_stream_id( - RIGHT_IMU_STREAM_ID + StreamId(RIGHT_IMU_STREAM_ID) ) if mps_folder is not None: @@ -443,7 +444,7 @@ def get_imu_data_from_vrs( calibration = online_imu_calibs[closest_ts] imu_data = vrs_provider.get_imu_data_by_time_ns( - RIGHT_IMU_STREAM_ID, + StreamId(RIGHT_IMU_STREAM_ID), timestamp, TimeDomain.DEVICE_TIME, TimeQueryOptions.CLOSEST, From e7ba58b957bbc85dde135cbc18997134dead5cb2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 13:58:26 +0200 Subject: [PATCH 523/665] rm stream id --- lamaria/utils/constants.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/lamaria/utils/constants.py b/lamaria/utils/constants.py index 6730858..0671c62 100644 --- a/lamaria/utils/constants.py +++ b/lamaria/utils/constants.py @@ -1,5 +1,3 @@ -from projectaria_tools.core.stream_id import StreamId - # ASL folder name, stream label for Aria cameras ARIA_CAMERAS: list = [ ("cam0", "camera-slam-left"), @@ -7,13 +5,13 @@ ] # Aria camera constants -LEFT_CAMERA_STREAM_ID = StreamId("1201-1") -RIGHT_CAMERA_STREAM_ID = StreamId("1201-2") +LEFT_CAMERA_STREAM_ID = "1201-1" +RIGHT_CAMERA_STREAM_ID = "1201-2" LEFT_CAMERA_STREAM_LABEL = "camera-slam-left" RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" # Right Aria IMU constants -RIGHT_IMU_STREAM_ID = StreamId("1202-1") +RIGHT_IMU_STREAM_ID = "1202-1" RIGHT_IMU_STREAM_LABEL = "imu-right" # Custom origin coordinates (LV95 / LN02) for translating large CP coordinates From d96f91997a083fb5febb17762da4c974613608ad Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 13:58:46 +0200 Subject: [PATCH 524/665] streamid intro in vrs to asl --- tools/vrs_to_asl_folder.py | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/tools/vrs_to_asl_folder.py b/tools/vrs_to_asl_folder.py index dc09cd9..6a104f3 100644 --- a/tools/vrs_to_asl_folder.py +++ b/tools/vrs_to_asl_folder.py @@ -5,6 +5,7 @@ from projectaria_tools.core import data_provider from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from projectaria_tools.core.stream_id import StreamId from tqdm import tqdm from lamaria import logger @@ -135,7 +136,7 @@ def write_image_csv(image_timestamps, cam_folder): def write_imu_data_to_csv(vrs_provider, csv_file): imu_timestamps = vrs_provider.get_timestamps_ns( - RIGHT_IMU_STREAM_ID, TimeDomain.DEVICE_TIME + StreamId(RIGHT_IMU_STREAM_ID), TimeDomain.DEVICE_TIME ) last_timestamp = None @@ -158,7 +159,7 @@ def write_imu_data_to_csv(vrs_provider, csv_file): writer = csv.writer(f) for timestamp in tqdm(imu_timestamps, desc="Appending IMU data to CSV"): imu_data = vrs_provider.get_imu_data_by_time_ns( - RIGHT_IMU_STREAM_ID, + StreamId(RIGHT_IMU_STREAM_ID), timestamp, TimeDomain.DEVICE_TIME, TimeQueryOptions.CLOSEST, @@ -193,7 +194,7 @@ def form_aria_asl_folder( # Get all image timestamps (in ns) image_timestamps = vrs_provider.get_timestamps_ns( - LEFT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME + StreamId(LEFT_CAMERA_STREAM_ID), TimeDomain.DEVICE_TIME ) assert len(image_timestamps) > 0, "No timestamps found" @@ -201,7 +202,7 @@ def form_aria_asl_folder( matched_timestamps = None if has_slam_drops: right_image_timestamps = vrs_provider.get_timestamps_ns( - RIGHT_CAMERA_STREAM_ID, TimeDomain.DEVICE_TIME + StreamId(RIGHT_CAMERA_STREAM_ID), TimeDomain.DEVICE_TIME ) assert len(right_image_timestamps) > 0, ( "No right camera image timestamps found" From 5f26deb16f3521cca6fb9607bb5a0d9d2f392dd6 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 13:59:00 +0200 Subject: [PATCH 525/665] streamid --- .../pipeline/keyframing/to_vi_reconstruction.py | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 8f131ee..3706a81 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -23,6 +23,11 @@ get_t_imu_camera, rigid3d_from_transform, ) +from ...utils.constants import ( + LEFT_CAMERA_STREAM_ID, + RIGHT_CAMERA_STREAM_ID, + RIGHT_IMU_STREAM_ID, +) from ...utils.timestamps import ( get_matched_timestamps, ) @@ -45,9 +50,6 @@ def __init__(self, options: EstimateToVIReconOptions): self.data: VIReconstruction = VIReconstruction() self._vrs_provider = None self._mps_data_provider = None - self._left_cam_sid: StreamId | None = None - self._right_cam_sid: StreamId | None = None - self._right_imu_sid: StreamId | None = None self._per_frame_data: dict[int, PerFrameData] = {} @staticmethod @@ -105,9 +107,9 @@ def _init_data( ) # Initialize stream IDs - self._left_cam_sid = StreamId(self.options.sensor.left_cam_stream_id) - self._right_cam_sid = StreamId(self.options.sensor.right_cam_stream_id) - self._right_imu_sid = StreamId(self.options.sensor.right_imu_stream_id) + self._left_cam_sid = StreamId(LEFT_CAMERA_STREAM_ID) + self._right_cam_sid = StreamId(RIGHT_CAMERA_STREAM_ID) + self._right_imu_sid = StreamId(RIGHT_IMU_STREAM_ID) # Initialize MPS data provider if needed if mps_folder is not None: From be0edeec85b3d0d0251652b879ad24b8f7335473 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 14:06:19 +0200 Subject: [PATCH 526/665] sparse eval result naming --- evaluate_wrt_pgt.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/evaluate_wrt_pgt.py b/evaluate_wrt_pgt.py index 6482803..c4a75f9 100644 --- a/evaluate_wrt_pgt.py +++ b/evaluate_wrt_pgt.py @@ -12,7 +12,7 @@ def run( estimate: Path, gt_estimate: Path, - sparse_npy_path: Path, + sparse_eval_result: Path, output_path: Path, ) -> bool: """Evaluate an estimated trajectory with respect to a pseudo @@ -21,7 +21,7 @@ def run( Args: estimate (Path): Path to the pose estimate file. gt_estimate (Path): Path to the pGT pose estimate file. - sparse_npy_path (Path): Path to the .npy file containing + sparse_eval_result (Path): Path to the .npy file containing SparseEvalResult data. This file is generated by `evaluate_wrt_control_points`, and is needed to transform the estimated trajectory to the pGT. @@ -40,8 +40,8 @@ def run( logger.error("pGT Estimate could not be loaded") return False - sparse_eval_result = SparseEvalResult.load_from_npy(sparse_npy_path) - if sparse_eval_result is None: + result = SparseEvalResult.load_from_npy(sparse_eval_result) + if result is None: logger.error("SparseEvalResult could not be loaded") return False @@ -76,7 +76,7 @@ def run( help="Path to the pGT pose estimate file.", ) parser.add_argument( - "--sparse_npy_path", + "--sparse_eval_result", type=Path, required=True, help="Path to the .npy file containing SparseEvalResult data." @@ -92,6 +92,6 @@ def run( _ = run( args.estimate, args.gt_estimate, - args.sparse_npy_path, + args.sparse_eval_result, args.output_path, ) From d307b5324964044f2ce57e78b74171b8c33786a5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 14:13:43 +0200 Subject: [PATCH 527/665] rm cp reproj std --- lamaria/structs/control_point.py | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index 40311da..04ec24e 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -19,7 +19,6 @@ class ControlPoint: name: str # geo_id topo: np.ndarray covariance: np.ndarray - cp_reproj_std: float = 1.0 # pixels triangulated: np.ndarray | None = None # None if triangulation fails inlier_ratio: float = 0.0 @@ -33,7 +32,6 @@ def from_measurement( measurement_xyz: list[float | None], unc_xyz: list[float | None], origin_xyz: tuple[float, float, float], - cp_reproj_std: float = 1.0, ) -> "ControlPoint": m = list(measurement_xyz) u = list(unc_xyz) @@ -49,7 +47,7 @@ def from_measurement( cov = np.diag(np.square(np.asarray(u, dtype=np.float64))) return ControlPoint( - name=name, topo=topo, covariance=cov, cp_reproj_std=cp_reproj_std + name=name, topo=topo, covariance=cov ) def has_height(self) -> bool: @@ -69,11 +67,10 @@ def summary(self) -> dict: def get_control_points_for_evaluation( reconstruction_path: Path, cp_json_file: Path, - cp_reproj_std: float = 1.0, ) -> ControlPoints: """Load control points from JSON and run triangulation.""" control_points = construct_control_points_from_json( - cp_json_file, cp_reproj_std + cp_json_file, ) run_control_point_triangulation_from_json( reconstruction_path, cp_json_file, control_points @@ -83,7 +80,6 @@ def get_control_points_for_evaluation( def construct_control_points_from_json( cp_json_file: Path, - cp_reproj_std: float = 1.0, ) -> ControlPoints: """ Construct ControlPoints dict from a JSON file. @@ -109,7 +105,6 @@ def construct_control_points_from_json( measurement, unc, CUSTOM_ORIGIN_COORDINATES, - cp_reproj_std, ) return control_points From bd0d6a433f08ecc02a3694104401cf84d6f2ea17 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 14:24:02 +0200 Subject: [PATCH 528/665] sparse --- lamaria/structs/sparse_eval.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index 0378e9b..93b82b3 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -104,7 +104,7 @@ def add_residuals_for_sparse_eval( logger.info(f"Control point {tag_id} not triangulated") continue - point2d_cov = np.eye(2) * pow(cp.cp_reproj_std, 2) + point2d_cov = np.eye(2) obs = cp.image_id_and_point2d for image_id, point2d in obs: From 084ab3903d4189cd346eefb23f4d527756a38f24 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 14:26:17 +0200 Subject: [PATCH 529/665] rm cp reproj std --- evaluate_wrt_control_points.py | 12 +----------- 1 file changed, 1 insertion(+), 11 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 8297a62..27954ad 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -15,7 +15,6 @@ def run( device_calibration_json: Path, output_path: Path, corresponding_sensor: str = "imu", - cp_reproj_std=1.0, ) -> bool: """Run sparse evaluation for sequences that observe control points. @@ -28,8 +27,6 @@ def run( evaluation results will be saved. corresponding_sensor (str): The reference sensor to use ("imu" or "cam0"). - cp_reproj_std (float, optional): Control point reprojection standard - deviation. Defaults to 1.0. Returns: bool: True if the evaluation was successful, False otherwise. @@ -59,7 +56,7 @@ def run( ) control_points = get_control_points_for_evaluation( - reconstruction_path, cp_json_file, cp_reproj_std + reconstruction_path, cp_json_file ) sparse_npy_path = evaluate_wrt_control_points( @@ -114,12 +111,6 @@ def run( choices=["imu", "cam0"], help="The sensor in which the poses are expressed.", ) - parser.add_argument( - "--cp_reproj_std", - type=float, - default=1.0, - help="Control point reprojection standard deviation", - ) args = parser.parse_args() _ = run( @@ -128,5 +119,4 @@ def run( args.device_calibration_json, args.output_path, args.corresponding_sensor, - args.cp_reproj_std, ) From 5706ef65c40796bacdfe458db1d219946f380ed9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 15:08:28 +0200 Subject: [PATCH 530/665] imu camera --- .../keyframing/to_vi_reconstruction.py | 26 ++++--------------- 1 file changed, 5 insertions(+), 21 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 3706a81..1f3d9b9 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -325,16 +325,8 @@ def _add_device_sensors(self) -> None: # DUMMY CAMERA FOR IMU, IMU ID is 1 imu = pycolmap.Camera( camera_id=1, - model=self.options.sensor.camera_model, - width=640, - height=480, - params=[ - 241.604, - 241.604, - 322.895, - 240.444, - ] - + [0.0] * 12, + model="SIMPLE_PINHOLE", + params=[0, 0, 0] ) self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) @@ -379,17 +371,9 @@ def _add_online_sensors(self) -> None: # DUMMY CAMERA FOR IMU imu = pycolmap.Camera( - camera_id=sensor_id, - model=self.options.sensor.camera_model, - width=640, - height=480, - params=[ - 241.604, - 241.604, - 322.895, - 240.444, - ] - + [0.0] * 12, + camera_id=1, + model="SIMPLE_PINHOLE", + params=[0, 0, 0] ) self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) From c24e3accb05b832c8cbc964ae026a47f201891ce Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 15:10:02 +0200 Subject: [PATCH 531/665] aria imu dummy camera --- lamaria/utils/aria.py | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index dd59234..861808f 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -37,16 +37,8 @@ def initialize_reconstruction_from_calibration_file( imu = pycolmap.Camera( camera_id=1, - model="RAD_TAN_THIN_PRISM_FISHEYE", - width=640, - height=480, - params=[ - 241.604, - 241.604, - 322.895, - 240.444, - ] - + [0.0] * 12, + model="SIMPLE_PINHOLE", + params=[0, 0, 0] ) reconstruction.add_camera(imu) From d48c76fedc5fac394c67fc87a974c7d19a0e48dd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 15:33:28 +0200 Subject: [PATCH 532/665] return reconstruction instead of path --- lamaria/structs/trajectory.py | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 67c17b3..b7518c9 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -71,24 +71,16 @@ def add_estimate_poses_to_reconstruction( self, reconstruction: pycolmap.Reconstruction, timestamp_to_images: dict, - output_path: Path, - ) -> Path: + ) -> pycolmap.Reconstruction: """ Adds estimate poses as frames to input reconstruction. """ - self._ensure_loaded() - - recon_path = output_path / "reconstruction" - recon_path.mkdir(parents=True, exist_ok=True) - reconstruction = self._add_images_to_reconstruction( reconstruction, timestamp_to_images ) - reconstruction.write(recon_path.as_posix()) - - return recon_path + return reconstruction def filter_from_indices( self, From 85ef4bd5284eed93539bf64d8723eb4f5f0740f3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 15:35:37 +0200 Subject: [PATCH 533/665] init recons --- lamaria/utils/aria.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 861808f..593f026 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -16,13 +16,14 @@ from .. import logger from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID from .timestamps import find_closest_timestamp +from .types import InitReconstruction -# ----- Reconstruction functions ----- # +# ----- Reconstruction functions ----- # def initialize_reconstruction_from_calibration_file( calibration_file: Path, -) -> pycolmap.Reconstruction: +) -> InitReconstruction: """Initialize a COLMAP reconstruction from Aria calibration json file found on website: https://lamaria.ethz.ch/slam_datasets Adds a dummy camera as an IMU along with two cameras. From 5f8038333bcb10ea2bd69f3194ec51c0bf7cb7f3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 15:35:41 +0200 Subject: [PATCH 534/665] types --- lamaria/utils/types.py | 4 ++++ 1 file changed, 4 insertions(+) create mode 100644 lamaria/utils/types.py diff --git a/lamaria/utils/types.py b/lamaria/utils/types.py new file mode 100644 index 0000000..bca263e --- /dev/null +++ b/lamaria/utils/types.py @@ -0,0 +1,4 @@ +import pycolmap +from typing import TypeAlias + +InitReconstruction: TypeAlias = pycolmap.Reconstruction \ No newline at end of file From 5e3f9e3dc9c28460a0079ec87b6001ea0a67403f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 15:38:19 +0200 Subject: [PATCH 535/665] return --- lamaria/utils/aria.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 593f026..1493705 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -32,7 +32,7 @@ def initialize_reconstruction_from_calibration_file( calibration_file (Path): Path to the Aria calibration json file Returns: - pycolmap.Reconstruction: The initialized COLMAP reconstruction + InitReconstruction: The initialized COLMAP reconstruction """ reconstruction = pycolmap.Reconstruction() From 7e86ed4251e2e0787699690ced6e859f8947fea9 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 15:39:00 +0200 Subject: [PATCH 536/665] init recons --- lamaria/utils/aria.py | 4 +++- lamaria/utils/types.py | 4 ---- 2 files changed, 3 insertions(+), 5 deletions(-) delete mode 100644 lamaria/utils/types.py diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 1493705..07bbf8f 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -2,6 +2,7 @@ import shutil import subprocess from pathlib import Path +from typing import TypeAlias import numpy as np import pycolmap @@ -16,11 +17,12 @@ from .. import logger from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID from .timestamps import find_closest_timestamp -from .types import InitReconstruction # ----- Reconstruction functions ----- # +InitReconstruction: TypeAlias = pycolmap.Reconstruction + def initialize_reconstruction_from_calibration_file( calibration_file: Path, ) -> InitReconstruction: diff --git a/lamaria/utils/types.py b/lamaria/utils/types.py deleted file mode 100644 index bca263e..0000000 --- a/lamaria/utils/types.py +++ /dev/null @@ -1,4 +0,0 @@ -import pycolmap -from typing import TypeAlias - -InitReconstruction: TypeAlias = pycolmap.Reconstruction \ No newline at end of file From 2ede45d9c8d8363c3fc86f74a541cdf32f2ae2bf Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 15:42:07 +0200 Subject: [PATCH 537/665] aria --- lamaria/utils/aria.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 07bbf8f..c168f2f 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -78,7 +78,7 @@ def initialize_reconstruction_from_calibration_file( def initialize_reconstruction_with_cameras( calibration_file: Path, -) -> pycolmap.Reconstruction: +) -> InitReconstruction: """Initialize a COLMAP reconstruction from Aria calibration json file found on website: https://lamaria.ethz.ch/slam_datasets Adds only the cameras without any dummy IMU. @@ -87,7 +87,7 @@ def initialize_reconstruction_with_cameras( calibration_file (Path): Path to the Aria calibration json file Returns: - pycolmap.Reconstruction: The initialized COLMAP reconstruction + InitReconstruction: The initialized COLMAP reconstruction """ reconstruction = pycolmap.Reconstruction() From 3cea488acff1dd02b2af616200839e5d8c98e4b0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 16:05:38 +0200 Subject: [PATCH 538/665] data input --- lamaria/utils/timestamps.py | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/lamaria/utils/timestamps.py b/lamaria/utils/timestamps.py index b797390..2bd78e9 100644 --- a/lamaria/utils/timestamps.py +++ b/lamaria/utils/timestamps.py @@ -32,11 +32,8 @@ def matching_time_indices( def get_timestamp_to_images_from_json( - json_file: str | Path, + data: dict ): - with open(json_file) as f: - data = json.load(f) - processed_ts_data = {} for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: ts_data = data["timestamps"][label] From b32f97c0f5f12ea5fe08fa42d636f5b47c9b272d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 16:06:56 +0200 Subject: [PATCH 539/665] renaming --- lamaria/utils/timestamps.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/utils/timestamps.py b/lamaria/utils/timestamps.py index 2bd78e9..f697eb8 100644 --- a/lamaria/utils/timestamps.py +++ b/lamaria/utils/timestamps.py @@ -31,7 +31,7 @@ def matching_time_indices( return matching_indices_1, matching_indices_2 -def get_timestamp_to_images_from_json( +def get_timestamp_to_images( data: dict ): processed_ts_data = {} From d42622c1a14d528f18e8b9fdd9150d6ce283095f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 16:43:18 +0200 Subject: [PATCH 540/665] upd control point --- lamaria/structs/control_point.py | 109 ++++++++++++++++++------------- 1 file changed, 64 insertions(+), 45 deletions(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index 04ec24e..6a45ce9 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -10,22 +10,34 @@ from ..utils.constants import ( CUSTOM_ORIGIN_COORDINATES, ) +from ..utils.timestamps import get_timestamp_to_images ControlPoints = dict[int, "ControlPoint"] +@dataclass(slots=True) +class ControlPointSummary: + name: str # geo_id + triangulated: np.ndarray + topo: np.ndarray + covariance: np.ndarray + + @dataclass(slots=True) class ControlPoint: name: str # geo_id topo: np.ndarray covariance: np.ndarray + image_name_to_detection: dict[str, np.ndarray] | None = field( + default_factory=dict + ) # image_name to [x, y] detection triangulated: np.ndarray | None = None # None if triangulation fails inlier_ratio: float = 0.0 - image_id_and_point2d: list[tuple[int, np.ndarray]] = field( - default_factory=list - ) + # inlier list of (image_id, [x, y]) tuples + inlier_detections: list[(int, np.ndarray)] = field(default_factory=list) + @staticmethod def from_measurement( name: str, @@ -56,48 +68,59 @@ def has_height(self) -> bool: def is_triangulated(self) -> bool: return self.triangulated is not None - def summary(self) -> dict: - return { - "name": self.name, - "topo": self.topo.tolist(), - "covariance": self.covariance.tolist(), - } + def summary(self) -> ControlPointSummary: + return ControlPointSummary( + name=self.name, + triangulated=self.triangulated.tolist() + if self.triangulated is not None + else None, + topo=self.topo.tolist(), + covariance=self.covariance.tolist(), + ) -def get_control_points_for_evaluation( - reconstruction_path: Path, +def load_cp_json( cp_json_file: Path, -) -> ControlPoints: - """Load control points from JSON and run triangulation.""" - control_points = construct_control_points_from_json( - cp_json_file, - ) - run_control_point_triangulation_from_json( - reconstruction_path, cp_json_file, control_points - ) - return control_points + skip_detections: bool = False, +) -> tuple[ControlPoints, dict]: + """Main control point loading function. + Loads control points from JSON as well as timestamp to images mapping. + Args: + cp_json_file (Path): Path to the sparse GT JSON file. + + Returns: + control_points (ControlPoints): Control points dictionary. + timestamp_to_images (dict): Mapping from timestamps to image names. + """ + with open(cp_json_file) as file: + cp_data = json.load(file) + control_points = construct_control_points(cp_data, skip_detections) + timestamp_to_images = get_timestamp_to_images(cp_data) -def construct_control_points_from_json( - cp_json_file: Path, + return control_points, timestamp_to_images + + +def construct_control_points( + cp_data: dict, + skip_detections: bool = False, ) -> ControlPoints: """ - Construct ControlPoints dict from a JSON file. + Construct ControlPoints dict from JSON data. Args: - cp_json_file (Path): Path to the sparse GT JSON file. + cp_data (dict): Loaded JSON data containing control point information. Returns: control_points (ControlPoints): Control points dictionary. """ - with open(cp_json_file) as file: - cp_data = json.load(file) control_points: ControlPoints = {} for geo_id, data in cp_data["control_points"].items(): tag_ids = data["tag_id"] measurement = data["measurement"] unc = data["uncertainty"] + images_observing_cp = data["image_names"] for tag_id in tag_ids: control_points[tag_id] = ControlPoint.from_measurement( @@ -106,6 +129,11 @@ def construct_control_points_from_json( unc, CUSTOM_ORIGIN_COORDINATES, ) + + if not skip_detections: + for image_name in images_observing_cp: + detection = cp_data["images"][image_name]["detection"] + control_points[tag_id].image_name_to_detection[image_name] = np.array(detection) return control_points @@ -131,8 +159,7 @@ def transform_triangulated_control_points( def run_control_point_triangulation_from_json( - reconstruction_path: Path, - cp_json_file: Path, + reconstruction: pycolmap.Reconstruction, control_points: ControlPoints, ) -> None: """ @@ -141,30 +168,22 @@ def run_control_point_triangulation_from_json( - ``triangulated``: np.ndarray(3,) or None if triangulation fails - ``inlier_ratio``: float - - ``image_id_and_point2d``: list of (image_id, [x, y]) tuples - of observations used for triangulation + - ``inlier_detections``: list of observations used for triangulation Args: reconstruction_path (Path): Path to the reconstruction folder cp_json_file (Path): Path to the sparse GT JSON file control_points (dict): Control points dictionary to be updated """ - rec = pycolmap.Reconstruction(reconstruction_path) image_names_to_ids = { - image.name: image_id for image_id, image in rec.images.items() + image.name: image_id for image_id, image in reconstruction.images.items() } - with open(cp_json_file) as file: - data = json.load(file) - - image_data = data["images"] - control_point_data = data["control_points"] - for _, cp in tqdm( control_points.items(), desc="Triangulating control points" ): geo_id = cp.name - images_observing_cp = control_point_data[geo_id]["image_names"] + images_observing_cp = list(cp.image_name_to_detection.keys()) pixel_points = [] cam_from_worlds = [] @@ -176,18 +195,18 @@ def run_control_point_triangulation_from_json( if image_name not in image_names_to_ids: continue id = image_names_to_ids[image_name] - image = rec.images[id] - detection = image_data[image_name]["detection"] + image = reconstruction.images[id] + detection = cp.image_name_to_detection[image_name] pixel_points.append(detection) cam_from_worlds.append(image.cam_from_world()) - cameras.append(rec.cameras[image.camera_id]) + cameras.append(reconstruction.cameras[image.camera_id]) image_ids_and_centers.append((id, detection)) # HANDLING THE CASE WHERE NO IMAGES OBSERVE THE CONTROL POINT if pixel_points == []: cp.triangulated = None cp.inlier_ratio = 0.0 - cp.image_id_and_point2d = [] + cp.inlier_detections = [] continue pixel_points = np.array(pixel_points) @@ -208,7 +227,7 @@ def run_control_point_triangulation_from_json( if output is None: cp.triangulated = None cp.inlier_ratio = 0.0 - cp.image_id_and_point2d = [] + cp.inlier_detections = [] continue cp.triangulated = output["xyz"] @@ -217,7 +236,7 @@ def run_control_point_triangulation_from_json( image_ids_and_centers = [ image_ids_and_centers[i] for i in range(len(inliers)) if inliers[i] ] - cp.image_id_and_point2d = image_ids_and_centers + cp.inlier_detections = image_ids_and_centers def get_cps_for_initial_alignment(control_points: ControlPoints): From d020ee92701ee963b7b7b910e4e724b37eceb88c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 16:46:45 +0200 Subject: [PATCH 541/665] comment --- lamaria/utils/timestamps.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/lamaria/utils/timestamps.py b/lamaria/utils/timestamps.py index f697eb8..7311a66 100644 --- a/lamaria/utils/timestamps.py +++ b/lamaria/utils/timestamps.py @@ -34,6 +34,13 @@ def matching_time_indices( def get_timestamp_to_images( data: dict ): + """Loads timestamps to images mapping from JSON data. + Args: + data (dict): The JSON data containing timestamps information. + Returns: + dict: A dictionary mapping stream labels to their respective + timestamp-to-image mappings and sorted timestamp keys. + """ processed_ts_data = {} for label in [LEFT_CAMERA_STREAM_LABEL, RIGHT_CAMERA_STREAM_LABEL]: ts_data = data["timestamps"][label] From 9c49ecca22ba74daee02f9372fb15a2c62f73a76 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 16:48:16 +0200 Subject: [PATCH 542/665] comms --- lamaria/structs/control_point.py | 17 +++++++++++------ 1 file changed, 11 insertions(+), 6 deletions(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index 6a45ce9..75aa87e 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -83,14 +83,17 @@ def load_cp_json( cp_json_file: Path, skip_detections: bool = False, ) -> tuple[ControlPoints, dict]: - """Main control point loading function. - Loads control points from JSON as well as timestamp to images mapping. + """Load control points and timestamp→images mapping from a JSON file. + Args: - cp_json_file (Path): Path to the sparse GT JSON file. - + cp_json_file (Path): Path to the sparse ground-truth JSON file. + skip_detections (bool): If True, skip per-image detections and only + load control point measurement data. + Returns: - control_points (ControlPoints): Control points dictionary. - timestamp_to_images (dict): Mapping from timestamps to image names. + Tuple: + - control_points: Parsed control points collection. + - timestamp_to_images: Mapping from timestamps (ns) to image names. """ with open(cp_json_file) as file: cp_data = json.load(file) @@ -110,6 +113,8 @@ def construct_control_points( Args: cp_data (dict): Loaded JSON data containing control point information. + skip_detections (bool): If True, skip per-image detections and only + load control point measurement data. Returns: control_points (ControlPoints): Control points dictionary. From 6cf98e4adbb832e70ee4b03c4685b0d1667f3835 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 16:50:26 +0200 Subject: [PATCH 543/665] fix --- lamaria/structs/sparse_eval.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index 93b82b3..1130fc5 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -106,7 +106,7 @@ def add_residuals_for_sparse_eval( point2d_cov = np.eye(2) - obs = cp.image_id_and_point2d + obs = cp.inlier_detections for image_id, point2d in obs: image = reconstruction.images[image_id] pose = image.cam_from_world() From 1d44bbc0dcea1a0c173ca969582965ecb69990e5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 16:58:07 +0200 Subject: [PATCH 544/665] cp --- lamaria/structs/control_point.py | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index 75aa87e..eef8fcc 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -35,9 +35,8 @@ class ControlPoint: triangulated: np.ndarray | None = None # None if triangulation fails inlier_ratio: float = 0.0 # inlier list of (image_id, [x, y]) tuples - inlier_detections: list[(int, np.ndarray)] = field(default_factory=list) + inlier_detections: list[(int, np.ndarray)] = field(default_factory=list) - @staticmethod def from_measurement( name: str, @@ -58,9 +57,7 @@ def from_measurement( ) cov = np.diag(np.square(np.asarray(u, dtype=np.float64))) - return ControlPoint( - name=name, topo=topo, covariance=cov - ) + return ControlPoint(name=name, topo=topo, covariance=cov) def has_height(self) -> bool: return bool(self.topo[2] != 0) @@ -134,11 +131,13 @@ def construct_control_points( unc, CUSTOM_ORIGIN_COORDINATES, ) - + if not skip_detections: for image_name in images_observing_cp: detection = cp_data["images"][image_name]["detection"] - control_points[tag_id].image_name_to_detection[image_name] = np.array(detection) + control_points[tag_id].image_name_to_detection[ + image_name + ] = np.array(detection) return control_points @@ -181,7 +180,8 @@ def run_control_point_triangulation_from_json( """ image_names_to_ids = { - image.name: image_id for image_id, image in reconstruction.images.items() + image.name: image_id + for image_id, image in reconstruction.images.items() } for _, cp in tqdm( From e897285de759e3210dc33380745ecd7838d17c4c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:12:55 +0200 Subject: [PATCH 545/665] ssparse --- lamaria/eval/sparse_evaluation.py | 21 +++++---------------- 1 file changed, 5 insertions(+), 16 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index e400e9c..4a0c069 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -36,7 +36,7 @@ def save_transformed_reconstruction( return output_folder -def estimate_robust_sim3d_from_control_points( +def estimate_initial_alignment_from_control_points( control_points: ControlPoints, ) -> pycolmap.Sim3d | None: """Estimate a robust Sim3d from control points. @@ -68,15 +68,14 @@ def estimate_robust_sim3d_from_control_points( def evaluate_wrt_control_points( - reconstruction_path: Path, + reconstruction: pycolmap.Reconstruction, control_points: ControlPoints, - output_path: Path, ) -> Path: """ Evaluate the trajectory with respect to control points. Args: - reconstruction_path (Path): Path to the input reconstruction, + reconstruction (pycolmap.Reconstruction): Reconstruction object which contains the estimated poses. control_points (ControlPoints): Control points dictionary. output_path (Path): Directory where results will be saved. @@ -85,7 +84,7 @@ def evaluate_wrt_control_points( sparse_npy_path (Path): Path to the saved SparseEvalResult .npy file. """ - robust_sim3d = estimate_robust_sim3d_from_control_points(control_points) + robust_sim3d = estimate_initial_alignment_from_control_points(control_points) if robust_sim3d is None: logger.error("Robust Sim3d estimation failed") @@ -96,7 +95,6 @@ def evaluate_wrt_control_points( robust_sim3d, ) - reconstruction = pycolmap.Reconstruction(reconstruction_path) problem, solver_options, summary = get_problem_for_sparse_alignment( reconstruction, variables ) @@ -109,14 +107,5 @@ def evaluate_wrt_control_points( variables, ) - _ = save_transformed_reconstruction( - reconstruction_path, - result.alignment.optimized_sim3d, - output_path / "aligned", - ) - - result_path = output_path / "sparse_evaluation.npy" - result.save_as_npy(result_path) - logger.info("Sparse evaluation completed successfully!") - return result_path + return result From 2bd27870b7ccaf4dabeacbad88f0a92ded68be8a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:16:15 +0200 Subject: [PATCH 546/665] eval --- evaluate_wrt_control_points.py | 31 ++++++++++++------------------- 1 file changed, 12 insertions(+), 19 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 27954ad..fe45a5a 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -3,10 +3,9 @@ from lamaria import logger from lamaria.eval.sparse_evaluation import evaluate_wrt_control_points -from lamaria.structs.control_point import get_control_points_for_evaluation +from lamaria.structs.control_point import load_cp_json from lamaria.structs.trajectory import Trajectory from lamaria.utils.aria import initialize_reconstruction_from_calibration_file -from lamaria.utils.timestamps import get_timestamp_to_images_from_json def run( @@ -47,29 +46,23 @@ def run( init_reconstruction = initialize_reconstruction_from_calibration_file( device_calibration_json ) - timestamp_to_images = get_timestamp_to_images_from_json(cp_json_file) + control_points, timestamp_to_images = load_cp_json(cp_json_file) - reconstruction_path = traj.add_estimate_poses_to_reconstruction( - init_reconstruction, - timestamp_to_images, - output_path, + reconstruction = traj.add_estimate_poses_to_reconstruction( + init_reconstruction, timestamp_to_images ) - control_points = get_control_points_for_evaluation( - reconstruction_path, cp_json_file - ) - - sparse_npy_path = evaluate_wrt_control_points( - reconstruction_path, + result = evaluate_wrt_control_points( + reconstruction, control_points, - output_path, ) - if not sparse_npy_path.exists(): - logger.error("Sparse evaluation failed") - return False - logger.info(f"Results saved to {sparse_npy_path}") - return True + result_path = output_path / "sparse_eval_result.npy" + if result is None: + logger.error("Sparse evaluation failed.") + return False + + result.save_as_npy(result_path) # TODO: Add metrics here? From a1039f8ee9480eaf1ce753fae7ba6d7c703de5a2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:16:30 +0200 Subject: [PATCH 547/665] sparse --- lamaria/eval/sparse_evaluation.py | 23 +---------------------- 1 file changed, 1 insertion(+), 22 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 4a0c069..345156d 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -15,27 +15,6 @@ ) -def save_transformed_reconstruction( - reconstruction_path: Path, - sim3d: pycolmap.Sim3d, - output_folder: Path, -) -> None: - """Apply a Sim3d transformation to a reconstruction and save it. - - Args: - reconstruction_path (Path): Path to the input reconstruction. - sim3d (pycolmap.Sim3d): The similarity transformation to apply. - output_folder (Path): Directory where the transformed reconstruction - will be saved. - """ - output_folder.mkdir(parents=True, exist_ok=True) - reconstruction = pycolmap.Reconstruction(reconstruction_path) - reconstruction.transform(sim3d) - reconstruction.write(output_folder) - - return output_folder - - def estimate_initial_alignment_from_control_points( control_points: ControlPoints, ) -> pycolmap.Sim3d | None: @@ -70,7 +49,7 @@ def estimate_initial_alignment_from_control_points( def evaluate_wrt_control_points( reconstruction: pycolmap.Reconstruction, control_points: ControlPoints, -) -> Path: +) -> SparseEvalResult | None: """ Evaluate the trajectory with respect to control points. From c1d95a2c29620d0c0b52ef406e5f5a4c2345b5c0 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:16:38 +0200 Subject: [PATCH 548/665] ruff --- lamaria/utils/timestamps.py | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/lamaria/utils/timestamps.py b/lamaria/utils/timestamps.py index 7311a66..2dbeb58 100644 --- a/lamaria/utils/timestamps.py +++ b/lamaria/utils/timestamps.py @@ -1,6 +1,4 @@ -import json from bisect import bisect_left -from pathlib import Path import numpy as np @@ -31,9 +29,7 @@ def matching_time_indices( return matching_indices_1, matching_indices_2 -def get_timestamp_to_images( - data: dict -): +def get_timestamp_to_images(data: dict): """Loads timestamps to images mapping from JSON data. Args: data (dict): The JSON data containing timestamps information. From fef2a952609c887185ee5bea17d9f225593814b7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:16:46 +0200 Subject: [PATCH 549/665] ruff --- lamaria/utils/aria.py | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index c168f2f..edfba77 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -7,10 +7,10 @@ import numpy as np import pycolmap from projectaria_tools.core import data_provider, mps -from projectaria_tools.core.stream_id import StreamId from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration from projectaria_tools.core.mps.utils import get_nearest_pose from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from projectaria_tools.core.stream_id import StreamId from scipy.spatial.transform import Rotation from tqdm import tqdm @@ -18,11 +18,11 @@ from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID from .timestamps import find_closest_timestamp - # ----- Reconstruction functions ----- # InitReconstruction: TypeAlias = pycolmap.Reconstruction + def initialize_reconstruction_from_calibration_file( calibration_file: Path, ) -> InitReconstruction: @@ -38,11 +38,7 @@ def initialize_reconstruction_from_calibration_file( """ reconstruction = pycolmap.Reconstruction() - imu = pycolmap.Camera( - camera_id=1, - model="SIMPLE_PINHOLE", - params=[0, 0, 0] - ) + imu = pycolmap.Camera(camera_id=1, model="SIMPLE_PINHOLE", params=[0, 0, 0]) reconstruction.add_camera(imu) rig = pycolmap.Rig(rig_id=1) From 6e01271c4656fdc3dc22bf2831bce950b908fdc1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:20:34 +0200 Subject: [PATCH 550/665] cp tri --- lamaria/structs/control_point.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index eef8fcc..d7a9cf6 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -162,12 +162,12 @@ def transform_triangulated_control_points( return control_points -def run_control_point_triangulation_from_json( +def run_control_point_triangulation( reconstruction: pycolmap.Reconstruction, control_points: ControlPoints, ) -> None: """ - Triangulate control points from JSON file and add to control_points dict. + Triangulate control points and add to control_points dict. Updates `control_points` in place to add: - ``triangulated``: np.ndarray(3,) or None if triangulation fails From 4893e652b83a2be1a909f70720dc4ca811f206ae Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:20:44 +0200 Subject: [PATCH 551/665] cp --- lamaria/structs/control_point.py | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index d7a9cf6..b400349 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -174,9 +174,8 @@ def run_control_point_triangulation( - ``inlier_ratio``: float - ``inlier_detections``: list of observations used for triangulation Args: - reconstruction_path (Path): Path to the reconstruction folder - cp_json_file (Path): Path to the sparse GT JSON file - control_points (dict): Control points dictionary to be updated + reconstruction (pycolmap.Reconstruction): The COLMAP reconstruction. + control_points (ControlPoints): The control points dictionary. """ image_names_to_ids = { From 5f85c29fa462fd0ffa00e32f1061ff784058a431 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:21:22 +0200 Subject: [PATCH 552/665] cp trii --- evaluate_wrt_control_points.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index fe45a5a..6c16375 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -3,7 +3,7 @@ from lamaria import logger from lamaria.eval.sparse_evaluation import evaluate_wrt_control_points -from lamaria.structs.control_point import load_cp_json +from lamaria.structs.control_point import load_cp_json, run_control_point_triangulation from lamaria.structs.trajectory import Trajectory from lamaria.utils.aria import initialize_reconstruction_from_calibration_file @@ -52,6 +52,11 @@ def run( init_reconstruction, timestamp_to_images ) + run_control_point_triangulation( + reconstruction, + control_points, + ) + result = evaluate_wrt_control_points( reconstruction, control_points, From a3ae3d63f4f1f54febd4535a34cc7cb32c36dc84 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:21:41 +0200 Subject: [PATCH 553/665] fix --- evaluate_wrt_control_points.py | 7 +++++-- lamaria/eval/sparse_evaluation.py | 5 +++-- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 6c16375..af86761 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -3,7 +3,10 @@ from lamaria import logger from lamaria.eval.sparse_evaluation import evaluate_wrt_control_points -from lamaria.structs.control_point import load_cp_json, run_control_point_triangulation +from lamaria.structs.control_point import ( + load_cp_json, + run_control_point_triangulation, +) from lamaria.structs.trajectory import Trajectory from lamaria.utils.aria import initialize_reconstruction_from_calibration_file @@ -66,7 +69,7 @@ def run( if result is None: logger.error("Sparse evaluation failed.") return False - + result.save_as_npy(result_path) # TODO: Add metrics here? diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 345156d..34c5297 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -1,4 +1,3 @@ -from pathlib import Path import pyceres import pycolmap @@ -63,7 +62,9 @@ def evaluate_wrt_control_points( sparse_npy_path (Path): Path to the saved SparseEvalResult .npy file. """ - robust_sim3d = estimate_initial_alignment_from_control_points(control_points) + robust_sim3d = estimate_initial_alignment_from_control_points( + control_points + ) if robust_sim3d is None: logger.error("Robust Sim3d estimation failed") From a1a05d024983d89b3d9426fd6121a8b3029285a7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:22:25 +0200 Subject: [PATCH 554/665] ruff --- lamaria/pipeline/keyframing/to_vi_reconstruction.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 1f3d9b9..45ba7a9 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -324,9 +324,7 @@ def _add_device_sensors(self) -> None: # DUMMY CAMERA FOR IMU, IMU ID is 1 imu = pycolmap.Camera( - camera_id=1, - model="SIMPLE_PINHOLE", - params=[0, 0, 0] + camera_id=1, model="SIMPLE_PINHOLE", params=[0, 0, 0] ) self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) From a3e2e7adc61e51fb8a4c6303231a3ac3db1d9998 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:22:40 +0200 Subject: [PATCH 555/665] ruff --- lamaria/pipeline/keyframing/to_vi_reconstruction.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 45ba7a9..ccf1ba3 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -369,9 +369,7 @@ def _add_online_sensors(self) -> None: # DUMMY CAMERA FOR IMU imu = pycolmap.Camera( - camera_id=1, - model="SIMPLE_PINHOLE", - params=[0, 0, 0] + camera_id=1, model="SIMPLE_PINHOLE", params=[0, 0, 0] ) self.data.reconstruction.add_camera(imu) rig.add_ref_sensor(imu.sensor_id) From 5067f037aad19df76e05a547904caa564cb5b90d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:49:32 +0200 Subject: [PATCH 556/665] cp summary --- lamaria/structs/control_point.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/lamaria/structs/control_point.py b/lamaria/structs/control_point.py index b400349..c9bbc98 100644 --- a/lamaria/structs/control_point.py +++ b/lamaria/structs/control_point.py @@ -18,9 +18,12 @@ @dataclass(slots=True) class ControlPointSummary: name: str # geo_id - triangulated: np.ndarray topo: np.ndarray covariance: np.ndarray + triangulated: np.ndarray | None = None + + def is_triangulated(self) -> bool: + return self.triangulated is not None @dataclass(slots=True) From 046586a47cc530bc88db9610d90375f05d9ee8df Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 17:49:48 +0200 Subject: [PATCH 557/665] abstract TimedReconstruction and refactor I/O. --- defaults.yaml | 4 +- example_vi_optimization.py | 254 ++++++++---------- lamaria/config/options.py | 26 +- lamaria/config/pipeline.py | 54 +--- .../pipeline/keyframing/keyframe_selection.py | 17 +- .../keyframing/to_vi_reconstruction.py | 42 +-- lamaria/pipeline/optim/triangulation.py | 20 +- lamaria/structs/timed_reconstruction.py | 51 ++++ lamaria/structs/vi_reconstruction.py | 88 ++---- lamaria/utils/aria.py | 9 + 10 files changed, 224 insertions(+), 341 deletions(-) create mode 100644 lamaria/structs/timed_reconstruction.py diff --git a/defaults.yaml b/defaults.yaml index f563abc..73212a1 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -1,5 +1,4 @@ # Default configuration for run_pipeline.py - sensor: camera_model: RAD_TAN_THIN_PRISM_FISHEYE has_slam_drops: false @@ -49,5 +48,4 @@ optimization: acc_infl: 1.0 integration_noise_density: 0.05 -mps: - use_online_calibration: false # relevant only when mps folder is used + use_mps_online_calibration: false # relevant only when mps folder is used diff --git a/example_vi_optimization.py b/example_vi_optimization.py index 3093df8..d108ae6 100644 --- a/example_vi_optimization.py +++ b/example_vi_optimization.py @@ -5,7 +5,7 @@ import pycolmap from lamaria.config.options import ( - EstimateToVIReconOptions, + EstimateToTimedReconOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, @@ -13,170 +13,97 @@ from lamaria.config.pipeline import PipelineOptions from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector from lamaria.pipeline.keyframing.to_vi_reconstruction import ( - EstimateToVIRecon, + EstimateToTimedRecon, ) from lamaria.pipeline.optim.session import SingleSeqSession from lamaria.pipeline.optim.triangulation import run as triangulate from lamaria.pipeline.optim.vi_optimization import VIOptimizer +from lamaria.structs.timed_reconstruction import TimedReconstruction from lamaria.structs.vi_reconstruction import VIReconstruction +from lamaria.utils.aria import get_imu_data_from_vrs_file def run_estimate_to_vi_recon( - options: EstimateToVIReconOptions, + options: EstimateToTimedReconOptions, vrs: Path, images_path: Path, estimate: Path, - colmap_model_path: Path, -) -> VIReconstruction: +) -> TimedReconstruction: """Function to convert a general input - estimate file to a VIReconstruction. + estimate file to a TimedReconstruction. """ - if colmap_model_path.exists(): - vi_recon = VIReconstruction.read(colmap_model_path) - return vi_recon - - colmap_model_path.mkdir(parents=True, exist_ok=True) - - vi_recon = EstimateToVIRecon.convert( + vi_recon = EstimateToTimedRecon.convert( options, vrs, images_path, estimate, ) - vi_recon.write(colmap_model_path) - return vi_recon def run_mps_to_vi_recon( - options: EstimateToVIReconOptions, + options: EstimateToTimedReconOptions, vrs: Path, images_path: Path, mps_folder: Path, - colmap_model_path: Path, -) -> VIReconstruction: - """Function to convert MPS estimate to a VIReconstruction.""" - if colmap_model_path.exists(): - vi_recon = VIReconstruction.read(colmap_model_path) - return vi_recon - - colmap_model_path.mkdir(parents=True, exist_ok=True) - - vi_recon = EstimateToVIRecon.convert( +) -> TimedReconstruction: + """Function to convert MPS estimate to a TimedReconstruction.""" + vi_recon = EstimateToTimedRecon.convert( options, vrs, images_path, mps_folder, ) - vi_recon.write(colmap_model_path) - return vi_recon def run_keyframe_selection( options: KeyframeSelectorOptions, - input: Path | VIReconstruction, + input_recon: TimedReconstruction, images_path: Path, keyframes_path: Path, - kf_model_path: Path, -) -> VIReconstruction: - if isinstance(input, Path): - input_recon = VIReconstruction.read(input) - else: - input_recon = input - - if kf_model_path.exists(): - kf_vi_recon = VIReconstruction.read(kf_model_path) - return kf_vi_recon - - kf_model_path.mkdir(parents=True, exist_ok=True) - +) -> TimedReconstruction: kf_vi_recon = KeyframeSelector.run( options, input_recon, images_path, keyframes_path, ) - - kf_vi_recon.write(kf_model_path) - return kf_vi_recon def run_triangulation( options: TriangulatorOptions, - input: Path, # path to VIReconstruction + reference_model_path: Path, keyframes_path: Path, - hloc_path: Path, - pairs_file: Path, - tri_model_path: Path, -) -> VIReconstruction: - if not isinstance(input, Path): - raise ValueError("Input must be a Path to the reconstruction") - - assert input.exists(), f"input reconstruction path {input} does not exist" - - if tri_model_path.exists(): - tri_vi_recon = VIReconstruction.read(tri_model_path) - return tri_vi_recon - + triangulation_path: Path, +) -> pycolmap.Reconstruction: triangulated_model_path = triangulate( options, - input, + reference_model_path, keyframes_path, - hloc_path, - pairs_file, - tri_model_path, + triangulation_path, ) - - input_vi_recon = VIReconstruction.read(input) - tri_recon = pycolmap.Reconstruction(triangulated_model_path) - - tri_vi_recon = VIReconstruction() - tri_vi_recon.reconstruction = tri_recon - tri_vi_recon.timestamps = input_vi_recon.timestamps - tri_vi_recon.imu_measurements = input_vi_recon.imu_measurements - tri_vi_recon.write(triangulated_model_path) - - return tri_vi_recon + return pycolmap.Reconstruction(triangulated_model_path) def run_optimization( vi_options: VIOptimizerOptions, triangulator_options: TriangulatorOptions, - input: Path, # path to VIReconstruction - optim_model_path: Path, + recon: VIReconstruction, + database_path: Path, ) -> VIReconstruction: - if not isinstance(input, Path): - raise ValueError("Input must be a Path to the reconstruction") - - db_path = input / "database.db" - assert db_path.exists(), ( - f"Database path {db_path} does not exist in input reconstruction" - ) - - if optim_model_path.exists(): - shutil.rmtree(optim_model_path) - - optim_model_path.mkdir(parents=True, exist_ok=True) - db_dst = optim_model_path / "database.db" - shutil.copy(db_path, db_dst) - - init_vi_recon = VIReconstruction.read(input) session = SingleSeqSession( vi_options.imu, - init_vi_recon, + recon, ) optimized_recon = VIOptimizer.optimize( - vi_options, triangulator_options, session, db_dst + vi_options, triangulator_options, session, database_path ) - optim_vi_recon = VIReconstruction() - optim_vi_recon.reconstruction = optimized_recon - optim_vi_recon.timestamps = init_vi_recon.timestamps - optim_vi_recon.imu_measurements = init_vi_recon.imu_measurements - optim_vi_recon.write(optim_model_path) + optim_vi_recon = VIReconstruction(reconstruction = optimized_recon, timestamps = recon.timestamps, imu_measurements = recon.imu_measurements) + return optim_vi_recon def run_pipeline( @@ -186,69 +113,98 @@ def run_pipeline( estimate: Path | None = None, mps_folder: Path | None = None, ): - # Setting output path for entire pipeline - options.output_path = output_path if not output_path.exists(): output_path.mkdir(parents=True, exist_ok=True) + recon = None - src = "estimate" if estimate is not None else "mps" # Estimate to Lamaria Reconstruction - est_options = options.estimate_to_colmap_options - if src == "estimate": - assert estimate.exists(), ( - "Estimate path must be provided if not using MPS" - ) - - _ = run_estimate_to_vi_recon( - est_options, - vrs, - options.images_path, - estimate, - options.colmap_model_path, - ) + src = "estimate" if estimate is not None else "mps" + image_path = output_path / "images" + init_recon_path = output_path / "initial_recon" + if init_recon_path.exists(): + recon = TimedReconstruction.read(init_recon_path) else: - assert mps_folder.exists(), ( - "MPS folder path must be provided if using MPS" - ) - - _ = run_mps_to_vi_recon( - est_options, - vrs, - options.images_path, - mps_folder, - options.colmap_model_path, - ) + if src == "estimate": + assert estimate.exists(), ( + "Estimate path must be provided if not using MPS" + ) + + recon = run_estimate_to_vi_recon( + options.estimate_to_colmap_options, + vrs, + output_path / "images", + estimate, + ) + + else: + assert mps_folder.exists(), ( + "MPS folder path must be provided if using MPS" + ) + + recon = run_mps_to_vi_recon( + options.estimate_to_colmap_options, + vrs, + output_path / "images", + mps_folder, + ) + recon.write(init_recon_path) # Keyframe Selection - kf_options = options.keyframing_options - _ = run_keyframe_selection( - kf_options, - options.colmap_model_path, - options.images_path, - options.keyframes_path, - options.kf_model_path, - ) + keyframe_path = output_path / "keyframes" + keyframed_recon_path = output_path / "keyframed_recon" + if keyframed_recon_path.exists(): + recon = TimedReconstruction.read(keyframed_recon_path) + else: + recon = run_keyframe_selection( + options.keyframing_options, + recon, + image_path, + keyframe_path, + ) + recon.write(output_path / "keyframed_recon") # Triangulation - tri_options = options.triangulator_options - _ = run_triangulation( - tri_options, - options.kf_model_path, - options.keyframes_path, - options.hloc_path, - options.pairs_file, - options.tri_model_path, - ) + triangulation_path = output_path / "triangulated" + tri_model_path = triangulation_path / "model" + database_path = tri_model_path / "database.db" + if tri_model_path.exists(): + recon = TimedReconstruction.read(tri_model_path) + else: + pycolmap_recon = run_triangulation( + options.triangulator_options, + keyframed_recon_path, + keyframe_path, + triangulation_path, + ) + recon = TimedReconstruction(reconstruction=pycolmap_recon, timestamps=recon.timestamps) + recon.write(tri_model_path) # Visual-Inertial Optimization - vi_options = options.vi_optimizer_options - _ = run_optimization( - vi_options, - tri_options, - options.tri_model_path, - options.optim_model_path, + optim_model_path = output_path / "optim_recon" + imu_measurements = None + if optim_model_path.exists(): + imu_measurements = VIReconstruction.read(optim_model_path).imu_measurements + shutil.rmtree(optim_model_path) + optim_model_path.mkdir(parents=True, exist_ok=True) + # Load IMU data + if imu_measurements is None: + if options.vi_optimizer_options.use_mps_online_calibration: + assert mps_folder is not None, ( + "MPS folder path must be provided if using MPS" + ) + imu_measurements = get_imu_data_from_vrs_file( + vrs, mps_folder if options.vi_optimizer_options.use_mps_online_calibration else None + ) + recon = VIReconstruction(reconstruction=recon.reconstruction, timestamps=recon.timestamps, imu_measurements=imu_measurements) + recon_optimized = run_optimization( + options.vi_optimizer_options, + options.triangulator_options, + recon, + database_path, ) + recon_optimized.write(output_path / "optim_recon") + return recon_optimized if __name__ == "__main__": diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 154d23b..f0767c4 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -16,21 +16,6 @@ def _structured_merge_to_obj(cls, section) -> object: return OmegaConf.to_object(merged) -# General options -@dataclass(slots=True) -class MPSOptions: - use_online_calibration: bool = ( - False # set to True if using MPS online calibration result - ) - - @classmethod - def load(cls, cfg: OmegaConf | None = None) -> MPSOptions: - if cfg is None: - return cls() - - return _structured_merge_to_obj(cls, cfg) - - @dataclass(slots=True) class SensorOptions: camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" @@ -49,23 +34,20 @@ def load(cls, cfg: OmegaConf | None = None) -> SensorOptions: # Estimate to COLMAP options @dataclass(slots=True) -class EstimateToVIReconOptions: - mps: MPSOptions = field(default_factory=MPSOptions) +class EstimateToTimedReconOptions: sensor: SensorOptions = field(default_factory=SensorOptions) @classmethod def load( cls, - cfg_mps: OmegaConf | None = None, cfg_sensor: OmegaConf | None = None, - ) -> EstimateToVIReconOptions: - if cfg_mps is None or cfg_sensor is None: + ) -> EstimateToTimedReconOptions: + if cfg_sensor is None: return cls() base = cls() return replace( base, - mps=MPSOptions.load(cfg_mps), sensor=SensorOptions.load(cfg_sensor), ) @@ -151,6 +133,7 @@ class VIOptimizerOptions: cam: OptCamOptions = field(default_factory=OptCamOptions) imu: OptIMUOptions = field(default_factory=OptIMUOptions) optim: OptOptions = field(default_factory=OptOptions) + use_mps_online_calibration: bool = False @classmethod def load(cls, cfg: OmegaConf | None = None) -> VIOptimizerOptions: @@ -167,4 +150,5 @@ def load(cls, cfg: OmegaConf | None = None) -> VIOptimizerOptions: cam=cam, imu=imu, optim=optim, + use_mps_online_calibration=cfg.use_mps_online_calibration ) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 6f12323..3c82a9f 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -4,7 +4,7 @@ from omegaconf import DictConfig, OmegaConf from .options import ( - EstimateToVIReconOptions, + EstimateToTimedReconOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, @@ -13,9 +13,8 @@ class PipelineOptions: def __init__(self) -> None: - self._output_path: Path = Path("output/") - self._estimate_to_colmap_options: EstimateToVIReconOptions = ( - EstimateToVIReconOptions() + self._estimate_to_colmap_options: EstimateTimedReconOptions = ( + EstimateToTimedReconOptions() ) self._keyframing_options: KeyframeSelectorOptions = ( KeyframeSelectorOptions() @@ -40,8 +39,7 @@ def load( def _update_from_cfg(self, cfg: DictConfig) -> None: """Update object attributes from a config.""" - self._estimate_to_colmap_options = EstimateToVIReconOptions.load( - cfg.mps, + self._estimate_to_colmap_options = EstimateToTimedReconOptions.load( cfg.sensor, ) self._keyframing_options = KeyframeSelectorOptions.load(cfg.keyframing) @@ -51,64 +49,22 @@ def _update_from_cfg(self, cfg: DictConfig) -> None: out = cfg.get("output_path", None) self._output_path = Path(out) if out is not None else Path("/output/") - @property - def output_path(self) -> Path: - """Get the parent output path.""" - return self._output_path - - @output_path.setter - def output_path(self, path: Path) -> None: - """Set the parent output path.""" - self._output_path = path - # Properties for estimate to COLMAP @property - def estimate_to_colmap_options(self) -> EstimateToVIReconOptions: + def estimate_to_colmap_options(self) -> EstimateToTimedReconOptions: return self._estimate_to_colmap_options - @property - def images_path(self) -> Path: - return self._output_path / "images" - - @property - def colmap_model_path(self) -> Path: - return self._output_path / "initial_recon" - # Properties for keyframing @property def keyframing_options(self) -> KeyframeSelectorOptions: return self._keyframing_options - @property - def keyframes_path(self) -> Path: - return self._output_path / "keyframes" - - @property - def kf_model_path(self) -> Path: - return self._output_path / "keyframed_recon" - # Properties for triangulation @property def triangulator_options(self) -> TriangulatorOptions: return self._triangulator_options - @property - def hloc_path(self) -> Path: - return self._output_path / "hloc" - - @property - def pairs_file(self) -> Path: - return self._output_path / "hloc" / "pairs.txt" - - @property - def tri_model_path(self) -> Path: - return self._output_path / "triangulated_recon" - # Properties for visual-inertial optimization @property def vi_optimizer_options(self) -> VIOptimizerOptions: return self._vi_optimizer_options - - @property - def optim_model_path(self) -> Path: - return self._output_path / "optim_recon" diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframing/keyframe_selection.py index 61915a8..0aa9168 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframing/keyframe_selection.py @@ -8,33 +8,33 @@ import pycolmap from ...config.options import KeyframeSelectorOptions -from ...structs.vi_reconstruction import VIReconstruction +from ...structs.timed_reconstruction import TimedReconstruction from ...utils.aria import get_magnitude_from_transform class KeyframeSelector: - """Class to perform keyframe selection on a VIReconstruction object.""" + """Class to perform keyframe selection on a TimedReconstruction object.""" def __init__( self, options: KeyframeSelectorOptions, - data: VIReconstruction, + data: TimedReconstruction, ): self.options = options self.init_data = data self.init_recons = data.reconstruction # pycolmap.Reconstruction self.timestamps = data.timestamps # frame id to timestamp mapping - self.keyframed_data = VIReconstruction() + self.keyframed_data = TimedReconstruction() self.keyframe_frame_ids: dict[int, int] = {} @staticmethod def run( options: KeyframeSelectorOptions, - data: VIReconstruction, + data: TimedReconstruction, images_path: Path, keyframes_path: Path, - ) -> VIReconstruction: + ) -> TimedReconstruction: """Entry point to run keyframing and copy keyframes into keyframe directory. """ @@ -215,7 +215,7 @@ def _build_online_keyframed_reconstruction(self): for img in images_to_add: self.keyframed_data.reconstruction.add_image(img) - def run_keyframing(self) -> VIReconstruction: + def run_keyframing(self) -> TimedReconstruction: """Function to run keyframing on lamaria reconstruction.""" self._select_keyframes() if len(self.init_recons.rigs.keys()) == 1: # device rig has been added @@ -228,9 +228,6 @@ def run_keyframing(self) -> VIReconstruction: new_fid: self.timestamps[old_fid] for new_fid, old_fid in self.keyframe_frame_ids.items() } - - self.keyframed_data.imu_measurements = self.init_data.imu_measurements - return self.keyframed_data def copy_images_to_keyframes_dir( diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index 1f3d9b9..e1a285a 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -9,16 +9,15 @@ from projectaria_tools.core.stream_id import StreamId from ... import logger -from ...config.options import EstimateToVIReconOptions +from ...config.options import EstimateToTimedReconOptions from ...structs.trajectory import ( Trajectory, ) -from ...structs.vi_reconstruction import VIReconstruction +from ...structs.timed_reconstruction import TimedReconstruction from ...utils.aria import ( camera_colmap_from_calib, extract_images_from_vrs, get_closed_loop_data_from_mps, - get_imu_data_from_vrs, get_mps_poses_for_timestamps, get_t_imu_camera, rigid3d_from_transform, @@ -42,26 +41,26 @@ class PerFrameData: rig_from_world: pycolmap.Rigid3d -class EstimateToVIRecon: +class EstimateToTimedRecon: """Converts estimate or MPS data to COLMAP format.""" - def __init__(self, options: EstimateToVIReconOptions): + def __init__(self, options: EstimateToTimedReconOptions): self.options = options - self.data: VIReconstruction = VIReconstruction() + self.data: TimedReconstruction = TimedReconstruction() self._vrs_provider = None self._mps_data_provider = None self._per_frame_data: dict[int, PerFrameData] = {} @staticmethod def convert( - options: EstimateToVIReconOptions, + options: EstimateToTimedReconOptions, vrs: Path, images_path: Path, estimate: Path | None = None, mps_folder: Path | None = None, - ) -> VIReconstruction: + ) -> TimedReconstruction: """Entry point to run estimate/MPS to colmap conversion.""" - to_colmap = EstimateToVIRecon(options) + to_colmap = EstimateToTimedRecon(options) return to_colmap.process(vrs, images_path, estimate, mps_folder) def process( @@ -70,7 +69,7 @@ def process( images_path: Path, estimate: Path | None = None, mps_folder: Path | None = None, - ) -> VIReconstruction: + ) -> TimedReconstruction: self._init_data(vrs, images_path, estimate, mps_folder) if self.options.mps.use_online_calibration: @@ -80,9 +79,6 @@ def process( self._add_device_sensors() self._add_device_frames() - # IMU + timestamps - ms = self._get_rectified_imu_data(mps_folder) - self.data.imu_measurements = ms self.data.timestamps = { fid: pfd.left_ts for fid, pfd in self._per_frame_data.items() } @@ -479,23 +475,3 @@ def _add_online_frames(self) -> None: self.data.reconstruction.add_frame(frame) for im in images_to_add: self.data.reconstruction.add_image(im) - - def _get_rectified_imu_data( - self, - mps_folder: Path | None = None, - ) -> pycolmap.ImuMeasurements: - """Generates rectified IMU data from VRS file""" - if self.options.mps.use_online_calibration: - assert mps_folder is not None, ( - "MPS folder path must be provided if using MPS" - ) - ms = get_imu_data_from_vrs( - self._vrs_provider, - mps_folder, - ) - else: - ms = get_imu_data_from_vrs( - self._vrs_provider, - ) - - return ms diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index 4d14986..8667ca1 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -15,7 +15,7 @@ from ...config.options import TriangulatorOptions -def set_colmap_triangulation_options( +def get_colmap_triangulation_options( options: TriangulatorOptions, ) -> pycolmap.IncrementalPipelineOptions: colmap_options = pycolmap.IncrementalPipelineOptions() @@ -89,15 +89,17 @@ def run( options: TriangulatorOptions, reference_model: Path, # reconstruction path keyframes_path: Path, - hloc_path: Path, - pairs_path: Path, - triangulated_model_path: Path, + output_path: Path, ) -> Path: if not keyframes_path.exists(): raise FileNotFoundError(f"keyframes not found at {keyframes_path}") - hloc_path.mkdir(parents=True, exist_ok=True) + output_path.mkdir(parents=True, exist_ok=True) + hloc_output_path = output_path / "hloc" + pairs_path = hloc_output_path / "pairs.txt" + triangulated_model_path = output_path / "model" + hloc_output_path.mkdir(parents=True, exist_ok=True) if not reference_model.exists(): raise FileNotFoundError( f"reference_model not found at {reference_model}" @@ -115,10 +117,10 @@ def run( ) retrieval_path = extract_features.main( - retrieval_conf, image_dir=keyframes_path, export_dir=hloc_path + retrieval_conf, image_dir=keyframes_path, export_dir=hloc_output_path ) features_path = extract_features.main( - feature_conf, image_dir=keyframes_path, export_dir=hloc_path + feature_conf, image_dir=keyframes_path, export_dir=hloc_output_path ) pairs_from_retrieval.main( @@ -130,10 +132,10 @@ def run( conf=matcher_conf, pairs=pairs_path, features=feature_conf["output"], - export_dir=hloc_path, + export_dir=hloc_output_path, ) - colmap_opts = set_colmap_triangulation_options(options) + colmap_opts = get_colmap_triangulation_options(options) _ = triangulation.main( sfm_dir=triangulated_model_path, diff --git a/lamaria/structs/timed_reconstruction.py b/lamaria/structs/timed_reconstruction.py new file mode 100644 index 0000000..05dbb3d --- /dev/null +++ b/lamaria/structs/timed_reconstruction.py @@ -0,0 +1,51 @@ +from dataclasses import dataclass, field +from pathlib import Path + +import numpy as np +import pycolmap + + +@dataclass +class TimedReconstruction: + reconstruction: pycolmap.Reconstruction = field(default_factory=pycolmap.Reconstruction) + timestamps: dict[int, int] = field(default_factory=dict) + + @classmethod + def read(cls, input_folder: Path) -> "TimedReconstruction": + """Load reconstruction and timestamps from disk.""" + assert input_folder.exists(), f"Input folder {input_folder} does not exist" + + reconstruction = pycolmap.Reconstruction(input_folder) + + ts_path = input_folder / "timestamps.txt" + assert ts_path.exists(), f"Timestamps file {ts_path} does not exist" + timestamps: dict[int, int] = {} + with open(ts_path) as f: + for line in f: + if line.startswith("#"): + continue + frame_id, ts = line.strip().split() + timestamps[int(frame_id)] = int(ts) + + return cls(reconstruction=reconstruction, timestamps=timestamps) + + def write(self, output_folder: Path) -> None: + """Write reconstruction and timestamps to disk.""" + output_folder.mkdir(parents=True, exist_ok=True) + self.reconstruction.write(output_folder.as_posix()) + + ts_path = output_folder / "timestamps.txt" + frame_ids = sorted(self.timestamps.keys()) + + # sanity check + recon_frame_ids = np.array(sorted(self.reconstruction.frames.keys())) + assert np.array_equal(np.array(frame_ids), recon_frame_ids), ( + "Frame IDs in reconstruction and timestamps do not match" + ) + + with open(ts_path, "w") as f: + f.write("# FrameID Timestamp(ns)\n") + for frame_id in frame_ids: + f.write(f"{frame_id} {self.timestamps[frame_id]}\n") + + diff --git a/lamaria/structs/vi_reconstruction.py b/lamaria/structs/vi_reconstruction.py index d2de4f6..9d4663f 100644 --- a/lamaria/structs/vi_reconstruction.py +++ b/lamaria/structs/vi_reconstruction.py @@ -1,87 +1,41 @@ +from dataclasses import dataclass, field from pathlib import Path import numpy as np import pycolmap +from .timed_reconstruction import TimedReconstruction -class VIReconstruction: - """Custom class to hold COLMAP reconstruction data along with - timestamps and IMU measurements. - Attributes: - reconstruction (pycolmap.Reconstruction): - The COLMAP reconstruction object. This object contains all the - 3D points, cameras (intrinsics, extrinsics), and images. - Additionally holds a dummy camera, with no associated images, - to serve as a placeholder for the IMU. +@dataclass +class VIReconstruction(TimedReconstruction): + """Visual–Inertial reconstruction: adds IMU measurements.""" - timestamps (dict[int, int]): A dictionary mapping reconstruction - frame IDs to their corresponding timestamps in nanoseconds. + imu_measurements: pycolmap.ImuMeasurements | None = None - imu_measurements (pycolmap.ImuMeasurements): The factory/online - rectified IMU measurements generated from input VRS file. - """ - - def __init__(self) -> None: - self.reconstruction = pycolmap.Reconstruction() - self.timestamps: dict[int, int] = {} - self.imu_measurements = None - - @staticmethod - def read( - input_folder: Path, - ) -> "VIReconstruction": - assert input_folder.exists(), ( - f"Input folder {input_folder} does not exist" - ) - instance = VIReconstruction() - instance.reconstruction = pycolmap.Reconstruction(input_folder) - - ts_path = input_folder / "timestamps.txt" - assert ts_path.exists(), ( - f"Timestamps file {ts_path} does not exist in {input_folder}" - ) - with open(ts_path) as f: - lines = f.readlines() - instance.timestamps = {} - for line in lines: - if line.startswith("#"): - continue - frame_id, ts = line.strip().split() - instance.timestamps[int(frame_id)] = int(ts) + @classmethod + def read(cls, input_folder: Path) -> "VIReconstruction": + # Load base data first + base = super().read(input_folder) + # Load IMU rectified_imu_data_npy = input_folder / "rectified_imu_data.npy" assert rectified_imu_data_npy.exists(), ( - f"Rectified IMU data file {rectified_imu_data_npy} \ - does not exist in {input_folder}" + f"Rectified IMU data file {rectified_imu_data_npy} does not exist" ) rectified_imu_data = np.load(rectified_imu_data_npy, allow_pickle=True) - instance.imu_measurements = pycolmap.ImuMeasurements( - rectified_imu_data.tolist() - ) - - return instance - - def write( - self, - output_folder: Path, - ) -> None: - output_folder.mkdir(parents=True, exist_ok=True) - self.reconstruction.write(output_folder.as_posix()) - - ts_path = output_folder / "timestamps.txt" - frame_ids = sorted(self.timestamps.keys()) + imu_measurements = pycolmap.ImuMeasurements(rectified_imu_data.tolist()) - # sanity check of frame ids in reconstruction and timestamps - recon_frame_ids = np.array(sorted(self.reconstruction.frames.keys())) - assert np.array_equal(np.array(frame_ids), recon_frame_ids), ( - "Frame IDs in reconstruction and timestamps do not match" + return cls( + reconstruction=base.reconstruction, + timestamps=base.timestamps, + imu_measurements=imu_measurements, ) - with open(ts_path, "w") as f: - f.write("# FrameID Timestamp(ns)\n") - for frame_id in frame_ids: - f.write(f"{frame_id} {self.timestamps[frame_id]}\n") + def write(self, output_folder: Path) -> None: + # Write base data first + super().write_base(output_folder) + # Write IMU data rectified_imu_data_npy = output_folder / "rectified_imu_data.npy" np.save(rectified_imu_data_npy, self.imu_measurements.data) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 861808f..9293467 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -455,6 +455,15 @@ def get_imu_data_from_vrs( return ms +def get_imu_data_from_vrs_file( + vrs_file: Path, + mps_folder: Path | None = None, +) -> pycolmap.ImuMeasurements: + vrs_provider = data_provider.create_vrs_data_provider( + vrs_file.as_posix() + ) + return get_imu_data_from_vrs(vrs_provider, mps_folder=mps_folder) + # ----- VRS utils ----- # From ddda41d93678839d25ae2d94d9738087cd085f40 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:50:30 +0200 Subject: [PATCH 558/665] ev --- evaluate_wrt_control_points.py | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index af86761..88cbe0c 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -64,14 +64,16 @@ def run( reconstruction, control_points, ) - - result_path = output_path / "sparse_eval_result.npy" + if result is None: logger.error("Sparse evaluation failed.") return False - + + result_path = output_path / "sparse_eval_result.npy" result.save_as_npy(result_path) + + # TODO: Add metrics here? From 826d41088f4b8ea42aed9bf486ca67fdb6436889 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 17:51:21 +0200 Subject: [PATCH 559/665] sparse eval --- lamaria/structs/sparse_eval.py | 100 +++++++-------------------------- 1 file changed, 19 insertions(+), 81 deletions(-) diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index 1130fc5..dc607ed 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -8,7 +8,7 @@ import pycolmap.cost_functions from .. import logger -from .control_point import ControlPoint +from .control_point import ControlPoint, ControlPointSummary @dataclass(slots=True) @@ -43,7 +43,7 @@ def update_sim3d_scale(self) -> None: def get_cp_summary(self) -> dict: """Get a brief summary of control points.""" - summary = {} + summary: dict[int, ControlPointSummary] = {} for tag_id, cp in self.control_points.items(): summary[tag_id] = cp.summary() @@ -148,62 +148,18 @@ def add_residuals_for_sparse_eval( return problem -@dataclass(slots=True) -class AlignedPoint: - triangulated: np.ndarray | None - topo: np.ndarray - transformed: np.ndarray | None = None - error_3d: np.ndarray | None = None - - -@dataclass(slots=True) -class AlignmentResult: - optimized_sim3d: pycolmap.Sim3d - points: dict[int, AlignedPoint] - - @staticmethod - def calculate( - variables: SparseEvalVariables, - ) -> "AlignmentResult": - points = {} - sim3d = copy.deepcopy(variables.sim3d) - - for tag_id, cp in variables.control_points.items(): - tri = cp.triangulated - if tri is None: - points[tag_id] = AlignedPoint( - triangulated=None, - topo=cp.topo, - transformed=None, - error_3d=None, - ) - continue - - transformed = sim3d * tri - error_3d = transformed - cp.topo - points[tag_id] = AlignedPoint( - triangulated=tri, - topo=cp.topo, - transformed=transformed, - error_3d=error_3d, - ) - - return AlignmentResult( - optimized_sim3d=sim3d, - points=points, - ) - @dataclass(slots=True) class SparseEvalResult: - alignment: AlignmentResult - cp_summary: dict | None = None + """Container for sparse evaluation results.""" + alignment: pycolmap.Sim3d + cp_summary: dict[int, ControlPointSummary] @staticmethod def from_variables( variables: SparseEvalVariables, ) -> "SparseEvalResult": - alignment = AlignmentResult.calculate(variables) + alignment = copy.deepcopy(variables.sim3d) cp_summary = variables.get_cp_summary() return SparseEvalResult( @@ -212,42 +168,24 @@ def from_variables( ) @classmethod - def load_from_npy(cls, path: Path) -> "SparseEvalResult": + def load_from_npy(cls, path: Path) -> "SparseEvalResult" | None: if not path.exists(): logger.error(f"Result file not found: {path}") return None data = np.load(path, allow_pickle=True).item() - alignment_data = data["alignment"] - - opt = alignment_data["optimized_sim3d"] - if isinstance(opt, pycolmap.Sim3d): - sim3d = opt - - alignment = AlignmentResult( - optimized_sim3d=sim3d, - points={ - int(tag_id): AlignedPoint( - triangulated=np.asarray(point["triangulated"]) - if point["triangulated"] is not None - else None, - topo=np.asarray(point["topo"]), - transformed=np.asarray(point["transformed"]) - if point["transformed"] is not None - else None, - error_3d=np.asarray(point["error_3d"]) - if point["error_3d"] is not None - else None, - ) - for tag_id, point in alignment_data["points"].items() - }, - ) - cp_summary = data.get("cp_summary", None) - - return cls( - alignment=alignment, - cp_summary=cp_summary, - ) + if not isinstance(data, dict): + logger.error(f"Invalid data format in: {path}") + return None + + try: + cp_summary = data["cp_summary"] + alignment = data["alignment"] + except KeyError as e: + logger.error(f"Missing key in data: {e}") + return None + + return cls(cp_summary=cp_summary, alignment=alignment) def save_as_npy(self, path: Path) -> None: path.parent.mkdir(parents=True, exist_ok=True) # just in case From adadd299e61d69de6c5be124e4c25850dc969642 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 17:52:45 +0200 Subject: [PATCH 560/665] format and fix. --- example_vi_optimization.py | 26 ++++++++++++++----- lamaria/config/options.py | 2 +- lamaria/config/pipeline.py | 2 +- lamaria/eval/sparse_evaluation.py | 1 - .../keyframing/to_vi_reconstruction.py | 2 +- lamaria/pipeline/optim/triangulation.py | 1 + lamaria/structs/timed_reconstruction.py | 10 ++++--- lamaria/structs/vi_reconstruction.py | 2 +- lamaria/utils/aria.py | 5 ++-- 9 files changed, 33 insertions(+), 18 deletions(-) diff --git a/example_vi_optimization.py b/example_vi_optimization.py index d108ae6..992deac 100644 --- a/example_vi_optimization.py +++ b/example_vi_optimization.py @@ -102,7 +102,11 @@ def run_optimization( vi_options, triangulator_options, session, database_path ) - optim_vi_recon = VIReconstruction(reconstruction = optimized_recon, timestamps = recon.timestamps, imu_measurements = recon.imu_measurements) + optim_vi_recon = VIReconstruction( + reconstruction=optimized_recon, + timestamps=recon.timestamps, + imu_measurements=recon.imu_measurements, + ) return optim_vi_recon @@ -117,7 +121,6 @@ def run_pipeline( output_path.mkdir(parents=True, exist_ok=True) recon = None - # Estimate to Lamaria Reconstruction src = "estimate" if estimate is not None else "mps" image_path = output_path / "images" @@ -177,14 +180,18 @@ def run_pipeline( keyframe_path, triangulation_path, ) - recon = TimedReconstruction(reconstruction=pycolmap_recon, timestamps=recon.timestamps) + recon = TimedReconstruction( + reconstruction=pycolmap_recon, timestamps=recon.timestamps + ) recon.write(tri_model_path) # Visual-Inertial Optimization optim_model_path = output_path / "optim_recon" imu_measurements = None if optim_model_path.exists(): - imu_measurements = VIReconstruction.read(optim_model_path).imu_measurements + imu_measurements = VIReconstruction.read( + optim_model_path + ).imu_measurements shutil.rmtree(optim_model_path) optim_model_path.mkdir(parents=True, exist_ok=True) # Load IMU data @@ -194,9 +201,16 @@ def run_pipeline( "MPS folder path must be provided if using MPS" ) imu_measurements = get_imu_data_from_vrs_file( - vrs, mps_folder if options.vi_optimizer_options.use_mps_online_calibration else None + vrs, + mps_folder + if options.vi_optimizer_options.use_mps_online_calibration + else None, ) - recon = VIReconstruction(reconstruction=recon.reconstruction, timestamps=recon.timestamps, imu_measurements=imu_measurements) + recon = VIReconstruction( + reconstruction=recon.reconstruction, + timestamps=recon.timestamps, + imu_measurements=imu_measurements, + ) recon_optimized = run_optimization( options.vi_optimizer_options, options.triangulator_options, diff --git a/lamaria/config/options.py b/lamaria/config/options.py index f0767c4..af486e4 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -150,5 +150,5 @@ def load(cls, cfg: OmegaConf | None = None) -> VIOptimizerOptions: cam=cam, imu=imu, optim=optim, - use_mps_online_calibration=cfg.use_mps_online_calibration + use_mps_online_calibration=cfg.use_mps_online_calibration, ) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 3c82a9f..65e35d0 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -13,7 +13,7 @@ class PipelineOptions: def __init__(self) -> None: - self._estimate_to_colmap_options: EstimateTimedReconOptions = ( + self._estimate_to_colmap_options: EstimateToTimedReconOptions = ( EstimateToTimedReconOptions() ) self._keyframing_options: KeyframeSelectorOptions = ( diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 34c5297..d74089d 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -1,4 +1,3 @@ - import pyceres import pycolmap diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/keyframing/to_vi_reconstruction.py index dacb4ef..50941e3 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/keyframing/to_vi_reconstruction.py @@ -10,10 +10,10 @@ from ... import logger from ...config.options import EstimateToTimedReconOptions +from ...structs.timed_reconstruction import TimedReconstruction from ...structs.trajectory import ( Trajectory, ) -from ...structs.timed_reconstruction import TimedReconstruction from ...utils.aria import ( camera_colmap_from_calib, extract_images_from_vrs, diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index 8667ca1..6673a52 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -4,6 +4,7 @@ from pathlib import Path import pycolmap + from hloc import ( extract_features, match_features, diff --git a/lamaria/structs/timed_reconstruction.py b/lamaria/structs/timed_reconstruction.py index 05dbb3d..af8b809 100644 --- a/lamaria/structs/timed_reconstruction.py +++ b/lamaria/structs/timed_reconstruction.py @@ -7,13 +7,17 @@ @dataclass class TimedReconstruction: - reconstruction: pycolmap.Reconstruction = field(default_factory=pycolmap.Reconstruction) + reconstruction: pycolmap.Reconstruction = field( + default_factory=pycolmap.Reconstruction + ) timestamps: dict[int, int] = field(default_factory=dict) @classmethod def read(cls, input_folder: Path) -> "TimedReconstruction": """Load reconstruction and timestamps from disk.""" - assert input_folder.exists(), f"Input folder {input_folder} does not exist" + assert input_folder.exists(), ( + f"Input folder {input_folder} does not exist" + ) reconstruction = pycolmap.Reconstruction(input_folder) @@ -47,5 +51,3 @@ def write(self, output_folder: Path) -> None: f.write("# FrameID Timestamp(ns)\n") for frame_id in frame_ids: f.write(f"{frame_id} {self.timestamps[frame_id]}\n") - - diff --git a/lamaria/structs/vi_reconstruction.py b/lamaria/structs/vi_reconstruction.py index 9d4663f..27df8ab 100644 --- a/lamaria/structs/vi_reconstruction.py +++ b/lamaria/structs/vi_reconstruction.py @@ -1,4 +1,4 @@ -from dataclasses import dataclass, field +from dataclasses import dataclass from pathlib import Path import numpy as np diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index fcfdea8..c62b2cb 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -454,13 +454,12 @@ def get_imu_data_from_vrs( return ms + def get_imu_data_from_vrs_file( vrs_file: Path, mps_folder: Path | None = None, ) -> pycolmap.ImuMeasurements: - vrs_provider = data_provider.create_vrs_data_provider( - vrs_file.as_posix() - ) + vrs_provider = data_provider.create_vrs_data_provider(vrs_file.as_posix()) return get_imu_data_from_vrs(vrs_provider, mps_folder=mps_folder) From 05fcc3b4560c6dea89c5adfb3d34c384fab2da83 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 17:57:55 +0200 Subject: [PATCH 561/665] format --- lamaria/pipeline/optim/triangulation.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index 6673a52..8667ca1 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -4,7 +4,6 @@ from pathlib import Path import pycolmap - from hloc import ( extract_features, match_features, From a57e41bfacbdd01ac0308cf656aa75fc1860aac1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 18:03:33 +0200 Subject: [PATCH 562/665] f --- evaluate_wrt_control_points.py | 8 +++++--- lamaria/structs/sparse_eval.py | 5 +---- 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 88cbe0c..b8354a9 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -9,6 +9,7 @@ ) from lamaria.structs.trajectory import Trajectory from lamaria.utils.aria import initialize_reconstruction_from_calibration_file +from lamaria.utils.metrics import calculate_control_point_score, calculate_control_point_recall def run( @@ -72,9 +73,10 @@ def run( result_path = output_path / "sparse_eval_result.npy" result.save_as_npy(result_path) - - - # TODO: Add metrics here? + score = calculate_control_point_score(result) + recall = calculate_control_point_recall(result) + logger.info(f"Sparse Evaluation CP Score: {score:.4f}") + logger.info(f"Sparse Evaluation CP Recall: {recall:.4f}") if __name__ == "__main__": diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index dc607ed..b55035d 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -168,15 +168,12 @@ def from_variables( ) @classmethod - def load_from_npy(cls, path: Path) -> "SparseEvalResult" | None: + def load_from_npy(cls, path: Path) -> "SparseEvalResult": if not path.exists(): logger.error(f"Result file not found: {path}") return None data = np.load(path, allow_pickle=True).item() - if not isinstance(data, dict): - logger.error(f"Invalid data format in: {path}") - return None try: cp_summary = data["cp_summary"] From 2fc7835d1554fba52b8ce84cc02f67a28219fbcc Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 18:10:52 +0200 Subject: [PATCH 563/665] metrics --- lamaria/utils/metrics.py | 99 +++++++++++++++++++++------------------- 1 file changed, 52 insertions(+), 47 deletions(-) diff --git a/lamaria/utils/metrics.py b/lamaria/utils/metrics.py index c3b3615..d1bb9a6 100644 --- a/lamaria/utils/metrics.py +++ b/lamaria/utils/metrics.py @@ -4,30 +4,8 @@ import pycolmap from scipy.interpolate import interp1d - -def get_sim3_from_sparse_evaluation( - sparse_evaluation_npy: Path, -) -> pycolmap.Sim3d: - data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() - sim3 = data_sparse["full_alignment"]["sim3"] - return sim3 - - -def get_all_tag_ids(sparse_evaluation_npy: Path) -> list[str]: - data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() - tag_ids = sorted(list(data_sparse["control_points"].keys())) - return tag_ids - - -def calculate_2d_alignment_errors(sparse_evaluation_npy: Path) -> list[float]: - data_sparse = np.load(sparse_evaluation_npy, allow_pickle=True).item() - tag_ids = get_all_tag_ids(sparse_evaluation_npy) - err_2d = [ - np.linalg.norm(data_sparse["full_alignment"]["error_3d"][i][:2]) - for i in tag_ids - ] - - return err_2d +from .. import logger +from ..structs.sparse_eval import SparseEvalResult def piecewise_linear_scoring(): @@ -54,16 +32,16 @@ def piecewise_linear_scoring(): ) return scoring - -def calculate_score_piecewise(errors): - if len(errors) == 0 or errors is None: +def calculate_control_point_score( + result: SparseEvalResult +) -> float: + """ Calculate CP score from SparseEvalResult object. """ + error_2d = calculate_error(result) + if any(e < 0 for e in error_2d): + logger.error("Negative errors found, norm error cannot be negative.") return 0.0 - - if any(e < 0 for e in errors): - raise ValueError("Norm error cannot be negative.") - - errors = np.nan_to_num(errors, nan=1000) # 1km error for NaNs - + + errors = np.nan_to_num(error_2d, nan=1e6) # Large error for NaNs scoring = piecewise_linear_scoring() scores = scoring(errors) score_sum = np.sum(scores) @@ -73,17 +51,44 @@ def calculate_score_piecewise(errors): return S_j -def calculate_score_from_alignment_data(sparse_evaluation_npy: Path) -> float: - tag_ids = get_all_tag_ids(sparse_evaluation_npy) - err_2d = calculate_2d_alignment_errors(sparse_evaluation_npy) - - if len(err_2d) == 0: - raise ValueError("No valid control points found.") - - assert len(err_2d) == len(tag_ids), ( - "Mismatch in number of 2D CPs and errors." - ) - - S_2d = calculate_score_piecewise(err_2d) - - return S_2d +def calculate_control_point_recall( + result: SparseEvalResult, + threshold: float = 1.0 # meters +) -> float: + """ Calculate CP recall from SparseEvalResult object. """ + error_2d = calculate_error(result) + if len(error_2d) == 0: + return 0.0 + + if any(e < 0 for e in error_2d): + logger.error("Negative errors found, norm error cannot be negative.") + return 0.0 + + errors = np.nan_to_num(error_2d, nan=1e6) # Large error for NaNs + inliers = np.sum(errors <= threshold) + recall = inliers / len(errors) * 100 + return recall + + +def calculate_error( + result: SparseEvalResult +) -> np.ndarray: + """ Calculate 2D errors from SparseEvalResult""" + sim3d = result.alignment # sim3d cannot be None here + if not isinstance(sim3d, pycolmap.Sim3d): + logger.error("No valid Sim3d found in SparseEvalResult") + return np.array([]) + + error_2d = [] + for _, cp in result.cp_summary.items(): + if not cp.is_triangulated(): + error_2d.append(np.nan) + continue + + transformed_point = sim3d * cp.triangulated + e = np.linalg.norm(transformed_point[:2] - cp.topo[:2]) + error_2d.append(e) + + assert len(error_2d) == len(result.cp_summary), "Error length mismatch" + + return np.array(error_2d) From 3d348555240af852a1c4886e5be61bbea65cc3fe Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:11:06 +0200 Subject: [PATCH 564/665] evo eval against mps --- lamaria/eval/evo_evaluation.py | 119 +++++++++++++++++++++++++++++++++ 1 file changed, 119 insertions(+) create mode 100644 lamaria/eval/evo_evaluation.py diff --git a/lamaria/eval/evo_evaluation.py b/lamaria/eval/evo_evaluation.py new file mode 100644 index 0000000..fff0afc --- /dev/null +++ b/lamaria/eval/evo_evaluation.py @@ -0,0 +1,119 @@ +from pathlib import Path +import numpy as np + +from evo.core import metrics, sync +from evo.core.trajectory import PoseTrajectory3D + +from .. import logger +from ..structs.trajectory import Trajectory + + +def valid_estimate( + est_pose_traj: PoseTrajectory3D, + gt_pose_traj: PoseTrajectory3D, + min_duration_ratio: float = 0.5, +) -> bool: + """" Check if the estimated trajectory is at least + half as long as the ground-truth trajectory in terms of + timestamps overlap. + Args: + est_pose_traj (PoseTrajectory3D): Estimated trajectory. + gt_pose_traj (PoseTrajectory3D): Ground-truth trajectory. + Returns: + bool: True if valid, False otherwise. + """ + + est_timestamps = est_pose_traj.timestamps + gt_timestamps = gt_pose_traj.timestamps + + gt_length = (gt_timestamps[-1] - gt_timestamps[0]) / 1e9 + est_length = (est_timestamps[-1] - est_timestamps[0]) / 1e9 + + if est_length < min_duration_ratio * gt_length: + return False + + return True + + +def convert_trajectory_to_evo_posetrajectory( + traj: Trajectory +) -> PoseTrajectory3D: + """Convert a Trajectory to an evo PoseTrajectory3D. + Args: + traj (Trajectory): The trajectory to convert. + Returns: + PoseTrajectory3D: The converted evo trajectory. + """ + assert traj.is_loaded(), "Trajectory is not loaded" + if not traj.invert_poses: + poses = traj.poses + else: + # store in COLMAP format (i.e., rig_from_world) + poses = [pose.inverse() for pose in traj.poses] + + timestamps = traj.timestamps + assert len(poses) == len(timestamps), "Poses and timestamps length mismatch" + + evo_traj = PoseTrajectory3D( + positions_xyz=np.array([pose.translation for pose in poses]), + orientations_xyzw=np.array([pose.rotation.quat for pose in poses]), + timestamps=np.array(timestamps), + ) + return evo_traj + + +def evaluate_wrt_mps( + est_traj: Trajectory, + gt_traj: Trajectory, +) -> None: + """ + Evaluate an estimated trajectory with respect to + MPS pGT. Alignment performed using Umeyama via evo package. + Important: + This function assumes that invert_poses=False for both trajectories. + Args: + est_traj (Trajectory): Estimated trajectory. + gt_traj (Trajectory): Pseudo ground-truth trajectory. + sim3d (pycolmap.Sim3d): Similarity transformation from the + estimated trajectory to the control points obtained from + sparse evaluation. + output_path (Path): Path to save the evaluation results. + + Estimate file format (space-separated columns): + ``` + timestamp(ns) tx ty tz qx qy qz qw + ``` + """ + + est_pose_traj = convert_trajectory_to_evo_posetrajectory(est_traj) + gt_pose_traj = convert_trajectory_to_evo_posetrajectory(gt_traj) + + if not valid_estimate(est_pose_traj, gt_pose_traj): + logger.error("Estimated trajectory is too short compared to pGT.") + return False + + gt_pose_traj_sync, est_pose_traj_sync = sync.associate_trajectories( + gt_pose_traj, + est_pose_traj, + max_diff=1e6 # 1 ms in ns + ) + + try: + est_pose_traj_sync.align( + gt_pose_traj_sync, + correct_scale=True + ) + except Exception as e: + logger.error(f"Alignment failed: {e}") + return None + + pose_relation = metrics.PoseRelation.translation_part + trajectories = (gt_pose_traj_sync, est_pose_traj_sync) + ate_metric = metrics.APE(pose_relation) + ate_metric.process_data(trajectories) + + ate_stats = ate_metric.get_all_statistics() + + return ate_stats["rmse"] + + From 7b0273385bb87765aa8fe604510e3cdd6ff3ee05 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:11:17 +0200 Subject: [PATCH 565/665] unused import --- lamaria/eval/evo_evaluation.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/eval/evo_evaluation.py b/lamaria/eval/evo_evaluation.py index fff0afc..9c6f1ae 100644 --- a/lamaria/eval/evo_evaluation.py +++ b/lamaria/eval/evo_evaluation.py @@ -1,4 +1,3 @@ -from pathlib import Path import numpy as np from evo.core import metrics, sync From 5cec9ed1a279bf718c6080df595f3a8619eda8f6 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:31:28 +0200 Subject: [PATCH 566/665] traj --- lamaria/structs/trajectory.py | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index b7518c9..80f8fc8 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -32,12 +32,17 @@ class Trajectory: By default, poses are calculated as rig_from_world (i.e., inverse of world_from_rig) to satisfy COLMAP format. + + Attributes: + invert_poses (bool): Whether to invert poses to + rig_from_world format. + corresponding_sensor (str): The reference sensor to in which + the trajectory is represented ("imu" or "cam0"). """ def __init__(self) -> None: self.invert_poses = None self.corresponding_sensor = None - self.path: Path | None = None self._timestamps: list[int] = [] self._poses: list[pycolmap.Rigid3d] = [] @@ -51,14 +56,14 @@ def load_from_file( """Parse the file, validate format, populate timestamps & poses.""" self = cls() self.clear() - self.path = Path(path) + path = Path(path) self.invert_poses = invert_poses self.corresponding_sensor = corresponding_sensor - if not self.path.exists(): - raise FileNotFoundError(f"Estimate file not found: {self.path}") + if not path.exists(): + raise FileNotFoundError(f"Estimate file not found: {path}") - with open(self.path) as f: + with open(path) as f: lines = f.readlines() state = self._parse(lines) @@ -130,6 +135,7 @@ def positions(self) -> np.ndarray: """Returns Nx3 numpy array of positions.""" self._ensure_loaded() if not self.invert_poses: + # poses are in world_from_rig format return np.array([p.translation for p in self._poses]) else: return np.array([p.inverse().translation for p in self._poses]) @@ -139,8 +145,10 @@ def orientations(self) -> np.ndarray: """Returns Nx4 numpy array of quaternions (x, y, z, w).""" self._ensure_loaded() if not self.invert_poses: + # poses are in world_from_rig format return np.array([p.rotation.quat for p in self._poses]) else: + # poses are in rig_from_world format return np.array([p.inverse().rotation.quat for p in self._poses]) def as_tuples(self) -> list[tuple[int, pycolmap.Rigid3d]]: From 39a84235ccda8fb5c550ec4ca7529dbe8b2f22df Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:48:21 +0200 Subject: [PATCH 567/665] traj --- lamaria/structs/trajectory.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 80f8fc8..0fbdca5 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -1,5 +1,6 @@ from decimal import ROUND_HALF_UP, Decimal from pathlib import Path +from dataclasses import dataclass import numpy as np import pycolmap @@ -23,7 +24,7 @@ def _round_ns(x: str | int | float) -> int: s = str(x) return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) - +@dataclass(slots=True) class Trajectory: """ Loads and stores traj data from 'estimate' text file with rows: @@ -41,8 +42,8 @@ class Trajectory: """ def __init__(self) -> None: - self.invert_poses = None - self.corresponding_sensor = None + self.invert_poses: bool = True + self.corresponding_sensor: str = "imu" self._timestamps: list[int] = [] self._poses: list[pycolmap.Rigid3d] = [] From 54c3bb99fe07bc39cc47b5dc7661bd48a3c0e1c7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:50:07 +0200 Subject: [PATCH 568/665] eval wrt mps --- evaluate_wrt_mps.py | 72 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100644 evaluate_wrt_mps.py diff --git a/evaluate_wrt_mps.py b/evaluate_wrt_mps.py new file mode 100644 index 0000000..7f4b2cd --- /dev/null +++ b/evaluate_wrt_mps.py @@ -0,0 +1,72 @@ +import argparse +from pathlib import Path + +from lamaria import logger +from lamaria.eval.evo_evaluation import evaluate_wrt_mps +from lamaria.structs.trajectory import Trajectory + + +def run( + estimate: Path, + gt_estimate: Path, +) -> bool: + """Evaluate an estimated trajectory with respect to + MPS pGT. There are no control points involved when + evaluating using this function. Resorting to evo + package for the evaluation. + + Args: + estimate (Path): Path to the pose estimate file. + gt_estimate (Path): Path to the pGT pose estimate file. + output_path (Path): Path to save the evaluation results. + Returns: + bool: True if the evaluation was successful, False otherwise. + """ + + est_traj = Trajectory.load_from_file( + estimate, invert_poses=False + ) + if not est_traj.is_loaded(): + logger.error("Estimate could not be loaded") + return False + + gt_traj = Trajectory.load_from_file( + gt_estimate, invert_poses=False + ) + if not gt_traj.is_loaded(): + logger.error("Ground-truth estimate could not be loaded") + return False + + result = evaluate_wrt_mps( + est_traj, gt_traj + ) + + if result is None: + logger.error("Evaluation w.r.t MPS failed") + return False + + logger.info(f"ATE RMSE: {result:.4f} m") + return True + +if __name__ == "__main__": + parser = argparse.ArgumentParser( + description="Evaluate an estimated trajectory with respect to MPS pGT." + ) + parser.add_argument( + "--estimate", + type=Path, + required=True, + help="Path to the pose estimate file.", + ) + parser.add_argument( + "--gt_estimate", + type=Path, + required=True, + help="Path to the MPS pGT file.", + ) + args = parser.parse_args() + + run( + args.estimate, + args.gt_estimate, + ) From 9c8ca1aa3e22e38cf8ebc68f91333ffe22f3df37 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:50:25 +0200 Subject: [PATCH 569/665] evo eval --- lamaria/eval/evo_evaluation.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/eval/evo_evaluation.py b/lamaria/eval/evo_evaluation.py index 9c6f1ae..51f9e5d 100644 --- a/lamaria/eval/evo_evaluation.py +++ b/lamaria/eval/evo_evaluation.py @@ -64,7 +64,7 @@ def convert_trajectory_to_evo_posetrajectory( def evaluate_wrt_mps( est_traj: Trajectory, gt_traj: Trajectory, -) -> None: +) -> float | None: """ Evaluate an estimated trajectory with respect to MPS pGT. Alignment performed using Umeyama via evo package. @@ -89,7 +89,7 @@ def evaluate_wrt_mps( if not valid_estimate(est_pose_traj, gt_pose_traj): logger.error("Estimated trajectory is too short compared to pGT.") - return False + return None gt_pose_traj_sync, est_pose_traj_sync = sync.associate_trajectories( gt_pose_traj, From c82690d365e32abbff9ff63cae03af52eeca25fe Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:52:32 +0200 Subject: [PATCH 570/665] ate rmse --- evaluate_wrt_control_points.py | 9 ++++++--- evaluate_wrt_mps.py | 21 ++++++++------------- lamaria/eval/evo_evaluation.py | 32 ++++++++++++-------------------- 3 files changed, 26 insertions(+), 36 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index b8354a9..78a2eb3 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -9,7 +9,10 @@ ) from lamaria.structs.trajectory import Trajectory from lamaria.utils.aria import initialize_reconstruction_from_calibration_file -from lamaria.utils.metrics import calculate_control_point_score, calculate_control_point_recall +from lamaria.utils.metrics import ( + calculate_control_point_recall, + calculate_control_point_score, +) def run( @@ -65,11 +68,11 @@ def run( reconstruction, control_points, ) - + if result is None: logger.error("Sparse evaluation failed.") return False - + result_path = output_path / "sparse_eval_result.npy" result.save_as_npy(result_path) diff --git a/evaluate_wrt_mps.py b/evaluate_wrt_mps.py index 7f4b2cd..427b594 100644 --- a/evaluate_wrt_mps.py +++ b/evaluate_wrt_mps.py @@ -10,7 +10,7 @@ def run( estimate: Path, gt_estimate: Path, ) -> bool: - """Evaluate an estimated trajectory with respect to + """Evaluate an estimated trajectory with respect to MPS pGT. There are no control points involved when evaluating using this function. Resorting to evo package for the evaluation. @@ -23,31 +23,26 @@ def run( bool: True if the evaluation was successful, False otherwise. """ - est_traj = Trajectory.load_from_file( - estimate, invert_poses=False - ) + est_traj = Trajectory.load_from_file(estimate, invert_poses=False) if not est_traj.is_loaded(): logger.error("Estimate could not be loaded") return False - - gt_traj = Trajectory.load_from_file( - gt_estimate, invert_poses=False - ) + + gt_traj = Trajectory.load_from_file(gt_estimate, invert_poses=False) if not gt_traj.is_loaded(): logger.error("Ground-truth estimate could not be loaded") return False - - result = evaluate_wrt_mps( - est_traj, gt_traj - ) + + result = evaluate_wrt_mps(est_traj, gt_traj) if result is None: logger.error("Evaluation w.r.t MPS failed") return False - + logger.info(f"ATE RMSE: {result:.4f} m") return True + if __name__ == "__main__": parser = argparse.ArgumentParser( description="Evaluate an estimated trajectory with respect to MPS pGT." diff --git a/lamaria/eval/evo_evaluation.py b/lamaria/eval/evo_evaluation.py index 51f9e5d..585ac11 100644 --- a/lamaria/eval/evo_evaluation.py +++ b/lamaria/eval/evo_evaluation.py @@ -1,5 +1,4 @@ import numpy as np - from evo.core import metrics, sync from evo.core.trajectory import PoseTrajectory3D @@ -12,7 +11,7 @@ def valid_estimate( gt_pose_traj: PoseTrajectory3D, min_duration_ratio: float = 0.5, ) -> bool: - """" Check if the estimated trajectory is at least + """ Check if the estimated trajectory is at least half as long as the ground-truth trajectory in terms of timestamps overlap. Args: @@ -21,21 +20,18 @@ def valid_estimate( Returns: bool: True if valid, False otherwise. """ - + est_timestamps = est_pose_traj.timestamps gt_timestamps = gt_pose_traj.timestamps gt_length = (gt_timestamps[-1] - gt_timestamps[0]) / 1e9 est_length = (est_timestamps[-1] - est_timestamps[0]) / 1e9 - if est_length < min_duration_ratio * gt_length: - return False - - return True + return not est_length < min_duration_ratio * gt_length def convert_trajectory_to_evo_posetrajectory( - traj: Trajectory + traj: Trajectory, ) -> PoseTrajectory3D: """Convert a Trajectory to an evo PoseTrajectory3D. Args: @@ -47,9 +43,9 @@ def convert_trajectory_to_evo_posetrajectory( if not traj.invert_poses: poses = traj.poses else: - # store in COLMAP format (i.e., rig_from_world) + # stored in COLMAP format (i.e., rig_from_world) poses = [pose.inverse() for pose in traj.poses] - + timestamps = traj.timestamps assert len(poses) == len(timestamps), "Poses and timestamps length mismatch" @@ -66,7 +62,7 @@ def evaluate_wrt_mps( gt_traj: Trajectory, ) -> float | None: """ - Evaluate an estimated trajectory with respect to + Evaluate an estimated trajectory with respect to MPS pGT. Alignment performed using Umeyama via evo package. Important: This function assumes that invert_poses=False for both trajectories. @@ -90,22 +86,19 @@ def evaluate_wrt_mps( if not valid_estimate(est_pose_traj, gt_pose_traj): logger.error("Estimated trajectory is too short compared to pGT.") return None - + gt_pose_traj_sync, est_pose_traj_sync = sync.associate_trajectories( - gt_pose_traj, + gt_pose_traj, est_pose_traj, - max_diff=1e6 # 1 ms in ns + max_diff=1e6, # 1 ms in ns ) try: - est_pose_traj_sync.align( - gt_pose_traj_sync, - correct_scale=True - ) + est_pose_traj_sync.align(gt_pose_traj_sync, correct_scale=True) except Exception as e: logger.error(f"Alignment failed: {e}") return None - + pose_relation = metrics.PoseRelation.translation_part trajectories = (gt_pose_traj_sync, est_pose_traj_sync) ate_metric = metrics.APE(pose_relation) @@ -114,5 +107,4 @@ def evaluate_wrt_mps( ate_stats = ate_metric.get_all_statistics() return ate_stats["rmse"] - From abc13a292acd429e00e80470f9dcfd15786f2c36 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:52:38 +0200 Subject: [PATCH 571/665] ruff --- lamaria/eval/evo_evaluation.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/eval/evo_evaluation.py b/lamaria/eval/evo_evaluation.py index 585ac11..8369ceb 100644 --- a/lamaria/eval/evo_evaluation.py +++ b/lamaria/eval/evo_evaluation.py @@ -107,4 +107,3 @@ def evaluate_wrt_mps( ate_stats = ate_metric.get_all_statistics() return ate_stats["rmse"] - From c625bf4efa743098e733bb54949fba626ebf6c57 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:53:08 +0200 Subject: [PATCH 572/665] ruff --- lamaria/eval/sparse_evaluation.py | 1 - lamaria/structs/sparse_eval.py | 6 +++--- lamaria/structs/trajectory.py | 7 ++++--- lamaria/utils/metrics.py | 29 ++++++++++++----------------- 4 files changed, 19 insertions(+), 24 deletions(-) diff --git a/lamaria/eval/sparse_evaluation.py b/lamaria/eval/sparse_evaluation.py index 34c5297..d74089d 100644 --- a/lamaria/eval/sparse_evaluation.py +++ b/lamaria/eval/sparse_evaluation.py @@ -1,4 +1,3 @@ - import pyceres import pycolmap diff --git a/lamaria/structs/sparse_eval.py b/lamaria/structs/sparse_eval.py index b55035d..90c4c6b 100644 --- a/lamaria/structs/sparse_eval.py +++ b/lamaria/structs/sparse_eval.py @@ -148,10 +148,10 @@ def add_residuals_for_sparse_eval( return problem - @dataclass(slots=True) class SparseEvalResult: """Container for sparse evaluation results.""" + alignment: pycolmap.Sim3d cp_summary: dict[int, ControlPointSummary] @@ -174,14 +174,14 @@ def load_from_npy(cls, path: Path) -> "SparseEvalResult": return None data = np.load(path, allow_pickle=True).item() - + try: cp_summary = data["cp_summary"] alignment = data["alignment"] except KeyError as e: logger.error(f"Missing key in data: {e}") return None - + return cls(cp_summary=cp_summary, alignment=alignment) def save_as_npy(self, path: Path) -> None: diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 0fbdca5..3514721 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -1,6 +1,6 @@ +from dataclasses import dataclass from decimal import ROUND_HALF_UP, Decimal from pathlib import Path -from dataclasses import dataclass import numpy as np import pycolmap @@ -24,6 +24,7 @@ def _round_ns(x: str | int | float) -> int: s = str(x) return int(Decimal(s).to_integral_value(rounding=ROUND_HALF_UP)) + @dataclass(slots=True) class Trajectory: """ @@ -33,9 +34,9 @@ class Trajectory: By default, poses are calculated as rig_from_world (i.e., inverse of world_from_rig) to satisfy COLMAP format. - + Attributes: - invert_poses (bool): Whether to invert poses to + invert_poses (bool): Whether to invert poses to rig_from_world format. corresponding_sensor (str): The reference sensor to in which the trajectory is represented ("imu" or "cam0"). diff --git a/lamaria/utils/metrics.py b/lamaria/utils/metrics.py index d1bb9a6..f09f136 100644 --- a/lamaria/utils/metrics.py +++ b/lamaria/utils/metrics.py @@ -1,5 +1,3 @@ -from pathlib import Path - import numpy as np import pycolmap from scipy.interpolate import interp1d @@ -32,15 +30,14 @@ def piecewise_linear_scoring(): ) return scoring -def calculate_control_point_score( - result: SparseEvalResult -) -> float: - """ Calculate CP score from SparseEvalResult object. """ + +def calculate_control_point_score(result: SparseEvalResult) -> float: + """Calculate CP score from SparseEvalResult object.""" error_2d = calculate_error(result) if any(e < 0 for e in error_2d): logger.error("Negative errors found, norm error cannot be negative.") return 0.0 - + errors = np.nan_to_num(error_2d, nan=1e6) # Large error for NaNs scoring = piecewise_linear_scoring() scores = scoring(errors) @@ -53,28 +50,26 @@ def calculate_control_point_score( def calculate_control_point_recall( result: SparseEvalResult, - threshold: float = 1.0 # meters + threshold: float = 1.0, # meters ) -> float: - """ Calculate CP recall from SparseEvalResult object. """ + """Calculate CP recall from SparseEvalResult object.""" error_2d = calculate_error(result) if len(error_2d) == 0: return 0.0 - + if any(e < 0 for e in error_2d): logger.error("Negative errors found, norm error cannot be negative.") return 0.0 - + errors = np.nan_to_num(error_2d, nan=1e6) # Large error for NaNs inliers = np.sum(errors <= threshold) recall = inliers / len(errors) * 100 return recall -def calculate_error( - result: SparseEvalResult -) -> np.ndarray: - """ Calculate 2D errors from SparseEvalResult""" - sim3d = result.alignment # sim3d cannot be None here +def calculate_error(result: SparseEvalResult) -> np.ndarray: + """Calculate 2D errors from SparseEvalResult""" + sim3d = result.alignment # sim3d cannot be None here if not isinstance(sim3d, pycolmap.Sim3d): logger.error("No valid Sim3d found in SparseEvalResult") return np.array([]) @@ -90,5 +85,5 @@ def calculate_error( error_2d.append(e) assert len(error_2d) == len(result.cp_summary), "Error length mismatch" - + return np.array(error_2d) From abd86dd116bdf9f496d1ec759db54ecf9d94b721 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 19:56:12 +0200 Subject: [PATCH 573/665] fix --- lamaria/eval/evo_evaluation.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lamaria/eval/evo_evaluation.py b/lamaria/eval/evo_evaluation.py index 8369ceb..6c81f89 100644 --- a/lamaria/eval/evo_evaluation.py +++ b/lamaria/eval/evo_evaluation.py @@ -11,7 +11,7 @@ def valid_estimate( gt_pose_traj: PoseTrajectory3D, min_duration_ratio: float = 0.5, ) -> bool: - """ Check if the estimated trajectory is at least + """Check if the estimated trajectory is at least half as long as the ground-truth trajectory in terms of timestamps overlap. Args: From e687790180483d56f1cb47ed2da18caef8ba817b Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 20:37:00 +0200 Subject: [PATCH 574/665] split estimate and mps in the data init. --- defaults.yaml | 7 +- example_vi_optimization.py | 55 ++++--- lamaria/config/options.py | 40 +---- lamaria/config/pipeline.py | 43 ++--- .../estimate_to_timed_reconstruction.py | 96 +++++++++++ .../mps_to_timed_reconstruction.py} | 153 ++++-------------- lamaria/pipeline/optim/triangulation.py | 1 + lamaria/utils/aria.py | 103 +++++++++++- lamaria/utils/types.py | 5 + 9 files changed, 288 insertions(+), 215 deletions(-) create mode 100644 lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py rename lamaria/pipeline/{keyframing/to_vi_reconstruction.py => data_init/mps_to_timed_reconstruction.py} (72%) create mode 100644 lamaria/utils/types.py diff --git a/defaults.yaml b/defaults.yaml index 73212a1..7fd040c 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -1,8 +1,4 @@ # Default configuration for run_pipeline.py -sensor: - camera_model: RAD_TAN_THIN_PRISM_FISHEYE - has_slam_drops: false - keyframing: max_rotation: 20.0 max_distance: 1.0 @@ -48,4 +44,5 @@ optimization: acc_infl: 1.0 integration_noise_density: 0.05 - use_mps_online_calibration: false # relevant only when mps folder is used +use_mps_online_calibration: false # relevant only when mps folder is used +has_slam_drops: false diff --git a/example_vi_optimization.py b/example_vi_optimization.py index 992deac..9aec62d 100644 --- a/example_vi_optimization.py +++ b/example_vi_optimization.py @@ -5,26 +5,32 @@ import pycolmap from lamaria.config.options import ( - EstimateToTimedReconOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, ) from lamaria.config.pipeline import PipelineOptions -from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector -from lamaria.pipeline.keyframing.to_vi_reconstruction import ( - EstimateToTimedRecon, +from lamaria.pipeline.data_init.estimate_to_timed_reconstruction import ( + convert_estimate_into_timed_reconstruction, +) +from lamaria.pipeline.data_init.mps_to_timed_reconstruction import ( + MPSToTimedRecon, ) +from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector from lamaria.pipeline.optim.session import SingleSeqSession from lamaria.pipeline.optim.triangulation import run as triangulate from lamaria.pipeline.optim.vi_optimization import VIOptimizer from lamaria.structs.timed_reconstruction import TimedReconstruction +from lamaria.structs.trajectory import Trajectory from lamaria.structs.vi_reconstruction import VIReconstruction -from lamaria.utils.aria import get_imu_data_from_vrs_file +from lamaria.utils.aria import ( + extract_images_with_timestamps_from_vrs, + get_imu_data_from_vrs_file, + initialize_reconstruction_from_vrs_file, +) -def run_estimate_to_vi_recon( - options: EstimateToTimedReconOptions, +def run_estimate_to_timed_recon( vrs: Path, images_path: Path, estimate: Path, @@ -32,29 +38,34 @@ def run_estimate_to_vi_recon( """Function to convert a general input estimate file to a TimedReconstruction. """ - vi_recon = EstimateToTimedRecon.convert( - options, - vrs, - images_path, - estimate, + traj = Trajectory.load_from_file(estimate) + init_recon = initialize_reconstruction_from_vrs_file(vrs) + timestamps_to_images = extract_images_with_timestamps_from_vrs( + vrs, images_path ) - return vi_recon + timed_recon = convert_estimate_into_timed_reconstruction( + init_recon, traj, timestamps_to_images + ) + return timed_recon -def run_mps_to_vi_recon( - options: EstimateToTimedReconOptions, +def run_mps_to_timed_recon( vrs: Path, images_path: Path, mps_folder: Path, + use_online_calibration: bool = False, + has_slam_drops: bool = False, ) -> TimedReconstruction: """Function to convert MPS estimate to a TimedReconstruction.""" - vi_recon = EstimateToTimedRecon.convert( - options, + timed_recon = MPSToTimedRecon( + use_online_calibration=use_online_calibration, + has_slam_drops=has_slam_drops, + ).convert( vrs, images_path, mps_folder, ) - return vi_recon + return timed_recon def run_keyframe_selection( @@ -133,8 +144,7 @@ def run_pipeline( "Estimate path must be provided if not using MPS" ) - recon = run_estimate_to_vi_recon( - options.estimate_to_colmap_options, + recon = run_estimate_to_timed_recon( vrs, output_path / "images", estimate, @@ -145,11 +155,12 @@ def run_pipeline( "MPS folder path must be provided if using MPS" ) - recon = run_mps_to_vi_recon( - options.estimate_to_colmap_options, + recon = run_mps_to_timed_recon( vrs, output_path / "images", mps_folder, + use_online_calibration=options.use_mps_online_calibration, + has_slam_drops=options.has_slam_drops, ) recon.write(init_recon_path) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index af486e4..67c5141 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -16,42 +16,6 @@ def _structured_merge_to_obj(cls, section) -> object: return OmegaConf.to_object(merged) -@dataclass(slots=True) -class SensorOptions: - camera_model: str = "RAD_TAN_THIN_PRISM_FISHEYE" - has_slam_drops: bool = ( - False # check vrs json metadata file for each sequence - ) - - @classmethod - def load(cls, cfg: OmegaConf | None = None) -> SensorOptions: - if cfg is None: - return cls() - - obj: SensorOptions = _structured_merge_to_obj(cls, cfg) - return obj - - -# Estimate to COLMAP options -@dataclass(slots=True) -class EstimateToTimedReconOptions: - sensor: SensorOptions = field(default_factory=SensorOptions) - - @classmethod - def load( - cls, - cfg_sensor: OmegaConf | None = None, - ) -> EstimateToTimedReconOptions: - if cfg_sensor is None: - return cls() - - base = cls() - return replace( - base, - sensor=SensorOptions.load(cfg_sensor), - ) - - # Keyframing options @dataclass(slots=True) class KeyframeSelectorOptions: @@ -150,5 +114,7 @@ def load(cls, cfg: OmegaConf | None = None) -> VIOptimizerOptions: cam=cam, imu=imu, optim=optim, - use_mps_online_calibration=cfg.use_mps_online_calibration, + use_mps_online_calibration=cfg.get( + "use_mps_online_calibration", False + ), ) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 65e35d0..3008989 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -1,26 +1,30 @@ from collections.abc import Sequence +from dataclasses import dataclass, field, replace from pathlib import Path from omegaconf import DictConfig, OmegaConf from .options import ( - EstimateToTimedReconOptions, KeyframeSelectorOptions, TriangulatorOptions, VIOptimizerOptions, ) +@dataclass class PipelineOptions: - def __init__(self) -> None: - self._estimate_to_colmap_options: EstimateToTimedReconOptions = ( - EstimateToTimedReconOptions() - ) - self._keyframing_options: KeyframeSelectorOptions = ( - KeyframeSelectorOptions() - ) - self._triangulator_options: TriangulatorOptions = TriangulatorOptions() - self._vi_optimizer_options: VIOptimizerOptions = VIOptimizerOptions() + _keyframing_options: KeyframeSelectorOptions = field( + default_factory=KeyframeSelectorOptions + ) + _triangulator_options: TriangulatorOptions = field( + default_factory=TriangulatorOptions + ) + _vi_optimizer_options: VIOptimizerOptions = field( + default_factory=VIOptimizerOptions + ) + + use_mps_online_calibration: bool = False + has_slam_drops: bool = False def load( self, @@ -39,20 +43,14 @@ def load( def _update_from_cfg(self, cfg: DictConfig) -> None: """Update object attributes from a config.""" - self._estimate_to_colmap_options = EstimateToTimedReconOptions.load( - cfg.sensor, - ) self._keyframing_options = KeyframeSelectorOptions.load(cfg.keyframing) self._triangulator_options = TriangulatorOptions.load(cfg.triangulation) self._vi_optimizer_options = VIOptimizerOptions.load(cfg.optimization) - out = cfg.get("output_path", None) - self._output_path = Path(out) if out is not None else Path("/output/") - - # Properties for estimate to COLMAP - @property - def estimate_to_colmap_options(self) -> EstimateToTimedReconOptions: - return self._estimate_to_colmap_options + self.use_mps_online_calibration = cfg.get( + "use_mps_online_calibration", False + ) + self.has_slam_drops = cfg.get("has_slam_drops", False) # Properties for keyframing @property @@ -67,4 +65,7 @@ def triangulator_options(self) -> TriangulatorOptions: # Properties for visual-inertial optimization @property def vi_optimizer_options(self) -> VIOptimizerOptions: - return self._vi_optimizer_options + return replace( + self._vi_optimizer_options, + use_mps_online_calibration=self.use_mps_online_calibration, + ) diff --git a/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py b/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py new file mode 100644 index 0000000..c1d98c7 --- /dev/null +++ b/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py @@ -0,0 +1,96 @@ +from bisect import bisect_left +from pathlib import Path +import pycolmap + +from ...structs.timed_reconstruction import TimedReconstruction +from ...structs.trajectory import ( + Trajectory, +) +from ...utils.types import InitReconstruction + +def _image_names_from_folder(folder: Path, wrt_to: Path, ext: str = ".jpg") -> list[Path]: + if not folder.is_dir(): + return [] + images = sorted(n for n in folder.iterdir() if n.suffix == ext) + images = [n.relative_to(wrt_to) for n in images] + return images + +def _match_estimate_ts_to_images( + timestamps_to_images: dict[int, tuple[Path, Path]], + est_timestamps: list[int], + max_diff: int = 1000000, # 1 ms +) -> tuple[list[tuple[Path, Path]], list[int]]: + left_ts = list(timestamps_to_images.keys()) + images = list(timestamps_to_images.values()) + assert len(images) == len(left_ts), ( + "Number of images and left timestamps must be equal" + ) + + order = sorted(range(len(left_ts)), key=lambda i: left_ts[i]) + left_ts = [left_ts[i] for i in order] + images = [images[i] for i in order] + + matched_images: list[tuple[Path, Path]] = [] + matched_timestamps: list[int] = [] + + # estimate timestamps will be in nanoseconds like vrs timestamps + for est in est_timestamps: + idx = bisect_left(left_ts, est) + + cand_idxs = [] + if idx > 0: + cand_idxs.append(idx - 1) + if idx < len(left_ts): + cand_idxs.append(idx) + + if not cand_idxs: + continue + + best = min(cand_idxs, key=lambda j: abs(left_ts[j] - est)) + if (max_diff is not None) and (abs(left_ts[best] - est) > max_diff): + continue + + matched_images.append(images[best]) + matched_timestamps.append(left_ts[best]) + return dict(zip(matched_timestamps, matched_images)) + + +def convert_estimate_into_timed_reconstruction(init_reconstruction: InitReconstruction, estimate: Trajectory, timestamps_to_images: dict[int, tuple[Path, Path]]) -> TimedReconstruction: + ''' + Populate images, frames and timestamps in an TimedReconstruction from a trajectory + ''' + est_timestamps_to_images = _match_estimate_ts_to_images(timestamps_to_images, estimate.timestamps) + + assert estimate.corresponding_sensor == "imu" + timestamps = list(timestamps_to_images.keys()) + assert len(estimate.poses) == len(timestamps), "The length of traj.poses and timestamps should be equal" + + recon = copy.deepcopy(init_recon) + image_id = 1 + frame_id_to_timestamp = dict() + for frame_id, (pose, timestamp) in enumerate(zip(estimate.poses, timestamps)): + frame = pycolmap.Frame() + frame.rig_id = 1 + frame.frame_id = frame_id + frame.rig_from_world = pose # as it corresponds to imu + + image_names = timestamps_to_images(timestamp) + images_to_add = [] + for cam_id, img_path in [(2, image_names[0]), (3, image_names[1])]: + im = pycolmap.Image( + str(img_path), + pycolmap.Point2DList(), + cam_id, + image_id, + ) + im.frame_id = frame.frame_id + frame.add_data_id(im.data_id) + images_to_add.append(im) + image_id += 1 + recon.add_frame(frame) + for im in images_to_add: + recon.add_image(im) + frame_id_to_timestamp[frame_id] = timestamp + + return TimedReconstruction(reconstruction=recon, timestamps=frame_id_to_timestamp) + diff --git a/lamaria/pipeline/keyframing/to_vi_reconstruction.py b/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py similarity index 72% rename from lamaria/pipeline/keyframing/to_vi_reconstruction.py rename to lamaria/pipeline/data_init/mps_to_timed_reconstruction.py index 50941e3..744511b 100644 --- a/lamaria/pipeline/keyframing/to_vi_reconstruction.py +++ b/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py @@ -9,11 +9,7 @@ from projectaria_tools.core.stream_id import StreamId from ... import logger -from ...config.options import EstimateToTimedReconOptions from ...structs.timed_reconstruction import TimedReconstruction -from ...structs.trajectory import ( - Trajectory, -) from ...utils.aria import ( camera_colmap_from_calib, extract_images_from_vrs, @@ -31,7 +27,7 @@ get_matched_timestamps, ) - +# TODO: remove this @dataclass class PerFrameData: left_ts: int @@ -41,38 +37,29 @@ class PerFrameData: rig_from_world: pycolmap.Rigid3d -class EstimateToTimedRecon: - """Converts estimate or MPS data to COLMAP format.""" +class MPSToTimedRecon: + # TODO: convert this class into functions + """Converts MPS data to COLMAP format.""" + + def __init__(self, use_online_calibration: bool=False, has_slam_drops: bool = False): + self.use_online_calibration = use_online_calibration + self.has_slam_drops = has_slam_drops - def __init__(self, options: EstimateToTimedReconOptions): - self.options = options - self.data: TimedReconstruction = TimedReconstruction() self._vrs_provider = None self._mps_data_provider = None self._per_frame_data: dict[int, PerFrameData] = {} - @staticmethod - def convert( - options: EstimateToTimedReconOptions, - vrs: Path, - images_path: Path, - estimate: Path | None = None, - mps_folder: Path | None = None, - ) -> TimedReconstruction: - """Entry point to run estimate/MPS to colmap conversion.""" - to_colmap = EstimateToTimedRecon(options) - return to_colmap.process(vrs, images_path, estimate, mps_folder) + self.data: TimedReconstruction = TimedReconstruction() - def process( + def convert( self, vrs: Path, images_path: Path, - estimate: Path | None = None, - mps_folder: Path | None = None, + mps_folder: Path, ) -> TimedReconstruction: - self._init_data(vrs, images_path, estimate, mps_folder) + self._init_data(vrs, images_path, mps_folder) - if self.options.mps.use_online_calibration: + if self.use_online_calibration: self._add_online_sensors() self._add_online_frames() else: @@ -89,8 +76,7 @@ def _init_data( self, vrs: Path, image_folder: Path, - estimate: Path | None = None, - mps_folder: Path | None = None, + mps_folder: Path, ) -> None: """Initializes data providers and extracts images, timestamps and builds per-frame data object. @@ -107,13 +93,6 @@ def _init_data( self._right_cam_sid = StreamId(RIGHT_CAMERA_STREAM_ID) self._right_imu_sid = StreamId(RIGHT_IMU_STREAM_ID) - # Initialize MPS data provider if needed - if mps_folder is not None: - data_paths = mps.MpsDataPathsProvider( - mps_folder.as_posix() - ).get_data_paths() - self._mps_data_provider = mps.MpsDataProvider(data_paths) - # Extract images from VRS file extract_images_from_vrs( vrs_file=vrs, @@ -123,29 +102,15 @@ def _init_data( images = self._get_images(image_folder) # Get timestamps and build per-frame data - if estimate is None: - timestamps = self._get_mps_timestamps() - closed_loop_data = get_closed_loop_data_from_mps(mps_folder) - pose_timestamps = [left for left, _ in timestamps] - mps_poses = get_mps_poses_for_timestamps( - closed_loop_data, pose_timestamps - ) - self._per_frame_data = self._build_per_frame_data_from_mps( - images, timestamps, mps_poses - ) - else: - traj = Trajectory.load_from_file(estimate, invert_poses=True) - - timestamps = traj.timestamps - if len(images) != len(timestamps): - images, timestamps = self._match_estimate_ts_to_images( - images, timestamps - ) - - rig_from_worlds = traj.poses - self._per_frame_data = self._build_per_frame_data_from_estimate( - images, timestamps, rig_from_worlds - ) + timestamps = self._get_mps_timestamps() + closed_loop_data = get_closed_loop_data_from_mps(mps_folder) + pose_timestamps = [left for left, _ in timestamps] + mps_poses = get_mps_poses_for_timestamps( + closed_loop_data, pose_timestamps + ) + self._per_frame_data = self._build_per_frame_data_from_mps( + images, timestamps, mps_poses + ) def _build_per_frame_data_from_mps( self, images, timestamps, mps_poses @@ -155,7 +120,7 @@ def _build_per_frame_data_from_mps( self._right_imu_sid ) - if not self.options.mps.use_online_calibration: + if not self.use_online_calibration: device_calibration = self._vrs_provider.get_device_calibration() imu_calib = device_calibration.get_imu_calib(imu_stream_label) @@ -167,7 +132,7 @@ def _build_per_frame_data_from_mps( if t_world_device is None: continue - if self.options.mps.use_online_calibration: + if self.mps.use_online_calibration: ocalib = self._mps_data_provider.get_online_calibration( left_ts, TimeQueryOptions.CLOSEST ) @@ -196,31 +161,6 @@ def _build_per_frame_data_from_mps( return per_frame_data - def _build_per_frame_data_from_estimate( - self, images, timestamps, rig_from_worlds - ) -> dict[int, PerFrameData]: - per_frame_data: dict[int, PerFrameData] = {} - assert len(images) == len(timestamps) == len(rig_from_worlds), ( - "Number of images, timestamps and poses must be equal" - ) - - frame_id = 1 - - for (left_img, right_img), ts, rig_from_world in zip( - images, timestamps, rig_from_worlds - ): - pfd = PerFrameData( - left_ts=ts, - right_ts=ts, - left_img=left_img, - right_img=right_img, - rig_from_world=rig_from_world, - ) - per_frame_data[frame_id] = pfd - frame_id += 1 - - return per_frame_data - def _images_from_vrs( self, folder: Path, wrt_to: Path, ext: str = ".jpg" ) -> list[Path]: @@ -248,7 +188,7 @@ def _get_images(self, images_path: Path) -> list[tuple[Path, Path]]: def _get_mps_timestamps(self, max_diff=1e6) -> list[tuple[int, int]]: L = self._ts_from_vrs(self._left_cam_sid) R = self._ts_from_vrs(self._right_cam_sid) - if not self.options.sensor.has_slam_drops: + if not self.has_slam_drops: assert len(L) == len(R), ( "Unequal number of left and right timestamps" ) @@ -263,46 +203,6 @@ def _get_mps_timestamps(self, max_diff=1e6) -> list[tuple[int, int]]: return matched - def _match_estimate_ts_to_images( - self, - images: list[tuple[Path, Path]], - est_timestamps: list[int], - max_diff: int = 1000000, # 1 ms - ) -> tuple[list[tuple[Path, Path]], list[int]]: - left_ts = self._ts_from_vrs(self._left_cam_sid) - assert len(images) == len(left_ts), ( - "Number of images and left timestamps must be equal" - ) - - order = sorted(range(len(left_ts)), key=lambda i: left_ts[i]) - left_ts = [left_ts[i] for i in order] - images = [images[i] for i in order] - - matched_images: list[tuple[Path, Path]] = [] - matched_timestamps: list[int] = [] - - # estimate timestamps will be in nanoseconds like vrs timestamps - for est in est_timestamps: - idx = bisect_left(left_ts, est) - - cand_idxs = [] - if idx > 0: - cand_idxs.append(idx - 1) - if idx < len(left_ts): - cand_idxs.append(idx) - - if not cand_idxs: - continue - - best = min(cand_idxs, key=lambda j: abs(left_ts[j] - est)) - if (max_diff is not None) and (abs(left_ts[best] - est) > max_diff): - continue - - matched_images.append(images[best]) - matched_timestamps.append(left_ts[best]) - - return matched_images, matched_timestamps - def _add_device_sensors(self) -> None: """Adds a new rig with device calibrated sensors. The rig is consistent across all frames @@ -471,3 +371,4 @@ def _add_online_frames(self) -> None: self.data.reconstruction.add_frame(frame) for im in images_to_add: self.data.reconstruction.add_image(im) + diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index 8667ca1..6673a52 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -4,6 +4,7 @@ from pathlib import Path import pycolmap + from hloc import ( extract_features, match_features, diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index c62b2cb..a039bce 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -2,7 +2,6 @@ import shutil import subprocess from pathlib import Path -from typing import TypeAlias import numpy as np import pycolmap @@ -14,14 +13,18 @@ from scipy.spatial.transform import Rotation from tqdm import tqdm +from ...utils.constants import ( + ARIA_CAMERAS, + LEFT_CAMERA_STREAM_ID, + RIGHT_CAMERA_STREAM_ID, + RIGHT_IMU_STREAM_ID, +) from .. import logger -from .constants import ARIA_CAMERAS, RIGHT_IMU_STREAM_ID from .timestamps import find_closest_timestamp +from .types import InitReconstruction # ----- Reconstruction functions ----- # -InitReconstruction: TypeAlias = pycolmap.Reconstruction - def initialize_reconstruction_from_calibration_file( calibration_file: Path, @@ -466,6 +469,53 @@ def get_imu_data_from_vrs_file( # ----- VRS utils ----- # +# TODO: merge this with initialize_reconstruction_from_calibration_file +def initialize_reconstruction_from_vrs_file( + vrs_file: Path, +) -> InitReconstruction: + """ + Return a pycolmap.Reconstruction with only cameras and rigs populated. + """ + # Initialize VRS data provider + vrs_provider = data_provider.create_vrs_data_provider(vrs_file.as_posix()) + + # build reconstruction + recon = pycolmap.Reconstruction() + device_calibration = vrs_provider.get_device_calibration() + imu_stream_label = vrs_provider.get_label_from_stream_id( + StreamId(RIGHT_IMU_STREAM_ID) + ) + imu_calib = device_calibration.get_imu_calib(imu_stream_label) + + rig = pycolmap.Rig(rig_id=1) + + # DUMMY CAMERA FOR IMU, IMU ID is 1 + imu = pycolmap.Camera(camera_id=1, model="SIMPLE_PINHOLE", params=[0, 0, 0]) + recon.add_camera(imu) + rig.add_ref_sensor(imu.sensor_id) + + for cam_id, sid in [ + (2, StreamId(LEFT_CAMERA_STREAM_ID)), + (3, StreamId(RIGHT_CAMERA_STREAM_ID)), + ]: + stream_label = vrs_provider.get_label_from_stream_id(sid) + camera_calib = device_calibration.get_camera_calib(stream_label) + cam = camera_colmap_from_calib(camera_calib) + cam.camera_id = cam_id + + t_imu_camera = get_t_imu_camera( + imu_calib, + camera_calib, + ) + sensor_from_rig = t_imu_camera.inverse() + + recon.add_camera(cam) + rig.add_sensor(cam.sensor_id, sensor_from_rig) + + recon.add_rig(rig) + return recon + + def extract_images_from_vrs( vrs_file: Path, image_folder: Path, @@ -509,3 +559,48 @@ def extract_images_from_vrs( msg += "\n" + out.stdout.decode("utf-8") raise subprocess.SubprocessError(msg) logger.info("Done!") + + +def _image_names_from_folder( + folder: Path, wrt_to: Path, ext: str = ".jpg" +) -> list[Path]: + if not folder.is_dir(): + return [] + images = sorted(n for n in folder.iterdir() if n.suffix == ext) + images = [n.relative_to(wrt_to) for n in images] + return images + + +def extract_images_with_timestamps_from_vrs( + vrs_file, images_path +) -> dict[int, tuple[Path, Path]]: + """ + Return timestamps -> image names + """ + + # Initialize VRS data provider + vrs_provider = data_provider.create_vrs_data_provider(vrs_file.as_posix()) + left_ts = sorted( + vrs_provider.get_timestamps_ns( + StreamId(LEFT_CAMERA_STREAM_ID), TimeDomain.DEVICE_TIME + ) + ) + + # Extract images from VRS file + extract_images_from_vrs( + vrs_file=vrs_file, + image_folder=images_path, + ) + + # Get images + left_img_dir = images_path / "left" + right_img_dir = images_path / "right" + left_images = _image_names_from_folder(left_img_dir, left_img_dir) + right_images = _image_names_from_folder(right_img_dir, right_img_dir) + images = list(zip(left_images, right_images)) + + # Create a map + assert len(left_ts) == len(images), ( + "timestamps should have the same length as images" + ) + return dict(zip(left_ts, images)) diff --git a/lamaria/utils/types.py b/lamaria/utils/types.py new file mode 100644 index 0000000..f00b40d --- /dev/null +++ b/lamaria/utils/types.py @@ -0,0 +1,5 @@ +import pycolmap +from typing import TypeAlias + +InitReconstruction: TypeAlias = pycolmap.Reconstruction + From 811e9f7b46b6e181a18465a3d8def468b83a65f3 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 20:39:15 +0200 Subject: [PATCH 575/665] fix and format --- .../estimate_to_timed_reconstruction.py | 43 +++++++++++++------ .../data_init/mps_to_timed_reconstruction.py | 8 ++-- lamaria/utils/types.py | 4 +- 3 files changed, 36 insertions(+), 19 deletions(-) diff --git a/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py b/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py index c1d98c7..604e07d 100644 --- a/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py +++ b/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py @@ -1,5 +1,7 @@ from bisect import bisect_left +from copy import deepcopy from pathlib import Path + import pycolmap from ...structs.timed_reconstruction import TimedReconstruction @@ -8,13 +10,17 @@ ) from ...utils.types import InitReconstruction -def _image_names_from_folder(folder: Path, wrt_to: Path, ext: str = ".jpg") -> list[Path]: + +def _image_names_from_folder( + folder: Path, wrt_to: Path, ext: str = ".jpg" +) -> list[Path]: if not folder.is_dir(): return [] images = sorted(n for n in folder.iterdir() if n.suffix == ext) images = [n.relative_to(wrt_to) for n in images] return images + def _match_estimate_ts_to_images( timestamps_to_images: dict[int, tuple[Path, Path]], est_timestamps: list[int], @@ -55,24 +61,34 @@ def _match_estimate_ts_to_images( return dict(zip(matched_timestamps, matched_images)) -def convert_estimate_into_timed_reconstruction(init_reconstruction: InitReconstruction, estimate: Trajectory, timestamps_to_images: dict[int, tuple[Path, Path]]) -> TimedReconstruction: - ''' - Populate images, frames and timestamps in an TimedReconstruction from a trajectory - ''' - est_timestamps_to_images = _match_estimate_ts_to_images(timestamps_to_images, estimate.timestamps) +def convert_estimate_into_timed_reconstruction( + init_reconstruction: InitReconstruction, + estimate: Trajectory, + timestamps_to_images: dict[int, tuple[Path, Path]], +) -> TimedReconstruction: + """ + Populate a TimedReconstruction from a trajectory + """ + est_timestamps_to_images = _match_estimate_ts_to_images( + timestamps_to_images, estimate.timestamps + ) assert estimate.corresponding_sensor == "imu" - timestamps = list(timestamps_to_images.keys()) - assert len(estimate.poses) == len(timestamps), "The length of traj.poses and timestamps should be equal" + timestamps = list(est_timestamps_to_images.keys()) + assert len(estimate.poses) == len(timestamps), ( + "The length of traj.poses and timestamps should be equal" + ) - recon = copy.deepcopy(init_recon) + recon = deepcopy(init_reconstruction) image_id = 1 frame_id_to_timestamp = dict() - for frame_id, (pose, timestamp) in enumerate(zip(estimate.poses, timestamps)): + for frame_id, (pose, timestamp) in enumerate( + zip(estimate.poses, timestamps) + ): frame = pycolmap.Frame() frame.rig_id = 1 frame.frame_id = frame_id - frame.rig_from_world = pose # as it corresponds to imu + frame.rig_from_world = pose # as it corresponds to imu image_names = timestamps_to_images(timestamp) images_to_add = [] @@ -92,5 +108,6 @@ def convert_estimate_into_timed_reconstruction(init_reconstruction: InitReconstr recon.add_image(im) frame_id_to_timestamp[frame_id] = timestamp - return TimedReconstruction(reconstruction=recon, timestamps=frame_id_to_timestamp) - + return TimedReconstruction( + reconstruction=recon, timestamps=frame_id_to_timestamp + ) diff --git a/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py b/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py index 744511b..0058228 100644 --- a/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py +++ b/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py @@ -1,8 +1,6 @@ -from bisect import bisect_left from dataclasses import dataclass from pathlib import Path -import projectaria_tools.core.mps as mps import pycolmap from projectaria_tools.core import data_provider from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions @@ -27,6 +25,7 @@ get_matched_timestamps, ) + # TODO: remove this @dataclass class PerFrameData: @@ -41,7 +40,9 @@ class MPSToTimedRecon: # TODO: convert this class into functions """Converts MPS data to COLMAP format.""" - def __init__(self, use_online_calibration: bool=False, has_slam_drops: bool = False): + def __init__( + self, use_online_calibration: bool = False, has_slam_drops: bool = False + ): self.use_online_calibration = use_online_calibration self.has_slam_drops = has_slam_drops @@ -371,4 +372,3 @@ def _add_online_frames(self) -> None: self.data.reconstruction.add_frame(frame) for im in images_to_add: self.data.reconstruction.add_image(im) - diff --git a/lamaria/utils/types.py b/lamaria/utils/types.py index f00b40d..b1901ff 100644 --- a/lamaria/utils/types.py +++ b/lamaria/utils/types.py @@ -1,5 +1,5 @@ -import pycolmap from typing import TypeAlias -InitReconstruction: TypeAlias = pycolmap.Reconstruction +import pycolmap +InitReconstruction: TypeAlias = pycolmap.Reconstruction From 80be58d1e2a7b1fb3842db80a2d7299519306ef2 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 20:40:32 +0200 Subject: [PATCH 576/665] fix --- lamaria/structs/vi_reconstruction.py | 2 +- lamaria/utils/aria.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/structs/vi_reconstruction.py b/lamaria/structs/vi_reconstruction.py index 27df8ab..3d23cae 100644 --- a/lamaria/structs/vi_reconstruction.py +++ b/lamaria/structs/vi_reconstruction.py @@ -34,7 +34,7 @@ def read(cls, input_folder: Path) -> "VIReconstruction": def write(self, output_folder: Path) -> None: # Write base data first - super().write_base(output_folder) + super().write(output_folder) # Write IMU data rectified_imu_data_npy = output_folder / "rectified_imu_data.npy" diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index a039bce..60cfbfd 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -13,7 +13,7 @@ from scipy.spatial.transform import Rotation from tqdm import tqdm -from ...utils.constants import ( +from .constants import ( ARIA_CAMERAS, LEFT_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, From 4d34a8b6d69d05791ad502a4566b9bec806417bb Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 20:41:59 +0200 Subject: [PATCH 577/665] format --- lamaria/pipeline/optim/triangulation.py | 1 - lamaria/utils/aria.py | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/optim/triangulation.py index 6673a52..8667ca1 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/optim/triangulation.py @@ -4,7 +4,6 @@ from pathlib import Path import pycolmap - from hloc import ( extract_features, match_features, diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index 60cfbfd..c3407fe 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -13,13 +13,13 @@ from scipy.spatial.transform import Rotation from tqdm import tqdm +from .. import logger from .constants import ( ARIA_CAMERAS, LEFT_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, RIGHT_IMU_STREAM_ID, ) -from .. import logger from .timestamps import find_closest_timestamp from .types import InitReconstruction From 4e74cb1e10cacdd98f33adfa0e073c84f6fe68db Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 20:55:31 +0200 Subject: [PATCH 578/665] installation readme --- README.md | 30 +++++++++++++++++++++++++++--- 1 file changed, 27 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 051bf0a..c3b8ac1 100644 --- a/README.md +++ b/README.md @@ -17,13 +17,33 @@ Using **LaMAria**, you can: - [Downloading the Dataset](#downloading-the-dataset) - [Evaluation](#evaluation) - [Evaluation w.r.t. Control Points](#evaluation-wrt-control-points) - - [Evaluation Against Pseudo-GT](#evaluation-against-pseudo-gt) - - [EVO Evaluation Against MPS](#evo-evaluation-against-mps) + - [Evaluation w.r.t. Pseudo-GT](#evaluation-wrt-pseudo-gt) + - [EVO Evaluation w.r.t. MPS](#evo-evaluation-wrt-mps) - [Data Conversion](#data-conversion) - [Example Visual-Inertial Optimization](#example-visual-inertial-optimization) +- [BibTeX Citation](#bibtex-citation) ## Installation +This repository supports Python 3.9 through 3.13. Installing the package `lamaria` pulls the other dependencies. + +Create an environment: +```bash +python3 -m venv lamaria_env +source lamaria_env/bin/activate +``` + +Clone the repository: +```bash +git clone git@github.com:cvg/lamaria.git +cd lamaria +pip install -r requirements.txt +``` + +Install the package: +```bash +python -m pip install -e . +``` ## Downloading the dataset @@ -45,4 +65,8 @@ Using **LaMAria**, you can: -## Example Visual-Inertial Optimization \ No newline at end of file +## Example Visual-Inertial Optimization + + + +## BibTeX citation \ No newline at end of file From f371eebaea58b89b7addbe6c6bf0839ab516e567 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 20:55:49 +0200 Subject: [PATCH 579/665] minor --- example_vi_optimization.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/example_vi_optimization.py b/example_vi_optimization.py index 9aec62d..27c0ea0 100644 --- a/example_vi_optimization.py +++ b/example_vi_optimization.py @@ -143,18 +143,15 @@ def run_pipeline( assert estimate.exists(), ( "Estimate path must be provided if not using MPS" ) - recon = run_estimate_to_timed_recon( vrs, output_path / "images", estimate, ) - else: assert mps_folder.exists(), ( "MPS folder path must be provided if using MPS" ) - recon = run_mps_to_timed_recon( vrs, output_path / "images", From 163f1948bd8671c9920a82df5b892476508e1522 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 21:08:15 +0200 Subject: [PATCH 580/665] vrs installation tools --- README.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index c3b8ac1..c0b8418 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@ We present **LaMAria**, a egocentric, city-scale benchmark for **visual-inertial Using **LaMAria**, you can: - Evaluate SLAM systems under real-world challenges: low light, moving platforms, exposure changes, extremely long trajectories. -- Benchmark against highly accurate sparse ground truths. +- Benchmark against highly accurate ground truths.

    Overview of LaMAria
    @@ -67,6 +67,9 @@ python -m pip install -e . ## Example Visual-Inertial Optimization +### Additional Installation +To extract images from a `.vrs` file, it is required to install the VRS Command Line Tools. Please follow the instructions [here](https://github.com/facebookresearch/vrs?tab=readme-ov-file#instructions-macos-and-ubuntu-and-container) to install the library from source. + ## BibTeX citation \ No newline at end of file From db93e997ed9744535ee0cc364c5493b36fb2faa1 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 21:13:27 +0200 Subject: [PATCH 581/665] fix broken impl --- .../data_init/estimate_to_timed_reconstruction.py | 2 +- lamaria/structs/trajectory.py | 11 +++++------ 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py b/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py index 604e07d..8ce9ac2 100644 --- a/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py +++ b/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py @@ -90,7 +90,7 @@ def convert_estimate_into_timed_reconstruction( frame.frame_id = frame_id frame.rig_from_world = pose # as it corresponds to imu - image_names = timestamps_to_images(timestamp) + image_names = timestamps_to_images[timestamp] images_to_add = [] for cam_id, img_path in [(2, image_names[0]), (3, image_names[1])]: im = pycolmap.Image( diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 3514721..cd9f616 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -1,4 +1,4 @@ -from dataclasses import dataclass +from dataclasses import dataclass, field from decimal import ROUND_HALF_UP, Decimal from pathlib import Path @@ -42,11 +42,10 @@ class Trajectory: the trajectory is represented ("imu" or "cam0"). """ - def __init__(self) -> None: - self.invert_poses: bool = True - self.corresponding_sensor: str = "imu" - self._timestamps: list[int] = [] - self._poses: list[pycolmap.Rigid3d] = [] + invert_poses: bool = True + corresponding_sensor: str = "imu" + _timestamps: list[int] = field(default_factory=list[int]) + _poses: list[pycolmap.Rigid3d] = field(default_factory=list[pycolmap.Rigid3d]) @classmethod def load_from_file( From 0b12d3b231d8ce9f46a026f28d0d751cb8f83a10 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Mon, 29 Sep 2025 21:14:13 +0200 Subject: [PATCH 582/665] format --- lamaria/structs/trajectory.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index cd9f616..9bacf5c 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -45,7 +45,9 @@ class Trajectory: invert_poses: bool = True corresponding_sensor: str = "imu" _timestamps: list[int] = field(default_factory=list[int]) - _poses: list[pycolmap.Rigid3d] = field(default_factory=list[pycolmap.Rigid3d]) + _poses: list[pycolmap.Rigid3d] = field( + default_factory=list[pycolmap.Rigid3d] + ) @classmethod def load_from_file( From a7bed5f769a0b2977c30730b89721633a85f7864 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 21:14:16 +0200 Subject: [PATCH 583/665] RGB CAMERA STREAM ID --- lamaria/utils/aria.py | 7 ++++--- lamaria/utils/constants.py | 1 + 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index c3407fe..a27cf1c 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -19,6 +19,7 @@ LEFT_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, RIGHT_IMU_STREAM_ID, + RGB_CAMERA_STREAM_ID, ) from .timestamps import find_closest_timestamp from .types import InitReconstruction @@ -528,9 +529,9 @@ def extract_images_from_vrs( extract_right: bool = True, ): for camera, stream_id in [ - (left_subfolder_name, "1201-1"), - (right_subfolder_name, "1201-2"), - (rgb_subfolder_name, "214-1"), + (left_subfolder_name, LEFT_CAMERA_STREAM_ID), + (right_subfolder_name, RIGHT_CAMERA_STREAM_ID), + (rgb_subfolder_name, RGB_CAMERA_STREAM_ID), ]: if camera == rgb_subfolder_name and not extract_rgb: continue diff --git a/lamaria/utils/constants.py b/lamaria/utils/constants.py index 0671c62..516c942 100644 --- a/lamaria/utils/constants.py +++ b/lamaria/utils/constants.py @@ -7,6 +7,7 @@ # Aria camera constants LEFT_CAMERA_STREAM_ID = "1201-1" RIGHT_CAMERA_STREAM_ID = "1201-2" +RGB_CAMERA_STREAM_ID = "214-1" LEFT_CAMERA_STREAM_LABEL = "camera-slam-left" RIGHT_CAMERA_STREAM_LABEL = "camera-slam-right" From 5305ca8569337cd02284b95a2df540088bdc67be Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 21:30:05 +0200 Subject: [PATCH 584/665] mv into pipeline --- example_vi_optimization.py | 6 +++--- .../{data_init => }/estimate_to_timed_reconstruction.py | 6 +++--- lamaria/pipeline/{keyframing => }/keyframe_selection.py | 6 +++--- lamaria/pipeline/{optim => }/triangulation.py | 4 ++-- 4 files changed, 11 insertions(+), 11 deletions(-) rename lamaria/pipeline/{data_init => }/estimate_to_timed_reconstruction.py (95%) rename lamaria/pipeline/{keyframing => }/keyframe_selection.py (98%) rename lamaria/pipeline/{optim => }/triangulation.py (98%) diff --git a/example_vi_optimization.py b/example_vi_optimization.py index 27c0ea0..5b046ae 100644 --- a/example_vi_optimization.py +++ b/example_vi_optimization.py @@ -10,15 +10,15 @@ VIOptimizerOptions, ) from lamaria.config.pipeline import PipelineOptions -from lamaria.pipeline.data_init.estimate_to_timed_reconstruction import ( +from lamaria.pipeline.estimate_to_timed_reconstruction import ( convert_estimate_into_timed_reconstruction, ) from lamaria.pipeline.data_init.mps_to_timed_reconstruction import ( MPSToTimedRecon, ) -from lamaria.pipeline.keyframing.keyframe_selection import KeyframeSelector +from lamaria.pipeline.keyframe_selection import KeyframeSelector from lamaria.pipeline.optim.session import SingleSeqSession -from lamaria.pipeline.optim.triangulation import run as triangulate +from lamaria.pipeline.triangulation import run as triangulate from lamaria.pipeline.optim.vi_optimization import VIOptimizer from lamaria.structs.timed_reconstruction import TimedReconstruction from lamaria.structs.trajectory import Trajectory diff --git a/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py b/lamaria/pipeline/estimate_to_timed_reconstruction.py similarity index 95% rename from lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py rename to lamaria/pipeline/estimate_to_timed_reconstruction.py index 8ce9ac2..449ea36 100644 --- a/lamaria/pipeline/data_init/estimate_to_timed_reconstruction.py +++ b/lamaria/pipeline/estimate_to_timed_reconstruction.py @@ -4,11 +4,11 @@ import pycolmap -from ...structs.timed_reconstruction import TimedReconstruction -from ...structs.trajectory import ( +from ..structs.timed_reconstruction import TimedReconstruction +from ..structs.trajectory import ( Trajectory, ) -from ...utils.types import InitReconstruction +from ..utils.types import InitReconstruction def _image_names_from_folder( diff --git a/lamaria/pipeline/keyframing/keyframe_selection.py b/lamaria/pipeline/keyframe_selection.py similarity index 98% rename from lamaria/pipeline/keyframing/keyframe_selection.py rename to lamaria/pipeline/keyframe_selection.py index 0aa9168..2cced7c 100644 --- a/lamaria/pipeline/keyframing/keyframe_selection.py +++ b/lamaria/pipeline/keyframe_selection.py @@ -7,9 +7,9 @@ import numpy as np import pycolmap -from ...config.options import KeyframeSelectorOptions -from ...structs.timed_reconstruction import TimedReconstruction -from ...utils.aria import get_magnitude_from_transform +from ..config.options import KeyframeSelectorOptions +from ..structs.timed_reconstruction import TimedReconstruction +from ..utils.aria import get_magnitude_from_transform class KeyframeSelector: diff --git a/lamaria/pipeline/optim/triangulation.py b/lamaria/pipeline/triangulation.py similarity index 98% rename from lamaria/pipeline/optim/triangulation.py rename to lamaria/pipeline/triangulation.py index 8667ca1..46ee1ea 100644 --- a/lamaria/pipeline/optim/triangulation.py +++ b/lamaria/pipeline/triangulation.py @@ -11,8 +11,8 @@ triangulation, ) -from ... import logger -from ...config.options import TriangulatorOptions +from .. import logger +from ..config.options import TriangulatorOptions def get_colmap_triangulation_options( From 55131159e837be2d1da0e9c766ef7c94bb3331cb Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 21:52:18 +0200 Subject: [PATCH 585/665] pyproject toml --- pyproject.toml | 37 +++++++++++++++++++++++++++++++++++++ 1 file changed, 37 insertions(+) create mode 100644 pyproject.toml diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 0000000..8328ec4 --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,37 @@ +[project] +name = "lamaria" +version = "0.1.0" +requires-python = ">=3.9,<3.15" +description = "LaMAria: Benchmarking Egocentric Visual-Inertial SLAM at City Scale" +readme = { file = "README.md", content-type = "text/markdown" } + +[project.urls] +Homepage = "https://lamaria.ethz.ch" +Repository = "https://github.com/cvg/lamaria" +Issues = "https://github.com/cvg/lamaria/issues" + +[project.scripts] +lamaria-eval-cp = "evaluate_wrt_control_points:main" +lamaria-eval-mps = "evaluate_wrt_mps:main" +lamaria-eval-pgt = "evaluate_wrt_pgt:main" +lamaria-vi-opt = "example_vi_optimization:main" + +[tool.setuptools] +packages = ["lamaria"] + +py-modules = [ + "evaluate_wrt_control_points", + "evaluate_wrt_mps", + "evaluate_wrt_pgt", + "example_vi_optimization" +] + +[tool.setuptools.package-data] +lamaria = [ + "assets/*", + "**/*.yaml", +] + +[build-system] +requires = ["setuptools>=61.0", "wheel"] +build-backend = "setuptools.build_meta" \ No newline at end of file From c4280bf22789468d3fceb821fa3819b58c6075b1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 21:53:23 +0200 Subject: [PATCH 586/665] ruff --- example_vi_optimization.py | 8 ++++---- lamaria/utils/aria.py | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/example_vi_optimization.py b/example_vi_optimization.py index 5b046ae..dbd8638 100644 --- a/example_vi_optimization.py +++ b/example_vi_optimization.py @@ -10,16 +10,16 @@ VIOptimizerOptions, ) from lamaria.config.pipeline import PipelineOptions -from lamaria.pipeline.estimate_to_timed_reconstruction import ( - convert_estimate_into_timed_reconstruction, -) from lamaria.pipeline.data_init.mps_to_timed_reconstruction import ( MPSToTimedRecon, ) +from lamaria.pipeline.estimate_to_timed_reconstruction import ( + convert_estimate_into_timed_reconstruction, +) from lamaria.pipeline.keyframe_selection import KeyframeSelector from lamaria.pipeline.optim.session import SingleSeqSession -from lamaria.pipeline.triangulation import run as triangulate from lamaria.pipeline.optim.vi_optimization import VIOptimizer +from lamaria.pipeline.triangulation import run as triangulate from lamaria.structs.timed_reconstruction import TimedReconstruction from lamaria.structs.trajectory import Trajectory from lamaria.structs.vi_reconstruction import VIReconstruction diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index a27cf1c..33fe341 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -17,9 +17,9 @@ from .constants import ( ARIA_CAMERAS, LEFT_CAMERA_STREAM_ID, + RGB_CAMERA_STREAM_ID, RIGHT_CAMERA_STREAM_ID, RIGHT_IMU_STREAM_ID, - RGB_CAMERA_STREAM_ID, ) from .timestamps import find_closest_timestamp from .types import InitReconstruction From f6f6eae95061208e2c70ff6a591b1d657578683f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 21:57:28 +0200 Subject: [PATCH 587/665] readme --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index c0b8418..add155b 100644 --- a/README.md +++ b/README.md @@ -25,7 +25,8 @@ Using **LaMAria**, you can: ## Installation -This repository supports Python 3.9 through 3.13. Installing the package `lamaria` pulls the other dependencies. +This repository supports Python 3.9 through 3.14. Installing the package `lamaria` pulls the other dependencies +mentioned in `requirements.txt`. Create an environment: ```bash From 8001bde8f7a7cd2524267b54429895f67cdc3e79 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 22:42:11 +0200 Subject: [PATCH 588/665] download lamaria --- tools/download_lamaria.py | 53 ++++++++++++++++----------------------- 1 file changed, 22 insertions(+), 31 deletions(-) diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index ccd7b04..6625b4b 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -189,16 +189,20 @@ def download_file( ) -def main(): +if __name__ == "__main__": parser = argparse.ArgumentParser(description="LaMAria dataset downloader") - parser.add_argument( + + group = parser.add_mutually_exclusive_group(required=False) + group.add_argument( "--set", - choices=["training", "test", "specific"], - required=True, - help=( - "What to download: training sequences, " - "test sequences, or a specific list", - ), + choices=["training", "test"], + help="Download all sequences from this split", + ) + group.add_argument( + "--sequences", + nargs="+", + help='Explicit sequence names (e.g. R_01_easy sequence_3_17). ' + "If provided, --set is not needed.", ) parser.add_argument( "--type", @@ -206,14 +210,6 @@ def main(): required=True, help="Which data to fetch", ) - parser.add_argument( - "--sequences", - nargs="+", - help=( - "Sequence names (required for --set specific).\n" - "Example: R_01_easy sequence_3_17" - ), - ) parser.add_argument( "--out-dir", default="out_dir", @@ -230,21 +226,20 @@ def main(): train_names, test_names = derive_splits(catalog) split_lookup = raw_split_map(catalog) # seq -> 'training/' or 'test/' - if args.set == "training": + if args.sequences: + target_sequences = args.sequences + global_split = None + elif args.set == "training": target_sequences = train_names global_split = "training/" elif args.set == "test": target_sequences = test_names global_split = "test/" else: - if not args.sequences: - print( - "[error] --set specific requires --sequences", file=sys.stderr - ) - sys.exit(2) - target_sequences = args.sequences - global_split = None # per-sequence - + # choose a sensible default if nothing specified + print("[info] No --set or --sequences provided; nothing to do.") + sys.exit(0) + # To fetch folders = PAYLOADS[args.type].copy() plan = [] @@ -301,7 +296,7 @@ def main(): if not plan: print("[warn] Nothing to download with the given filters.") - return + sys.exit(0) print("\n[download] Starting downloads.") with requests.Session() as sess: @@ -317,8 +312,4 @@ def main(): print( "\n[done] All downloads attempted. Files stored under:", root.resolve() - ) - - -if __name__ == "__main__": - main() + ) \ No newline at end of file From 0e8aaa76aef0d39e0e8718df24b76e013ec577f4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 23:02:57 +0200 Subject: [PATCH 589/665] Download section --- README.md | 53 +++++++++++++++++++++++++++++++++++++++++++++++++---- 1 file changed, 49 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index add155b..19ff54c 100644 --- a/README.md +++ b/README.md @@ -1,17 +1,23 @@

    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    -We present **LaMAria**, a egocentric, city-scale benchmark for **visual-inertial SLAM**, featuring +We present **LaMAria**, an egocentric, city-scale benchmark for **visual-inertial SLAM**, featuring ~ **22 hours / 70 km** of trajectories with survey-grade control points providing **centimeter-accurate ground truth**. Using **LaMAria**, you can: -- Evaluate SLAM systems under real-world challenges: low light, moving platforms, exposure changes, extremely long trajectories. +- Evaluate SLAM systems under real-world challenges: low light, moving platforms, exposure changes, extremely long trajectories, and challenges typical to egocentric motion. - Benchmark against highly accurate ground truths. +This dataset offers 23 training sequences and 63 test sequences. +

    Overview of LaMAria
    Figure 1: Overview of the LaMAria dataset and benchmark.

    +In this repository, you can find scripts to conveniently download the dataset, evaluate SLAM results, perform data conversions, and run an example visual-inertial optimization pipeline. + +To learn more about the dataset, please visit our [main dataset page](https://lamaria.ethz.ch) or read our [paper]() + ## Table of Contents - [Installation](#installation) - [Downloading the Dataset](#downloading-the-dataset) @@ -25,7 +31,7 @@ Using **LaMAria**, you can: ## Installation -This repository supports Python 3.9 through 3.14. Installing the package `lamaria` pulls the other dependencies +This repository supports Python 3.9 through 3.14. Installing the package `lamaria` pulls other dependencies mentioned in `requirements.txt`. Create an environment: @@ -46,8 +52,47 @@ Install the package: python -m pip install -e . ``` - ## Downloading the dataset +Our dataset is fully hosted via the archive [here](https://cvg-data.inf.ethz.ch/lamaria/). + +### Quickstart +We provide a small script `quickstart.sh` that downloads one sequence from the archive. The standalone evaluations and example visual-inertial optimization can be run on the downloaded demo data. + +```bash +chmod +x quickstart.sh +./quickstart.sh +``` + +### Downloading LaMAria + +```bash +python tools/download_lamaria.py --help +``` + +To download the dataset conveniently, we provide a custom script `tools/download_lamaria.py`. Using this script, you can download: +- Specific sequences or entire sets (training/test). +- Specific types: + - Raw - Downloads raw `.vrs` files and Aria calibration file. + - Pinhole - Downloads ASL folder, rosbag, and pinhole calibration file. + - Both - Downloads both raw and pinhole data. + +For example, to download all training sequences with both raw and pinhole data, run: + +```bash +python tools/download_lamaria.py --set training --type both +``` +**Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage, else** 💣. + +The training and test sequence information can be found in the [dataset page](https://lamaria.ethz.ch/slam_datasets). + +To download the raw data of a specific sequence (e.g., `R_01_easy`), run: + +```bash +python tools/download_lamaria.py --sequences R_01_easy --type raw +``` +Ground truth files are available only for the training sequences. + +To learn more about the various data formats, calibration files and ground-truths, please visit our [dataset documentation](https://lamaria.ethz.ch/slam_documentation). ## Evaluation From 336961f48925bcdf030e63f2485e7b7f8a317c94 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 23:09:20 +0200 Subject: [PATCH 590/665] more readme --- README.md | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 19ff54c..2d76da8 100644 --- a/README.md +++ b/README.md @@ -16,7 +16,7 @@ This dataset offers 23 training sequences and 63 test sequences. In this repository, you can find scripts to conveniently download the dataset, evaluate SLAM results, perform data conversions, and run an example visual-inertial optimization pipeline. -To learn more about the dataset, please visit our [main dataset page](https://lamaria.ethz.ch) or read our [paper]() +To learn more about the dataset, please visit our
    main dataset website or read our paper. ## Table of Contents - [Installation](#installation) @@ -53,7 +53,7 @@ python -m pip install -e . ``` ## Downloading the dataset -Our dataset is fully hosted via the archive [here](https://cvg-data.inf.ethz.ch/lamaria/). +Our dataset is fully hosted via the archive here. ### Quickstart We provide a small script `quickstart.sh` that downloads one sequence from the archive. The standalone evaluations and example visual-inertial optimization can be run on the downloaded demo data. @@ -83,7 +83,7 @@ python tools/download_lamaria.py --set training --type both ``` **Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage, else** 💣. -The training and test sequence information can be found in the [dataset page](https://lamaria.ethz.ch/slam_datasets). +The training and test sequence information can be found in the dataset page. To download the raw data of a specific sequence (e.g., `R_01_easy`), run: @@ -92,8 +92,7 @@ python tools/download_lamaria.py --sequences R_01_easy --type raw ``` Ground truth files are available only for the training sequences. -To learn more about the various data formats, calibration files and ground-truths, please visit our [dataset documentation](https://lamaria.ethz.ch/slam_documentation). - +To learn more about the various data formats, calibration files and ground-truths, please visit our dataset documentation. ## Evaluation @@ -118,4 +117,4 @@ To extract images from a `.vrs` file, it is required to install the VRS Command -## BibTeX citation \ No newline at end of file +## BibTeX citation From 995136bdb7e3c783f41b732736c792a6192a7e05 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 23:19:48 +0200 Subject: [PATCH 591/665] download dataset --- README.md | 23 +++++++++++++---------- 1 file changed, 13 insertions(+), 10 deletions(-) diff --git a/README.md b/README.md index 2d76da8..70cb3cb 100644 --- a/README.md +++ b/README.md @@ -69,30 +69,33 @@ chmod +x quickstart.sh python tools/download_lamaria.py --help ``` -To download the dataset conveniently, we provide a custom script `tools/download_lamaria.py`. Using this script, you can download: +For download convenience, we provide a custom script `tools/download_lamaria.py`. Using this script, you can download: - Specific sequences or entire sets (training/test). - Specific types: - Raw - Downloads raw `.vrs` files and Aria calibration file. - Pinhole - Downloads ASL folder, rosbag, and pinhole calibration file. - Both - Downloads both raw and pinhole data. -For example, to download all training sequences with both raw and pinhole data, run: +Ground truth files are automatically downloaded only for the training sequences. +**Some example commands** + +To download all training sequences in both raw and pinhole formats: ```bash python tools/download_lamaria.py --set training --type both ``` -**Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage, else** 💣. - -The training and test sequence information can be found in the dataset page. - -To download the raw data of a specific sequence (e.g., `R_01_easy`), run: - +To download the raw data of a specific sequence (e.g., `R_01_easy`): ```bash python tools/download_lamaria.py --sequences R_01_easy --type raw ``` -Ground truth files are available only for the training sequences. +To download 3 custom sequences in pinhole format: +```bash +python tools/download_lamaria.py --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type pinhole +``` + +**Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage 💣.** -To learn more about the various data formats, calibration files and ground-truths, please visit our dataset documentation. +For more information about the training and test sequences, refer to the dataset details. To learn more about the various data formats, calibration files and ground-truths, visit our documentation. ## Evaluation From 8340dacd9e220d1ae89a1eb6c85cdfcabb592fb2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 23:29:41 +0200 Subject: [PATCH 592/665] download --- README.md | 31 ++++++++++++++++++++++++++++--- 1 file changed, 28 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 70cb3cb..9138fb6 100644 --- a/README.md +++ b/README.md @@ -76,9 +76,9 @@ For download convenience, we provide a custom script `tools/download_lamaria.py` - Pinhole - Downloads ASL folder, rosbag, and pinhole calibration file. - Both - Downloads both raw and pinhole data. -Ground truth files are automatically downloaded only for the training sequences. +Ground truth files are automatically downloaded only for the training sequences. **Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage 💣.** -**Some example commands** +#### Some example commands To download all training sequences in both raw and pinhole formats: ```bash @@ -93,7 +93,32 @@ To download 3 custom sequences in pinhole format: python tools/download_lamaria.py --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type pinhole ``` -**Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage 💣.** +#### Output structure +The downloaded data is stored in the following structure: +``` +out_dir/ +└── lamaria/ + ├── training/ + │ ├── R_01_easy/ + │ │ ├── aria_calibrations/ + │ │ │ └── R_01_easy.json + │ │ ├── asl_folder/ + │ │ │ └── R_01_easy.zip + │ │ ├── ground_truth/ + │ │ │ ├── pseudo_dense/ + │ │ │ │ └── R_01_easy.txt + │ │ │ └── sparse/ + │ │ │ └── # if sequence has CPs + │ │ ├── pinhole_calibrations/ + │ │ │ └── R_01_easy.json + │ │ ├── raw_data/ + │ │ │ └── R_01_easy.vrs + │ │ └── rosbag/ + │ │ └── R_01_easy.bag + │ └── ... + └── test/ + └── sequence_1_1 +``` For more information about the training and test sequences, refer to the dataset details. To learn more about the various data formats, calibration files and ground-truths, visit our documentation. From e9df9ff9e2efb5d0ed4baec4abe0eb797f8eccb6 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Mon, 29 Sep 2025 23:33:14 +0200 Subject: [PATCH 593/665] readme --- README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 9138fb6..8ca895c 100644 --- a/README.md +++ b/README.md @@ -76,7 +76,9 @@ For download convenience, we provide a custom script `tools/download_lamaria.py` - Pinhole - Downloads ASL folder, rosbag, and pinhole calibration file. - Both - Downloads both raw and pinhole data. -Ground truth files are automatically downloaded only for the training sequences. **Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage 💣.** +Ground truth files are automatically downloaded for the training sequences. + +**💣 Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage 💣.** #### Some example commands From c15be65d1a7139786f65ea32a739ad03cd977344 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 00:06:10 +0200 Subject: [PATCH 594/665] demo data folder --- .gitignore | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index f27b08a..6b44e6f 100644 --- a/.gitignore +++ b/.gitignore @@ -1,2 +1,3 @@ **/__pycache__/ -.DS_Store \ No newline at end of file +.DS_Store +demo/ \ No newline at end of file From 6e2d3e9520fe540d2bf6a63af93f8471c8cc9023 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 01:16:30 +0200 Subject: [PATCH 595/665] toml --- pyproject.toml | 13 ------------- 1 file changed, 13 deletions(-) diff --git a/pyproject.toml b/pyproject.toml index 8328ec4..adf6dbb 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -10,22 +10,9 @@ Homepage = "https://lamaria.ethz.ch" Repository = "https://github.com/cvg/lamaria" Issues = "https://github.com/cvg/lamaria/issues" -[project.scripts] -lamaria-eval-cp = "evaluate_wrt_control_points:main" -lamaria-eval-mps = "evaluate_wrt_mps:main" -lamaria-eval-pgt = "evaluate_wrt_pgt:main" -lamaria-vi-opt = "example_vi_optimization:main" - [tool.setuptools] packages = ["lamaria"] -py-modules = [ - "evaluate_wrt_control_points", - "evaluate_wrt_mps", - "evaluate_wrt_pgt", - "example_vi_optimization" -] - [tool.setuptools.package-data] lamaria = [ "assets/*", From dec0aa80648b5da79eead7ae7522534e1ce0a849 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 01:23:30 +0200 Subject: [PATCH 596/665] quick start --- quickstart.sh | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) mode change 100644 => 100755 quickstart.sh diff --git a/quickstart.sh b/quickstart.sh old mode 100644 new mode 100755 index e69de29..5321af8 --- a/quickstart.sh +++ b/quickstart.sh @@ -0,0 +1,19 @@ +#!/usr/bin/env bash +set -euo pipefail + +URL="https://cvg-data.inf.ethz.ch/lamaria/demo.zip" + +if [ -t 1 ]; then + PROGRESS="--progress=bar:force:noscroll" +else + PROGRESS="--progress=dot:giga" +fi + +echo "[quickstart] downloading demo.zip (~6 GB)…" +wget -c $PROGRESS -O demo.zip "$URL" + +echo "[quickstart] extracting…" +unzip -q -o demo.zip +rm demo.zip + +echo "[quickstart] done. demo is in ./demo" \ No newline at end of file From eb55944aef1c1229f1b3d5593433524f84c5e10c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 01:24:43 +0200 Subject: [PATCH 597/665] ruff --- tools/download_lamaria.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 6625b4b..931dccf 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -191,7 +191,7 @@ def download_file( if __name__ == "__main__": parser = argparse.ArgumentParser(description="LaMAria dataset downloader") - + group = parser.add_mutually_exclusive_group(required=False) group.add_argument( "--set", @@ -201,8 +201,8 @@ def download_file( group.add_argument( "--sequences", nargs="+", - help='Explicit sequence names (e.g. R_01_easy sequence_3_17). ' - "If provided, --set is not needed.", + help="Explicit sequence names (e.g. R_01_easy sequence_3_17). " + "If provided, --set is not needed.", ) parser.add_argument( "--type", @@ -239,7 +239,7 @@ def download_file( # choose a sensible default if nothing specified print("[info] No --set or --sequences provided; nothing to do.") sys.exit(0) - + # To fetch folders = PAYLOADS[args.type].copy() plan = [] @@ -312,4 +312,4 @@ def download_file( print( "\n[done] All downloads attempted. Files stored under:", root.resolve() - ) \ No newline at end of file + ) From 2de021e87b068d1dc951145722c37a550a9089f7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 01:26:09 +0200 Subject: [PATCH 598/665] read --- README.md | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 8ca895c..6b6c38d 100644 --- a/README.md +++ b/README.md @@ -63,6 +63,8 @@ chmod +x quickstart.sh ./quickstart.sh ``` +The data is stored in the `demo/` folder. You may run the standalone evaluations and example visual-inertial optimization on this data. + ### Downloading LaMAria ```bash @@ -96,7 +98,7 @@ python tools/download_lamaria.py --sequences sequence_1_1 sequence 1_2 sequence ``` #### Output structure -The downloaded data is stored in the following structure: +The downloaded data is stored in the following way: ``` out_dir/ └── lamaria/ @@ -125,10 +127,21 @@ out_dir/ For more information about the training and test sequences, refer to the dataset details. To learn more about the various data formats, calibration files and ground-truths, visit our documentation. ## Evaluation - +Our training and test sequences are categorized into varying challenges. To evaluate your SLAM results on our data, we provide two main ways: +1. **Evaluation via the website**: Upload your results on our website to get evaluation results. Results on test sequences are displayed on the public leaderboard. +2. **Standalone evaluation**: Run the evaluation scripts locally using the provided `lamaria` package. ### Evaluation w.r.t. Control Points +Those sequences that observe ground truth control points (CPs) can be evaluated w.r.t. these points. This script computes the score and control point recall based on the alignment of the estimated trajectory to the control points. + +To perform the evaluation on the downloaded demo data: +```bash +python -m evaluate_wrt_control_points --estimate demo/estimate/R_11_5cp.txt --cp_json_file demo/cp_data/R_11_5cp.json --device_calibration_json demo/calibrations/R_11_5cp.json --output_path demo/eval_cp --corresponding_sensor imu +``` + +*This command evaluates the provided estimate w.r.t. control points and stores the results in `demo/eval_cp`. The `--corresponding_sensor` flag indicates which sensor the poses are expressed in (e.g., `imu` or `cam0`).* +To learn more about the control points and sparse evaluation, refer to Section 4.1 and 4.2 of our paper. ### Evaluation w.r.t Pseudo-GT From 1ba9277eb6aa7de0bde82bd7ca2e520b186ea367 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 01:47:56 +0200 Subject: [PATCH 599/665] evo fix --- lamaria/eval/evo_evaluation.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/lamaria/eval/evo_evaluation.py b/lamaria/eval/evo_evaluation.py index 6c81f89..124da18 100644 --- a/lamaria/eval/evo_evaluation.py +++ b/lamaria/eval/evo_evaluation.py @@ -49,10 +49,14 @@ def convert_trajectory_to_evo_posetrajectory( timestamps = traj.timestamps assert len(poses) == len(timestamps), "Poses and timestamps length mismatch" + tvecs = np.array([pose.translation for pose in poses]) + quats = np.array([pose.rotation.quat for pose in poses]) + quats_wxyz = quats[:, [3, 0, 1, 2]] + evo_traj = PoseTrajectory3D( - positions_xyz=np.array([pose.translation for pose in poses]), - orientations_xyzw=np.array([pose.rotation.quat for pose in poses]), - timestamps=np.array(timestamps), + positions_xyz=tvecs, + orientations_quat_wxyz=quats_wxyz, + timestamps=np.array(timestamps, dtype=np.float64), ) return evo_traj From cdf01f71109d44776156ec43b5ebd1411a7fa24b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 02:20:12 +0200 Subject: [PATCH 600/665] readme --- README.md | 29 +++++++++++++++++++++++++++-- 1 file changed, 27 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 6b6c38d..51e9ba2 100644 --- a/README.md +++ b/README.md @@ -20,6 +20,7 @@ To learn more about the dataset, please visit our here. ### Quickstart -We provide a small script `quickstart.sh` that downloads one sequence from the archive. The standalone evaluations and example visual-inertial optimization can be run on the downloaded demo data. +We provide a small script `quickstart.sh` that downloads data from the archive. The standalone evaluations and example visual-inertial optimization can be run on the downloaded data. ```bash chmod +x quickstart.sh @@ -136,7 +154,7 @@ Those sequences that observe ground truth control points (CPs) can be evaluated To perform the evaluation on the downloaded demo data: ```bash -python -m evaluate_wrt_control_points --estimate demo/estimate/R_11_5cp.txt --cp_json_file demo/cp_data/R_11_5cp.json --device_calibration_json demo/calibrations/R_11_5cp.json --output_path demo/eval_cp --corresponding_sensor imu +python -m evaluate_wrt_control_points --estimate demo/estimate/sequence_1_19.txt --cp_json_file demo/cp_data/sequence_1_19.json --device_calibration_json demo/calibrations/sequence_1_19.json --output_path demo/eval_cp --corresponding_sensor imu ``` *This command evaluates the provided estimate w.r.t. control points and stores the results in `demo/eval_cp`. The `--corresponding_sensor` flag indicates which sensor the poses are expressed in (e.g., `imu` or `cam0`).* @@ -147,7 +165,14 @@ To learn more about the control points and sparse evaluation, refer to Section 4 ### EVO Evaluation w.r.t MPS +This script evaluates the estimated trajectory w.r.t. the pseudo-dense ground truth from Machine Perception Services (MPS). It computes the Absolute Trajectory Error (ATE) RMSE between the two trajectories. + +To perform the evaluation on the downloaded demo data: +```bash +python -m evaluate_wrt_mps --estimate demo/estimate/R_01_easy.txt --gt_estimate demo/mps/R_01_easy.txt +``` +For sequences that do not have control points, this evaluation is the primary way to benchmark your SLAM results. ## Data Conversion From 1d1ab110900aaa3959bcab8372032e070e413070 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 02:46:33 +0200 Subject: [PATCH 601/665] fix --- evaluate_wrt_control_points.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index 78a2eb3..bf62e36 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -78,8 +78,10 @@ def run( score = calculate_control_point_score(result) recall = calculate_control_point_recall(result) - logger.info(f"Sparse Evaluation CP Score: {score:.4f}") - logger.info(f"Sparse Evaluation CP Recall: {recall:.4f}") + + logger.info(f"CP Score: {score:.4f}") + logger.info(f"CP Recall @ 1m: {recall:.4f}") + return True if __name__ == "__main__": From a7b7b0be1357793c87ce5d896f55443a0c580724 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 02:46:50 +0200 Subject: [PATCH 602/665] pose recall --- lamaria/utils/metrics.py | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/lamaria/utils/metrics.py b/lamaria/utils/metrics.py index f09f136..33981f0 100644 --- a/lamaria/utils/metrics.py +++ b/lamaria/utils/metrics.py @@ -87,3 +87,18 @@ def calculate_error(result: SparseEvalResult) -> np.ndarray: assert len(error_2d) == len(result.cp_summary), "Error length mismatch" return np.array(error_2d) + + +def calculate_pose_recall( + error: np.ndarray, + num_poses_gt: int, + threshold: float = 1.0, # meters +): + """Calculate the percentage of poses within a certain error threshold.""" + if len(error) == 0 or num_poses_gt == 0: + return 0.0 + + num_poses_within_threshold = np.sum(error <= threshold) + + pose_recall = (num_poses_within_threshold / num_poses_gt) * 100 + return pose_recall From 450f7c110efd7d85b8627314cb96615ce5ebc25f Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 02:47:11 +0200 Subject: [PATCH 603/665] pgt --- lamaria/eval/pgt_evaluation.py | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/lamaria/eval/pgt_evaluation.py b/lamaria/eval/pgt_evaluation.py index 4ed3b1d..04b0e90 100644 --- a/lamaria/eval/pgt_evaluation.py +++ b/lamaria/eval/pgt_evaluation.py @@ -12,8 +12,7 @@ def evaluate_wrt_pgt( est_traj: Trajectory, gt_traj: Trajectory, sim3d: pycolmap.Sim3d, - output_path: Path, -) -> None: +) -> None | np.ndarray: """ Evaluate an estimated trajectory with respect to a pseudo ground-truth trajectory that observes control points. @@ -37,12 +36,5 @@ def evaluate_wrt_pgt( E = est_traj.positions - gt_traj.positions error = np.array([np.linalg.norm(e[:2]) for e in E]) - error_file = output_path / "error_per_kf.txt" - with open(error_file, mode="w", newline="") as f: - writer = csv.writer(f) - writer.writerow(["timestamp", "error_m"]) - for ts, e in zip(est_traj.timestamps, error): - writer.writerow([ts, e]) - logger.info("pGT evaluation completed successfully!") - return error_file + return error From f6308f791463258f1faf239df8f3421ae4c3f59c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 02:48:11 +0200 Subject: [PATCH 604/665] no need for op path --- evaluate_wrt_pgt.py | 22 +++++++++------------- lamaria/eval/pgt_evaluation.py | 2 -- lamaria/utils/metrics.py | 2 +- 3 files changed, 10 insertions(+), 16 deletions(-) diff --git a/evaluate_wrt_pgt.py b/evaluate_wrt_pgt.py index c4a75f9..30955ee 100644 --- a/evaluate_wrt_pgt.py +++ b/evaluate_wrt_pgt.py @@ -7,13 +7,13 @@ from lamaria.eval.pgt_evaluation import evaluate_wrt_pgt from lamaria.structs.sparse_eval import SparseEvalResult from lamaria.structs.trajectory import Trajectory +from lamaria.utils.metrics import calculate_pose_recall def run( estimate: Path, gt_estimate: Path, sparse_eval_result: Path, - output_path: Path, ) -> bool: """Evaluate an estimated trajectory with respect to a pseudo ground-truth trajectory that observes control points. @@ -25,7 +25,6 @@ def run( SparseEvalResult data. This file is generated by `evaluate_wrt_control_points`, and is needed to transform the estimated trajectory to the pGT. - output_path (Path): Path to save the evaluation results. Returns: bool: True if the evaluation was successful, False otherwise. """ @@ -45,17 +44,21 @@ def run( logger.error("SparseEvalResult could not be loaded") return False - sim3d = sparse_eval_result.alignment.optimized_sim3d + sim3d = result.alignment if not isinstance(sim3d, pycolmap.Sim3d): logger.error("No valid Sim3d found in SparseEvalResult") return False - error_file = evaluate_wrt_pgt(est_traj, gt_traj, sim3d, output_path) - if not error_file.exists(): + error = evaluate_wrt_pgt(est_traj, gt_traj, sim3d) + + if error is None: logger.error("pGT evaluation failed.") return False - # TODO: Add metic calc here? + pose_recall_5m = calculate_pose_recall(error, len(gt_traj), threshold=5.0) + + logger.info(f"Pose Recall @ 5m: {pose_recall_5m:.4f}") + return True if __name__ == "__main__": @@ -82,16 +85,9 @@ def run( help="Path to the .npy file containing SparseEvalResult data." "Result of `evaluate_wrt_control_points`.", ) - parser.add_argument( - "--output_path", - type=Path, - required=True, - help="Path to save the evaluation results.", - ) args = parser.parse_args() _ = run( args.estimate, args.gt_estimate, args.sparse_eval_result, - args.output_path, ) diff --git a/lamaria/eval/pgt_evaluation.py b/lamaria/eval/pgt_evaluation.py index 04b0e90..d5b9b45 100644 --- a/lamaria/eval/pgt_evaluation.py +++ b/lamaria/eval/pgt_evaluation.py @@ -1,5 +1,3 @@ -import csv -from pathlib import Path import numpy as np import pycolmap diff --git a/lamaria/utils/metrics.py b/lamaria/utils/metrics.py index 33981f0..5714b2a 100644 --- a/lamaria/utils/metrics.py +++ b/lamaria/utils/metrics.py @@ -97,7 +97,7 @@ def calculate_pose_recall( """Calculate the percentage of poses within a certain error threshold.""" if len(error) == 0 or num_poses_gt == 0: return 0.0 - + num_poses_within_threshold = np.sum(error <= threshold) pose_recall = (num_poses_within_threshold / num_poses_gt) * 100 From 01529bb10bc8eb3ceb1b03ef530df44d2a25b8c4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 02:48:26 +0200 Subject: [PATCH 605/665] space --- evaluate_wrt_control_points.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/evaluate_wrt_control_points.py b/evaluate_wrt_control_points.py index bf62e36..212da74 100644 --- a/evaluate_wrt_control_points.py +++ b/evaluate_wrt_control_points.py @@ -78,7 +78,7 @@ def run( score = calculate_control_point_score(result) recall = calculate_control_point_recall(result) - + logger.info(f"CP Score: {score:.4f}") logger.info(f"CP Recall @ 1m: {recall:.4f}") return True From 4a3eeb10e8eb51198f561bb91da79d3313679fe7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 02:55:34 +0200 Subject: [PATCH 606/665] array --- lamaria/structs/trajectory.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/structs/trajectory.py b/lamaria/structs/trajectory.py index 9bacf5c..2339fdd 100644 --- a/lamaria/structs/trajectory.py +++ b/lamaria/structs/trajectory.py @@ -330,8 +330,8 @@ def associate_trajectories( shorter_traj = traj2 if first_longer else traj1 short_idx, long_idx = matching_time_indices( - shorter_traj.timestamps, - longer_traj.timestamps, + np.array(shorter_traj.timestamps), + np.array(longer_traj.timestamps), ) num_matches = len(long_idx) if num_matches == 0: From 0c0b87b2345dcfd1926a5890a36fe224bdd1c91d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 02:59:31 +0200 Subject: [PATCH 607/665] readme --- README.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/README.md b/README.md index 51e9ba2..b5e1339 100644 --- a/README.md +++ b/README.md @@ -162,7 +162,12 @@ python -m evaluate_wrt_control_points --estimate demo/estimate/sequence_1_19.txt To learn more about the control points and sparse evaluation, refer to Section 4.1 and 4.2 of our paper. ### Evaluation w.r.t Pseudo-GT +This script evaluates the estimated trajectory w.r.t. the pseudo-dense ground truth from our ground-truthing pipeline. It requires the alignment obtained from the sparse evaluation (w.r.t. control points). The script computes the pose recall @ 1m and @ 5m, after aligning the estimated trajectory to the pseudo-ground truth. +To perform the evaluation on the downloaded demo data: +```bash +python -m evaluate_wrt_pgt --estimate demo/estimate/sequence_1_19.txt --gt_estimate demo/pgt/sequence_1_19.txt --sparse_eval_result demo/eval_cp/sparse_eval_result.npy +``` ### EVO Evaluation w.r.t MPS This script evaluates the estimated trajectory w.r.t. the pseudo-dense ground truth from Machine Perception Services (MPS). It computes the Absolute Trajectory Error (ATE) RMSE between the two trajectories. From 20e28624cc8e0af42121b32e81195ad33fa9ce9c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:00:50 +0200 Subject: [PATCH 608/665] pgt --- evaluate_wrt_pgt.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/evaluate_wrt_pgt.py b/evaluate_wrt_pgt.py index 30955ee..db82216 100644 --- a/evaluate_wrt_pgt.py +++ b/evaluate_wrt_pgt.py @@ -55,9 +55,10 @@ def run( logger.error("pGT evaluation failed.") return False - pose_recall_5m = calculate_pose_recall(error, len(gt_traj), threshold=5.0) + for threshold in [1.0, 5.0]: + pose_recall = calculate_pose_recall(error, len(gt_traj), threshold) + logger.info(f"Pose Recall @ {threshold}m: {pose_recall:.4f}") - logger.info(f"Pose Recall @ 5m: {pose_recall_5m:.4f}") return True From 6755bb068f18ed9aaa1cd1bc84c557ef0b4fb910 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:01:08 +0200 Subject: [PATCH 609/665] ruff --- lamaria/eval/pgt_evaluation.py | 1 - 1 file changed, 1 deletion(-) diff --git a/lamaria/eval/pgt_evaluation.py b/lamaria/eval/pgt_evaluation.py index d5b9b45..d997e61 100644 --- a/lamaria/eval/pgt_evaluation.py +++ b/lamaria/eval/pgt_evaluation.py @@ -1,4 +1,3 @@ - import numpy as np import pycolmap From d2b735d6cba807d108cb4f462c0fe3cf498dae34 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:11:42 +0200 Subject: [PATCH 610/665] Readme --- README.md | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index b5e1339..a3c8d4e 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,15 @@ -

    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    +

    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    +

    Anusha Krishnan*, Shaohui Liu*, Paul-Edouard Sarlin*, Oscar Gentilhomme, David Caruso, Maurizio Monge, Richard Newcombe, Jakob Engel, Marc Pollefeys

    + +

    + *Equal contribution +

    + +

    + Website | + Paper +

    + We present **LaMAria**, an egocentric, city-scale benchmark for **visual-inertial SLAM**, featuring ~ **22 hours / 70 km** of trajectories with survey-grade control points providing **centimeter-accurate ground truth**. From f35fd6e95ed439b74af6cbbef7b8fbc77706405e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:14:45 +0200 Subject: [PATCH 611/665] readme --- README.md | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index a3c8d4e..e959947 100644 --- a/README.md +++ b/README.md @@ -1,8 +1,9 @@

    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    -

    Anusha Krishnan*, Shaohui Liu*, Paul-Edouard Sarlin*, Oscar Gentilhomme, David Caruso, Maurizio Monge, Richard Newcombe, Jakob Engel, Marc Pollefeys

    + +

    Anusha Krishnan*, Shaohui Liu*, Paul-Edouard Sarlin*, Oscar Gentilhomme, David Caruso, Maurizio Monge, Richard Newcombe, Jakob Engel, Marc Pollefeys

    - *Equal contribution + *Equal contribution

    @@ -109,7 +110,7 @@ For download convenience, we provide a custom script `tools/download_lamaria.py` Ground truth files are automatically downloaded for the training sequences. -**💣 Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage 💣.** +**💣 Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage.** #### Some example commands From c07c27e155d64755c9f3a9a42ccdeaf5aedbc5dd Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:15:34 +0200 Subject: [PATCH 612/665] readme --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index e959947..bc6ae9c 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,6 @@

    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    -

    Anusha Krishnan*, Shaohui Liu*, Paul-Edouard Sarlin*, Oscar Gentilhomme, David Caruso, Maurizio Monge, Richard Newcombe, Jakob Engel, Marc Pollefeys

    +

    Anusha Krishnan*, Shaohui Liu*, Paul-Edouard Sarlin*, Oscar Gentilhomme, David Caruso, Maurizio Monge, Richard Newcombe, Jakob Engel, Marc Pollefeys

    *Equal contribution From e07ab9d0ed3eea3b8a8833b32b1cf47a49270cd7 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:17:36 +0200 Subject: [PATCH 613/665] readme --- README.md | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index bc6ae9c..cf9404a 100644 --- a/README.md +++ b/README.md @@ -1,10 +1,11 @@

    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    -

    Anusha Krishnan*, Shaohui Liu*, Paul-Edouard Sarlin*, Oscar Gentilhomme, David Caruso, Maurizio Monge, Richard Newcombe, Jakob Engel, Marc Pollefeys

    +

    + Anusha Krishnan*, Shaohui Liu*, Paul-Edouard Sarlin*, Oscar Gentilhomme
    + David Caruso, Maurizio Monge, Richard Newcombe, Jakob Engel, Marc Pollefeys +

    -

    - *Equal contribution -

    +

    *Equal contribution

    Website | From f83e5253514a6e3ba277b56e2be0d43620112db4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:40:30 +0200 Subject: [PATCH 614/665] readme --- README.md | 32 ++++++++++++++++++++++---------- 1 file changed, 22 insertions(+), 10 deletions(-) diff --git a/README.md b/README.md index cf9404a..6cbaeb3 100644 --- a/README.md +++ b/README.md @@ -1,16 +1,28 @@ -

    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    - -

    - Anusha Krishnan*, Shaohui Liu*, Paul-Edouard Sarlin*, Oscar Gentilhomme
    - David Caruso, Maurizio Monge, Richard Newcombe, Jakob Engel, Marc Pollefeys -

    - -

    *Equal contribution

    -

    +

    The LaMAria Dataset
    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    +

    + Anusha Krishnan*, + Shaohui Liu*, + Paul-Edouard Sarlin*, + Oscar Gentilhomme,
    + David Caruso, + Maurizio Monge, + Richard Newcombe, + Jakob Engel, + Marc Pollefeys +

    +

    + *Equal contribution +

    +

    +
    +

    +

    +

    Website | Paper -

    +

    +
    We present **LaMAria**, an egocentric, city-scale benchmark for **visual-inertial SLAM**, featuring From 11f76380de2274e70bdafff0f826051d0db95521 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:40:38 +0200 Subject: [PATCH 615/665] logo --- assets/iccv_logo.png | Bin 0 -> 41556 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 assets/iccv_logo.png diff --git a/assets/iccv_logo.png b/assets/iccv_logo.png new file mode 100644 index 0000000000000000000000000000000000000000..d47a3b028a0d18122bcdc4d6a37513eaf1687e81 GIT binary patch literal 41556 zcmX_o1yohd_x8D@aA}clK|m!%5Rks4NQX42fFLE^T%{ERB$Q4`3F%HLrMp`?rTd%9 z`~Q8cbtGKO%-Q+uXYV0cMM)MPmkJkxAbfc_gc<~4sz4CTNQF=q&3faDPp8m-rbz-9whz`fsjHo|3Y&(z*Lt2T5)iI+M1K4t ziAjuzGw*mT%s@L^aq}I<4HyD^u9|O~}%C`L8j-$uR z(=J}NQz9$p1vT3ju;Z>%I*08GlY<`ND_!@wUAJdWp$G&b>M1)`Hu#J{WR%>V_KIyd z?I#=&ak(tolXdY5tJyiDbLl;$(}dmMu3apwd~`UPBdm7)YRY5v6Xo#Z+r-4G_EV|V z(9O2!!ACZrh81_DnH;i+=#dBqOE`P zryv;oju0Wb2G}^w@BFfQr5M74bTSx_8{?$mNn3(GuASKzJFfTr<>#vL8?VNL-}P|F zt5V(C)xT}Cqlx-0@yZ}la3a;_3!CZv=tjP;&4)7@hlJ{o9c_hYp%UScUeba{`y<@O zv+>})FI{oLmO4ya+j0gC2k9Q(jk8nxB3H|@Vsl9~-r|wc8FsSkKHw2j%eiLnrLFI% zQUNDq<318+0edMRKXDb1H6FsCDh*r%MjOk!$WWh&B6}+F`7Bn^QpqVYmX4vgve=sC zi}1Sh9{Pmj#G*v9BqlT)Uax%H`ftLXKclTt;(PoHiUu#v*2Y;|IUxtbgzAWGtKp4( z$%fmsa`V-vgoQp&DEE%ov6Mu9KA&aHh#!=BQg!E>!wO-#!}iJBHCEXk z9mW_2=m}%FGD<&l1jCp_C~2H?{xIMGt5;(f-#AC84<6Ofq(cv@7w1KAN9e${GeKAK0 zSdx9T&o`xaSdAJ;wagU)qXe8?Pn6L?3FtQxA*&Qve`tFc&&n7K9fD`br{`rxb#VaRaO z{3`TGrn;k~rH58^tupha7i%5$-H2j@C^`eR+WtGA-Un{a?>jzS&YoG(uoYvIKaW3n zRS{|Vl17BCHfi zV}(UQW5k%s?`K(KI*#RT#VSG`=;c3gw?i9M++Z4iFC(No?()|jxAEC{**-C`8GOZb zudwqW>b#=-c{AQBIv73%#}Zf1`x3~?v z2#I%iCO9+7JS8kq9`{A)lgkGNyZuYGs>$1DogWAXE2~Hf3=WMYS7`i69q4vV>ub)##tp+M7^`}UTho-)l5l<&p{`#kchd1R}xJpL#SY7ZZWHVAv zUb*K@8F+3Oi*N)-w$~t62~4d<2H^~24lQ)@b{@3Cxn2Yrx$5>~8h3Syln^#Dc%(aH zP`13TDLCxz)d<+Ly}o=O3j!n-1TW!A;3r72+eziJ!g(AnQ|mAX!`QKARj0BEpRf(S z@UE1|Eogs&Zc|u}_~(9CuWv)h9XNbU2hgY+ts-IvMN9`|{VNHQ6>3?V_M4N0Bw|#I!B{1|i~Hc+fW+k^L-9a`DbR zaAv&5bG*>1I!KZA_yEavS)Nf%fg2q@q(r9Kq9CA%-wSnk9UPd!D!%HpO^z^6#m63@ z2lfhoDSuA2*W=Hz>P1(JE#5>X zD#o3jZ^3@v$g*tsHclHImtxsmK+fmiX^!fTFhuz6YKaRx~eubcNhY7ki#-)~Ko zquX(q2{06aQ?H>J>oM7`Qlz=h+q|?fb{l=he;|Zy%ZzW_LE`qtokI%2Q7PpFOKc=@ z8zgbVZhYtH?5djww+V}S7So|OlORLeP2y$}e8Di4L|Vv1$BLo4=I^n<^D5Z0N!Vh* zKfM~MOQJ;?0tY4_R9f>U?IhOS#2U+n@Pc_AlY4ndYiuxHiz4?E<64_3AFs5Dcl!mCk&51Ld?73|A39sf^TAb~b$**cnt4p`!!{4EyfYW1J*-yCvSD*rpX9gdw4S%$R*`jrk=m-i9a#<^a2FLAcZY>su4LX> zWY_0<>UnWn@12OoV#}TQM`G3I=TjmsUR>L;`*rV*6Lu17mOXd6sulwWY9mU@1VR;V zi7x!MJbZ7!D6M7ZXL3qD*aEEPT+lr)SXQ(gV1=}&GIEi9gQh%Qk2V|5r`DtzPgY}^ zzoR=EA;I@>g4~Z}GQWM(EpdkQt%~EwGej+X%1-5_oOo!n{f8~vR zwb{B%A)AxoHE`&4W2Az0{EPjUrZehE%3THYjZ4V_VolIP&&=MHLx4WH?q9zUc-QBB zRB{)s@g8(O|9OPX!)OsAfW{oJ=Yu!B0y8HBy|Hj;2S(49AC>lLlNeD?d$R)Vh^`&E zL@@?8+*WbC%?ka*(}keIa;0hgT}5Ls_OYJM42)?EBZf$C-oSmAJIC z*coDQTJEg?W(%nB%5DE24RT7VUCBZ7&@Kq-eXLS)Yv^Ox=dW`FRbN?FJy)Vn)#b&& zdq^5*bEe1;>}>{HgEzylc(#N;$Ucz^XG~ijLm$SrJwajyWaVxK4>qeAj`i$n&9e>wu5l4)kRkWHRt9vP!uefzC8RyrnahWARF=> zrg-7@=if9Tt%!9F=RFe|#D&{3eqM!LiSLKdxTGJNzl~)Bm`NB*b=tc786zR8>D8{e zWjARGI68dwu|li(;^i}K6MY|TviDBh=WYq}m)hc2KUFLCb(k!XFw6K_`HFFML>=E0 zq1UvS-NRiBBkbvz4syk;7q{GmBl{kR4|`qjcGn1|PS%^|fuotcJgmmEtMjwt91!mB z^Rd?1zL@SGEMJ!-VV1K!E0<&{%*yef>@7^ZH+if0+O8Ctgcof69GwDW@xmOc+I}0% z4&lN<>xrP>_@7>cPx)5hxir;Ch}{jW)x~1md899A85ktl#&}_!O;xSzzFLl`PpJ-) zp(uZAZi~^9<+!c`RZ6ve5mHobw;NM6fYxkZ9tz#w_VAz2(f@uuQLLZM$t3XsL&Q0c z5Ts(E%1ciR&+XmT@d+F%ME3}P>nthq$LuaC1QL9c$mq8(8j&_DuYlD|FmLQ=V;O%_ z`Z?z^!7|9M6sOdWthtqhCzLcuqDqUWGWqD%rTbH->N=sG`9*&%-`tIqNx#duRk9Sc zP7(Iox$tbM_R(a%z0>`T?q2P}ct2rQ{$7@)JjGE-`=~iA{4F7Fmy?%+DrvlOJ>Tmu%GkQk$dVa=kLVcxO9SSjH{Ly=6^K^P;pUsokol=*V-0@(d z_;p!UEO&3P>1~pUZv+Dms@{KCItr3|g{PvY4Px@+p+a>ojlyG#LHI4Td!?V=K1b)9 z4hZRd34Ar+2cvfsw36h-?yy~T=*p9~KAFF@Dv2pol1-HEuG(!>7k{NPLix-nj3 z9(3ex^a?8QF0uZ3I4kUqICOBn4163k5}2)o-tj$ zrV^o1(WECq>oW?G{>X`%X^=O5Wi)&Sbr54#ATMz%gg!)8bZqgE6bQ`}qWPFwQV{Nu z`kUhS-AI&Ug5WUJ$MZBRDAD8SdsmgY(f!7)(0cNVhbpG4TzWAqWyfB63UHrjH;=s@ z`O2O4@edc?P^7ktbNujZm)9Qk?Z*0h@q!RTyx@sx%c60W?R&Okj-ooD^>Q9y6$Qfp zxD0-6;DObCScbLnAvI%tjdZt4m47l{?vKGczhvuWDX|gX+RzVOK_X~@?%(3(!c#IG z*ZnPXIgxR=C4oh^Uru_XLKvcg&g=6!np|Q@Z+(>DpE(Ty=d8f&KyMSXInJ1&^&w&l zNJ`s0uzaVmT;ZG0-{G3ItI>PEK-{-#m`phd7xZk9q5vp8JROiCA1efN z;eCk$G{Q>zEsn)Bq+C-=hgL%zW2uvex=dV(S*w11N6ZK7Ka(nt(=$KOjpf1_9`}gW zm_Xa1S^=5v^5{iewgzTB)Pj*i^A+7Mb_I5}RjO>86x~mnLmMW4hlO>gbUXY2r~LgP zuEgu!c02$HbLnk*2j093u9FKim58lQ#wv$e5@PvQsH}>{Rh5(+UBzd?>i&#qnGH05 zfEc!+2xIvt(;Sez_M|Y+xlq`DqbnDGoYa`H)jyRl2Fvc^--u~p7qwve*#(1IOb4}C zH8wRmACD{GC8oE-&psB{s6_dXqfbpc1aj$?&C&oXU6ysZHlBIBat?mzO$6wp`i%nN zYayrO#93jNnLR0s9$Fs`5xb?Q9+V`VCMW`kjq{0LgW!>9Xc&Ng(fFhL?hml5UZlS9 zFSFgC$XKIzf|WX1G{qZ;=N$7WkN?{n+c$hUhwFdy|0sN|;Cw#u(~jS)amA%+W#u)H z4ivXT@6<9_@pY31Dcp6WSt)h(Af2sxKIs)c%QhpojEo$R1(-8)&?*# zS;EkVbo^@71pKA`zBOZ;;y-=mH&k$2t;Tze>%jd z(MhJp@5cs=>%nUqQ0h_&MxX5hsBzHxO4W61~-C0lKxl_ci4MV21Op25q zPM%b$Kvf=nK?|u2VQHZZ|Mt?2h-{19)j$x-I8YGhZA#yrMnUDsAAl7bos8-7th1J% z->`o6g}cy9N0M5prOk!I%CtjtE+9(=c##!+E7n@uS@?+g9&Q^7H%Dv(Mp9gx$1t=A z@7QnT=xQsaY(`aQDq-U{l3MLone6ve{LwaRAOeCEw?cJ@0z3RINfMg9(8HxUA1a7x;rXo_0r20`Anyy{h2Th2A?XH* zaD#LF!uB{=g}HcPud^l*Zn*{9SfRx_!Y9bvCW55*FyI7I#BjqcoW(Xik7m)QTem|@t7>` zSO^n|zBUgxE5Y{X!}SZA_*#w-rJmFM62!Jgk#cjev`Yv#Q$5Pte#ieU8T1FP&hhK6 zoF?%M4(6nlHf1AnjWnN|>R74r9*p#1gupz3Tc}jHrQgst^8v03D2A8;yOG@l4_$f$ z*p1%@Xx}c(CKsmAWqaB!jRX?YyjIDV*>vH;8&!YX-V3~L@EZ{w)x%X5k^jc|o{imp z&JCYfRVo3!j0YI~^C;LRf8v5T#k>Wu3ZYDOK4>!_!L3a4dy1^@w!}Os(&`2HFI!<9 z2s>@eP~60zR*h?CI7X*`ZeSndSw-6rk^xydtD)!(GTYG^tWb}2Q~;m-HV z_+1h^B!iqks|Oa+24Ktqp=!%Ii)G+Yfl)PPm~{yt7%!J6oKPy^1^?*Er8jw|2u+^) z{GhDdneXRMDnAFsjxNMq^47%6Y*Z57sFK(FoY07^^e2ZL4QH331ER^vV?`H%(7;9? zYI7u@K8jUR9S^Q`DSn$f;r%Ji^Ah1V`L87;?W=uDX!~6RzON0r!x}~c>01~5&u48I z(n>YQH0* zQM;wu(~839Pi`b&O7}}k=1mmLN`d}>HVJK;=3F8K@a}K0t$c&@f!75EIkrk?EMx&- zcpno(Z~ig6V}0XDS_L3_%^yb4i*K|*>10}SqBwPAhJPd*axf=SCqs#8ZIp;qOCPR^ z{mV#Yp|729Omxq%3F`)gHJMuD3|agGbnXFcE=9D)b7iYP7u^P8-#~V2sy#2*so9C! zN8heq#GZP*68JAcxPhy?YO(NpGL4|ir1SHvH+4twLBEFHKfIP?wV?Mf23YHC*pYa? z)V@i<1fJ@@fP(c2_~YNBDx=4LvVW(ZJ4K}!g>@CJkrl0-8CpjJ{6z&24V$CTG{h+4 z=vCtNPQr<}*kHPh+reqHnPh@Mxgh}qDd2vFSK0nc`<+McFy9pQc6*_fkLSOd#Bq0l zB!}IKxnXf&yEe&Xh<7nsMHF1bst>uv^OZ*l@u$&v#M8wq0tyOEqDtMZYmW=G9!rZ? zd=diA1VdHjeOretX>ag6!Nyaza?^HT(}z=w<85TgyrH?f2V)O6)A4C9qXHVLt8lZMo)fIB*3jQOKwq_kPv>cF4B-FREGUXB?ueJS zkhn=X;Xlp<9* ze)ZgyG3yuJ$(X~+4FjxLCk}V9yn$?LN8?L?|g3==_%%_m^Vfp0bv@ir2# z^BnW^Dn_H5n{ue$@K0-(i*ag@_veDc{q39a%!2F~ymp_JD7oTxtfh`P0sI%!G%7j*PSX5z9#Ut==tZMbC=35 z!#ODX=N>=(tZA^PelKNkkYp3+BC+WMTek!m>SQRt8fh8FIUw^7AnBWxzI6{Le&W@3 z;VgzWt@m@fo7I^HJ0l?jk zdJ)fR0~*|6%+gL2M>lP#jN5tpC>uZJM>WBKt}vWedSSgs`W_OeRA81J+N`fQ+y#1S zuShn0hgc#+gL@k4ro!F{n0IB8`Z0qygGVW+spTt)-5o#rw*y-2G z$4emsh-rw9V3Cyx7YW*~swa-{DWH%EX7C156{C^Ot#tN$)Ew??+8ktMS>0JNFe^)e zr}?~d`)-g5=r#7ET5FcRYoyktK3%*^+L8!TWt4g)mlKQD5x`xa>kMOR!~%wh{OKCQ zpDk5*oZssVmcIfT1>2iFjk7ORO`*0r?1lrc$dnyIDHf>4>*=BR+1yuO?}}%L`m&k^ z7agX;K{pEG2wn$}=@3JVnW??{Za)QykI1;*xX?9lqm<3^uynR0OvrbD`aY;3&F2HM zw&++N%v;PsuKWHzB{QpQ@i6Y7qDuq8Yc^z+Q*RHoM^c%T}3l0X@7ob|pbU za*t6K(QlWcjEn<-<#uFJRJDIyIVcW;CAh`EpGEoO&Teh?e4ny2(s9-O>HV@2BjsT4 zQM_WM!#%Ti`;Q9oj(0TBjHg}R@De18yyMNRhCW7j&n1#plY)^@YFgqHRW#WDTW)Mxj2ux5FRiK_zQXa7-cdrZelGn-!!n-WC|39&S= zW?+UNI%V*H1|KCd`34e{fwN(8f3N<0D=0acCLRU?5;Im?`qUVpz#kd9u4lP$x2QAa z?v~gkFxCJRT4{n*K#;=leFZ>j;2;4(djMyivb*5+GI9eGDXToe&qQ$RRmbuA;ntar zIX}A3rv_;I=QHl7EKCsKzkH8mDT}c06FWV<(Mvyj2obRB2u`>yjHZ5eFJ`h(Zxxxk zb-g!mzvbLW-GuU;vFy)?9cMHDihLV-<>U{O`%!QKV%0KdTgZt~bmcPwkqV+Lf|M3? zEi@f*?`?o~q>6zQKKM2R^O+NjxC5;*oz)t<5mxs7P2NT0{C?`J#wj=%{CGL^diQ_` zyj^u@GTp(ZzXF0b6y-3ErRz=ECgM8JD%^BInhGZqGNEWtJ-o)0e!R+gFn>O~)kS3& zCTu~kY!1YXAFI?KAS_@nd_nUmD2T-OzZGy*QjNrQ9^`?%U0vs$(fIG@sCoE>VXVNB z$dRNq+t6ZDg>dmbBoB~F+Ae}W>=Cgl2{+1=KHI<&Y+$AwiR%yIl_E?K@R^Py)7jOv zM>DJArnUVg&yK@q3NwrxoiFEEq%iBLqEso3dH-9E6*KI0Zqy{NmpgcQo zm^}_DyzQmOeLQt)*BXO|d}v1th5!4gFn`uH*dRi8Ql`)EoaSgYjFouwm;3d6_xbs% zyvM&V>X3J?g*-5mZlANQ&p$9zW>*F&lSovB6?T0}0)ny^Z(eYO`2dFz93yVGhDbO%-W5A3ueB#1pr`+?CwZcq|odOCW4SzoGzGKa9 z6CIX3j!`KQ8A`f&ho0_OPYUPCx8O;~!bnoNZ{Nz;_X!P(P+lNdHaCGIH;0g*Y-v>d zN;8#8zO4y_p!b4_OJh_eeGz?VAk8Qi^tBrCrF_@1`>uPwBtivYnQBGq?1}}V`*9+Z zkzkU7BNDAx&Y-s$|D<^LSakcS{>ZbK7Z9Z|3eWYHFM~4F@`Ng(>pmBoegGQ9-2a63P2&OicMVVFCp_EJ0iFc~@G!vPy2O`@@-%iyFIRuzihG`Tp;JfXnY zwH)$)(-AS;S0U`qYiIl8bh;t432c7x;C;IjQ(BB2F*}GJYh+sM)g55~Nm>HNPjfV- zdC$Lr7pBNCG4tENu4Q1NknI5d+r9rR9@ zCuam!(Q(O4Lhz8&K90vw(%+vfu65?O6;kd$ya4kxv0^r>&(DT1Bf?3OsE+C42DUP3 zq-~Rzj*b*;!Va`Q2$T2*1(^YC@Y)Uv$>U7J;$l1aKIwsZ%S5#1US>+~MLJ0B_y93z zywe~jDqDnKbs}=_whUStKy6CY)W;kZvT%I5SF+llNw93LX*syX@t1yoPEu5mbakh1 zQAaZdqYGU}4Y#qq7)^OE4=S6?nTt=kjv8|BteV6q zb9y%2COT$N913#E{`^qSru-qT@O*-ov(y)DZnCo36EJra|4IJT#Z*?A%;v@X@lHF? zO9sFv*1?`%Ru1klefi*k5?(I|%y+gv&_7#x)VIMrqh%nj@tNZ!3(r;RN0K2FnHBnV z1M^(#R~bT{@8rrjN}Ac9JZa(6<=j!IB$^?76HrSu$yK`H51rD~chtoT8-=aV zjeDDAs-dwg?Ye}#Q*WG3gBLmd_+*A}Dst{W#kY5OBLI|%8=Q}t;hMg&(j;J|RMnU< zy2Fe4D)FxEWEVo{0^;A>2B6Q$I%Q2iJYTKl+)#L zJ-#dfSz5>yPy`1Ev;_sl-GpWyuJFN}_BgHgEKs8RFK0EmC|^T$)>W%)A%wI!!D0o| z561EWtFL#Glyuc_nV520K*(DC;XucfR*pK5npBp_H=y3fsHD}u=7g&!;RNG(buiSK(c>>Pi65g> zJ7z;g^$b_J9Tfh{>_1Ja?(lPd+H;nkGy6$W+k#`c*>#RII&}k1jMZ}tkV>CnJg($l6G>eRvBTbBt?m8aO3VI1JY(# znpuNtJ5B%m&M0Fyy&*3Z9lf{vf|PKxn#TBLW5m8z9leHsmc(%u45Y&hoSSqg^b#eg z&r0NffF;o-N{WE&X!7JD?2-)W4J4&6Fmgr@Pg={w86>VprMAYQ9xjmqK%WJRdeD@%hRCviEM>(Pk) z<%ePwL>Eq?yNjduge-nzGYupF{vmu5rMmhX8U1qn_<5Zw*Mi8Hf8#INcZ9(c8t)%s z4ktgosqvK4NBmzuZ0on0Rh;U^s{C{j8|r=1ebh>Z424zjT!A&IY{7>^`bm~wAU z#gX_yXc(56>Uus5s=|(c6R$FnlTt<6)-1FSaNtglYpTAKLS=Xi$B}ne%+@da;L5%; zA>Yu#;bU0DsvsAGw?lbsMvPLEFIYr!?{%;4E2f*&a1QG4b*xeZBG)ZF;|p(?0C5BHwoE(u&%YQHtcu8^D8R6hW?sx`B!-o*%Cy}lC>$2c6 zIwOG5qo7Sy0}SE_P897T$9TgNXQw^9C_)$>UgQmD*4=sYYGtnXIl9fspWUc5zyLF( z1bmWlo6iZItE)Pmy`J#9Q-sfyCg-}6EgzTUAH+t48thcFrP{Wf{;k85tV&A9ua|L8 z0n}+1PfqryF(D7&=E1K^cPUtxsG2pfj7RkN)~_eapG4Ywm|)^7x9|8^zhp3`eh(O& zj@>H(bp1k)spnON-_aq^_L@)~l15D2XFRFxMIeH2+)@NP4kO#nS5dFu*~tWy*|aTT z+dTlNH2SB>rTVyDN}Uh1Md$w6eQP|^Q8gJb>;ri3dw=N&KhPy-K}%@m{V{pMp@1kkC^x@fcSi{HU59}fZ< zK?`53+5>9L%iUo37e(A4{pYBcTG0IQNv!{zz`fs4*SS&rtupg#P@LP_dElBeUhil8 zIiI)%fp$gK{E-5+BK^fcL@fu?z%v|svfjH)A4O0haD8nkUY2d5KuJW!$z5dq%*Xqz zmvZX8nnLni;w`)5#3yyES<9gb`NBW00Ez#wBlg)C-mCuX9cO1aR24-XCnK`*j(p1B z^eD=Og9f{R9I$g^#G~Q}V(!F+5SD-Gb5rXG1j+>Y=0M^4F_%Fdj0agOW@S4e&*GCW z9XS6Ug?!Re7E=(#p2x^GIk4hLZz?(~tl*$TCNSomZ;L%u{nAH(j8A2sYAtY#ElwwI zeBn0w;a!G`9N{B576k@s)Z%u5D8f-F(d>PqN~wXtGBQ!kpwY^Ezr=?Q!;S_|SzcL5 zZYzMtCtJ{V>4*AxH&~yC(OfsA|D4dr@YY0!i*QLSC~>;M!wS>?pcl_MZ}C__ZcEP? zG;wbYw-QBY4A@{06Sv+(L=gah8gILWgS0_>$Zwvi{>`hU;rhUcx8XFLCgVea9q3+P4f=E>^jAEo=-^}!Onrfh!?YZsV)@Q3_u+=_zup22B>i#)7g~zEH;1Oe* z<)Mh9oATVfFJ~oP?&Qeq6|igq_}-eAOd?0f;tQ6bDB_fn#N&g1BP^61@!Dgx*Sjm$ zm$dcM{gJ26vgOb*Ru9oZ>;NLb8&U#Ixc3tGRe$IJ?tn=RRmerq2?>g8mf2~F2-Ojs zRQQ~Hl_*+aZ~b*Qoj#x+-HD`YWaC8AfK_l-2+e=^ZW026zL@~Z=QzEC!5s?0%scSVqJLq4%0OeIkfhH;28qbhyiJ27(tr%U#j5BADDy@`o{v zJK$>ZSbbn}+zDWA6}HlZ?Ld^kMXi9bASkTX59YI_k?wO5wNT);y5~5_B-PhG8Jn4o zSiRlu;GXFuXZVxf zZgTus?q}w>{@MW@g$cY+z==e&$O2KCs0F^>1rrP688|ha4e@TK|9=xRMq9cDl#7YJ z*ue&DW>QV@vgrDa#mllv+wAR;yvkaL#cG z_!00hf}A8SqAtaZbv>FU1de0<x6C1G1oSkGb7bz2*h5Ay;GKN|cE9(iq(M%YM3Ae6wo<1!Jjvf8^E7ZZrSPLv`il zw-3@eWF@IH<~M$$%z&#J!;L9zYn6l#CCG2Ud2*#%yAyLj_*keAc)Q({Zf=?UR$>Ot zt?;Sc$wg>GCwMn%&6Y#?g5MX}EJrfm$zmDtR%pYg=*pDaRs%o--!w2AvvbRdNl%jc zlGpvSdpp7Qj(x|s_IifY(BEtyLU|`{z!eV|<>1F##oFxovzbG45!Q3(-S|dPY<^`aqLDWbwhR$w94SS;h`u?63j&%lX zthk2<3>Pw(Upq6G_IJKc%+e{&e7(D@5yi8m23o%uQOujizTqVelOz)i$C-h5GGIF* z#Mz`-)h91@`Wgu#~Bf?}R!hQ#4<3I*6WB7PFKM+6LEdWd;5`HY{Q+^!?pMBacr^ z96`f>K#3J6UD=eT1j_|zX!Y=zK`rNE_owovbFyz7JNH$wsSam!b9hD^#BdDo@1t2O zBYmW3`^Xy2DM%Lbg7L@YkEdPq* zp0$Vs?35wAX|~@kmhRT#O*xc3TJH7NC?Fbpltd8R9`6y zW3b#?Kex)iDfO!wpaVD491~4?bp@vAl>XBDj2AzIyGfNpb9bN~fl0DSIg3Xw4y+pu zBLehzs<&A~`WW$#7xWIj^PZ~6BP}|TIsJF=-Rd|u*!es_lbM!lH|li4+0977P!B-8 z`{jCfe^A#gzS+9?O<*!PJ@fU4MeGC*fgRvfnetsFk~ke0gTp6BS-7KkI;-$Q(RKH{N7eJ|;SX^@ z@bmknWq`y2U&v+raq?H2+4IzOq9qxJP$ovZX8(oOxshGcra`m%qAvIg)2gUx#oie8 z{ui`Hqw z9?eOrR!@TA&HA0z4|2ltc=TURgmaAZz?dlBsDb>1?3aTYjOeI_R!37(80y%Ut0XA_ zWOf0Mb?TIbF6zAUF`kh|upJZEgtl+{tgfz6hg}zP{K01Q;S?~iIq2K`0V170kjzJt zF9IQA?2I4OX2Rz(Fh6_R0{(Xa4~d?;5pJv>>2#+QkS-)&ctU1#FK#Y!U7}p@7SAdv zW7#A>K_Zjo{oi*!6Xf+BswGfpb6SAu4=J zv`42|)KIO>gA$O)^Bm5`yONgLUj@aSDC(7?_`E&z9&b3AHPuy4T=xAOjD&VqIR2Dy zJPi|)1=Iy;g3HfpBVZPrD|Ry~AmWA_PdI+W9F~65p-*XJ5IWgk z{!6(dXpuabzO-h_HS~*3JUPD8ThaHuH(PDe$9IHd&xbKrJ8I^Ol$~frH%F~7QnhN6 zs@`oHSdAz(q3&|YDOY27fE`T>zR>!S`IsN61b-hG_<6f+K%F(@dzO+JbihCfXUOKg zJZ=}Waq%fl?fvO@pbExGFjovp7qcQW}IhBPL%b8tHb+`K9dJ0{e;Ug{DgM-OlD%?A%96=Upp}3Rx0Mo=;N|0Q?+~H&D((j&q)Om4iI%A&c!^%l zEgVg=U({J?x#YGao+@3%yB}oGN^|ALtngg!FSBAn2Z1l(twunh%(9w6RDu4!fOO^K z)nr`HUQp9j4Vc_7&5!p_{0+#gO!Y3w9qNH}yJMFlKHCTvE7HF63)kc|(ry{C*Qk1% zu{*#K-nm8jWpe*nMU|^-(;a0G6qBTR-VMeOc&e6s1&V`K^bJ+1FV7e0h4Y{8=5;GC zLA6vif>BTvFxj#y9oZ&V@@bt_k)6NZkWN5W|Gy9AG)V0f+urhbl@jsatHUezKKyvz zw^7E?vL)YTA>^5j+wLSRmV{N5JHB9Zqk-?w8d+`f{nUQRH1Mu}~(f zJv~9u%^5na5^PsMDeNj|v+JO)vL?q0d#bJ=-$GQ~@NJztyQdKsb#>z3{c`Cx4d0NB z%sR-Ja7h}>u#!!^dPfv-fnPVe-iH7D*%GE??fY4U-m>r)x31!TeI$P!P&b=5H4F1P zI(5&WU#wfK^3QdU1T+8Rldw6Ax}P^8#Hbp>a{x_whajEP@$_6PUb42itY{0H`{cr0 zmIiuq_=~^g+?#CMUuEQcAV+(l56E0{n&_}j!2I3IgXO}I{ODsN7HJ0Lb5Vp9yv6dM_au~&&#ssV)?ZoSsHagQ%+sT%g)th z+caDxIoD_~j-UoKep6yaAgo!Rm+?4Iueb9r!^3f6kKwGlzImdwlwbfT=;!)i1m2Wj zlygg>tbAZqFIKNeMg6u%-AbLngFLK_S~LrlwAOaoRiUfBALsMh@yYk0RYF}Nr-z_1 z2`ZB)yc?U&l%l}spgzjDiJB?zKQ}Dux643MSxIC34(q|zBV)HGZ9E7mlS7`gvEJ3% zVZFQjTlq8Y6rP4`s@cmkKInYPVPoT{avMpcS$b00Y$bMKxvzc?SqFQY+LQUmoB&*! zZKb(Ekf3S3+fjY%&X)UGNy>YwhZn*VK=&5x$1 z|C4`l@&c>z9%5GbF@B@ywP!lfVSbUM#`u>1u)2qSl&CY+CCblD`zLn2)5h)AvB7=U zFCS3mHv`asD;S<|T*F@iXbKDxSwH7Orh-nH&?{vdjxlBHL?@eRb8n9y2VJ&dvC7v+ zl~5nLi_I`w^N>v!30eSYS`4%qIcE4`r&BVW-m`2i2XAUtDyzzxJrfi~qkkO&!HwRR zAvb$D;tYKmLD&4+u)$I5rlW}`7?#IbDOF2*o|8XvqOK=h!usQ6^<)X$Lm>oT$b55$ z=C8WX!K}S^NLO;|uN?CA3 z2rv&Z`fkIISO3MeM^k4MjH#X3wVI_5vx*#=rQF?ge5!m zA~%>;q4-U{Uw93g13SsGP)C zb$K=xbNWYM)+MF$XS&Sv8s3$|;71VF?-ux@w##O@*$&K5HQpr^Ga>_|_VZP`-8Nth zKf{t{tgesNp34X;dp6T0>f40H+0E9}5Z7w2|M;W;6F;u8)w@-HOXGNFL?rorg2}~a zKmPj!K?An79zM#px)J^}>I64e!UJESQk0kh+GFC~)9N37R)D0z0XyLg!;Lo=&H1B6 zz0D%utOWnr8Z}4t@4@FhkMC#0Vn5vz1t-y~XT55O?5L5#Aq{@WI&*pv3t`wsHd}hn zR2H~psqtZ^anKL753xV$j|4^sEMVZpoOsiZAaZRJ;p>U`K5U67gNf??cb^%XE6P<*QPeRkQl2H8goypVa!!@$Ymz!y~kj)EumU^F>P`$_64oSI%dmY z+JS27QM{5(D}$Ml-AA?}Fh~nt0=%W_1*)TU(*Fn*x>av`pR8R31mw9 znh;t6yMCC(ib)c(;1F>dfQoSQ3F~$wBkfAg6J72z=F+dt=6lSX{Egqirfl0e@igSv zFAs2dpjheSk;c7N8BT=?NkkwdrMdPooxq9waATb?Qd(ytN+UrJ7Th4&x3KLwnCt-9 zW{V|DDGs8Ocq?JK1Fm|R8)#U9p*F?lt@(A?p7X+4!|cz!E1HvB3iRU@d~qH^aAP^i zNksSVH`E^uQ0oG-QN+Y$zXIr_3^14QH#8YJ$p<6*77w@i44?o}2dSav+lwrd%6FeB zB|1XiR+99Lkdx>3P$;?l#G{|f(lx+ksR9x{&A7FnE%=k;RSpuAw(MT%{oB)LIJx3w zQJ}}y@M-B3Nqj#8uX^5s|M`JYWB#F%D4-z}AK)9HdQTN}=V1OiZ9VUgcJ%)ZKKx(c zUjWvFWQF_Gjr%PLU4RBeUs?&k)1k0$mR1;e;oZztZoVaqse{p`pa!Ro1V85 zV1UQAMx@%yPm5ML|7?{H>JNU{w1BdNP1NxgG)W){h9nt><^w@ID zW)i0!VIj3m%SI6_d|Ph2tCT#pOI?kCPz}B{ur18@*ljj7=RG(VPUQ|Qt>|sXn4r-_ zaE=31(ak1Wy88I0olz#x>9owIM>>G9m`87)Xu;$je=kBx5 zK4-G?I)RcDN5uV1DdhrQ4RmL{&4)u;r29>|scVqXL(p+0R_WjQAatMZs56B>Elcae zezT}O8taIaNO2@ z7wK%xY*Ak9-&7Fk z?{#cfbL>v2LT($W>EBCIyP8SXx;72U!PtSff-`9Pvb*2R|G>7^-GnGr9yy>Kh#5#( zOK;~PJb!cKsZ6DX7I{C};>ZF}K*bwtX*Fx)Q+BJ^?|j=GCL>iH1$9I-pk>JaKPn>j z&Fb&A9!44emn_wH1iW%)J-U@5MQfpXx(`bNGWz!vA#y#nmZg38GtS1^YZ6|3*$T+f zR5Gn#ixGT|Hwms^6*%E)xyti_mE=#BItr*Hr7p~z(RDq0- zLPq9K$4fv|y=%vY^cCz%+)IhFWxh*!F4!+jwQJf>U;e(y7hhu<8Y^)w$SI zuXoO;4fdu=M>En^wJ-eoy!U`|(LtSkgix6vc=HYLnE)R=|3XM~2etYTc1YffD1>4? zAC%FAg?&Zv=jx4HTsTeh61;m?_y(CBi^bYN$m z)%~G6X*Z&CwaL`&jR6DC+~3MFT)j%_dOx6lm2FM=nGq z!P<_y5VmXRjEQW3C-XeB-@zF?JGM*68po5^#wP&mGCul9+IYTzN`6q*Gv~YBs zdd0;m#hy*Ae><=LyY)Zv5s0Da!|nCR)#hX=KyE}2g3*H}_<FRlPvbV*UrjH84m>2j>AM}5(%oW_Rt5szpfd9kq@vpae<|z`y2-;k-VJggh=xg1 z0ObMzGQ*E{-q9FEN}Jc=od(trCgR1UQ_2HL1fF9%=+~z!`=-OU-p5x+wUMOSJO%fQ zC8uM@K%!aUZO32Wq528ai^3O?%Yt)^w za(hL5!u`)IabBv?W>jCd<knfaJAv}-x-|GgdB;@iZOuZBZ_U9K)!a6U z-RTr1?cZD9JJ12*op(R&RUR%IMy!HtRr;aV<&?R~6y=rY>|+!=izF1UA3N*^(s1P< z;eA=w-_^U^ga?NeSV?|qUStR8bFw!<@Ntrr3#%4BJY)2O#=|&>4Q@b+WRM$*71fTM z(2p2Zy1z?yEr!%;{u!mm`zv=fCaK`8)V z^=Wa>zN=Gxs5CLdJ5V@PPkiN%R+0qD0Og;>2RssZy>U;59|+u50bVGq14xkDo2K7M z+~FoDSU9Xw4L`nOsnsm{MjXt~-;T{A^LoF4LCbFL@l}~zl&q`R!Fdkf@ z%0ZX>hj~lMtbPi}?>FmT!S9V49Ser+Zv5tklI3Lu4p|^LBHnwN+a}YX^bU8a{*jxC zW&{~vNXLFO(%3$mqvR-%9{o^{)QGjDt+>{WM9e^QO}n9tM?DY^YS$ly+g=g6c83nx zyL$-mVhyb}aVK-s3S_|DO{_p}?)%JF7zrX0S&@r`kQ{_B*i=~zqws~exl%hccdC>V zwyv!uRn_e^*em*!-k#n9DueV&Ik&Z40uJ-}AFDl(B_*#F z?ZO&*V2IpFP6C>Apx<%U zC1YpqBhPtsv+LpBJ4%;^Z{-rk@(-?qz3K!XjO7DU>9EaU(mFxsbcS`@M`=OAoW@i@ zUf2YA*4X;YMx|#z^2@CKs|{THaccbbIp3F`U;WGX*fWx+Z$lx`1`I|K#zJT(;Ru%^ zvQ2;!;V&K&0FpVhAd>&`*b>s6H&Jw6m8i*xILIG<-lu`>ruM#c|2ZHOr8rV4k(JSH zASJhhYPkdoa#z5I)L+rTYqd-CmM#m^qiME_;K4t4!ccK-pQ|GY)9xC~Cr0C|G|#qZ zY*Q5})l>ViiC2*5SJv`sB#6BAaZX2>^YGfHP|DEOk(-q+mGv_Z!&Lo>2@U9Pc6350 zA3ce52Ip8xd`@AMu$ z=aRCSjh#+((=Nf>|F**qm2)RV6-(J+yxJd4x0LH{p~EX}o@JBM;P1ZJXA7Yj3$ z3<$LoE~fxpxkBGBj=_w>3PArI#HwVu1Qpe0wr;Y%M~W<_g^n69S8BP!zD35$6@hoY}`$TpP6?@U^gRX^uQMzYlo` z$c;Mq*^eNSMOl|gpu~d$<0nHe14Wqiq2`$p>vw{Yh@Zs5mVo5Y4uu6{)|iQT@5RxP z83<8PvUnqq!Y}r5H0DaCpgPeG5n9b@O3}}QW{g4n$ym#LEx|d_v}jN5>1%XcfHA5; zQU7T@dBEd81SnsSX7YEh`N28@+2fonQ7<T*UDIoP6#lD!X$Iz<;iy(1 zjmTNh(V@e%l+D7d=#uC`)y9XRS2QA?A2vXSSqTyYnZmeutz2*b$ZT@sFT92Xn_kED zsM{wS{_#M<9$i#Tq2@C1BasG1Z?F3be~l~mdsueB4zdvSzug)!3G>X3lcU~X8d*ME zoh{|Ovwno*yQNbgr3EtgiTJemyv`4#_%x!cpp;!RQNZa{E3T#y5*J6I&j_+t=2s<@ zq19Vi43M@~mbWWSDgYZ=TKQ~fvtFP{LhEDMZb^ER+BhO>O^jg1)i&3-_dLGon+bKk z!GO^KFPf7Im_n&adMn~t3Is(TIp8EZTAHR}ltY~jlZ7Yqxl7|93K zP-ff!B>edSY;|2Zm*FR_hcqnGa05R3wY|SU#xemu8{mTooIK^?X3@KZO}broW5b$2T(e`cb|fKc7meEH}1LBj^zI#%(StZQiRItZ+f~ zhx3QKNpgn;rh-9Sb)(NuWk~32?C=DS8{7*Z$NNg=4K5qSACir_Aflx@k>*7X+tEafF^+ziYiwjN7^6K+9+v@K?(ifj(pN7MJ=X<0y zGHu-cp-`bBZENju_($m5R;9rLBh~bR=5vEW{_O*qArGmQt4C3q@YVYJp-{z1+UubP z@JH1yzKp!{K$tN6D7)StEG61zdo5+=Xp*Sxz!Wu;2>((F7b@ZoMq?&Bo&b&sq=StDi2 zhCO4qGtxKv>Y{l&7H!F>0X!|D-4LuOQ}g=V!mjhTNRSenT#r4EciH0L|IGe*qD31_ zwFHdZxK{kt`=pLvil-#^{?5A_`yGzZqKG1&W zpM^9}mq~lFa8<2!G_LmM@Dr*p*>QV(J-hbn1C?<&dCj(t)O&HX+)2B1gvOe|z^v@Ojte zjJK%pWczz+dP*s?b>DmOhkiMSpAK1)9|lBE{7+Cy{d~rCn?C=x<96%S6-*%P}i@D0|^p}Zj}mEJ88|3{>vL~I|9K1yWdP`t35WKl+*B=fLaa%gxckLN<6R+un`%_HuYVSLHT;zpl1!DAwv!1;pvJ@I6P_ur1TP zynfF$l=OPqID@0=bI^aVdsEh^@W+8#OM#)#t_9D(s>FtWq-6AR) zdpWJ9%kMMFw{=m`!X@)FR)jk6A_%6AKPL>S4zF{g6x#VUUd8FXM=zMMY0WDf_u%d6 zGGUFOac_2dV6!3wSs!hC{wWY-Pz@k%U{jV<~x zJgxV{bXJCgE|RNLtbYsfR2$kIZCf6`{lg3I%IF21mB{=9R2Pj7w#5&jp4Wq3P{?fS zcDr+xWon=wJl^g0u=zxVq*Whv_uA!Q54}v`Z_{o>otuj*)p~mshH66(j54_Bk}AvF zkvFF0iEEA}q3fk3rBR@)^6G~=JBwH$HJ611-t-5(+vutTM*27S@mL{bu?!5XA*6qe zw0c4YXesL*d1`hen?ByO)ELkSh9$i)z}3q_Q69ZaxH;&OB$t))mqF`Lqupuv_kv+1ld+Hh&aoxAmXQJvxK?{*hkD^R9 zX%VLqA(_MhY1J7;Yh59btAQHrL6MgZ9@2K{XAAu|v@zOFWkdW5meY$$tcpfOAn@O`;mNhdO^_rAHDv4!_Whw-KH|F3NGg zZS;Opwb+H=?dxFr0vaM44pVrcnCh>+{C9eD|I)$orTS$v^oMHv7{2u1JCNdH z1G9p73XA^i`Zd~XWtsUBGH5|%WI>gDjgVq%;fV3N(XPo@qKuV5joif`n@eyg29Cz3 zKFRzTt~33I143Ge%6vm{NXAD`icZW*A;{c#w+g9K|M2PTVF@x>AxQ?-+alyCh%AyN z4(0bdT*&41A6n#ubnAqBgk#WcWP*AfIq&Y~O{kzu6}F6xIDJuv^Qoii?I*lmTSd(n zAo7x0ozf#Bx0N%`%NrAP)z@q0$d>>v-6{ux5)aD65CjV$e21V_W(wGb1z{e{xL(eL%6UW}o7_?V(DRZ;5oAO6iT)oKsGof0$f z?kC9+q><+Cp50z}q54xe3`-J30G>aJ9#e-ixX?(vjud8$l#m{G5A4)bOv`k7qTf%n4NnK4(I||dxNkS5;Q1}Wb&9*6pBmNOONI|1DLS^E{ zL*cp&d#m|_jieBGaB^NQ;oIWL;Hz^dZA(U+pO8xa+xxOTw`@1RMkvIAt#(U?wQg%D zJR8N>^ZXZ4+P0LIV9S1*BZPxB*fY&ldfXhc1h%i5t#jvFc@(f#h8I$a91{Np?+)N) z7o)^0<7)krp+`t>)@yjQRy0bBTus}+6`FWL?SB+7U}{+Rbbo6pK@0k{-6c+SAvb@S zdOiz<*!|R)n(Rb|z$Z+Za<-*Lu4k*yS0TAoRW+tiYzZZxaD0Rngq7w1B*gcWd=>ydSsM@2Ux)0?M zbgzrsnvL_KjFEgFn#E~OvTs|3;UXMrk~Oo{Fv+(V5~~xdOdpiUvf5Xw&sBnT^O&m2 zF=@h>$)P;CK_T4ABR>Cmrn)0XV*QJ59ltf9RP4dUW2rZN=b=26$0NlpPvi)4guvBm z(Dce%yTNaSORZ5mJfu;p{I_L1SCG$dfC|m)Ui^}at#0Bt>q*v_@i>1IRN%!HJEtBE zzDw`?V@wIvwrJFE+&F*h6J<(7jz|Q+1ar2Ll~`MYTR+d<|7qc*uf2@GfXLb1)Jc?~ z90vIniY?WxtOzA9h(BpCUEXhStBuE^=$X_&m3M~l+6mvkqOVs$l9-r?(Pd@+dq-c0 zIf_OwEb%z$gOXXLorTWSCx!Rq2nddr=>cV#eV)XT5mudg7bWA6@i8Ceop1kO0cLx+ z)ulOAHhvIkhhzPGNpYx{$d_8vOEA`F#l_&?8s z->}x)O~j-TkYs$q%GHXtt}~x(y!TXZ;60s#O1t*GSfk5wcMh?x7uR(k;iLc;kb(N& z_eRRRMA2GwMnV;tnaNwv*jfYMu?V4%$PXChhq(3cmR3XtGK+;!$y|)QY%-Xw&rE}v z`@DMv4>qBOqBNAVxI`(x9}!SOkmCyRd^Rk*cN~>*Zlc>Mjl1D5A%3!T?W3Y`rL?6g zq~apy1V#G_IdkIahR>BiC5G;3x37)Sj6 z#UXuvG$>nV{s=^afxe<~yD2biu|FG;1VAnfeZ=KN$vnYgLov`j>%fA_aPn>$EeBR6 z7@Qskd!s;}QD3gtdjsWVI`HmA8iHw6sv1-brOD zgB9vj;%Pw@Q!f$sBAOa;#2O=fp`>7a+l`Lhngij&=_iEFDI5F#ti`er%EJF}R2#q- zIkio46RQ7st-QK37s}=6C?waNku>?y41<+~R2cEVm?N!YWr9^P|CpTIclM7o+ZROh z-$de_Xm%tGLq(WFD37GJU zE(jk}^kVZU(vXCQunLkfjeo;MP;<%X#~2YhR+2GD?HkfpzSURvb;&W!mh09VM$swy zLM{6=7_B(9&scv}IxW6rOW%}1rAucLe1>DA2?ndi8~e(^^y)vLK7u6{;V_A)bB>IW zCCBe){IY=yxJ55Ck6yj16IS_@u{#F!TG>j8ZW|OWmxsWR$e=g}OM6okX|6t-J%r zmz7VkLqSaUg|TH`JqNWe|LIhx8dhoX{D09U^Xr)@WT87%kc?~T&gE?;e0z$AwOHi? zrWl(Oq+62KQZDc7hVMr@p#bE2k+l|W3o+MtBlhYw^(fkJIviU!rP12@Xrek*mEbPC zG4Ed--dKZO+n%O*&IM(MkoNjbhfmMj|7v9y>CG$a>Xa7ycv96)L5@Ce>$4y2?K2rA ztG`^D4y7&94%ogjFuk{sHlwch+5EZK09LArHYxM-@_)nCPwY)PHq!HcCJ$%Y(bnbH zK0L(gTy=45Nx_Ojvhu4=d+De|HWX@F?~epdk$tEs>z6V()Nf%jFOd=V-TCKafvReD z0J^(VF>Y(q-I}!m-m?LbGqqxkx;N5C3u$X^!d|Dt0zV`4Uu^i3eb4&8aii;8oOQ8q zO<(<7z26dgRmLYruMwbmc{Ah?A{YM%Sk@hG0wznE|b~VKRZ6 zBzxeuB4n&6bh|f${+RV>h1N(NyElOc0&)7cKgwa)+S^HXFF%}O$aaK8$_JYZ+2W~1 zK53U9MSI`2LXPtD=wxlM-ugL@2(Hl6LizU5QG78CYthTHNidQBAbEsE)P<}fP?`F{ zT~hy=7Vp27FczjC!1zK*YjJR7g+@HhLQB=;v_OFLUT<0=KNm-E8)@2`nstJ#8m&srf_E zeHH5i*@IP7d&0I zd^@`FZSs8^Elm;Z1U>{7`Bjx+&i_eG@O!pHQ4Z?ZK72<==k(ucgXykwyC=#F zQf4vjpeu6s{x(hMR%t2Tnl@QJ{rLq++1`wh2o$;F`=kuU=(?C+UIlA2^WD>SauJ;2W{GQc*7@e{$t3_ z$#vA`I9y?-Vq?+X{cdG2$k(@9PVl20;v(4mXe}=N9349S*E=~!X13L{PLFNp=8gJc zf~_}~NPi@r2F;q!@z$$P?xPt^sL6!Oi$suUb~}T^=XM6^)r=n~B!t(W2-yHGvK|*l z!zIb6?r<&zIALZ&+nbNeFHB`KD?VzW@u#V?a7j={3!7e5SUBjHhF9sbPy@e1egvqW zM<`nT(Q_A(>zLE*CuzODcNV{brvH~GFYS~qGCd9b{Gwis^#m<=W4xIh4 zlqTK`kP96cHJleJ5ldZnPKM`it~4nbt6VDP$}lb;JXm8>L_ZxYLg9C{9U{1#x43B? z_nJKGK89@3x@{p6Gm8FAp35~L8=w$M6Z3AH1!ssLg1Ng^dYqLtIv(`SYw`nC^&%NR zzZzo6414d_@a&osak$AdHWa(#`(KEB2%gJaE+?Ofst+TWHiZ{=tGHXDUwZfXtiI-_ zrp0V;6NJK?S|^#1dQN8#2p{dXKDZw@k)!TL&+PmF1jjCl#a&HcULhncI2Bsq!QJGv zSSRJ%MHv6NB#th>fnQYJjd(0GpnzO5I?M6%{i);h>Fm)AUWrlhEM%=aR8{b1e(JEI8NV7-TI^&k>O85<1KXR?(dhadVHnJyT3YkL8i)c>3yEAt| zv}tGa#1f#C{vT(L1+>wdl z`W-Qc)_c4ecIQA%H!y<{XKtAsxhemwV5S{Q;n&ljgec&B`MgguUQKdAA-I)KLgsWZ zg-xbK-<6W<^7mD%#2|7CLT;6Pdp`~Q^w79W>hUOE>$zV~f4|8?Qu@ic%^F*;*5RU- zotEgkaeL7)|FqM4w-avAGdPo_IZr@>*abdZV}ai3X&!v^JQ=fW>n@2IypeY245>w* zSP+4gK%RNDn3=@JIscLs4EhV8m$8SUWsJ_r5r-xdG*mOQH>Q7Va zkAVedb~YJ>$vRdbP!PgVTSc6tu3p*kJBbpT>eg*HeyeX~HcNXeW5v9OIojmV&zUu$Y=4HTEAWy@a~(5j+T*XC~SvFXQT(fdz~xw-9B#t2_EN zu<&E$K+P-L;WCfszsp8r$=?48+&A$ejd+|vy6*dC^=QXP$QYgT-pcD3-$7xLL;t7h$dw@2 zV9A`@01xQ#p$ACb41AM%f3Xqg*d4*}q&%WHnS5>uWxBVEPBq&?3Pn*=E=2X^FQYD@ z{5b=s%d$%f#dK|q4G$#3jn@gd?`eyM9ZcLkMFy8yAU0pB(!&UAj)|g0PvQG+od-E} z%SRYACjz*>YGFz6yP;_ShmY5A36W}@+cc?1iYQsNNHW#3I5eVm>zqD3iN``23u>1L zNe!Ofg*Z65)6c)g-Bz_){&n(*xWtCTBkQ2`w$0|p-}>_HB#!nMkFR|1!8^(v(NUum zCH*iy#X@7Yyj>?p^Q2U(=(5p~TZs8IwrJo_i+zjr#w=$O8CzHbSopoJ@Ij)SL)DGQ zb_i^M4`W7Af*{Lq>g6MdSCkIvA}{BYpXq=AR-Tj~j{6QrQynW@#u=#%+R-O|T_2sV zrYD1+Z~2yi?H3B)Pp*t<)B5Pg7L1sxABC0aaD1t!++3@|o}^tQ%ucE@AD++tMghJC zvtGv19m`8)BI?hK>Kr%;jn5B%7inAigI3#pUo9NawpGgBj@*^BAuj#)!#~$WiZlC*_jDO;x@sBF=YRTfMJ|r4+CX{*q9D3s+ z-#(P1xqf3QIgf@D=i7xXJKG{9$)TZ044Q}pw+G&^x;wIvkg6YX0ec}w&GcF*!L-Tt zfCSL4bXYdFTasQ1$!`N*yepOi#!&SwI4@nK{12J~MO$aQ4Y3*Z7;oB@5qI86C=}*l z7?5uiw!=78TE-`Hj-Y6C06JEF98$0+0S#zZQC1z31)a@Kcw{Pp7O1nGWo8sI5rASZ@JbAs5J*dODjo~Vx%Q&pAuk*c}zgKUr$ zV{<9PR64m&T%kKwwe`qYaB7_0A(;-f;AlV-J*(;xU~nl^&t``{6_hvVJiR2RzVY)A z&81WLj8yPUv~B9uQI@1S7&jn{!7UZ8aSyS$f;6Sl!* zb{qA1r0S2;d{2%7SJOorE%91;ta?YRq$Ye{aLJ?!I$1s1hQ~j9m|S(^Te+1On3UR| zNsc3kABBfAV^Q}lhog#T7XiO_@};0l`tMD)yXd5$jbY{pFvcHj$-eHx8Bv(Ims@K4DIMH)#h+Z@@5B-IWY3lw%<7^B!R+jbl4;6#_9F?ybB8yhlw=7q@648 zi)D<4-P8>hVmCQ&BU!hVGd~gEgs>|fT(ns}+l}@CK3!+UU{HuUu*m-3Ho>#3lURx_ zr4gU}0+g!RpDZL%7{Bp@v|UFpR+?YNgXi~ikfarEYZN92jn+oV7+yehjI9ZQ&d!o^ z9oK6R+z?}a4{)bh$I~Puyv4J_;bh(*FJU@7sjrBetdA0MuMm#DRn_Fc(q7Jwq!UTi zQq%li-8-Wi;?j1BRm~leC<&FUSL=pclDU=;HW}ee%FNqlWtfp7suHt?%Ucp0=GEeJ z+JDLXo!#A$h({oT3GiHfQ?9MJk|226B73U)eKfB4!-Uy76qHffOAWc z6wBSiUwJ3-*6V2x$OgyW+tnf=hmDa_ z8*s@Mf>W&_6}xLHG5a?`hs!d=!6k64Pwt=63rwHWV!nU`-z+k0?7O&RC?H&MBvOH- z3D;V%U%h!(fv8_sY)gg>VOz3g;f(-_CSN<(`H0>$m)iavr(WP7Sk#J-Ri&Up*GS zvv0ce%~`y{4HdWXsWP2MKB*b3ntK}H)6157P%7lm)lk;=CQL{ecn3p~h_I{^B#}Im zx0xn?nLWirwS2ld_nF7XKlR>yWKAW(oJg;X0+{cSNe1h%IW?E+SZdmXP+yDvYwQGZ z;-|uB6;&c?`&eXHhiR63cQuy2gDnPo%)A9iABDflUxL&U%OD{Cg7RweuvMX`nX8Ef zSvX1Gs%Wu6K=5+uMr@4gtqNUY({R`^4^NMuKNiG*bMNiw8f7^ga{G}JRVdP`X+7PkYPYmcTry$Ix!i(Uaac8{bKtJz!HdZjV|X{f zj-}jm6YZW%q>A@^1O|HC!KcRgM^FZey5z7UM%cOB`$2J3LsP0dgYc{wqdH?tCY5Pt zH3a2v@UQ?qD~+K{1SrCjxbPdKmg6pAPcyIBUGVOQ!auYhowbEhqhjdGVyk{y)(z1W zr5+mf_Db%DPStG`SSA-3k9OP6<9xIPGHJwDat$?II9AriRwr9ldpy`4!W9aia1I)4WB2`}H0c zqvL9R@2b^-=2?nX%|@TNE-qvAhz)`&T#3)XZmm}d)ipFa66+_Bs6TiR?6FbJ{=VDp zguDNL1ECSRraSdZeoRva+sEOS`hB_G=-|tt3$cA)q-O_^K`|r!Wm{;Lrv!InbPJBF zOur){Xqz53GDN&2FYqd z#>drWk%H?!c&w)C5L;TOBW9hXH*34Q0DK z=W3tmWYEe8+s1C5l0u58X9q#s&Tq$jQIu5`TDlml83(7G>fQ~tApfL*NO}^gBkesb z*kN=+1x9tKAu4l6XJ@(nD}Y$tfKW+#2#3rg86{9u^P$tJv~F6$+HxM@)RoN@+?n5L z-wf&?6`_@3440HNVj9Dz?kfhSd`sLEWE8gb(VtqG=NAmF`yNIGySIFv`lG1zuPsnm zL>nKVxhs(b-5SpoiUKo7llcV*s3b@%liVL0nA!TY1nT8mdTAQ%*GkJY7U$)o$EDSk zSx52gp##ISEuQhK=5Br{;%R=cL6gh?IxpDFjX7fIckEk+ps$_Pbo{P1#k3wEaSIMK zGyDkHNusD-@+srtd2GG%{8>^f6d*|@)5&E6mDgayR9*D_&k3UoFt(0rbz9m~|IHPK z6m}@&J9_bi9SPL|{amr1$S*s>POl;n2*XZPH#~hm%KsVi5B*j>KQGCFcC1$hJG= zw+le21H*!=iaC9V(%Y%3T!0!GvM_T(xKlA})F*zuG)`*J;%jEwQ3*=k-jaC!`vt0u zeA&P6e?X*4exJHE-8to8yZE?2e0PLIDg1OM3yUz_1*z_LD?KdJckOP`w+rGR*OfYJ zLpQVADb3A!z~^H!Nnt;J&okmopED1B-e8mNy7FC?x<1#bx5oIdmlj}5USBOCm68gS zcm+hq07CWq?Jcg1J|Rf%;fc}3tNEjj8yad1t|+YB*u|11_B@pdfe&qvoufa=_$nkMRnI)AnrYI|q~&U_!~H&-q;t3K z;vEKSJZat$s4-bj2a&-i7lSW&-7+(C< zdd)-}wFz?I{583lr@cRId!Pn3>_@2Fi&>fr@(Rk9q+k9f`0aXh_ zEhFpPdh?Ck&e{oN>tmNM{L8TU+V>-B@vL+^oI&lqw8f8SG$!+EnHHKIJGw3;H|o^6 z`a){Z>2E?^|Mj9EGMq9py0fQ@ehYPd>9pF{VrDA;B#3E*{$u;>tO3|BMH zEDmBj^EVg;r52RgLQ26|`)4a4!#wuCeVA(Yo8M0?$&}bY3Zs4g_o}buIPG-w7@m?| ze`tG~FT));T0&ZmuhxBEZQC?^>IdDeem)uIKxy<5_n9(u$|ac#gr>s~p?bkkpJq&L zN=LJgZ}tnMdep6p0WRNOw|)}GEbwnALZrckCNA9uFO!1^lw^2H@#^7Aaa+2r2zDoj zne~ppKF(hEqCbZDvx|cD*Id+)Tr(fXHUVP~b+IiF@({2hr!Z?PW7_FBh*7IbrP-7C zse!28micB6qMMhKNM#pkZW|?Uh)!cDt;WTL3`9X@MI>}Ml}45x*Ve6LvAWm|$EJpR zFBzdseZKYMl@<0R;zUti)d8)*m^TD4ML$^o5{yb_y7|tE+I7v&9gRo3y!&k%;oU0e zXfkQ5Uoxg7^X+Rie1Tm^ZN1DsI&pzEVGAycu5%va?bTpG!2MJ>?D5apTa?-o6 zS|c4nr?nPNsGDDo5tP0nzYo_=VA|nPbNj&hSeHMQy#@o426M|R5Cf2^6ZUW;zBd-}8gW*{kE3qK65@0zMuAvGGGB2S!?E>;E1k} zx5mXe{C$RG)00IYZN=>RT1n?x)hZJt!fo6;1so64S;sO>pZa2^bvk2y z1TJ~RpSexlyiE$t_16vM+Oo>n6#JdA%f}nN#J9#UZ7o_8BS&m9v?x)IS9x&w!Tz%0 zhojl3uI7)g@GZqsN!77g%$-x>v2h<2Wk&F$PzIw?Z!|}$Ft8sC=R*sqkIT2{+;RDQ z{p^d;?+@y|6LHm)e_UI2*Kbqe`3Y_r&&!p4mR5h63(9Ns2jZ0%iCorKJ+lm{9sYim z$FLf-bw-B?adb^ha6MBmdCMKVNObO~I_9(0@VcGYU&s9@y{DW)8~UEk1u9Dr;@yW& zkPEpTCp!PZMI|qEf#YA3$uTyCwdDNdQvZ3;G4I#lygnD&nC)+T+Jw%@A{Z`A3QouF zGKAna2uZAR5AD#7TrVkJ|L6T+ExGS?_B0@4QuT_Wlzxg_>zB?NIz$fS{1i1c|GXYW zTl@ROpAnLV)G=x()(aHB9l~nZADtZh%TpZ~vTlcdRsPNJQPiFe`0PNbozC{Ib<*YU zZ`Qrf(pfMLG}y9a0sft^x+x~!#C)wdtgh>~3yI`q!+FTu8ad>Jyu?O$J@}PoyusjA z1C}CXxyjzrujo!D?mN<|7RKkRgtC`38Kzj1n#R)iE2zJfiCH)R7d`|>97}N0d zy{zGS6DUvg;QnsDY;Y{gE%QW%gmC(`)e}wjhk)MIhpU=qF%8mpXp4IFTqEi@SyIn$EHvUfkpA^J_BniVddO>@rEkarzY=gA>0jF13GG?ukZv*h8(GM&WOTg7+p9S;;lqGiJyt6m&!J(y_R<47F`*OHxQ*y zKRM$4wti}b)AmVq$K@GGK7BIVOI4sT>Z*mP>BNNF#&o}44$ol^2z=U-T(p>-N0^z- zEh3-Q(9zh3*1#@zoMB%_%qsQ}DJSsVhXOu~NPisEIbNok`H zD=IzRwBTLi0ZDsfVr$PjWRAT@dviE7+R{M-f4J!WGK}pznG6Dx`aY;jM(8K7d}H*z zuMi?hw&Nbe@>=hHAot7uE^EvOP_F(}@ABT-o)e`1xQ*WYCfOx)`F}<`;vNG@ZI%7gM9FSQl|(a=i@Cwq zi1It;8uk9){8gti&>+nVRcTXq3iL`nRg{!Uiy8Ot!d%fSv-w|Lwi3R_EmyCI=vIgk z4zJ79D(6-?Qam^`G*7V+rl>PT6neE!aq9*BckOy>=4T$u+K$`j9gC>} zX6%SAJuxqtZkw;NxTcTS2e5vNqg41Wo9lEDrZmOOZ1WRlj>^kW6&4yPy6)9qd-r#2 zRVd(P1)FF4#wY|sZE)Yap+7yKgfo;JWD$pnlQb_9hbaAr>G6FL?uZH(wt|R)I~(Sp z!*yW#B8DxmUyD$rg;AU)4JNFYGOx&n!?TKdABl+^x&VJJu<=Aay^x_Rv2}@sh3_|Z zRReS<+m1+^iAwdtyI-;~4i|5%shP(Ie?SdIWK{Xs#b~!WC5YE@g;uqw&=3R}zN4?m z)c)deGGu9l3y!ir67RCrwiS;YwENMyv_8|{W9!+W}vUlJq4bK2B{JghDMb&2=DB&TlrH|Rey>xfDsygwzB_y zoF(F_-f_ksFjF$4{#h?hL9YeF{M{s3+T4Sv8-7HS4rBiKJ+P!dM~h}gC{@-JZ(jt3 z^^gjw7(QRb*X8p~QL9Abn`F?tpWbJF^6{miLeJ zsuVlDQCwQTex3U|s<~sm_5Ax*rlr2}wULIE%I{ehuGI5G3h0&Y?295ILs;A0iYP`bYaBqkgNPSN<@cKNQKBt^s_W9`xh4DB06|5ix zlopVDlfTDE4=RiY=0RGO^Xwo3!aPRS>U|lRcTA*ShhSTWHPgLtzttF|WF33nKgSt2 zE-VIaKK0E7AC1IgLNisXClx|Vi6}e>$Gl(#jLR^Vb)n z@z;aQLW-QsDmHpIKKJq%%gDSB%@aGVCsY00z(Gc`cndf3Dy+%=inKF6_i*=n|E<@L zu$~N)$mWO3&N-HAf*A zNhQHWE6;DlQN{|R=(nV7gC00fh+hHm0*G1IB|65=zWl)(BOP1dq-MH{xSf_G#zyEm z!>|ti41N$j%F=M2Ug6Tee86Vbzvkrxcf>JG6>1U59;$1VO z2LGs)JScNy}0TBn^ zQsI;3-Kw{JQ`;pwV#hG>Y1DFIs7Swx*I zqD#S(n^}84b==Ia@Hd`TmYUwAMCz-`RO1r3q`Z5WYp#k_@ro5C&w^oECBZ(tgF37) z>wcg|j1TotJ&w^%u9Mg6)Y_iIkJHp&C@JQhAG$+&LYU1nz9=^0sJN}uw)p<-V}vf&9#qnOCydS*34{Z)m|BX9NqMar&E!= zZJip&UV3=Lw;V>Ab{k;28NRuRDlN0Lb1eS?*-zb(S{8i%u=kOpY62z{Qk*{9VF7($ z3Hj?O9?^m|Xn%canDN8CH!M=ry6bhb+UFj^SEC-rS`!2xA!={h(tIZx=fY>TWyFuX zKMd?!IsiP0fDGYtUp5(QxRK*K~LUGewwQ!X&O;9Za7M#1J-|EkR1lBlwL#c!%!Tf!=O~B2&wn!4e-+ zK=Pi3R%ObXNk?@dVTxaq*rej!Cjgh_CfRrID8c6W2jQ$)-{}t+f*V>It+)4P0Gk09>-<^Zg<&K~Fc2gm0Y;3M0W(nSvPeAi_=R-YV zR@t8fu9g-)A;qL(h9ULO;Kc*~ia0^EcyV41@m9ETRhBHZO~LO+thK>&yJP-yg>4`O zu!m3*h7>o%Cf38#Y<_4V4}1yDnFRO^Mq>%MeI{qFaRe#EN*|H=BxBzr^gp10G0nJx z47;-CeE3=I$F=<2cMA<__)i+S1zcT$b)3D<>>e|rN76H=J?hCBocD|GR}m>MU?F4d zlyYA9lyNS-?0{Mo9awKeEbgHW^?aof`REUZLFpvvQcvaUp( zsrirrClb*0m<&m)sBS4B)DF0n6eLm4lP9Bbh{rDjr*os+?>0yV#<4=ldvKqMn@J#5 z<2*u8AP^`>R8XC$Aw|}&hWfREsq@@7-VVkyi$;rPc2Av~wTrK*}4rk~YRfi7%VfFa^2xFOPATi84w< zd-Tf>4z>$X*zEB3dj|=s&6kN8DHKS()9I%zFYc|1_XbY1sSJWw%Qr+I;U)S`9-y{Q zXQy_2W|osewmPy+IG|2pVzXI?cP@3-JOcoP5=JPJu%)Q{Q3=~{o}$-){Ut&qRCh-8AHQ0=w+;8feU4rnvcpHoJiHlX*+nwxNHOzo%vBL0lRgsrq6l48t zluh*erJwXm12NrVQsKLQ>!Y5u0j~iF{Qda{AO;tws);R+xno8nWz!M#SyrI`d1q|Y zXsOvaw<>cgaDqlFl6r`B01sB5X)W&;v{AmuBM>M5HEOrc9%qrX4mM_IB}YkA!FmoH zo(W>WTbZWky`MA|L$P5Q$VFfz+aFMBt1>drmiO)&G8)ew5Sw~T;z#6dFG%iW*jJ0AmUs9{h;ue#gdHZG zD~P52xfWLTbL`p0NXfP0@#IRu$|f0KD7E(gaFHQ}TV%f}DKzS&A3TnZ72fF;aqE*( zzBBT}FnY=sU|G2v)u zba0naH}|NM?B%FLM{=yo#5KH&*?{Vn6GZcpJ}=C8$rD$sdTrt*2kP!|(vKf_-=2M^ zWBID1kUT!QR#ZKw~-B*sdQPXy!ZrmVst@y=j7ey3k%T zlewV5xoCwWy}Led(X?ezu@jbtAEMs`95$E>O@0%8I46nIUc27RUV!$W=_l8t6VI+m z*btQriW@qK3`K$J$7Pp_sL!hxWl_k59yGTg()WKb_$;sDMp@aMn>vBM_(dPK$as|c zuqQx|bUIg;^EF6Ul5xZf1lFqUymDtT>fCUyFq^&+R^nT953tS_1bZhvSDNe7&j)^9 zt`umyLP!6BKt|^wMU5)zczQE%7(IV?Tn|457O0?6%IIRpJsh>4O(AN?xc8zN3M8Mr z;00a%&jYE!5&bbHivg9vCAS;P0Ph^^IcbFvRN~k#KFgbQ1H85a0IuqM53I)sR#6#F zpQzIIKsHiK*X{fD2Ihxw7~$N%YQ%(oDvz*(5+0QKnQ{1i-B@{+d}H2$vfy^LqZh!M z)6;eCHhwMky5uVkwiLs(Y=x6C=ov?KZN2-tOK_nVxxtb`O8Xa?5&<_{h5c5c{fY{1TWEz<&w} zp)bkM(fMoIT}k+b0-)-nG^+@FIW38UCs!r8@Zx;F$Ei#0y!I3CH5x>QUNL7OpD7ME z$Z|3M4G#+_TN~|>?FI=bfKN`QdETSpr0f*W2TypSnY(K4u66@NAT+d=##`44dwR_b zCkhb7$FXn7K&s&HW_?14<6_S0Px_gdzs9s=d<#qD2KjNgkZdRsJ=AV zEK{;*1SiM|^ARowQjUCkdR~*_-L8-62iH0hrY$ckaNxq(Rp3bY^(FD%+&? zf0FGGfdUry4B)zJ)%uP<-rTN5%VL;D5OBCkbIkoE!p)7M0J%zi13p2@g&xQG2PHd! zBlSTn{znP(qH8R5+CK6Ea1`MB@!&*Tv=qvQb6Bs&0PUVD5u1qNW1^K*Z(dz@a)`sv z;#d4V5aI}N);nF7T_bP&mEiXOvjTmjeijF?MYGpn4{-HACQV(<8YPjTICm zCVXVHiAzd@^0Tda76mtxR+hlh=o|po_)#dB#2o4dUfcUIC{M6)fFrf>n?M_2(lo(d z^9Zs%lhjCI`-L?O*tc%za}9MQ6m$bg+|sP?y`=YX(tG(nvwGi;S{-uT$C>R7UjYBN zTm^>jp7}zrSQmN=beM_QhWm^=Q#l7=qAqeub&4sxl^Aox_Hi%WJFqC9pH!uGW`M>k z_db|Vxnvo-cJ;?RCcB3el%ks^rbRsc^3KM*pW6yeF(_56fi?&&y_fz>9#n7OTjoPK>f?`Uv{GOmDMA$L|SWKO6PWb_rHIyf{Z(z zg>JaesK4JQWU}0qwm~L~9HRCgP6#;b{iZ^)UL~xOE%`;KIE@6#(QzIaBKR#xL>ACTAu~$%{SVievp57b*Ke)sj8BRJ$+~= zUO59pl$2RY7FH1a#v+nAJs7yfk$M(k>vwP1$ka^AV_lz7999?Oc>G!o&#D>cT0s^! zuerqMBaoKNIG>+3#S|TO3Wm3l+K=^>cgX#-Q7j$)wqoHnx7sMEuY91fAU}`gUvi+n zuA$DFv<3G;O4l! z-aTXVRkV^yS2v6%0tQILR$*hip3a3RJ-URAxcG4Aj2U8$PTQ@Ph4vuKnZRpz*>ccp?&ew4TvkK600Z2x%~4wo_I*@gm@uJQa{NA4Ir4TE>vDuD2BZbzY82$n+HS(yT zU#g~8a`H0dr7?Uj@r8lQ6y?5ID5hOB%@vfN=r$HpsWF287^2diP4FKJNYe~tT*j>L zv%ogg5BNVs&cJp>!{~Zo%pTuOpA9TlD+r+zhk`Y@a`2#E7 zIzizSl#=DRJxAkmp2k;Q=_u+0=mh9flUwJ)g@u3u!y$iW zDV$7pdQum2iP(Zje9a?A&oJjSkUKAm3qE00$@Z(Ln4csh#MAlXL}-ILOFr<0I;EM+ zXPFQrH~)og6|dGB)p!Hc?n{U&X#ifOj25o+L}^=eOj9_Bvw6FHFWn6P_#;}SpPlEMfUt_C0k`Ac^`h-wMG=^ zcx@GqvPra$QC&X7N>a^#TO`6Qd;urx7hpTWncKITJ>ouaJD4N0<}AwC(FXdoXYw$y z<<~;sC|0SqiIWh-g8NBe$sHn;i83`Qf7_!Nhw52@U^=#WIi!7P-HCdzdim zw`@GGS~%GTYKDGnUvs+Ad+=yo}~?R%U<#`$T{hpFAqUVsh{ ztqfI$Qv0!JjcYR#DwR|(ehRt(5gA8~T463r64M|O=_O9O965E&D}~VGSb8A9zCo-0 zvvcO2oR`69M2!<82WBZ>1Ysy{z+@^-hW(E8`u$1cSyN@u)!In51uypRMADRTxFrwv zO^0v+1D*#DL&lUhssxv)?;@^E`pl(d5o(pd>OV{cvDtikZ=H4p(P3J?{(19OLHC|m z)2)z@2Meo8K{u0r0T!>nEiwD6VYz>`WB#K~&uzuI01kIwpU*hbxnBqxX|KNv#0>F` z!~M1xFLoi~k=0J~?~k~XH9YSjb&Gh@r=s+k(7!{b)Rrw>XinBhfg+@<_IS(xe;4l>ZrDM zW*nBLx?c!honnK=rRXvBh||c~N{~b)(wUHjPKhLSbv!T0Cyr~zUuxn5jE=P+<(b;Z zIQv5p)hF+p2Yagoy9;vpGY(xo4wVc?2biwEwdAaLd1dsp=L%`{^l=btAurx1^_dCf zH0+Io2P1mgHu-JN=5WD&IgJ4>+B(y`*AUR@rZoevCIrqMvx%rK)F@(8@hURhg3-N` zb%M{U<3xQ5D@$%Pg`=0uXRVdcOuh4b3pJciW-C2Ty?-5f7aCN%Bjyi412zw|LgW-x z)#ST<4%bjR+R^nQ{q+K3##6PdNw33}n`ebc|MQ@?8NW__vnG2<&I@;ZSM$>9w)Q@~ zn>9Gyy=mw5BlT;o!H=!uCd1}I*sY?9w>Hm)2j(T?>-JCbU>4Fh34I10#n?sEUZO>q zTQQA)Z?+5t7R7${-pMI(J(2W^wo*6Lp zhZndew3dXncKN^xK*g{6DoVcwhJ+w#oG1}u+WIc(LjS;bIMNw-!tD$J*_^`W?k*ZU zJWm8D5rzXU^td(Mi(|Dw>;^_B2oGpSU-!|&3qhUPSd-Ul6EXyJ9dXC2P^NE>z(WC` zE}>~nyR;V08oGYL=Wf#z@EkCaeOnkoE>8Y>?=x&Q`2VL1BurP&zTrY(Ut*-QiOMt> zqn%2DaH1+Z+;ZmF4uXg}RpH7=Q1qBbkQMm6rbzcqOhG_xiXk5y{v{^C%k5HwN){9P z`t~i*XBP}H5OPOb1`H|8wPXT(`a$<;B)63}J5*I9)A#rD6k)xB35B8tvM+k4Tnqyh z4w`8s;#45O+J6Cxm;8H5LU#w|*-+1`1ON%K81e(?bv`l1v8;GNgVxk#FS04P3HMXg z*%D6R^b_Xf`(9~t>P-3uV*1K8e!F1j_sq;y!b>l3ocnpR%hrflx@XX+ZmWD^Q+Out z_Ors1GkZpdU8rlhCa;_n`e4U_I^?~;4`xM25bh3)OafyDx}($3GKKd43&W{Ej!J%l zG(D->OzEyrH_--DG9V(+juPt7g7JL%q}+=QqCyr=Z$0~T5fctwgE;H2fC@a26x&&! z){FgNt+T$x!y>Ztbbh7P)3Ya}Z-RE!paP&d`)PSZcm{@lgcvydsZ8A|$Ga(>0EwyB zy)Q;XiE*Tmf_*=zOar72k3I9Q6K)gz55R}Rhh*zcZQrE_=s=7qcdiu>Gc8}z#*@k3 qtzyr*qO`1kySBGSlkhldtLGQLwlrc5a#e&NFjQ4E;f42%{r?9>YcQ+; literal 0 HcmV?d00001 From d41aba6771edcbf8758324f200bcc8aca4c12fd2 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:41:54 +0200 Subject: [PATCH 616/665] readne --- README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/README.md b/README.md index 6cbaeb3..923fbe1 100644 --- a/README.md +++ b/README.md @@ -22,7 +22,6 @@ Website | Paper

    )aWhS>kYT)xF?M@=_f zjg0z@;w?)5TF;hoIve@xM{nQSIgVWgts6mo@51=rO^+Low>bSirQ={BQfuvFJuy89 z>da>-7d2j&`<@r(0jv^v`_=Siom7yT*mSAs$n{XVnj4{}TV0H_$@!7?{s?P~n67z& zHT0|D;QK{6W1-lEu+F`i4R@U6vfRndZKre-cT0P2&RE91>-%!TVwQg|D(bHf?ih<7 zYv?ODU4k{G28kMoq?B}QY&rRha|;nMd&lU;GnbZ$!#gTvAy&>7^%X)*pR>Ai3dhmE zQNf*?{7k_Wrv9!jSx;!FYI=M!}KlP;h(qh7E>bP%nW>`(L?=f0y;*r+d zo0seliQ0GH{$82KyLveF%u4^e`n{+8YQ_J(x4{35U+jPDb1dF&aY5VGy6}Zn|Fup2 ze|?&@dV?Fgi@LGE>58s{(#fhr1I3+w?9}YQEOnKGeSLe1D^b%C<7g9VcXyn1%xnO( z1vUy^T)B>HyF;}uL_{UP@d)hZhr0qvif*jPu0R)eV^5ZnK66RAjyMhIW>3Bg55mQO zY=Rrh8uNF7>EsZ)Tr&i|a0N&1gA$MCo?TSgjmkPZ+bkv7G3Bl*HEKGTF4GIl{jEpe z^4VT2DA(!Pmq~j0=)>z`a^IEa{KJ=7^W;ll`n%Wutxr$C_i=ak;rU^2)iK(IW`9)t z$vo!r{&_3b8h0>b|ACA_lG_#N?i(;Dj%Au&0-Qm~**ML?%F}FwJ}hX4n0O$ZbD$b=R)+eC!{hW0}G(MVW_PS8_s81b(&mFS@3|C0_OnbGfh`WZrOUx}Kup9Ef)-2PU9mC>FDWOq^WZOUWeEvt*dtQhWzNzIqZ&4olHjw z>-;eAr~CL^wsaj7^IqF9l^1NJL*vqx!Jz@NX>>cO0 z!1=-!D1C1a$m~m1*XF(e$DqTW4KjB!@ z!>C@B9=~?kS|z<0K9}i5V)_GWx}kLaQpD&C-!CdWh31}ebB|*E#%_XM4PV!c=8Wc! z&gB*tAFoNJBhT_5su$Z_^posWzu;!+YB? z<3y!`^JKNBghj1c^K{MA2Po>?y7l<+<2!N^xJs=_c?Ip6@i7ZD5_P5}WTwVqT!;K= zdx$MaPS}$t)uKq1YlHg;nc$r}6EF!G4UY<4S|QQORGL3KDSYGfKHdfEngDxJFA3OT zXS_C3UJkF2cgsEpHe|Jpb9|Fr8@E~&sN@dZE#u%6tml6eNKs~ddbCgzHO-(Lll z1l*@(b1UF|?E|@uzI6|t1%&7MFIL!F_oap4J2!y+Pd%ysmW$_EXz!Hv|IW-{Wx4NN zEZ**`g|D{2AMF;nloa=tIGymg;0-|(uZfIoL6CM;OAE0jWdp@~h-@yt*LS_Ij~X=h zRDh}nJKh4Hlagq1v}E;tW9xW)klyuhI zF$qY|N)jmVU8Iix9YW8>;*98-$An=x&SUyA6@@s z`V(y449V$}YD>yE@%*YmoC*|>VpK5vK8cH(1~yp7gCgUQKygR_mNu$NXQoC*{!x1W zC->+&`q5N=ep_1?DKTF3Wb!&%m=l$X(}@qKkg{~PjVizVbT)hby4oNR4|NnfMsqWY zYN5l0KjI)1lUSY&OuZcm9I<5MH_P!O+krSFRi$_O?c12X{?* za99@}J-x6#;!eSatnKAX$WD*xi9Ow6?{IXLQb7uFgUzA!Xuw@vyM`h4Q^Rd-SKF$u z?ji_YxrXY16hxmRej=-bf`Iz!uC}Yg{X-uJ=dU8BUqE>`%U5~&tH&s%%@+{Mz=A-o zfJ7O3SmGzNi-V>HVsIOhFM%XRZ^kUetw}!jPy&kkMU-v}t+x@Tqe4=zVRby{UAsw9 z@1MTAf1cKhcemYTkH}rZ;(sDZT^!FgsV|LY0wSYMB9B3XTn~E$^opo=^|atzVJF2| zN};Vupgrl5y`#{+VKsH5m_ZP>^YNI&__okQUU^lbif28ow%~F;v-aR1*Y;#;G>Qs~ z=>8N+N#^RT#zTi{Y5LSQON@;zk!e%tfVuYVEK z{k9jl(kQ|hI_O9$54Yufk)V#z+o5#eQdQn#+qpYjb=tW~rM@u(iy6JQzO8=qH@`8l! zgLJEw^go#r(tpECRwkps+%Pq5R+lL zzaeH{9-~Yz=;`A<5u1oq>|Eu z!W6^FEh!nzTaU*h786>Q0TmDf1!+)bxIQU?0 zIb@YNRhuWy0XKGVwveaTbz$ag%tCSAtS!zatiXo@n~ zSG;FW!Jd14#UB@3FRtu%cXYVj9gepU!;@4+N@PeDzVya)f=FzTnTgj%8I<|OGi#%B z5u}bu#_is7`Z`!terYCv{x5RD#KE2h(_H~&=>z$Mq_7WO#uub?rN3m0ql`nHOKuFs z$-B#lC6qTk&^=(YyyEGt>5vu#O8*)a zNiWmmXFMuy1aF61O1l!PNJeQz?S#~obwV&9tgjxK zi5S7@7)ddq+~`zYI@oy-3Z+q!nUw9GZ3Yp~)xTKy;)^3A^)ITy5l@fBr25pPw|{78 z`t=Jm5QW(L+lE_1X;+T~zx~jLb1$8_F+RR<{H>Ls=q2~m^W9yeQquF^8Oa3hs;<9$z}LJS>c_pXZ0sImMY`)O033mYR;%&&`=mps34s?yaY$ zba#D!-Tu4ey~v$D-#>z=u4YmMHTKV2L5>#VPC=5M6Kfs|d#Mo8orXlrW;b!lx<1x2J}u=9GV)Sx%NHaVXO zF7q~pJ@T1=?eUCbY2mkSMspC8wPySNzDm+w>XK{IndGtAcuc}-LN%d7P?t5GPoM%B zZFciG*j-#C%`jso-jO%M8<}n4EYKYqm`&|BGi#*uW2!9m{hu&mx{6$u3M}DO1DpbN zY3Vxn)bwX8GzWf_q;4=>LF!wck(B<%8@FyzDXLCLDkzoLMUuL8f}(!wIZI3zqs#ch z2_24ntWN5S$z{Aucshe>Q3xH+i@02;=A6q=x>Z1mZf+_@rJq}Bx^9I1<^PN4MaTan zZ~Aw6;hQ#nyXR|P(_1n=6^qw5na)PH4W*yIv5}ny=-$ZWJ<`(wbswcmOjoA74)Uf; zPRBHZA|BJT9zk6W7eZak8H*TaIQU#I#`Z#YBWg#XbWVVD@)*O!>81&(JT9Fk<%P$V zGyNe0>G~DO@gg1FIxYq>X6BH#7fdjuT5HQ z#z;I5k0SSEG&2q5n$^l52d*jB%)_N2)fkS3$OWEYDVRPnDm5M8^slC)CvJ0|i0Bnj zylz_Zxo$7h3u3-BWxyObm)SgzW$uivg^f2D_?>-{ z$#WZO=2EFwRRB6~lcG?CXf#NX001BWNkl8fQ83+C zTKdwXZyAfs%V)8?5XExs1E1&R%KJ12{pgeaQ)S5dL!V9j`u$&j@(H#V?CC=msJBc` zKe6MmvApPnM(@(p4X4`_zsD{KAc<{2wz$&8fAYaUO79=qg~)2FAC}JEg>(*ASCv9c zD74DoMx-a0aI(}`M4;0|HLDLIh(5qY@uebGs+*fTh)+*)*^3H;vw|J;JPm2Fq>yj;03LU&!$|2Y^BU46dIv(R+J=d! z>w&25k=%t+&gklNCJ~@|m$!eUe*d=pyGKs!@5c<&f8pBj$owy_k)=NWOU1vKq3{lDiYDZ9%-} z!sfX0@&JYBRC|kQAX|CV%XwXQM@RXRMwqwyYVB0zz1;RyKYqQqh|+|jW_@65(@R5( z4>ufGwdzP^GqIHJY`N2wTb@q0 zd${o_nywR*`yxuGSt$a# z{4Pdm2jelQ8*2BtUchvbx{uNCTVUjT`R)yV45TBb%jzO6-H^9zFHpM4XT+Fp$>}6B zzG|`=S+LCL|LKQ6zX+RK7sTs-@x$||>3-J>I=b<_sFqaP`mH;6{Lb`?IN0%;)2~Qz z>X5o9T?d$5c)m15{XmtJC@ozuZ`5?3=S5+P9Lx#x8*#hYfJRD(xYq*d3qCbn$~xY3 zJTC;L%bOn0P1nbpJ8V|jlQTqS z#tu5{fVjk<^o}tnpurKDiem`UusG2vShk&_UO{DhCfJQ?F8UNzL+GG2u&(w-gu&b~ zVzRF)ltjkfno-&hrS;a_;SRbBmTkC{ySHbyqcd|r;pU-fb1Jhr2h)C(92rD!0AC9K zSW2&+d2B)c|M9Q{CzKu*5uWlmoKCi40-=y8u{kC~Wlijwt+`FdOQ_F0*q%AQG=4lP z2j)*8c+r`Gf{ie*Jo5w3KmUTp6VE^WL_@>LhK3q2T^4(G3n2c}Woa%gb}Satcy8|P zrrYwBqo5PnawK=#aXc>|x`A{s9XiicF|3^aJi@3ZBG#ML8&+}dZDurP#{-)Q=*MtR zq8ylx;7%A0)uXp{%L(6K)W3$af-mMa{_a~Q*zx!m)-^BP_l3(}UHEDXe6^ z8_DwmVfv&^;-;nRaY-rQ`JRG4!d|Z5LsF-KCcSyiQU&^!JmPme$tj#SWgor&E7}qL?XN%nWQgGO{z;#p zKK=Zv!}7Zr&x>JnRQAc}DuNXqNSai8mWCz{xTg{an5wk)^U&{J`CxeWz!X-U7gY^d zU0;g9UO9|`Zq#y;IBcz62r9Z&-U<+v`9~sK5@y4(!Uzf_H4#js-VwJ^b93DGxcb6Z z>d(Cbrel2}>xI5PFen6y3heDaeBsKr3m1m)enb~W$~ok6I11x7ytJnTr|o-%tD*GO zXLEPPhdT#}^{KWHU8S6woym5heF1@q_5qCCRW?#iqDd)X*5+_CnNp%6rVnVHJi$dw zr|`6Ra#w9_8A^05jEk|HsS2H02Q>58h1J|sRSJR{t2r>P(ovCjs0vD%81gB3KuzZ( z#O*0Rm7dP)tJZ7MN0Sz%)orNb^p4uUzyHJuJTU$J)BP_J|1vT>+<$j}|L{-de|dpO z7%EDc!7wnhgYnE{j4>#Y2f%>SR@xd(gbP)fnj~s6C{9nxDqneMMI&aE{Hv!X+jboT z*O^SUO+vT$<%4XYRBl9Om1hM7rl${Wec@?*x@*>~0dz8*-*K-lmz+M_cKG?ZA4SDJ z9iJk56;derD^q&LlpypbOqa(VR_R9hSm_9GJsA?O*c_5 zJJHPLN*9EysMK(}WmA9VA3$unj{el>>*fSjXJAgZJnER$7wbnY1)U&9S<~V68@D(L z)D_R@V|3GWRFF=;qRVgm9Ctc&u0+P4tILtB>6VsmEt#58tuwm1&;D{=o|vDigjA#F z+o~kpLSQ6G@K1ev)5bS&rW-N+;`v)UDKRBBY@F(lUaYcF-$US1zn}B6d9!{C z0(6>SaCpF*PG|de%qDrKoAQ)rj${pjJ9EYmpJ_f65z!fywgB%El7gN-mPUsjL2C($ zI}z(*ab)k?U?m+tvAjs#mg7ZYxYdv?S)g}NAtdF7J6WfAjtfnN? zS7wyl!D6ChMwNsb!#Ouq6{qP|g!u+#9GM)AoK{I;sXQ7JjhG0RgkV zNrO=WS6*0!X?$X99!V+7E%FdaJ)bz)u;U4E z9gF($BZJ3DS7a)ZVT>vCTh(^J^wV_uJ6Kz!brasQ@APpN4Q4~#4anxym@4uGTa5T# zuO6QcE6uz2pKwc7jq-NJQudCG?!crz(ZKx_QIpgAecGt9P%_c7% zQ1mHarK}2b`ksPHY%ef6YC1jQXE3vWGf8$7Ksq}sE7)$cEE`ow=ZUzh)jX3#La{n( zX>=3tC~{qD7Q=ZCwJ1Kfqt_05iR=%V%YaJh}bK6V$l z@FI97>G8ux0*7UvMq_u+y7472$swnuEE!XCo7>ibUjiw%!x6V3vhbC{7hkFW3APv7 zv8L}%&nG?;PM7z+&C9If8r7s-U6Ii(&363#Zt4&n8|*KAr+0ijZD0ANORFzkdfT}- zVxgg!Ttor08Tzev7{Qz!Dm<54a0k|6AAzJDHUc!=ZVDDj1CJ|h4$SXr@rmiDhESG^ zPvtkR+jVSL?Yecz)d;zCX5ta-c9KQ%tM~|r{P}^r{j6@xRjBE>yR{F;dJTjJvIWGG zxMe_nW+?Rp;Q+INMSQe`*~G+Dr$>8>_menTuR7W;?=%frcVDF%xPN4tT=n@YC+59E zbvT`%MlgMt9S+)0kWVH%vxrhJkI2V9j*nipi31HtvS$$;dZrYDj?~O&NmC*I zxHW;!&n|NjB1Bn@;yNB6L-SlDlYOx)IX1+c^N~h-M^|(Lg$&&Z7y+L2i@c zV*D?@+?St=*+uF9Mq;{d;fHgB=mytSKx&-ne}UTmoCq8~f9k1kKegqSV%K%QH*P(1 z%TT)Uyb#8?sRyNeJp>M^1L~Hdj!oT{^5Rp|NqXrVU%Orvq?@2^I6Yo0&OOn?$zX)J zE$l{l_k+4BNR{*grLz#R7ae|_)O5@<2JF`p%&3Rp_DW+k=bQO00O{snQo#82_ci^x$R`rwx$EA-^rF$Y$F7rs@DHH_=Cn`}m+RFs42mnE*%(}~nrp6NlAFyn zbXYOd6rsEHb?()EFfS)8{^9ueKaKy<^INwesPCWzmLdSle4huU|Es|CTt1L%GapgU z(0^el{QRMkBA?Gat|>n3cd9}Eh5LSW)mK~Kt1ZA5sGx(6Jk>7ZN&qIQ;Q*Cts>yQ>Xn zfEt+EJ*~|y@-U`6Hrm4zcsLL$Z~B#aS<^q%K^*P_br_usPkxK5-ZGjxeMsqZbQWNL z>FB3NKmGL6x=-u&U%QKOoQRNN;>|Vwx7S{K|KpDU^Py8$hdv>k6XH!g~4@f$38=Pm!l}mh_kCYHCT<70NRUr4O)wA+UAQQMiX;-R`NGL>qB~yVoVtLW#HL4hSe}we#c1+8!Ah zoX%4j%L~%;WaZ=(Hl;>SaU#;}x-7~n3EQM^5VgSkLX)Y$bWzEvXSqMPNMwxEbbxeG zO;-gn?^kNN%tI8omg+Sk6!VDy+$nXHU4}HvuAptWK{LXZw!Z83@j4Def+A^X!Eppe3K%ob(cX%nbd zuntbE_h`)6L(oh3c*#JKGwU zI&wQstRP+l;V;a)Wlm3=Y++vwe|uS^G$|)uKKVl{eE$l0LkyoATBz<5kLBf-H67`E z=Ra%$yKmik?gzJiu+!&NM^-nc^jivHgwen5bGs1IXvQ;8y3}-3c)TxGBT}WksFYL* z>OVzFw~9(l;EQ^Zg6Ozsj2B%5&X6@7YX2@eI!l*-Zsjpr$~jjfpv!~~k^Af}Cg(+o zFUGn4jVqs@gu&?wWrVIR;oLyF&y+6awm@A7-bn|0b+K0-V`oIf z-k6@pP}9}V2&mT$STbU|0do>FqnPn9x%v6SsAH=0bSR*xr*@HRZSqZWg#kT zd2DK0LPX4u5}sZ2LJh)o$=LE3>^{qLoPc}^Z9#YB9-pX5p@C>ZUhd%|+g@9>>UoB< z25CJN0tVC5#(UCeKAM0uk4p#N%IRFucFBY~jg#AQd|U33ZO3;UbUvMT@IW4%j-F1= z3@?l7Q3>PZGaAwcwDsyCbIW-SmRs8i_ez7T=H#}>tV4MyJxkSB#Ugs{G+LvCb*??o zo*J|Hq0RAs`lruk!0E@g<`5B6f@y|VT0-8;7i}JYq@>|%TNEY#+&@3EmEj1_C-C`5 z4GRfb^HoI4KfkfQy5_4b@K0_5eYeNCLMeTWMyHg^z(O}ipu=-&*RIJ^v&DU2dgalA z>-TQrdb#-#ln$wLVw7;T2X#bOwn{Ly(e$1ZRCGeX)t;O-NeHB&G?}qg?y1DzzNcVt zu(GndvU}E~Gm_I7&=HrNT{d7uyrz6PeN>_aJ!zX=y7enj#TfQZG3n!00$vAuV$tSNLeX{b?{hyvWapJ^X z#=C?u&UdX_x2{V#{cqp>->&?ME<~nTC?V&RlYad1umARMp>_h)KNub!s_UM;w^0*+H&Ki+46L zIeUQV5Xy07i;WbK7F)fFDcxW@Dl}4i8Iu{T5DF*sma=D}sHmfZjWJ__)Qz5Qsp-3G zt4muTbPV7GI#z`es(4BbIqSPx3!BY6s-v>9t~GRf+?n3JJsVGh>4a(>b%s5bQc~cZbUrikCil-HPqog9!MG_5|B2E8QKHMFH8^HY&hxer3CM)s|JY zwsg-JTmKx~e?0$nl~0<*CDsZV835F=o*eO2wrZTk7UdOdsy=zc4aF z1k4EejH)T+)Y8f{CwpeVHDI?jyUK;>wfVKDuF7HG z)^f@~dTlLfj4hgL^4sx5JL0ylqnpzUv?sudU>Z3rU3UAWnJi2%>%4#c@WadAEFvA} z!jB$ay6nzNkDeX43cGJ!I)109qkic1N0vU^nfvlz#<5j_;|kJElZk+-bxmP(k?h@E zRh_@9&0|X^GhNM#hy+sQf~559V0&D$gWu%-N>{TjIolG+**!tisYq+mLB?qSwWky_ zL+TVa$i5z=no{Nf+UBY|jaED*-B1$)vJ|FDPLt$xe|sZ+of;Fg6m=u2Z^q)W6!gTM z4(Iv+$Ury00~t}oA#Nk48`}$2q_h>i{Dx8(4Uro<-^r;gG0#v+`kYQQxCKW}FsIYz z$Q*!l<5pKDquefHbmK!8L|X$shs+J2Q$G4#)sR~4j2;luRWOPt-5Apa>>xYN^dDkf zKmYS@$XLJW+fO}r>*A|_|KZ>N4adLvn-Bly@BjXm_sp z>XORogVbrJE7qiCsq}G7F9_jXj1LoJ$*UdXZxRFUapzBX6Bj!KL79a{e6Gb zwBBJuJnMTW4nK=8-WIv!$D0izRyo>#v$Edu`v&$aasxiu9s8z5})Z0iICpYrykFAC;z zMtghvUUYRZ}&;^}~>4N=|&(beokj4`ddD7UjwJ7>?oc{JhS}FzI`qAt!W8qEqN1pd3g{0 zU;BU9!g~38;g$5|7?nvq$k5e0`AJMT)zCt;^$zxQq!N%V$(H4y3*ERcOd;u5zx0${yJO@ zo;Qy@|7!1V1k#1l$DT*nTw5h3ce;`OSLs9K9N1mpblmCx?c<}p1isvTb#$S-`?HCO zPev(K>=jT)meq<#8!=}Dc-LeH*=LOIqyd&o$=>KmM0(`@E4@>vigDOEGzexx6lBP!SewfWBP<}ux=}b}RGT$hLf8rtPynAUg{tldO|Szt2XuG3qyy1P4!5IKRFB$`ZGEWMKpW!9{$tnSX) z@6L|Q&UVbsj*z+8k(Fhhk234r*ax7qX5H#A%8n82=n~E-g`~hY_|03!I_)6-n<12H zx8s9n>ol@gM^e@02NK03PrgqXGYTIcD7~qP?I$5N$i+U~NwODtvjF<@y`P)}&+({_ zE{FtWJMY5!Jg!^JV%X$F8b^s^}`u8oM2Dh|!%mcprTjX6-$jqKh)wl`^&e zC|Ng|JC8C8iI4V>NfeSlWdtT;Si#y#$XhyvK~FRz^ICalcqDA|rnPIQwx=v#@tyzg zw$c6Ni)Y%rR(|cH7v`gFMHc0lnXP>yXp&qIw=-R@We%5Jtt~&J*rS@{62mj4pDz z2I+E2WTSApQq!HT7esWC(tk{IB%$+v5RqJlW=F@3j*c!hq;d+iGvs#lBlZ@l8eJ08 zl{5YOFa3Y8yu9@CTTlHpugo%h^grf* z3%Aq;uZbJ{SG>^D>WsjY<>CIJ#aaJ~dq2L*<1O%b3w(JCYzWYcj+ZUgXi1vJV*p2K z%oYi!kiJ49W7eRhQwm74p!9|AnR#5&^XQNwrz^(`|Nq7O>SK&FcrQ2{P=I^cf&jW? zc4X4P5eKc0y{Exu8LYNe4?B$AmTn{L9fdy_@-!IB7G}ioVsOJRj8~m-7mO|(q!THM zx*Mc!Fk8(gur7!uo&olncn_DF{sYbIa=(2M>N$%DT*UXXt>cZ4ZhdrXwi_ciWArzR zq`N?G@Y}mru8dYe=@8bd%ANkJpZ&N0_W!EG|L^~i^3jh!{`kNBH(C?zKT6)qmC>$% zneN%o25D1|O`ICyX8LljYo&%LBAr7aSW3Jg^C07N~p#H zL=^W(JBVUr!%_ z&Nf`=$Ou00Y^`Mm_c$~x2lbgFrz5CS!K)HxJZM@~z~%vJ19$-))zuyIB_-Y6^QH3^ z8edsiaktS7laF+EWOdJXQ(nBS`$EYDV`oSAyfLdYiqF~HVKMVj8};b9IKvgBlW-_% zI^ij3=njWnk9N!?k8cUJwNN@8Q3+S!ATLY>Bbp{n(w@lMyGimL@rZc3=`i+Fd+Hv* zw5O)Ls;jB0YibBr`X_xz=zP4C1@vAer$;&;Dfi3TDyA-cZUj26h10950=fb`3g|}# z#0CVAB)%@$Ejrp8%hUcT8Z=?`KiZTT5A$N6xBJ*lMBOl@jb2-M^dfD4!&hzzU(-f- z;en9ZBlFPvTG80Oo_y&@72I%vLhVlc#HoF-D=y9YsgcYRH zcQn;~Fv}8I^IQSBkHgN*NM=T1oHs>tX{O9$E2c7KMWM%~ z3DKbtvJJ&&P8fTVDAS-adUG0gr(-Em?01xC?(gp#*IG=Lx!=a|aB4g&l6*I&`1?g9 z5Sf@>pBNGvk+!?Oy?r}=l$MCVmil%K?VxiEEk)zfk^=o`KZIT$LJ}e_m94e!9o*a3 zx3~R#`}XtgdxAKATEs@6lbX@SNr%Hkx<_Puq>ogVx)W6GLF_iY%}v&Z9?NjG z$t`QR+mY2RndzM*QDaaSO2@3u0;w$J$hxr%yBWCvug@d0cQ^XzR8Vz50DU}zJi79Q zw-;Z16D9}BVRA`vInv4D&Fl`_Eg2neprp^<%DR6vgygh`Nz%oT}?~m6j zbv{3Os^(O-gDzATqRbY{P_NCg`OSB}KK{+uD9(q^E*uX%kdpS<0uFE!Fia|=#_1xb zQ$ZZ*K}-4o%o&>s;Pg!el^(>vcV~UpF;WVR&y>z&&CGXqr>4$Yjpo^oPCmx&`3v2% z^BYoU;q;M_*^ZIT5zF}axsOdg-vqN)N3#n6Zj4y*Z9~*?* z(8>vPXEH;bt!aQSrDmIHY7Fwg^kSeim0bWH9;93nRX!9?xohvxXm4*-*XX75qgO61 zLhHShmM&hox(KK%qk0$FFAzF|j-_&Pid{1v@zDhv)~(x6V5lte9y%$h@jG`;WfE(i zSrqRXPYY2;b*~L4%wK;LX7rv~493vD>W5Dp(N$JSYI)I&k4M<4XwP^$#oBd7U4Tw7 zy=kG-gXf9b92LL^8tp0lftkkW+?kjZxUt{CXV8{qar3k{>iG_3mc#NjFgio_L!r+{ zyWw0X5tWT2Iy%{oY*g7XLmdD?n|NL_33%C4N)0Kav~*KZr1KAkhJpg?{AiRYap5w= z_yVUt{q$+cb~!D;t|7XT(uq1(?ToOtXdJIjUAX?%Q_qN;t|A)owLgOv|JETqFB+&T zTe{SczAdH~0rl_Qr*zGqE}Sl0?qYQDrn{0}1l37kRCMm-b14rMs|$x8sqv3wGJYRM z|LIR(`O%L!MNXH2>4haMQ)2qF1gSqri(S5;S$pY(M3*Y0O~GCXQHHi zEDvJ(xtmF}+5}diQUXR4lfH+x{GQ0>XAjZB6Q?wObS0e22}ig!?T(*3NP#+4p&>WX zr9T9|m2ZZ$LXcOqXepIMlxMXPcY+>GXH7bsg0|v*55#jG6M+exNJW2NKPWdeBe69p zVtk`NHR>TD5n^|VOK6$c-rhcu*iuoL5F5L%_~7=5gT=dc#1$6Pa0zU_lM)<96yrH; zG17S`DQS281nm7zdPCn}-`<1U4`TR68~<*@XX!+!5X#OJf%_34c~-3V%FDy)ha#54 z%QA4NY?XRX(aGN-I+1sRUd}?2%(1Q?E^cW_iwoTmcr4}^p)G${-{P?bqx4`2q@OTUSjxDfm9aW9Eg7q~(x*Q}B1CAmo8wA+@Pe+TCnoe}O zl{h%;FOxG?tBDdr9XT(lZUdybm=Vlrr;eeRz!8%78mS;9#jepk-asoA?CD$%GI$ea zVlbE{v#hLSz$~JA1Nkvg$;M=)bAqCwlO)3eJ-NR-cR}#RW;#N#B-Qg8=w3NrIpOS zsj9VW>lU)&tEQq)ElM-eyKwnu|MZ5Cx+)(PXcslTk|I;Okp{UJrTR3Yr4J3+#PXts z^UO9xHz8dBiZ6j3`HrR`^$;vCS9%+>v9jP;fYXiUM*7c_A@1(Jut4gi^n}E@-x!o{ z8e#*9>OK%Pz}yEvOk)r+grcOgbAtD8h#FuUU~X4N79F-1@upKnIy4nOC8eX4@m=Mo z3Qj@pT~$-hkJdb2^Mh;wXw-DVy@zZyo993O5O;C?2x9t%l8)U6QqE2ASw;q_51tyy za-djH7&RR+Jt#?lgLG^-YW9t0u>^8~yfyU=&$QzW)S+gTYIy!K|urPJo?0m@u z{OKdz+c3Y3aBaSW`*mkoI+4=}9HDoS`g&n$QIO7adh3ZXad%cg8p0rVvg8FTQPkl~ z+LUsgoKMtr6R%3OHO2Fy^VDIl5=<`-Du>gD*b~GCh{vZsT7%2w{FUCmON&(`s`rkL zT{-{BVlVOP#Js!kTsv2!&W?vF-rzc{>CuMN$}++jGs~KGGV7r@IC>N1)ikZLleA9W zp_^xX+0@k4Gy5zhBiY-s-3-`~I_J$tbncZ^Qx^g9mEZZOv;1h&6;acH^O2n=ZwRJ; z?UpX8YwDkU1=GLv#F2x@5h>PPr}fVK$Z?+Y1#Y?3co(PS(EY=Q#bDYAJU* z8lks z-$jZ?ajFo)h$|ffx>HP7A&sJ`b5xEOWOk*hQ$za9GlxV;f6YnhDC*)+m#7!j&q(53 z#O5MHK|0nKmG2@=j^rR$6trviQFjzk9sd5&KSJd{RmUIw=zj>I|MVY!^gjg6o#P*0 zfyue%B6YdI_|c0mz4gs+9C$K3oZd#XDSA>ns`T@5P+FsO?Np(7_^OQ?MMKB!B6Xl# zMqHP2P>^1rT!v7$K=&HXVRo7u-O+3>cwUsBU7YEx98Zb_Pvm}K&&C4wutG9(B({$Ue3lPokeq($D%*C-aI71 zE+m0}h<)V{%KC>YEu26_30247O-3RB%}-nmK{9>>DiUlS7ZE5U^bnnh&c(&1W#A?$ z&InzNn4S_!ji*@BLz4=3*QcYOqe$;=NxQM*MoUX!;riVz3CBW_!x6aSLX#?xU>RgkC`x_mO}c`LEnRgSl4u!pbICPlAeW2Zym+EmQ90;7 zahy$2PnJ0sYg;l}ix0L_jI?)qUNH?y`)PK1EF$9A>cC@=I(?s3a}wi^n4S_$DJxTo z1ku!k+al22h11s;^A51TAg62gbj|ppU>$${*|ZoQn$mXW#xDzR%yGCecW-)n`u6Ym zpZoZx$6Mg>7I?e`exEI{4(9ctl1~Yj-WsFR2r?c@FE2aVdvyQK{T5QOdwOg(qFTW8 zNvm}M(JqX_&s2lSybz?6;W8f-Vob#O06K+?H17$Dj4o?*lzBuFIA{Vm8+{-LiXu(q zJI)Rc;-ksR8m>l`@0?Fg7BUA=K}wEdc~@bNTvDh$PpeYe8<|ad9WM*E^QrOdJKWb; zbN4rwFaKtAY;0R6@iQacjxonrZ}Z~SD}5q<(?1lk{ara;776`V954S$`A|^Oox$4C zZnJ~#o4U-&HF(v3b>*ny^v|S#RFl>J+yDLl{L{xXMN^~L)0>BaJS)o^hkAw6ol5%2 zMs>+LM3trwn^IEG*`LtZNXiS{O_>lZj@Ia^eQxIxJ<0~n8tgMQ! z8LIi4s#7?xtHifngPK0}CROMwA39ro^q!e_c?X3SZg^WB{#^P-v`+16n; zIy#K0-Ln@;Q;F3F0Q+d9<(;l!n%1G*|M{MN0)Hk-OH0?4CP$Y!|6)9d z=`J~a<;pE!>K0Mc$E6MF(@&58&*#V>ciLV4r)pC4%-i4k*0)4S$KN7CI;U?*EDT+R z(9tD}@mpA5NO=)=x-*m!Ru|ig^f^+LP9r1H(go5rLSG7cf!3F#bOCj)sLXWki9uZj zGk*UiF`Pr({{wZL!~Z}d*A{RAHg_K799>;N9gDg)1l51^4{v?*x#z;6X;sk)JdlK6e4PCXI)y1;J80`nA>1!sukZ zkmbljS8;bO<;5kWJ0Hm|3~iR=w4^V6FwPGO7*+f|L1xO?L)4KXk=MV+0pm*TA@phS zk<&^PJzbz&9ptV_5Hg;0H1qWI4{s*5;u6P_uG!P+|3jN3)brMikh3JAC!w6LriCfY z9~bBwEKD1N^o{b3tRAyEFe5E6v;yx5G3Bj^Epfi%YsMp>^wWWNa$-Vb6Do=cT}i_^ zl98BqSdtQV?Ve~)U!M>g(z2VEq7v0vQ(P!*m|%3tZQ(_wA0L$dpugTb`0IA@#WU(_ zGbFS{I;^5-D>Ucf9GpYeg$ccwmZTG{WXGR7YdxNk{@vl~^o$DP-*>ef+`e}ZOy7Gj zZ#rQ|Tz?#>4yQ+i9s|-jo*}kfGrh!wVonFt8OPd!3wN(?X(5MQ1of7dR%K6Do)_VC zv~)mSPR>>&#rXQ;dYMB^XY^mY_EGvn@ZV-gl?krEq_0? zjFZGnqp6$lq&p_XS&fGwvQaR-%;bnHGE$N{c)Z70-C#8h6ZP0(=`fC%XN1$|IRfZv z(5+OmWH{o3R{`rZOgH*S3m^noeRN;#-l4ytMpGKZ)8?nwRx{N6NgqyR@K~JZVm+5M z^k2Pu*?D&P%4H18{4Cx@S8bHa!d?<*W`~1nhPtCvcKVgOJ11xV>9aTf=?%ej;u!xQ z+%Nw`h&tIRy{y`XTuW34TDrqJX9n#Gn(xI zr{Z~kZZJHdIARTwKzXqu_#nQEl1|geRD%vzi_yM76)qK$7&_QjfhiroI!dX#(PUo` z`?~1q0omDfA$^`!K3$b$GIFe(!oKnR-~7$7YyCT3-ehWoe-wYsxw)-Q_YyxFLWC_QPR7aH*vRZc+@F5wOW0MuYnvX zR#o3EL3SCGDPu?{HZaUXC_RiX7Cm_+`5QS{?joYTk9%}v^gyIk*<$+l$u|Y%>kI)D zK)q4XR55E(dvGsVC z1H2vyGdjw5PTghkiYUFKyl-D}m?-iQjTn)>GyaBJn)-Z|pk zRp8-HhI_f*aU^WBhwVJVU;Qn!y^-AetDsZuU?*OsC{NFL5F1*T9z`_tyLYF4Bg!X%;vP**bGfc0lT}kKRQSPdslnix)p1c>fo|vsPN~eaEe3}yI z-rMB-1F=Md+69r*Ron=8O5V$pPf|n5!I^C+dOD?}q@F(mqD$>4(z+nJ6V}C=4y`}^ zmfR#ly9!%Z?sNs{0_l{Ix)>e)Mo33d7f44l$KoOo&JY#-?+JSO-piVxE>3l^!2CVY z>7=xX5gplF;GCgRx`^jL1;({SP&$G-N;_u==g9Lfy~zE3;X-xp_oE*_^$lVd#dWU2 z&m|#|{RiRFOw>u~>P#bW?zNHJbWzi#K@nm)$uBHK9ao?p?vllk)5FE{!cu2rOPY;IbC92M0Ix#wb9x5vP(nNk1l;M&JRj_NJSV}L~X(p4^e$e&Ut8SZN{N<5rM&5 zQeu*lLSy`tLnI<(H@$@FX*xtSOX9)$kciNXgX!sm2jT7r|M87z>7fKMuJ&7fETIAc zdKV`=paB<4`}RDH-Un$_gw0(9aQY;PO3#zU9U{q4)v5}VA17Mz*YyW~E$J(`U~rb> zOILFTm650@U7YF=J3bs<(UjTz|xlxMMkI&R})%J>&1|kDWfn_gGwPKL>74h)Y>>3=y5y z!Nml(6k|{a)0LnuY!0Ohr^}G&mx>+zXWDiY-s}IM?M&O;?TfePuIE1bU+&{u9&dri zTj22)_`SBko&ay@{jR9V2XOEqgCidyotSA8O1g~69>}`S>S(^&hpygB{$M8m_jSfd zqscm{`WYdp<9P+rO-&2*pu~U-rb}_8U?`{_iA{m@4j;Mb9!cRL;9s3(=*IejrcN$M zwTP}WsOSRb*a+t5FF@&XjhGU1r(1FuncjM%-b92owrL-|XV0a*HrgBEUO_a+*MNHd z$tU7C=S%`%IKb(EvYZGp3pUH0&iDG*ESbqROMcMaYHN4*Y@elh(LCRLS#bXD=us4@nRsa_%Co!Ze(yS=81c?co#l276zK6HZ8ee`ldS4?ozAeDbQA{tT5@y2*~vWtU> zlTkOo490Ch=Wen$!ea|mlgg$MIsJJoE<_AgRZeAMx}ZW5K$kJfPtEf`IF+6KCPeRM zv}QH;jlG)v=C*Gif9BceLT;5@0Mv(*4g`mMhAGLZrYl)mk+HW&c}-Bh2TFQD>ZU!Q zdg&%lAD^gsGgYiJMA0lrV!R>M-DEVIp=|aKc-OgGt-Q_Dl2kr7GnmdNxUG9zcjpL3 zAG6u$22?9MI(j(K{D3fs4Wzq+=|=JfF_Z|WOO~MgP*2Kx=W8jFxsOLQLE?mqlQ{{a zvkiPmoj0&XzP7BjT*6+0%7w2bSBTc8^fIa>g0ZW&`D$}7_WeE({nDjgX;iv+b+LKK zxhqBF^yh`uh0@oqEs2h%!&c^iJLWB>DwF{;_o65l<2N%1p>&9uZG9fqe8m>ABlsrN zR(H;K8ufNUc`+)!GPCy@m`*rj$LPg2?oH@Rl&8nk;u*csNGpauf3 zyTg{%H|YG6u|$JhSTemJr=zBekz-uk>8fy4ok+fmNa9eq49%CWM0DYGO-+C6X{Dy) zPFG2dkowb7I4af`alXLlZxg`?k^c}#7w3!AiYl**06KCx6{6fKUKeF|;dbe3RHBBAp2D?G>jl{Kxzg%KpL{sOm<-is#2%QHl4YlpItRlJ5 z?~W+yvA+HI!CKmYCS}x8723W#HX=5oSaMZrTLZ`a z11mz}?&SF0iJ>I4rT%#PL6t^c-`-cfcdx`SPE731sNI^DCT%`Z>?>MBXiiG;sADCt zqW}OP07*naR7^57%Zkh@YKs$#Ss`ysV$EqT#9%3A;;PCE@mg3@;!eWVx*?V>G-t&hGk;~(lWF+i}=#SlT z?AWoK6yF>qbxbe*DgGqAFjWE6QPfv2_fOlEf!AesajmpXl1tK~RPbC1Suq63U_*1d zYhVAFGn9~ikdt%f-o^K)=jPu3z5WS5zVqWP@OTS6-U5%@0-~lvz2ZnvgS2XoGN1S| ztmb9pV(%9sv-C{bdireHHZZ+edizXDGjcmT=`hpB$ep(G&{1UBeu_uSXa>Vh|0aZD zZ*R;lK6qk*1#lfOYb3R?Ou0hb%d#vcL)Ngh8-sfGES*WsGw71@$?WSl&SI#TFNvDJ zAei1Ue9LM~c8ik0z5qMV(C9rtiiN(pq3>#q=+&PHmy1cA>_c?`(v@g_SHp9;aTKHY z)#q!j_6{|-TXcrmEMrlRrQ4DYOwP?P#KV6?s14PlPDr1bnK|0j zI6Btbw@AyF|X!(3ay|46{ zw6LdyB=h*nO5|?$0bD&Kh?h`pz&xNNnb}rqGJbk8*mP&mPO3bX9`$`Q@~Kh| z%6ku!cK2ZvAJ7X4ftSv;aHVXjASN(|$msa8M#Ny|EqJu_dbT5NbG6AO-Fx`9#S;Oq zn&2|W^eM~t@Gkd=FR!r;)igHuoj<>L^^>c;eSP#mB3>PK?|p#Oh1Lbs3!@(Nb2*E(-abG!)>q*&~=aJnexPk)1S7p15Rsje%sw?lyx5V)RfxoOcTsdCEnT~ia zjIJCloPz1->1we+I^Gx!$G#d;2HyMS9{bPdYoCXvvW4yfj+=`a3+q{q;{ zRH^OqSb+VNAHDn(vFWSEd82^3yxVXMp@q`rz)>N(a5QRqxR5r5pkVr{jl?5zL5b#K zHxC!KU*dEjZ<>%wbE9W5z4*#OLemA(nGbMhZeODnk7|$7)O0rgSH*N!AR}73W@W+d zayHKQPRNJif)PEPBy=r`Q4wt`K9YLsDc`B3QWQ3hr3w@OIhWGnZj!2q&pak3#_tYZ z^K%d?ZHdHnep5&~BQDO59Fv;~NfFv@aTWFL^~GtFUq&QUB-UdF*|n=MAuR*fJER_W z2h(}z9V$!Xq%YD$1LhT?9I4(Mtj2I6V{ouOvEuA*DFKCe30af~7RX!7<+~+2QFy&J z5lk1CIhsG-oP(DR)*r@pf@FOtf#yk}IsW509LCqk7!MyGr*5@vJgy}-*7w-K`q(qU zYc{sptb{W*v{xr)Am^`d$*bRfUgY$>d+Ybb-VpnFNMYQL9kFr8LZNH_GiOqKeFf8l zb71%W(0=^#u?Z0=8;>P~gkVocQKyO&dpaI`$$McSrfY+9q4tWx{+u(XKj_bCYdiD) z^tF&{x$iylKknlj9&driTj22)`2DuP9uN8$@sHkJ7fD8-E;0;!l6)4lOPVB#Y>F>^ z!O}Nq*EuZBJv~FFosBjE0wHvxVSxC)0YfDHVccoE2{DK(8%e&YoOOtCf%Il+u;?zB zjypC8iCqnY!O>`R@39crcPq=Gs^g~;(9yZStyG_9*oL8Mr!5m2!G|3d3 zL(@^@bfei@-_zIJ*DU51jm^=*FaPS@Pktp(E|`Ah@?ux--mA!|y}doXRcnX#Hdoa& zH;*+}cTx)Z-Hy)BNSXZZ0w!xqdVRZNKIrys3QUpHU$vm7e|GEEta7On$@p>U$8|HN z{QS`xY%f>g^wIdLO!o!UbjnDFNKmoaEY@zL%y&`>PGrV@b zX^|L-R7WkIi8xT%J5dlFPdFyE1kJXw#l4HqkJ?7Zu1a)1lNL&g$B0wc%rAoJRcj04 z7DUYm*g%hpZnYAA}aO~0Rs>pIv(M_ zZ{HaaPbG}~LYPw1^_{#Rnc~P1PB$?_G+B-}*b6+_j50-Lvx4$;Dm6sH>FjLc8lmYv zM5ucj;^B0Gb=ul`m*HdDL#ZssI;K88?m;$7PgZla)%iC=Ufu)4Md`@t<13Xr9pB4y z-(X;Okw!(DkPeoM4;=*8_*{5h&|I)x>PL~%>2IVQ>P|xE>{}wmi;S+U=onroA$|LG z2wZ{}MMrnG85J#^sC0pI8jx}VVgLQh|5@2wlt2!LOJ0j6sLPqaw>ksQ6~rr8mrFqU zKmO=NE{O5v$4XEazJKMX{|N*88$WvaX~A>er_+Xl>qQZ?B6LZ-5%i`OR8czqmIJ{= zF{TKeqpSx5>RYxTs%y5F2O(W3eU;PmB2h0An+~Qwsibsy$~ECwW7fFzbRNovm+ymc zx{Tje(*?YR%Eg=BO6obxi`p#LLk=l4C;PmW?wf~5FLb7%0OwLd3WJ75oQu0jgCZ>Q ze*O$!|J8(-`}y68i;K9EwDllv^LE(#&KRZ zcQ~)Ob{F-l5?}rf@;F*L>!-02ke^N^C=&!wyI~l!Inuk#7wRWk6LH&Q>?S-$*q+y{ z=v<;yaDWS%AG~zw5=}hYv81=|&X}Ig&CQ*=9&tSaGH0wAU%m!H_vdGPIagPVZ{*;g zlarG%eQb4N;*J>Kw%`o*(Wcj?H&oYV6jngl#fP__Kfm`X$HRrO3H$bi?g-hnPwXwn z;u3b`oIytS7d4%v_tg>T>7k+6UXo({*Z3t7&6t*!urGsL#ui>QDt~K>lhPHaYsg-) zE9Cl_oNG7w`|-T=-^ zl3F!f8I5I?MKiR4U$FLAOqRZCeVDzGz!%E`rj-Q}(mQon#tk^B2f%guI7ZHBzU=&_ zOfVgHF~TQeF@hiYgh@1eq>cQEpL94N2aPTt~|AMFRyIJVn zQJti;n>&ZohdbTCbQlEKpm%#Di7>_iT~ANY)xAJDK9|c*bBhwyah~6m#Oy1*mHYSZ zT`*1>tv%M{J=VeIfb8aG+wgF9=eApd>BF<1HFVE+E@bgvsW~$LwismIefKwaZS-2b z_1Qnoa**OtW(or{JF!zV)=-7GC^6h!@f6sa7A7s$p&B~35234@jAWXpBJc{iV`LXd zr({)h{Lvu?J`tlaC}@aaMR(#9J>BFD(Pff^9pVU$fU2it>CuanP{u}waUjawY_$r& ziokA|pD~)576g@xyzA|5>bBz6*CFj@J8Ei%hQ^}laFl;?s+<__Cf^XG)$jD7pat@rL6xbxwy3l~Oe4}_ojf&u|-NCYy1=SofIjFcDE*(iBa z=~{g0{6xcn2<=3wq-V5dU7w<*6o z$mD?uM5lA})R9ZbP9R>be9NdM_0UP*Ta#KPG|QJv**&5?@F;avb(N2S=Djsl+FYwo zjjM}elJ=v9xYOgYwbOeP!xl049v(Fa((DqdvCD1`Ld&s~=yV>Hm4eqIe=|e`-|~(6 zBSxKxHb%01%hz6sYC2k}sp(t(>LX=XCz=s8JwE};C4D#H27RZpI+ z_Fe?>xnY%mV14hMg&C-e^)$-w5F1et-J5x@JFb^Tb6<5pX{w%tMcI$# zW6E{}>Dfq3bD|9aNa@(vgY53=cgEmZB;O)I_UK9|eJzllT;LXoJ*&~~>6zWvkmc$l z_+?7x)d?)h(ByPnA$0u_NY@7t`MNnQ0Xaz>_u=bCpNP{#=43~SMpbc#l`A#|=CotK2zVe^lE zgwy547dg`)odp0ptj=N);{THq>R);J8K4Kp!DRZeaMeZ*2=RcqK)rKt8RZ>9CpR5PmmZ{|rBgjB6M=9*UraAfPFLDJ+gu>s zITuu4Hg%%?Az!D7={R2`PmuW{X8x0!&aJ;-Z>W- z9PS@@F7ysnq4-;fI*AEPLeWk@CFkbQ;?H^p8!*$f2Hpt{4}{W#sjv**7`!^RqN1fD zHUTF{aeez>&))OrF_Roj3~A+=QNfuY+>z2%Iv`PKkv=@!K%*gPKU6@tosr5%Ii!;^4vhgS00texIC_+>GhMxYOe~Ij3_@pYFe&(4UYq z-nOP~dfymzQ`T^g+%{;TIS!Oj6wUf8D^(LDLsV){PmQI0Z*MbfuKCax zuUvi=K3=4#viIuMp{vb}rk+8o$*k+B?l44U4G-FE!=GpMHH>w9p7qhKj)vh5>vuoP zvf3>)iy5?(e{vhg%)3AN$!~_F(<+{qk3XJ0IyFis&k@OfkEE$8UFL<;drx+iR~m|p zsG8K0+HAyc=y28JAEymX6RF$x#dJFBygFLr2%?iD3a802=`j1CEyL*;o!#hX(@AU5 zR0E;#Zc#o)()RF>;CEr^g4_b71EfZMC-E+lYEsiUgwaFqu$m>d9)UM|EU0E|sK%oz zzDs;4Q_qi$z6zv|)%<{z7X}J&RG6+aE6X8{m(S7Dk92JT$)znEEjNE1AlYhHyKCJ5szIL$e>EoR>O;Vu>ri<%EN1!`j06u!& zsO!B(7De`0>-4&Ub(_L4{t&N3w_1lITf}qaZ=odA!Pdc^?yd0LAa0oG)Vfr5j}SY# zZtaGG0;F{L7<}Br9D~Ez4`8}_V@@nwqV$!5n*b%fIiJ*|baAmriVHYSnI1x}+ z<)bWn>YH-QTX4F{VU##VQQn^tn+z(t=4%nzT%>Z$=%S_5A_473B3%T{mq^`3>}s)ax+b}Qgx3Wwe~~yw86T+wn68{J!s`6| z<10UW`pNN?YsB~>_)N{LlhQ$SFNNpA-UoncN=3z7e&B%cx}>P1rjy+w7imulcnfVIGF%+nuTH=akjn3#2tH+rl16z-|>4k_zoqcHxH$SJ{x`@;%2Dt#shwV=cK7; z>%_sq!JfgbalZaJp>ck36N7^jU*I;slQX_LHYCB%AC8YeVh&9xZXeuU+mcw!1Nz#} zZ$G?!``*11QrQWo<2gSRSfTn4;e3a_IdUQwm;)q=!JG`p^k0MSQYlJ{quO*yb^+sS z6L%#f+&Fh87-2iGaC-XM-1WJNxzl)A0CiBk|9WiycnUiDnl;Opk3;7`ck!85FxJ&m@%;VOqPKp~POL1Ufo>Pq1sRpbO zIGf8w>I@J|#}J0?#%#<3HTc<)K=q_QBj5T&5@KRV9WcZF=ISh?X|RFk=Fh9eXdcWm zTN|Xfv@@&0l2vUbZ#^}YS2GZgwIVaKsEFi~Qj5)_rq5P0h6`m8PT$)++I#-_s#h0# z$F6Qa-#p~e*WS};A8tQ>E4$;Ct)rv*yVOxN*leGFG)C{Ej|dj19+@9L-q1H>X}0_H z^i=g;`2=q|?sUQQNt&(B&P+~r<=51_sV9~XM9Z%s)o)buy>w;97p3AwxApdp4LN8$ zgfE3AOr9RmQ^br&`RGq@%1i9yD4>rl3z3?D#{~$xk&;R1*)2IW)o6sp=_(4OWB(8# z9Zl5T$3bDM_X7)A1FqDf~YMyI_~x7kgvtI1~VHfcpFX7Q@3E-}3P zK#sIO%Ep+!Svo^?XWi<^MoNDbPX9s2=kFaFfAUcJM<4Rde}eUe(Y!eN>XeFQly`x9h*qVPp9-cEqQaM$y+IVoGQX4=MZq3yR9Ab_ zTLTr93tX>i-KHZ;@s}*{TKUu)7c%!}I=$(CHApfeOIJO$EgDS!87z)y{`PEF)BMqs zSCoSO*DuYNc&@#2Ln-U;Y%_WsUA)o8O1GTdcEL@jN=U_dkFiB2I!sASlg7G%)Y4?4 z6iW&W*>owOPl2kd#gv2toi3yXrpHX@OcJclq)>_J(G&yMk!G`Q1C;KG|A>xJjaZPv zvYQ=Y0P8>$zjp2OT6P}?AGoB{bb)lBQfqOfRCMvV(0~*zUC!l-aQa(sJ^jtMxFSkA z%DU!skx)kEk9itKhrk8Ig~iqJhe+v?!}zwOw`fB_I!q3&OW~-{IZhYxyZq;umHw@~ zEiOyCK)UmXGl6z>rk%^Fpt^IYzDI)UE@J<_2<(9^86aG&=NhErhCxlonl1xSr!kTwv$H+9 zi^k{jTxugDrt|UNXY>a?2`)N6DDjzR2z1jt6w}L1x{(T-hukEAToP2sPz(({N33~L zYy`r&pMQ*Ba6|@4FCif@;lV)n>hN%y`GkZN=B{6#w|(zbItqpOZuAQ!Aw4jyH3WNm z#+_$T;eTWyr59x`m zl4q_g^Lg|t!pPE)esJ#~%`DpM>kl8kT|Aw8Z94b5|LL6ZHEn|6t8@Hw*7Tn^aqZfP z>(}O3iV6Mn_0uTo*SU24^m53Y_P^ufr-5{_zo4%xZJo2zA;pK=ixZ9ox3&5AWexT< zSEr{pr0=GZwk1*CVBST-X4>--Vt4P7AeWGqkOXQ-`}ZNL!|5pL%Kbw%X^vQ4`gfqJ z2ZnEqz{j2tQjuGckd`Y+FAQmEB-Zo{w#Yse_!1JE6SL#=-0k=8-Mjw5Tz_G1F5dMF z=Lhxp?C} zD3A9sMIw{Wn>yzWJq;Ffb&oa6Zmh2Ec3Wt$%r6Xf6R%#^tO@K3DJM(^ zN=@F;RW$(xo~MA*(INEh0i!v2U5QR_aM-Nwb;)*nCxO;HWXJ*h8i8yKSA)2vng`J5o9tB6d`jqI=ad5 z(@34xs`IpQ8sLYT(FHTmO0giJ;q0+cb)yEOG_=9?VO?+^z=o9H)znD8_W?H+gN$^o zlvqYb%_+~WF8G<|Jz{u)(($`wXP?3rqu+Z$1bQH`zfjABKm>M5`X)pO`^YBQrUJKHH&}LSwj|b0$EZ zp6>P<4Vqby6}Nxql?|0emAy1ILQVgx zj~10TeZ^D1n5l{d$1G zC9_DgycBIJrF3-dy0yuhH|qlI^m{c?Chp^*w`GOtZ#n;pd>IL~YZ^2v>j#|v+;ft{ zC}6H3x;jNUSF}#Ni_rNuX?esYDoDklj-W2*Qb9^I40^dHp)0{$3F$u;NPi1Tcal2` zwH8Mx>0)(JkS?%}kgnoc1k&-l2%0lACYLkqqENaza3VuH)kJkg>70n94ydcEIB0-$ zWn6#dA78?sKE7(@n(#GrI+CFrD4Ov_akP+hxE$mNoFl7aN5}pm4j56?$AN7?JzQz! zN>WE2=TT6)lhet05gA?_L|Tvxw`+bE;dGwR#pu7~c)5@1T~Dlt9edUiLUk|2r+~t7hhijP5d@)^bfp=L1o{ri-_V7>_h^H zPG{4!b1^rm@ofF@Z0H>*Jt9I{gocKO)Do50&_Hic6!3<@&-y;wJJ`^`Px=HlbD|T^ zR*;*>1C@*pp|_HxC}tMi=II2z$Z?QV#=N}Z^}F^Z>?)A6M;IInC)uX}YRBKrGDR>!)&u`LFZItKNS1oZTbX^bx!PEN;3L?)$HNg7Lrd``~#OP6k+ z;DrmOOS=0X`hWTH;~#H<$6Mg>7SOf;YPyQw7;s-eP46~Fb=>N_FyC$IHq1|ESsZTe zR!fI4yY5kePK z4-(l|qV0%iX9P8QyMyU?&5_BC3yuYg$<2~Q=A(JA&*5$z>`t{dSgfCA8M7J|tb;uR zb%vtUBH{G-ojVcJ=~ik?H55cwtzDN~uuf&^)$K_gnMu76RdOM9#&fMSCZU z2zeP8Xd(vCWW=mYUn7=Yh0}-1Lvm7*w!LlzT=eN7KfV96(rI=TWx5Z2!)t zqbC)mL+XoH&-XQ3y5gm?5Q_G)U4zW|F(s$>Eq+3TQLimX z_6k%Iq|T=tUxn+1XO!ugyEnDFDw4MU1hJ9^zyA+cj0xXnqFCS1^(vB54V-)8z-B7rquMWy)l0wy8LdxTzT@HZQJZk zCx0nw`l{E!bOYve>TH#oE|l&8rF)buEEJi7+zMzQx-QwnV*xQ;Hib8FiE8&uL?$Kr%@5f zCpY$8ocJPSA7!YmwOcbJhWw_2ZJHjXg~kz09(reWXhLdJA)ERl@I;&#yB zD41jL>SKX9{=PX8apF*qi}h{uXK#cW2?Dz_(?iC8AWAmwX{zm=#I_wh`LIch7E{{}@Ba?8jW|rg8lI2yG_kN6ajr<Ig5+(Jcv0w{msi6@S1+xEoB22oA{`X~T30A+*csTVkR z)43&+A(<&rj6ZqzUBYI>@j|!_MW4u;X4+V$MxP3D)MPtsW-3R`CfxmCI%CE}?0V#Y z$zd|;DXYykhN&CoRS2UQ2qT&i*8^SQ^Mf4TqB$FglQ+7hChJI?&%zcGR)AC-RO6@# z@Cd-kP89*Z5PCvk53x7uOzZ?6mJ(7meqj5&Ipfawb9Dc{`D?qI-Qg3Dw+G+3K)P~3 zD{lq;uBbqS|H@>)2oP9PBVUt~)Q`$IDVCS3iz@Pkt2_6XVOE{HTV@Icafx1SjMQK&!DL*RiMabNF%|l0~ASCZuK$swV zWsvSY>Gs1Nlx&XqTCyx*QN(^jfIE!dh}lIAJn*o6IW-Y{5y{e_e3Dptrdp`x>~(O$ z`qY?ot?g5?`X|`ciQDAHDl9OB&^L|dcd@U4Eh8bLl-cqXwo?sk8mNnw*cbNk6kXl1 zTqN-yKJmgxIf0BI?RRE3l+W z$)M58DO~gV>sKyBHBBw<;G);6m$Ju9<)f0h?zQr@Z6mZSDvIxlkD@YwPli$trKjWf z(Hqyl|Yx^B;g4apSW5(i2( zioJW%knR%A zIVY$^SlxM$GX?4@HC+JQX=#y1ek3wFc>dx`>O`)*EJhj*3@qy}z4Z-9nUdM?Ez7qs zKM`zJ>3#Yje{&E_Ta>KYBR-v==!*!u_nEg3%yNK&WiRo%v zYQ}Vp<2BFA5~VB8%U3@Q`HDC{s5IIT(Tm8>FHqVWf$5UhTaiDpN>6@z?-`! z>f0M?(a6uGrBebl*xDL$j_k#oht5Iies@sM&m|=kt}mY0zPFtk&)VAh?>5x8Rv^uz zjAL{sQ{6B0P()}_tfVfAjIP||2kRA_7X#=D(M3micR${i96|IG*G?49v6O3bU^=ds zYo|p`$C!?!KE7u83Yc9k$!H_?MS$JEu$T(clr{a;wuT1Fa4pjgF{l)V!)uN77_&i?@>)pJ|5%crT>EvDLL57tKtt@ z!{Y}(-U9yzZh>`cDLytB`@HEF9-Tbe zxIc3ztrtxLQTTI9OEy610_mCY(fVxb=a^i;b8)$hYMxEuMtXT9F-oCLqkqZ zKiTC`B$Td!dMaKF$yAxoS0OLrc)0@6Q;A6j8UV}W5SPlSfEw&C=;I*O0+KnIHL1Y3 zk7?3jLL_yV?dI(4&Q2ZKjstjM7R(DK9vPHRNDlRrtctow>DC!Wj67j4o9AsESq-;3 z0WWMX`2TCzTLG(fVtxnEH%nr9C$h4=daz-TOhN{l`qg@;$ zPTA2NQ)fs7g3!W0@4k|^HVOE4y9|DK58L;{Ab!_`kylK0%R#U@YcC!2kE0d z3&`eXY*@F!4FifEOy@mQ|4NTm&PdXidQ2?n2I@z#wW!)rF7w`$m@afK-WR2+^X+ga zseh<3pPZKflyn*Fmr+g+tm))6O4K^=j;BiJ&NmPc#ZvFdT(Jh!W@iSIF+kmofJQ*v z*?Lq{)rqvUNj2#rxc&(hu~HxF)Z5EPX=mD0&McPX7sBBwy6`b~n~ag(o&^D6y41R& zfvNKnbiV4tU;JIv&dVRbQClb>-LR+98SwI7Y@`2GG53FY!=tLGlA=*C{Xe|CZKS+Q zKc&=kudlsv!LzApQ6B5{Wcm?@sZ1hcVB^4teeR5eu+vluv@O@~^8p-!cr zmn5@?#+@Ex7>oF|Adrz+RZt^oj8tp8dovj%(KC5ZDbpq_NTsE21__?`(R&zum;h4B zt9Ng-Wi>nhvV9c{o!3Q9hajnqr0`LCk&^X79^+fDy#`|cSfh34nYyC-9&zb4?jz0@ z?Es}e^Q~uI$BX_lh%TLsL?*}a!o?r5RGN@VAt{+Jnk}6gQUP>fbR6W0wOvX&U5P|6 z=b#2>|A`CEC0a*Pm!R%KaL$QYS2X^km*|T`>(ZBg^nGak`!prhC|%U_AHDMyhH^#Mj z;JyqzGO}u(%{3p8tt}xt>hP71#Q8ymh6dj8yR({>re|vtZ^n^;?jIZ&8tWIn5jA}^ zdicJZyXwh7Y{jpVmJ}G;(l9)Dyfra|u0Wwlp_H%^orrHHq?OQ?y`NqEjEc*x*jgF} zs~c*?*^ZZHD-Dt;KP9>a^Es_R$$wP6hG<13q2`L(6_g{f3&2Zg`vio(w*l!~8`}@& z?b;_boae7zJ&%@7gv+&S_pV)=zE^k+13E)g^Xt&~cpFyqH8K4;r`!4w+OJ(JJi%gg zbkuZhfaw&B0_Q^KBCN}4n~3l-mZPZW#O^yos`~QP4OtDOw%500OiNHp1(;r+xBhVZ z`Swe@Vs{kR=B5#y9!e5}*ksu!k_?-G&_>&Lvve|20)>ohi=i*pyjbm@7N@$b%?Zr{B|zN(#n5F=Hyh82I% z8veKsuHWcq`6H}RSDW(4@53MIDek|@e{qGs>($&}&Erej7GP`rB}^RG0wDMmcJ5p# zn_r-{yOHjZ*tusrI%h3(oP^3}Z=s|kvCnoZFcBESb^=@1*!t5pUBilNO z^LAo-4TxUT)i~5to~lFp;pEddXt^l{7vD z_(Y+mewO%iGDEln$s>AuHfl0fZE8vfbUbiCLS4*_BQN(mo>A5VU@@P|8JSi~1JO#vfPkd@T6sLpg8%n5xC37-Tj|(1A-lvQ@QYI?I zu;39=tPYD~L3aW=rJx)jcHHWCU{Kb%pS&6q^St<~Xtpw>F2h5b=YsPD4U+c{@B``s z_vFPe0C#Cn#MFhf$)KP{QSi~zyJ{pYeQ8L(3(Z@{7MroDf6@%6L+S*oqq&Pwy?lz? z9vNNnY@d9#3(@$dfoNWEnBF*0SCly=8v4o~zVO0@{GZ+6pNtdJot2{>c8+OHkDhvC zp(?uas#4Rx@y^JIcf7|GC8XduYI^ci)0KX?{NziW+4eG0Vw{+st)BR5`USd4 z;PENXXDY(|(CaKUOw`x$Qd@rN(} zkV`Hd9m~rzU;ozEzeN_~_h57gU0g2;(O-XEQTl5lt4k=ON>f)x7gmPX6qQ+8sp_>R&9Aw^mNp8 z5yCY(=lvtHtBs)g5^*UU1{ZTWi#19o$`MmLwsyHiZkAJS<-WlR(y1O5V~orLqevHjF_hV_U9l=oF7!&p@=)aetsZ1!uQRHq$J;stCQmV!oyQG`r)1 z<@)t&*Qp_0Avm5hzMP~NP#r+W{=yRVP?gbmx_?JXN=n=E9D?JIAMdFLmP4)~dXv(! zJ#T#;{`kq&>tAPFSliSAC!(GU8(65k>;$9iNL|K`WStV654193u2zEHTj2EEklci{!q8wMethpFQ8JpFFqeC=KX*N@dkJi;U{?I^Y7Exb z^H_TKHR!S8?Vp?``;Ie0n2fAETX(pXK%BUbard5Q;C{x7ZYcfOhj*7NwH zY=NGH-|^Y~IXBU!NV<&@pE6K3W1NA%Y447CWgCw3Sv)VstStN^#*vQh8I|<%8Pq<5 z$E6c<4371A^K3_V*0v}!iuy=L$C3H43;H(&)B}8KhQO+P;2gZw5L@N~cq1}*9z~ii z!!j^XG_!MHV4%omv03@CSvj{_rE!v(LdylKrCa1|G;LNPZI&?4?98mJENgU^eg3Jb z(nzNyI-jWP%FN2T0F>x&3zt8E13~n2rJak#MHW5r#v9HB-&WU;ybv|Qo&u1T=yxhO zy{DcZ9Ys!O+#PEkc9ns|KjsYP)5Oe)EV zq67zs=S6bd?=GHXPXcCY@DkuPA*Q>91#kz!D9NN0zlIUQcQc~Tawms7eM!yaoKs3k z;ipg(vk`|$EE@#pFijvk8)6mXHoCFV-eK!ZwKWV|&D}b^Ih#!`GXU%i5+fr=K)zG2 zH%k6^R^M=6R<@?5i=s{p%#ryL$u?iMEIGi@SQFqaGYSpTfjGo&NY5LeGhA3Eyw1oU z+F2L>1qS&12C#fU8%Cbc!KJr?1&Iw?&DrwPQD_36J|0Zy7SqItgI*< z)R!ePSyH6VVo#FK5!2aM;KN4uagRxjN#li7VFmfo$dbiU zH61bi4$Y0=>bIcu*PwJKtSd*$_uhW%ZI=J=b#bICCycmWRMZQg4uxxxE~<3&_19tZ z9}1!ivdiIZxr4+psv*vChL}=BEPqAnJzc7~6Uo(81?g%5cT)G@RID#fz!yV{I9%jJ z1{YD%MO4TBf(b|DdR*(`Tz~PyZ^F+mbQU^asgb%m6&YONwQLJWoCHR6bcR@^*Qi=h zuCgdxWOD8#x8Zs5efHTHLG|Z|c@g)J)A7O+IiE}0z+}p3gU>-o9naC1hVx$o{Wt@0 zyu^i6P_jw?AwS=k&{)!2h&PXjjSY?65!;fuk3O3bp@f>$7N^C9ra|0^pK%$}c{+WOR4FKRq%y#Bye;B2*E}y`c_CqOx7* zinBz#;B>D@Bwz9H#Khsl91n7!0TNCZYE)%XfByWXi-p(jp{Ad}>>`{#{i$36!P{ux zDUx_UeLQnclgEfB2G9CwE$3wpe>y;}iRf~^LNz&J(RdpXF=9>U(QPSbs6}mCz9uK6 zqPQWwx)%3%0)@46B(>BRugCbZ{qU|G`w|m#vB9(?9E;dTy7|6i{Sh$~j*6O2*o&`k zP7Djc^oYB|~chq?@Sk9^h*zwhgM*nE&S+yp>&k-%t|>6ima?lEgFbKQ7_803{4WqE}(9)S^#yc!)nPI zZ0O;ISr;sm4u$BJ$&;3oJi0Qo%*2CI341Ap)7N@32OwIbF4<^?(IIk1=1C$&%dCXkHR@JPqR}(YIM=`2DU!#exx{=ySl1`)CX7zk~*aBF+_?xTKe5ZRQE7u6F#@^hl zQ97WWs(0i|_fZ%dLKit*P5?ZQJ#__S(}<8OBS^Iyby7NF`uW9^AUdO{a=+{`iKIuV z2Y3%D`r!EYEZBr2X`R$LmU!CDCP`z&h=J`z;`GTiM@nZfi;$ETk@Jw7xXC+T-d7F95Y$F^d)D!Q z_Bk;89*P+EiY-DLK`M zJIUUdk9GZ0%8CQuePLu|0kaCVpI~|krWYv*UGcRyd`9mQ^+HVJcV7sLuF{gyiEz1K zKuy<7FW-FQ!iBZ*S4B-<@tt4)U6`>+Q`5KLP4DcS9|$-ljSRdo+_PC_#+OfYJf+ul zhRD=SsOcq}KyPg6c507hwui~e-5sC4s{Lga<5stUN?r^v$?S5V6OwF39~E5`Ip8DZ z5ac%+Je_}%<&VEHZj&eL$W!gN7(v9BmeT?BQ>Ie+WzXHdnZ1F003 zlKi5K={VD$;xXI-E{5#idL5pB`>khOc+OP`eNj>AFghis;z(DBuFzWv;?TDf(?vlS zIv2YOKTc?uUPbV^2K79QE5i6rw~NN<5WB|d%KHMUquE2~FMVI29WTsle+`NQ-dk1( znY$QWcpIk1XD%n;bvUPp>6}q3#*2VHVmgG+f%VJ1 zWeBHhlrDfSmY0VN=LfYrDK<3p(8TfMR7xhE^YfSVmca3i8^?Vkuvf2+2~9}Y5fi!( z%g658bW#&D&LxnJn3$0kd+3h8UnpRC7HqG@<MeAOJ~3K~%rqHh#Ko`Eo(+ z97#f_!W1!m4p%xVx){@?h?HA#u0!S&kAms)qpay-cM&l?=QMZ8X5`mILFnn2 zV==zRB6dW?u1@hihetMad-pVZ2n5r&z8B)}o0Nw6B@KN&A@}`#b71=1 z>AAw`Yt9eq-}0I7?^zGJmGA2xi0S{D%{BOEOVKI8Y`^ti^OAnoecYBcuw5R7>3@`` zc<|}}g%$qpSM%VC9$#Lz&TZLoKD$Tl3Hftwp*=I*lShl{@Y&8FryEDQN9K=+b)<9N zNJ4tIj84KrObcYAmtuFBogInl$g-LjqEhEOX>dtR9TDo>Wqw3F(P27dT?+hyFmjXM zCzY27=oEh<+3%b@Ik|slQBh`Dewl%1OdS}QA-LtJwDTOYIviGOHzz^#^fX)hCW=3^ zSTVhb!$pBQV*1e0OoacYvPwFgqo*r1-P6FX0QUdaMd{GZzwMOFU0S-3xf;LN_Qo%? zOW#&!Z@w_H?M>1oJG%w3=TnnChsK`o6~D^6S4Mwe?aZDvn+!81lW?<}AuP&ZB;gy| zL|rt^Z<@M9Pp2X2*yvO|)}2)GzKE_KU!%lyZW|jXs{(JA^}x`fRhqHaLh# z&MpXtUON7`GY!xMhz`#yhRjKE)MGWFkCHLKXzLpub_BfXlGDe=9NC-M5mCZCr&MY@ z9X{Z!G&jPuB8U!@!{*U+!;#uebXWMVtgL(|)^rln?@IkBvNQFT0`0`Slt!V_+Fe^x|EYnxpeg|KG@!?WT{_mzN#i-Cxz52=^jO7eNZFXeAj5#)Yam2OD6@$ z@+IH7^Zc0=H{amPZyNm>2J=FVhP9iNn!e)6mtF`nn(nHUn3ZSW5KN!@Ri5IC?#l2uomy~n_bOx4!i)mebV; zQb$kc%xQo5*4xsr2(|o&Ah}TbGZ4K<=&!#Gt;6YWYkUr*lfNk1IR`lr^p+u%uF2&~ zWUj<>RYxkdq)J4Wb9FbDnl7NOFkjhRG+O`uOD}()1DMV$LR*)mK>CX>z4Huew_v&& zToRh*Y$ex0bK!J#4xn=c)Fn?*C>=RngLI{;%M}?sQnRKzt4GI0N!Ls-+N$MFN=)ZO z4NXaZ*hk^~*N`5P6dM=YI@r@ud$u)VwIAsuf&OdgrI`~E5hzqym{^-Pk=U}kw!Zx{ zy2MQ+B}tBXMp_(9AA^=I$%!;BMH;6?DDv(IB4@Dz zIOl+BjA0!fkG&ZiN8==X>#RwZBB_T|B-U@A-~gmwlJg1bHc`_ruD^Kr=OnZD{PSLX zFZXiqiIje=UxE0E_owfj5FDpWbX+_xBrn40r-jkyu(}Y($SrMZA#pF<2A~U{FBfbd z_iB^ybSNFf&x!5tXCdl(!olLWjN^leg$W^rhps1GODil)Y{?^(arh$(crspocSJ*G;o)9v9yO#E;b949lb5G%(G!}Mh( zgIRwBCDo1X@<`PC<2*(B{XGo-(h7g)tNC-1=f8>PQd{ef@E!O=-)w1F8NL%JeR9%R zqyx-ny9o#EGzD z<&qi1=t%rCbCV0(t|xSbXS3B>CQ?>o}NpK-gfl*wSgs z>Y?Sg5Y?h5{6*yTFlA*ia95z-hnYZrP!LUe*CR$6 zVts%YhNWR1RacSQz5H&yaA96o7hmO4)BkS6+O@rMC#9zAj`nIDOkWo@oo=&LG$T!= z>nhEac(c*b1@b2GBT>s>*i%}tVNV_L@O)#~8a~qOmOA4|s-oG0qb5p7=^H2=txI(` zl9i5}o=-1V>O{!lWS@A6ZxR{$w|N{^#&j7tZjuM481hbvJW_1rl$ zmHk`z(7&Y!UBVcjQKlDaOTQ;MFUpp#Af3mGn$8cfF79*?9yuM@|NEC;Bqd!Tx)@%d zZy8ShR%9+G8kjF#6*^a-E_yl#L3Ks?iuUoPGc>;or*g#b^7nH3V`yF7gzM#{7hnFS zlGC@e0oaPOdD|-?X`%J64DqIii+H|#%W@6UxsO`lqI6jSYPtlciw1op--0=Xu*E}Zhbl6heiqPtw;Efw7T3~T6lAA;kw7}FL2DBc+{K(Oc&|DpVQWc3 zK@Z`G4;^p2bW~z+i8W;;Dnt7A?Gryg{PV*aq#u@a7v%Kz_Pzhy)6<8letY^vE>)!W zBpscf+?Rr1--cK^4*wVpw0eR8VB`|%t64T|P7-d9D z=a>_FJxR+#JO z?!%g%6GI89pD!(r#@oWjeOJfqh}f|@IA?Xlv17g|XPEQE#qAJMhtcInYDI5fUL0L~ zzkhC;%F(%m>vPiw-kOjSM$etPk$k6`CU`2KjTZ>!@vH4qN4ri)@AOE)(#T>=m;dLxn>?f8R{tq3~;wkWLa5!WE1t4#JPx_ zyliLVWSPmk2(BnA-3e-!v9o?pY2ARkVSuQ`oxPY|B)ie!usMKqj*VuMWp~Tq0yS~g zNh_Wg7pD*PTAI+#Hx;=@8a$K9mn-#*q~#Gd_tKK6`4Q|aPiRc;JXNF)wU6+#?H6xs z6M&cdkpA+*wvHn&T!_MAe_?)vuAfm3TfmT*(|_{rZ$9s!=PJ{cZtO6fBilyiQ#r!) zsmAV3mJOJO^1G&96+!*V;!sl)2K&^R`I&*DDxB$x(tAf6%RL5+GZ=vzaYfU{-k}F8 zDeZJ45D!BFK8zY~eURBW?`E7w`?lIW@S}^!=dxWeJq2zNp&ttx}&=h>^H!^kiQ$Xwbtx612&)1*Jz#>f%TfrYd5TA zo>PLLPWw(&YTVd+33AVY8ROd;DFb4`UEh2KuHJYDccoS2DA<(qNoQ@`H7}3 zN;>_DL{CR57vkn-CVpT#Q-^ZeOcC1R5KM>C@vjS_8}JCRw}T5XI=&ZA5(fiV6IttZ zo&m(z&|Os=Mof1!(VctJk5h&1L+QfkQ({)vh#miUW#!t+fKl6GvshoQQd8PYSbkSL z@;e5YF3J+7=IATB<=Of-Pi2?aLlf&tG@HY7dGr!dxc9Y|Mra$ zJuA<{k$&Kv7dFRNo`=P^oF&CH%DvK4sp%_7dJ#;A4M(PbXO(4tobk7=HE1S zjua$cU@FE3$;5+hM+BqunKHzdWGF2tS+}V)RcBvdVrS5qh`0Bl&8y_X(2FTLdC#(S z_|m0xG}%B2uRDFE%5mB^4wbu?mElg(M@j`Q+Pm`)4u6v#Jrt(HlTVI62c^U5qNd|1 zXGlhi3Tjc&E!b96W($xm@r+M%Ah1z>o_R+6E=cJ=Mm&EVDg7 zOD|K`s^oOSUw-t`KfLtA@2q-qrNU=*qWBzw=8Ay2=6VrD{7JbU&I#i_q|4pK^`aKb zO&Hj*P*FO(o;M+wzP|Y9 zG%Wq>pL>wgZ(lrdZ;rr4&DMfVT_|089JS^23!h_BXXMPCxK2zXIgBT8t22<;mE%P~ zom55<)Z4hE#C5qqKT?J9SdZ4^CKgx3oNh^+&Mkhgkn+ztB3W9Bao7L+;=Ua>m^Gk= zuTR*KP`rB|M)LlcKro#+dDL|O;PJMNG&#zN=np-1EM;|nXwF98oE@|z6*--%QW^aT zbJMpO_n2l}E1bS`J2y9X_xsbi)3j8jI`-4cw@-X}`^3L}(@VP7UnHg{`+NQQ)bu|R zhb{jdYWg4LDQbV8kLpkUYW^s1=`Up^wLaiodsv$I*B(ch?(RJt-K8z;zsVaC18SmZe{vwuKpQOhRzA;$&P zyo|z6t0~fl_C)v%qOCoHCWED~r=icZ2{S~pf!K7@{-T|ey@KHmIS8aTnyk$|)}F-T zc8jIiB28EvRFHCylS87X@6RkkiuY!HK;VYb0z*;e&Vl_ib*1wos#Meo>Kd-Qg!NyH zJb{ufMWh1hZ}RiP{E;_0XnsVLq%z!7JKLday!wf%Azl33-2Ddm@ZGbx*4e#4{A4$I zliUY(pHIcp+c?w(lOw2$Lw$7gWYf|81fh)HrF`_0E4^c*H8th#Mx!bXg~>h8tHE?n z!@MDi1QQAx@nV#FD-9IDracm|EtGwt)hn|Lxa)&HP0~Du7wRBu^6`oIkk^Ry+%fOA zA&X)!NWFQ`fgvO)NFw)8`q9p11=Qa%?GuFT>@N0nW)}#Jqs%cvrCH1i|nE>DXFGP?v2dkj{^k@N$WV7*OtY z4m?V@UX+%eug@1(w+C7}U2-XEpv#W}b?h!v&jZrD6~*mcHBDXY?5V1Z$L7+DPyLhT z#l^jQ`}%r^YT$H8eeLMf=ozqk#fm%W+1aS+LsxJ39yCfBa3rxX_u5u|=Wj9E6&}5(o>C*VO3Wop3&2Af#^DI`=YGtRYd@^ALesX z!fO|EOo3#<;EPG-3qs3WvV{m>gwq?Z_6*T6*5sqtr52>pYD#Z%{!x51qbqV0v6o12 zx*Un=Mf0bNvHW{Kmc$pWloWHiq$^@p$N3^Xjg&u~en%K!P}@aImxLG5;GYp4UKw8A zdRq)IZ@mrRi{}McN7`0kEhkR+2C$WrMO_EPT~fMJQ0J?Y%Y%wR96SqpbaS= z6|;-z>Eyh~+yNszR|VjIgb(IrY%jvsG89H@#LX$!)Bw??4ph5Y3Pxps+(O-&-&{Fh zWGNwz2UNz3=1T|CCFezZgxs!%rlzY_QkpBB|E8|N*F^ea$#8y9AtA--iAi`(VhQP{ z3DKb#a$o3Mbk5H&E@W#1e>r=q_qO9YXNc*Xve2}Q)(m)CNSpG{-IB2grGu{rA=nAk zswl5`H(fUOB_+ht&h*^5z%=D&A;5*lWZ+4M?m1`@I`TP-QP$JaDhd-4_O&F!``fqw z8a3T{$eZ9Ga{9&M?dSLYbKjuCbh6T~_hV02oQ^$RVY>7h6~Vk8Odnqkkz;%5=i2pa z)9^dZjbQLLtS&1M-KB<9r84F$$BT~P1=kDC7lrIN+{f4CZq3b2I94&;GJWt;F79+3 z>J=@;806dY_IVbZZ2zrYyj+Uh@!>jis%FuwHI*usRi zao=M*{KW(l+8;-|BY|~w=$|`r@6%6DK+Wo~nSTOy6|BG6; z&NJE#wbxW;@EK}`(tEPlN6M*1ia9Cm%(9s6CPci*{gYNOJ?pdK&uHM;O?nG^&`r{J zQX(VVBO`Yb+p=>%4sdWe@wkL0pbT~s@ z(Lz(vPRkGsJ~U*5(m76Ad+Li5i}NaW?JmwMK5T*B8=Yc0tbWpxADNjM9a+ZYB6%&g z+f>q42$Nh$-7w#&VfvRWFB+Fa<-b5tU$UnQrjKm9b&G`cTes%7(Xk1~y*0}?Ngq;a zAG&BGf^yr(baP@)!N}|zA77a57GJ(#I`$YH6`w=-Rb9_hatNrSsf+!k_sZzqyYEsz zO7&<>IYpxG#u@i=lhl49WYQJV(=EynWdO$o(>*-8z;vtGG@t4=kM#vlIZC@Rh$#u8 zC#tj%I+k?ay=pxKs_MOs_|VNg4OtyyHd}MET^|%c1`2hiCb7-W59p*HlEd2QknZt9 z>exKcsjciEaqz4Gr)rSXwP70zKu+HzSuZ8YMoW*4W~1_=MNY@{!n4IkSH{y#2rszZ z9)PaCi4aC-{pb~mEz~YgRqo7ZXMvt<#B!z;;B;iB0b>O_0`TS+Y*H*<2h*P) z<-I6Ouc~P*o7xGCZ(56V{ydsGK6Pll@00U=S9^!L1naA&5W83Kr*7kW*)`EkLoL3E zjaG9bF*NwpPu}oa_1DJ@dnUQh*V6etX&fC2a=&_P#mcxhqAHtXS9rxVL`BWJrFs}7 zH(l84n;%`!RaR-a>EC%LEZMko^aeM0t$cmtLR9j6X>#`bh7C-?k^yxoPB6sl0w`u6 zAw9azExM#Mnco47QcQkiXN+(hT*MO(Bar=zE%VB&f?Erq0jI@O@BeeZQp{d)wwaQZ{> zt%wUo+8$|XFLM6%XI_WU@t?oVQFEnpRov+sup?Dj&PB{DXupq3LRHCfSQ3q>D3M&X_nbd-(BNg6(MOEQ8aZmPkfSFHVRCwly^! z=+=ryp>zh<6sd#eiq8e%mDn!Jh290(SEV4PAMk(fIk^75n67S?0JT6$zq>J*|9q){ z^udG|jnAE*it|54aeYHiLt=%diH96YI_LYW-|9nw=K=%c&ek4Gr@xTEIVKj|C@tbz zK|W8!nj%{I?!;ouE%merJqVvaF!J*9iW4VlD?-l!{IN^|6rRK9>RdgR3Q}UhMNB7C zT{L!BJvU=lV&23=9`^5_Pl%4LVfqAdFS5pq#en+x^LyC?ceVWzHKg=2qJ@#viBd{R z$5CZL$CXZ-BWgxZx5-HkxAr5ZqqFDWZV{ziL~}+P&5blQU2afTbuqmxU+&M16!NYZ zpDPYYm`g+Bu04FX6)C+iBqW#rB@^e{FW$JZ@0W!a3vcYZK^xM%ynQ?R6ZS;}`klu0 z0;UHC1L`Ek_*2CiJDrP+pK}Zk&au-wB7pR`{!k8a{io;N$MbUg@~4+Ce~Ns5JNLxx z+wWh?J%Pmj={3Rkd#LH3e)<=I>7{n7oVwz0TxwJIakJ{~-(U;p3-+Nz!#{)}#dqoF%h}`X~Lv^KI7G`zjN!`DFgWan8%Ii~4q}}5ouWLgF&$0Xd3YH~1 z%*kwO^Iyc~e&BU|>EfRl^)`fl>7)A6Q$OU&pZL{0Ww^pg?SawQL(+PM{ zwsTEMcNLSuW^on${pb~XYzZW_c=Lzpp)(olQjg2_az2yLN&OQtQ9kdm4nKrx^+ zF0$)8t+tNAVe96wY~1G2B_3oPmJzoOl`oh&Nr%DKZY4b%&=%W6q^BWL7hoH1?#PbX z96)Vvwv*Fobrf_;W;qgR8RZym=%F4mC_uw>QLZtA8{*3|YFz*u!$b1UMf7E} zNC3Ea%#|x&ha?Qg1EIp$st6QH$7wG~GjMvj7~aX(m&i#?O_ym8fX>thTfT<%VsJP6 zc-phFK>TQr0NIR8K``4eu`@(c&;X%RQn_poo*wbBNG<8kot2skhKUK$_+3+SOXa4j zs+uu0_2y5M0S3D|yGbZMox*~?!fVY+uh{gxmv$W6&YT9!Mwc{R6fxav)j#}Q*ii5J97%e4 z^0gzL$pcr9vHlfafA!f&*adR!9oZMKwL~Q+Czlq40qSIWN)2x00J|a#1*Ii)B8{f* z0qeTXTfTJ?-y(jOO|*c;^inFuCyZ%KdDvCMhr$Gks@If|_DQyTfEy+u9^w2$#Ora% zw(8=SPQ;9XL3<0mf1aa;^c%#zJpJ??Oy?L^u&`i#c?}&LVf}lrN%RZ87g`=^luj;; zWHWvpv$_N_!ss$o2BWy!m8dRx>9jaPPFJO)FtwOeH0FlV89!B)76EXC^H=`Uef3-} zqN$7FMcoRZb6I5cFYD+|QkQi(b#%q#-zS?!Qs004vWV-F_X4Lsv!tdAe{&E{*O;1X z7+$myuEn*0;w+WR+K~H;2}V#Id;0-jni@U#q=@M1MDD~5+E8m{4j`PaWr{+F?}>T! zkUZIm;B|3cEl53aX(Er?4mKPtZh_GJS*(=+03ZNKL_t)sxDYeQK_DGCC*Fni%V2rh zS%^Qab+;sn=eESgu0JfCPEh*9&nLG3IuG}YIA9c~7nAlnw_Y|f3qyhOfWRzKaQZU)q$a?lyei)1o#iaDK9Qc==X{)=EbWxV72 zil=kaaw+J{D}FyQVeZg1JTEPYgtu@1;>HIzF8=c3y&E@n96PozFE0U3PwS7!xf2Mc zV|odu1{Y8d4nET#o0y24e=KK5&W?WWe5`+8LVw(j{y6;Z)3-mpefi3#*jqlG2GL1@ zKXLKiwNGzjNxydQHk1ylfBLEOgZkfjHi#_XX2#Z_x8 zH~0=}ueUT^&Csc4s7PnYp5a(8`tzg%c(vLc9=4)~tLgIC!DZ{R0$F`ZZOMb%qbEUL z---n1lRBTsrCmPkb(tf0fS0d)JJmaIB+2Vsy?bJL@`Ee>OS{Z=`%~)I6>NhC=1>39 zyZ;lvnt$o(|Bc=L7c!|SaqF~q%o2}|iY`9J=AOQ08;*q`{t=+4V`ZSJqfetxW)W)o zKV{9r>7QkF<7CI-5=oDuvi*^nJ8`*`VPDyq*>rR$o(j>*MoT03Xt9~BS=EEpojui7 zd!0p7DlAcM1gEi&7)qb(ZSpESsIm)9mc$31!6bBEwPRS+b5A+zqA4-Gj%6Z8ZeM zYdFlQH(r|jNK#Isv7i`rsNzJXi+(PoF7>0$%JL#HFI@u81aJn)n<_Iz7r7&&`|y3p zr+=!CE?RsUgg;_W53_p*AfX4)?FqS_I$_DYAqie2aDI@2=~pVXuM+iw8=DD@n9Z^B zO9d&O_Hy}YQbUfqA#M!wBZJ}tt)bf2avOYx4BwpAN_TV~xn7iKCm%fnuX%B<{NA2YscO?XV} ztr5zR3p_pIJ%^{yw6!g7TeIrvckI2>_*~kSZ+Y_Bigwd>b$R)k|M0iz4q5}OJ4M2M zNwU-sl$Ivr1M*BxCJMcdu%qa@(&Q3J(s}dA6c*bkR3jd5jtEZbxl*n9n{_T{1f{z}Wn!XZX)#UVVjz9bCH=iYM z5eEO3N_>IUUlaINP8cEgw^Uj>qPk{Ie+o)}3xJ2walFXA`=M zI9CT`ZWn~V0;7v1T^mB|a#`J~VYzmL*j$zZ|U$!lS_s9Y#r4e3&%g87u0cIjEF_HG82lF6l8JO4);!qJ{FP>;`uTKQT#fZ+2JSI)VbB=NW zzj{bWTxdvZMd<3Jw3Ic=+hTX^xKYeQe=cj-eo$FnfOQNn+r{-Fi15F zo_^xurw}`fE`sQ{Pn@{z{EhnGccu&V3QX^50Bo1LIJhC)D`e1eoJDJnYx463Aey05 zh%J}2yVeE=gC|~0TY_8H(T9=C70V{%b}vU;zb-dsQmkZ+%%|jus+XrU*!9)Yg60pv^f3P6$Uhys zhPrxn&56C1jQXV)Y~7lcmN@LTE`#UN9-wv)Y|tKlpOei8D-zOL4;q&qxa@bL-UCnJ zb}&g+W80mU(eS0+10~hF(~>gUqn1`_$vDV=)cUmD`en%ySMO!zRXexs11nrsI=D3? zsbXu-hNVX?``xeRf&2aOF52relG19`H%GRdw(*#;Ni`aL;d&xVtCfpAtw|N>_qV3H z(K->5lu;|Ux<+zCMMA|v>#`p8MSkSR;g+7nRVXc+->9E7EEoSj-NbuYSyr{PdRD)A>ehtuFo2Gd;LbzI4MwuWZSrmDcGEeGI zqbuohQ-G@KZrj^uZ654tbc-}wvj)Q~)zw*MgHh}kJsl2vSSdb;($q5dB8Yzf$==D6 z!syDK4u}KfmPt!u%U&BXje_US!JST8q~B3wd}KLlI);k1Yop8KGj|s4957IAr&=3n zjE+u@ur7e^G^|U*qc^nM=s-#j(icd6nSbF0dNR?xbiv$73Vdhx-pf!ru9wlVEUfAC z-Ik%nENjQCHPvdfTWvN8GO^fvbY^O5jSCCXooGN;Gj`?f-MhcJ`x`(VPDf3zF=c0C zC}(=(T~>|@8{3P!BuKt|BlT!ghc8`4KPi${iwqP=%#QTtLLd$p{-AKR=rk6~e z&Q@JrJ#5K_(rff!I>G6-v7s^BPG;NV5>gNI-^X<76PW_US8ggO2*V0aHR%-n zSEbx?>S!;Hm%iRAJTR1xR+W3yWM`AwUZbbXmB(a8`Yf18Xml^5cRiVso=~KEmSr1~ zJ;8Yl=q7QzaGP0nG~jumhEz_3%0Y57RLx{YG(&(c20p@u{ zmCELg9lyM3G`?!8OB#>HcU4su6ckiF&s>ZqrEt0;^`Vnpy?fuAelM}M+A_q(&kibY zYMN^5Vt+^eXwlBAm)1}G`c_owp7NQ@%Bg{<3nQuI%U@03x_jc5c|K}>GnJt6(H_TZ z@8#z1N-W;`@;lAF7jt2%*47Wt?mB2~U!Pl1v8yog!w+kRJ5x)OqoXchOp4O!Fy*Hf zxG~KWPY{e=SC<^^p|=OHiA!*rSYegg00yZ9bR30F`*u9m~+9My_A zWzDNp*(lprs{wfQXW;yxuqU?f9jrfl=upVnG;AH%##_WIjX=$;6cYK34hKD9?T$L1(#^fL)n6&eR^}AT1#^Yjo5lcE6{RE-ulE|nqU7X>2 z31qx_{`NFtIbIgQa?#P@bWX2dM>j`12gos|V>CHEcb$Hu!s*KKBIL|sIGvvrn9-TX zESH!U0d`0|9M=oCk<_w$MGmXay&f`Me7Lx9R|uG17(2JMu(0-0!^9UiZv66>_kQ_b ze|h7BGiPqB-$$5Yza*z0%klN~yW<~B+RJzjuVWVxH1AK(^`9YN5d!~|T>!}BH|B0o zHM)<>_in#?LOA`?%kN(P^aRG86DaDr_ddP%zUb(9VD3$yc<4XdKjT7kiWd1@x*EYc zOFc2B6h-0dB;Z`b&#iGVJDA?;6}Yt)?}S%4^rVJBxxmso-RcA}z*G!-sk_P=9n1mdzx(FHN3EVfv$A7x!qDCu8W= zEVnC~t^I>AeL|j<5h^JYYLHl2O-=~8;{nnAAAZ+1)E5>OsBBhE5-@ktYO{pjb5tJ&Km7QOHOC2 zRxGpo^CTMw)w9bhQ09yWSGa5))2Wm+*{U0>U9Ux9`kzwUzyCzeOZqggHGa!^eGzt+ zq-|8M)oZndO)VR7x%Oh@g|8S~#^jQ*BK$s9gU%6NYeHp%`|%iU^lbEs&ESnK*Bnrf z_&97CJgsqAt*mlFd*D~MrE7)id|j5GS4xCz*476~6M1zHb#y{VM=efBS1xq4bDA9u4K;)5oJ#sZq+re}^GW3po zb6Zqrx3#0g7}nW6GDC3sPr&pmi?2GmM?RiuqKgr}A1W+uL}^n=*xYNgIP`iN5zQFs z**XKK(|~5`)mKNyNbc*sLQ)KAjEyE5qB^osr;&iE$~4g!5&*U9!E_zDg8|ewV&tIf zyPdv2#(Bd$_VmuqY_s^u_lxHR8GR_o8<+=l-3dhTCL+b#Y|9$XGG;e)WM$b-)#$}Q zLbzUj8CwiPI!e45F86fDOM*j$VgYIdBgrz?*@pWD`?5Oib|w$cA5l^|V!93Qk$BU^ zoo*g(7_?;9h}#8o2rrFZqK&5bskM~_n@XZKCl_prZyJ@r^r@-+G&UlqP($|0srYz2 zEMU4mAfU#_J0IPf0M4?=asq$c%Yr5e1tipmnE+$mhGZHu!Ih18^^ww%$Vsmu|3yK% zWKAkDocT2nDixx#<3R*+95v#5areeq5)ZnIA6+w|N4bfTuBqwxiRkm{ZnyT;#`2e7 z%S5Wl+Yk^<-%$pZZqI1RmqcOSQzu#Dbk;HyNtUKzrfdegmPGG^wUtcz=xP*?mLA_F z?UX#KPKhxFQl}8%ldGTf(R_7p@6cGysm&!w+EraDm2vdwXj4sq-dKKgYX8xx)C(6b zl$7q-R8%xo={bMlh2))6Q_;LiALEg2BO_6s)ZLVCzmGcB`e=*nKaZTyE`1&R-41K zw17z@K}l8zp^dbv-9+Um@3gdlO`1wA1>Sz_>CtXnPGyltUyKwauJBs!Taj)v&?xD* zl3uj`sq&}kOGA@;#rUGe_>)*To`lz*dkznbM5#YbH>0QIjCdC%vcu<6Ju2pxuRkS} zPFgx-4#*3gqq{4|3pRG?P5K|j@A4vq4pO^@svi}kR&u#Qc1>TG(+BX}iSSB8cly#% z%w4qaT%)F>vo?k5axN95FTec#e~|QwZVx=87Q=<4`eu9y2Cg7a^9`oW2b;@Yhh zbOFuCE!?%MrDb<9x_SKsZHiRjdD;Z2=jrd%AOG$|!tR!c&^T#7gcc5;V^GOkPr>KG zdJHfS^+6SPj;_vfF#X{6iS-q-#`VSP6E9LGR7{OfUh$4&5i$P38)>{6m$cEJ=1S)x zG7|mUQjYE74m?!jbgVAh^GHrtYWhSTZAi6oapLEqrJp}f2Fi&OC+1McMLHKi2h)Le zvA1Y}jN=rHt^m`8%Yk#rM91vnRMMezrJxI;yC8k}npI+aSq{-7t*^+Ln@hOXf1ObD z_j0AUHGy8F#VvD*q(WZ2aRy4ic(3q-{vBs-?2A2yH9a;5M@xjif6QustV#YU{nMxW zr*ltZHoqoz^Y?L_pSb*~oHMPSODLS4hQUu@d7(@c6Z*TKBB#q+x_9k;Z0VoA532KX z@7hEE+5Y(!Ci{AYDuh*#5+P4af65H!3lRNT5j)p~C@cI`J~-u>UM>=GVY)mbi{)u4 z)ypitUNP{?BUZF5ox629pJC~&m4)?N(yYriR15#Oa0x&43MbNAS-M(N8d>vFuErx? z7k`;tn7-93&iOQfe~6mCtVCX;%g)0ZL%q^AtXt-mq0r2Q=?Pw2WqaCq6AIyMJVaqS z3u}2%&P}UN@meFQZx)LZI9G!exmM#^q|P6FioqCp5nein3%k=?cim9o6%w#)nL_}U zXK@quh+lA}XkGCJsTKC`zd3Y^%D_you>FxKW=tsR8*Yo|6&n@BMeASeV zDqLPfX|2GypL&+#e6Q48&8)qtVNYLqZ!+4KUIt&QgC+95S*p!bmRVK?o4LJYtCv@z zcE5*w9K+fc)yvn?^@Ly9mP^l}U6|0OGu3={5j>+B%yB~2u_3j&oWr^Fs~_{DKfPu8 zV6Q;=#yFg_LAAr_s~g3++DD(2M0I29fYCqWXEuvc&fex`pd8mrbB|!U4eb>VjCH|% zW=46_A@zls{YUo~6=7{S8dHAL-t43oZh3P~W#s}b)mT+>4S(P`1-1L0+ z$g*$E2)xnPZjIAc=+WI zja$XwPGSyml&(lh(bBmYV8`rYpy8@pY8Vfd=B3HH!NfrI>#%0Rjs8>~Sh*4DF>!m~ z5D`Y-vnQEsQCe$77r7DpQiNf9VPXINfynqe;)k%{N5^AYkB6ku)$^$!XsoG`louM7 zs;vCJK0uw_2~5}=0nwl~ZA!c7m(<9YqDJS_mAQZFXn7Qw^kDiPqC)G)b&28^B(swq zR%Q}?j9BJn%x~TlZ?Wigog;6WY&OF>w{9Ed$@*riTb+K^QWTw>+Rf)2g*V+=Qfjni z*`wU-R&&8RH>*`2=ILXx8TX`8faMluwHiy@99d?go6hQR6YmQcIx*cz z>H_D|)kq!1@`9=kmBZr%rN1o}bl42a>p8BLyu8EpwEq;Rd3vh`>FE=9wjNJEUca^W`00mkr5b1gZ zbW0iOL@lS(eJUyapi;mo_eA%eSdV~STzvT8MefOucwzEl&jiN!`=^A5Z;T5K_B)gm zcPKC;F{bTU;jTpPt00|~LFS0~;&wSKyv`4=4s&|m;q64H!|9h`+F64) z6hJYu{dc<3{1n@BQ+ZVEPAVZrteKv7@4J?%3)6!i1b)sz`(V z{rq$KDQ?Z>HPI~f;%!pir*W|0ZMk;u()+n{bJLeDLGL1)%iFk4rpvVxw-M8&8dfdk z@`>qd^j3ZJf80OEE$bjpi}pm-{6eqcVu}BKty|Bpa(I|_`)+OzRIIej!9^znZ+H;X z*U8@m;GDD>a?l&+%TIFC>-wIky`g zBK20(9t)fEcEEV)%{mvUvj?AoT9YlTCM!I&x@29J{10;>VTKb$H$<>7ot8@ud0iDD zaXn&KV*ca&sF+1OxI$EDZdO~{jg1z&^u&*PHA{E+qh83~5^h&3lqp!Sn&AM~UTf4h zE`te?y3yJ<%-7RvFm6RseXaa=@>=PdSG3EURztoK2i2w3u1_mt>C5ojA4it0hqvlg zy`^1>DzsV8SGJ|LUe{@@*GlcBR`4(<{ws^n)|B+*b#AiM^)Y_+V}A6fSL)~bBxSk~ zN6Z!<$wM}Z>qR``ywpIIq!9WWZ(w>s{6;Xg*f`I^(Ts2h*2$nlsC|CsV|?lGe3o@) z=h34(_xDh5Y8j|2TWD-7T4=UdJ?(>8Zu*|;X4`_r(wJ(gPWHSt*xX~$8GHaX_sF8? z0ZQMB>Y_b~0$f)*uzx>mp>2_P&Xv1Gp*ZTfWAbWo%U%)Eh0VncBNrH!NtnD2xWbhz zedza~rsIhpa3eMSVcv9sashRTe|ZCYx?IC;Rx;T`W0wWf-@Q9# zo|$PL>guIik+{y^CBX&P`sH`I_M5vx>Rnv{?zC)$(l5++I!FKvaEy*!xgtR?y+aaw zCqj2Q?i`V*^?3b*C?S;)K|_ETvbgMF6iAO6NOc=P71kL$&8h~}kV($VP*c9_LLfTb zK?q~El^estva*c2tYO?Y4!fr=$dPYiljJuwp}tFvDt;Nsdm-FWaGC1fvND!Y#=1GX zdU%l9fB=0>5F&8R*yoE*MLjz#StICV$6$Md#apRBnn6kX-}rO-g`9Qwa!`3! zy^dW4Y#N4ok#M>pS{DhYqoEtZ=EDe=SC}q>x&g(TEKiC{&1{`c3?5=v=O8EIbHS0W zOC~X%4o_J3b(Y%DaQ-AQmQNUhNJHV#p18OZG_LIy&BiZmJ&T`J**mUBc-cAoU^kE;TpPrIcguP@@E@uLaiWeZ<{7 zqS?FP?oEH(Qsu1~h^zyfk+6xFVgCfXJ*0;h9wk1aY;Rq5^b<2OH8kZ6FJ~Z+I}hp0qvEJm^D{xRoyNty?GR z>$j@@k+P6co7m!PUbA~QX&+i28-n;SFoX~cskRc8s>^+oYJ0T5PRo|5h5y2dlPI0- zegIF*9M6q^)5+;b>6)4@g1UlqaGfJ^`ZI6;Sfuo~#S|m*y5?qA?sTa*h0>AIU4ZU7 z7YBEN zfBhRzZdvhQ*ozab1+c>fxyhz@vVM4(7r>VbUZI< zBB1BhqLbr#Dc)VN1O4#;03ZNKL_t(cWu?OEgJM(R^2Li_`u6pOyKrG$I*bQ~(DRAI z+%qphVR|r_ekTdHHv#Q&AuS0h$4EA$EhoK8TUx$oS$LENiXqHFTudW7rzfu~p|J2N(F9NNG|=jSu*6}&;a zx0QwJjfQc-e>J!_SRorxFx~SZD`fiPoJc^G8(nw!^Lo=a#CSQ&AeLbh(e|aN`G#z6 z+X{IT&H;{l#il4Ym+ziyPlrFju zqiFYeFZC?TyYl0Zh2 z5iwnJp(|sHM&j_fOG^jT33?$4Mtm{qE^_(Ewj*znonoQWDG4bHX4?>Ix>iGK={Az= zvG@t@L$DqCzCs{6)^m}|@4gDAdyuzir2P|(S-Y*2S$fyVgGFy29V){aUIvUdl>@6D zWC_~AZEx`p2LuGre-mL{V#3XOdWPaefUP0ZPC63dFsCk;sCaV6v8R*Uft(&@zh&t( zTaRQ7I!YW3JvvW)fT~M1(VmrD%qD)knHQ)n93`?cC6kfD+xgPaGi-Aw*jMe~Rgl2$ zI0a~qjr9WRxL&e1Q)DPTj@+!r+xx~G_-xAaq4aVR6=77I*~!V9lS>Mqbg3T&)KC61 zgIi0Y)z!0F_ii!DFMon0r)^R=;A*J&@OcW1swWRrWQ zObGIc0wsfmK{BI37lormFkPj&P~WI-p~w+W4`Kb4?mAnBIvptVC4zaPZm7J_^3+6ib^Z0T67rvJb~< zK{ekyDBAhnz2`Z|?4+5VM}0ke+w&5q6RA$yJ)MZwc=*yKz=j5lhYudEKfHB!%dU)F z87-|X@Nf(H7|u?O6}u`b($d%iuUe$Y1?uq77lg zlyvR%x3>EI12SnBF42MvF6mcCIQDJ49V9&4?y`UVnJ~`dzu};q{A&Tw1^WAPW+A zf$0Z){Woq5_YI+zt|Cn=G%Y*MFm5F5+r=o{hx_J>mM@qBTvRIs*#-UyPiG07zIX5C z?dNaf9LM5~>%}#M*CAfYG&R?Y)Q~DgTxvG^bC$O)htpBY1;nW&RhK2vMWH&Kkj{*! zv<1r@+DLs_zUF!%crWpeN!J7WLs~O-ZQZ)7WxApe(@SFPj@-)^Z-_PhgBx@EkkfPN zBRYM%Fyy*_PL6+0VeT~o&|&mz{U=CV{FE1}Q2fMg(0uwt;WaYS$$dYOd;9XcpPs<= z0-ZzZVo2xer%XNibA;3TuT4)o$@G!`cmK3E00&E8Selh3oCmGDv_OJa_(r8@FF}|{ z!;odm;Gj6?3lmCS!gM%u>9LPo(Zexao=I3zjR>wNo*m?Z-L({#i3@4@^X+=wk9b}D zRdNA!9BPcyqtmc7iC9|c?{y)@3BdB8t@mFUuS-?Ph?=mPpS*;o@bD^9}W3(4# zUV0~j(oWD8FuuR}zVf=3o%ySda@R*AYO+SGdbSs!UE;gu{&!$mHOo|CFi$P7SG_^J z>`U;xj9nV+_~B;0J+5sMlIVP;5B)e~0<&a2!sP$3ZMpPL{k&FcpX@UE6rH~vvdw+9 z#cBshn7aGJKIU2;q^T+;Olcq`g(+Cw+W((8EWg-!X6Mk+jS-TJOzdWXUm zn-%-B1DTmVmp#LMeZ#mWZc+Y87t#d@ddXU-LvT#>Nw=h$s;!o4hoh&*GTGB?)mK}? zl65A~XVPLd*t3&2dzO$-;Q;|5GDgRfur4yM2O%RR8}>w(VS33tIwYnSfpql)rlY1e zHWz2?m8PT|uzyIXy4*ZDd2%N{VhToy%cc%>&z{Ok90dytKE_UEM%VcK!BZEg6TtY3 z7o;1h8cQ&LtS(wm-IPYc+_q* zV%ivxraQW@s3_d&op!1~%SiDPg`Bcbas>4beQB6wIJ=`d%UV60mDM+Br5e>_mu979 z^mxs0%0KE;hIfR`8x5o59HAo68yTNxw$rln%`j?62b;~}H{F7lX9OjeD3tD_bd?4i#!cBcw!m7y=zd@Jy6plBQwi*BrlygoX%hb)I~~H zYC8FXo|x2AivV>ulIq1TqI#18^AhSpt~!)17u|Gv_fES$E75=XO0N|N8!}eL;i{#3 z3pp5ZwE2#ul_KGBGU9e<=Lxarjs+eg<>6RFL|{zJ>cEJ=z=(*5n3yvxi8+H$)z{be zj4%Jc$N3K~KXT0R%|TIY+t{{oO}KCYKPeki##2(-Hp*y&9~di^Z&|6GQ)8z%c?HWj ztdQH}sIEAfcZHxY$c(nl8*mLl=;gc}ImlR|X1Tg_McwqTKhYlNe6;flPq@bUr{Q0< zBIm1CunvW)@#Oe7#=kkPIQ?mYAQT{iu@C|DM!x z#nLWoy3n?wbOr1#JXfHu3FxYIk*MkFHlcGTplfH&M}Ne_1<*NHpsqDBQh<(n&jBol z(SJ;II(qsK6{iF0BC)^r^pgi3plRW0O(IvP&iAeWT=a4c)!88GD1gpm!`VElc2wOe zi`K9fEvr#ht%baxr>pM(AFX`4+6Vr?hjIVoc79MTREkaza-Mhb($B75zF3=A3#3of zCfup5uRYuPh1k^JQ7-lL`Y%#aWa=m0boz^mk-RuB5i7f3I(t^csG@Xl@xtJ7fzI>R z?<(8{rXM7tW&QfxmW##fcdu{R5x9Ee#^CT(;eMg9=PHP90QxfuV|M`Q`zrQP^(=>7 zEpqv?EBiIy+KF_V{93;yGPIe-5A_RF`Y(W;dXT|{(*Zy|Dy7*!}CrG^wn$8#bi ze;Q5vG|`J~3e)-BYeQv6Z3oDu?I^aFwzi!9+k3a&wF8(|3dE+wa{dy!OGF{txyQ?mO0B7;-J)+Vu773B*5+pPtK|&XuM`BBFnK zSvoJB7EGVMMm&wY!s*Mm;doKgKPBx&FntNqMOViuBRdH=#TT>ef9pU#bxpmY6PYsT z`8w@hdQGMB<;qr9AH-o$KEin)S?uY$Ka%1SXFhU8QdxSRa9s~=X5p}F&LX51Be#fw zz{x~h6T;DO7$|b7>5q6_{3`60H8A8JUJ*Uol|StCIBRl+-)xLsS{FF!d^v&8mQ(o^ zdp-j$T%#^Uw-Fm;2=D9==grFXW-; zn?OQa7NA}|+hLuh>8K1#x1*cbbTUPH#QI{%8m`9eGTSq25qo;pXQt9R!XygP`)sxz z$1O`TDz7El)Vvo>o!$CSx@jP?EH%1h50WPhCiM;iOQ>hWwCsaJW`RyKi0KFTV zw13hfpl$`l)!^w+iJS4JBc|Jwjy`0AqzRwla1sGNvdE3j=x(T^YxmR{C?Pd1=rlFm z8S5e>?!t3*2|E9UG$H-P$O{^#yH3&5DZ;Z@Bm$9^sidG^7EHhU>SFT{)cpzCIpgl) z-Lbo)i?1%;1>G;Bn2$C^4$RNccyef{mz4BKolpMgN%Z#1S9(XE?`m8yVh+dkqIo;$ zo*CdxccOp*D4l^j*vD=TGQ+qcBGbziKBdiMCyKF;X@R0p4Cj)V4yR*zfwdjgHY9Ot zHU+*G=0ZVMN;4x#ghX+lly)_6y2(fORv07*1nt?IknwWwfSPPDoeUXUHO*jYF^Y~o zBrT45UnTB^%om4#vuY6vK|2~6_SypI+UXJBgqRMcqx_#L*t}VyPH5DrJTKCJbgwiv zq8BGIFO}s!VadF3PtSOFx)w1{;JLBJ<8T+)_s%zXxJxRdr}DsSiaMNLzXJo1J%&JE}FfRwL*9XbaWlm5S!S^zOBHBCB{{xYod; zrAN!fk8qq@Z(EgwGv2Q!-;DxF29RxPQJXZ!&kTV{p-#T3c#)<%LTpq z^3|VR280FDx7MEX+lme5c>S*xq}Tr%RDY);B_;4&Y?8QM64EMaX&FZoqn6!y6JmM+ z+R002;7{T5#V^3=!#~g6RakhDoN-ap1=)A4FK$`CBQS<}C_8KX($eBG4q;%HkQz^sqE#U&kPZa@U(}V# z0I}sd$W9IEnYp%{6>VZsr!gtM763eli7~=DN9sl~q8H}oFh|buZ<7Y5ZCKWMBrwl| znN$ZRR8&mY9*ilVv^_YRbch~HT^GMT35n5)Ly~5L9gMZwXoF5 zSU|a#--9y(X@?r_y5sVt7nPi)ZOc;GOb=lC(k#dI5ZC$rr`Yh|J4S@nJ_(^e`OhSS zi<&gcgYK`;znL%0^_Bb9`qFw&;CcSK6%V@9Nsh>G9R}3(5OCO|qWoka> zdX3^%QL`m^`x@GF(>hVv*{F8Tyb_nbo${cEe;hJ#)VtQHxr3aq=Ki*H-YnG|t}m8a zp>z2Io3nwnIk)I#CYYiFUDNRok-3PRyF^ zV04?U-B#PJ>S2ttIH8T*S=G2=WoWN_NPeJq1NY1DOMn(4DJ*6av?@a#7AD z>O~vUgw%O)>5TiKrgvbyr=1W_KBTf*!1UjYHZS5dry>*$orJ~bv7!ew4Z*k+mEwC@ z9Lg`+>C=>tuH1WawA>h3HiR>sGE*W@sv;N63o|A$VB=k;zdeaB^sLwC1Lt}OAG(Lar^z}>4BfH$FQ77m=sq4kK01AYt~q@;+uD$gHQmgf3QLxq-Znu# zk>0#s5SQ@AGAaehR;Nr-N24DJXD8_1r-q~%g3{j%=sXo>wyKp9#9lMx=o%XPTud)A zvJ135QX5M2%?<5@z4&;SNBStsOF{H0d%!8O#!r=NmKR(vSYFOw?G^tEayo^UCOzu6 zBq>Id^XC!m7ELA%jf=3xi#gr9oLwjcqz4h{xEUpV*}4rS9Ni>i61l!S(xVJ}y2LgH z;S5)Lx_HxZrz^*cDCY5o$atB4L}LtM@J!&l3R#EM<-q%8v)LW#q5L|130}GC91jpF zOTKzd{l2Q--KG1lbX|JL`IjHg9UgXP82MojeaNy$FLJKoVJo`-pcTJ^@bBO25tklZ zwexSoBkuXzi+R^Vmbf((iHh+BOTsq<)N#EyGheW~JpI;F9HDfHM;9p_L;BO|u;fn1 zvHl;irHf76NzzVHU65Rkav}%uwzz&+tf9JQc+qYUJGyq@%r!pJF1Yg2h0`@wM=^J1 zq`$}|S{zA_qaS|nZBDr+hnGM6;n$x9)R&;z1?vjg6^cXQ%G7e;Ne*0+;}WLJ-IR%4 zEH4_RkE5oq6#o%}&ZBaa149t~x4%mden#q3aDGt8)mz`Goj82);?J)9?9xTCrDJ+Y zjPnnnULjq6>ff2*4z*j)CWWW0Mod2>VtPVGEfuE|g4d#^Q->;LpVHfig;FVcaXp=g z)?X|v+_xSp*TuYx>&4Ep3(xub*kk8N7Y`<*eQU_sL^{kQNHRM*Ifr7ZNO#kb4i-(zH=N$WahF(UE*@r$c+>CY?wczliyUM|uvi>FmnNDV&=-2BV)zn481$LeR@NZIU=Z*fOq%v~I1h z-CbCbm%A$=?NDfFZr(kbknX^mPC4n0)42)PLav7}D^M*^Pw#I(->Q2>GJ)7_AeVucfRx$H?_t{ylhVIj+PoF-0b&Id-ecspmgO+~$&fVj<&sli~ z#hqeCJlK1jsis%g7$M!*)Q1a>_mBI(?Z4Sd=*W>7?bj6VIM~RlrQChSJS3EHRKSJz ztLae?f}W#T_{bfZq?Z^MgZ09qFC!u9ZU%SeX+hugsJuH#rt4)|Ehn&}ra$7i_!kkS zDGwUA+Cm$i%r1VvtL5y*+RKwG9r4;6&MIqvI>h^>`*GED`^EEi%;OV?egrY7_t4St zj_sE)!<>gc34rz)pz5Ic-GsAP-4^?KSZ5WYAC(?+c4%I#oalTVOqui2Uw1UlHh-*J zx@~s!=x^{Q?Bh(~D4lp8`?aK|cQ~($Puw!dJjsINnlaNNj5;sMpE6@@g0nfd<9-|h zWAE5T#_!SDbYTFiKvchd2UV6Jb-e1pd!*1+IC`w_Bx?F-b|B7` z>Zs}IrR*h;l{)fb~W-$9_T)@abtV% za$aauCY^?cy2b!I&hK2}?OU4V+J)vQ+-vhvcxN+^l zaB?o0E@$h`Ufas#0AAD0=?yu?3rR;uPB-c4B&g?hl{M=NF~2OXwqti&ZG;d=Ho~lv zR$LtK^>%e7bR9S#?OYQ`DQt9R@VcS&&o2`5(n#ogOVBftf`V_NT1bSCr@oHc4Ww5Q z7^6n0B%>2g7K19BFJ!2fC7`y)Cl|u(4o@`2wr|gl>?e-ae zy7Y82$CN}E$>=0ID%yp-MprnpMbWS#8vXT;Z4XgS?1Nvs{1A>mV(W3x>JeLxxB54{ z%GkqWOJ+B`ujpHgE?6(15yyBh_22*{x(7C&Jjed45Pjk!b`gCXKaSWEP8XHVld7>1UpQ)mxyAZo*W{#RTbt9w;(^Zx9lZO*tjP~sSx6s|8ZwJ!3wf!x| zrf%R}+c?iLOD2O+kS;1$v-#Y%yI5H-0(3*^_+F6o-}xz%TutDMC>?eE{oA)+T4@XE zyiwTNxx;c4)CKE?(4Rm~H;OuRPM8ZDsC{#pk=uz(=lPP;xuscz{=^j39yLEA^_U(W zchUZ!w(p>%D9GL0|LLcfnD+^!V^m-NcPm$6Oy9irzpq{U)lSNW{@vgGWZIm0%cg0L zgN^AZ@9WkP6tnKd{mXY^43jfmVT>?3l+FcAUs6)?;gZi3rU<5&U_3`uU-IE}3}Qb) zN`GqZPoCOIP&=tHcv`Tt@FZ@v1F+wk+^QL+aJm6?1NwXAqWKKhOD}mTAMPDqiezpy z^TSZMnEmk3-&|c|?CCP8<62pRjfICamy`e)1arC11@l)a4?2vfj+{Pa<>8Xy57)fB za^>N@hs~PF=M}yl#q=jv6|DV-^{ZE->aSnAXz}gStJm)>DB1gu&wpq_8Q&Z#(f*YO zi9dc|z_@SZO7ADgg^LmW@zTTUhnXmP7≺wDKXgJAU)(abjx*@WdR4-j(=%{NB|e z%B-5<$4&c#`ggkF-|u~_W*JMOd~3N*cAJBX)o?)-TTQ=TqJ`|Dn7*0s<+wZgE!1?m zLuTq#_1%t&q{fhA{RxUe$nlRWHt7ZI-_H}&Ui?G**~?DUWApQz$VlyR>~M@&$~Frf z>3)3q)*Qyc#Z#s|6UWBRu!!B*-S?Cu=04_RaF4x&h3RGw=4^-cNiY(z(J;e)$T}|P z><0JriHu=-%no_Xvw7a+4HawIA{Nu5ALiID|1?XMlSD@zbM$&CIbasvw@zdp9nVRG zHUl@_&6Kf2%jcfHKc1N^@ZbIN=yz!Rk3-*~;Mmj0?Mvrj5F+Mmle0GFD=bLW@vi4*UTo|fY|3xT&vWPH)fF6WK$(<{2u1_niA)&GS98*YR8QqxB z$BZw;ra$|uXRrJ!8p^0`^^2PR`s=lrUXb%o_JQf9zR{%~DBZ~B*U4I}stk@2M%j9K zbhPlmfzIpw^1a9jBg6Xj?neACq3&+%Fqf`3ZmjYJ0+&Zy8yI&OIUO+_mv~|w>4{7o z4FO>3EoZlMERxo zy=d$j_0XXtls6!!Yq}}b>XT95i5T~Il9-O_%FXRTOh0>e>(;GjZ{!dv5|j&x0GGyi zIGqS^8`OKeX_U9*-%wdr7w+`7+C&~F@H{z@{F1INZ&DW-CUCh)dFeKh=_ij#N>|KF zHZhYed9MeJm)xatmb@L}&T;k-<5KBDE+;nL<)YwdMc7Olo-a(FUrfM0Lk+hJ_j)0* zHpHHACmt&2=_Bk-+z*EnF(1!3BoV0|MIA~{MMBq{Rm~tJ+L8Q8d@(Gvt(s@pG?pz{ zj=igY)G_UA9(tJdW1jbKyr?%Zjxw*KkN&yG?+)cf?`mPPjnEcITi0xa^#1r`lONZ` z?7(?5Gp6r2X#Z(&R*l_`(^LFc%a1LmKW>0inlXAhoGv-tG(0ar`u9u~BSob%ar9}f zP}HGw<9T5QDU^=q1;dM}HstWMfog-@LT|yh!{-jKYjw;zTTC~U9)s!z)Xh#ULI>2* z?5!(l=?`4sbjqN<_Q?kpr$g!Qz4JeRc>DHDqo<3pEkw7MtQ$)_=h}&6)U6Hh+?=Op zj4wu^FyFS)7?IO0MwgI2#S+skEj4*T7n_%mdHycebnak*K_y=brO%!=Z_X1_7fqY9SanI4L*~-pt;|NF$D6$wT^?qK z+r{ooAk|)$^uAlv52mB0(?D-x520|X7!41hp#LL_r~mQl@IOjU$D=Me{WLsowZobq zdVbBzvd5@|=@7+9C!e437*F0ieE8+JRxT~TvaT7^)GehsYWiu_IV#vtu)Sp6x}}Ss zy#3_B`n|nNK78}}|Ba~r)?0^H4J~3QaC#|>4t}$1h6t)MN(4HJ`Y-@L1b1J(!+J`M znqygWm^8+rA<7EMDr;7vAZbQJ#t5n#`F`>*Ij9Ai=wam=vqP9Y;%tna@6!k92b9(c1E8_ zn)X`rw`;02qUhaUQv$NluobXRBA10TNmSG47ko#O2L;oHobeSHV>sp2ylsxaP`kG_zt zC5OqQoN39yXI@cZ@?HLa=;;-qmYly}KIxu>ObV%IM><38Zst77v`|{=&#o^{aLaJv z^Jn|WXRJV4XR;(_7b@`pY|I&~OvIg@PV{*>YWl2F#X43WL(Rs)44ezn5s9@#0h|bo zUR$99z&sxDCZzjo{QHiP(XJdl)K&5r=NG4m)9ahdQ^$f{Y+AP%oojv!v?HcJ`|Phw z+KaSy^Ejp$rG9X56Xnl?vssmjnsh;GJn=x*eRO}?iNKe z@-VpG(|w@y^5s#PVJ=`qVjQ1YmCG~}*g!e&D!p^S+#z2IVrP)L*ra6B5JAZ}|b zpQJt1+7~JfK%#PW1V9>Fba}&(IAR_T{wUw;#psfomrGi!tP73G3=x4WfJ-792ZCgieiYvq!jB275rKekRx+L|U+T5gK zj40^b^O4i{<6r{#6WOLPzIfJ(u9U6Cvo0R6CX6Dc4-THedv7TH@_SxO z%7`bNOIV^jDN1Xhf>9xXjPcaFBq|@ZJ1^pmqtrb$BWM}T0g5|ehrz#&Zr^~eE^myN zba)0CIMbDi9*01WVD9Fe0j_%{#}dTIN3MW%^3@ZJ$3L9w;syN_<;;I^(Ms#DHUE%e z+c=OJ`|zWeAIV8TuaP_r>hgSZPu3I74;4~F%^)%D+e%nrEm*7o3KP1bX{A;(t8|ur z#yk_xLNE(IFY89v`dK!I+K5x9^E-9wbkbe8ovuY)gG_|%(H5(~9}B_{&Z>zDT~XR4>jeDB^~a?g#L{vio2Oex*={6hGD*~)n{ zpPD-FCv)e{T?(d4aJM;~MQQ3sWuZ}cy3k*{7QSm6-05eEiu&J$)3=oX*HAIIEhJ|V z6Ukv1UCK5WCB6&`%Q3kKo=ap&U$cf4+`A*Y$sNRYO(C89^5MP1&%d?i<-^<1*ZDU# zLsdj=$BRJ!2g9p3EL~bKuxkDKrxx5ky?E!l!`n)pfByLo?-YFa)|xekm!4kprof*= zAnbfdPkkOa93MK>MrDFg6{F!>z&nLThfbe9etgYU>Wq@ec=z7v;emSvLkRLR#3+ps z)&1Trnbu2=57-~nzthb${uS4by>`VWWw_@g$nHAb*JzGSrBlkafY^Q&Ur4C+rjIv{10Y#ZMHd323sfqh1 zqFX@6({x8$g`;ad+?#6Mqco{$7p%MEe;h(*^J!TdjoX*b&iQZ`ILk4&F`tj#Opf)? zI3M%4pB`H?oLgx=oeJpOd`lnMDKRhmz~cPoefe014(5|bSaD^OG;=|EzRXZ2l(C|9 zbhIyrd>72=2XiV~@;3d&iA_2FV#+mEHtfqTt?X;4&L+#eCL2q&aSNb;g?NQ;2@(yWwk$>fC8ZarbzG zEeXNA{E9ZL{t-T%FiLvZ3(l&GNUTJIu5^V8&FKg3uzxp<3#F?ibzSSab_6AT>vLzn zY}=9(_P9bg-VLWyT9bHq%k_de-Rsf6BL1$Fg`0MFG$nX(pcHcCT}&Ni`sl1#Odpla z1xh~zrVpO9?%+(%W<2Kg26I~ooNoce6=f4ALkeX>$)Axm9nT8{E;~MF0ul&m$M}Mx zUQT&>FD~{fK6hr>x(nHpz@17?9+02;w9?g;Y3{C+g+{fk;BhEjH!}9n6?{!XoIqgQ zB5OXNK4t!qFOnrqiE-UA(FCSQC^DBYDV$a6)RRWE!1B){=<80 z^3>IB5iC*mUj?mxWP4E8w=iAf5uj5fik^<5?ikb+^`c6n%64%Yh)!g>2~kH=H=cFb z(iNAkkQW=*#q7dugWLjbE0%FgN;g<;UpZ@SR)^7}Px~cLwZ(L9qszvUZmch2c5^YS ze*E|E!RfEP_6eN+&QBRVV0wAy{U3gRHf7|O@g@yE(YTrOWh!Iep=RpUj@KY~Gxo%vrX01C|(ADs;_4-d8oRpyNQY3mfOKn-(a?C#Dh_>i`g(JWMP0_tQ zaz`fVr6u|b_QHK4X&J|0@Kj>{m@5Z>nSuaKkfVrCC9hok#(%XuM(=EhgkH^}Oux01nz%gs(=y)(pCJI!M~81oXb zpvPZm3mTzO8%*t;>4qmoKaWSN=@m1k%(EbMEeBKPe3&ud8MDhj&7uZB_ITvJ7x2zo zsE1|>KJ0ei7iH2iI~sH)TSbF{CJED@a-Oh>!5i(Mb${HCL*JpGv;8FMVU5$5&cnQt z<4)14GW*bCJ|7u%Y&CtHk9pirPdj4U=?s<*E}OE@`ZONZDbA6McUxbv>5IYqFZvLR z5zX0V#u`hr-sfrbSqkRpdd9C?Z@-f3)p)P4f%O2tx4~FA$k?$kJoSYT%T67h{ zg@I){siCtXjkv}TrsHr@QesjP)(7k?ZnzDQr;dDfdV6+#melkBO8&89ji{ydnf1l- z;A&=lf{XI;L3c8Q9wK7ABEK`)9R^5pN&UzU^+ENe^?rX4@fqlwpO8?KMyMY#AO_Q8 zC>&O|aD9x}e|733TTFjeNIxd0=j|a$rn~bbm~N@*{ex|HmGZ(=(NN`Otky2lNg9&D zbgbxwbpmw-tQ$M}bu8$8a;)D)YVJ%AP!_eQP9PtYUhGAb(}aFrsB zprrTUjEO|*QV34x@7???71BxaCd4Plr>AYCz~+js6%^mRXoLCZhYk*&p$4lV_I)Pi zCDDb0r-ehMfNB_*4pT*$_o-Q((&GtE$MGV0p1}wciNhWQbs3e2YR9}|ij<1djd)M7 zO!|iaO8ItDakfygl>r+ml0H#~KIi;_-%pHAd~*K&xl-WNDRfQq-;zgxNQ$T(H?k!t7wrrs=%?t4giK;E zwI)y;r|g_`Z2M_x0Zt?&P=_dlIxH*mUOPS=sTXmaMoT)faU#}m<;wUqR z2@h6_BjhrLaa@=88lZmTv|;oq^A@b$U7M5?ZV20d!kx}Dw+~|C{r(%ohZs%=N@+$< zCqeyH^mJ2oRLL&iHA=by)LG&OMcw2vBD8-OF`arshM>7p`%5mS{ojVt;dhx^^aHCq zDDIeCxGyHxFHL-It#Be8ZAqOMuv{-jMAx!`bBEC_QYV5DfBI{1Is*&*=}Kn&DFKb| zgXy=YzG^t#fVf5JTt_M0MsIF3TroEmwQJ_6v8B(0muE;zS9{!S2B^#MVmZ@|fNs9M zT*ZEi`5^B980?LDy{pPjn*Y21*&CWN{fK>VUj6dg0w}BuQ%TG3m0~*ro53YdRuBbZkYA^*KOCl(Gtje38oh)UD&>)7uU<|*|+B`TlUKA znaiG>yIQ7~%@&udq7hB8i|dfnX~f68tC&aQZ^t{2F=olScZ<$^hMo?mgXx0wq2mQe z<7Tno_z<8@^owF%Xjr`ocR5W2BX^kKiA2tX(KUJqJzeY8yiC-~WbEqCzqNAB%hTV) z7NZkYz&WZrlz#d=m(!^dD3t% zKK9{~f#LD~ul=`Mw?+SgjgYF>+%%)is{(_{BA zb~t&~>hP0nWk`N}`F0EMgudp#(+swAdWqe{P<8AJ#3H;I=GgGABp&ON06!fz)DtUK z>zW;!TP;VckeWL&JIr9<@uIcTV7mQy^o)jc|4(@v=IHHjlzEv|*7qZ0HnEkEHQYIqTOgkyzrLdtX`V`jQ&(wyC47K*w5oJ-^g+M(s}!f`BVFhbBD2y zy*&06i1DUx8RuixYd!SoX@Bz2U+?SA9o|%>A zN%Xo1>P~QZ5(33pSR1IV6DRc;jh3mXu43#hu4DU3QSjS+I6G7meSR83v~RSJOl@0C z2h@e%mdhnZIY&*W>gY#Tq7OLIyK%kjsU_xx(3ZYK*Hzx=7gE#j;%lkx!<2scGF}x5 z?7-ZKgse0qQ#>Azi`B5H!>;ndu+ZH@<7$AedLtk{ZdW$UC^H}DVo zpU#MZ6iqnYM-C(2Z^U%c9+PvCv#AQ2vUTfIGho*ef`Zeo(EMtPZa%NnLQN5aWf?ofjU zRX%?`l}MYL>wUhUDm8H;$d?uutRDNBgVi8$gYA>d_7jAcyn{FJ$K@^{=Usvyu7WJ(-ORf+y28~_nqB` z_6>hAttPcMdPl1qPJbNu6roB^SEVDu83|&PzXd6sB}p}H^t<@gzx!P(kwWPo zi_&FGH$u9je1qJExJB1d@V3?%UEKn9L*%hKyFqnb*-iK#mCzkhw*_?eET4yG>7 z$A5{Q{=s`6{P5}Te(;XWIPVG5pI&%-;q7ViryDWc7SjdmV(!?+3iD%KkuYv->Ed*@ z;xvxY+szYrve}PurlY2tu6zj4?QXyC#`>U|d*x04hqcTg#hMOc6ZC?WK3QQN46R)`Z!u}VRZ)XlDckPRe;(mBl2z?6uT%o6&{o<`+x5#pwv?^0%{+2B-J-zDsU; z(Pz@=;q(%eboo~V-sH7NSI47{n*KM4*Tlb^MnFg09>%jy77UX-A#$<~hyTXN>&z-8 zIDH1Lmz8iiP3CoDdXb0@;e+bu1?viCTsrU%C36Q>Ex5g4@$#ah+x9-WVDFt0O!!3u zC5sNfxfh2yGe1pZ=BgTe4zmy4>AlCX!0*`3Me#(VU&Zi(nyysFrP_J$s{qe(CFJq|zkW`xjD`q>->GlWftA>{{m=56vqj>!Iq85=n83wn%&$+}hJsjE#FLh*~ORT*rz z+**wFq1bE2ZpL2XzA2;&9W`B}hpA=J?N^!i$&;K;;1TsyLUfDh4%PGd*6Q^vIv@Sl z9!+#Ff2;*m@fbP1Vg~>D)0WHLQYL4XbrMDEbhsT_Q1f!f9J_h@);g}W4d1YX&YQ2G z;~%pg9rxqVv%S%0o2ZqC`qFuLGuzIzK^j7tXMdBU-D%~9TH5`1A9L)mGWzMU^YT?# zT|5=uGINr}yxRDk;vC4hw;6kwCHh6%7hiOU&-wl028MJh2{AdbkE)ou30-bCxSH*% z(0tMpC)yf(jg6Hk+xr@ih4xVhv#((vQxxOl@i8R23ezhav$I(jiBFP`g}6ZE^hA)X zlH%))%&pv4npK9Ho|#5UOLn8;u>-{l3rWii;5+svWFaUvgIHvFP}DskKFOPu0+HAF zE331QRZC5eiwnq`P8MLcG-awA+1zb798$Nna!8#etvvO{8!?%TMt9dXc+(MsTfuah zUJeZ!Z+ibFFulM3dS~lsW$ESM=xC6jM9pmV`CWO*?xc+yk8~41eqAx@OeTfcMd>}H zztkm%q4dCISP}@N)DP2QL*Ya>Sjl|L5Wy&%2Vk;gFqjuc zVPbmmEI_@>dmw!yrw^=@mqUZQF!%`5yH6ft(r#s;F`tK$!z~_6FHp1QA%L!;>GUeH z++})USdpmuvy4%~!7KncV-n(hMtQlPu4zb4R$!&-KY{5;k~o|H$p$I9ma-UB8VyzF~R$i3w`NnH309Vaz8Qi?uyRDp|T^z`%M^lzyG>BpjT5M4sLXWa+X}e>?FU>fMmo1CUa{!TFN@}(Us_T+H)fx@(Y~D@`D!dV9Z0tw z>i+{F-MT36<>U9>|NngFg%2o6`r12~Uf%y;HW4S&X3m@kVB<5FH(eK)ceq*M001BW zNklp!|7!c{4Xc(uMX@fLDb~g01x385V(3$ISMA+~BXQ)3+BaT7Pu^l9B}r_72=x z(mOD4Yk=_pg-DM>;EVupn4f-&kak(%WtS(yg=wzFcMhc&4BSLvKYsIFI2}?4$f3-xY>ON@x&_vTD0;gQA{dZXpWj{qNZnRIjVWl1J~#;>W}GgV(jDi z>OJN>U*{VZai9lrCs|EwY%P!Xab&Q4tm$RkzI5Jrgl(gr*rd76zk_IZTC+i|LmBU5 zj>Yuor^n7$Ikp_+)KvFT`7}R*Uxv63>R2MAiqgyGH)nC8KTcGVi^`hh z4g1ov_f==_%dYpgd*V`yh3V2#F~w8D$FZj4XR#G?>&Dc=Y%z|Ue(Lp8 zEiJ9JJtuplrVrk=)bw3vF8$)}bxtE(4z!Pk@{*HL+j&QYfM?hKa-u14^lhj7!i$D~VWS8l@;Hgykg&;l+`{n2JL^9L~k1g6Snq{{G6!ys(to zKp<4H=|@}kq_&VwpB1cV3wa1hclo_!I6|Weu9S}6*jPx!iy$2zNLmugEVYctIhQm2 z+Sca`q;vh;)@x_K{PN4TO%WnxLeyOHRi(qd;`H2H$*4(5bzy&&zUYv8*Nxp<@)Ob$ z6OqyZb>#FaJTG#&AfT(Tk(oc*-Q9SxzO)@#o?=yrSX07C=s{Ih4Td!cLAdp&r&nS* zXUxVcSb^wl;I2nbZ=TdFk4<@&AUhc=KZCb)4euDvc_U%hh{_w`Z}FpE(|?TbfO!=8 zL=(P#C{_XuwgNiS4C1ldp6!XCWAx2+cXgejG~T$#mLnQ3V? zS>_o=Nk@p+ZGE8qa(kduoQ{^BY9PHmFv7cc=Lz-`Qo63?p8e(N$JeaA(UqHvw$6kH zoJIEE2K}Y_ts8$pX=Vx}26bG}f>+r*RF9M@q*nVL#I9eORnkaRNU3n7D8`?{$B=mp zr0cGQ-lFTjGFrOLeYZ~kM`K4VN>6cpNTtVn~XN3HQ)s3DmDmRe+ zKUfl_|1-Z*_7$K0+Q;Aj-X{?H2OseB+WSA5etY5cY139Nv*=rltqb>TAlG^=KW;A0 zTJ?pZ)U70SrgG|mZ>x{&Js_f+38W6Ce_h8%Ph!{~)WGuP|NVl&^h^D~Hju90<&@i8 zy#Z2R`jpJ*D!jY&DekP&Wz~kgb2nH}PV&ly-Me;QSclb%hKw#}x@k+mbn1wfY{yA{ zVF|*wwC^P*adGv6+do-|nm%Xdyk$?x^r8%QOGA&sKKGBVBg#?cbn!Vi#+?qn_p*~B zCXpUx4ymE^62xgj&V|S3hbsx`cQC4B9=Up0ev%=hqpLQlNS)9|ZA!ytauxSFK9`qY zp0j49OzJDo&mj5*p9^R%!;2Bq<$hVSX8Q1sTdRJs;P%2d7j52ubZyCk!=U+{;{~Li zGi!ACcrPy{FdumL=CEF9Xqcpzp~JGf3=b6$>N235MRfI>ckbQ0c?(L%g?@VI=D;nE z^bT_SdObXR=N@);_OkTwKMkxM|9{(myR}xP$c%;4`RZ8olRA}eScf@+ycv#4Y(+EX z+s6fdEVCCST+Z3l^yF&p3qzx1G-=W!c4SJt+fHG7C){X1j;Oml#%C;uT##k9TRmlR zg~eJatQ3T+A&)xGlT+C_uEnfgUi+fN&IMCudd#L-%N#g1cYn{TJoX&x!eBQrnmuY* z5EWV(q?rEP&(=-mrQ#6t?P1JHBzEhVwpcqe!xsKhIwO^bj&1BE?lTPmdN%K?AEqqe z?b5b9ZtW+A9a*a*(ST)Bg0_k7a5t-WYRx2*FP}0g!`jK$9gW%ik9if=(NBKHoNDkq z`B+5z4$qivsn(l$EIRzt7sZT!vpQm3hkYefSXmfy_qAf8E>6$%5~SYoqmBw@f;N)z zQkgBoGd6VOa~8296Nz10SXz@=Q;}boEY4sWVU^73b;#*tjgU}+tG%=ym&JTAJ-hT+ zUuSJ?g=RrYG{uvvEIxOxJDh~V?kUdlyHJXgup}qD(tHj3s*h#Yx4VNl4}|F}($akG zlsihb)O4H4rJmcYZu?%e;?ze>BGqc4`s=S-+d}oI=`DM5@*$^_`MxY|7$A-4rQ z%*(@*PC+ANPETr3$lgL)CFc>++d;t5N}ne$5|m%T-_n|MA}5&IdLl27)lw0cCg(+% zqNS2pWkv5xuFP(%Yy>SUNvZT>+lJHY!U*Hc;#`r^we`7cDCy7rT$sM%xof$#O&up{ zJqe)(1!W4;6=WV}SVXl_x;8gV3XA0QjQNohZCfJPqT}Pcy5xGP+IZ2iyfA;%SY9Ni zU#xGg98FYeOe4qS_Tqsi3qA~qE47_dASskSs=`77Ml#8KB+ZZoR-4fM1dm1s!R3#m#3MKjy>NDqO z&TmeO_tkTHfwv|BUB)3dV_0eFE(R=#$mqDzL+P0?x|%#Mpgo>2b01FUOEl6xf+yYK z^Z<2k8J^IQiA*oP)^c{sKdt>z=Ut%mI&UtvvNZdTgF5baX;IgUoZ1ALJVEXtz85?% zRwyH+{v8B$OHoHgH|^u^y&%7fY8sJ_XkEgV%iv^n}ioDFJ0~-)9u#v*e4LBbFDIW><@}5 z7Hh%u-u{0fHGT7iwHMZs^s;#^bCO9k7pliJLRr){yuD$=_H`HFWG0EOE84YdKXgvS z%VwcFKbqvp^VeNi0;ca>0#j4x=mMT{FnxJ1;p#h{T)5!&)OpKhzB=#x-_2zTDbrBx zS)(?l3(t=p-7jbQXY1aD(2MZAa3h-6XrT8((P!_z+uK`m2l0Gph*_i*BfUpZiU?hI z5u@+iDY;W1pUG9>_>e--C7r7&Ufqb^vYEi~Yru5W^p!JL&X_S}2GEYN2rS1fBd?25 z(+#DcpLu%eYP9q<3l}V1e{}Oe$>GH%y#pn9&)Hqc@!RqTknNb*;g4(z;Te^CE!H(BCY zt2v$%?^M1-YrT`Qw#=KdA;Ug0<{84G7B&f;9Riv!O9F8lar~{8QaNR(#ngJ*xI2Qr z*y_o#t*jT2NNVNgWkKm%46o@C6U;tsQ`w}*swvCtVM4|ZZM?}m@lnUsp-rYduJ;5T zuN2J1EuAtmXrA;3UCmdI#X_B#25KYXf+#}HwoUcv7H;MZn-EqDzH(Poc4U zSE(}=OggARM}}5D;?VS%L!r{V!}fOc{xoaRvy9bK9(!u@Gi#?iQ$l&Y+0h-Ey0AOY zn9UQ$c4!7jIlTOqc{-S;tW{=s@pVTN-RB=~K`73EZ|D9O=T5dx=44HO%nV-mV$I>9 z{q}1$u{_iMR?@f5NtFzc*ZEGe+Q{$+r!2ES?@iGYMB{!O7kI7(*4B%R*O$?^8m3nf z@n1aAwsu+cGf{6XwKwTtS>LzuKj!g2JfLc+e*zqYDZ;`~zTAsf4@{gPC($lR2Ltz$~I$s`t6t0Vrfcg?HeU z%?;<}lEGLT33`C3#CX)_6-4wU_|xj!5$-ETv+Ef?q?roz0SY9Q*3_4!oN`Pr^0@q0 zM=4j5i&OIG6ge-y`i7myC`RWQ)(yUwyu3)H_K?bu_8aO3(g|B^8g0Lf`<^oaQlPPx zRG7eXk3jr#Ylu0bJ$2VFojF4=;ZqW%af>)3?em#Zbn4N z%y4fYjxmbpH5@@7uTxOE=v?iru9!@E?aMEJ*_M;*;!xb)BnDMx4uM{=osvf`U#KD+ zkTspcLo1q|*_|JsP@I-nh%dbhu2hqrj^$-=Pz#@Tcb}|ot`Ci3*Owkn&$vl6$8nOI zCs~~tq?leXr!dl@{w!iY%Rx>Zj5b7wzX{+&(LY6OFDaZK!M~D7{n8|j=Ga-Ju!^#* zf^>W@sPZa}g<$R?PcqrfUO9IV7msTND|e9Dsp#)+#%{EP#AMR;=~QIngh1_%Ia3~6 zHGe)MJQ6H1%WLkb3)@jJlo+HCZed|*DMlj(6$*dEwB3+jA-S5}@=5qSxWwV#ET%O3 z8Y07QHKT%UXCK*ai?YEFJHZS8{vi&UR-kF5Hq1KRx^S@QnyL{$dMibikc#| z;CxeOZPOvny+~`9oNhGt?mC0&_@oN!3f+w5JSkbT$}(paCnqyd;;aqfH)#DHdXJ)4 zTIA#c=cLlp5^(&a6wjJJ%WB2x@#)nK*=fzQ%4U_92ioCuMuNO)-k-*kfy;S)d847r z?#qlec*k9*zO22rf-@~!&oVtBm%3Pfzy0Syf2XYWn7Og8wK%q9Js!PwNL`F-_!Tvs z^mHzoNJ=y#l#cU-i&S+Y8oBze^3r8Xx3qL?+9-r>C%uTRk;0Y#VowPbsE;+XQme*R zvpGMOfX;1{%Grg(=UTE+U9S_hyg=yxY*V_!>F<2}y{BIzL7hhR)F0e_X{tbd>KqfT z$on*J)F|kW+mtSP*N=5yoc>KErCVW)Vt1<$GDwfmZGnU6r`wz7iRzZMYo?^IPHn^GndUfzj!qXMwn)V-mxKx136(>zG4I7|O8XP-H2&3gH^ti&$Ow&df}pnR^o1RozHd z7p&@r)PZTO)Or;vU3s2qqc1O8hAEwCq~|A3o?^`&wR6*T$5Pd2uQ~nF%ry&7FWr1} zd%>c`hX;Bg>=O1hbcflaWVi^u&CUhfR}sxQihGn6#R79$Y=Eq#r-tt1OsaCY5sJEL|O1J+#{Xp#J@CGA>x(r|FQI-O84W*PxNy9eY@Ov=k1VZt#WYO^+h@!#e^Jt(SW|=JoUnLXcrL7}ZZEVE9#%r$S{J9EnP=qGAQ8JPh_#WLId!_aSP zu6B{Jcq}YtypID>{{HhA5BH^gB)T~<_MhA|b7F#Z`Rrki^_fi4Xw?i8#{HNd@#%5$ z#ctaB%*|$B4|Ph+QH;M>wr5k$iH=Pk1_W6JxrCo<3-gp#UZ=Ji)%fz<)WPf}@ge(hWbTn7x zb;CH4DkVrZHdfa#`xH!{pXC~@+_x{$=TaV@vOko>7$IldWXt6xS17k#Iekg+6xrRG$chq+NtifHI+L*QBO5 zeHjTe$FjlekpaIbp-FWI8d1*0=EqL{de`8= zLo8C~=wu^_n3qQhe`k6lDLn2(j=_^+z6iuj3J!@(Ou(fS@>0YJaXm52@XOsIJvV?~ zTrur@bi7KK69B+AL$t)iBvk%LT_W#@9x$99=TCyu!(e))tVVp#sBfF*S5!_S{l`@j z-b!ns`2wNjsGK!o1QRO~&1bHHQ2gQ2hw=bNP;8e(5|=)vju*X~j&~ zD0U_L($X2V$SuX&bOlwYRzsD(kc;UbOz=%eC@$9A4qb}VNc{ArXJ@C?Gl_IodEoNM zNZg2DGjZuGzH=kYt!Tw~&sdo035;Vr*IqxXSqsl??W#MA@rBPT!T!7H{6+a4Zf(=c z;~=Wd>BgOoKmA+Zp(rV8x-F+u> zn{V#x^s)aj?pr;@{v*D9=URe1d;7ukJIozLNava;BdO_dx=?+)mbMGqx3AvG?G7q~ zQeyPX?$36^&Zy~_Ua+RC88O_Xrjy5VVafLGdnp=9G$W|4_!gY%R4YBY`Kbj@-lo3M z%qQk8TZ}b*?wFb`HQsKL&<&f*?jnae=x!cj7|{C_>N@81J4=j+eV2Mc%oD}-BHOuq z>7sPG)&XcsOc$%e>C`L2oDQf9tifQ`;8jO5e`_Tg`pZPFo?kN+SjYAvG}rV~nOy|w z;`Es;zjXfm)HMqi4J8d-v|#yn7Ewzcav$ zQoU#|wTvil)O-ByrQ^rBFY)~}88pr@!te#eIm$aj%!`iqp9&lj8UKIXf0MOYTQ={! zU<=ju3uc|Tuygr-IV576jUlnCv|M{499{L`+xe|`)WrAq#H9Qe$9dUFk!RNK+}sg` zfAeCoFEsvfrEJQv&>86WbX?f6{26cbF#nK+`Sa&EP7AY}gU^_8%YrTHE|ou z;4|h_#`GVV4=;oGbF0lTl-_Y+p6<@uteFR-uPFYH?eeKcM zd;25bWN;G2YOD0IZBkFJuGNbK_nSBJ*y#5GQN%k~Pu}1*fKqbFO zn_e^{#|3kAFN8e^e$d^-2`lkGf zkP8Vk(iv%RWv5p|>3w}z&#S7dD${E!JNp_NPFAOt`mb~lN|&FQjXSy!XpsK^;3Rb} zH#rffGk$b;Z77kv@H$dNEJjB}uWN`TW2I3+_L1~Lb<#=<8KN%W z6V*32H!l}?8)l~lXDzcGCHl#xG1}lO%^oc*^#xGV#g=hW)2pjxO?T=RQL#uOxzi-9 z1Mbg$ACRrGyJXr_YUvg(;!GxZ8bbFb|(^X}Zi6i2V#7 zLcx*t)TDUo2Sp-`M{*0}T?dlEbK{7C;-vCI;eM3~yBSc&d%?&C zi-<>dc5E1N%&a8rB?&FvR?~rW^z>`bZEZQbrxw>bvoGBdcTyM^yo)KjewdAlN0&7x zHWCSzBc*4Y%g9Km?RcimgYB6aq)Ewyya>`Ea~v;&O=h|Kz;TQ5v?YDHt6huOa7k(`CXL%$X|@I6uvo3UC?g4#LMS0nZfN=AGKSl zE+9Xjx`uCzDmWd3CeBNFWN@Ja;c8cWQkc3(j0qFs!)zAvq?I?9Yf7a*zk`}cOh`76 zE;ZfDbbz2=BZA7pNM%}SJfo;MUcs9jsjV$!s9-4F$8-XwGh06Ic;Gm>fm1;YH90n_ zRMjQ>v-IB5%IEtz-&4`HbMuMX&I+Ax>N|F^hEh<$%vXwj!thJh$tb>@W7;hv;9E@fXHtM~66JPe|3c({ZSuH-Rt6>8R;e z1Jb{5LpoCWPk;PZwlQ5|x{=atFf-b0~dqn zbO9GNvytI+YhzZahfEfugX&|TPN!SMet+-Z*X#BNwR-3BwO`?R>HoBUV8>T$*M6nD z;&fnqr(|>*Y|e!rQTmP@Yj=>g$Q({c{lfascJJC%BsxbBH;^vVi`w$_m|mztx?~$_ zI!TI0zv@-;i^`2|{=w`g7cP8a=A3y?Ec=0(LTah$#xi3;x@M5lU~>T7ieo%#Q988G z-r3>1?-pTtd0taSHSbcM7Rl1WZ?3i4+!MS*y%wXRs8cHxG*=c3>sV{F^|vTcL@c8c zURF+@`7*iblO>)THW!|Y)U7si+UfIaX3ku*prl|aY3U_UI&(cWIh5j}W*R83#aQ9A zsamh0}%X>{XzY|?IxCj|Da?0ZFeN`w&T&S^xN*{zCHY2Pr7dp2oX8D=|CdUeeB~ zbDrEUINm>X!H-O@ecjQp-JhgYtOj-;TXcd7v7bRygCn096 z8cRwy2efIGcz*h3uYGv6b5Cr3N~>n?wn`?N^|2qv=9Kx9a@ITh-(){eH~05t%mZ4C z+dP%ME{c9%quu$;q#S2wo6QK~fsgrXK0WW_8|E&WK69SVuBh4m`};cOfx{T*?h4P1 zEeC6B(XShPeq7i%f0Gl_<9#@Cs~bmMJ~u?D@Y%Epz2jGlZ|2+RaH3e!i-L76B< zIQ^RKchL=MdT#BF9+=ILECV2D)JV)pB)?onVXbU;jpii=khjY)r+1|t+}%;j{KVqo z%!E3EYmDXPjEN8Rp4Blx8hXmrI4Ju?$Rc+#2M;Hc@c1@TF^=zP?4Rg_{p#mNhj`IAY+ zcPAF|GT7H~1jT2U8lQJ2mUrSHLxt4O#bTslsmX;2#ePyJ17*bt!Elo2;Ofo!B*COH zRe*Cu)s4qGPf`QxKqrd&5kUQ7&tO~6#^NrbUTSNb2Ac-kh~n?zv$RU?txozEjlXO?LUyapw5xK_+E18%S3dC-HvVoc!{; z{LP#OY{qak5*L?B9u4nFRwDhw^Hy=XBC)ZMicq*-uAS{Ud-jNibgEUm^;%b#{f9w+ zM((4+-*{i14T;01;rV#n*wYQGi__85O-a)4fB$3bFH|%#MUDPXRUZ8-lysw^TY|d9 z%oat9v48wm_p9kPqC2Q=Z^(_!;JOi-|B~x5uGfyV>Da9;w_7*7sAYfQNPf%#3DV6K zndyJeFU3d+WqjfLuf8<%rI|Bd!k)fT=q*)TSC3nuZn3&nswpg8*ED6j%mdH`>XOtg zNVlTWtsYbFsngY>3)bE7uk85|X!yKoV> z(=fDbM=CGc{n@S})b#zk&+PtxC}3n{a6{_MBmD~7%aV13sw?Sb8yok2)qB)Rdsz;r zQ^r$j`ZU7Wr>@$-6jH6TxI9KpUx$P)uL~FRV{OojDvzA5VD(<)^pdxR-vYGJuYp>@ zE(-#6SlMa@ghk|N=i*|tbMv6qL(@z>JeMlK__Mol+d{;~;Aw;A2s7+_zs zX6fO>&mTU#1ZBM7_<*eC_io{P!T6#Iq%ijJ{=3JiM>-5~-?`L}n9f1)D?`lj0Vavw z>p#w+XxIRa0sWx@0DVA(mvpFT`B$&nAJl*P8+p@>TKXTLC(6e(T#nZKH+BC} z$7PMB>X}FECwQ#?)9&BczBgY_8E0R5_`%f=-gkD$9^zt05YGCCZXe#kgKKm+53YM? zH-GFE^ULn**>QKTFG?GaJk-ag%ga;lJ7{seR^7Lf=URIQ`Yvdm0MZW?d;zkW^y(n}Ycaz@L`>*MPZz1Y%G`N8b~f#=4G;dN0|)SE!xAm-v+ zXRcwQTooLy8wa#Mm3f9tO$E|hxZ}s}(w+(tlW^&(1Um^8feXDz#0L~+f+Ig%0l<&8 z1{I;#lGoA_agj4fZeVf)(;&%Hfh6gaDyh4T$;Wt-vQ5}?9P;xB7=|grq{sexHZ6Q@@f2dSvVw<%!BI&86C$<0y#FE0buNg-$e~!-8j$zafqH15{boB zBBjalG{0DSI`QT4@t`~>WH9@OLh4b5LNqZyIgixM;u!IU7wQpAC#pY+Gaf&?3nvd_ zC7EGJT#O?`Tp=y}MbQX$9Itgc*?z$x2ru zUqQ;AGGUZ&C%dWlB^uT>r!E+hAh~=q4*WJ5>sfWXwYkK4eJuFaH?q&C(LvVWLtmg9i z_VgNq=_K>`vfF)$ym`W2mdcwM zkdvRzThvA5&5a#>uDdjHZh&-4N`HcKMotE!^(1XU>fbW&)|@Pv0&+A3$K=v2!^!N0+Z7-v!qTnEu)BGs0AgqaefJKGzUIxtONXItkvP|Yuf^!PmWnPSHxEjlJ`F-kTL;h; z%_vG{;my-;t&!`+sx3T^n#1Q`ehAI)TS3{;!)u-&URQMU&OpKOTf%R&bfVC~Y&mbP zVtFy*I$17vZ}#If$AiOBn5v|tFy8CGhvNm)I+d4zaojf?6#ki^;elalH7USxjWGT6 zY5RlvPk-|p)b#)K{WH-4b`Sh{eo@L6F3Y;_Bc5g_)7-c6H{U7CZ`;(A6UoH{UQz4G zvf#?A9KGU%L?%H7N8$p3){0pc_2_0ys{^+wRSYl??a-EOVPx^ltd=AC4hcz zbWRjNUwdYGacw?iMa+x4$|b0j{aiM6Y%~-#%C0HL{4hV@Ls+k@#8;E8nWlvN#a99M zav+dpt@)1N7|p9^15lNP{(3mQ9oMbY_>8#rddxZ5ake*I=#A+`H!d8(FP2))2n4Y_8A=xj^9>S;BgoT8cVrfBNaqmLjKK!O4q+`6nvxEW zp+BS$Pv*UfT!HlY>)j3MR>lw!26Nn;?% zzAC|f;D28w2}edxuV)v&5Z^)0>|ki(1B>@4%s<`}hlvKae9q3zO>Imx6);WtY zi{KU}7N=`}@{DQzH4#Gb41D9#0yd=!=F?n!pWK{>^6)XXGlGdDK8e7~@;JU~0l&L; zR}l__yG`AM$yk`4SUH+ZsaOr?a*@%^Hw8_dyY}CShq3TCudyH<%(OrqMIBC`CmdC& zqx0f)6Zc}f(!cldCx835HWV9gI-qXcFUF>BQ#BMVm%6Z8fX=OBUSUy)?lhLQ5l!;A znjX~>zvgG`R!e}mZE+Ej>o80TBiBFG&v*^@%R4XJe)XmEU^=4u9Dw|BAYHJnIinV+ zTROSkveb0Fc{M0K%IN}i{h*~kVe(x>=!VUskp5s_$3nZaY=2O5SHHb;`x2??1qIu7 zzHKo5?d@;djBa9HG{2c9n|cA_yAoiwE51b(-Fty4q()0Oia1Lk_g6%x@4)u5ecOf) zk<*EJ!JCenP5{gjn0?*OCvPvfJ#EgMdEY+2VAb5W=gwWe*%8yFrX!d`=(ZmnIw$PK zkh%eNJTJtiFF~Hio8Eu4_rswNiDXgPBGW|cW|FA9Ei#V8G~EGvVP%1|p1?ILRP^XA zTTY)mS=JY1egoEzzEy9<~gKr;GTirq4ZF8eKu1_>-}j)O;6BN*Xpzsl3pwT=f?b4 zD!Nu$OI#zTpHkS1Y4+w+CVlAfpUS67jG2F};j{=9JtsoY2j=^_T+TYAQ-r933AALUc;(g)f$539w0H`-VsVk4PD}~NTEznt zru3v}oRHcc;6<=Gpr^06CeI7a($XQYYdy6+;cL0MNh?x-cuF6cpOmdBob*T@MWiki z6uUhEbthrzSv@DVGnfXK!eet^jT$bB)x6ekaH0_A_Q`&vT&?tU!e5ZwscjU*Y~%Ga za)>9$rr2-31_!sVZ6eb$5%MR|h*;8Uye}845!EpaNiTOI7!9m%?5gWg!K1rvTTYzd z_BsLT2IGyOZf!DaW9F>PbWHBl+Uo3XEbOL~6_lO6F+DylGZW`M9IjSORO+ZEhWeNl z%Sk3zJ8mh4uEf%p2bdudSD#I-t}|_e*OktGAPHYR&U)rfsHH;cxw5AlF@43gtt;$5 z9b=$qu+U+{hn+BE8`?UsfldSJ#^PZ>T}4UJ)6c`{rhV^wi0PlahcDe=`hAej8q1(= zLpC^VH9K1o=C**_tTl_#HCiy68-3luc&)L2&E^zQG6KH%+~7H~`B>wie)^tsd2g(} z_TGCca`eKt&d-_iDuq2~z6z%c(XA^9<2HYb%Z=g1ru1(cOt%~_Vst&@n^Vlw94%da z7bW%BE`9W}{XuPbd-YEE*Ht zSFpL&E>L@vhUaC;`W@R!mhL5y(O~sD%^$_8zHR;b?MtWMUNG%8sp(IgR}s=xbC(16 z2G1|ZJ`>wMQ`(D^^v|sLbWKEM+vVK!zRMBxepoVu82+YYXG!Urj%iK%1f-3MF8URo z>)OF|77V2e(q%eXv*xhO>5iHXrbFp7Y(RgI)2VfY20t*M$)h)K;&|zm!{+#ap!??4 zA?^+J1LRWIS*0sL{q8Sr;!pR+w&X7+0Y5Gl!I2A+6t%%&%d^ z@AIGWpW|~j@m=otb9`eH@9B@*1AmrkI&W(Keccp(e9L|Jf7?6dDTu3*8qa;0@sYha{x&y~^9kx_!xuUu(qZEX!)ZoQI|H_~z= zr!^S7axgy+dDZx6FZ)I-M$*iO_I(oV>r~ho^jgdD_jl6O0RNm`GO-D=z(f{QaN?06BX=#Of%Fv(576%!X zViL?FEz(PrVxEhsj+iqD`5VpaLu)mo2{-Rp;&{a4M@1)PgBhV{-ICIg+QY;s8gF^1 zp|dYknMj{dyUFc^pCWa+nnl=H*U-rnUIm+@`ywLKW$~40@L()~gS-m&IyGEj*dqX? zT&G?qz)&E?BM>Jj-Eg`A^|ROD^w)E-r`Micv104Btv}=Ot^5G%DM_+YgeqMq#x5qS z>g>dih4+{E8QTid}4a%G@_cX1z23`)xm2NPd0m@n#CC zg%hI9qVf-O{cOEoX$=Y6GiFOrC>UoUQYhwWs1a(CWF4= zkS7qI5XXCsLru?1_U7SDZ))-CToUh*!PhbT>6{!Q8wRs_m93P|5`Y_CSG-GiQ`3#M zwiCp^FtPOdp`XhfgD0I$%@-KJ_x z;tr+TD6R*rW+S=1!tl4XY?HdZ53`w!GxkNkb3^Bn&mA}ynj1K`sQhCa&OfHWk=h5k zV)>o--hclE@cflI7++qUNi3s9-Hz14@UYCGwfw`e{b9Wn%ZWeYx=M)%1P~X41Xt&55 zkIPqL^b22s+{o!mzFNOz+ujfNZriqvYDB%g7moHin7(Z(l}&FioOAw(88a8pRe7W3 z(cJV{Z@Luq3$cC|@jF60pe|Xy_ubFd9qm1Qr(pO)NE_^yky|(proSvBiB0AXo*Pov z6=ZBgbP(7G@yc=;Mo%Y{QFBOfz6jGNGmrHAHvAS5M7t&sk*>Cn!&FB}$hcKt#yhRaGk{OTRW7B)sbk@9l zdg%1mKQVpe_6{$;5zjpT8*|T5X`0~V; z1Z8i1Lu;5f_#FCa*9xW8gyP9&q-+kZ9e?@!jIvp?GFDWa_|Yc!teT6qn0^vXcJTU1 zi_*b%FkOYIG7+t5ps+09+@Z=R_7%E=fDw7pvAw|R1gT&S0b*$wmnhnkoRm_WmOu&F z@-mXm@vti|KN4Z`Fp|61#Ux~@?|$}xmx}mrh93l-NK9|60+RXXKJr>caBS9x=Wp#(>qm|p`FYcqKf1f6!=O5(PArUZs51hxHaAa@S-tx@n9ZEi0|$73hZ!Mh z@KD2uK<+77!ptw{2KcAtNehPj^_oIUFNA!Jht8boKT~w(dP5ZlrxQTAVFLZlDISU+ zd0I{p^0IY>r)vc@vFyJcu|PQ9@`C_5#+NM7#I4`v$25T}wT`}NQq+y{g&;;IkCIMq z5xOYdSYBjH*TR_m{g+H2H4JXwm^>E4+^n$ILEvV|MsYA+Om6lO#q%+Ti?noJ+3~iZ zoLlYv_da<4eQFtfz|RNofBgQ(A8<hVPVZg69M=nedfe%~hYJeslnft!)A&P-I1b*z-!HG>25P2(zou!?u(}=> zq3edm4AR3TvYO8^5igoZsy6xjd4814h^`K?3)1nwynOz&a$WclPHWbutTocZrHxZQ zN#1v|7H{2@q;4E9AUTwdfUfDS%r`B#Ibgi&3Vtz%1dtD1J4`TdmUKlYLQ5%;&2H#K=}o;96yQp$_-raJ%C z{*EtFp7R$u(#mtbXl*@pc|;(71qwek0bWyU(J zFcv93UV|N9yb#TLF5sEMfy9jj+6nd`X)guA92BP+(~D9(&PKl6)b^vhd%$!E{bxMH z%{4UCtzDF(N=zWyn@Oa|>K+P&&dNBqA|o|t%a+>obVKRg7cr(^AN&+Cow&i1DoHwP z7NIcnXJr-}URIt9)$IXwWN>IzMt2l%94kqL%cS_p>s0Qfk((2f3X^l)Ogb%2Ns5yq zUp}93{h-I?Av4g$++&qF;$%u8BNC$NjWRre^#A}M07*naROjW|2vRuyaCx-pWy0#& zoL5eQ)4d9!MB2{6?jlnA}E9YG0hW77~>^;t~e z6{HGfDS$80Y` zb%DBJSL1szc`uqis)!ds`cMDze;7#rv2G1O8$n$aj{frh`YYDhC~hS7AOBy-;$zA< zEN<>-6NBMY$Sy+i7@;U%U|A6~Sj$pqKxtgqN>CcPZ%vnuF>f`rDXZY`6Mc^mOi_rvE=h zln5oxW&i%73#*s!Sh8cgnPy55%vTD8S%R2evUl&^l5KB(c(ixPx_6KEe#N@ICCiWQ zU;hKd^aZcZ`}VwPPtD!AcJ9(0$nZjNnke1kbrz1Aiy?G-2B{VFvL0(Xa(Yoerk6W+ zdI$Dm5J4t4&@C_ryjhlASm;d2OGiu&OXG0wcXa^*6L97#^63CIQK zcwVCBbOY*G#vya0^IP~^-gM-4g4&13Z^SG^ z`6Bc9aaJ83Adyjll7fE~NG+gX)78@hw{CI7$8Sw|)A_0%ykIJ@PkD0l!QT-}CN}@i z)&nYm`{JM5n+_;RlNe7X^UPgD*yGaQA>8G@z9>KV1sskr4w;XfyZkH!e&zD1oRM>& zcWWz;wO&4F)bvfGkCYE!l=gyt`*}0$n>}L+B+v@r$rKZE_ zYO=+!IR%f-z47doZ=6fvFw{~?Uc?*fB;c$i5zCiP&j1?JW z=gz%;VoOJZDQiShx+2qeA*Rdma*~^xS z;f#1$^l=jPl1MStq_oW9vf?=E_$V2P(EbW)`1pNphC5iDT*L+@6)Jm?AqZN$S_1P` zDGpjFZw%c{sZhPHmn3#oEOq&_0CfD?^RtQr0(3*@(7N%w=+FRufjZ|J5azwA3Ck$Z zoy2@#p4|?jXEQw_yHuk;(-%0i8c9yc_QUC!&Gm7ND`oxmkyG!|5Wvr|u~((hgqtwE z$eNB-2Fp9yIlgKieiYPn+%Huw##0A~Mwg6kFx~L?#h&ZfU3&1EZQ+&~rQ97PSiLhj zX~ha#P?zq`#^wqKj3crWze9mi`PL6yr1li?rkb`|rCJ1C^j=LGS7}scnl!1tz3}9r zU!UpkKQnl;k+2wFD5xr7*rNpM;&i^uq>8RcDDK)=ym6!bC&Bzpc@PoDBSvlbm}Pb` z&#^;cL3OKHoGxO;pH5X$Gm(^%L6jbq=>&4N>D=7t4t#FMuUKGhfZgcp7LF^KMd)qg zy3Obom0PfGN$9NMF>Pt?JB)4+-7=#K(m`@W^YPkiDC&so=5Y(uKmOo_AAbMUd9SQ| zW!bV<&cBN5!!(Q34Up??n%Sd9PM`P0JguF#`uSHKeeT;9sO$Re4Ld19T2%CI5z|7~uiIbr z%;xQ+HJV6u0lH~~yzJPvVeitV+df=5bsf_8g>}6JM7@~c^yP~&y*xQ{-uWj`(^v1@ zuyiMRj5uSI%4o!NC!didMvK+CF-4w$~$(t+Zu2sM2&0);xD_5?h{;1*f$s{vMN;i;hj4vqbkh}JUcjYj- z=u90|BjrVqPD~4FEj)ndrG%PAhwt5DEsW08(wn5GqnoQ@(eZ(Sk|E9m+++^vE&MXf z9X))j0N0JOUKC7YCc_RDuyp+9Et%D?-uIvEf7UxW&+LANpC3K5J7;3p@}Kof@Y}ub zd?l98Yx;Bhnv`25oUA|S(|-T61?BnqLH_GD{*`mm#!o?~tzSUyS6aDk<*tk^i0o+Y z$mZN@y>Y7b+2FHaI@FS4Mo9_1F_g?uhr`GQjpLvvtEL z7kn<&K0hIVgx*#5?Zaow*?UggqsTJLO%$Y-Xsp7Z2qjPf+1-iKZ|^hd*zK&lF^0iG(+T33(Pl8y&+1sE$h@fdgB~w`ni#Be8jU} z-?OJxsp z{JEbi6#Lq>v$aiI?tYo;&CSgHKWCsf$C-Kr@SSnBcBI6@sw`zGL-SsmxOobk~F0Gx)^8JLppN0j+DBuZs9o) zE`PYJEgrw-RGMGE4=4}NVQSDcpw5@bsOf};(p3qm%or?k3Z zUukxqhEVhdGcwVieJ&qUNNJ@EBFNBWelXRO@Xs)+z?!Z}vkBy&?y5zdN2BLVM<`i_ z@$B?$J|EZ_^NX9aE2O<}u>f7%O+q^LNP7-+<<=sk)1Y((HMTX~Xxfv@gx{Ydtc%MH zs+(D;mbz}N>#XlWUdOY3=z5d!M>QVkZY0V@&)ArDpfJ98Rx_iPdSAn_?(UPdtFED53~m^UnaAOZzpM(Nl6E~NP+3@vHz4l8V?`VcOMtd$0+KM`eX+~jrYaz zf@m74EDJMc_da%cY5c(ZnI75F&#PfA&fIXvOg&KTn2jk zKf777ZQIVd($;qp<|0&=-9?~oaNWr2mQ@{0->`l^Vmeiggz5W>HcLoX^&<$~)GB3~ z>9+0UyzG5`Z^`p3-|Ahz1bYg}j373K^;Jt3%$~hq@znFnX3Ts_hMH9b$JlB*lrHCs zb%piaDCxGQu6t$*sYy;(a7caP;+HC-CU!Eo87Sivp{bO z+!gh5^Iic7FL!Rqg|74$#Ppl%&`{nbW*tim+Yyrv`l}5sRY>INw}^Ow`fuL4$y1JB zU1Msw{C0%$XS0Y%nw_?N=;Q3^#!LDei#rTEd%t z`AR+!)b0?jY3vDwmFejgVpr{1XDvu96jw8+^^|Anz9?5HnP=@nBVjYorosc?`y56YQ1$^fL zLd-C2q1dID%yQ;X7AkcRlQ~WkW-@~5Kw+5jI-TP5Lul2Ym*q{THhsiPT^ld+RMG75 zD+oN*JruAE(Di%;WK^?Qa6y!)!DPi=UZ3Qec92`)Jc|1Zn!JO zJPN7H_;QW7`()|Bq=ob0__8u6M2eiAyJ`2CK_NL|jDtASnZzh!zxX-Fc(OW>m6g>z zD-(NqeHOlWkd;FNRn^dyjqf|0C{9O8M|t*pal>#nf%M66A`WI_LUF0&MtT@SWc$;7?oe(x7ki9L<&4nK6Y8_-0}Ny8$u?=G z@IvhXW8*p8YdA>+;r>oK?lM6f^HFV>P`=~1m zrkkJ6h8`eT#udwcPQ|0^ZG#8oZ|OSHboa~aKkw-wqw#K2ZPSUi6DLmGII*dTpvLi= zrk57$A$E7Dhp$S{q0U2{d~FUu$^_J{EAY+7REsev84{q|{eOpeqMRnZiGN@DM=v&|U{?nhJ zrvI(sbV0M4bakVwkICuQ8Y7(xwc&Ok-DvG*ouP1x;U93q*!a$KvGO=`CkpANJHT}F!{ElDa_4re7a!5(&T9LEg2$JX-0bh~ z-BwVrT5cC89qC-27n{%JdSL}OnoG*!h8^42qowc1o4#c8y8X}WUytcUbxL=dYDfe( zZZnflSMOc4_^A!gPhGj4SQZMAs@BnZ1oov%7c98_og=Dad>F?lj`S8Z79V7laV zOzMWnb#;_DM&^-PBD-OD95L(;Mwgy`w0G~jy}dVkhd%^&ok^rHxF~(d=<9~Y4F{Vg z^OznNva`n0-Vd)qOP{l5<;*$a^v8_p1ujQGhs}lOY6jB>?%u?fA~y@Vx50D_<;dyy zUo=Wk^!ag|=gb+Ebk6kA0tg*O$038}&RAmj=B--;XzK#`AyA!X4C_Fslv<$p88d!R znB)NV^dV(4I*9rQ{MS73)QKLL=z;(6JrMm%5MB5^-coTDcHuylCrn;9Y|doDJkE`W z0;!kt@>*NuhZ)6q9w;xz*wQNfoVI5quN8PjZO7U@(t3(~#>l7#lmb&Kvn#7=(reOv zAxJ436*b=DO-jIN9bt+ch8S$wxB`wf`uuTalKt?OgXz?R2P7!DNohx;5>qWFOqEEF z3rcT<7Jt3_3~Ks;D&$H`3YBR-a$+*dR>TELt4FI{xqvw;xhVZvq8SZ@3&d%xw)J!F zj3uX=&EL54(T$JzefHFi8?U$Q$-i_L!wa^TONY8zFyHIU0X;Bs%A7LbL__MSJ$WO~ z%EDiU=bRWucLUQp>ohYG^_%57=F5_BjuDt*J<4H0zHLEE2i&n-cP7_Sx->UAk%0N2 zD=2E`iTSlm(){eqr#KY)KeKEKjCLqp>TLl=&X5|jE}Bsis*}%UBkx*yVFBl2thC`<4jq<->bHi0Q|nW*WQE3yJ{?aUzc^X3ergZzlmm_KseUQGgZ zp@oCS3OEmIrf3lDdp-{M`LkBUdpj^^cWlbZ50#gDLS7fvZ?t$4_B*MWsd=Y-58{Y* zr1`T6qXE;yUY{!nE_fDc|I952Tjvg>R5I{T8tg&YQNK@(IHB&WmarF=UT)vh{9SY1+z%Nb>O z@TjMFaJlmlGI7?0E>FQyWIa=OtTn6$mW{s(;S!5p4Y?#-;B10p(rJ+So)n zQs$IyJkoO=x4K2?zua^qC#RNKrNZ(1o6*>%v{M%e>PKkrKF}>%SA(`Y>y(gA^t$?^ zy>pQ76X%7lU;lKFU?m@?Jh~2aZA?#3ORp)dVmQ^cvFkvc5S=4CV*dsCjkGwn!GlZ2 z_Tpfu1?i8AQq`oVf9pF`ApPLA_ue7(@NcDTn~S*;OUtTm+g=3kMiZA$-IB%)uA4=( zE_SuGfo+8`_#PX(=&0ypl>XjNv7V!r8$%0_PWvI6I_+s|`G-H`Rw6rFK09FTSLVGkZ{91*=0W53#k@g5y51(MP0>*+E!}Kk6nDkJnE9i^bL(Pp`ooa^V6Q%O z-~J2#Ppfx+b>~k1nSqj$g4J(hOIO6pPFY^$P1p2MmNo#>Ry?CXeZ$Ue>!qbzYWj=& zFDzfJvPav2ba6V*2h``zh1HiX+Pn9yl`FRs$#{XF7mVslN|rAD@b6|XT=?YTsZ*Iq z`y}W;chzd5VqkLO9l0`yj=XNgr<;4`${1dd*`>`(O4sGx-o0d}7xjM#F(YpS%J8>A zainf3)Y7R%<9cMQSyDRJiip9SZW{GQ5#ndOJlS|$EHHNvoqJN&Uxvn+?1`}jYl|E# zusCQgIURYO^# zGdxr{9BxA2vQN|AnznqFU@U0s^yxn{^5MrWR=Fx>`qhu1Ao$C)0J$7oD1SDs~_ z>_^{t<3`S&XKQP(Q-f5LeyJx-ejd&hqz3o2oC3^o_Ox(Hfzt}Sdma*{kGe=QL`SWv z!ZwW$h47Xtr0EdAo(oh`oE77^rv`&na)PJp~J-1hg(4XROPj+fDa0fVu+q zgy9C!tymX=_>}R8A)c9rb&0mxPTI?JTf5GB!-Yv`^orkU81>CZOo!4l%5ph(p^BsX z4pG=>@DNMPC1u62i^q;pel+N!_zyz!e4_s}f?ygdm=4|2WTBxCNI_@hfbAUPi)8C? zs0Fwtkp(e*{;XM9)E_-~B0uP*uxngaIR$xK$m!&~&^?{WRY|ZoobE>%kN5bPf{f#w zZv(CxVjIbmN#sSDNvfiwB*tjCfd2*^T|O6eQYbH3#Y}b2QqzHTnxDS(dnmyw-sWpY zx@M5Co-n<7AB9IlO#jtv*LW|lA4+uj1-!JhN=>Xt)L|%UG9j}pP|TrG?@F^a#pf;z zH#%`-1}l6QV00#UHa2#f84D=gAhdCqUxcCy4;>JsZ`^vl$Kr5m8~wbe_RFRlsOkJ} zI)M{LQH@6)#p==Ns35x`cE$mn5Ifp>XI;GE^qNCw`W37F>Ge;~oH<#^T#$|F7+iQk zQ#y$(_A2}{8zFQoHAgN!gy|3Q;cs5yfVvRW=Jdz$Xd6xkWWR-){t2A^9@9u^n$9^! z>Xw*pF}N*;8%77lNa>!!>3>P?$h6;iPR0GzknY`pw1PGFMQ{}eCxk}>3T2ARJ+L;fM|t@c=;x$ z4J4r(SGulfOf+@onyNpdjIJe%)1xXOOEc%p{D}qvt2Pklh~pfVUvEI&IMpq5k77EHVRn&} zE@QeOb%nj`U02j!baO8yK85KL$x+F{ZW&W-N(aXcu{)@4xZTjaHs(<_7o)$7rv5UF zzH-e>)+nA434M)t-BQ$FKEFn$adKE-Y9oe|@?u`bU^@Ix+BuSW$Vyr zbdne0ca0+kSc!f8I5$8%H>m7*+XtX>*;ekHHXLhzjk8XL=Q~# zz(f!H9z8IN+=v75)H{^ZK(*u(>k_NFI3dn$QbLj@&Ji2oBWcm)4V0(0M&dI36*)N- zEm>)q&FwA0_8_@{;7WXURbz4$RVUSw;^VT&OPrLEm5P?`MouSsoFGG=r#-FI@2{yr zrz}%J9pv;w3)6x0F-CV--H7Vu>e*lYFI6{U;wbHPnO;6RMUW%j^gTEBw6u5+-R&nbz5nw= z5r4Z(FR1AwMBQAmd_G`04xbF1K}?vv+&b#@_|Uie`U;schz&)BjS{PZt`^D@5kmr@ zLV|Kb^S(h#TAiDctj6}D0SWKc)R2Lb9C;JrM&qq8gew5!~|N#mA3_YQ)S+U5xrC0Wf)K6t9X1!=M90i9LAa^@KTXH zyAj>y>nDv#u?b7oV2MpjUEMN#XC~!AT+t~k?^~+sp#F0l&7S65=9uJy{qiJOn}MAu zs=ZrJ*byHhWME}g#_pZ%>ajO@-MZ}ptdCc06Dzw864Z#n2IF`HPk;KC?A@T41yT6o zxTDCxn598P3&xH1;CRmB`c`4_9n&R2@eDhAr%b^G-!m{E+J0aHImt3M|TbbyMd`?w9LRQR|FSi<>BUJQ;p)>*XN81u}7> zzr>yMz9K%Ho$7gHsLI&Z&?@Wn(9l8u*t(hx(6&GVaQil+@lbS{b4w%YR!;%Q;6GjS z+LrJ%@nonMzKe{i8>zjHlBd?4zt|h%*7&IW+4JJ}*g8BI9nqa-(FK_F!d9FLFuh+v zaz~yVV&jN{q-#cIapXj9Kjy@+IPD2kR5FnUz_+%B%;B2Cw&olM46_t~8#gkdgTi0! z3I1rj7gD7XIP7yq{M{)k+UtIz`T%sxUosA_%qWRNu7%_V5dHnxH(@R3W$E>DQtxlG z4C^yV5$9Uc6w(*5>8G^00>U-+N1%xX{SvsV?#=V8;lnbh_8Aax{wUmHM~r6p+2>yl zT##W;NzQJP0P&&{5wHgy0-W@myK8e!B*;ifa&%NQk@a$H|-9-uqt)Tx}mK~g6-y!PR#0AbMs)x8#8TIcTu7!b=6_{f? zm-S6kPKSaXAnr7z{>{~;sTy)zR9g{oj~_ot#hl9C;WkIj8Swi#!Q2a~8uEfE?Kn?$ zm3jY}xZT69!?*TzJwOUzBR(W@<{WW<_wA*i^pnxW+5ymCN-gGeS#PLbxD&~`)=!__ zOW~ID4ah2fOyVD@hkQKqd+Go;`sHw@x^WscX_e?C?@U-2i<=T9+28Kr-qIM*nh&eUMB%`VkH?F*A~{=~5qS$I!^#iuuJNl$BEpEV*FJRi4W zSGe)UkS=c8yxs_-2*BcIL7h8R(08rE7H&<=HnO{~h$6|Pn>BErnYO>S>{;3P(KKy} zg|@o5tGM{%ro;Miq;Y5uoyVy>JTvBa-Rk*B^(GYof!aY)MpCED%zv-IjC>d}x4>PI zd6PxtXv>X*{|DxbW3T!uamB4eGmH7yVg_5F#8ry|< zV`owmL%d>V5%03siJQ+ju`b0?bDY_KmT=$PtgcoMNm*JT?SjT4tgR3$7`2d^k_z&p zOCrwl>_1Sy`HUd%|4Z8(+izS2h1g3UFbu4IUdu{pP03Of@@4sM81_6sG_?mq>W%t@ z6Zi$ylXXthn^O@M)WI7aQhT)gY4F+u`G7#YN+fC;Q3-A2`NczP<-ltP5RO|yb}TsQ zhA_{%tfZ%;HOxMsr?NHflD5{mh)$e{S6Z^HQ`V>x`VSvQx>wAoLrO-dzqWWXJ@ z7D1tb?=vp_BPF2h)%rC(v2dGaMrNMD-CY!%`-B+Z<#&E>3cQ>&Zh7sBXzUJqLsNVu zU&$?DFY)|sg+w#`3Fhqo`lv4cya5pVcaJPvg|Toz1~(Q~+x0Z-udkTNY|fI%y#pj< zhT|svHiQfwkrq;pcoIG;G@cV<-M=rBD=R3x zqOd=I#-Ns^x_sWd3wW4P-wNCjt^v-=Mk3dGP)L&kb?>rwbRTg-opldwc-y2rfb+sKxRY{c`2foPScG zvVI)h*y22$3MyuNEnhg~V6yPM4U~B+CcTOA%@Q%=4%=H8v?Y~2lmF}5!fM6ej>?R7 zaISm*ff*vy?1savOZqaVuy*hJ4t>N1*}PSRq$>JcnKPqmrzhw8U$>+%y!Bo`dLhF! zJlD_G+#l353Ydy1RZ@S;4meR0_DLV1%`^ppx~y^iUOEnwBky7oe!&Cxj7ndw#!JwH zoOlcfCeY7EkC2M4r8*iTta~ql6{!Ny+tVF<@EOKG30bgkjV0!~7AInz#O|4*pN?vG zyB{r8CG4Fl`qTZ0pR`pnJ@S@DW$M45uQ8-q7`XZ0UaMC$F5Q&*(eo3@({YSCy~?2K zTl0jn#YE#|eN>?`IniUDHN7_=)RR4=m&g!!#f816kp-rZyB$X#) zlB5<%49-9;Nelwf^A{#k|I`DvOT|r?Tb;56o0E?$ zxnNi=V}!^qh%!S5WM_a4+af%jNi{!}8SWr!!#G+akCY{hiQP^-v+OdE^C;#gp?kSXBFRdwU|$Q$fK&RjZ#I$KL92Xl(lt@wuNP zR8D31I@prUHgsP2aeu(#*0J863i0PY1HHck5>o)lF_Br9r3Qv&l62>#v%1u$KA2fa3DJbAW)5j1NLghWit54gR}a`WUL+ZdUJLgVbAD>Z%rZ$! z3)SI}8ose?YEU7X6q;R1Iz`PFVvzE@t&JeQgO6qkYSUE=d+{!b`|Aql3agA-#u*U| zZBsqRg#)0dIdPi@mNbs6s_GAw`G+C}O^4QVi3AIy7z=jzQ^dI?yp&{yde*UmqF~Ha zzhV%ojh+Hs&h)x=pzFwZNi+`l2y^f6NZDk>I6R6Ei$gI{57>d}#psg5EPW$rqa{*J zOOnlnzsOV!0AS}7O$cbuVhAWnBnlsZ``%Sw<9^syiPh@61H4{XHa*%Fir?^wt`thAQ zajI2Hs-|LcwA>%jhZFlC*6(1yaSzozTa6)GK~_$(!*-eUnUCF^?GI^M$H~&p3!r#@ z+)s}Zc*UulPWuZ;Q!Wp=A8*=M%&HkG&AQ<&*>a|nBjj8Dq@dM=8%$*WyxT_C-OMMI zJS@j7c+qz{Yk+?U#l~PcmbL(3R2Pfx17~bh3z*P2+EX^ZMn_9;biZ#h3czb!;P2`w zf9TD50bgJ&{OBEeAXGkicQr`o$Xi8B-%`3R2WR@&{%Hauyzy)up?k%vi-!2Yxpqn1^224)L{w~R^~|onzuk&Avc*XF{5i6^zP7DUvYG_@T(}0La9aG}F7H2D zBGytoJNy=xO;t_+)jJhm@5bZvA8pV0CZwVQIW|1TwfX(QNfVCtD*$89+d;5!oLk)iDf zze^7ihDO7LaH>D6(X&;SE$f(RAvTKg*TZh2dhP~5rvZ4o+XOzm;_!fVt@ zp|^VOyVm*W?|ioL|9t-*KqNn#$ZMpN6EuKn7z$&gZ0@gs{ zOmLI{ao>wqPMr~~AVliwFgJ(K=r-EO23Cl2Z@;uBfw56oMh7|G*d8p?P1vnQJt+*^fWe$MUH`)I-QNr9oagi6JJHXSDwT_u%@GEszAW>mF> zcH>(~&U5|QK+Myc?jeRbMUBI;kS}hMymI(rGI*2d5>if~qk@&`$E7jl_??35dA}&% zgzKSNy(%fyNrkiZ*DtCHr|`M-ATk{5M`Uv#^ypx4pF2U6MW7`r zclzHlDd_IW)x?Jnwy~4hQ5?S_l2%(% zHgJ=3BX<)bL;g9Z$_wcldw0g5Kvfc;g?y7Ka<&U|3|@-`ceGxt)D30C;CjIFTOW2S zV@#TantX#`$O%*Jia~8+UR1iw=wajCuHSbBHdc~OC4^e0^6A`^<(BzQ+d1>{0|PJ= z&==HoJq5TDlb^@l^!Ec!A;J!HpcoXiZ_DtWDsmk^5})7!+4ExS_PcL$cRxb;_fK>4 zW+bJ7(?P(uPhCZ&l&Tvmra1N?>-ivt97;em%SM+&+40Y_<}9bnHrfrxk7000sQybn zvHP9}x6gyHA#r|#TCP)MynXVoy^E%+rr7u;%^B5+C?qqnfS4eP=J5Hg*Zap2=+@KW zdt((f2;HqW7qCG-etJ1(GTl>maOveeI$(OX+B%W zEQT9vmOwIYlW&tRWSsz$bf|sotS0AxGUy|Br-mP_FMtco95oHLu7tYX1)r$17g^6_ zm6-#P1gmUc=UTGO8ZlIIZqKZ+0UTKn0zSAfq9=Q4&m0i;9*U}w+Tm21^*)jYIt9U& zk+|iNF*gHvARY-XRc(y}$8x)rJH~3`$XmtOm4%i_X7sPQ4>Sezr$kGQlSB1CbD3l| zgq4)q*)feP$u0mbAOSd4>M56~g@JCRulIJ0S4J)8n}c=qZV!tUZrojQ>;-XyzMX|# z8kw-Ao|#EPq51g3CXyl07Z0|#vrZd2#z3Ek&dlzfF1&n)K306(^|{kvs7MHMw@*{( zo1kY&)%E}ETEQ2ZHDtckm{qj-`S*|XKZ@T8lcu4WS8}%@8ak`I!!u05G`q1a-8k#J z*Ej*Dxz!?to-5bLy)<= zQL3aNOpKU%2mDp)eoJt%3$>jJTNuYq_60q2&NnrL2Do zd;H5{_m_0~@=l*1|^4r%j*EE+e%p;*v8Ln9yhv;a2|T>|@$vPH}vd zJBR}A1)VZj^#h;i0foH}Ju?c0g7g5#*3^-vne@SUOjf@jgND4!g)ZS|0m&0)a@tSV zCK5b0&hUKN&!mpZ>6pi_I9CdP<0YxWfkr*6UL$p`$S17PYiS}_y4oF$VlfeEIDPjw z#bLs?`-fSjwxdF1tPEZWcZjDY%n))6+F`eVa26$zmnX|aIzy&WuzqT2iWoMPe}eU| zU5`;hl6h{|BIfX)0XX#Gyt8z~#3dDv8na(*AWzcp0LFKW;Y8#+>t9T{DEXfCZER?M zlir$&WXl@nICL0f^xq{pP$TEIDE0Gfdyi=|NcfOCDm8p(K)|3Ru#x(-I*Au6Pd!T zC7Kpcb_Ox|)c1X8OJ%>?B8pq3MTACO1aBjo`FxP&1P*4fQ10aq`rwNNs-{uaNAJM( zH_Ct@dY)p*wZw4rxpG4|Ze!fT9m=5A2Gy5UV_Suu!;?F@$Z#fHOvm>PQrEGv3DPw>1i5wk3FW< zIrD)_;OYM z;Z-u-RgDbv6m-;wO3LwP%im)77j_8x9p@}xUW_a{dQMwyx9#f>-u8fvx+qNv#B27N z@iSGSx)asn6El7}$~24f@6vRYU%o^)XO-kPVT%R`^1A_12e7=AbFq z%pQ~U+(|0lGZ87}kGA!;aHeOx)Xclkoqnch>ZPou{n+k2SN-4`Fa zj5jpCoO2H@h`#;NYA7N~zL@ge0J(0U%M<={p!e>-|M|IRekY;2$E|jc%(l21Bf)$Q zXj0qY4~DLKRey)wI%YLL`W2mZ%{@Fw_y)Z6`sq#9b)EbP(`c3tz!Jc-P}hnA$eHD7 zbblaw)=?hEI8UwItqf(%#W?_sVO;ozQ{{qze0O`GEDWhZ*(3v73QrLm( z`PM8SPestvpK(PMf5fY~f3*Tqb?6vV14gH9vK@_S+23=-V9Byeg1+fo#V>TwvTuew zk~6s3Fk5LhRE&n$%vlsEtt%+1e=X4}%Pve08M+PTnqWomRDS!4>z>3>K7vbMGi1j# z*Y7)!+Y<YWW{$N!O?eC8{+W;Gf zUp@)-LtR?;L6I@pRnM;D5kyqz?kgF8yqcMp6MkE`Us1NZvewH8QS*>+b;iXO!eNp?C#X=P!lK8J8T9XZ%dou{i@%ALH zBcGLM$L3$#Hv!eLo+~LE(!}mys-F$W`b*cYuE8?8PHPD@21WPYWIQ@n!+@(F1jR?+ zx)98O&PLF1*W`iW5?&&0yEy%!H|2ZJg9evb5t2$J0GFcng}=kCtR}=sO*xy&sy$bI zo@1p@DLa!1sw-~Ii{8UO{wk=}2ye_%jmOhurSWpaV>}P8ZM0nZ785CJhXi2OAUZ zlr4Zv?5NAIsQhUzqUyR$>kQOQ)@LY}gxDPGmX(UDG7AnW9elG>PT@=jaN z+Zrp+9X#y7$-$2d*{9i&AD){gk9kII9ri(aLVCq2tY~2MeM^DZj=!+GZmWF|9Qm;H znQS9rX7YxJ9(4Luy>1`G%xPly;QY7E&!5wXX5r}$KDWI}%|sz=3~jx|;S@hY9^^?+0t|{Hz#@C^-$+Q)WGq zlDt}tqz~#iVOdZ}t{SScRJFEtnio{bxz_by%5QD!)k)mo2Rh-#;^NKC;}h#uaq3`E z<71o`Z-Z_YubVWxJhqIQ8^#8AkA??~a&AtX2j9gCRe&cMhD+^Dr4jh-9{iDDK588K zTj=Ur$FbPhyJ9=FT!CW}U9?)4M%U1Vle|LQI5o+Fp<73qw5iA8N2x<|iCnSZm`+q3 z=dW*QkQOkuv$%49CT8|XW*Zn$Vm?GbWF)JjaK_{uGbEmEXLC8H%0R3NfQoS(8K;PM z%H=iDQ`!6R($cD<^p_mv4yL@W4+hL}mmd^4ebt@_g`VZIR}wI?8$?A3=W-rjDU{UD z#?B%b0au6*gckR+k>lo!+ZdvzaD(yjL`?&x#Ycna%7Ic%QA2|>(h_tb&Rx4ZZ9N4V zi*JTLhN{3|AOkS*j?iqhHdGTkZOS01)p{{6GiTQL?F9ptrnd6VT4*b2maum(i8mE9 zz3&ynHv?)kS70pBH1^Lcp-WnPu_fox3t(zoN?47L?%{_awCmY9q3Fh-+u}r=JdONe z04Py`hOk_lZ=nja8Ag3Xr!s*(GKH_fuA;YR9F_^285;6m&C+C3y<`1Z!kho(mV+<3 zp1Q69#fJO0#Kk32RCN83WMc$R2_%0EhvLOvD+`J+ym3_g=zxZZokXxEz!r|3lOnuq z6feJM*r9!PHUfRTJrizrrpX5~*W;D`i5D~}oI;pYbB&1HGE~OE(U$M-__oJD2F?jl z;g-cIaXrh+o>u(g$p~`bFUtc}LlFN>i^C&DucdV*4M?W@q(6V)s4u7}o=Xk)IT`T} z{c|S%&Mfxl;Viesoo2(^ru3@f@tpH*HZ-`N9Q9=BiX zGA$A&%W{s(a(A4yv#&D^sOym2(pNI#;fcOjvh_G%trLl)RYUi(S{8t}84yV$WDiVn zuLJ769{GwKbY28p2*1iEol88B6^XwA^V|1AV4zLGWf<_`U^s3RWrC~ zVWLIXiJ{zTG~u=L>qh#=JMe0;a>a6*m8 z%~{`meY-QD3)VavV&vgYdo(ixx_X4o>sgpJtfY#!Iw)e&?RkANKdI=4Xbt7XPyINr zFEf$@43_F={jzr=Fi|6uKHyL5KXk4(FkdyrDUMp2J+d3~H*mXI`YXZtj#QR)*C#J! zc5(jI<+yk(cUPF%QgaA!(2lcl!dw&I2om|wA(9lJJRQG*sy$9&y7TvMr|+a(Lu`?TUoO?w+|-v&>KKiJ7E=?G;2MwQGpc^T}r zNyGY<{dXa_t+s<9zWMjR8t%|(D0~C{%sIDw`olZ1Gwc!UEt&XK0^T{iXE*vIW|_0w z@%8MdsfO8lcNu@}rr2rIq97+!MB0A}jb%)&d!TEfAa!{4z@Jh$R=9@uMKfCT;Kez| zZ2;I<_cdUg$%Di{!Nc5x(B!%lJm6?f4=d51*-M|AwAkwm)oKAE9CEHN7 zs--+Y1htn%v$@i5?EdRGkUincm+5u@$~BdE<@c(qk2bLO?JRwku{ljMx&|;EzASTI zm5e+Ixo&oNRMK2KQHvDUY%LbhG;NYy^xNr{L{k Date: Mon, 29 Sep 2025 10:00:28 +0200 Subject: [PATCH 509/665] spacing --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index bbd5642..051bf0a 100644 --- a/README.md +++ b/README.md @@ -8,9 +8,9 @@ Using **LaMAria**, you can: - Benchmark against highly accurate sparse ground truths.

    -
    We present **LaMAria**, an egocentric, city-scale benchmark for **visual-inertial SLAM**, featuring From 4b07bdb4a8ec0f6a56c8983c2b748560f0ea0030 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:49:37 +0200 Subject: [PATCH 617/665] tools --- README.md | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/README.md b/README.md index 923fbe1..146cdd6 100644 --- a/README.md +++ b/README.md @@ -204,7 +204,27 @@ python -m evaluate_wrt_mps --estimate demo/estimate/R_01_easy.txt --gt_estimate For sequences that do not have control points, this evaluation is the primary way to benchmark your SLAM results. ## Data Conversion +We provide some utility scripts in the `tools/` folder to convert between different data formats used in our dataset. +1. Converting from `.vrs` to ASL folder format: +```bash +python tools/convert_vrs_to_asl.py --vrs_file path/to/sequence.vrs --output_asl_folder path/to/output_asl_folder +``` + +2. Converting from ASL folder to ROS bag: +```bash +python tools/asl_folder_to_rosbag.py --input_asl_folder path/to/asl_folder --output_rosbag path/to/output.bag +``` + +3. Undistorting ASL folder images to PINHOLE format: +```bash +python tools/undistort_asl_folder.py --calibration_file path/to/calibration.json --asl_folder path/to/asl_folder --output_asl_folder path/to/output_undistorted_asl_folder +``` + +4. Rotating ASL folder upright: +```bash +python tools/rotate_asl_folder.py --asl_folder path/to/asl_folder --output_asl_folder path/to/output_upright_asl_folder +``` ## Example Visual-Inertial Optimization From f3349098924b14c168c28c8de1362516e8ee34e4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:52:17 +0200 Subject: [PATCH 618/665] naming consistency --- tools/undistort_asl_folder.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/tools/undistort_asl_folder.py b/tools/undistort_asl_folder.py index fd1ecb5..047f781 100644 --- a/tools/undistort_asl_folder.py +++ b/tools/undistort_asl_folder.py @@ -158,13 +158,13 @@ def undistort_asl( help="Path to Aria calibration json file", ) parser.add_argument( - "--asl_path", + "--asl_folder", type=Path, required=True, help="Path to input Aria distorted ASL folder", ) parser.add_argument( - "--output_asl_path", + "--output_asl_folder", type=Path, required=True, help="Path to output undistorted ASL folder", @@ -174,7 +174,7 @@ def undistort_asl( undistort_asl( args.calibration_file, - args.asl_path, - args.output_asl_path, + args.asl_folder, + args.output_asl_folder, ratio_blank_pixels=args.ratio_blank_pixels, ) From 66fe2eb65ad8bbe621520f3cd1ffd071959b6a73 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:57:08 +0200 Subject: [PATCH 619/665] readme --- README.md | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index 146cdd6..9417f77 100644 --- a/README.md +++ b/README.md @@ -110,7 +110,7 @@ The data is stored in the `demo/` folder. You may run the standalone evaluations ### Downloading LaMAria ```bash -python tools/download_lamaria.py --help +python -m tools.download_lamaria.py --help ``` For download convenience, we provide a custom script `tools/download_lamaria.py`. Using this script, you can download: @@ -128,15 +128,15 @@ Ground truth files are automatically downloaded for the training sequences. To download all training sequences in both raw and pinhole formats: ```bash -python tools/download_lamaria.py --set training --type both +python -m tools.download_lamaria --set training --type both ``` To download the raw data of a specific sequence (e.g., `R_01_easy`): ```bash -python tools/download_lamaria.py --sequences R_01_easy --type raw +python -m tools.download_lamaria --sequences R_01_easy --type raw ``` To download 3 custom sequences in pinhole format: ```bash -python tools/download_lamaria.py --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type pinhole +python -m tools.download_lamaria --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type pinhole ``` #### Output structure @@ -208,22 +208,22 @@ We provide some utility scripts in the `tools/` folder to convert between differ 1. Converting from `.vrs` to ASL folder format: ```bash -python tools/convert_vrs_to_asl.py --vrs_file path/to/sequence.vrs --output_asl_folder path/to/output_asl_folder +python -m tools.vrs_to_asl_folder --vrs_file path/to/sequence.vrs --output_asl_folder path/to/output_asl_folder ``` 2. Converting from ASL folder to ROS bag: ```bash -python tools/asl_folder_to_rosbag.py --input_asl_folder path/to/asl_folder --output_rosbag path/to/output.bag +python -m tools.asl_folder_to_rosbag --input_asl_folder path/to/asl_folder --output_rosbag path/to/output.bag ``` 3. Undistorting ASL folder images to PINHOLE format: ```bash -python tools/undistort_asl_folder.py --calibration_file path/to/calibration.json --asl_folder path/to/asl_folder --output_asl_folder path/to/output_undistorted_asl_folder +python -m tools.undistort_asl_folder.py --calibration_file path/to/calibration.json --asl_folder path/to/asl_folder --output_asl_folder path/to/output_undistorted_asl_folder ``` 4. Rotating ASL folder upright: ```bash -python tools/rotate_asl_folder.py --asl_folder path/to/asl_folder --output_asl_folder path/to/output_upright_asl_folder +python -m tools.rotate_asl_folder --asl_folder path/to/asl_folder --output_asl_folder path/to/output_upright_asl_folder ``` From d9bf6228fb091dce44d649957f775f5825c355ae Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:59:04 +0200 Subject: [PATCH 620/665] fix --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index 9417f77..3ca1ee0 100644 --- a/README.md +++ b/README.md @@ -220,6 +220,7 @@ python -m tools.asl_folder_to_rosbag --input_asl_folder path/to/asl_folder --out ```bash python -m tools.undistort_asl_folder.py --calibration_file path/to/calibration.json --asl_folder path/to/asl_folder --output_asl_folder path/to/output_undistorted_asl_folder ``` +*Note: The undistortion script requires COLMAP to be installed from source. Please follow the instructions [here](https://colmap.github.io/install.html) to install the library.* 4. Rotating ASL folder upright: ```bash From 3d11031114ddf0ca71fc55f45491d3218cf06101 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 03:59:43 +0200 Subject: [PATCH 621/665] ros1bag --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 3ca1ee0..78ff50a 100644 --- a/README.md +++ b/README.md @@ -211,7 +211,7 @@ We provide some utility scripts in the `tools/` folder to convert between differ python -m tools.vrs_to_asl_folder --vrs_file path/to/sequence.vrs --output_asl_folder path/to/output_asl_folder ``` -2. Converting from ASL folder to ROS bag: +2. Converting from ASL folder to ROS1 bag: ```bash python -m tools.asl_folder_to_rosbag --input_asl_folder path/to/asl_folder --output_rosbag path/to/output.bag ``` From 26713802e5ea93e5b9adc91867878c881f3ce05a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 04:01:41 +0200 Subject: [PATCH 622/665] read --- README.md | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 78ff50a..258d993 100644 --- a/README.md +++ b/README.md @@ -222,11 +222,10 @@ python -m tools.undistort_asl_folder.py --calibration_file path/to/calibration.j ``` *Note: The undistortion script requires COLMAP to be installed from source. Please follow the instructions [here](https://colmap.github.io/install.html) to install the library.* -4. Rotating ASL folder upright: + ## Example Visual-Inertial Optimization From 3333a69f11824d47f95fcff5f3fee743b24bb655 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 04:06:59 +0200 Subject: [PATCH 623/665] readme --- README.md | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/README.md b/README.md index 258d993..91b1c31 100644 --- a/README.md +++ b/README.md @@ -229,9 +229,26 @@ python -m tools.rotate_asl_folder --asl_folder path/to/asl_folder --output_asl_f ## Example Visual-Inertial Optimization +In this section, we discuss an example visual-inertial optimization pipeline built within the `lamaria` package. This pipeline takes as input a pose estimate file (in the format described below) and `.vrs`, performs keyframing and triangulation, and optimizes the trajectory using both visual and inertial residuals. + +### Input format +The input pose estimate file is a text file where each line corresponds to a timestamped pose in the following format: +```timestamp tx ty tz qx qy qz qw +``` +The timestamp must be in nanoseconds. + ### Additional Installation To extract images from a `.vrs` file, it is required to install the VRS Command Line Tools. Please follow the instructions [here](https://github.com/facebookresearch/vrs?tab=readme-ov-file#instructions-macos-and-ubuntu-and-container) to install the library from source. +### Running the example +To run the example visual-inertial optimization on the downloaded demo data: +```bash +python -m example_vi_optimization --vrs demo/vrs/sequence_1_19.vrs --output demo/vi_optim/ --estimate demo/estimate/sequence_1_19.txt +``` + +### Visualizing the results +TODO: Add viz. + ## BibTeX citation From 42826a4ac104aa4e2d440f6abc6ddb619b538399 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 04:08:56 +0200 Subject: [PATCH 624/665] readme --- README.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 91b1c31..88a9e70 100644 --- a/README.md +++ b/README.md @@ -229,11 +229,12 @@ python -m tools.rotate_asl_folder --asl_folder path/to/asl_folder --output_asl_f ## Example Visual-Inertial Optimization -In this section, we discuss an example visual-inertial optimization pipeline built within the `lamaria` package. This pipeline takes as input a pose estimate file (in the format described below) and `.vrs`, performs keyframing and triangulation, and optimizes the trajectory using both visual and inertial residuals. +We provide an example visual-inertial optimization pipeline built within the `lamaria` package. This pipeline takes as input a pose estimate file (in the format described below) and `.vrs`, performs keyframing and triangulation, and optimizes the trajectory using visual and inertial residuals. ### Input format The input pose estimate file is a text file where each line corresponds to a timestamped pose in the following format: -```timestamp tx ty tz qx qy qz qw +``` +timestamp tx ty tz qx qy qz qw ``` The timestamp must be in nanoseconds. From b7b637f481cffb82c26805b29cd653a0a130cce8 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 10:07:24 +0200 Subject: [PATCH 625/665] evo bagpy and cvbridge --- requirements.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/requirements.txt b/requirements.txt index caa96d1..0e1cbfc 100644 --- a/requirements.txt +++ b/requirements.txt @@ -7,6 +7,9 @@ projectaria-tools[all] omegaconf +evo==1.31.1 +bagpy==0.5 +cv-bridge scipy pyceres==2.6 ; python_version >= "3.9" and python_version < "3.15" pycolmap==3.13.0.dev0 ; python_version >= "3.9" and python_version < "3.15" From ea77454e685b84786e9c1dbb2cebafc6771d438d Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 11:33:33 +0200 Subject: [PATCH 626/665] llaalalaa --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 88a9e70..b61507d 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,9 @@

    The LaMAria Dataset
    Benchmarking Egocentric Visual-Inertial SLAM at City Scale

    - Anusha Krishnan*, - Shaohui Liu*, - Paul-Edouard Sarlin*, + Anusha Krishnan*, + Shaohui Liu*, + Paul-Edouard Sarlin*, Oscar Gentilhomme,
    David Caruso, Maurizio Monge, From 0b10ca7aa2ea5b7776873b8f3063c7a4d6c672c1 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:04:53 +0200 Subject: [PATCH 627/665] download --- tools/download_lamaria.py | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 931dccf..20622f4 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -25,8 +25,10 @@ PAYLOADS = { "raw": ["raw_data", "aria_calibrations"], + "asl": ["asl_folder", "pinhole_calibrations"], + "rosbag": ["rosbag", "pinhole_calibrations"], "pinhole": ["asl_folder", "pinhole_calibrations", "rosbag"], - "both": [ + "all": [ "raw_data", "aria_calibrations", "asl_folder", @@ -206,9 +208,14 @@ def download_file( ) parser.add_argument( "--type", - choices=["raw", "pinhole", "both"], + choices=["raw", "asl", "rosbag", "pinhole", "all"], required=True, - help="Which data to fetch", + help="Type of data to fetch: " + "raw = raw_data + aria_calibrations; " + "asl = asl_folder + pinhole_calibrations; " + "rosbag = rosbag + pinhole_calibrations; " + "pinhole = asl_folder + pinhole_calibrations + rosbag;" + "all = everything", ) parser.add_argument( "--out-dir", From 916b3889f25921086aa68607790a74c9d2841317 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:08:03 +0200 Subject: [PATCH 628/665] readme changes --- README.md | 103 +++++++++++++++++++++--------------------------------- 1 file changed, 40 insertions(+), 63 deletions(-) diff --git a/README.md b/README.md index b61507d..658f6f1 100644 --- a/README.md +++ b/README.md @@ -20,7 +20,7 @@

    Website | - Paper + Paper

    @@ -28,7 +28,7 @@ We present **LaMAria**, an egocentric, city-scale benchmark for **visual-inertia ~ **22 hours / 70 km** of trajectories with survey-grade control points providing **centimeter-accurate ground truth**. Using **LaMAria**, you can: -- Evaluate SLAM systems under real-world challenges: low light, moving platforms, exposure changes, extremely long trajectories, and challenges typical to egocentric motion. +- Evaluate SLAM systems under real-world egocentric setup: low light, moving platforms, exposure changes, time-varying sensor calibrations. - Benchmark against highly accurate ground truths. This dataset offers 23 training sequences and 63 test sequences. @@ -44,13 +44,12 @@ To learn more about the dataset, please visit our here. -### Quickstart -We provide a small script `quickstart.sh` that downloads data from the archive. The standalone evaluations and example visual-inertial optimization can be run on the downloaded data. - -```bash -chmod +x quickstart.sh -./quickstart.sh -``` - -The data is stored in the `demo/` folder. You may run the standalone evaluations and example visual-inertial optimization on this data. - -### Downloading LaMAria - ```bash python -m tools.download_lamaria.py --help ``` @@ -117,8 +83,10 @@ For download convenience, we provide a custom script `tools/download_lamaria.py` - Specific sequences or entire sets (training/test). - Specific types: - Raw - Downloads raw `.vrs` files and Aria calibration file. + - ASL - Downloads ASL folder and pinhole calibration file. + - ROSbag - Downloads ROS1 bag and pinhole calibration file. - Pinhole - Downloads ASL folder, rosbag, and pinhole calibration file. - - Both - Downloads both raw and pinhole data. + - All - Downloads both raw and pinhole data. Ground truth files are automatically downloaded for the training sequences. @@ -128,19 +96,22 @@ Ground truth files are automatically downloaded for the training sequences. To download all training sequences in both raw and pinhole formats: ```bash -python -m tools.download_lamaria --set training --type both +python -m tools.download_lamaria --set training --type all ``` To download the raw data of a specific sequence (e.g., `R_01_easy`): ```bash python -m tools.download_lamaria --sequences R_01_easy --type raw ``` -To download 3 custom sequences in pinhole format: +To download 3 custom sequences in rosbag format: +```bash +python -m tools.download_lamaria --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type rosbag +``` +To download 3 custom sequences in asl format: ```bash -python -m tools.download_lamaria --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type pinhole +python -m tools.download_lamaria --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type asl ``` -#### Output structure -The downloaded data is stored in the following way: +The downloaded raw data is stored in the following way: ``` out_dir/ └── lamaria/ @@ -148,21 +119,15 @@ out_dir/ │ ├── R_01_easy/ │ │ ├── aria_calibrations/ │ │ │ └── R_01_easy.json - │ │ ├── asl_folder/ - │ │ │ └── R_01_easy.zip │ │ ├── ground_truth/ │ │ │ ├── pseudo_dense/ │ │ │ │ └── R_01_easy.txt │ │ │ └── sparse/ │ │ │ └── # if sequence has CPs - │ │ ├── pinhole_calibrations/ - │ │ │ └── R_01_easy.json │ │ ├── raw_data/ │ │ │ └── R_01_easy.vrs - │ │ └── rosbag/ - │ │ └── R_01_easy.bag │ └── ... - └── test/ + └── test/ # no ground truth └── sequence_1_1 ``` @@ -170,11 +135,28 @@ For more information about the training and test sequences, refer to the website to get evaluation results. Results on test sequences are displayed on the public leaderboard. -2. **Standalone evaluation**: Run the evaluation scripts locally using the provided `lamaria` package. +1. **Evaluation via the website**: Upload your results on our website to get evaluation results. **All sequences can be submitted via our website.** Results on test sequences are displayed on the public [leaderboard](https://www.lamaria.ethz.ch/leaderboard). +2. **Standalone evaluation**: Run the evaluation scripts locally using the provided `lamaria` package. These scripts can be run only on the training sequences (since ground truth is required). + +### Quickstart +We provide a small script `quickstart.sh` that downloads demo data from the archive. The standalone evaluations and example visual-inertial optimization can be run on the downloaded data. + +```bash +chmod +x quickstart.sh +./quickstart.sh +``` + +The first sequence of the controlled experimental set (R_01_easy) and additional set (sequence_1_19) are stored in the `demo/` folder. + +### Input format +The input pose estimate file must be a text file where each line corresponds to a timestamped pose in the following format: +``` +timestamp tx ty tz qx qy qz qw +``` +The timestamp must be in nanoseconds. ### Evaluation w.r.t. Control Points -Those sequences that observe ground truth control points (CPs) can be evaluated w.r.t. these points. This script computes the score and control point recall based on the alignment of the estimated trajectory to the control points. +Three sequences in the controlled experimental set and the additional set sequences can be evaluated w.r.t. control points. This script computes the score and control point recall based on the alignment of the estimated trajectory to the control points. To perform the evaluation on the downloaded demo data: ```bash @@ -201,9 +183,9 @@ To perform the evaluation on the downloaded demo data: python -m evaluate_wrt_mps --estimate demo/estimate/R_01_easy.txt --gt_estimate demo/mps/R_01_easy.txt ``` -For sequences that do not have control points, this evaluation is the primary way to benchmark your SLAM results. +This method is used to evaluate results on the controlled experimental set. -## Data Conversion +## Converting VRS to ASL/ROSbag format We provide some utility scripts in the `tools/` folder to convert between different data formats used in our dataset. 1. Converting from `.vrs` to ASL folder format: @@ -229,14 +211,9 @@ python -m tools.rotate_asl_folder --asl_folder path/to/asl_folder --output_asl_f ## Example Visual-Inertial Optimization -We provide an example visual-inertial optimization pipeline built within the `lamaria` package. This pipeline takes as input a pose estimate file (in the format described below) and `.vrs`, performs keyframing and triangulation, and optimizes the trajectory using visual and inertial residuals. +As a byproduct of our groundtruthing pipeline, we provide an example visual-inertial optimization pipeline built within the `lamaria` package. This pipeline takes as input a pose estimate file (in the format described below) and `.vrs`, performs keyframing and triangulation, and optimizes the trajectory using visual and inertial residuals. -### Input format -The input pose estimate file is a text file where each line corresponds to a timestamped pose in the following format: -``` -timestamp tx ty tz qx qy qz qw -``` -The timestamp must be in nanoseconds. +The input pose estimate file must follow the same format as described in the [input format](#input-format) section above. ### Additional Installation To extract images from a `.vrs` file, it is required to install the VRS Command Line Tools. Please follow the instructions [here](https://github.com/facebookresearch/vrs?tab=readme-ov-file#instructions-macos-and-ubuntu-and-container) to install the library from source. From 60de167442242dac980b9e730ffd9c549ba32956 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:16:26 +0200 Subject: [PATCH 629/665] sizes --- README.md | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 658f6f1..afbfbb7 100644 --- a/README.md +++ b/README.md @@ -90,9 +90,12 @@ For download convenience, we provide a custom script `tools/download_lamaria.py` Ground truth files are automatically downloaded for the training sequences. -**💣 Please note that the full archive is very large (~3.5 TB). Download full sets only if you have sufficient storage.** +### Data sizes +- Raw data (vrs + aria_calibrations): ~ 890 GB +- ASL folder + pinhole_calibrations: ~ 1.1 TB +- ROSbag + pinhole_calibrations: ~ 1.5 TB -#### Some example commands +### Some example commands To download all training sequences in both raw and pinhole formats: ```bash From 4de2fbfe047352b254bc79ddf99235e091fa5d6c Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:17:39 +0200 Subject: [PATCH 630/665] fix --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index afbfbb7..2e3a032 100644 --- a/README.md +++ b/README.md @@ -93,7 +93,7 @@ Ground truth files are automatically downloaded for the training sequences. ### Data sizes - Raw data (vrs + aria_calibrations): ~ 890 GB - ASL folder + pinhole_calibrations: ~ 1.1 TB -- ROSbag + pinhole_calibrations: ~ 1.5 TB +- ROSbag + pinhole_calibrations: ~ 1.5 TB ### Some example commands From 5da1c3dad4c127ba57cd7296279a3c6e8620d525 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:20:39 +0200 Subject: [PATCH 631/665] collapsed --- README.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/README.md b/README.md index 2e3a032..d14e5fa 100644 --- a/README.md +++ b/README.md @@ -189,6 +189,9 @@ python -m evaluate_wrt_mps --estimate demo/estimate/R_01_easy.txt --gt_estimate This method is used to evaluate results on the controlled experimental set. ## Converting VRS to ASL/ROSbag format + +
    +Click to expand instructions We provide some utility scripts in the `tools/` folder to convert between different data formats used in our dataset. 1. Converting from `.vrs` to ASL folder format: @@ -211,6 +214,7 @@ python -m tools.undistort_asl_folder.py --calibration_file path/to/calibration.j ```bash python -m tools.rotate_asl_folder --asl_folder path/to/asl_folder --output_asl_folder path/to/output_upright_asl_folder ``` --> +
    ## Example Visual-Inertial Optimization From 145987cebea1db574b6aedd2d09a8e4209bdaa10 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:22:00 +0200 Subject: [PATCH 632/665] read --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index d14e5fa..02a085f 100644 --- a/README.md +++ b/README.md @@ -191,7 +191,8 @@ This method is used to evaluate results on the controlled experimental set. ## Converting VRS to ASL/ROSbag format
    -Click to expand instructions +Expand +
    We provide some utility scripts in the `tools/` folder to convert between different data formats used in our dataset. 1. Converting from `.vrs` to ASL folder format: From eb52368be90d015b50745191aab99fbd8d89c0e3 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:23:58 +0200 Subject: [PATCH 633/665] better --- README.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 02a085f..56c6e56 100644 --- a/README.md +++ b/README.md @@ -190,10 +190,11 @@ This method is used to evaluate results on the controlled experimental set. ## Converting VRS to ASL/ROSbag format +We provide some utility scripts in the `tools/` folder to convert between different data formats used in our dataset. +
    -Expand +Click to expand commands
    -We provide some utility scripts in the `tools/` folder to convert between different data formats used in our dataset. 1. Converting from `.vrs` to ASL folder format: ```bash From c3065d79eca13467a394553ff72b8626c9aabe44 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:52:31 +0200 Subject: [PATCH 634/665] train test split --- README.md | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 56c6e56..cf880fd 100644 --- a/README.md +++ b/README.md @@ -85,15 +85,20 @@ For download convenience, we provide a custom script `tools/download_lamaria.py` - Raw - Downloads raw `.vrs` files and Aria calibration file. - ASL - Downloads ASL folder and pinhole calibration file. - ROSbag - Downloads ROS1 bag and pinhole calibration file. - - Pinhole - Downloads ASL folder, rosbag, and pinhole calibration file. - All - Downloads both raw and pinhole data. Ground truth files are automatically downloaded for the training sequences. ### Data sizes -- Raw data (vrs + aria_calibrations): ~ 890 GB -- ASL folder + pinhole_calibrations: ~ 1.1 TB -- ROSbag + pinhole_calibrations: ~ 1.5 TB +- Raw data (vrs + aria_calibrations): ~ 890G + - Training: ~ 117G + - Test: ~ 773G +- ASL folder + pinhole_calibrations: ~ 1.1T + - Training: ~ 170G + - Test: ~ 884G +- ROSbag + pinhole_calibrations: ~ 1.5T + - Training: ~ 247G + - Test: ~ 1.3T ### Some example commands From 0c67fd9103a9c23be3272d7f8890830b1a3082a4 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 13:54:27 +0200 Subject: [PATCH 635/665] readme --- README.md | 2 -- 1 file changed, 2 deletions(-) diff --git a/README.md b/README.md index cf880fd..4c1f68b 100644 --- a/README.md +++ b/README.md @@ -38,8 +38,6 @@ This dataset offers 23 training sequences and 63 test sequences. Figure 1: Overview of the LaMAria dataset and benchmark.

    -In this repository, you can find scripts to conveniently download the dataset, evaluate SLAM results, perform data conversions, and run an example visual-inertial optimization pipeline. - To learn more about the dataset, please visit our main dataset website or read our paper. ## Table of Contents From 871c9faed56563ef59d3f52cc66df845762a6d68 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 15:48:11 +0200 Subject: [PATCH 636/665] readme comments without viz --- README.md | 56 ++++++++++++++++++++++++++++++------------------------- 1 file changed, 31 insertions(+), 25 deletions(-) diff --git a/README.md b/README.md index 4c1f68b..fdf195f 100644 --- a/README.md +++ b/README.md @@ -20,7 +20,7 @@

    Website | - Paper + Paper

    @@ -53,8 +53,6 @@ To learn more about the dataset, please visit our website to get evaluation results. **All sequences can be submitted via our website.** Results on test sequences are displayed on the public [leaderboard](https://www.lamaria.ethz.ch/leaderboard). 2. **Standalone evaluation**: Run the evaluation scripts locally using the provided `lamaria` package. These scripts can be run only on the training sequences (since ground truth is required). -### Quickstart +### Input format +The input pose estimate file must be a text file where each line corresponds to a timestamped pose in the following format: +``` +timestamp tx ty tz qx qy qz qw +``` +The timestamp must be in nanoseconds. + +### Download demo data We provide a small script `quickstart.sh` that downloads demo data from the archive. The standalone evaluations and example visual-inertial optimization can be run on the downloaded data. ```bash @@ -154,13 +153,6 @@ chmod +x quickstart.sh The first sequence of the controlled experimental set (R_01_easy) and additional set (sequence_1_19) are stored in the `demo/` folder. -### Input format -The input pose estimate file must be a text file where each line corresponds to a timestamped pose in the following format: -``` -timestamp tx ty tz qx qy qz qw -``` -The timestamp must be in nanoseconds. - ### Evaluation w.r.t. Control Points Three sequences in the controlled experimental set and the additional set sequences can be evaluated w.r.t. control points. This script computes the score and control point recall based on the alignment of the estimated trajectory to the control points. @@ -228,17 +220,31 @@ As a byproduct of our groundtruthing pipeline, we provide an example visual-iner The input pose estimate file must follow the same format as described in the [input format](#input-format) section above. ### Additional Installation -To extract images from a `.vrs` file, it is required to install the VRS Command Line Tools. Please follow the instructions [here](https://github.com/facebookresearch/vrs?tab=readme-ov-file#instructions-macos-and-ubuntu-and-container) to install the library from source. +To extract images from a `.vrs` file, it is required to install the [VRS Command Line Tools](https://facebookresearch.github.io/vrs/docs/VrsCliTool/). Please follow the instructions [here](https://github.com/facebookresearch/vrs?tab=readme-ov-file#instructions-macos-and-ubuntu-and-container) to install the library from source. ### Running the example To run the example visual-inertial optimization on the downloaded demo data: ```bash +./quickstart.sh python -m example_vi_optimization --vrs demo/vrs/sequence_1_19.vrs --output demo/vi_optim/ --estimate demo/estimate/sequence_1_19.txt ``` - -### Visualizing the results -TODO: Add viz. - +TODO: Add two plots and caption. ## BibTeX citation +```bibtex +@InProceedings{Krishnan_2025_ICCV, + author = {Krishnan, Anusha and + Liu, Shaohui and + Sarlin, Paul-Edouard and + Gentilhomme, Oscar and + Caruso, David and + Monge, Maurizio and + Newcombe, Richard and + Engel, Jakob and + Pollefeys, Marc}, + title = {Benchmarking Egocentric Visual-Inertial SLAM at City Scale}, + booktitle = {Proceedings of the IEEE/CVF International Conference on Computer Vision (ICCV)}, + year = {2025} +} +``` From 6dc8c3377efa11fd96cc87da6dc39bfc04b6def5 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 16:01:12 +0200 Subject: [PATCH 637/665] mps estimate trajec --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index fdf195f..ae47f29 100644 --- a/README.md +++ b/README.md @@ -181,7 +181,7 @@ To perform the evaluation on the downloaded demo data: python -m evaluate_wrt_mps --estimate demo/estimate/R_01_easy.txt --gt_estimate demo/mps/R_01_easy.txt ``` -This method is used to evaluate results on the controlled experimental set. +The gt estimate file is built directly from the MPS estimated trajectory. This method is used to evaluate results on the controlled experimental set. ## Converting VRS to ASL/ROSbag format From 3e91c3467ff131e99f91a484ee83e114160fe562 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 17:26:31 +0200 Subject: [PATCH 638/665] readme --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index ae47f29..97c4ef0 100644 --- a/README.md +++ b/README.md @@ -38,7 +38,7 @@ This dataset offers 23 training sequences and 63 test sequences. Figure 1: Overview of the LaMAria dataset and benchmark.

    -To learn more about the dataset, please visit our main dataset website or read our paper. +To learn more about the dataset, please visit our main dataset website or read our paper. ## Table of Contents - [Installation](#installation) @@ -163,7 +163,7 @@ python -m evaluate_wrt_control_points --estimate demo/estimate/sequence_1_19.txt *This command evaluates the provided estimate w.r.t. control points and stores the results in `demo/eval_cp`. The `--corresponding_sensor` flag indicates which sensor the poses are expressed in (e.g., `imu` or `cam0`).* -To learn more about the control points and sparse evaluation, refer to Section 4.1 and 4.2 of our paper. +To learn more about the control points and sparse evaluation, refer to Section 4.1 and 4.2 of our paper. ### Evaluation w.r.t Pseudo-GT This script evaluates the estimated trajectory w.r.t. the pseudo-dense ground truth from our ground-truthing pipeline. It requires the alignment obtained from the sparse evaluation (w.r.t. control points). The script computes the pose recall @ 1m and @ 5m, after aligning the estimated trajectory to the pseudo-ground truth. @@ -181,7 +181,7 @@ To perform the evaluation on the downloaded demo data: python -m evaluate_wrt_mps --estimate demo/estimate/R_01_easy.txt --gt_estimate demo/mps/R_01_easy.txt ``` -The gt estimate file is built directly from the MPS estimated trajectory. This method is used to evaluate results on the controlled experimental set. +This method is used to evaluate results on the controlled experimental set, where the gt estimate file is built directly from the MPS estimated trajectory. ## Converting VRS to ASL/ROSbag format From aee915a2be7432a6624f258f912fb3e9a206140a Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 17:31:04 +0200 Subject: [PATCH 639/665] removing the rudeness from readme --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 97c4ef0..82b123c 100644 --- a/README.md +++ b/README.md @@ -38,7 +38,7 @@ This dataset offers 23 training sequences and 63 test sequences. Figure 1: Overview of the LaMAria dataset and benchmark.

    -To learn more about the dataset, please visit our main dataset website or read our paper. +To learn more about the dataset, please refer to our main dataset website or our paper. ## Table of Contents - [Installation](#installation) From 748ac9dd20aa2aaf5654c5d4b6b0b0e4d0c5e416 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 17:41:36 +0200 Subject: [PATCH 640/665] rm mps --- .../data_init/mps_to_timed_reconstruction.py | 374 ------------------ 1 file changed, 374 deletions(-) delete mode 100644 lamaria/pipeline/data_init/mps_to_timed_reconstruction.py diff --git a/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py b/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py deleted file mode 100644 index 0058228..0000000 --- a/lamaria/pipeline/data_init/mps_to_timed_reconstruction.py +++ /dev/null @@ -1,374 +0,0 @@ -from dataclasses import dataclass -from pathlib import Path - -import pycolmap -from projectaria_tools.core import data_provider -from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions -from projectaria_tools.core.stream_id import StreamId - -from ... import logger -from ...structs.timed_reconstruction import TimedReconstruction -from ...utils.aria import ( - camera_colmap_from_calib, - extract_images_from_vrs, - get_closed_loop_data_from_mps, - get_mps_poses_for_timestamps, - get_t_imu_camera, - rigid3d_from_transform, -) -from ...utils.constants import ( - LEFT_CAMERA_STREAM_ID, - RIGHT_CAMERA_STREAM_ID, - RIGHT_IMU_STREAM_ID, -) -from ...utils.timestamps import ( - get_matched_timestamps, -) - - -# TODO: remove this -@dataclass -class PerFrameData: - left_ts: int - right_ts: int - left_img: Path - right_img: Path - rig_from_world: pycolmap.Rigid3d - - -class MPSToTimedRecon: - # TODO: convert this class into functions - """Converts MPS data to COLMAP format.""" - - def __init__( - self, use_online_calibration: bool = False, has_slam_drops: bool = False - ): - self.use_online_calibration = use_online_calibration - self.has_slam_drops = has_slam_drops - - self._vrs_provider = None - self._mps_data_provider = None - self._per_frame_data: dict[int, PerFrameData] = {} - - self.data: TimedReconstruction = TimedReconstruction() - - def convert( - self, - vrs: Path, - images_path: Path, - mps_folder: Path, - ) -> TimedReconstruction: - self._init_data(vrs, images_path, mps_folder) - - if self.use_online_calibration: - self._add_online_sensors() - self._add_online_frames() - else: - self._add_device_sensors() - self._add_device_frames() - - self.data.timestamps = { - fid: pfd.left_ts for fid, pfd in self._per_frame_data.items() - } - return self.data - - # -------- internal methods -------- - def _init_data( - self, - vrs: Path, - image_folder: Path, - mps_folder: Path, - ) -> None: - """Initializes data providers and extracts images, timestamps - and builds per-frame data object. - Per-frame data is used to create the initial Lamaria reconstruction. - """ - - # Initialize VRS data provider - self._vrs_provider = data_provider.create_vrs_data_provider( - vrs.as_posix() - ) - - # Initialize stream IDs - self._left_cam_sid = StreamId(LEFT_CAMERA_STREAM_ID) - self._right_cam_sid = StreamId(RIGHT_CAMERA_STREAM_ID) - self._right_imu_sid = StreamId(RIGHT_IMU_STREAM_ID) - - # Extract images from VRS file - extract_images_from_vrs( - vrs_file=vrs, - image_folder=image_folder, - ) - - images = self._get_images(image_folder) - - # Get timestamps and build per-frame data - timestamps = self._get_mps_timestamps() - closed_loop_data = get_closed_loop_data_from_mps(mps_folder) - pose_timestamps = [left for left, _ in timestamps] - mps_poses = get_mps_poses_for_timestamps( - closed_loop_data, pose_timestamps - ) - self._per_frame_data = self._build_per_frame_data_from_mps( - images, timestamps, mps_poses - ) - - def _build_per_frame_data_from_mps( - self, images, timestamps, mps_poses - ) -> dict[int, PerFrameData]: - per_frame_data: dict[int, PerFrameData] = {} - imu_stream_label = self._vrs_provider.get_label_from_stream_id( - self._right_imu_sid - ) - - if not self.use_online_calibration: - device_calibration = self._vrs_provider.get_device_calibration() - imu_calib = device_calibration.get_imu_calib(imu_stream_label) - - frame_id = 1 - - for (left_img, right_img), (left_ts, right_ts), t_world_device in zip( - images, timestamps, mps_poses - ): - if t_world_device is None: - continue - - if self.mps.use_online_calibration: - ocalib = self._mps_data_provider.get_online_calibration( - left_ts, TimeQueryOptions.CLOSEST - ) - if ocalib is None: - continue - imu_calib = None - for calib in ocalib.imu_calibs: - if calib.get_label() == imu_stream_label: - imu_calib = calib - break - - t_device_imu = imu_calib.get_transform_device_imu() - t_world_imu = t_world_device @ t_device_imu - t_imu_world = t_world_imu.inverse() - rig_from_world = rigid3d_from_transform(t_imu_world) - - pfd = PerFrameData( - left_ts=left_ts, - right_ts=right_ts, - left_img=left_img, - right_img=right_img, - rig_from_world=rig_from_world, - ) - per_frame_data[frame_id] = pfd - frame_id += 1 - - return per_frame_data - - def _images_from_vrs( - self, folder: Path, wrt_to: Path, ext: str = ".jpg" - ) -> list[Path]: - if not folder.is_dir(): - return [] - images = sorted(n for n in folder.iterdir() if n.suffix == ext) - images = [n.relative_to(wrt_to) for n in images] - return images - - def _ts_from_vrs(self, sid: StreamId) -> list[int]: - """Timestamps in nanoseconds""" - return sorted( - self._vrs_provider.get_timestamps_ns(sid, TimeDomain.DEVICE_TIME) - ) - - def _get_images(self, images_path: Path) -> list[tuple[Path, Path]]: - left_img_dir = images_path / "left" - right_img_dir = images_path / "right" - - left_images = self._images_from_vrs(left_img_dir, left_img_dir) - right_images = self._images_from_vrs(right_img_dir, right_img_dir) - - return list(zip(left_images, right_images)) - - def _get_mps_timestamps(self, max_diff=1e6) -> list[tuple[int, int]]: - L = self._ts_from_vrs(self._left_cam_sid) - R = self._ts_from_vrs(self._right_cam_sid) - if not self.has_slam_drops: - assert len(L) == len(R), ( - "Unequal number of left and right timestamps" - ) - matched = list(zip(L, R)) - if not all(abs(left - right) < max_diff for left, right in matched): - logger.warning( - f"Left and right timestamps differ " - f"by more than {max_diff} ns" - ) - else: - matched = get_matched_timestamps(L, R, max_diff) - - return matched - - def _add_device_sensors(self) -> None: - """Adds a new rig with device calibrated sensors. - The rig is consistent across all frames - - Camera ID layout: - rig_id=1 -> (imu=1, left=2, right=3) - """ - device_calibration = self._vrs_provider.get_device_calibration() - imu_stream_label = self._vrs_provider.get_label_from_stream_id( - self._right_imu_sid - ) - imu_calib = device_calibration.get_imu_calib(imu_stream_label) - - rig = pycolmap.Rig(rig_id=1) - - # DUMMY CAMERA FOR IMU, IMU ID is 1 - imu = pycolmap.Camera( - camera_id=1, model="SIMPLE_PINHOLE", params=[0, 0, 0] - ) - self.data.reconstruction.add_camera(imu) - rig.add_ref_sensor(imu.sensor_id) - - for cam_id, sid in [(2, self._left_cam_sid), (3, self._right_cam_sid)]: - stream_label = self._vrs_provider.get_label_from_stream_id(sid) - camera_calib = device_calibration.get_camera_calib(stream_label) - cam = camera_colmap_from_calib(camera_calib) - cam.camera_id = cam_id - - t_imu_camera = get_t_imu_camera( - imu_calib, - camera_calib, - ) - sensor_from_rig = t_imu_camera.inverse() - - self.data.reconstruction.add_camera(cam) - rig.add_sensor(cam.sensor_id, sensor_from_rig) - - self.data.reconstruction.add_rig(rig) - - def _add_online_sensors(self) -> None: - """Adds a new rig for each frame timestamp. - Each rig has its own online calibrated sensors. - - Camera ID layout: - rig_id=1 -> (imu=1, left=2, right=3); - rig_id=2 -> (imu=4, left=5, right=6); - rig_id=3 -> (imu=7, left=8, right=9); - ... - """ - sensor_id = 1 - for fid, pfd in self._per_frame_data.items(): - t = pfd.left_ts - calibration = self._mps_data_provider.get_online_calibration( - t, TimeQueryOptions.CLOSEST - ) - if calibration is None: - continue - - rig = pycolmap.Rig(rig_id=fid) - - # DUMMY CAMERA FOR IMU - imu = pycolmap.Camera( - camera_id=1, model="SIMPLE_PINHOLE", params=[0, 0, 0] - ) - self.data.reconstruction.add_camera(imu) - rig.add_ref_sensor(imu.sensor_id) - sensor_id += 1 - - imu_stream_label = self._vrs_provider.get_label_from_stream_id( - self._right_imu_sid - ) - imu_calib = None - for calib in calibration.imu_calibs: - if calib.get_label() == imu_stream_label: - imu_calib = calib - break - - for sid in [self._left_cam_sid, self._right_cam_sid]: - stream_label = self._vrs_provider.get_label_from_stream_id(sid) - camera_calib = calibration.get_camera_calib(stream_label) - cam = camera_colmap_from_calib(camera_calib) - cam.camera_id = sensor_id - sensor_id += 1 - - t_imu_camera = get_t_imu_camera( - imu_calib, - camera_calib, - ) - sensor_from_rig = t_imu_camera.inverse() - - self.data.reconstruction.add_camera(cam) - rig.add_sensor(cam.sensor_id, sensor_from_rig) - - self.data.reconstruction.add_rig(rig) - - def _add_device_frames(self) -> None: - """Adds frame data for each rig, - all rigs share same device calibrated sensors - """ - image_id = 1 - - rig = self.data.reconstruction.rigs[1] - for fid, pfd in self._per_frame_data.items(): - frame = pycolmap.Frame() - frame.rig_id = rig.rig_id - frame.frame_id = fid - frame.rig_from_world = pfd.rig_from_world - - images_to_add = [] - for cam_id, img_path in [(2, pfd.left_img), (3, pfd.right_img)]: - im = pycolmap.Image( - str(img_path), - pycolmap.Point2DList(), - cam_id, - image_id, - ) - im.frame_id = frame.frame_id - frame.add_data_id(im.data_id) - images_to_add.append(im) - image_id += 1 - - self.data.reconstruction.add_frame(frame) - for im in images_to_add: - self.data.reconstruction.add_image(im) - - def _add_online_frames(self) -> None: - """Adds frame data for each rig, each rig has - its own online calibrated sensors - - Frame ID layout: - fid=1 -> (imu=1, left=2, right=3), (image IDs: 1, 2); - fid=2 -> (imu=4, left=5, right=6), (image IDs: 3, 4); - fid=3 -> (imu=7, left=8, right=9), (image IDs: 5, 6); - ... - """ - image_id = 1 - - for fid, pfd in self._per_frame_data.items(): - frame = pycolmap.Frame() - frame.rig_id = fid - frame.frame_id = fid - frame.rig_from_world = pfd.rig_from_world - - images_to_add = [] - # Camera ID layout from _add_online_sensors(): - # fid=1 -> (imu=1, left=2, right=3); - # fid=2 -> (imu=4, left=5, right=6); ... - left_cam_id = 3 * fid - 1 - right_cam_id = 3 * fid - - for cam_id, img_path in [ - (left_cam_id, pfd.left_img), - (right_cam_id, pfd.right_img), - ]: - im = pycolmap.Image( - str(img_path), - pycolmap.Point2DList(), - cam_id, - image_id, - ) - im.frame_id = frame.frame_id - frame.add_data_id(im.data_id) - images_to_add.append(im) - image_id += 1 - - self.data.reconstruction.add_frame(frame) - for im in images_to_add: - self.data.reconstruction.add_image(im) From 46bf9926e4ab0291e3cd8f0ab2672845e23c0c57 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 17:41:56 +0200 Subject: [PATCH 641/665] mps ocal rm --- defaults.yaml | 1 - 1 file changed, 1 deletion(-) diff --git a/defaults.yaml b/defaults.yaml index 7fd040c..10bf868 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -44,5 +44,4 @@ optimization: acc_infl: 1.0 integration_noise_density: 0.05 -use_mps_online_calibration: false # relevant only when mps folder is used has_slam_drops: false From e6a118d15b3d8e335ee3716b9a4804ac2551d142 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 17:42:42 +0200 Subject: [PATCH 642/665] rm mps --- example_vi_optimization.py | 80 +++++--------------------------------- 1 file changed, 9 insertions(+), 71 deletions(-) diff --git a/example_vi_optimization.py b/example_vi_optimization.py index dbd8638..1b9572d 100644 --- a/example_vi_optimization.py +++ b/example_vi_optimization.py @@ -10,9 +10,6 @@ VIOptimizerOptions, ) from lamaria.config.pipeline import PipelineOptions -from lamaria.pipeline.data_init.mps_to_timed_reconstruction import ( - MPSToTimedRecon, -) from lamaria.pipeline.estimate_to_timed_reconstruction import ( convert_estimate_into_timed_reconstruction, ) @@ -49,25 +46,6 @@ def run_estimate_to_timed_recon( return timed_recon -def run_mps_to_timed_recon( - vrs: Path, - images_path: Path, - mps_folder: Path, - use_online_calibration: bool = False, - has_slam_drops: bool = False, -) -> TimedReconstruction: - """Function to convert MPS estimate to a TimedReconstruction.""" - timed_recon = MPSToTimedRecon( - use_online_calibration=use_online_calibration, - has_slam_drops=has_slam_drops, - ).convert( - vrs, - images_path, - mps_folder, - ) - return timed_recon - - def run_keyframe_selection( options: KeyframeSelectorOptions, input_recon: TimedReconstruction, @@ -125,41 +103,23 @@ def run_pipeline( options: PipelineOptions, vrs: Path, output_path: Path, - estimate: Path | None = None, - mps_folder: Path | None = None, + estimate: Path, ): if not output_path.exists(): output_path.mkdir(parents=True, exist_ok=True) recon = None # Estimate to Lamaria Reconstruction - src = "estimate" if estimate is not None else "mps" image_path = output_path / "images" init_recon_path = output_path / "initial_recon" if init_recon_path.exists(): recon = TimedReconstruction.read(init_recon_path) else: - if src == "estimate": - assert estimate.exists(), ( - "Estimate path must be provided if not using MPS" - ) - recon = run_estimate_to_timed_recon( - vrs, - output_path / "images", - estimate, - ) - else: - assert mps_folder.exists(), ( - "MPS folder path must be provided if using MPS" - ) - recon = run_mps_to_timed_recon( - vrs, - output_path / "images", - mps_folder, - use_online_calibration=options.use_mps_online_calibration, - has_slam_drops=options.has_slam_drops, - ) - recon.write(init_recon_path) + recon = run_estimate_to_timed_recon( + vrs, + output_path / "images", + estimate, + ) # Keyframe Selection keyframe_path = output_path / "keyframes" @@ -204,15 +164,8 @@ def run_pipeline( optim_model_path.mkdir(parents=True, exist_ok=True) # Load IMU data if imu_measurements is None: - if options.vi_optimizer_options.use_mps_online_calibration: - assert mps_folder is not None, ( - "MPS folder path must be provided if using MPS" - ) imu_measurements = get_imu_data_from_vrs_file( vrs, - mps_folder - if options.vi_optimizer_options.use_mps_online_calibration - else None, ) recon = VIReconstruction( reconstruction=recon.reconstruction, @@ -252,31 +205,16 @@ def run_pipeline( parser.add_argument( "--estimate", type=str, - default=None, - help="Path to the input estimate file (if not using MPS).", - ) - parser.add_argument( - "--mps_folder", - type=str, - default=None, - help="Path to the input MPS folder (if using MPS).", + required=True, + help="Path to the input estimate file.", ) args = parser.parse_args() - # ensure either estimate or mps_folder is provided - if args.estimate is None and args.mps_folder is None: - parser.error("Either --estimate or --mps_folder must be provided.") - if args.estimate is not None and args.mps_folder is not None: - parser.error( - "Only one of --estimate or --mps_folder should be provided." - ) - options = PipelineOptions() options.load(args.config) run_pipeline( options, Path(args.vrs), Path(args.output), - estimate=Path(args.estimate) if args.estimate else None, - mps_folder=Path(args.mps_folder) if args.mps_folder else None, + Path(args.estimate), ) From 100cbe3a35af15355d97227e93e383cf6e639d9b Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 17:42:54 +0200 Subject: [PATCH 643/665] use mps --- lamaria/config/options.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/lamaria/config/options.py b/lamaria/config/options.py index 67c5141..3015b67 100644 --- a/lamaria/config/options.py +++ b/lamaria/config/options.py @@ -97,7 +97,6 @@ class VIOptimizerOptions: cam: OptCamOptions = field(default_factory=OptCamOptions) imu: OptIMUOptions = field(default_factory=OptIMUOptions) optim: OptOptions = field(default_factory=OptOptions) - use_mps_online_calibration: bool = False @classmethod def load(cls, cfg: OmegaConf | None = None) -> VIOptimizerOptions: @@ -114,7 +113,4 @@ def load(cls, cfg: OmegaConf | None = None) -> VIOptimizerOptions: cam=cam, imu=imu, optim=optim, - use_mps_online_calibration=cfg.get( - "use_mps_online_calibration", False - ), ) From 48b8025e640117e6efcad0b52a075dcdc98f8563 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 17:43:18 +0200 Subject: [PATCH 644/665] rm mps --- lamaria/config/pipeline.py | 11 ++--------- 1 file changed, 2 insertions(+), 9 deletions(-) diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 3008989..876f509 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -1,5 +1,5 @@ from collections.abc import Sequence -from dataclasses import dataclass, field, replace +from dataclasses import dataclass, field from pathlib import Path from omegaconf import DictConfig, OmegaConf @@ -23,7 +23,6 @@ class PipelineOptions: default_factory=VIOptimizerOptions ) - use_mps_online_calibration: bool = False has_slam_drops: bool = False def load( @@ -47,9 +46,6 @@ def _update_from_cfg(self, cfg: DictConfig) -> None: self._triangulator_options = TriangulatorOptions.load(cfg.triangulation) self._vi_optimizer_options = VIOptimizerOptions.load(cfg.optimization) - self.use_mps_online_calibration = cfg.get( - "use_mps_online_calibration", False - ) self.has_slam_drops = cfg.get("has_slam_drops", False) # Properties for keyframing @@ -65,7 +61,4 @@ def triangulator_options(self) -> TriangulatorOptions: # Properties for visual-inertial optimization @property def vi_optimizer_options(self) -> VIOptimizerOptions: - return replace( - self._vi_optimizer_options, - use_mps_online_calibration=self.use_mps_online_calibration, - ) + return self._vi_optimizer_options From 9460a875aa04597592a0cbe62ebcc39e1dbfb968 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 17:50:19 +0200 Subject: [PATCH 645/665] rm has slam drops --- defaults.yaml | 2 -- lamaria/config/pipeline.py | 4 ---- 2 files changed, 6 deletions(-) diff --git a/defaults.yaml b/defaults.yaml index 10bf868..82772ff 100644 --- a/defaults.yaml +++ b/defaults.yaml @@ -43,5 +43,3 @@ optimization: gyro_infl: 1.0 acc_infl: 1.0 integration_noise_density: 0.05 - -has_slam_drops: false diff --git a/lamaria/config/pipeline.py b/lamaria/config/pipeline.py index 876f509..e979d3e 100644 --- a/lamaria/config/pipeline.py +++ b/lamaria/config/pipeline.py @@ -23,8 +23,6 @@ class PipelineOptions: default_factory=VIOptimizerOptions ) - has_slam_drops: bool = False - def load( self, yaml: Path | str, @@ -46,8 +44,6 @@ def _update_from_cfg(self, cfg: DictConfig) -> None: self._triangulator_options = TriangulatorOptions.load(cfg.triangulation) self._vi_optimizer_options = VIOptimizerOptions.load(cfg.optimization) - self.has_slam_drops = cfg.get("has_slam_drops", False) - # Properties for keyframing @property def keyframing_options(self) -> KeyframeSelectorOptions: From 066035ca30c67486a4c26f195c7167d7fab50596 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 18:34:22 +0200 Subject: [PATCH 646/665] make output_dir mandatory. --- README.md | 20 ++++++++++++-------- tools/download_lamaria.py | 16 ++++++++-------- 2 files changed, 20 insertions(+), 16 deletions(-) diff --git a/README.md b/README.md index 82b123c..7707362 100644 --- a/README.md +++ b/README.md @@ -64,7 +64,7 @@ Install the package: ```bash git clone git@github.com:cvg/lamaria.git cd lamaria -pip install -r requirements.txt +python -m pip install -r requirements.txt python -m pip install -e . ``` @@ -92,21 +92,25 @@ Ground truth files are automatically downloaded for the training sequences. ### Some example commands -To download all training sequences in both raw and pinhole formats: -```bash -python -m tools.download_lamaria --set training --type all -``` To download the raw data of a specific sequence (e.g., `R_01_easy`): ```bash -python -m tools.download_lamaria --sequences R_01_easy --type raw +python -m tools.download_lamaria --output_dir ./lamaria \ + --sequences R_01_easy --type raw ``` To download 3 custom sequences in rosbag format: ```bash -python -m tools.download_lamaria --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type rosbag +python -m tools.download_lamaria --ouptut_dir ./lamaria \ + --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type rosbag ``` To download 3 custom sequences in asl format: ```bash -python -m tools.download_lamaria --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type asl +python -m tools.download_lamaria --output_dir ./lamaria \ + --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type asl +``` +To download all training sequences in both raw and pinhole formats: +```bash +python -m tools.download_lamaria --output_dir ./lamaria \ + --set training --type all ``` The downloaded raw data is stored in the following way: diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index 20622f4..ef29020 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -195,6 +195,12 @@ def download_file( parser = argparse.ArgumentParser(description="LaMAria dataset downloader") group = parser.add_mutually_exclusive_group(required=False) + parser.add_argument( + "--output_dir", + required=True, + type=str, + help="Root output folder", + ) group.add_argument( "--set", choices=["training", "test"], @@ -217,15 +223,9 @@ def download_file( "pinhole = asl_folder + pinhole_calibrations + rosbag;" "all = everything", ) - parser.add_argument( - "--out-dir", - default="out_dir", - help="Root output folder (script will create out_dir/lamaria)", - ) - args = parser.parse_args() - # Root: out_dir/lamaria - root = Path(args.out_dir) / "lamaria" + args = parser.parse_args() + root = Path(args.output_dir) ensure_dir(root) print("[info] Building catalog from server…") From 1093ed24e61ca7848f3940b5668b4c2fae673dba Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 18:41:27 +0200 Subject: [PATCH 647/665] fix. --- .gitignore | 3 ++- README.md | 12 ++++++------ 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/.gitignore b/.gitignore index 6b44e6f..aa31370 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,4 @@ **/__pycache__/ .DS_Store -demo/ \ No newline at end of file +lamaria_data/ +demo/ diff --git a/README.md b/README.md index 7707362..4f36aa8 100644 --- a/README.md +++ b/README.md @@ -94,22 +94,22 @@ Ground truth files are automatically downloaded for the training sequences. To download the raw data of a specific sequence (e.g., `R_01_easy`): ```bash -python -m tools.download_lamaria --output_dir ./lamaria \ +python -m tools.download_lamaria --output_dir ./lamaria_data \ --sequences R_01_easy --type raw ``` To download 3 custom sequences in rosbag format: ```bash -python -m tools.download_lamaria --ouptut_dir ./lamaria \ - --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type rosbag +python -m tools.download_lamaria --output_dir ./lamaria_data \ + --sequences sequence_1_1 sequence_1_2 sequence_1_3 --type rosbag ``` To download 3 custom sequences in asl format: ```bash -python -m tools.download_lamaria --output_dir ./lamaria \ - --sequences sequence_1_1 sequence 1_2 sequence 1_3 --type asl +python -m tools.download_lamaria --output_dir ./lamaria_data \ + --sequences sequence_1_1 sequence_1_2 sequence_1_3 --type asl ``` To download all training sequences in both raw and pinhole formats: ```bash -python -m tools.download_lamaria --output_dir ./lamaria \ +python -m tools.download_lamaria --output_dir ./lamaria_data \ --set training --type all ``` From 4e7b35b94ec1ee193e9f0a39a726c60f21dae0f4 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 18:43:08 +0200 Subject: [PATCH 648/665] change example to lighter sequences. --- README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 4f36aa8..9c8b4d5 100644 --- a/README.md +++ b/README.md @@ -100,12 +100,12 @@ python -m tools.download_lamaria --output_dir ./lamaria_data \ To download 3 custom sequences in rosbag format: ```bash python -m tools.download_lamaria --output_dir ./lamaria_data \ - --sequences sequence_1_1 sequence_1_2 sequence_1_3 --type rosbag + --sequences R_01_easy R_02_easy R_03_easy --type rosbag ``` To download 3 custom sequences in asl format: ```bash python -m tools.download_lamaria --output_dir ./lamaria_data \ - --sequences sequence_1_1 sequence_1_2 sequence_1_3 --type asl + --sequences R_01_easy R_02_easy R_03_easy --type asl ``` To download all training sequences in both raw and pinhole formats: ```bash From de29d77035d3acf4458e45190290efc96a9d6889 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 18:44:05 +0200 Subject: [PATCH 649/665] adapt file structure --- README.md | 31 +++++++++++++++---------------- 1 file changed, 15 insertions(+), 16 deletions(-) diff --git a/README.md b/README.md index 9c8b4d5..553be8d 100644 --- a/README.md +++ b/README.md @@ -115,22 +115,21 @@ python -m tools.download_lamaria --output_dir ./lamaria_data \ The downloaded raw data is stored in the following way: ``` -out_dir/ -└── lamaria/ - ├── training/ - │ ├── R_01_easy/ - │ │ ├── aria_calibrations/ - │ │ │ └── R_01_easy.json - │ │ ├── ground_truth/ - │ │ │ ├── pseudo_dense/ - │ │ │ │ └── R_01_easy.txt - │ │ │ └── sparse/ - │ │ │ └── # if sequence has CPs - │ │ ├── raw_data/ - │ │ │ └── R_01_easy.vrs - │ └── ... - └── test/ # no ground truth - └── sequence_1_1 +output_dir/ +├── training/ +│ ├── R_01_easy/ +│ │ ├── aria_calibrations/ +│ │ │ └── R_01_easy.json +│ │ ├── ground_truth/ +│ │ │ ├── pseudo_dense/ +│ │ │ │ └── R_01_easy.txt +│ │ │ └── sparse/ +│ │ │ └── # if sequence has CPs +│ │ ├── raw_data/ +│ │ │ └── R_01_easy.vrs +│ └── ... +└── test/ # no ground truth + └── sequence_1_1 ``` For more information about the training and test sequences, refer to the dataset details. To learn more about the various data formats, calibration files and ground-truths, visit our documentation. From 59604b435abd3559cebfbcae6f209a1bed24178b Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 19:12:02 +0200 Subject: [PATCH 650/665] rename pseudo_dense and sparse into pGT and control_points. --- README.md | 4 ++-- tools/download_lamaria.py | 8 +++++++- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 553be8d..89978f5 100644 --- a/README.md +++ b/README.md @@ -121,9 +121,9 @@ output_dir/ │ │ ├── aria_calibrations/ │ │ │ └── R_01_easy.json │ │ ├── ground_truth/ -│ │ │ ├── pseudo_dense/ +│ │ │ ├── pGT/ │ │ │ │ └── R_01_easy.txt -│ │ │ └── sparse/ +│ │ │ └── control_points/ │ │ │ └── # if sequence has CPs │ │ ├── raw_data/ │ │ │ └── R_01_easy.vrs diff --git a/tools/download_lamaria.py b/tools/download_lamaria.py index ef29020..ffeb895 100644 --- a/tools/download_lamaria.py +++ b/tools/download_lamaria.py @@ -293,7 +293,13 @@ def download_file( for folder, sub, fname in selected: url = BASE_URL_DEFAULT + folder + "/" + sub + fname if folder == "ground_truth": - dest_dir = seq_root / folder / sub.rstrip("/") + if sub.rstrip("/") == "pseudo_dense": + sub_dest = "pGT" + elif sub.rstrip("/") == "sparse": + sub_dest = "control_points" + else: + raise ValueError("Unsupported folder.") + dest_dir = seq_root / folder / sub_dest else: dest_dir = seq_root / folder From 5289efee95be5a09f212cf107fe54b942577d0f4 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 19:14:12 +0200 Subject: [PATCH 651/665] fix readme --- README.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/README.md b/README.md index 89978f5..8f6166a 100644 --- a/README.md +++ b/README.md @@ -72,10 +72,9 @@ python -m pip install -e . Our dataset is fully hosted via the archive here. ```bash -python -m tools.download_lamaria.py --help +python -m tools.download_lamaria --help ``` -For download convenience, we provide a custom script `tools/download_lamaria.py`. Using this script, you can download: - Specific sequences or entire sets (training/test). - Specific types: - Raw - Downloads raw `.vrs` files and Aria calibration file. From 414af60538408070da0fc762c7bf9151bb0aaa93 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 19:15:50 +0200 Subject: [PATCH 652/665] update readme --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index 8f6166a..98be5f0 100644 --- a/README.md +++ b/README.md @@ -75,6 +75,7 @@ Our dataset is fully hosted via the archive = "3.9" and python_version < "3.15" pycolmap==3.13.0.dev0 ; python_version >= "3.9" and python_version < "3.15" From 1e8885a3f188f296c9ed8dbe83469ec975ae32fe Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 20:19:48 +0200 Subject: [PATCH 659/665] format --- lamaria/utils/aria.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index b18fb80..b7e6375 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -423,8 +423,8 @@ def get_imu_data_from_vrs( device_calib = vrs_provider.get_device_calibration() calibration = device_calib.get_imu_calib(imu_stream_label) - # Note: the bottleneck of the following code is vrs_provider.get_imu_data_by_time_ns. - # This should be very fast when a parallel getter for multiple timestamps is available. + # The bottleneck of the code below is vrs_provider.get_imu_data_by_time_ns. + # This can be very fast when a getter for multiple timestamps is available. ms = [] for timestamp in tqdm(imu_timestamps, desc="Loading rect IMU data"): if mps_folder is not None: From b82fbd1632fe05e242aaa90a1734695ab98daee9 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 20:33:16 +0200 Subject: [PATCH 660/665] fix --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 67cdb10..b45487c 100644 --- a/README.md +++ b/README.md @@ -213,7 +213,7 @@ python -m tools.asl_folder_to_rosbag --input_asl_folder path/to/asl_folder --out 3. Undistorting ASL folder images to PINHOLE format: ```bash -python -m tools.undistort_asl_folder.py --calibration_file path/to/calibration.json --asl_folder path/to/asl_folder --output_asl_folder path/to/output_undistorted_asl_folder +python -m tools.undistort_asl_folder --calibration_file path/to/calibration.json --asl_folder path/to/asl_folder --output_asl_folder path/to/output_undistorted_asl_folder ``` *Note: The undistortion script requires COLMAP to be installed from source. Please follow the instructions [here](https://colmap.github.io/install.html) to install the library.* From 88b51aff2d948510e6b364c01f4c96dc32f5884f Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Tue, 30 Sep 2025 20:43:15 +0200 Subject: [PATCH 661/665] SE3 type hint. --- lamaria/utils/aria.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/lamaria/utils/aria.py b/lamaria/utils/aria.py index b7e6375..0eb2494 100644 --- a/lamaria/utils/aria.py +++ b/lamaria/utils/aria.py @@ -9,6 +9,7 @@ from projectaria_tools.core.calibration import CameraCalibration, ImuCalibration from projectaria_tools.core.mps.utils import get_nearest_pose from projectaria_tools.core.sensor_data import TimeDomain, TimeQueryOptions +from projectaria_tools.core.sophus import SE3 from projectaria_tools.core.stream_id import StreamId from scipy.spatial.transform import Rotation from tqdm import tqdm @@ -224,7 +225,7 @@ def get_closed_loop_data_from_mps( def get_mps_poses_for_timestamps( trajectory_data: list[mps.ClosedLoopTrajectoryPose], timestamps: list[int], -) -> list: +) -> list[SE3]: """Get T_world_device for a list of device timestamps in nanoseconds using MPS trajectory data. Returns None for timestamps where @@ -291,7 +292,7 @@ def get_t_imu_camera( return colmap_t_imu_cam -def rigid3d_from_transform(transform) -> pycolmap.Rigid3d: +def rigid3d_from_transform(transform: SE3) -> pycolmap.Rigid3d: """Converts projectaria_tools Rigid3d to pycolmap Rigid3d Note: to_quat() returns in wxyz format, but pycolmap.Rotation3d From c10748c85eb5fb1a0b0192418469c1b6d5d96638 Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 23:10:43 +0200 Subject: [PATCH 662/665] optimized --- assets/optimized_result.png | Bin 0 -> 362054 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 assets/optimized_result.png diff --git a/assets/optimized_result.png b/assets/optimized_result.png new file mode 100644 index 0000000000000000000000000000000000000000..cb7f42c8a75d4f2f605a08b4cebbad7caa6a438a GIT binary patch literal 362054 zcmV+8Kpek`P)M00P+v1^@s6%wBvp00004b3#c}2nYxW zdZgXgFbngSdJ^%m!CUiwubVG7w zVRUJ4ZXi@?ZDjydb!8w^WpE%fFd#BBIxsgnF*qPHFfujxfssf603ZNKL_t(|ob0{X zlU!GR=l411u6c7`YG1H}AP9f}Ni@l3HS#P_*rsXjxKg)aq5;TtuQ9AV6#cu@z9Ly(;&-%Q?pnSy&3FLKT1nP$28` zQdOBZ?>(87_nh)^;c4|M>I&hqu1^6<*l4=howY`L{p9^IYD3 z<5dKL>A5+^hKC+{j8aO3?cfTDlg=QN!aIEucltV={V$?38K^E1XLH1^M-+9?T0ivl z?uXV2r4-Hj5}xOhEd=CpS@Qh_9M@TK?96lnV{!}(4z78=*_mmST4Hc0`&h=?3yk@k zR$~OMGCez|5CSPJtkb6uAH9cp`&%UA+t6C|>>4*|)@#g9-=JBq;rjuep8_EeLaaMR zKa=O@@Bbsme|?;>u@R2Ec#vJ&$2ocWJd2Bqy!OfwqE4&lV}4vDNlX-W=o=cLRjX26 zn8WdW9M4Be3n>Jw^SL|-S}CHiP2b2EnOweS=Y1BbF3hqpJ%#J1ky5UDOdQ9YI(?Q; z&tG7CWC+jmsTA`}Oy1!9#jE@`|MH)#dHy7hXx8W1`{Ju>p8sj0wPAj;Mz)y3PrCp} zXlC>@$k_ z0C$!1-ig!(=NCUgz4RI?o57gd>xU2tsq`5v`#E6c=X&YPC7SgF*GoO{=kZ0tvTf4Y z0+9xZz$6iND&QBte2*6o9^i*R`Z0g}hrdU4cIs&lbyHxBA&Db8ttN5U!FC+{AcO6C zoATcMBBQm&`jdbCU;i(UauUb&sJA+VQHW>TBymh%e;;w8c>jYB*|B3MgMFoEYP0a5 z7^6uqE|5C*0m;Z1;R9?WKKk`1NGZ88ah=OouaV89@jREG{Ne)+KEIdY!2vAGBAL=uw`3 zZa4W%icT1D`RX-NsT2d166zUpG^iv&2pAY0CsQa=85%(dL9@C<9JWD#kP=wm*xJzb zRD#k81Eb@QKKN&xg{f(@(m1ZW<}oKupJQ@*mT!FZD~t>eQERkVsyA>Qm+yS@tySll zn+PFLO5^z{T;G2jZ{d*$TQRc}a|F2*uHW6<8)J|`7J1@h$Q9A$3U@oRga8yIT9LV9 zE$MVRgkgB=Z(|HnNZdO<-zbV`x0|F=_xn5q(s7~E51tFQv%;7FfwWpk%SQwo< zF5$SF@AH0=_?aBnr{{^|h;pew6tzkDKDOuc*MIW^jvjr5z>%or*_kUJ2S#hcc9T|p ziLlecvK=z{5~*|+%XWG)=Wg*}2qC!lu6{s*Y@VO|?cedv+izmIE+mSNe)S1sVI*30R}q^v9j3>-|)vzo#CZJ``Nv78VuR0jKSJPXUZzo!epaV>1y&}udb(&<%?aUBQSPtjqmr8`b} zh)O@i5ki|)=K<+J6h|0iZheN9v=BnvavljGkk-oYYBranR-0dEWCpZGOkPLM+`xS8 zox7eF7_EVO*F`_@upNOh8X>-%9%UgVaiXc!suc4%q-FE*@smhl6J*l7`;B+lK0e0$ z)U~HQ)Tf5lns%c~r`<#diRY(DWwKjQh)u#H852SXl<98fEX(Heip;fQaY1TJ<>2Cj-5C~CY`3g@@y=iS|xM}MdUlbi7u3I6Gc0zt^2x*mnX<& zGK>rjGB!NK-km!@z`y&y{%;N+c%E{xu%YYUOn0#@8&@TWYz`qHef+05QspgrwEF%X8E_R1y&0+^#w!Q21sYq_-P;8ez32cWeHqY(rUNYG$y2F zVcS0KcH=1;6B=ltbrqwVXyub6B~+5enDvdON4>WE)juMX!W?}AtS94{$>a)Tas^b9 zFgJaJ`RN<@o{#INke0n7T4A)t(EYw8aYQMfCYQ@%q7dElDA?meD}_=Cx#H?`lOLoR z-o6X7&9FE-&Em`y#(?Ab*p7n`@_{^OS}Bq^qS)8ptGDpXA}vX~UB~r;HIMoD_(@)P zZa1edT;lwNi^TEm&Fl8DQ7&A%!qw}OT)jStZQHzZ_yAu$`qGO3iS2rHT1yyH*mPb_ zA;58Lv;rY-2Lq+$z{{^ekVZHTBr$hKC(=Q{+{6@mMBj?e*p7|od2~7*gb+B6gMU{< z#T7&@`YbcE^SpTI0MpYm965ZLR(y z7Z#rxV*((FW0G=r!I#D$q+IsItj)(KPBJvu$54MC0IutB_1YxqREm`E(P*~Fq*qxu z@9-+wmW}PFaM~@>$3DQSF3~#j72@&jG`{*aa%PH7zCaR3s3ch)Q|~u##u&m*6BWn! zfkUAZP#PE}l}>e2VIE;o&gC5D=a(oJi)*GR>E~BuNUb zvZ!SE2^bK!aU2hEV-jIo2;YbJ$$I)N+h$;7jDe9c>Pw3(&P>s6)VuS8>vhw9?(#T> ztycGY{0tcq#u$`RWb(yz7cwCPrT#%m{e!d{4Hjl@(5Nor`6+DI+i7{ z>$=2BqYbP(vyN^iga0}GZ?dkz;O2fi`NbFb^~q29yPy06 zzyDjm!M3rHM;T_%2*Zelr7A-MefK=4k_e*`(x3c_s9d2_tf2JTo4RJJ&B9`pgZrOb z;jRDp#3_ab`}y_B(_FhT&GxYo4(#iu$Os{kmWAVbSdN3Uuz)vtkz`;9q(p`tI=l7| z=L>|LHc8Y$doH@!;BgobDv6itD`G4Q$^!-RrTlW(+Gf=i?I8#Phlz;=;y7N@mZOJr8H4z45hZiDvRXfMhF4bD)>GoUj(g}$MAGE>DfY&Y@tXJ zM=VTFu{b-8?RvPLkF>0np803UkN_~tQHet3-uwT4q%s*sGJ7yuvp6@y;_MVcNNm@` zvg|dZ6_`c7M z@llQ*KFF~Xr%00S!f87$j@GzQgt0YRS~yV$dvOk3DAFF=M*Hn=k%S>}5@DLrs@HuK zj4>G9-QYx>HbK^>Jdh=m&yvY!9$W6Bkb+_M2q|wxD_V^ji?h?T8&xdF!?sPOGc1 zqe*|s6`XG3*fw#efs-lU_c%j0ig70|zj%OSCr++-EVVq>-c1rm6f6BJY6~_KLU#At zE5{}?fahagI0WrBQd%f=dmP5t zXk%lU7KoK8tF~iP?k_VpRl^T9uPWc;Kx;)VA5hBYc>lfkn44eVr6UJ9a^xjurl)!P ztv6}c*H4>%mWjg-olc7+>L8>fohyFn3-X^e9@?1DTG6UkdG+Yay!F{q088?n zZ@r6aIS9wWsV z?L7YU3n2uVjLWr&1qKEOS6u{!5ClP*D^oWZ9yW+xdACd(V=i~=K#~!(8pdc3V>X94 zfK&#gg=p3>OY^A5P)Pr%wo;F4ZQkf!3CCIhh=*E!pTx{DWxg*VK z|8slzw}1BMD-Jz!X#c9Guq=l--n@|s=%y@Ty7Qcr-AJSs@81JI0a3MI5&YtTZNs5acTbrY5FZ@oYICJhCKltmv;@x-OrBSQXX;#-i$umf&)ui2OppzKeb;uU`u(wh=pGh7{ z8dgY2kS*Z2E=nb|8g(kA5-+{@BBxKEW@vbns9DE6z{X~BYKF@b*Esn6a}@Kr^!qLXU>04z0t&TUEcrrIH%5>Xa94%SESt-qp>^>Z{`LED z5=V+o`v6*{F~;R?o%E-Nz&dptvABR48OOZ%GHMg24q3KMCSRa3G=h|pW^IYE-R^oi zm*r(Q>jq9I2}u$&IJUi~V-!*nWU`b7hH!nKu-%~3YNB;a5=9Jc-?gPyvWyUdR=rLX zwy~WxgcgLLn9p$f+~-8g={$RP?I4O{E?-@#g!8-Ke)nEM2xExC7KKXxrj&-gNfIim z^WCWbO=Tx3C5&%}Vj1H)tIB(KbI}w0RBBCm-PH^YDJAps^P~g+zTZb71Tu<{zxXln zk(aqUcS_0-%WfmYy=%Obl2)Tl6eeGq8X?E?NoVpTS}jL>3<5)`Tw!Kz9x(Whe5Rzc z*Topxtp>Hlc~lbOdOn##nN&KrA~L(hv&BP2CW1_k`NbuwwJO<6np`%AWmzOf(LXpy zwOS(|_z%=u;^X5d85-z+s%cHlR-4o3KBK>KZwUC}v>-Jkg@+jbK?e^1^w<WwuX8pb%a^Lega%evv z9y>u8hP-n40RP{A`tgcmc5NTW_f|1TgrL)DlF9cvRkF7TX_%j!r#P4=o$JoULI}kC z9AvW)te%P|rNHQfD2};X+9Qc$I$=nXBuFVq2LYCS+fd2p^E8`H^0~F0ea0-OI^_zu z7cLO*Kd{2lrBnvE4BT4>X*)K#QkLr%r@u4}?1Xf=d~K5HscClY*iMl0v1~~;n_+%o zk)yA?Lc6-2EblXbF(|F*G?$$Lwo4|L$MI5I&XO+(54BRoQAEo3xH?he`t?bQ#R4hc zr&_I%4g#`ipX330ON3Fx)$5bI@#@R>)FM1djx85IzxUCvxN_|}uN*!|xmaLfu}T<4 z3=i~^NvGMpV|9sAfH(~4?AVQe>2us#osMPQ)x$w>=!Jb41HNTbay_>9_v6gX5Pb9= zsD#GXzKJo0PPsxOmnZ48(ONxG!(lZn%O+HYX07qWjR}BKCC!b=D&#@ zJmr$YaeCwBkk$Z}wLp?Q`Lw&W5r`X;n6Yh`Lq{NAcqTi{d#Myd+jcOtZ3j!UGc3$Z zp|yT!Db>e;)*7W0#qyJJbXc}Sd2slNT#Cr&lW1e8 zH&)i}z5L>VdtYZD3|o{3dXvibII&%u?FUA0sW}0ddJS>>Bh2^?D6cIN5M%n3!ugm~da%<$+cbrTL+Wsoui?ltD}HCmWqsZDRjNyiq*5vNKfjN#-6DB_6sHrX&N4L6 z&(!oRABM*n9von7oMd=#V@>3Y)lwu>tuiO16nV?MrYpvV%J4E9+Bsg)T_5co0}+g zMM|66Vx21VTe%Y_igpZ^fq zYGH=Q(BJu8%oCP`?KOqIehPidjo+rHs8<(pm!lPr()jIB(MsWXF3xJ6>@A)+mHuI7 zZd}E2yfrr@nIPbsUw<8?6z4y`gl$mK*G z=x+8cRID({V7nH$F0`5m$HC}i&Cka7JnGAmn>SNcl~T(E|6PnR#LH6RH)W86binlV zB&E{*(~ylZnCJFG6fKWoW&MUqTx@6c{ehqINM}>D8p)T!n25tR^Ea+j%BJ}CH{T(Q z6_>AEVc+vFkO@3m&uHPbO5$!7L$g5=$7J$Fa-|BJW&PZu_dHb11avpeao8d5v?&z} zjEsy>D&&a6HgULdIaq*yc>g2DMuzY`kB^R@#Pi&q$iaqT)NQ1*flcrE&o8mCROQhA zeeB(}gOR}j#z%)h2>$j*Kj($#_AoxWzPGUJwULNI5veu8?xreuK|uD}RdT=j5NQmm zZvc!Y=^v!sKS*p0Z7B(jCb`uQV)LMqgs9U(sfcEy&ghPNRZt!`LVzWq)iPwVtEV~% zA+Q~XMs0~q*6)$?Lm))Aj|66Oq@7rCj11D?`A{s93=Tb!x|t_|?YLx%CCURs7-Og} zE|5gwa=(i1=Hy95E40=maY(6u@S#9V+Kdi{X?uJ4{Z#zT5Yn~?5$!~Ap~(0uMlvsZ5uyz`#UeCq*1HldCvNE z6H`;jU;G%e^EvcghgxT|f~yUfqbV_EJ~k4io%v`PruO;psOQYzy)f+XsY z#P_C2Z)V~+q}{5~s#l3S9n$#{xniZ;Z)nSq_(Ic@ol)3s5wo~ zxon!(j~*e6dXxA4!LeUcEEIU*u0rY6xS8TK*k1v<-YbAlPM>3-ue{*~dfiFZU^@=M z#m~^%5V;OIoyDEFjB#C(e79?G==mh&3M!5xsHAp}9jXYzWDfx)3QRh@i4#r&MYXoKicH)v@Uv8*K$J=l};JqlJFV_p0VF+GI{ zQm7YSekN0#*5l5`Z>>h1g_$Xu)x}%26;C2sp;dy>ifp0ySg*6i#t}kLtPF6ic9wQi z;|G}yZ8~@F+{W&m_x9{CM$>B6C{+3>_Epw={mJ*fPb!n=}U4eE_1 z!vp>I9Q*O{lMM8gxpHliPfnksTD$i~7eZh;E}rX?@q7ZMu$0DHT*Ud{XApK!*&MYa zM_K&p+f;)zjp_nnt4^eKqZJ(hN6_qTD>p;hIb5;JmYDbUv#wA zbXpCT=B8-XtJrpmd})AuWdO(Xw+x9d84sQ2wAndv>I`v`&}_B&yPy67r8J|%tM@4Q zF%s&y!k~43tvh`2n8mkxCTV3uj4x z{60F9Ls$AR=?w8puTk?nI$?)ME21debSX?)E0QRr(`q1OLavmif3(8r&QS`L0$$3; zdaPZgH;$BoPAxa-Xf+x|plkhjwdHL`^wL)*6BH_A16@e`)5p5gN84=4?6n zkfLk+2!W_Ku#dfuF`8sx{pe{NCm00TY;IK<*tIZPQLoiVr|+NgCxnIW>qAHjO68Rf zGh<;}(^z(nRoh_$sdS2&Ytu-}dFGm1evvWDQuOU+o%+%|7(p4aUg^t1=L z#Z%!6dzT(Naf;!=eqKI&fLC8Wyxehj^{@Hqa~CKT3(U?htnj+HuESej{R;c`?Bch- z^$!2jzy4QLDiv(kBUkDpYXpT;$4Sl3AS@f%ZV^8B0%4_}cBjRHFw9jKy0r#TxT3)A zY17>(wF%oblDJMPBiVCk2m6lfVSM)(g>nJQ-r&Oggemp~H0t&Hex9Xrg=)3ELP_M& zDdYNAdw9NwK_X8a!}*K<6O%2F*w&_sY&}VWY>ttgd)T@E5ZQd5cB@9%Y7mDZN+pjR zt%0s9mA&x@gC`2Xq=9(L0&`K@$=;=lo2gi3ZFnWJO z0w9S)e&@gXH?(T=jO}@e{_%ZGUp>p;{MrA^{Edr`>D{eQW3kEkW0#2I1abLuL}g=& zbE%X^tyX*Bdqi3`LWm8$P7IDgDp=JRP`U`Loz7#7p-{;^aQ)>LkB>MCsV^-sKXo0g z73KcnZaswOZOVPZ7EhMVQBB%oCZ}fElo&Yx03ZNKL_t(=Y`d!pH9W-F@X(5GsCRPa z`~@ndA~&XIId|bA!-E67^R?G-9fu&5A{_(>X<<7qjxqT2vzTHDB?NZV!D-fEeuijd zjHSazNsJ+hBlIRzVbDsUlp^djk(QxY$&oFT$d~fB^u(V9{FFnYYD7_lzeZyz*L4w= zL)eK4(ml$%6)9{xTJAaVbUrV;(?(vqjM=#dCAyoVFFVq*C=ZTM9vq=jTVio`nohHh z?RZ#rx4Ghj)>hmsyzU#OyWD2J@A#qP7f)d&uMpWO4

    2-KBXlKV z4NFUHa{0Bp5*wgat&+=my)&AGg^&}((I8JcOVE}!`Pf-Y6=YKFMQok+_foy}1m z815F0wi>q;=fwSMD~vHDQAn;>BFNrfQ-6!ihY$kCaj-0jp9=7NzuT|Gxxb|8dN{Vr zz}P;dWifU6Q-*iF$oA)755#f1|;$8kLdx4qEAcXWSDtA+jZAHw(! zjBRgtEoz4$mhBJ(E1R$;NkY9|CypW#rLb-L*1aO7WNvPbwC}AeY$9AAd3^#|U4-ZM zuc#F?#=&-PAZ3BI>L#R=D3#Etwy?hhJtv+v#u(x#q*-60(`tec1eqM^Tmi@Z^2qdV z@o;?MA`>S*J-Zy0*jVnUloo-PLfST|D8jpN7M0Br?%WGNxMv?xCQB>?ow031oi;|r zunG5ZNgNSJ5yr%LDT~pa{iJhgJb&{PQ1=SgcQLd`k_2}R4_OcdC~cv%?qLC~gAhYF z&J=O<=)F)jijWd9aT!soVs<}wtD)h|lm;Ozz;yGOwZ0<+EfAtxWZzBcFx}T^z3dPa zH;=mIAkz@I&Q4REpIwetc(+oZ?p!F1>83ap z`!-X@^DQ<5eItA58`;C3{tvJ7-~O*Zq*0ya^6B@1ZjH_K)zdraxs>*@6QNtP zAi@y+;V+4mhA6^3Kz&cj_h{4`R4TW-WhZe$v)LfJ+20_Fx}pbn$i!x|Sz4_YdH4Q8 z6h=Vu##_*AEDv{O^SUH1VOcGNSUWW=Un+3p$_!fjPgO#C`l5d>(!_Crq;k1gE6|B#uUc{S&u>`N1;-{5B#q3&ll92Af>=h zS=4IP6^r4W2q8$Pvn(yv>Fe)RZw!GD1#I^saWuq}icVP4M!f$sgzKUA9|EJ1!h+c; ztY!lVnC-g}*RP@4O{`W6f;4*X^DsM&voMEgG*BaBh{0h@t%`N=LRY>qoy81~AX*K$ zdqpib9O*WA^RGBr!&7jO}2Ier5~|$MxtR8K-|_oZ8|%i!)Pn z!WOpUVcQNucKcSSB*72TSoYIX?b>4Va{cq;pI_rJg5Im>o9@W$`=>{?w1 zfTT9ppiylRM-d~t2e52`5Egd5L3Hj@>~DS-mCIosC|W5H!mLPV62cJQ)hJD=uJrQF zwZu=QSZJ)@3&9wJl`kOLZS?Z%R}^j=z(n`8yBTTIicN4VZr)5u|J1M1*&OY|M`^zDI?A?*JfEmh1H`6FB{9aJl9)ISky7J0lD?q=#l9krXMd@@ z357z6$%%zEjR}B!p~&Qw*&Z4b03Mc=$Fggvq|n3ju7yC(&vl~`ue}LUVhM@-=zYZT zkGk@U#S&`A9>m-X_SsJnOAD9-hmpf0h>0tRPmXo#1ulL@^auYr&b6z^fBYrni{QKH z@^2wN{RA#wL}~@nLhalIbF)|{e~p-(hV8pxU=TTZ4W@5ED!`14p||b8#1TeF5G<=~ z-OPpFoRYPhtIsE2-){{9{2nj}lF-%^X=EmnYaC{rvv6!Fq7~I|m2nf=6uYL_ZFo@O>QmoMVoxQ0$=XdgL>u^sH|SBY~4BHJd3dLt>>YmCv$ zstO@tr%fgwQ0gxbWYf!vBwx-+Kx@O*%QXguwvkE&YaFAQxO$07#p+?t34nQ`utnJ3 z&f`dHxD(5=v9C=aCa+^g$Kl2VW^6kmilEg*_YY#y8I0>7jle9Szh-M2^ zg0U>n3X#oYIvs@TVCEN~R6Rplx=l^Rq0@PUCnfM(*19Y_Y}NbedIK^*P*B zhO;04km)O@`TFnw$t|^~N5Qfje)JbVU-`{fm^gopg{cJ&eeD1& z&SQc!*fwDl5w#Vm?8c*MNurovtTHq_x}s-KyWOVUZlkrvbzRcwV8te0E6tfRpE5Gs zhqX=(ie)+2-~0DatdRW1Z=uwkQ4d3qIge#;XRW#k=+5Eij-MroZ9ISVd47wHk;D;8 zb5po}Kss00cwd$+wpfRroB3C-O)@qz^i;l}!$X4z(bdAX9hU=p_Tb&Pju3)mXoTS0 zDO9dNQmT+3NIGqr**q$VFwrK{vtABEMqvvf3`rc*H(X(GdT>V4iy(?Kq%RH-eGG2*+Jclj4rL zjyq~UjONZ-jhkr_x1}$|a_plwQILGOk9@grOKx|I4dJKr_~~xG|10nQ^PZktDaFo% zJ9zJ}KVW#r5K$O$_TzJ$|J4P)`g^Zq;t2a^e~*bn;y?IjOkbHtE6q@<56j+Inu={( zwA&%(u84;3`?u=Qx{UzuQgp%)1OagrWBK=2SyC!SY~P7huS2^H?w#wF!DtC40kO6* zA*Ez==NO-TauLV%wrVFH0n2s}(!%xJttihHJ*B7Lri)i5IDPH{xonm~KHJMv-xnz@ zgtTyM8$SvW+MrVbvePDY?o)IS5N_Ya!gv1&Rj&~VF!d_h=&sJ_CZXF@DM3h!+TskE zT#8bEmTVzQVI5uXFDrh^W?`{TQI*zI7fGcvEX*xX$g3U}qB}^L!nT{l(c>~E1Xdiw zhrfh&2U94K95{p+9z(efCW+Q~omu1O9Y>gz&zX%JV+=Qy2b9q$qY?Q$LM52dG2}n} zFOba^bXt%vz~zf@@&qDCBd<>&-gp}^aS1*<3&k=fnFGA6<(qFSxf-&bDo z__5@RR|&wjMlq;tK@_5b1#q#dqZn?)(L<^mW5X|A;miGrRwV@v_t znIVqK>mU0N2qBS+i-?oQ(QkbV_8&wiF|c{khHgd{0F=@w-$kT+gi`RrA;h60STj>7 z+d*V9h*}j9FAEw(5wa5^&z(Wc-oSj`LY6A1Juu|{Kj`t3v)OZ&Lg7`vRU+3zJ{2a z?WS%S4XHF{d^@Jo2HVB7n_bO*&skPHF$mF(fZR^ox-%NGdFw;Ac=qUi#}uP`hZx#9 z!0X?Ajj$8qdMK8Lp~57%n7nO|IDpudm5|Jg5z;)Fl^?r%^jmwGl>AuWtnxPE}+ zdf3L`pFfRNuhBkmn51t2l}Ztf?VuBdB%L-I(4AJ##?UKn7E*_uI*wVMB?{%j zvRviXWVsQf6cmd-^?H?Zd2LmvLa|JBsY?Gq5BmlPA1MveYN1u{b9sd^h@}Pez%Y7X z2%W^sGOe4N6$(#@LYK>c0F@w*eie?sfsQ*^u8#rqo9}kLtO9U7j1cgZufg_Rs6r7d zj4;^@V$VKQu?(3kCJvFd1GxhF8{YwybT=xwJe2w&jG)$brcA~nQti=VeZL|C^-*O19UsSh(a1fBI{=4XT6rp=(Aq*;>zhI8 zY?>hB5{D7Cv(?1zVG+yyBigO{mNBtK&v+VqOeUIh0xi2-KdSx z#8HGwBBZ6s6FDbin&?SK{q`L0Lvn|vl!F6S|)F~cKBDZBL<807X{n4#gW6mA?LEDJTZ4O93%$mS7C z^O*iYgp}xmM=+j?2)i2lOkGD_`WzDkh>zY!{j-0CxO4&e-p|02NXth3&L1JKT}4b@ zgQZ2t<}h!56RX)keEJEdUPTTL!3&4cNrd(5k1;|Za|O({9bnstv!7xd7qrIg-b<2B z z7Qt~**0S+qI~X)Z-!?|J*klNa))GH#ap|Meod0~5eQzFNXjdP%qG8(5tTvFAAYDjp zcqy@D*C5gQUSs0seYRRB>`W%Z^=nr##q9dmQVC*k1byQg=HQEWJ(U4*9vIuuc>9L? zxO#p9+x8x}?!~5{yJrZoZD-jL(Hp!}npU%pN|LSm%Po4seZNJ=Pn~A>&K+ce+t%xu z^A{+U3N%}7{^CFW71>OhKmMKXaPssyjvhHgrCg#?F0o^L^pOT8gurn<90a!32+JXL z{3G0JSBS=U5RGobqym->zk*H@l6LEsmu54ewL&XJ9EBJYlP_njW6nk1+#X zd0S(lXF;1XqWlu3-awZe%-_41D2*07VQvoPr7{0$08qat+fv4zp`Azh}BUnHAJH*mLH}CzO zZzD#>kQdGqk8Q(hG%&dW*fvThx69kN42-9Uz;#pnq+Dk+ zYTKB60XZ{;BP8*i_o-1NQ32NvVV$}OfJ`ofAGjoOgzbEByJ8z-h{86ldX-{do`sod z3VlO8>j5F8#Pw1%8#Qu;-er$$@#SUBSzu;vo)e#*rN6JT!kGB@_$kImhdF%UdB#VE zXtvs1p14LnpWATP>DB2LeOZo+EhV;}LUuZ2e)(gJWz+onyL5IvM>sl8Sm`H@LXvh9 zqtxaK+b=J?aU7Dw9fSq0V==mGfNUYNWk5Uz9NWT^hIXs9rZHjLHb|RBr`=Oy0^tBI zwlzOwtWVL@{7qQ&PIty@2D{=T@l(FHoa%42uRfCj*7 zbKv+YkNx)m*f#jSA(et4^)kMzNTmhA_YA2(;9KLQQidP^|3kZLjOc$#katK;bnqKK zDc=yte~F(Gq;#F2I)dMf310p$@!PYcGZub-87EGVufBmbJq4D9^gLLcN1Qy4_k+L0 z^bL@_{Y`Y=0CM6AmhE9|3kFBfMs=e;x1ty88yHCfN(r6@=v{`;=ux{rg_V#RSc&!-jG4vY+IMn)7P!i|aYm7F+m1nqGxu{2)zraemdv(-vDiD0Y%0oIZDfeS3HP|LnbYm?dX@ z=lgjpo}Bu0PBT4uB+V#G2uYT)5JDg@_L>#g#`cLM{fn=(YL?%TnzMhwOsgcOVn4Fj=o6Cj7VFhG!IZloDlgkDe7fsbkAhZ-# zWE9`eqtu0mj5S?H9NNc6zj_8T8dj zL$6L>zs|(O<@vDmeJB~bmtJ99mZj+*vB^upHEUJh^ zLlP6!e}$OkBLhkBH#UACkkg$6j!&Rlco7?kLEv}HHwK%bdG?0W%`O3~Ea&JQ1bkz3z(D|W=D z=ju(Qa%r6E;ypn#G-giClWIs{tkF0W0+R6<^Ye3LGK*=+)#`Gobfpx&=P!^6fQW73 zdLEI;*_|^A!oE1OGqqI3#but;f*vh^SX&)LGLs?_Gx0nZ(|YyPPI#_^=T?X(ZQ3_( zB$-KJnBn!`($&hTk^NYa=tWat(hU>C&?y&YNu<}K6YIDz7<={|=61%S2zUBfhP1Dc~3*9t{ z6bqP>leil<6FD(}In;;SvlS&3K7#UwP57>ZD$ZYa;r8$b>*Bd(1cE@iv~O%Do6n#d z#zmANUB}swN=4}F9me-NRwWaOM1teT90LDhk_iwZfzY#Fx3 z-o-zBw-dg*xa4vr6H>z5oW|UoV0Kn8Tbo`wZ*ERwc23~Bq37811bz^<%BLtyw z>U)a>!Sf*S7nj$^E;VG=u{J0Lm5QKJf$3%5&6S)TD@9nY{M_nNNpR$-!I7h@kI7^d z?QH?=?X`$Tjbyz0U6-~OQ5dln=(>TJIEDW0uYr`vd+w*Bt&4P9BW}f^_b0uK4V*;N zHBt@H1uwr0Boikl(G8t+ex)edD&MOKG_++NYRj@HmluUgG)+TWB0DRDAf8AvJ9Uaw z@@(Iw!1WLVy@+Fn2;TUX)0Wo@x!1P6rfJZ&p_Tqa!x*M@MMwJUb(F=qNgA5-bZ^~A zED>FHtO2ZuMZPUZY0kl3rKi%lLI{B!iBp)JB$mvqM<>>CK`{30-OtW#n>lo>mm79n zg|6%DJ9vba=0-Me?B?q2TNyn$&W5fIo_OlVy#AIOh{qOB=I34v3$KSqPvW{B?XAr; z<(Erk3Ly|8j6hh1fmx}b5-Eh|l6>lMWGao{+(KpRPKsN1;-HY_B7yH;UMWn}CHoXk zwS-eCkjZCBH)P4?v&2*JbCcLx$3=ruipHiSv$HcaH@B?#8z`k{ZEa^}dY0x^>mo+T z1<-_H&Jg(X1i|?W4``Z(n4aPvzO(g=WvOfv-}&|on>PhCHC^26qEHA8{+U^E8WE_y z*XGrU!P0q!!j*l#+qR--V?aYgDF3Qyp~qI#-ZfEs*I2fE>ANNrLP<0s5lZ1Yib@5l z6%iWn)$mnyG|E+-s-sbH^~mOs_&=8eUg=99xrd>Ux^BKThIEOStqkCr;R^;3q zC6S2Dz|aWoZHsk|hOU!{$EZ3kzV8!_M6m7UQ2@ix5kgy2nv66wbjyT^aWvOM8jJS~ zDI*}J*1o|)kjkbp?NR(IJUTHyGeIm7;krAn#WbxmNJJf)rqRBkjf2k}#fn5PnvG#v zHkz(cEfIvxVTnulB=^3=%UbN%2S8pF$ zZy%J);JOIU2j2tF2hT%`$nmX;N~c%_=k*QJ(@O_@f*qQ2SvWbl6=xke(2Tz`<90cF-%dkU`vYhP)6z5ZOWUI@`t~Z8 z?delx6BYVAw{;u0J%uwW!rG}o=-xZO{WmVxz&b?b5hxbBp z?8Hf8a*$I252g14W{K8HaTA5%#W?jAqYokOpG6xLj(;mPtI-hXf4;KI_yCazby}pQ z=xnm066@n&!ClQ{IGdaurJWL@-0m0peY}{tF+OG?`1o_6c2ZaHeaT1k(6^x#V&c#@ zP_??o;W!Q(wEctg#U@TVblY-yn$HzsbMu4=A^sKEq1){i?d{=^;Z)nl_Yp*Gu7?zGjx#$8mIEK4#T?;OPr9+= z?>9@$Otuln%dkWqFiMnD?=*XY64LRCxTUb}_6P7iDAhJ8NJH^?`e!Czyt(Un|9bzz zoQPCl{Au-mk~L9b(9+JHE=xZDfCMo|#HC-_bMAbk$HLmK2c$?+Lkzqqymq{S=Vf}X zE$x$l0B@|RmdRh)2Lz?FyF`&a*qRsSu*A=kn1(9DudHzK>hvxmRN)fSBlO3)ekP#M zzvv^Rja#-WfiQmf{(CQmLJf!8RB^V6{7Qw0O!ITyI!NfNx4%vqb=+}7vFFfP3`Tn$ zp4Y{Cu^kc}p7cESf>b`YYMg<4LDX3(CR`CNS_w)YYtqkzd}O)m4=mISiBQBblikq7 z4KpGOehJ$i=89S|V&YPYH>ZvCs!)Wwa3&E-AqY|m5(-jodYVh2Bk1z!lt_|1^!yfo z?fU3Dq=&u0x4>tT=3B_Si!V-^U&lEz{^a3kW_q7yDiMTnBW<^H`sY;GSa&eY_^Eh3 zD7O9;(eH7Uw(WGScd8lNFl}l9$L(ulG4=8rzaJJBK(a|o4>WpPZ%JC`o==}Jq&rWG zPJ2wBpCS$G9SV*4>a^hYOt4q9moCh$C@vqupanJW*>mOlw&Q_ZUjOdUHW6k69W8 zds!mH^(Sv1bp5qr#7vC+&yknUL#_VKTxNwSz^|m$Uu7AUj2-I)>PPdrg!H(GGF8??K{*{`65C{5KUqV z9ZvCQ_&?wJ#?Xw++=jh8exRCn;c z0q-PdJGA6$3~q-8xdXX_j>JD-@>E2O>Y&(jYT5wcGmZ{OK}89~L= zAD>8_a!I_oslN>a%Q;#-;U!;?p*PpgLy&U~1@HNmjzKT0x7eDla8%X#;+k#9z)0<9x9htUXT00KUWREH556?veKRHyUBnS9Tno_2!Xd{RXkp4@ywM` zu*m%zTx6N%2EWPy5xS*~O1B(oT!nD*z;(oC4sY&|oCy)GUw#=Lm50bO;h{8YVYJiA z;mAu^9@x>7M6#3yXbvWa1tBU`TVA@^c)P|fPSYYD9LC^6bQEG!f#!QfH4@|E4&DkqrKC$ppJhBWb^;MPiGm4tY zN*Gw~P|+boss<}a)g-)0`K|WL?o2sH3eL>>6#5Y>=&$lPh_xjhPOU-3-E2xnZ3MapplE|QH z!v&{spZ=wGY0SYs(p}dhbK7a-gn~Yp_b%Wx!_xj%1oAUk`uedpsvhG_eunlCYy`Mg$@1;`_l|cV z#ovT(Ur8}vN&nfhf_9w+U$^}7rjhJB9xKj17%XbmlOT;dpSO6&r9^WtgsHQsF4mAM z2f);j3n)WD?4O3HsF2|P?0UM;qWzQn>ga^N=n8kv8~}DWG$GDqu(Z-zb^av84S^~D zUGX`=WIwacN-m{hmMQtcl%zmqicd^u&5avKB~zuT)}(3vRf7+@2b-dN=81~=)nLQW zbnEw|)p&%Svozu2YNn{|auoEMPI={vV=FG;w2iP6YBv*V2fXiuqGLs};sk}<9zgRD zT;>;aC^gZaV;2>sFcw1XN#rP zKajTDY#IB6cmC$4)Iqi_Pq^)@9D4+mK_gyNv|h2K$lo4t>)P6HAy|Q13dslOpZOc= z3^hrZW@)lC zD0sE1F>@~X|BSgw#=lZpM>KxITUvv~&#y=2*lRj)9S#Ui-!Y2W=s|DTBn#E{?q0Uj z)F1M$4VpYunqq>Ek}NEgpfl47bR^9iUZeL1pD{WeqFls3i6NP60Mi8Iyfovhs`ZNu zJ(;14Doo$_ZW8rqsz+0k%C|2IgKcuD2AFJk6Z@UX3QjlgPj>NrHR0w(itC z%f*s=%Rxp1R;V_>E|8OUPztfl1E!eZyLl<#;PGe8TX-XRT%a zaP|`3(v&}VANxaWL5hiL%*_UMtrery`O=p5 zY^@e8S+fLKW4oNA&nu^(^dQIlX)JIPh{SvILEJo4!BRY#l2FjGrl3OSnIMfch5`B& zxaIzuFN@Ssd+A&OR|9&E>O3^6GV)Ch0>&u@!|x`J(Lstyhd>2Yv^SEizvdl1d+I=F zy+E5Hn+$n2=Kx4`q)5vV(r+sUAx8cato9zB1e_)IzMOFc-jAYC!6fdTLct8Sm^2fl zh}eQL7#7^$RRWR;>3~@>CU5k;IegGo&C<1)6bZ`s`DK*H0MwYrV=unuOZnFD6~_v5 z-hbg%8P))WBtA{GW#`;bY@@bCl6sy5#%zXs>EHfsgHZEbjVEZtOtqPX`Ri*Z4|}HQ zuG8j%iBmk9&WC|6{<#248s6)!A`10CH`Xs(K~IbNehKT#ujZ%)G<@aZcRNi3(l3nN zIj@pY{!fpdCrdoBFZ+$Em`@~!Wy~^>XDiH$19*?w{1Vp6r15Fv1J+(&2!khLu@?96 z;_sRZrz~2eHasolD}(^L@FF#yeDX35%qpSfqC42YDmX75n?3#pe~9V_#4(uiONSwK z@5i%RMprWGrAfL?Eo2=a z>;Xb=3~~qI%Ij!)C13^m$Y)I?c%9{&|EFi z<2Dla+vqg?dqKLd28+LS=kxhnuyD6M8pyqF@>G-Hm?r6V=KXJYVkWP$mz7@c9n;n% zNb{o{PB3?&xj2ybK{@YPKTg>v-BG%CeN{3 zkZMup!kh1DGO%;Y%h8c?N(zl2a;~Z;a`V8bu`97ZiQtHi4&g1;NRQ)Vgx?jJMEXzO z7IuTJM<*dyEQ-$I17TBFJR47Fi*hAB)9vjNMkO4~Ph8@%-$w&~Cs+?pEiDFmVwjx! zY^dv&4fQ_)xNKiwMtUQYXrOTQ#J$Tg{&DiNDRaUorF|uH+6H5%5 zPoNVda{BzzNK951%LBe645lt?hFj;tgCpP1E~mG}U!lgxRYH`Q2xXW3z?F_h+ncC4 zaE+9kn?#ZQsUxOlJL$0@>_3(50gES&}%26T5y8$iF2uo%E$oA)&Wb< zzI&tC?5a`*p(gTDy=+8pkblk*p$%~ja@!>^>~}8uvflZC_v*Qx^B>T89XwSroc=1T z!QrtX^qJye7fGX?wbg8vi&$nLY`}2@H{O1f)%mRXTkKbHsKge* z{Y|~Rv^A2NB1_?#G@$crAqsQFG2&HQ*rdy4V+E=)_dh+2Wef#7kz1Tf;qR#ibYg`h z{goQ_oZ_wU^j4MzQP3wUgMT`6l&A9YW5WygH#6ZJ5M@@bDO|zj!&~?F)8V`+GEJ}^ zbK1INgj_X$R0I$WD(#X#S?ev5v&iF{-6K1(iSZ4|yt`c-uBIoHk|V44cJ)z)R*bnr zje8a+D=1YI0UnCEFK@2jP!=*H?Zty>ak6@DmmPHpN44%lNg)!l2dYV2oM^ZR4^v*T zKaz%u2rN#&yuQ$?xT?&eY@IyDk?Rhz3K&3n0u>126@u_ZSA8kv5E#W|g;ggJdC>VV zKkx9mtoN@$d|@}aV*9Er0v}Eg)ipA||990bRT%Jx*@cJvUrUwGy&qqqUi(ik{MipI zM6`x4P;*|szwFL196SWMW7!CK+Xkr#m*@m;ix)GFr7(`;b1DRt&)Z94W8FncE~xkQ zmGh;gI4bEz{|oOg8D2EKsA|bg95y-A!R!U8>!em#BGJc#v!Cy+wHSqTVk^?`P=&bh zM5n^d6lf*v6qj3ZNR~;`a}LB2=0<58nN5FuWi|d@<>*bA{*=tVmoP*(tth(j2vh57 zkD2G`y9*#x`_VO9mx0*RdHgpm3C&(DTe}d<7B@jJ%UdK{lt2fD70I{9d?ZF;oVP+P z67SXJ|Ai-t^^W@dr#fhL@D_}RLVs)#82V&IK@bA<58qhe>^mWyqIlJ)`x6u)bza#? zJiQWeC0JMTb!sK%Vx{V=aj#t?gQ_;Ll!*}T1dMSLObY(2izaQqSG`RQEw ziEZ2djyO2MP}Q|ifj?_&rUbdArDgxV2WJK$LIzZ0v9W zfnOdxl+vl<7!MNct$#JQBd>B)dfarz)OOPzFLDH6nVP(b@HB~&l#Qm6!Gf1nfvdvi zcExT#>{>wTadsR-^0Ovg^tt@A_W5>(Xt#&V?dzw2D{Q?VRV;WBXQzJ?LQ{KAeNJC@ zK0Usimu-XKOJ2>xzq?Q8^T}r4>HFcGu43wpDC!LI>-o)8$OE0TSig=QaKwc{$43b5 z+f6^jn0~7Arq3*&|vWPugNLTKMaIk^{dq)1!)Fjfw|_0641QB?5jOv}k(pommW%cM^q2AZ1G%LB?NWoX>s z=Uu}GjFRN&ajN;gHAdJ~?|&H>-BLWGO>LZNp%#@08K-8XL|;N-^hl0vR@ z3&wEZk&{62TsC5aBNc~8laiM{M3lYur(bGqt}37G>kgR0`;mF<&G!zEEXH^ZH9xMO z`L5@8R>r0jk%>7h#vkh64X~dNb#+#>=-`sXik#_EG;MlGMMU0D2f0A|u_h?};crFC zD?&PBTz{e-T7J4dl0XVLeFS(v*nL`2z;=^ngJhu&HA%DzbF$cJQ!uz*j6dD%X-4+q zUMe(9d1~eF$i@a1E2|LM=IkxMc+?%uP(91_nN0P<|ep zW7YQXo4mAH??`O-);BnsvprsK%*j?HB_<*&sOD5|)+yAfm|B?`3J5}MJ}4sf*n&`A zgz~lpP`=)Mw`={!qqp)%!>i*@9u`YxI(S2_pr8;pY$ir4h%~h4goi4*w7i_2o^7-| zM~;SpS#3Osf$;FS*x)N*Y@F}nZfoG>6|t8>AXkVpY=WaZebrxIA~ zrhejGQ{3&IY+uRrnXUp)+=7GDk*eeD@(Og~e1(0#uLkMzwwO>6wpCu6X2WKqj4(%Q z9CQemYmlC*RMh5O|I9Ks*nTZnhe*&Q$(iCn_zIoUW#|IY-~`thjF#~t>5ZxxLyY2G znEQ{9$rf!w@5SDZf~JF|N_1%AWjH3%uuq(=c0;xOYsXZTzai#w1HdKQc+Rw#E2*sFv4qE27dn1($dPz z&M))?T_`F#y4v-KAT%s&vDz20m$uhtwJmxx9@oXy{gaT8q#%JfuR1)RLtMa_c%Dw6%{An8tr~{rZ(B)KqU2If*jY<-1mq-M&t4t*D)-m=+e5cBpaWu zNlxz6uJlC6q7d*ft$PQfP?N(cyH7FJefPEH9HeNxP6>|@Zm zzf!MXD7C%3_*|}tNO@eK%gfT<-U1BDF@QRL_D;51^H+U+ba$?(mlu!I*@j_*&57Y_ zK#3t0djj1M0^ELIu5n-uB{)3$F8vG=(o zU3r~*^n6G+Z+bW+9~&FXMOKy1B{p7eDEB$_jy*5pUG1IkJV!tAAALSv?#wwkVH?@y z65U8tDn9sk1Y25d^|;%V_E=tC8@Z+MjuJR+3R+w9^O>hkodk}&rIppzMy~jZ)8)9} zL;IiyRLFkkUdVf)-J4KcymzODSa7mfljZN++C)69bko5AsmDz-tm!&M8yL5TwCrwU z?&AY+a6D#aFpHrO^2m^)_|e_pN%D1d4V<5Z#zUh?iA6pS06$pV-kx2+?WCZyGbbe_ zWvZ7Vk{U#=3k_%3;){`|iPz-ViR_1iNH_(Q%|_oPXTK{>9R7%H?=RqUnK=quofP+} zy?j0!qOCF>9HG?tn3Si+h!Z_H$z*EDEyKi=EC(<8qsY?Sr6)Th!^qDq!KZhz{hFU- zps_R5%8tJ2{u*Ai-A)WAnsR`{`vOC;D7Y-XAXKX$s1UP+*1T^~Gx(15g_JTZ9}(+ov4J1O>uP7Hr-6u- z6WQWIl$CAJ06`LpO2pFRNU>vy+CVCa?LYF;(AL30=(hxf4BT4%aMWQ4F#3mXfQ(+*!cW7Qi<{$NwhD|8H_ zW$aLCrKz~lPu$%7!0kxS$t*4|4x^REsP(?Ji=hx2m?*8-8j8=iSzhVgIAc6e`?KUs z_y1l1lwJ^^S^O7s1qJ(3ShYW|Ee}p)3GjIV$As6#*~%zTjSEr)bhP4M+#?JO4lFcT z;y(L6AGcXCNXL*Bw(f-}_2D8>JN!gh)Om-yy$t}(WaGhD=Wn()=F*6@wY7a)j$bxC zF`9Ld|JltHLKFNPb>~!reha0m#B)uYI>9xUjbeK5>XOx|tX)|vA!a|CO8R@5!#jG9@ zgauGWDY{}BoH&QzyM}W)m7>S6AX(Zj1Ma1GsI?}fP@ARZgFLL7kJyRExKZeeM$!|N zr8oR~0!=$6fOG23Ln(v`Df0K%bd`_;Ft5w^!9uCk8pa?8m6|}cL>Uo9Ds;6ti4h4_ z(-Hz#O^z=vAYF01y(u$u?B{mI_1^Y>7{}5t?>Rq(Se=U5?o%(cv5sB4{u$Ep@GP%K z7scXmb4noB(5*d8lPerMGhkmO@DG;{kucANhW0omJb2+2JC>);8KiPjz2f48GLyJ0 zyS5IJ=tZxV*$g_K`D*4lCp*SM74YWci@aB6vRYF`Bn;pI^=OmLW0JvOwqztL@L{zk znsbPe$@(o2aB|~>yz-?6+pY%?(W?Upt{h`@5dJb`$bpN@L)eqRc8 zinfA7JBloUEPw{>DdD$h3H|EGQ5IL19RoaUg*6LFY&eiOnZ8tR->-6%9d<~~W zfN5l`c9}Hb6wr=Yw5R{hiZQ3^&1r1cBdlNYwcHZ5`1ws|xwg4EOw-37N@c^;9I}{0 zOL8qq$TPKucAypyhZHHUIw!w1PQC@eb)4pMic=X6QAuIZ#fu8aA^&sj179cc14(X~D0HAZC~OFJ`E*uN+_c$p@+EK>#(swed5=v>{waXhd~208+v(V_y{YP0CtTCoO8Z86uo<+lJIT5 zQL7I|=buOul1EMd)H`0=$`*pnecYRMfQHvMEX&)cuYM`+?H@<8g(3$pYum#1o$-aw z3j z=9EcS98T5kb|#C(%N077vc=c_Aw|B*4>MRtt#U*yNSK+u@L`X&Ovc*UibIArSp2gq zyzQbIR_OgRA_0~YERLA+Az9|y(I%;)sT58wat<-fFd_M?ki}v!IA?k{U(L@(k{$=n zD=5%n-Bd>f)$I+}b0>_Oh7aUd$|-MIzZ3qIyF(QIhL}&rk|v0*BS&%=IxIeZS@7lV zZ5~JL?<7_9=>4Gfv$4c*IpW1NNXA;Q)oI^rGong0{797w3DzAWJ@Od8C*SMF_a;_m zmOS0}4Yu1}FQ(ppa!lvGvh`X;TIF0K`UV{;1!{~OTs$!_M6%CbpByfG%n642o&>8U z608b)*kAru0`ym|@08z2fVhtJF-3tWhE3^0j^E z`{>s#TuO5no2W{^>!Y^Itj;d~=Su%78tU@IsqTQc9WS%~dnwxbgV{pfO)$kt zSal&Igw{;(iTs2j1s=65U_VAZ-?Z&s9ExJG%n-7K@F^BDrY8E_j|$(e+XKjU>q+@M z^Z0dh*5`@vML<{ov2$YKg&#y-ptYvy7Emw`c19cTLT&qWqo|!X@-3{wGV+h|wQWV= z{Os-YRP_7B<&en({$#mymy2U~EhfmwE_NYJk8>(3ZcnLhvAOPe230T>G>$r(Y_KE+ zGLTYyG;>4~d^XHoINZq7!Ca`v4!>AL#-JQ!Tykgn7^O4#F&6a$F2K`xQ^?)#hvxZ; ze=1q|pa9h=@~HB|(PKJ$69C@+lHN5hI=0!G#SNMJbVM$;DE&S=Y>z+OhJaHb>;@RW zR}y%N-L?xmch?IFm%=VV<06orL&GeXz1!-7|1 zP7cuuNY&C`#kKlA_eV}!6boQ^2nNa$q?sV0SctFs1#oGOSPs1Q@{S}b@AN} zgUGP7$iv{(^$iaETPPH2D4}FQCgc@tUD@i_yus1ut{~;&3EPNJ z$>&O1y7?Dk6QhH)hX(i#!61o;j?Q0a^)71%ap1X(Y1Z?n(q!3O%Z$;v+$8=_83jnK zGOdwPZ52mXS7|=~tQ}6SPJMP@yA3%>6BqXvWb(m2l+Pyha^^!oK{f+U|7nMmKGBUV;>*`d7Hi#S$sO8NWCj^ig1_k z9nnc|xrVUrqGe3kf3t*O)enfnZF(V%N}vQZ!z}sy@Kl+oD_eO=|2r!|v?(|hEFv-7HnE}?~{mnkFF@`Y2uUl87ARN&qLZ<~*z zdhoSG5bbbPsO%WaVqY4wkGY?pJ*T`U8Rag|xtbNB(*lGZ~`p zyat&DTPh)#A1He>in2rn54Qp81t>IiTPs9IrsCQkGOShP&aa>%Tc^U8jUL&P01J9I zBI2Kn>30@X*U)egAL|1@dAWabOqZ;55l{ha5fB`D6ghjlc9HT(L{47FAu@RS`a)S{ z3{w(*RetSr?|7_SaXKpZIgr=iX_#-1u>g&9Z6L3COtx#L^jE$dR$jCNIbjsj53<$) zs1!>*|5e`et6m?KpMdhf6ZVgc-y=@oq%HB*f8%+@ZTV;sz_cOv#2-E|Oo5_VwHq%s zF<*IwuS+^NBlYhDr-6qfiyj98W*obOC_jB}b=Q}cw?+l7D165xO!&4lJuPkHQ_elw z>!tq_X2(r^r6T~GSOoMcj`9k`_DB8AC-t-WX$vJDiVKI31N<}2F>~MgAi$enHK=^_ zAa@a$o_Bfb(kEiL`V=CB*86+*GI+hxaw)1e#J3++}jg?X&ROrH0B44!tEizpZ zs*|n~>F~3{aU3i^8h znzgb>n!iQw8R|POku_s5KWH{HZJvE-r#pjFSQfNKxv;wZan_|$p{JwJ1n5$7dD=}{r=Sn;J^ zr{6iym8&}DTlEL7+@wGFsv6iCeRbUbp&1hAw3PddZ~RSMn{X6z_&>gz7~tMfnc}Rk zlSz@!T#%Mx!Q~zx!HYqs9%FijRcD419cJ0~SKe$hBE2)&N2tOCh79S8kSPaRZF1nX1b%HwIK^xTTmE^1NN=VJ^yGNz6Kv&%u&=uHzo`|8ZerX^In zPWMqy#}7?~*%p(R>Q@pPrL(37gdL~sj2KzMCocAN+kECxmxA_-e1&+)a=T+smrJ)m zl5uzEo!9ke&3T$BzCXwxYxKTyCrptij#l@7MkXF<>rc_^KwMPr_T{Y8 zH;wkc%71$J9j0JcH1Aq?Qi4tc1Q5UDdl3Q2!PLSb+@>Nxy5kb*)Jub~(*OAg(r*+M zm2Kj5q3XA*;h$Wt-N?zu(N#Msq-<`E7%TY1e!N&4CIjm6y^#gd*z~4x62jC&G*0^IMLHZ7Fkw!wKL#A zLX6x;b%ZYPqon{Ay(uQrkf>Dn$VHbSU7KRln-1McOK;~BKt#LJ{e zj1+R(^yaog==}MJ(X2o?7=_pa0KhPHNT01%t1}%KIS-P`CZRL93n!_0sUpUNS!kw; zK}8r%0Q&NK$Bc3$2O!J6J>WLu}rK#8n8?X3hP66`OR> zak1%h($Y#(HRAg1!5>cnLK@yu9olA{cdMj4WldvcOff%?uCEhJw(7_%=3N0g3N=33 zL$D){p&oDm@-oQMi3Rxp6YJENT|+k=TSWCwBYau{+#Z@*0-*8&OdK8LU z!?i6qZ?%SpK#I=Y#;m~`L6lGAX6EMiW9GuWNA{grVV%#cE&Q#XPv?|?S{<>?2Lx(z zG)zqA<2%l^i#_jf2^+NDodHt2o%2CT^W_HHrx{%l$!74&>!SB5V{663@oTMeYrEp< zVf#W2;GYZR96-Q{62A`#ZlJQ4fqP4~)#ZguPfZsbcUA$fi5!Q35sW4G26{|{#-?d^ z*lulBVClYh<216?DKgRSZU&;Yq?50Sf_;~_b~#;jKXslE+SSepGhmePvPnuwG0Us| z50oMK-)rPZAa##?vtDSn#zYe3Nu?!Go?2cWoGV`j+SsS-iM(RJ&uzL=V z1H+TrVqRWEget|n9loWhHJo{tg}LPKS;TD&K`rv3-;~nPS}d`B;sO=>qqv^f2Ms~vM*b>IbY@_ zXys1%Fj^{bV}i}2_Ys0bgK-urqLUIF=mbj>Hzu*W>ve-aJTcz0Tq08g`tL$RbS|ky zMq1W)sXOd_14fStisT1R5ke$tq_JG$M!%SegC(KfG!vYThw(R=uRcF-U%o@@CU5Wv z&k}gMi#u-7DDNJ)VS4Xm>UnV^f~(lXDSsrPJfrz)6pJIF`!0X&sJ$E!C>A0oYsLSl zA`u>`?PR6(Aq$lsLT_~WcIrFOKHu*Xe;)4`(TtP*k)xby`mPP`MsOn9(*4e>SFaun zr-SyDAth?6-2yu!SEMq{PA^U62Ye0Vw+hvIFApWSNz}X@u>v%X(n~5(Ff8{o53^8& z8PV@-;l9`x#Bwm)sF>YKFpBh~j|BDxt1PbNL1LarpLNLUFt|yweGs&7K#p6;=8LqQ{CfXHC8sp|7qY#28OzjH}6Q zs@b9}!c`n$%lDg4Va`AP{DGjYErjdYU@O5%yNm~s*cZ{uYd%=<68c*r=KK*YOG2&G zKrve$4w0Ho@r;Qx%+{M)lqp2Fdf4143ca`_MHlT;u%Q%ZISj@PiiIH{{DAR$RLB?V zbfFy9xz=Mvgg_X!FDahz(J|LOhXRF>kaJ!IqoTVJMfM|q%|@rUi2Cun z=-!TYS!v;!bKU(foAQvw))L2e8&s(laW4D)un(7_!4}J%DkDxT`F#l!xg7f>crip< zrr#JNP2n5t;`P&7--TSj-3E40oU;WJ@keR}1KjKsbXodOa|pO(Eaz#Mves|a>!kD5 z&+o3663jxtiJs`dr$C3ZIdtxqQmNUUP$=&?T~F${@$%Sw+HvZ9wU1r%xwH8*g|ce- zf@X@Wus)zLoK4621@}i1*4nQN+jZR2|H1=g-!O^?;$kIq$6Lzw9Q_w3RR8Ds94V&$ zhwG!eyFn2pKC;5*&;5~=ofL}DyG_hfV;h&G9FZqR(*GLcWiBprMEVd#?f})%%cGZ6 zZ!)i6-UBAEKHS*xtoU+it-pIdn6p7kd5`o_z03l1IQbs7ttm2}ep2#h$u+-)ZA*ha zwk&l3ALYFmb?16P!!;ht`~Q~5zI$fbKQcb;cm@~*2Y_8)5@_M`dm>U)9RJDhnP9*n zBb?grrc1Mlly7Y8;#TK;H-t^Vs?(RGB`u>E_3S^^Au0_0LZD zv8+U!6NKxd(XYiJzTUTIBN`nM?@|0e!x@7!$g(2&Wn?L8HWzN>6g0f zizh_|3>yi4X!n8+m-9o-cLH`jIYHs9yn3zj2Y8egQ4YMHCn|DCAvAym?X&y`E9PLs z+>8wDbVtx=UuHt)SsTZ1K^;1;1<$eIE4p1UWK1)(`m1HZ43gwlaL?u2ZBHGdzB%a= z4aP7FE;+y>-0d)B{xgl;xCM^-d^E-B7neu&7beWf$gL&TA9~IdMMe=o=oUf2L!pi# z7hUcoRl>+4V3X3lHIjIBJQED>k0)Q15icF)ANm~Gr>ihi>I_(yk)i=!_eZ_^-s6u*pGUPw9A8hH+Fn`pftS^wIq%80fFJltg z{ZipB`*Kdn(D?6DTaL)q>peRHVs477s+=mL0&F5yD!*3hFqTq-MaSdD_^xHXo43<* zLf3b#yTP{OGV8R;_2`pLlh?bW`AXB>Kioc#%jT`lab|CheLwoHFPqMWvWtg*CXJQ0EzC;zr+x}~+5N`+OMLNNYTY}od4g#t?1+{@)3QYPYHjLwa zL-1m?NRnm=24lt)Fw}U8rCg(uyS8_Z{XK7)xnbQ>asf%AI<4D7CuY)s8l7+yeTW;$aU8Y$Fw8N{YYR%)aLO8&N#E4gP zjooKdO)S-Jy9^Aov7895I0A7iRu=n>YU910Qzi~>>fe#Cb$33nV~_{Z%ai2DG6AL< zwbEGx#Y3BgdephB?|fuGwCzI>DFq+XU;-pA30?D@FWe1ws{{HkyZYl=d(I`-E)zVj zGy4x}utvLrd8xN>OhO<<`=s_6(v?C6(#3uLM2+^6b~R>fh{TWy7oZw*@^dM0%}RVo z6vc&8et5v?{_gT zf7E{Igi1r}8XKMWr$m9Tjogqgf3Nl8?!4>owOR8K5_vg~ZQ4yqt@2%VBVgB+qRx?? zf4`{`UhR^RoedCD{9_NLJb?Sbtzz8=NM|QIOVOmCy^i@tQ`yaJY=S2y>@MzESjWff zg|Q+fSma8y^76~G6nNwT+eL3LZJB0A67KUe%c1sANj$ZdwiaWG9Q->`7hNiP;EepV z3IVE$`okkt0C)y=zlqtNn;;Cq;twb;d942U|6YK`uK0Hz_8uSE*2+595BP4z$)C$mt5qc6aJNVK6VnPsRUG&qSTOcT2YR*P>Sns6U2 zxEo&k&bQ&w!hhx?FRzOPG&_?zU3;xCHIx+*B1tO!vXoEPOAv@f4KWrl8LU-^QcxL6 z;T(ITPUX^XdIURv3Q@5-Yd(m|8YEU375*L(y)u<(SD$wjEMOQ;m9r3|%^b&$ z9ym(^p!v%Cj;RKWb4qSAhApXNb zj$&gQ8ygZ=C^YEJ~~zu@RSZPms$?~!;s zSiZix(*9<1DhNWMkh7{JD6d~CIfX*~m-FbEmxIf&A;XcCBT1WNy z@`aY;T`8vA4~Bn%%8x5!#l(Xpw zB2^jju*7~L4-rQE=i}hu>q?-P|Lk)1Mm~kj`1PgT=SX{flN@l`d|MviLjS<^o#5)) zabx5EXgbTND7&wXE8Ps;-67r0fJn!HAPCZ3lF~>G4bmM$3?e06(hbrL(%mg3@ZQh6 z*8d~(VP-LN?sN9J_I3TX>|B-cc-+bI{vn{{+eFxKDwJ;Dy7w~Bsbk02xF0}(v!o}A zh-0z!3oaFv5mr3bybtfNNSvG-yZTEfTPml1_cP+-hZ-;R$J?{Q){?ZOkPsv}Q;GRL zPX_~tk~&td*+#e2e>&@CpUOh(7aHIuu-SV-AW)piN{G1-r)KX)fLLGs`1jNrDC>bS zzbWs_^ju6{WS5qg*a$JbrWmNB-Rx{4a!=J8&K8C;XUpy{;sd)+8rQ~d+h6=YxjZ@^ zFSe%jMW^uqUy=ZMp9iJG0KB<0a*IX%XTXY>=gDdhT#ei8`katgWBA!}5pLq$ca#}`Phn}1Z za|Z@%9N)!~(S*r|;jTV2Jg-O3kVzpE8zEx^>wN@WYQZH z?4QY6C_#~lqmhm)Rw}4=6F$krud4z^toC>`9aVydhaRn2Yp8k*hx&@b{QhNE}KWa{jY+p$k*{f+ixQgQjRJ0f9urs8*%qQXZ z`~+nx@MVCf>!7cn9h6i29+bo2qq!b{JV}TVW_uO}hLN?QH8>`XT8)dUD-QuMIe`IM zQY`%FoQ&Ast6#R{=&#h&)N1E4S}T`rGI3BsYNsmOuZzzo+>UzfmxPnAH!<1*? z^~EVhtzT+44$Hjn65cf*Ku0D1-X#Iogw+3J#ko1?-qQ9ZvQLYz7f=;AwO=Sud!3j3 z@flI^I=*=0u<$uW!!1+!b)vQ$L%CsfaGvBf|Ebsg$@4;5dvZyhH?aP6c|}ANfrVCs z1^BG{1t}_byYil6^!~U2QsV4&c?0~eRV6TD+@k!=*|DOq$n#^i4 zIE+#}Ae)Fo_vcGzz=O{tDFp?~Y;yONp~O5xLIhwN)Sp-$s3sWDuQp>s#XYs2><+_< zj{#ByE=H)uwB+asLst3|tzQcV;%ofwF>q+45SD{O8*2%ES#9koNU5qsZf8STI()5TbAc-;f0k#PA|swHwu5^{wF!Q( zznmw#_JDM{96)o6;4@DBucKo-zWuY{z)Ub%UYq|-&%YjX4vO2t--@Z#N%{}Eo~Foq zsX3p2aIw6bD$hyG)DfggwX2Wn#!Z)}pMIb4?%g}qU1l36^&E5LpilL@r;o&(pP>G; zf~*x|&>j3Z>e3X^oK{13YW{?*L0&!)Fx|&)o?uel&MKYs0SPX=-JHlhETT?CL1?mh zlM@F7-!I{w-eo%)agp?y9|gD6%TEbDM|5Qlf%F` zV6SWMstWSs?$1+-Yb4yNLkI8<71;U|>KvHmS3(_@g_PL z(C}nV$`EpD_$}Xt3mYS53eR&F>wSi|dOcVH;XNeNRd$(iM#Ce~pVZwY<_dXp;#DMR5D%5u&9f15$GG z;?~yaq!7gG>uVkX3Hgt1{EL1tSW(V62_QF`x^t@8tMHqfn*)6{Ua4GWym+m8|FBaV z0kBXOLyB_Z(8DNv(IHNrUJ3S%h4iP44RB^K;=@01K9D85hJ6;<7T!V$2DHFRboZXl z1}cQtm;;_XZ>G6j&_66RXuCyO7XGXFq`U16#0SV1DLT9j<K+KkvHmA1kn+wnD@}SGL%juwz7}vxlmL~E4F^+OI)@vCOZmgZGz#DZ< z@0A;JRJYYUinal>is-X#*UYYjz5fx>CXR>50y@z8wH!!Q)lBBN=P5sqfQFPXWWn&> za9qZaOYy*3oSi6KxiqGXFvB5kZcZ1WOS91S1DcC$vGPs$hc?1Z)lJ(zGZ*z@xeQe} zEW&{lrTT+|?p6n+RI^lvT#}%cmo4bbYv#SpxV)tgvmqAZ=L3j{pV#FLwQg-x+jGOo z3Z_b0;`okc=l(wHl$*$;v`jt3@_ZXucbSHj5k?i7+&Nb_ELhLiJv8E5E#&yPRL(uK zgnSDBb_Is$PO7` zGu*(+LokLXL;oAWy<%YUIibj6VDR6+R(1NJ7$x9oclXkK16e48b~bt#kw_TP1ju0I zkFXDQQ=Ezq>u99h6QFU`G$X17{tXVjYVwN^uGg$sLM#4!JdBJ=!6m#qUZVo_xp2f8 zeCThG2-7wSWzow|hGusEDoTz6kt-_!T(f0`YZ|!`b=r^1T|9U!Kt{U9MtBW+y#F^N zPRMZigN9^u_>}iq4n(o^vr(E^Y1EO=wyXYTBqK~Q#zN$G0n-TAf_FLwn`L2F^QR=5 z_yKDX!rI9E95!)Kq&!d*l0qjz99h^&f`3l+`GKY$C{}@ckk?BnPTs%G(COh(yVUe$ zC+lT2=t2Mn6!_O7Z%P?=>{3=wxd4&zGX(!mLZTIWiT1P)rjnI4+0(`hD!s)3JA>Ww@A~`R z8_M4&*tAh1)GgAXWGz73VhwtLI1CWph(yK>Q~xb3NtO( z08M^Q|I8U|uJ`%mkSM1jU3!E|jQwi}L^N3Vvi7E>5H7tTfHUyx%F<-jS@9&?rb|G%nAVh*#y(U?rrdjKqr#|M1i1 zLR64IJvm;0(wS999JN@~PWRnys``*nIJF0T zTsGiUO|qZ|94Sb4V7Hdayy@3s_Y1EQg>2SvI-cwluQeWjQF!%5vfs7{y`Fw0IP0Bl zr*rp00xqzkVkjlRn&J0IGCwkB-YW|f;x7~SP(xRx+S(BI7;At>L;5-G)v4Sn1&?+@ z4b0n{EA(kTQZO)npN@a)7;`DJAL}ot)KNy_KkRpNqOH9Pnr=`*E18RbZ#;b!C|(T8 zERU_$8WwX@dkv=3tUtNj6ZLODu%8>4*>jVfX>|K5Nb&elnpk^&#v!?mJdkDH-M>o# z9enlAyY2@~lc=K_9i!AqeI)#S0w0gL8r@;Wr$XNN33gU8`Duxw@)K$D@69W>0&4Fl zG~^_LzL$D)90&$0?S+^LX{`M~{&0l-{PaWi`6BoA^T9$HJof&qaQ`Nb z3g&Jy3=no9rNIHY9)H^nyg>68KM|~P>Dh{T;;7zIihea{q0G!I6@Q36M=BsVSKaY8Cy2t4N*k_X)8vYhyI#Ic(? z!(O?*r{1}U|1CpukH5tT%CWS?kw*qzPL$&-+tS;!*O>b2(lVhec<`_WHx9FLPkGo^ zgC-=8>59SGqYI~I>`@H55ZUCTd^_my&ZYVhy-Bkl`cCsU22&^;FPa4%THx+^3!BBd z!wiB%`ANlZ-Q67Dpd2s8{F@G&v!c-E*89Q1nFYVkzOWw8-z#s+Ezh_`UIe(=s;rbi zPeXDa+I4Ew8lhk=anVb_soxShKogif3dnJ}{;iAdD?l1gN?u5B6KH7Q=k9HY;N1Uu zH#&bAkI1F<55Z#j-Pb$pq~H15%8xR$1bE0Qno`wpmkMT z40Xx|`{e9DuvRWZvc|1X6KY}-(FOdG#*aFAG&aSk_I-%Qqw^`=7qQ6p;+bKMJ9hKD zOK|$=ILex-1y&+368=^bnq0BpFJrDYt_C~smf+Sra%P3;V5m`4R)|LIc^23bcxnID zCNND-?{xdf^V_s&IT9Yf;jQG(5P$9NzEVD#CO;jX@QI{FDtJ$*@IX|8JJeJ}@t{Bl zL5-r%?IUkFokZh`@pNo{7Ew_NojhSLl5#`-!4vCZ?A$^)!W93+%_|78Ofl#IZR$uy zSbej(;yKd^t>@hCNf%GvpQc<^qLD;Rg~5{4sA^Lw2!@)#7Y|WGJ7I+UEja3l_5bz> zZRPx14F+G_#K1QviWbqB>m`r@yn$KK7SSbCC@T5Q{)1A{vBLC}mlM7bH}Dpf;aYt2 zcT`2k^3xg{&2OFqT8LZFA-Z_IvN3ckIPTNZX`w=K$*6%lliU5RX4TI^2gS9M<)NXhgrwj%m5! z%wjptX!}a^)74QGy@`QdIX~|jzl*G<40>_D)^LxTq=fL{JMALT5dYFofKn@FQ2mwk z_?@^bh$xQMIe=_)GEdHvGPMHSPzQsQ8X#WnIA!YEWafY1+!DhHGb3B}P-4sioR;$R zE}xcgw6j#K`46p+T+(CT9Jucm){0V*M701-NUn5RjW=FK699C~X&&$g@RuJaDeT599AR8QO9UuQoY;}KJ`|AmY@!b36J_m#g+B18w z9I8#e`ca$Io$JW|w~@Me?wWpTn)f#+cpvReI2WU`$UZb2BK!PALH@GWdE+J)rvmY( z^f@b(L66AS!J)&ybFifAe9IOIB4(wK2eBfWCJ!?Jb63|mk1|3Z(m~2ZAbJ!++g@-o z65gx#$awOl1cwIhQ=yu*Lz;gIDH z{kh(XHoc46w<$7!DOB(!@6yg*>}wc=DHLtKq3e3SyrLpGHoXDf!EFMx3q+iDIqh}r zmy7HkO~z`hEM2jF2*vC9j#oMkEY7+A>-YhA^mimD%!_?0AJ<-%`cZH0{@^TaIoj{1 ze$q5sE789=FF)HqgFU^paAh!UnV8zz4i|SUhahJw=h_u-l{1ND!p&o1=>qOCd#mNX z&v|aYY251DOn9#Q0HfZJ;I`RdyYGjQGL(5q*?_(jP-jJdn7B1fS2G3?&{1 zNPOEOTYuvvbS1Dspud3E{^pD4c%9%CoZt?HC1_nXO8_0QI)O&b(p3E#3p}F}Dx2ZH z%H(m$MYpfs)@JIOcers_%J08@A{ytv_`{e>QhFn$DqI;h0aAvER*tvmuy5SF>GeAg z|GxDOF9_ti0+6>zV3ZW4=*B#i)vJ~ZWd?P>3@g_cal)e1U>}M~OUYJvfIdkm7^Z+e zb)Rp@rOlN_VK-4*Dn72z<^zWwJY++Z0W}iYTJ9?}HRvo~1W3hlP6LV{J_hoT1s`LQ zQhz@HxwWI$V+8?x-!h`S`T-Yvj9Ti*5Z|d=YK_ekIoapDdVVVi6V!Z(q zC62k?4^nv8kvD0}ZY?4*BG15TB5VWi`9V8x*ZBEnQ{GJ|466chNT8C#L5QB8WCCnjW0f6Q#lqasNuUsxqm8(`e|gwZ9(|MS)Ra^8((}dEctW9Ahi*30tVgAanNsk6 zTP1MF*fDQ0J7?nZ-&5+qj3xRL%m)q*4y8JMRo;j3T8D)**lp3@R{g zOub-v?7{4oMToL$PQGyvMhxI@V(O%-{4qKWs8X?g#GdYf_jR`VhK4GfmrU-SHN$lJ-&r=Pf zoSbr4rG4!2sE#2@P8o{l>C$LVyu*g%nZNUvm()F@;g^-|^s1$Ll2Rb!*Okzvi%{gb!2aK9icK~;eXh@HuhSnQyh2ads z5^dW+mc`V6yXI=bcJWBY+~I~eL};{}BWLKP$&&_wlYUuqBh=$CrMgUyqr_=R>I0+`d0_9WgA!S6AEnuR5C$8Z&g+0h`#6RP!}_QJ|WDdko|!)70vSm-<>bVfC=}S#4w<4bW%(A{A{rLee(v~ z&`{X&sM$r!8s^}b0ao2(&RsHHMqa1bj5ADvKHS`)QQ<&Zy0~OO~xr*PN!Hq;YTvK&Pa5<-`s} z%A;nk3O1({Jj;~6tXfO2BDZ>dibLv*+i2Sp3;-VB_aPwk&6N4=s4(-Y=a&nB> z*bdD=>OnS-Nr+EUj7IL3I1N0`pyRb;Pjm#1<>y-}xahiz`@B?*<^E@JAbtc^PD^{4 zWv2dj!{E0*ih4KJI|6s?*~@Frn0R>E9&c|0HMLurKcD?^@ z>qDT-792ED9+Wl>Bed~tU>LUStszpC!X=tg3Ccj-ja?U$m^WV^eARq`ugl|ey4L_g zlEWMB`~8dG1(|^`_9E6fFzw~cqpG;D4N%U&%vqN1?pVtn7mPM7yeI9Si#L!@Rh#Z^ zDlLI6$|IQ7a`1SOE;q)XXm-0#I(E*m*YJ5t}$-suCQMkuGDp=Eq`G93)k~C{4J97Rf$N)O;+r! zzo%r<4D#iHVi2kEepxs5uv2A0klU|UA8eB3o`umH?SpETc)poem8|H&FC4uv0VU%u_`0;O8I?w{jf+|!Sw za>3cO7?Lmka4aQ!CCTR3a%SZ$oIz8@NFLr2Q(Kt5(cUL30pHcxDHmW;jk;*=AS{{V zGC(!JA~ExSg7^2kTeoJvDbl}vlesNsSos{T+#GcxMyT?>C^-~tiV(!(|AuOB)|{ta zf9XoX^K5kp77{Mv`47q2d*tIn;}`DRRbTGBr(8!QijU7*pfPIJDZH6Cb z_Q!ZMAj}1IhE*%gEXHGm1)m96@aeEyev?Yl62S)(1j8)|r^|1+Bc>nqxNHuhp%320 zNBTur1aYTuh(QFI2s#p|AZo&0;LR%$Gy_c?kQuge3SI$j2W4rrydPHbnJO7Tjq#3& zo1^gaS9N2?ciW4|!}g?`%iqc7m}?k~ePabYtFz%U5xSu^eHes16|xdlG4_q7dWj!k z=!UICYGr^__G9uc^RtGM63=oPnv&Il0{RbddW(u+U3 zH~W%rOKwH0Sge!&g}G8Dw15|fhK80pzSeD?8fdo+FU^)s2+Hyb2PL|qWbLFxkVNor zyb?`zmBn6Pa4{?);5q+Q9IMsNpv7%`sS=ocRG@xie!Ld#>H5n1CfZ~Ye`eG2yCp}$ zO569(XvKu=c(;qJ*w%vYno>t-~ELGzbt-^aC!XrhgNp%kpZ zQZ_LlXmUd1@FF~@haK4_+kxk)2py5SaWWgQ=ngq~r@7w-ogtxVRn=FDdMPJx6Os=! zXtMGM!TD!1(m(B9A48TuHl%;vPx*Nq?)E(PSQWTeYvA_Zf{-VqE7Eygn5+!Slhua&&kL~LJh}8#8DaiqOU$v;qQP%jPMimk zSyx2Sg??mKMUUWaM`QAfL`cgHj;p!%56dk3mvg&-D%QKf66VHZAlHg}q4&Y~o;^h) zutun=lgDFtmTzO=8007BOyqCDIdQmM0-oS~^qpH|gv)PlA0v$GU)HE8d{_ivBE z8mhp3^#S*GO9vTdvl*Q0-K81o&>W#%VUk-hU`9=XoLO0Di;@Z3(iyfMokQ)x6LMJS z1n3o_pVz;RM|j$yA=L>Ao2Fq{|2s_yHP*5QZ`?}jXt}=9AXns$+CyM-Gv$Z?t=*pM1*u55sf9HjNe2yHi zZ*H_WiP?ywfzBX3InLEwV|xma63r1j`rP1nNrf7(${Y=8pEe;yiPL7X(GLa73aD9M zbbsm~+!wVd{7&%%=D0^nFu*gadc~EwAr8u{1ks}}pe6MFln7mjsMHJc@sz!a6rd zr%b5gojig_4%PlZTz*P45`%0J>eQ9j-U>?I^SifPdsTv9io6|3fCL{{@L)}&FiUz9 zteZc{AZ*PVF<_n?#YDe1^IembiP!T)#+_S+ksub7J%L4wSeLu@&;kCQT1L6x^2!L8 z0L{n?svxW;u#ykq8WSf-BZbA#21`+p=`R$BoYl$ICTY_P)s^f=trXn52qyyFGD5lXJY>;&-OPM z0hlY`tutSnT_E{m5(^@!j|mOTph1%p?drjRWt2GjqV3E-{=cM3xqdA)t>fR0!@|!X zqgKzWhxztYz;L&Jct}r)aZw!~kPNt^|33>qttNc2fg6|(7#s4ln89f6|8}@*0Xv4% zuL}jvqhrE=n{qj^9Ok@nhU8usJHKs&rH>FaHIvN#@+YD+a#-q&Ey}`3{dF{>ZWYrxE z#%jO!@Oq*c7ZZvY)9!dIw60&3*uCiPpYi=9xe1`zqD;2xL6~@EbZ~FVR(yDUYsPMz z75xPWOycmg=t*3DSXkOdmZ1v6#+}|yR^mK;E6hkIcky_}c_ADquK)K^^!eNE`xok~ z)hg4M=d(E>S=zQM-?97A1+%f6;%@DIKqyF6j!+ZMxAPB!C}=`ZD=KMUx&e*$k5}At zPsqN{zP>2FhrAiOD?uS32Cp=Ek*i&$$9?APN-b$fiGa2TBxVZ-O+G8+QGMM+9FQ+!0m#{r=$e*Aoa@aP^Y(H+ zrbSp|i9w+DnFJ?#B%61*^l_A6O6jQMV}-!JoQb*DjUD8Tiyi1&_jrEu0y3Y(_GFdb z79VPQP!1RKp#>44;bAH4AL_sQUHKqE0noR^zZ~bcmSouo^n3XvLz=s#U#_HUy*9wB z&*B|DgXf^Y+b@9w0Dt9fk2?SeD_%4Fx+JPvr;&OT1&)=TN%MjGPE@JRva?@FX)B%- z&OXywcbfpJQ7mWIoaT`<@Z~meT)6!LTgZ9!_szVqbQuF6I75_c7CE=Jwn$s@b=V*9 zFD^jvgEG>``p)SNUt3D_wTby_`pnO=$&+;$;3iTl95wzK?~;nYWL5{j|CaC_}?oTya8)OB|*^3IdS@*YmqR2j=fWVWUrqa8vh z+!3SbjGBMf_9gXxd0hT`nmLUb+e`nl_p;t|;f87`0hNGahSs>Zzp z96Wd36`8v)+EHONRnDL1ocW~z7MPlsby=+GO@H8I+7dZl zsLlZZ2xb2PuH1cM&H`VgG@}6HEZ_-?x6SlBb<6AFiGdCasz!AI?s7hYfGtf}ItyNW zLQEKsT1W$Np7P&IMk>3p5M707OtcL%gMrC9<~(BE=$V=L*DVw7u}V8@9JP?f!m^A< zU~PKe`kp%d`XVNH>~6i;%}*fyB{L>oLrgQWi>OHY5xv5bmA>kMhM(tg z%aM#g)>nD;zSZ*i05gf4^uP1R|E$CG&&#XR6Yg7;Z&-O5XV)gFj>`bYL$#+Dmxc4b+`8kJ7KaQQzw(-SIA zO~8r);MW{|Gb(X64X{%%N#T*^dXc^O+bTo`AAv3!6MG6@saMSQgCNj_nwDyNPO*jl zj@k?2r+ZCN%$Hx|<@9QvKj9O_R5UEPzx;3-tqy`-Dk0Aq!wmEy~e?t_#U(lew_5u@gqE4)*ug zai7<5?|^ijT)mw(P~gmWPiaWrGp;?Y-hQYz6Kz}xKuxu*_PQ_=a{863DH58T_|e#t zVzeUQ=|I|l1JkQ=`?U3}UqG$>w(aa9weeRN!9e`QjJ5{9h*zTT={*4uF7l}IrD}m! zZ)9R)f3ol4`34c%HyfC?E!xxK+(i$U3kAPcm6WkpLFj-zT^bRAMbdT2!+Lq3AcI#r zNNSBBGlq4#F`q-@X1(+0rva}Wj#CrB>)4JQ(0}M|w_t0jK3-sLHj;YK-(y9My1q1t zAEWMK^*!>yLVfugf2W&KC`hqX6JmzKdHf^RHbbN#nuy1R3SfCq?4_HMV|$X$yYQ+a zj^9jNlkc@5tV~ekHCKk4?kj3Mm`g0~x7v~t2*P=oo>;Yvwl&dsPkgl*Vw6iWMVMF* zu8!tk=6D6kMS&Nqg7nMFMc?x7S>%jvg(1GJ5$$yT*Tq35;TJU)7F^hR8IwcKkcfeg zh5Bu($KFwH_1XS94$g}W3?xuIxC9PXH8}%!Y07Nu zI~ZXFYorD+a3?w_x{rK|bENy?k7(`>jCvP>;hTS7Kb?pHlot!ocVRIY6tuNv2`Oa_^UKg= zRBS%R$I@?#>lN?_g%>8%gCf3h+!Z$x4KSr*05%+>6};gTjJ7s(j4%W$s%RI=@Kdg6 zvr>6I4YYX=QIA8yaGad{5*8(2-{bQ6Msx9^@M)}@cs!McPwwv!Ix(Pw)>BP!u|y)$ zEY{R}&s)JGdOJUK3mT>ogs}9CmUg+mR zi#=XvP)N9~t?l1OgFIADbq~X!vC!`MK-Q4V?{6_X-3pt=F4D=%!q+VrwdCyoqiPhjGX(|t@qN>9|(C4c+a=4&3m0eESVb|GI9^f z#0ix6rdP+mUB4uaj@zz6s(YU+9?_u;XxQ05(&hDrR>#}#PNlPnc9r~RPtPL7r5{(`487TExG_>G)A^yjmo4_A_V)Q1de*pN z2b5Bg$&8V`E{;ps@rIMIS)0vWx4WEI9OiJ$Ci#sfp$dg?Kj38t(^f7RjhO+8G81EU zw`Xk~IdxcpO6_8|ixHnbLDd#w6r=i2sw~f1HNaB3Xk#iaMMGk2Tj(yt(Y79QDDpw#rJjd8-wZhdC5PRLisD;2P z(AFAzRJ7;TA3!S@iq#WQo>M%1{EegOE;l}-ddiWIR96{?-;=m%w(CvP9aUaT4jl%4 zXgX84E^`RLnW~IEL$)}^G6fZ&2RZG_YsI8gqy2idJc{r2noK;)sj#@s(k0u(@(q}~ zvxYx3K(T)e6h4U+q?*Xc)DRFc%hbfb>>eTk8BV@Np@UiiGwOAPR+JdLLn2hpjQ?Rl?d5@)dQU(rpqtie{C_OpZ$ zHICot5`h84e31l2$+hr2D6%pLi4H-QzE%G#YuAKeH>>=-hXgmRz4*S1>gj^pOt>&U zhin@_co@-=MgcaZ`a{xtaLe8Jj!`!)Hu*k1w#WzF)FMQ(k*;XQ273Y|I{OC{^x$u5 zS%%#_7Wr$iMJK){q1iKIafeM`YA3FDq@ks>NeU~%Gp3yYO^9FO|&6HE4OV~Q}=j%!T#z-1|66=R>u-p*; zY;enEMJANlz3z~(Kb|%oLQ;C;T^>XOt~Ht8+qMES9w`tL`@M2mjH?*NTu+;5kEp<%Rs{&Y)x?H)(Z$b)Gho@Nio((lcb z@>Vwea|K|23e7AP`T!-1;;yXYfg@n_2-q%LzntxM1|b3)S)&sb0Dj*d#FM&O96x{T zxP9Ed6a^T(_X`8hX3S=owuJiZeSkO~bVh(ejS+UVAVQYp3Jad-#e7Fy2V#1IWlv~y zg=g^9R47Pxs=rsQh_BSHzxk$^aL`d8^N;7zD5Z2j_Gp&ymN)gR9klt0@`~bT+8RF~ ztxfg`WK1ZrF3@3fGf`m3h9HC)Y?b?SB312}8{j|>-~~;UP)H(pkx7XjV<*4@e~XxX z#o@I@4USU5XH5TIQ~An?cZ6>joVb7Z0v8SiN@a(}@J>vZKNvwIiKD4Xn@C}R^ASNK zaVUAe4qUE^UPWYPfDD#?Ef8uoWy?%zm235;v(B~dkgg@6a7CHqH+X->pJs(8Lu{qL z#^ErDy2Wm$0Yxv|hY*jf{6owCu)k9N;T#qvdENX;I zKjU*GWoSiC3*?Ak3|dh6ouM^k^_;m6TGaNs81w@JuL$U{qa^1`j(iPj`0pkp z^JvejsnXPIgFbRj**5$%3Kzke9(URgZI3@`5wH`Cl9a4F!p{DsLKvEl4n%^l5gq1X zQtyj(4vO_F5;%y^o?gLh4}@gDo`?wicpuf)CIJ7jJ@Pg zlhQ9<_}G2swZG!nO-p;UPe3jfKQaXOLt{i z>gFuHjruI>Es6JK7h>}Kb@jm|hVkQ!oT06QtmodiNE`@aCh>sw&?_=@B8}WI>bts< z@s62#UC=KjZyT=hOm*4u?{)4O?-#Ygz37D(1a-KVIM@+>JqD4alT7_q+ z=j!7j7`#ca838IL^WQPC$>>m1lME|858eVpuB}HYWwxagA%INtQD3gYicjiO;Rn_4 zI#v{Gg*=;`Tc{Bs?y!!jpDPmDTi6!(g+_z2zC_W`6c4Zcjdu}Sp&s_(ti%|E|2?EA z2}&{Z#Qnm2VPzMTsHpN+jjvK7r@c?K!(xj+^Q8x!YRQ)pm9)QSYvX}{!eTyd>1!=P3!rAY zyFyU48OW!%&o_F0-H$p0aKX#{!uZ5dE3fru=L^h^bIjw_`si{0Q@7(qH!?u8dn0kT z9>VWYb>=bkFrCBI+&JrPs~C!$*eu5eS2{6l1?5C3_J4R zw8tnG5NJa&dy}b4|Aeuey|Qx_K=l6GJM{YiFyksqAO$L~QzsH=CJfeU<-n+80vHfjYc|wQlHS4!VKoVC4MFBs8 zuLB{*^zYHSGpiZ|CZ@J0(IQpW8yxzSZqMl}Usd9PKa`W$S9DG=zo5C zy#L$SF$%?|Xu99cI;hZL4W$Ek`3i+Wwxl9)(K`5RS3?$@Skpz*2kYHBXX(5WV^jiD4%mQ?tYAp((#k^iQ+6JMJB~O~S6C^^ zxfd7gAt6MRC83VX>ChmjbigGP)rSvct|=wmlRfNJL@LMjC$%;;d&VTCt7H0rVeKg{ z=SymT!1u_ayCbi)NPn6y>$czSP%m(S5}SeFK@9AmAZiK`BuP0t{+VB6O4;3PV+=bJxUI z6P`>&I_V7X`fGcgG>}l$PUgKxWTR(^L4@+e=G<0RlrosZ)JS7|m4*t6_ng%FfD zk&7W2E53810vh9e?sb8H(gjdIfPSnbKS-JFzw4rgu4^KbJ{<57RH50LyS1xaLT*BF9TTuy)*MbqoQF z*)QJ906Seea07FY(R9Aj$Zs8yCi{!}(OgAVsZy10S>5s*gtfxygKutBH5pjVW;i{Z zZC|(P6m0N+(ES|(&VJbP2 zTeaj};VF(z?X_81Qj*VB>rYiHDw0j|&&Z8yMh3+q)0*CL2#0)6n0<%#D^!Ht+)9>) z670Ab6hVN55VpC}@dr51+6S||zPCh|N!{GaJNpoL&gITen`aVNa%d{My1FMncHF#q zeu9O6S62guBv>J=ZIzbfS$Um^#ZgK3PfUQ)&Q?a=>$MfMMrc?)F}CpSfr}gNO85x8G#@j+at+ zWX2*VHy1%W={ zu%m=4Gb(kTpVP{MYE651PCN%otCM1Kbg-~0i*>jN?ttmu!0RZ0xIS`FokZz(34+2* zTldaNnidAdxNb_(v;ScVH+IY<^z!zBgYx{Ij(D-LxzR-Y?pT4rD8(gy$hvdP=TrDB z*n`bnE{Q)audEal)PK4>0h0z>$)(X0gV%!xe5*~vhC&&siZnv(5(kko6uV9Q(#8RSE8+i(izktH z|M#`raeDe=mxrOl-aoO4cepg0R{%@pv9dLQIg!D#`@b#f^a~A;N@ozrdP5CNn)r{A zqgkfzVrCIa;p``v3BP#0?a1Q}yjS_-wG|7bb7lclVZ3V(wy>+6LySUO7XdJ_peJ6U z`#*xj{P+`Rvtiu)+GWzOzq|8zZ|N4DEIgKa3Raw^9fZ&k^E_L_9G4d|u==v)jL$9& zh0;(Xo!m7cCYJF9N5r&~0tCIZ${A?9)@DT3PnR`dsl2W2p~(#7ct>%8@j>WVvZ!P{ zeu>+S%B#;$v&jm(^R9EOvbD%ASS0(1KlHLl=cb5N%0BdsyjH?b;vk0HFxp>S=44u( zZ_7O%eEiroM6n>6wX2hq+eIDvjdYh)=@_tf{Oq6YPB%93y4c5i%qFDXTr ziZp*-Nap!<(Va8!rAE>_=FZ(XaTFC7+6F@wWf)BJJ7fr1%8l1F)(5bvXylorHg0Tb zk}FBRL14DiTksJxQ_=&k?4cs_ydwjL)hQLy{%kS9v4co-Ao$&9nAvqD5pM_!%{Y@K z$;WHUA8i0ykLf4@B|#^Zezvo~7ez_8^^NiJK)$qO4!%L>d9naK^9~JA25qwTzN&2f zYuA1oGH`zzPGdDc=6LU;p`g?V!Rwsa1Eeueo4Y>@oto%ya?_Ma*y+;$Kvar=kv`BXb^ z(^=}-1>kNBx7|K789yC%TmpS^B55=m0djynk~Fd-;$cTwO!(im@;@wE<_48Whj!iFkwRe`7LKkBO3vQr$R`{VH)3dEws9~D zx^+*67<+B}prOTn=dxF5!QUWkZ~DI0resr!eQ{(?fw8!7$WvL~*y3 zBN+7mfd zY7BBr+P?bEs+yH8s9PRspsbY0Shqyw$1TsVTCSS<+*M~QTCtJ)1YCuHySx_RB*2+* zmY!Y&@Mg9`S$}-b+O}Oqf&M(MdOU5s*iO=Ly*oGkkCj)^xC%sXvj8l}f5ieoDdQY5TWK++jdi+j*C?FqycN3( zidV%qWQnfigrcyIq?f1S_LK)lOx80)MS~#zMtzC0Q|$J!(Hl5Vu3v58u|XBO>?2-M zOe`5+(){1k`0OKOM4sh@sLqh@u@E2_+~7c~Gc!K)v5$qSnw7^?$Mlvl>J48)jen&a zdd0#`V_9=W-+Y`$TVK7`~Y?TkH@?b|2RR0i8ZiY4I6coxCOFGM)Bq@;!+6VVd0L) z;6h(3SM&`ld==Cd6IxO6VB-w-Fe=e;<#Epo(Kuo0GCNuFh{+@0!ZiMepQ9d*O(FDo zbhc{!(7v+YUXbT~4S-}CUT`Gtl z_6lYRxFZyAaAb}vP^mOVNL6Fjc_{qBYB$I@>!h(Mh2M;m?5S`MVP6q*q(#k-&y~*- zi6s|}YB?ZALcl}%&QT?MgG-M^(Cq0bjL=$xp^9 z{dQ}s_&Y__+_`VRefsosNC2jzBS5tCCW(=TE}`6b+2?r#Alp)gh9o3UGe83y<#QQj zxC@9@+$z}4gE-!ghVLhi0IWrKsooSmPUMXjK-pm}8u|;7yj_GPr~>R>|8(FdmZs$Y z1nD@@KR-^4hWc-HxK^T@B|1)*KR*)h;zVaUDXEwo6RmIxta95^8 zL|EGzsA?U+PV+;G)3`lW!nLre+F5sy-e3%Pg`%<94S12hIncU%$@SjGk0l|JsR*VG z|AvGLP528TL4wC-ckH9KK$c>KfO}C~OnwZJM6F?*YUF*_aFz`9n}}cL`w7X$cqVW` zU`76!s+?=JirS>(>NM-uFPaW#V}q&BBiFV!cEn!@eZ#b+)A0~biAaO?MdFb-L>$eO zLT0JM8anNCrT5Kj_u>A%~hh0;6EM%JDbqkDe2~L`kSrNowrPj|yhnu6w#sl(VF&7P#N? z6v={9xwBpPt&9v+U@UKnN|6)}k)|!)GKt;AlyDWZu%Z%eUY#7+kdX#Rnr09gTriHbJz8s<7 zjyxEN7l8>)Z<2HL>)>@5m@*}oSTTpd5>h&OFbSsQ3)?GCk(qrtpWv6a$kX%Z`cN|G z$&Q69iXOr-Sq~H-`hC%o+qum80RgQea12+3kJS4&5(HWez1+7r31qw9$ib4~27kA$ zxzE;QF$YIn3DH;Giu7<5IAjyUTRImG?)^lDM`v9+YSngy&-NGIr^{Fk9xH#L5{4Qd zixr9in1ZxRP0*Cpo}m@7s%qgUDq1aN6$B1?hff*Ua*M=i7Tl2YhipN1P}SDX{&>Zr z#E@vd2k;K@`uyW<0f5+Hs9&~wAWF`FZK1(+m3w{{CMl_GRGS~S^~naVIjfA{DU$b- z<@~N@J^QyS&#tQlM+_;9lEn^!@iFu;U<#oTd%Ze|zx+=gt25fK0g=&*WFu@kE`zF8!z0L)js=02K* ze9cI%u**JxohPVxYXf0=(c}C--a_eRe88@IPSS~<*5hQIj}DA3E-%m;eMYO ze7xvj$BLIW(yEWtm#*|c(^{1P3R}2z3Z_LjTSn6q&8BiNkIPaP9Y8C|nJG9|F| zh_fItbZQl=@+hYkSqFYMjQH&yQ}1QwnRXk=cl@ECdiQBmMTP3EjjmVypU)p`T@B@lCn2jM~G`MUbEKer(0i z5su@^u6y7*5ly)@(lDfr$q|-QeVH!PsY)7M0`$WYPzH)_^R$)D^dsfLnpUR)jhyNt zxStik@gBCtmRfh*Yx#vdpLgd0l2an(mPqG)=gS|*SCYSe&!;a_=P%5FkpDHccXRWD zkWip`yRWG2_OdfGOxw47Xx0S&Um@hv^Q9PK_3*kZJELHcQ*%e)5J z^Fr;)D8@afgvmunTm|Y6X)vM{hn9WQ*S!!aYSYVp65&Y&o=$vODue@alje2p&sXD& z&YAB%TN4AV^V!T`YD|$KJ^LO5;IbG9Hi;CH5*Ha5W7gyMVg9Q9`^nXN>2*v<@Oi-5 zuGPnx-nG)UxTMs`;=7qXboUVjoT|M~0!zNoGpETb+)wbGK4HDH%mf790yp*EiKqJ_ zB5pb!k!&Ek@Gqx}kjB^SsdBu~2=F}e)^E~S5;4JRPMh&&Pocy>^pYES>18E3Df@<@ zS!jx{883wtZ>90`K)8WRl>3@9nlYY<_UD3gvhAtJoH}D21hVkJ4{O>~SPUO|40ltW zYo!)BZLoI!t+(dDcU_Z~DaIsCA2>C9RylnCt#s|#8$XH=Nl+jHPPBtE&!6uzq$T52 z{sa_T*f3NR!CT5`qL8XPvbr`nZpWZbtt4LVu`yC}ed;{qoMnYc?) zgt6jBZO%2(a3bse#$LUvpOGXi+r0ZJbsdRid0vsg#L<00$AT>ld?+;T%p=6XVLa0b z&%DZ4H19ISUM6Km{jacpcc5}{fL_yynp3|_B}b1vLDu-&#Vm#3^OA~J*qG0r<9mpY zQov&O4nOj*)u3{itUF{1^Ay&v(1$DA0;NL^0!cM0J{85gRYjcsMj$(^x?%Smlc_c`txaOtZpt#t*)#v8<%H@&<)IWE z11aZO?y$yNV?8{f172mVi)q6LOh>PN`>&+|xYb0)K4eB7r((r_y{1q~QFhg_$rbYk z@Ps~|a$j=QNscjushWoAx>LVRM5?=wL$+LjyVWP!B*BpnP z`^U5%W4zL)T+rlim1!v-i%VYX>ubH}nArcMNg#gq?G!+yD!tz*{YNZcZE*xt*sG&w z;mN-}01Z3Xcw~1MCdMnrXI*O1)eFQo0kW26b~n#Q*9orW!5|-CEdxk5|Jh_li|b(#)U}?k)LA8V#i|Q!Gi;2e z>wim5_#+$9b_2_DGkL|Z$vzEwE+A#D@2ZXk97OWPinu45OwTDuz;31!$Q_zut6qPl zFr~OfX16juX5iq_#m{mpN+qbQiJinn5l3i<9p~wKB?YRULVBuH(eieH|06+~VRM-K z`y2}O&<)WTG+Ibk6qY;dm0v3AateQXoASsfx%=bx&EM|zFCC4 zgACo8B1S|N>|{fVD}#Z*I_QdYb6cm+O8=diw&X%EPO*$bg7P~bZhv|=`!D+}QUnWx zU~_HDgxLQAQ3daoOaYUo@IxCK(?zbaX>Z`i{h0tz|>TP7Jwtz(k zMkhsdT5EK;NR;+4KG$9B{W~#fv^Wkf?onXW)RV0`2s})C!ML2f4|-;Q#8%s|W*sQ( z;7ce4+y^W@75@&e`D|kO!;!qwx(KBp_w&~M`wisJDdL8L$FrWER7`YwD0~gE?@Z0} z+RetY?G{Uw$4Y89$Mw?T4S;V42#H{uo5amHZe-Ic7jjw|sD)Ik9BTh!hxglm3wFF^ySwV0&g&eJaX>Z!IXarJKLa`9ZvWx73t2Z?Em48VC*7_c zu{O^bsuTIL6z!}t_0CA(EQt|eFjM}Xto-e+xygofH51XJhQ8}^+uLZQ;h-k z>t|x0Lt_|%y7ot|^wQqT9U7~J(w{dt%A`+h0FNHY={wBM4X@2E-WG~TfCU~p%*c3M zAlK`N31Z1Ek`ZZ|Fq~NU`E#%ec=(z&jR6_?)@1dr@QDOa93shG^bLRdAo5mu{?q%( zSmiz8jAoVsB5@+Z3jH`KouktPDp1~?bnN(IHZXK+YYF!!DnfmfrkC}^%Ik{))}b^! zEx9C`_2`_<*i{J(9aVda2>f_0)d} zoC-mqPf0}BknlM-R0=JRiR-JvG za~8nQJEBciK&r!Es4BqK*5+0%HoH-sxPJZg%;9?V6ZJbZOAVe#udmS9Y1QV@C~AWz;=(#T|HZ@YL_{a#ZwL0~bnjZJ1s=o6+W9xJ%bBI}9b^J9yJ4 z%2f-9f@tbsZrl3Oy6D;yT%kZxNhtDD&zTs4OlrtSO*3?pADpu{SK$vsD$%Nla@DL% zL9Ed~zYqeGW{Y3?e1<3ri>i}ufWeNuI$8=_Iz1IoNUfz65fUW&fvW*zRus2 zo75F(H*b5<`b1u_{(2t3PRoy(g<@yFn<80p$rYiTb=+Hd!IMpq%y`%LHiAJZP)Vjt zE~~8^e@j!NKfdmU9Ci!2wwL4mo^-4!{pQ=MPP`w~K=)-KMZiM=a2Mew?nW6Tp)V~v&jV`V-viEJAkMYEWdAAJLK{#_=oafj|C%9DCs_(-rnwcjZ zkGvAg(`&5K&{Tf0IKA9q7?IyGx*Vg*r)^%clO@h74N#|fW)pR*YQPNI3`Cp5HFKhs zlcoxAC#hzYtI-}H1fokU&Y~o-UN|A~9Vcmwr4SP=@GDMH%VE=om|I>52s^BoXxl2& z;vBiGe9b@>N7!a1&vL)ivH$Lwrr8;!`|ZMqM2+WX!)L!?8ZDPYPND4VAO`~M@xfZ3 zo$a4~ucR^3ZB{MSkM~1=CnV#%oqVZF)izW?pB{-q_{^Z@{z+bn+bD|vpw?740oqX5 z{9?dwM(Gq?$|77%8;j*+c)m%4%`tWq8p)+&I&&wR-L}4H|+eSwQ~D z*RCb76gI!L9Jtxbn{(>Z9JNiZd4`F^fnSvTVi-KK-T%7c`rH(iZ@k$j@}j^Ilsair z{n**J;$p78C`~3mB9R>5>pdYI+ta?4Ns$_bX_T)bDqhkx`(E8TfE>W_N0l*V57TBnPtgr6Zd-M z>WnFU#FNHSa3pUO%(O_PKLD3yv&0-us3v&X(-Nqmlv0<**B5)Wf$Cer6pJF%zJ*iB zVTO5}#(&=st@H~KrI(w|Bw~-CyZJ4f5$`%@A&#A{nM)Z9SZ^?3F+x;HT!IqTnLbX*r!7nv<20P9Wf_!j1(o zBbUPjtFjwZEz+eu^SRl%wG&Wr&&N5DrKi@Llq3T3WeKvvqV*qw^o){}vQG(H%fo2j zZ%>#ljU-SJMv>G1`Q8!}KmS2nZfhZF!yls5JPhp_Tao39RX@R?RHiL-6-=D4OMROX zfb!e%Wo0s18rrjb@FqU^B>dEimMC}$6Z8Hi67N-+d&rNf?foa3UCt! zRT|9j;#OvMX+5^4?T@t_PxPsu3aoh_8!M%$*cL9?;25aop(V}e;k$q(M=45wjLc~d1C>o*jiHp1fXK`rl;?X z(V@oKFFTe)BCRtIYP9tZ(^as6(9Z8Bfzm~&P%x3I^|Fq9Va*83%SaMr!ID;AIBQ~z zy{uNS#TkmMxs{Q33be4;5M+ZzhBk^3bfOkPia$Wtf{-DDFHAam$2 zhhFSTZ(1j9-)!~ar>$wGThIPN65ToCR&IiY+GGA`;ALtO=!{?hKq&mzzel#dPk2L6 zQGrL50%Sk`{R6{U)PKunG^TA^IXjpFW2bEuBB2i>J%jPq%8QZ{RVze=NjO@nYo!rw zMA|mrIyK>aG5+t?7RtG)qIZ@4BQZTR7EDQ7qpMBI`}mJ6)V*4Q8Ur#a+K)}yB_09u zHHca;Kb-d`iPJZcW2Se)2ExawJ#6>2Bj*i~DHiBAEa4uke|tOr@AB2l{tT1d4@lek z?H55G#v3de(iQ*g1$X0>5QHdyI(=YMcSKWv%5dw{RHcapCWt-%HXpac&;!RrS!B?n z^9cvdnI;rImMP`*9eF8!O_gdbOB=AwubXKgwLLg&JPz(svcRX(sgnItM^niKI6XG` zQK4ULzY(SJDjuFzY`O~CF~}cw2Lr;qcbHQ)`f#L8XK3=Le%4V7dv5z>{;~{DYh}=6 zl2wRHZyqIECU?6C8BA?fKP$M9Hgi;%(c)bk;rNyx7^_JaDVD93w&)eNB=;ZEvkHk6 zgXG1LW*gx`m&JH=5Qu{R$gj`}`4r@I6r;nD0g>k-nA~P1c31H6Mxz zKg(g39o5Q9v3&bz)h6b<&AFe;6y+DE`bi*bZy*Bl;UFcnCMVO3Pp!9=9ZLnf-K!gDRRfQ-O}Z1AQz{e2<8@;#(&mRz9rZm z9ae5<4jUu#R3)3aNtch11s5qZlLD@%L0$fg8BUbMc*XXZ*_6$5UC8uqd7K^@onL`9 z;Li@&piXLHIpVt;4&jX);p2YPi`D5A1Kw-|sN}>Oji(U{_5rcyVc$$#oarpEY)0zA zJRy^h$Olej28j~K539|%r|;-eDvP8_0=C{{1KJi&2ja&Q8Dv?V$`YzU$jeGPc32Q`h zcx-&8E}J`?1x_46T*SyKpM;L8)YAdp&Nd^q;@~*rXPY>j zHAg;V5RMaRSuW3%tSa zxsp^Jm$;6l%IrVBS;*@LQHTh}CM+!Zcp@rXE0brzL5+2W^OBzqXASzl-EyBSEZ@X@*+q`q^Af2ZshPeSdjpFY~cCK+aeT9 z-hoNu(!z}La$2Zo3ETRZY&8`eJPrHRUQY<)(QDEAVLl5Bq z5===%Rl3MQ^1XE~vtJdTUrih{t)cm*uj5q{N6o(J-&fO0b7zso?%=B$XYPB>g(8vY zf+AESy*d>;4dnOqeB(^WhM$1{)ArVZjU2pRWR1~gAOR6_(U$-`eSYYlt?#z>^n=nV zF~air#eFNK{?Ns{refHueo}xyhMMK&ST2wc0ZE{irIoL)uC9;g%s*Rz>$F1{%j>rw z{FAdebsudXH5E)3t};DSe8z`zE@17j*SD9pEmq%sqS`Y-C@i*ZkaOJY%hq z#)XE+WOlOd*L?PcJfe_Ol+0uw6Y+;6$SV{HPh7^zl(w<4*?ZWbc&E_Ii}cgo)SIF< zk%n#(F4iBk*hZ(U^a9cmPM zQHIfYSZ`A30{?J+fsCPheTjatp}6}_ngmm~29ufWjGFQtBZHE&bST0wFfufX9Dp?y zvi2cK1dBaR{t{j#aZf%Y*|Wtf$E2DlM@h7uyBFK&61s-tW-+j19F zBqAtJh z3xO>7BJ}`QZQ>a(2OgRdjEnX_9w^2s*b3A=Y?F5MCtFi*wIV0`n0!Ey987BvFW6Qa zHFM&#g~aD~eh)-=Wprw}0w#*t$iBTBH{7(*ikc4fn%%iFedg%!l z@-=5>f$<@6BysTXXqS0CDzt`^WmepP1LvDfz+F7-hBRFjAaolwk~m`43wIz{D8u&zbCeO_^E}1Ce?Np7OMQSXO80i+ zj|1?G&;5Aj(+)-OjaAEJb2!M?F)!Lh)GRxW#=i}JiOdm5bF0RM4n{|=CfS_7BuNr9QH{Uu(y+PxiZIS}P{sY;QoW>7!XWnP3j-S57%AhTG zpOs1Kmt}tCc2?0vUS>DrsJ|fRH-iK&4V|Wl@(@7PD!0Vqjzh z4+uKVsHj@6r`YXsp8~6u8}aA7Sy8cc z-bK6}38)vf*FE2Jf90)I-D|X)F&UT{_du=MSs~S)>P%!YHA%^t8^V@qr5A6jvWo}-Lr~?yvE5_h z`7@9LQ6)%j5g1)A$B-zj3z}hvyerdxu25%Cuj2CApu%q%E#5wSntSH1rTm_Gr;_|B z)RS1MzLZJ^(j&&5h;?AIGyg>zeu!3SLC#ztoJx&%fj-ol-Ni3ZO-3mJJnUqX=wZVr z#REW^nB4>w@nC*o1`{T*BD2~hks=U$n!i8oj1hV1pT3-aTYmn?`>kgilGk;QA zQe+nW)ju`N?{}vD)3|TbLNEbRHKj8vZ4oqif_?jw-j{+wChH|Ssq@F57TO|l8PAsrLuwUrIv)NVnZskXkt;)o&D<+<<|u>I8N>>{l3Uj(#+&1P<^nzBuBva? zHqfs4zjeNkwQt-yaNDnga`?0L>9yx`%2cpg-9kD6VPB)BD!d@zv-x(+rOHIe6aRxYz83pCisg%9j_`Pw zZ@cAQ-2GY3^9z_&1ux5t?>PkN7CdrPIx_9&c6ME-BsBQ8?VLvZm6GFQf}s@Nl;QN6 znQuPrCqH!3U`Yrz)W%?qMtuyPJFx0h0kK@_Xnil8lQTps&jht{hLqNwp>{an+jVv# z73?EaLOPX~KL_T$!iLk-Dy#jshFU)g)tLs%*H)X9H|Bh?nRaw~X69j*E^z*LdVZed z`t{tOL?dLYKu)kloEwXdt+h5^GYF)iToZn{QQ0%vI-kc2cKs=OI)FYLiy+)vH{G?^ zBdTuEp~7Y#{1JD4oekU<0&A2T-T;I zcK5}euSMP|>%UePWS)9;3e%hzWx_=a=t1*Ism!>38IC}Fry25)f1*zerUS=u*%|#*%N7HuO+uiuL!&(gDlo$x*I} zN1E|QR-d|GEuP=3A z56wd2(EUs3XEbj&`-5@AH)fItBlVR=W!8k|I;J>55+rkKY$+)a0KnK6e*bof4X9$hjPV^5@CCb#ZQ^2#^DI!Gqvl;$o(JG7V8pgd=FpIu0y(Cpp-0j2*-_HK&Ij(XyU6r7~^~dAE6+@giBvd%(dHx0Hpq$=!4U&Ax&@JZUwZh^` zahzZ?)X-@7f*(4q#O$3WfV~z#xvLR9c=&9l=Ffw~ml%uU4Ld;8RDJJ!>Y` zXx6~i+LTc}ut(5Zdon5KD~^o^ggX)q_hz^a+70{!_8NgSkp-KOmtD#lCVch^ywKXB zI;(gTm3jInFr2uGax!mtjieA7q5FX;lhc>9*(j`~2yBFaWU>WNL>unRT;g64$s@X2 z2ozxHhW7Gm^L%_0!280BwO~-o`au~RXXBcpI|7BjUX;`GGxe2~H^H-T9tob=y}dyB z;t9~FYvDGw^n2`@%4EP;E`wP4yQ(J!Qc#yTdV@(|Uh<|z&l>heV!uWhmixWUK|A_< zaI@FF_^S#s0g%!OAZHVuGTO+%LhIctHM`Y@7@srkxBU}C%i-9ZY(dw|PH(qgrq6Cy zML|4Is*e2F8m2bi1MQ#YVi?nc)X*}BnBwhziGqQjH9;ziJ`v^BC_0Eh`tO)4lX!6e>V7H z+exYO;=-NIGd<5;OAl4_w7HTt+*gpog9{e>p;njZpn&zzTUo*Pu~=6j*sAxZkf7zK z4<-f^~5Ayf?`091G$|raaw@X5eh>c2Pw7+2x9vK%Vdr0|T{Rwe;l$ z^5_q;h;7zn(Rd5rQ_?+se`$9es8%H-N+@H<(@Qyiw`KR%(yY>;rlA37f6k!vT1f<0 zK#YQ9C+svXTv%K;dC`L*;tMD)LN-edH%Qe$aj}OQ7moWP68MF|XvJFH9!uN~R>uks zbDTzmJH%RwNpK*bXAiPt9&yPo)5 zCFSixlRQuvJVtsyK5e`*_1HNsCJxyyeiVq6Ejctbno@&?ChYz$iXf(|Mc8GS=dR{P zR~{+)gzC@~XpA>Yz?dsZPq5{hizN@qf*S=hM7T8L%W`U?!xmZfkObMTZu_G1rkB?`;wxrPr)(iF+mQKr#;zX!mxf{`Gs%bm8k`lt5u zRT{{Up?fW6q)M=*aI*OmZ8dHmYtPJWDEy&^;BiPidt%D1Z{DgymH^uqQx+!Z{t4Ga zeFC7yzbss8O?kdB>4z=#U&^C(oa-Ag<%VEK=BKl8&KE71g&@FcwEV=vHyOo_v>=~< zt%AZH29@2vAoc70ZdvtIceu zcz)k}{Y5kxf#X4es*HM3GT;dN1ScbWFnTu_J>3FZIeov6UWnrrM@>x)84br%3rGy)cz^!uf0c^-@I9*ZNOwtcl(1Ru0p=k2HWrhsi2bn@dfZPPOj5D-%Y-D5}UFNJy1qR^Z4jrn^PZu z^?ADp;EQ|T9wC|V-QsG%WVP2x3&#kZggw$R9x^E}oyp!Z>GXz`yEJn zGppW9xN!m3?6^9%450ybr)0t7qGmuZLt2!;e%)z%3nEd*Q*hC;&r0n9iod1TWSxXks)!hbU1!iA0Y z&Iit15j3U`wLvHI%kvwCjOONzO zcWd`b9{t_Um)nvcH~S#?bHlku=;_tXHD*G1G8n)?ay$X-{jf7FGx|Sj8Sb8JJis}W z=Vx5<4S&)oGH}np!!M??z8-=%90qoQHUGBtN3rCRrrJ47Rl|vw+v+@(9brOHRWz`q zCdo=7U5>*K&1tbQjmgnb};b964jWG!Q?wlo&043dmE@O&k=l!~5%4dDJYj?Sw2Ds?-;VgG3b& z4z~`fTnj?i4JWA3I;;L`b_7Uf8?nMRDdeH04XxdAmbu=sqk6Fkz@qpi-k=GFKIHN* zf7AB>Nq%SjbpiGodAo-RNpu*z=7nz-jojs zQ$86H(-#-n!^DyPo@Y_1@hLy7dI?}KHD|Y4MyY}eRh=aw2cZDyi`jJU+Rg3#^_aK8 z)X^_Xxnk8{x0j_~C{o7~t?m0G%Pyg5_pUde|E)AdX>Huw{MFfm^DoT8l9M$%{LPIo zfFF1uOZic31_Qq-lbW0d@sX(S_sUlVgn$F@L#=Xle#M;sg1>i$W1a6Nw1w~L<1YVl zggqQ zX`G0K=OE0AVgIxH*Y+3_i5^({#>{T-^t~wP=HA75xXYI^i4It??mhZ-u+(CSmLi_3 z>W5iivs6E17LE&CD{NA(G^8U40c%LbXAsIgTJku~-C1YM_ zC1$%vVCyR;3Eop@EBxzAdzy;_9aUxl4^0^tIkHdUC0_m4Xe3-XkL?PH#uhVx^w;wr z*A!?nh&A>mmYsc$A$dFV%g&8%Ziyp}q#;8)aU!55y+R%BiM5W=?-;ZyAw2{se2B16 zJjI;Mvo{5_99#S|bD@olP#YQduFdvpj1ycXoC;AaK3msjzwnt21eK_hwhO}EVI_hj zz>10hp{n+@`wzJmxdsjymH0xuz7{-IP!P|s4@+=YR|=m}1j6Tk;P=#*_hipXi}wutpb=(Id@cxfGob!Y1Xg(_`dlX)v$_EiEl0 zCYhMbp#8w9jVFb{d;5rcQ6;t+hMb#4DZ&I>I6N+)x(=NsON%;T87#QWq}}<%gB#5-!Fx28Db^P36lwQPF84Po zwDVc?YtMSEzQYjSu*%_2A=SC+%h>9=rBX6 z@Tud$B$r-cUwfkd^`z;3OhEhf+^nC?>zUZ;eK$qCy8E>A%pBq3Gs!KBtq~65CmqFdC^?bvFXb?Z*hA%$uHEcA0n0Y3X{b$>wwZyy)t&6XXc9DRl11vTR35Lys;` z7>W$-xp9*4d?xAUy54B6h;Coq=-z?>bJnm3B$6O2OuQ+O|JvkqdVaERBM8NTZ3{#( zM42(WO^0~u*Dc}`5Ny9ZUI!bC`a9mcJSOz+zbRrDOw4vW=y{3k zTb=2AHuAW(GDm|aV6a1tFCLUouS<8wN6ge1o(Fisv)2AeK{$c45z<|h*K=QnlE&=2 zKGmfN);-uhQkfUkRk?P-gDHoAqzN;6+(#QrYQM*Ie_mU&f7uc7%QJj#io*m3r8YQ= zuFGvW%=e0XQ^W{?wE0Wjj-vioY%-ein%#T;uQ zDe%zYjy1Y55C7_Nf(cBW;;bab3|>RPAe~Xp6@Za|4nFsp?qEtX##6i(dH8khj2Ak9 z$@X^I{fJj;e!U$vEGpS_7a|_u!mq&SpqAa{)*XXRPYb2u9xt?ZH*PQs6{w&C~NX zg`7fX{`In|Jz?icIUwA4pvGk}Faq|=YO${8;84-36)eqCSCml!t0r7C3}e+h^Eq1KO;B)P3fO>8(C?iUey#D^D;DC>d}8< zIDR;S@S4Rv38&HSHo2ydt>I$Bn*Np1`r_L#kJ0S*jLQFe0UjFQ*Y9gbsvRPN#bg;% z^3$t|DtYdGe;Oc~^Xlthq-a^C#+<+k`tS1Djhm<$l2m{Ly=tO$8MYP}WS9RrX)E|l zQ>2bmuazeK7%lj88!0he%a)IZ4>w|lxiz0}0RMbESmSV*JoMd}9zKxt*y*Jx?j1u( z8oRUCbvkB#eHC(XcT;A- zwH&9+`nzJ)eJ#)(bI?k(+<}&t!=1G z*F8e_RTT+bVW}(`jDVX}V^gooEf!T`wkeXXffac6Xe>8k+;cNTB?) z5M0U4fpr4gqBAI4Y;}GJjHJ_P^87NtG7gn?2|qnQm8X<_%duds&pZs3>(n&-^(Z=K zmCJ-%s@$X)ydA)qAQn!(7ua8qOm*o&H0)#ntER3|qE~zI;vDvf_WrhUy(ZH&{=9xK zEPQ=5{q5{8-^!{$_@K$|uyifoL{(($H=%UAkghJzK*Zb3kE7BQ8FD6gMZgfPl*Q4W zf+|{R_pm+*uQIasq?ld%?-h1w^NV3>=@A&b52SbP_AYjQ9;VDwVhV1Zn@bl|~2C_fv<@ z>IyO(j8Kb~tNVV55qPCvXmYHL1=9{*HfI{#!C8!7Hfk_DgaO^@yYX#`bMOZN^O=>k z(DU7R)rjI|9!IK<15(PQ39W--YkHs!Xr{y`&$xF!n7Y~|Br$uQ($D7ih0|C7HkgG` zgj}%c|+f+T~uv$8o#^wg^1I1?hwF!9|B^7!{pKd?`fHxn$vmY?2H$M$W zz{sa{Rd@X);D;dKgvxN1pT(wr+tUai{E_i3BzBN-Do><$t3NDYB-pl;tU@!&C7o&9 zVt8sz@GZ%b2TTFnsgtj%g3~L`ans!b)#Y)!%AD>VU}J?mlM|3Ae#d&tdDQ%M zI?u7&Xn`doDy0r{vc>5m{W>op4gnuGf%^BvPB1pEF;M=mkbmwH`CGmriZqOwp4G=(Q>{vI(4dhbY|CI zvEXoHzJ6mBD&^2IkU(Q#6v@oFp{SLr}Vj z-(BrI7wB&)l2{THEIqHY)+b0_dPy$OHeTSHrDOEIHplF=>74}8MMnO9#u@Q-C*yJa z_`4$O=g0Kah?Ig~YP6q$rKEh?g!ymuDLS)SbjZ*?)26GblRnpZ#9Q7XKFLwg z&>p$N>II_oIX1Be3O^VKex^k#9|H-nmHR;MUS;Bk`mhmKFHf!*w2u8fpB<8};VMJl z4VMcemAb`C!8p>3Sx$iHWjI(S@@m;}TV~KwegD9R1-0{sKr?zdHrj_abuY%OJ$CUZ`+EYb+p|hjZHp;zrRV z7>6(Qe3U|mS)%*31!pIMY;A4d>smLpKS2nNj_%z=xN&1TeLO8~ zqr6wX%*soobAJ&5x3l8T&K&zy^3g-m3pV5&R%F~7pLljjbq3`c^7f<=^+@2>uXGi; zZ0gWv1jTBfB*`ybv(4OIriuZT15{*j##B*|9OM7cbe2JJHQg3Y2yP)*a0~7-xI4ie zGPpYg4Nii)y9OKF-3jgvgF|o$?tagEtG=rF!yl@qr%#{VYp?yRBqR2eFA#2_bpl9~ zHJ-czYE4U5N@KK}Y(KljWY!-?B7Min_s=*(%Umrj+FO=5d8IfYJ4}AxME5NUh*|F8 zN%4_A#>>xPrw>R!6*4@}KcwX5<_^)Cc|tW1fALqOt*)&p@U8Wfs9B`E2-yH)LVrnX z1XnsTdG$6Oc-iZMD9A)9XY+wncye)bkwE|OQDk1-v+369&gVzXZlf_A`Om3Z1Awg#daw}BAH<%+aB%*O+3?IGf@Su9p%Gj-3u76t^B$$k@p2?Cd2_*4b0t_+p8A`01%H zkSsG1O{`OO{AA!@okS4i{eDf?GyibxG!a!CelpteXy_~7Q`^DXOax9_!`Ned8s)J3 zWqfN`B7p6k;Qztu?uLPH|D0tv={($6L^vTYgEViQCQps_bDIa4d&8DA+MmEnNx_+b z$6{$mbkIx3Tox0=Lh$gueLH11qtYILrNS2N0Era*YyYX553L z1Auk%^6jXyw^^yG>< zLtyvS2auipVeNiP`;i91gTvcR*ZJ*_XVA;b%YW2dV*W-zq@)|^S!RO~me4655JDwS zk_vv0jWTq~{HWhLJemplT9A^@)rSZoUSI!{m8P18Dg>DSy5!b`Wqu9AM@~zYI270)6-ayQ^(ke+fzZR9%>rrb6=O4_;Z1e#FmtAIBo%lif7LK;& z_PCE~aG$E9K-D)s=Pztb5pmOw%;=~WbF)eu0(^?}Sv_|G&#k?7{69A5i07LG_riXMSD9hIab%Xj=!72sp{>n!VFJrV2kG-qpQqcJ zw+Vj7W6q-_2;Dq*+l%=yx#182i=OA^9X>L)YdDz<1vZ?~vf&a6^RxKIV70Nc02^RZ z+po+LxS30ci~{7d7(b%PD?CzSY3NO{06ocImlT8nReaHdFt35wDt)Mu`O)2Nf{ojm zHBN?RDoW|EzE8+)aJ$VQ86Lb z7lr)gRSat<{O~Ni?&tt}Q{_2+jJzD$r|R21)?~YjQZ3@mLE%?6QNZ{iGJDO-PYIy> zHVN1JOoTl#{oqCr%D$E;=cyKRs&Bb4VQWw&kIl@iOIwZXK9G{`9jHkUMeSCuc-az( zsVl6Vw?RttKHZDEMrKNGsch zovTL})<=P#ShDdY0|859h%%<}u%c@3ccgL;;q8A{+uZ59*{;dT@%(MqUix&Nr{rwkUu+|ip9`L)n>1oj909%r2|UF%LxU4eM~>N! z7OY7Gma@)Q`#RUz}toP2`}eYfprZDoG4~BMAk4 zfT6$MxIm{>c@B183H7}1hhI;S+UN6*8+=_o2bbRN3VuTUPqey_vTCa|ftS^*cFXIF zvKZ8>IMPT*inEE<8AW|^wtpB8utcxxGwId)49@8ZY0YoG#*GR!i|!&ouYF$CWBxRX z8ahzRG?B^MdoV;hYzosGZSsvP7_-*yirRjoF2mEzCnavZJn&bHeYwKGHz*Fa2NSP8ucHQbvJg7cfj$WD)08F|>cWY=m|9SH5p~(9PK^K&1F96 zi{&4a_!4X{hmFbY7*gO--@)T2;=wKeY1HP~5D#Q|))&%;l;;@)VHpR9j}P7?gJHFw8j15Y%UG6As0%4=ZDPP%0w0%F&_skk z?-Tu~v!JOx!7p&BT&nKGYb{kSOS}+BVMVQBjIfn+lUxf9&-+a~5?)8GU@x?w$NIk7 z?@eDy8ew>s`Q`&48O~eRmCOU@KOiLI6BBo-qNJ`@V4mH5KA>1wlO^^GX>L%|We_1vK&6Mts2WQ9o zr){TOfWvWTdeB#%IcLz7STT!t{MK%zL@OgchC7@Uk(Cjv1wM_x2$R*@DZU#GLqd?f zhc&Ll=lw3Oj=8nqkK%1RenopQP_fuk&Wy;WGE5PiWUuTi13FaFez~hpPKb zmlt5be3B#EI9Homi2ir_UayNjwb}h*k3_hu0#DbAq9 z!%MK(r_@G;3f0!zKMMAA3%kS~`@~*64_j#aWtwPh{2d~@d>hSsZ>_30v z`V|`>*hP8ef%c3haSh1YZvOH*AAdP~KMLXycnJ_k%^_VskN6Ih415h}IcZazS+X@3 zsH1~9QL1BIzFq|d*Ne(QC7v=(p8(0s!*F(W;BCp!80oSaXvE7impS`xz6Wf!csJJD zu63AUI2>B0V{@htK*d0pQuHNj>%_qqrR(y~$2`P8Id6V%5xPRsa?}ddia|{FaG>7b z;1Vvzk!qqX{485(qWNl3?DwLZe4(V?2q#P8)gp9qc)N$*rdw zoN;I{1gN@2f?-8}T7ePQD74-B{Y4OQkgoJoGEW}2 zD)R1Sr9|!h1~s6gI`h42b3ZESbw_EjtspnTV`t;~iWlDC$YS?Sfm^0vMFzs3hL^o{ zcqTkv@};O4n|lx4v;!50$sbH}bAJuCM-ppphRxFsEGBs7R&!lH8)$ycb8 z6(@Quoits&y&9>>a4Efhpjo|CU64TQgE|Aaq(M4hKC5{cdm zgYPD(Qmk2;swI=K@5IaHusoImu=MD(=-V&X1At*!$J5oNB_WJnR-^#QHfoG*lhA#1 z@`)^Xk=yH4r$4YFtyED~`1k9VNm=h?ciHC;T@%ip3OMj}OR87#`s;0v=7-+vjl_1} zIcD+gibc=N!I}i@)9wst-x7kBV#}*E&OqUL=X>0O-Cs6*U2} zsy_t^untH=k`&p6ZV6!XD`pg5^{2=_TNV$<^~WakW2~@$(kkYg1Q~w#zSontpHnq< zcxfoM?k9}lp%a*LIL49$z^tjZ?q8!e-Zjr(h{v>Q<%5}2(nhxDM-;SH2qPhc*hR87 z6li7E-%k(TwR|GYjSf(cyP+@O7?Oa&{nkf~SyL8i^5blM{8;~vPcd8IPsd$nIFKHb zT(RN-1W&_Cm;{sFL$zIH3W&ucqa@H4+2cd>P7K9lhvg=_>MIKtG!zO8>)RTWcF?^&N8mj@ig z@`@^BTFvfGsrw{8(Qzof$70qU6=i4|W|Ex(tq^5~6mz-0APm#GC9@nQ6%EwUo@kmH z6UXJ&r{Q{6Ou2$;6C`Yn{@N||(eci3oiJDa{J||Qgwv%#HNfI6c-Ky(q4AYEA&&X> zT5JZS@E@u6qN3}K9nk642{rZA%hWGQg^u7E)-c3GEs=u>q`7Tn;X=etL7MVK6>V9` z(aD59VJKt{;r+#>NB8#C zw8@k-*3ct^7p4rAqPkC_7=|l+s$Axmr%ys*w#Y>Upbl!l;s7H#o1Y!Vd4MqMg2P{! zU~45koh>?2p@K0x9fm5tLqU<(Xs6&MGj>x1FjR&5HoM=ocmp8jM(5Wa$wvD%AO_c| zW$f(b^vqwIN9H}^wxj!%(wF#QT8`;81yTdRlX!zl?LBE>`#n>eBB&G}_SfW&W!$sG zFLk;2`+_S<^e|MEVD{1pM0@*IBH$LrA)eVsIUa z+C}oN`RgBs9~kzG1bDR@4m$vun%8l1*%^-2>x|kULNftNY-n(v;^c2 zD$mO$j1G0f>FWs(n4H<}kD&Dq_=lB|W(>;@Nf_U<=|M{p2~*tXK^0bDXu&W{d7)KS z-k&`|;yyJYqp4pQ)8j1J{DGH!CbSWe3cwg#y6FU2;f}@n3&*O@-P&`1(JS}ch48b5 z&~4Qlr<$6FFA$!YQ(37f6^sz~cPk(`mJAJx9w$&4sc1B_&+O0m=5Ia+Kd4i2GDG4e z4rnbBI|f9oP>1A`H5`Ze!6F!skf;z`x{7fTKk=%Ffs%p93@0h#NFTG^40NXQXzPEt zZNWNefC;fRB%un{^X6__nnrpESQ%V5nD-=~S;x%+&YhKNzO;Ru*F2FHVGpxqy^K=MG%?udXRGr#K40{3d~Dw zmZ4^n{4Ly9Vin?P+`6+5yglWD@iSX;A5|{V7#U*i&QUxrP_@$abLDaa8UreGI38x8 zB_3UkE{=#M z*}*%?<-H+366;4$+AC$09hcf~d8g_-~(wb=30EK3#+u@0s8MS9? z8;{SU3$`{7di1es+5C4Pw=>79lh;~t^dK$Ot~+>1Qn3O2B~CZmium5X`R|86)C!sb z-5=SQOcVgBrpV+1SL5n>Odbw|gM$3>_GO6wBiVS+Xa%ZVkvj9lr=BTL6twddt$mx= zVLL46Indx?-XOQ5Bf#Ks*WgRm@Hva$cE0U$eOPQi6xQhAi_S7e81_9$Z4sgRO>3Ls zQ}*PX=_g6H6zq1Z)~^Cd{q?n|2B|xP8@`#q#cp#>({F!Gu}`L8n*sN0s1DyBm#cP& zRiDc*yYd;SVvIgD{7i7ep`J6!cfC%@&a>?{ArtZKNVLej46blx;FnZoOc*Pu^ofV7 zmXGMnb^}C(@oYh_eL+ZFT|$_5nCBXKoOTTLycxuR-<{=Wu)r;m}~+Tc%#t(0+fh8Xp z7+7j_9j*Tq7iNX0ZsY3Dnu$)$oOR`SBX4P5KlDi~R)!Lf2(KW&uBPjkgmFKU08L;9 z$E*E}>5>G*)y8B9{|4b_-dBGz{u9+spybjbSLjs$GhNx*c{d{q(^Lr=^t0=P zFM>Td*Z-Jsdh3y3NGB`ut;1}(HjxVwfmww81;-5<0U^FKrb>5`gLTR^g1=GpQosm%ZVV$OviQQ|va!yAqDo47G*H_1bNsTq0AE;7QnbF!5=cNAt4cQjzSa z7lJ9^7MT`S(boRF29Bs>kQ`)z0d4$16l0T@1-|B>2F^dCmN_I-p<#c$7qyQja<0PUmE+Kr-5-Wx?A4bgclZoA>&ef3y& z-MLT}>jf^vfOi{?X#@0_x24_pe)%Ev5@A+^>3);umM0G zIL~+P?EMQM6X3F;>V*jiXEio;iA>RdWc_Z{bn7!B4@Ky{qS=N-O1nQ3Zli7eU2R*ntH644RC z)R=WCEqn~OLFT@3Q=!K#hVC06(uIrhWf_$!>(@!{^-aNwv1wvcR#5skh>BIV^tA zstCL|VlnBc*im`C+$zbZGYz*0*t@RaumDYgXi$_RDY!~+mXkhcrU6F}C~@H~1VbcR zFKl<6*i2wX(SOlnP?(9N4vTcar%#A!V*U5XXiZgNkX(4jw4Js_h~;*-IPc@(<3oT; ziSFQgasV|m%Z}t9v~P9T5*Um>udB#?77Sg2^V;d54L8<@qLyI9VMIVy0&_)u%X_-h z$fcOk)mlhuYsF&63Y1+D{RcQmA(bz0|2lrenhyHxKMZ>}>Ob6?dor?i8*ajrkcq~^ z!p7yrN-)nP}SCNGC3-M)TX8>r->y~GB?YkAGcwxU=`I+-=+k%$JWr3RF7e~_xmN-+w zGn3t?qKUGxJtFpbhUm0AoWHYyF<-}a-rZ!iBB_?cDKsFqq`Ui_gU4}xI(K3=TK*&5_D$P$;f{VGQs18%7QeLAAX${+MbOdyD$+#oy8_1(C& z%s?Fm1ff-L2&5&l_T*VTqp)h7VOYW0FBUCT_v<9HhU@O`<2g##y&NJr9x0)T;rG~} zAUO84Ili++^eCx>_0yT<0CpxzE)j;nlb?!H;yU|jh|fQ}W2#feEp(8`&8&YxxpGO_ zJ*=~jbfZ+2!c-lQyt4XkugDX|r{=ZHeM_TL80-&p>Bur1`Qf3Fxhi|R!@@(RSBzuw zzmvr3?<`7*N3h|Uh@ggs1rf$Skhr(Y2~Nn-0)T&2GJBP}K;0+o_Wf(kX;wkQz^Dga za8$-{HdL~KKzlXi|XOm>VMT&O5^IE4qL z$$GA#)URqcDiGQG9S1I0D~xVDeBb`_BH(weP1Cozpc8Yx(A1u!`+8Fkwpe!E&(IxY zus~;g`;Jq-pB9=jpY|>^&vaYzm@z@B!EN00+O0Yu;+HIDdBmcvJt9FtJmUmHpJ-rg zi4*Aq%s;_*LB@~1I6!CU<=sm4B=75qgI~r+pM#W#AcJQ(ND)N4T>U;@_*wj2q9!m0 zw&l7b)38A4@cjPT?niD4S9ZXMYmRxO7TDCRBoF~14U8)CNC%u)mlR&PFsVLvV0SHX zyKWpMo5x8%7UgHUUi!e_ZCwaf2WZkpW6%$bGyvzbn38%4=J0h_2Fjrj-)EP%nb61P zTc=1AWLap%X-(-UKV>~tK4Fs12HmI)A&glSc^i6HxnD`hwY~<8GAg#A7<&Nsw(?7o z!|Ibq#Cpy$^Ua`XX&1H>}zKG@--po{Ohmi5J=H9xK3NIKwl{e(Xo6% zk3Z-g6WlWYm$we}W_yNqtYo{o{Y?`4&V6dxHD(kJ6Oc7Z1~PH0GNRR%=S1?3k~?pV zu~sx~`*|ytQC_uPN?IB|K@_|w9vd4+S7Z9@%-Q;SJTzCVA^7pv>tFiVW#;^0WgLiBGS>E&U&vP}n--i3O1VMo#T#v0uADw$LSsM+^CMCE18%mT zM9g`6#zG`lH43E7(>>ivv(RLI{jshcl#)!m2%DyTDKB#@Z=YzD4m$c9oMT}nGj)WS zGP(*Jd31qf;miiE_f8J@D-#q^$P|_D&FVoIG%@)f*IFSKFsh&8%l8Y`=WjvEC5+z> z2E?(E;eh&S$rdI(EX=XoP1}Sy2q!5;^Tn;R1fk|l4c6KM>vqyAA&SD1(tqdU6h!2R zt@>}|6Ae;f~LQ;13q5rblseJ0PKG^z@t7qi?w*#aGa!F>!uqY=W{ zu`KZREXx-7Y5yUKrgEFao(rz7&SqaeFdO>N0kjP=oVjnfL&bx(?Kiqs(A~b5#P&JT zw^ZDisUU$+B};4rrYzSKpBv@tGk*1Z>{RN}Ht@9!H=`#V!RU2ZSTiKb>aBWTjRUzi zSeZP$BQ>9+$zg%0TXCM~*|?eoV>`L}Sj-xp7|S^fN7%+N0-|^1c+)xtaQq##?kxhB zm@=AWl%mI}*?-oVj_Z`^V~3X|L<2zzE>8}Llt_Syi?$D>kT)frj_z2FzwRZt>tqe9 zr>iR=6|U)%t*V67g+C>%syKgp+3|DWM)lBvX8U*2K>ZlHsJ6qp0kV-GKdLT4d}U`u zRqtO<=7&7FDdZncG?f&oU>hLjz~Ny`VO*tRjx{jIh)3IvWU#{>D=(4SmxJ=WS0Moj z>bl6eIvK&zImFboIunKi1t(A8SCEg{)i@erDp{yo!ac`X*@I}mluTgEE^+$FEj&AC+LlWb4nWdRi zw!HvZ=#>1b{KJp+R`VPijYK_UXZGM=zKE|}8D^fB*Z~2AjNl?rr9}cIa*JAnJp#Y> z`%yQ`d2an7r#eLcP-r%>#hcwXTZ?F(BZ>=wKE1o%Q^EZ(g_Om{x)~UzO*;oKueR4H zQ%lR#-VleaX#O*KVO)QCYH>W!#e%kRqH3`*eoFx@oFU#puBg-iGg?|INfyj1)8y_9 zI5$3aJ@=G}(;JEIfaJjVxxvv`xI%^mj(o{D`ZxZ}e2O@o0=13=UB9hlk>m%$D7QGZ zfL|Ri*llvf668@gNIf&^9oIiPN$ zvBS2^*j9Ro-#Y}<^3`_2TNJ36<>+d%5*@`oIppZn`hPcC7*DSIc;5^=TvQ3&uQL(9 zV(vlqSQQW)6%Z4$QIh%&D0{A*v>N(_!}8Izm^ui6l*yLoJ;XR8ygBQ69A1=-7iLB+ zCFUgW+xE*C2Br3w^K_p|DQe16aq6QbqTSoN6-&_2XYSK9)-iRKcIAI(v|a~h@pS}I z7?+W7wk1)TR?m$KSzH!Ev&8dhpmNos&TO;62|MvY{Q75sGMT z1_lOO_Se1m?Iu!Kr~(7Ch2}EWVS>Lt{R0z}D-n+MRMvNA;_D4>bTg@#i_P1q zm7VNrMbdO`t||uFlnLYU66CTdwu98yv)_lT8>F~$fR|Xp@NTF$X$2L83Mrr-UbbwS zEMa`6SaaC@+m;(wN`o;|a##Cso-%&@wEP9QlLoAUP@w<0y5sNdYz)C4Csb z-3%0CwpJ!yokW{VnSP+2XzM_puot8fW<7|9QZLIYpFxSv#+1PmJ`*J|Lv1FOrx9ti z)Ta_^R!E);vHG2;Sj0j;Ym>(1=naW7O3mVVNSvbrq)$xg6PuvVt5R0;Ey5+(-Zf3LF3PCdQc)hG&-z;DPs`WbPy z7H_>R;w1!qs+{wC`v;(HII74!A9_2$9_}cRVqPIiy+2cmpdFng%YYn3jJ3Lbf&l+0Hms^&DejCg6gT+sn% zD^4(8@-OUo+Hglf0InUTHKbZKH@w3h=o^Z0_>3L&NpYax0fH29V@=GGL4GbC2unw4 zgt6u6Q=hKTo++KbOg3x(g$mIMH|$o__2-+Ne{#$*&J0%zMTIBUN<&x= z9-SxwwQs&8wa$P8FfJquI%cw^S^J4X$BLRF)$p~XNThE4_hLfPHydMq^shuk8>22I zEL^mAdjM^DM{dcDu&u&3pH)5rT&P%6Cei`US5|y-)FVuylu!|&K33JyE?876;Oi1; zjQwKCS@W+xhbP*RgSjCHE_@A+zD{jNPV#vHCe1c@DU7!^h%wqmt&CCmA2XXUhhmLx zkAuc68x4|5aW!$oqj7>a-Qe>Wc7G-N_#;eo2KiUaL{$LY(*ex)4zY0yiq@3LSEvpS zyW8y&RNG>8?QQSY0q=P=+LU6Zh3_3iU%`9?y&%MwpFly(-X>G2{ad9BLTULe1IRb* zK)vawUlJ3d>RKXlB%)ZpaoeKpsby;So;16XUu^u-nGwRun8Rur0 zSyGj+|7L!03Jfo*9Bm@Ngah*+ZR9{%n>x3N+(>Iaw z%49O`YQUPZue1%sVE8*JrHzak53*JVFhq=MKFA^dGD=ndY<-P(=fIO-KouUB`~JT+ zKhOsZ!GKv&Wb%_sUXsfH^Ctj0ZQFRhfIPHHIiM7oFl;}D+?IuL&s1P!Y!?tny{37# ze99_sqZYLB&U&8jZqG0H(M`H!m7V{5uZ z{&8V&(y8x{{(DWACeWU3Mqh<7whn<(WwYD5X4srFxc%KnYb^ul$cN7uP7UA#=+b^U zK1?Gxqd{y$=E^V-JIiZ3(pCS*-b0~@Rqk|0mV`=$3yr>xO;%$V*6jwc#lrbXQjXC{ zwb@>I!dp)FK1dh^S~Uuyn5UD;^6z{>7DHcmi=Fz&W|zPdK1(?xQ7ADiv$DEL0#t@2 z#nO02%haWM@~Vwbj_ll1)*wgSknWFamxMGjbQr*+OR;JzYr7T+l$6y(2|Ti0MTzmW z$it?BM-i^=y1|;ggKp)C&y6d6DiXJtyH6GHic*OTpvk2J;cK%%i zE_oNLsG=Ay;WO|5E!Cw6zb3r>2@#%=#H8tSl)!-WbG~vq)mM&<+Ax( zNHxx;ZDHgKI#?%6y^vo0uQWs%f?AigB+n|<30WFk+E7F(0iy7E}HinGyo zlfazX9N3Rh^(*s;UEc<4i5Z`cnzUtlo9p|7nX&3si%p$xa6LWSJhsXV_Vc?g9h7B( z0U#vtgx#2WExnTWUHYL|nK|<6>F)zZOHqfkMLSFeH+JI zfB08^9=2)@G&9Wb9+d<9X?Qpd_k%;{3wwPNqhl4p2S33hUrG-kR) zKFnZ>PE_FaULG4TgO16=7Vbq+CjY@>Q*7t9c^O*58i8Xa%Cc=z;~^XWo;97FoyR68 zuXYj)^5?BDUO%?ye36bmzu%4lhY>u$DWwd?!5c8n7#9?f_f&C>*Bx!irot6n3GY*1aHM}0#|H` zW3hL!EMY}|=>pts){!3w3jHFP-+F=8r5Y}dP_=(BZNl)m*6fWt5@bHVx>d!=!4`0$ z+cw4>_N6|&2`=tkXg=Z-m=>HunXxV~HqLSm+$dQ&5^${|SB&UJ|7y@Pe6;Q1s1X<& zX29l?yqpP2X!#lDi^m3)+ExIX!jd-qSguCYekMu9n_aK19> z>Zq*h|5IwQXq1#`v0H$c_^_VXx0igP6GUxH!G2`Qk>cMN7VvWFL`}`G0ivgs z>XsyA!}dKG7jPH740mc{c2z}XM710M#IUTilrMr7e99V>3N69>3)wk0WFWs`50Zg? zImR(rNylWf#6_bNJ+sl~ilkKG89}SU4!aV`Iy3#~3iE&O!d^`(_jQ;#~p6 z|2D0qh^!NXCCp;?K;VpGfd3rW4|mP?w*V}j8=F5}{K0B1bFMmWS4;TT@BBlIKu^wF ze@<@0*1>dsyVEmI=SEMXt+%i?4Or>-{(kJ+^^Z{N-N#B(WG z95GWqxqk_MFs5^0r-Tk>L)xy!V%J-{JkZq11K^=1o3Zh8C^(!oq}(m>uZE~jBd1*x z>-y^6u9<*Idvf`@8bPbzePY2!AD~zjrRV~sg-!~_qwrzj)ArL@L>(mHK4=06MZ|CgzTO>=Gq~Qm4(oCa;)HA zW;x_o$!62VPZ_27b^oo((N81fJdqDV^oNo|7)DDN_Za35`NSw&dujT$ElA#uh6*a-Su#>#ZJf4z~QJoG4<>V-xuOhLf{38Gsyadkh z;DDzl(@e0HIn91062m>%lCyNN@`n{8CIICbH%GlmM&g-ltp})W3 zYl}9?nfG~j>q}PEBPT?(4BsW5DS(VD=SqevO{DX`rJ?@`zk;hB9bz=`yWzcMyiWA* zyMNo6i^FxBe7FrqX}mIsqCjBcT*<7!<3WD=w%yss8yfcic>w@vf#&T@iDJb_MN9^) z;P>KPW=@gQJg(?*Pufn2nu&|+&Gh^% zLIF|{3JMB{z#_iIfX6KoI6H)J8Ri>WmoOlMMUEUR24Z$hz~wG+pfQrO9k;PMIqQ#u z-2{iq&_0jnHJt7b-f6vkt*`|pW&SFQ9?yfmaxWH4{M$tzZZQ}d7@0TsrG4T4~>Hb_=s0T3Cylq;%_CN9E zrUr>+^PobHaP^MF4E(-a44rbw8eiZBA|0yF+ql1BU`&^5h2=L4)+AMDp*EgO&9At= z4rGYLTPkLzZqJoazleJs9-W@5_hx5inpz$#U&+3sbOh7L*nL`B{j>L7a!7*yL+V0i zv+`US8a1_f%j@IuEYBO62%RL+U>4d$SON_zlW1-|=g09yn|vrJ%~JjI42A1T^z+B)C$nJrc7Dor#aCkn+W+ximnR{m*&ntla2DYxO@E8qMc_Pyu8DwYhM^O zZRF(@&mSiJvWo!jKmv^-kg5q}5lO_ATRme~6<+9^iL|Df@nY>yJP@KMe6|uy%k2g2W>`g5h=A%&p(P4)yb-jt~djjOgbRc&< z%iH(K>q;xYh+s@%!Y+c~8Re;J?0;Tw zGDJ(R<3w4Ha;DI?Dy?J6utlz~!-PQ#;oS~#EH}3NKIVlKwiX$3ym3eMRY`Bo>&}Iu z*aH%F6vV;gUu)yBD=D!uuH>&d;C?nTh4;^K7^PEZ?>kj}yv_JP{ z9NLY&uPd^acH{*jV~StQX>#=gdX^`f7p#1Wc%oSqA~s%6lrEQTXdW(sTr7Z$$~q}< zh5AwO8Uw)SJ#Xr)&wOhVoHX&ZX9~M_S&z?oBYHfyqYQCS_~>8+Qdj>uM^Df$@Z#NYZMS92t_i~*h<(MyVR zuS3$lK`Hv4VKIKs+d$7#7h1Sv%L)R?H#3%hwF#ors%k}t(JS-c{tZUsa~{wP&zjSZ$mHX-_vabi}?bMVfM&#q7a!sz*$!vt&UT--(~VyS&51m(M7zxPdlN*Xq8K51O}u9vbs7;{zD^;q`2 z=kRJ_ZVq{f+PJ?X@_BtwY}3T6`1U@-7X5D%Yk}k5V_9IMy_tIa$>P6GU+y~rZU$8xm+^U+BN3Z;N=mIuKAaWq2v5Pyonbh7jX&p=F90imtPm*9>{ckh_5hP= zc%)uIok9tJ|5BtyHk>3sL;(jRULe#Kd)Vy{PSQD>e1v(2B#~t5!t%!@gV){d=WC@m zm%;EFY{E`TFZlDNN$+4%FX&36scu41(U5Mhei*Bz(K444AsvtFZ_eZsASgAut)nbn zCt0#?y+C>WzGIJvi>2clx$9caV(6;%ug~Y>v}&fK(E>xW4%yq5vmQg?eVBM< zIbOTTi{YAUN&v~uYql^XwZ=ZE>qsEmt5JAh#XDf%u zJ5QaUK%M^6Alr>+mQ#y-JSA{%R4p5yT}jB*C0SHf**rn*I!qWgp9W`Xu^J+zpli8s zTczVR1OaK=x+(JQ=RKqCf6>llu$q#;Y3o4`F(O%>Z$97qy&Z5jnd$;3-%v^;bK`}o zSm>MvW8trvBY%0$n||aL;|KQ0Q%n)Wo~bTsv8lW%8iQ3`f4@xxqLvrj=&nclrZwNE zQafgl#a3O;csaNlJ=udA6>Ap6k77lO1{Qv{5C4Yt4Z-7zyl?Ye-fB`X?T%odi15N> z=SSjTvj3y$EQ8`|!YqshcL)$5xCWQt?(PZh?!g^`ySoPuA-Dy13o^h29o*evaQ1$? zwSTFCp=xgT?S9WW&%pqGID7r02g?vB-oi3MtoNfaytmr>p(O!4M#mphvOj#|oCe3E z!iB}m$cNN9+?!C9~;z1k#!C@$a zgoW@=ZE-nv%cJbSd$ZaDAwN(Oz%nGDftMcbhjH#@-Ycu5r~(LZ>MsC zfQ2lZpW&l}&mV{#f{pMA_7BB(11SI~O#_MY)b#|v3L&l93XE-wGKvdn|iV@byFV=Lr-8|B!xB)G>%$hhvZ zoWWkPGYl{$4d6X9UkEmwP?_KmZT>zF2N^Rn_|fD*bnlL}Gy0ylzELWE)d>pvFwR+Pt2(%J(Lh!$6Dr~37b)!QWuOag!p_PV zf1VJ^J~?`yWgPgxw_xZcNgqZnpOO#~=LkWj^xh07{BvFakuQ!dboiD2$;62y;&?Y! zM+LDO_xWq=v@;+D;nsHhXer=?!``)2=NAE|AwE-W;$=evBLMwu*dX7|oTs%RTey#W=Tycgkvf05)`vn_{lmD<@kqS*y{*aDi3 zR1FF8j}!4FV zy4@zP?OvFc=U0hcXvcNVKYWP1UQzAzB!$bM1 zaDA(G*qnUj+eiB0AGIWgRpOSgU#j|6goaBJDYlSrpRW%pZJS^YBZ<7o!~@Rx|9KTe z)Uf`GR-cG8l6|fyl;qW?c;~vneznP)46J~nhVMoOQfq!#!=YG7&!?ir*4C6UNv-P< ze|CBP&Fs&BL?Rj9<4|`bL06QYpR2yz@JnfHKXy5Fe7N0$&bXnO=puu~fM54@ClwY= zbb5?hbK1dJC{ax;4u$#kW$Ws4q?q-5UASQW0(u4#X?dAp{?JqX{p>sLjjoJHT zkYp9?kVcLL2~!gBN0}&xr*rzaG?+G{r*7NSG(JRdv8098%H1n7n&vU~kKG-s=nIE1 z7#5ry`=}KgqLo#}l4YqV0g1;08r6_tzE|887f^e8c=-24DCmZs}bG(xd^n|9?^PB{zq-2G^E3B+U442>?=s*M>K$-;kttjS4Lw#f$q^>0qilUCIdHEQi}C96~iT2pFz5ap>m0|b^rB_|Wj{dqeKGVcvC z0HG}3X5d8VVz7)|b}uZ_dnz=*c3t^pAg{o0YHRh}C|3^ur$%u;n42@~9O)xy@cCJ2 zC}rTU^4#oOCP6^+iFbnxN!M?~*)`;rkxwxFcgGqe>E%*Cf-N@*3oxXZ9dD$ZY=e#4 zRlXmv!G2op#0{p#re=gq!Czje!(MViP}IBN&_OhF79Cy-_RQs8GFS_Qj~Z|s5A>bz z-oZE>A2wM$tS1kmzpr)&Ghrl|bY44F?o$*-^1*>6L>|8htkJSL4oj}NFbzxA%7Q@D z?HzqQ!1*KpfI(*AS5zOR)VyTpp>k9(2!J zoH%SfG5%o5pV|o}uZQDm%qiT&I^-|dmw4;n2@{L)!ViuI?)zlb*8K=xmQjFLm6Vd=g&^px3fzY>PHe z!riVBoRN~y0PZ^zehPPDvq-zh)}`?T7U&&K{u7!b9BMU7 zlpZofyb6I*8Cl!9Jv)QZK=4Y~haTyCHhWI-b? z$OFw?WeOoV`4Y>R>eDqtz#g1BpGkiUYErr?6IznUFsPUDC{n1Nr9q}rqQ)Q*5k&Ze zPJDxzF>3t7plg2GP9`q?3;P7=6LcNOGwD^!6sh&HD;LXz&dh-MoF>+~_=P}go-uLy zC}2I@x5d8nK}&i(^#eRa*a+Ab`?~XKC)C}!)u6`4YXFbJVFYcL75JsBq0q3zhtgCEWqGYLwdw`)iQy3fhpqb>pYNNOh>6$Sk}k_F8oj{G{%G4OusJ@Q)jablU0m zJCmup&kGT{wF`eWe40P-AQ406ehe|3&}QRqvB!HPH2UMhfAzp@{ItybkWB8wmL!5i z{%n#yLe6%5TU+?xC^8td`L$rT&&F!#AvHC{tEXdPWo3E(H*GC~SYt(|#Os7x&hWNT z{QT1GaOsp?iS~m-GsZYBj$kY@%J-l7BVGT>R}*2GMiV-kHkw5Vadz^X;gWu zuhWUOZ{G$J`MRCDU)FdAp~wVbKGrH$md;b)4w|5FxEnup-V_SCA}5eW@F8%~3SON- zlDt-P^a3FxakAtJyyF?UXaCTnT}G}DS4`rvpM@43=cWOfs z=7Mh%S|r$e@hYlakNl;T1P>o20lWSBq&5V{5I<@OE^JPcJb}c2GiXYSGQc#{mBPPD znk)|==RODz=jOKerHfCWvYLtg{O?dbD_0gB^M|$7w0fBDk>J5$CAU9o?mNb)x0}X| zc8Yhy1I~zL>OpTIDu>h^v>?e@JIV%K;9pjGdo+GR^mQQR=ML*UCp$Q! zdgx#)?s>yKI_pS&f>QdmN59>j<1C^7dT+YoPHpC$wX?LZ;jGXY?Xr&}6@+yOO`v*# zseV6v+6s#*%$u3Qd-&avBAo7FHWNEhNa<=qJ+3$sXmq`ufU-OFeDt`&w-DahfO#C0 zAM6g8wpoZD-JMLKhW!jX;=_UmPzmXAFId+1HlQS;(+D8*lyTNH(@HIldO_qJ04 zozt_I{0064+-kvF0Ao|u=Kuq12C^`IfA2lgm`#IHa}0EJN4V5j8ruYOI}VO*+alL0 zd{yr4#!b@DU?5~ni~UDnKal`ZtK!C<9ronR?~0yBW>x@!I(-TEUh${`-RuIi-;A zljk;{lfEY}-L?+kG{3o_3A9h{?nWO%JAmdy&JU{l>k4TJ>X2vp%a%9G(4x5fqf+rl zErWaMcpM{e{Zr6LSCY`5B>EisHkM3{_3gY1T66F4z|Y0S#mqe6^7evd@Q?3HF_E8R zTwJTL`*oQqRcYVh3Tmx67;Fi9;!_XiG zCYq-XDkz6X-ziW-JPdb^i)L(G*8{vbgoTxZf`VjwUhoQkUX4;)6324|Z5QspZR&6O z=`_UCqI5p38Un-YzawwL=eCy>LB4yuhAMO^o8n5;w}`gY@+kJrb!Vso2|m4B0EY5iZOz47sVU@78&_;=ozUenOTD_F~ZR{UJ{0T9t+bD{9=i*5% z6|d5|SV!Uy>s|>~1zDT~?94h=dGJaP@9q2|=5hm$0%d#qX7Bbd_ zeakq>24VZ1f6&vZB@h2(E#EnAPNkt&DK&RD94rt%s1-`y8@FgYFu-(KFg&n(KTMxw z3NK9fBVPSxytZGNx2XFK7df7_3+Lt5nd&{euyljY2%kUl%b@l~a-_O>>VXE~{DsrM z@!Db|Z?Z3m>=NX{7XlOQVb_f}%6MW4IdcYIJn@fMApZ28S-F8b&=PzpE+8{#;xw$>1%ANE~sZs{h#844@ibW7l z*O)2o>A45-lpc~I1O8|nd;RlwH5dlCoJGxa(bRyElX$~Q$rrJM(Ib z-V_H0jB)0!x`}nVhAv;b^orEZj7mU`aIh};8@`Yp&Nka@n|l7#nC(R&=n2Q#<9wk_ zk5^Q2R4CGCfJ8U^JORqPoDC=>x$nJy8?uI+15sku0&g?g=!Xp?5>gS;T1mPHj^#aa zN(3~t_Yo28i+!TJzooz5=)Og|35$=v^&rB+QRqp>bHggaj0;uo%|?sw3ne?_QH;wy zB{!j{MIB64?03K!psCk^@|@A?SS(!FtX*kv2fJYhyIX!`%DFM`bji+wJZ448+1H-M z{?5kVbR967oPCh%No^3L`yPH7@uUe#-Yw0w7$5e&KIZ5oms%i+(%{Fi^gS-w*j3xs zMAka`xYUe>NiLCC5aEF7_J%wbtvzEJwelG~8{O9v=kbxFMo^5KC*j-28x!)h4vi2n zB$hkwAIXkhlt%KJcg7zt>`E5*mT=EJZsy;($@mJDP#fU`1aQ;We{nhnzb~2rybM4O zVrX6UBmsitFLeLcyRzNRs%Ot>lwlDsASfX>xOS|j{@qj$JG_d{#6IAmKW|?06O&;7 z*|BU^ewO9)4j*ttKXzUXZHxG8l)^wK%f!rs`}i0!wtp>U8a0m!X>l>kTw3}7sHtTQ zKYBzHZJpjO)~draP}vGCP0QyhJsLupLRskX6lni_aqW3pM8RvQl;Or_6&!_0iuUHHfdFr4H| zW_H?2M(S8%4F@C#)$58Wax_rnNllj^9U`GdDG?Yir*DR76qr2Lj*7TLHHMN>rtQfM z%&{7bli@x6;k{~)A07FY+imM5`Kx3+xPmt5b)PBq9BAg!2Pj#w&&##dE8NWV zc#YXYkukQc>iE*`UI4P`K8H1;DfBezwo}l$XB`GsPuw#@VlJaq`*fP8xdG$50hJgE zpCVaa*##eY%m=ZuErk2Zc`^R<_Zd%!;%MmasW1&AzY?!qvxa4upiUG%Epf|kwG2$# zNU$b~_+uLoUdygW+x<%_qw2g>9~2|Evm)EnNvg;8i)4@RlM5S+dEak``;Kg;tD`>b zUC=e5iC`4uOzgOMpK;u?Qj3IXe#)#q>ilUX=q=!6wIh*6p6}a+n5>Yc{MM?D+v~Iq z_tdsAMIgAumTZO&&ELq0dF(IH1n?sM%bixxxeyxp(LG*X6jT_D zYD<2?@xu7Gd*>>Ds8`R>_Or?UV$YM;e#C|FjoPTSXa`K5zP%ZLHp8mB=Kcq6^iaKK zAX0vZ{b>G0s86u|p7pEp=embA9q= zF67U9vkpXodAaK^?%qt%>%D0yrAfy13BMy4Vn%lXaYR5JNkZ=I&oyh{tvR{*xBuMQ zSpT^#fvX|x+HH+jv%S=ZV_*EZk)H2aM3VeYIc)VRKj-F>6JJ&|eV!72__>+gsPVf(Rl2+_`DK>da3$yO+7h_vbMSDwgQc8~=44 zoh_t6c{{Fs4esv7aq51sg8AQ!29*@?vU$^X3n2l4_ep)vmZNh}l*8SYR$jQ>sOBFjVR4lF-m8IhbmdtE1y-I;m~VI0tYVjqUK%Bsyjxx}jZv^hk3PY`qUy1LgZiGJbV-11obBK1}#q zi<1YK;s5Er_K8$FAuc7LM{i198(>FBHpvpiy9Z(mwz9_45I0q1!zX{aN1zlR7iWz@iT zC95aGpFoe)Gac#&@uN@cjn=$C)>toJ4ILvnUQF6&;maWbo(JAF*)(PL5qc-UKT`{?XBb=5u?mF zZWSC-*(-LVN}?(c5x2K7Uia$RI0SeiOo;$rim-v#fZQf2;{SUAC{t)mJv}q*JTeR= z`4tQyJw(U5VWvdP6U@_dy#8g8S0J+EGlVn^8u`webbtP)dBA;&{ST}#B<}s1x(rCP zTUf6fp!>^0Z!DlNNQP0maY=$P92*XFEpX)qkcLhGD9UE9nBC*LU6b_o5f!J+D;%`JvfW_*{=!p0|(! z6S@m(R7hWNk7Cgvty{OcI=}AnY3%LOoRMs*>sQfl?E*CS^;?F}*!&COkuYH@wQFZ= zrtO*qT*l&617bS-dZwH&f(qPTtwkDpCwW_|L*8yYyx)4P(hQlFnUkZvZN5v?PaiJ0 zkRILcVI~7RQ4Oq(=2k1W>9{O?rC6jGRnP6`!B`MmRdBt)YtY@AkWkHa_xVewwP>R` zB1~UCzI60I*5n3D-3$x;W|k4fyv0im*{*g^&8M~n`9@DgNbcR3@^ZN?*viK>wW;#t zX>mctoW23P=;$z(U^&*ppg3=qj7ykI;W-g_cijz5ghz+P{UL`;7~$ml^ty1pXr2hRX}N!e_J9Cb`@<#|2pd6HKhaUw`z_FMjQ#jc#@*ok{4wd}HYfjllfpA+4+US-+?KnMy;V~jKwi86I>v+_z; zxV@t1uH|k&WgSvz^Kv|Ld*Cyttx2OwkVv8FXU8u(H}BZBwB$=qE9Im`^~Yv>NRh16 zC=)OkXqs~5YXl!&Wnu;8Lpz}X=$M#r8$M*FSu6kt`0T@$(9;Q)&)Gx8!-4F2YcX#p zcD6!JBa8dMUMJlk8(fZ4(kCE3za4R0Q}V&Lw7-{?kElF&-7!=HUqMNPs!w(g$H%E+9;I?aQf;+iKNTl z#VBTXen?``O!&z1?av*19ZchNUp&;-9UqbSJVDNp8iHBZLEOE{;9d_d z>a5H9RR71Kx8X>UXV03hyCbx~Yju1MVUgH?4^_AlQEL)C$38$$`Z<6jqyoJhP|O{{ zgu-VlB<3@5azRXfeBDi0hG~pP1OnJ2h4-xGwsmhUxhS1O*=M&}>EBPTQ#gmXYfpSo z%J5rqsZpuF&emCW@FWI7<<}l+uwZrDyo_>OUi)dl23(h2b+U1-p~6cR}r@hCabUr2seUdJQh%@un>WC#O_orgv;44Y3M2 zImFVs=1jw~=G5*X8)cl+rkPNi2tTIqsV!*qY5gq_2oI^_tFxv9wIAaRfB}~oA6b%o zze(H@pCLWOlq!Kd^eg=8;b& zQU;?uW7^`HcJPF|CL}vT*d6fUF%!}?L*QN zG)Kk=PdB<)MCD`iT?0F@JQ6_!Wi9ZGN4H+V(`q?7%S3?*H1Z%h3cDN`Tza9G39h*K z{GFXK^}l7Xp2m&2g6Ey7eSPA~`K-JBv+25&+*+-v@3@x@w#?$Eln}%x7MU>2n0cI5 zqH7L;{it!rATlxF#2j6#>fdqW{VJxQ=hvTFt}hg3=~2Z*t9A1cOQZIr=HM@q_=-c8 zhQw~+q!C3kj=b#5;*Q%CZ4wEtWldW?;p}k$8;)#yv*($v@OiLeG3bf05Sj9z?V-IU z)>2oF5g@hnC=fLRTkTq7@xD+#UtHG5T64inucU>hj|JX0&OQr*>*7^&dsDofu;3;> zpDP;YHYk~#1l78v4Wh!qeYYwg+)XHjXr%oLRa($LX}1%cJgk%s4qJCj9XD=6JEO%3 zVL)F9o~Z7xL;u%6R%cD0=>`y_uz+ZPHz5p=7Q{!5jVl=*8UEwAJ_-D}&9~Q)&WG^C zzD$CX9aS!p4#ae>kZ2_DpU{q#hHQ87*uIk!<_<3?(!2lrGJ2aFX1T>GLa;d`cGOM@ zP=mist;JN@FNxjuyCv2f`){HdZyX0*^BQzmWBJvr#*!l-h>MkJh%-uy6w=4Q<%P3o zxK&7&(TsiRn6aWuPIujN?{>&dHL-nH6|0C(`|ns}l@%X}2Y`A2a|OPHwil0DNk-`s zb?ci!bwos^76VOj@DtkF++YJs3SWqaiJ4!Sxx?bkQ37aT#UCU8D=!+elKGH&vqsDS z8~HYq@dIM{m(9$;2l9IJkpyXoO^%94p)BKEZmRdgw0QUZ5Ziw(k+J{msv4uvpOf~K zVkIoUeYtDJMF($;CYPYk{c;!h*!}cEj}rPlGm&(+>pYOKJ?TC;)3M542{fU`Kw#Ul ztkV*zq^a?at^1z(*Dlpj6Ku0eqY6+Iw(D(Ah(Sx6af%%-qH^{ZBQ5Q(k_Xt^vh0Z= z=FegI@lViH1JM4mwoXWvo7?KJ>HNB33RC5 z{xd7pvRU48n|_wqyD3zhCBHoYS41wL@?V|s=|eF!Nq@o%iYYYJs}Cj?(E6-LZZJnn zQgRnF@NFmgZe5;Vr~)Gj^QSM6Od$ez(O!=X{z&9tE8U;^#)&l_N6E9kea}0M4n(CIFtadlXKh zB^iIBh{OonsaeiAxAV=dO;nouFlKpg6 zro{L@)*tGp%BfRjMuZ6My8cKi>>HPTXls|Q@%8LW3QfWXGE$(o?Ych}sV!h#gg9Ox zvcNAGV_@J1jjOoop?|o9u{FW91Q9%up61Z;%L^IfQ<^LMlmygdQCAqqd0*7iPFI)}b7e z*H}Ag8cKOtKR8w?qVdoN#B7Lx!PyRKlhrXg`WIVX{T(!)Ek1EDH#(T&2L1|oBWEM- z_QAI2pBcz#Qh@QnEy(R;;R?~7UCNa?^q6>Iqh#dalt~{IA2i5%jyLz*2G!9~^YWB8 z-tENtv{$n_ameCJ0TndU6qsD0eNG*U-CDipzCaR=m>yYKlGlBUy`Nu*pBp`bCI!1ESq*~XT}i728j1J3X@ z$G}P9ba7BU&Ne$6(gl+yp%89L45-1TIi%@ z`~XV#`HgB&&M=Fvlz3LYw&EAD5V~F{Cz6BD-S42Ba{Q|{<^#eI&yM(Qz7@aouIC5i zXMXaB(MTNRU+|yH%jp-Je9#mo17uU*(HBS;1fbI54Zb~%L_q_HzEoPwMUTtnC>(ht z4!eKX{8{I+O;K}f#Z^!wl}IJDZtZJFI*#kGd|eY;!KA0M|{=s*VNoKO^hVg=>avGeI8PoF62FFUNkDYN+F$7XZYg!uJ(R)?|t9 zF66tvk&MslRd+9@n~&!2!wX*077qB{tNq_qx~#tFojRU#y8=s z@F2Tlla;^wKsh81CkK`yQ)?!qcYBrS%FF)okr{`dfU5duc zseyi?X)ogPF(VjojY?28Ut$Had{TS$II=k9jyRF#i#3V|epxMSFOc$xbtdMEdN z`(oBlxBl?RGjk0{j}JlxcF<_sPYE70P--DVo(>i{@@9Gop$msy0c0kM=7~z zTcit=%D8E8kotWQH{dh22@I%22LZF2R;h-W9-Rx3HRwG8AAcs_#2OOAtd`Z&CH(I; z7#91&(LIFyM3w<=-#+~mi@rJ~&9L&Kf0bg+rWc;R=}Pj^I>qgt{Gl8lm|D(PBlLl; zSrlwr0wqk$fdiD%?K}?{2s;K{#gW5uXS!A6SZ2?&B`{L}O=LHJ+`le-6MBN4ZtJf< z>XY3cCSGieyo$iX!;fk;54yaq6-}^h zJAptEMV>cv7u!9UlH@ZU1HT`)3u_;T1N~NoKmvno_~+yP`p81OVTDQI(f&~Y9NVVEJb=_xcSKY?c6M|&?f2n+Abp?jlJ z`GVdKOHt|Ic}wNL2(|_N4sYamhM2MUY;P!1$jKNC1w$Y2n6ZY>JsC5;5>J0pD8p^M zRqFmMk1LRmsiEN7Mw+nw?fKrNrsqtcpTdB7^?n0sGhFiG{PjC9(iFVN*YtWBtbup% zdq~#=H3XokXWb=;u0t#5V&p3M)+IFltJB#6OM^|!a--O()|4Gn=(jQo=<&~V6uND6`W`Z8Rbr;ZQc8&;Y69Z zaG1nKaM@w#Fe0HKw}lLu-1KPprBSg|s>QhJ;m^Dv!w|KNJu(TlZDGJnYY?l}pu3Pz zQXFAdh6B-SkAiKR8NU8)BAI0Fjlo4g9d|(%Dg-Rut#jo%th0_@E?4{(DHQ30E~M>_ zg%V}ofe&NaL3zO*pHf=wr!e~_89)2U9WIY4qFSA-g&eV>m#*PDYHUT1-VUS-QHyf$TZCE!0@&SQnpu zf!Zj;et=KRmR}yantOi*9H(nYnGT|X$hZ7dUz28LKD0QjO+|`cQ9!&-4j3mG%A$&q zLDzCA6WFzC40(T77^J(5_Iq9zM2pnPw*l#QM4KfE2Dx42R0hfI!+M;ea?W7WF&G`+ z;LLwjB!xzN;d6)+@O^Qdl6n@&rIas5h;R4-u*-EvY8X&vtn#~kxHSLES;IJ1mQNim zhB7WL$_p+l{w;MVlI_*L^Pf`6_bo57#t9ESg+5g%QWwBSm;yE7@}4J)m==xb*ZuFV zN9N|M^?e>L>dOod-cD<05AB3*Mk>D0(goVjoX&Tw4{dCyvANmh(A`$@P*d-(SA0T{ z68AQmov}}Ev`pSV7kt@IfldYxpzUHbw>|B_|9k z8qa>R1&Mn11;$B>etwxy3~}-O-XitGYD(|}n~PC?&v--T+ti{HY}(P6SXF1SFAAG~ z!rKam)`TWk#$X_fMWv-0OvR<8+)3w_zq$AiPeiiI(a{N#ILp*nZ|=;Om$t{7h2(KH zYn-T*8|)%9P#ODNK5p^R8WT~Wnz@EkZZSxJnblGlM&X*AnEJTK-E%10bq9~7Y-}jF zm&L=TnU6FLmBx!Wb^(lXAg?0g7`F_&pL}REUs_x@w_@9#+ES897OX})1Lbrgnarv? ziM2g@gJbMiw$-^{oAbH|46sM5HU_qxzVib_M51#0r%Kn5y&`m=dzGJ3~!TqAMyX1!*Oaq{2F*g z?_8mm@4T)i#~8hx1#s`T|Fj-7?5X0rJ^A0v$of2AI=h0EJN`VKK{X6aRUcgM4GW#d zskMJs9|f|d@u5cz{K)Le8)0|PnIw4Iu6n~;oo?H{dok!b{sc6{UI>hOyY&3fh;ix= zcO1w77n%k9Xpo-we_Gh>9m}-w5*E3BU;{?Dyl#+cUc7rUg>tDtLLbZz+>{8x>qCL> z%hGlM1!YzH9KgIwI;{M$RZr}wu?}bl8lmIj&{;_~gxp_h@mP|)SNZ>Kb!ip~H}|Q< z*LSQY!f+pX{B2I}vMSpn?6cS0ss~wGg~Jk8AX#<6oc^P`USBsFQq0AgCP46Y zgMI*hHsM2K?j%|P_nT`Uh_5$3gr!^N`*co-8hH^SIja->$Q`D2^qa*HCzVeT`;jJ| zLx2OhV z8fu+~;%nZd&(m+#_9Ac|P)KPcf|D;&!A|CXk?9TUc*BIBqiU~l8~NDEAs`@Llw@va zhsgN8U>|Jjh0+gGOM>k!a+(lHj-aHv!0+#!=C$^QDe?#w9hk}&bXgr*Vgy}Zy!=?u zMqMg4GkSdAAbt!AylW&CxbFkkW&6*)SPYo+1Af%W!Z+v)J9^;#$u%(2LV^KA zyDrn-2lG#bAW-@it>UDu=*{%j_D%3Cq3O}T(~Xz&BApr&NQKDp^l-P#wp|c%6hn1swuGPT~Xfc$TW;K?Mu`7U0J&8A`I#$`@Eti{)tEFrC zm2s8EcPq)ClU|;TLBsJR{4URY|7+>1eS55hUwU9fZvQimfZu;TQ}9S;XMtz-^o2r` zn+7gi@5jgYBPPZhyJCzst#EWQ`ipIx3#VN;;0B;Qh*5Kvn-*P?j&4|PJ4spJ6+h#0 z^uWzFDg=3C@^sEwvoPK-|Kpol~kOdy5wXujz%7TE` zcLIjaGaRL*r4XkiHsd7)S!=)~Z!0LJ{!KS;+>v)ASyC1|XLw_SA`%#YFrV)0 zkFoRxItIjn8@oZx2X}+|Zelbck>6^bWO^~R*KFd@X7hLm#@(Bin=T$&de#n2jhdkc}-8&ljUs4FR zIPY2q-D!3?0$Wp$fhC+6T@*E2$uG$zgPdt>hF=q$1C>)DzJ?`gI!i*~8mP4-ocdTv zv!>qHD$L`9SQ1L(!}X3~-=i;6-Ma)NCEMP8Bn)7smx$sAFbgjVk1#|710?qcvZAQp z_dR?r`g&ALW=?#Bv&xr9GV~5nrr0^10sBQgbJc=A;BHeDy5w7bou>w5|LCW)Cz#!< zp%3NB8ncdma+QWScgGUE3>i#9(0*}lN`_2DAbZKltyMCYW%{&-fvnNbcO*=wtl8gd zZep{;*?ko|-pTD?YjQ9v+KS!vHNQkQ0ei|4o7ai7D9H^aL`m((l4JK#_g)!}cDqsC z$6WgEHyY8m@~6zz@?(#sHgghj>;m-|(XLOI1@;BIzd|GZT6gnX@r;7d=KFsQE)wPP zR10BiD{SpJ=yA=YR}aorfTSh3(A%qdBn$+CC>Y$oaK%r`ib*87&*;? zls-HzvNr8LOJnfcsO)fOg|zT~ke=WB0$ab;kvf68rpr^+Iai`yEWiqNLHE(1h8d~M zR@Y-Er|YNQd!rE8BWnaa{nmmY_Dvs-)NSR`1|s6M5X+^ka`_y(L6?y8rzT>IkUH@; zhXxmO$HRw4k<52x_(kMq#;{|X3veexEul$}Te7hPrk_>P?a}Xm&`3;ZxV6K~`WZRhS zJ+AOfTHj+!k2APJAt$-7tEoGl+^ z)bMoB7IM){o|CywK65%h5*S)_2a#WbLX{_9lWGLhwQ%bYpk&}SUGT$Ffh2w4@w1;iwZ^9jaxrxVhrB$ zmS8x;q!%ML!W92KDLy^Ay?)Bu;(D z6NQJ(69aM$SVx`$pMi{K54qujZ7W2p3chQzF?<3Eh=91>9H<9g{L>VA-eq$cS6;Ya z>bY`J*p2P^bI>G!V5C%2$D@@u6;b|Sv1Xha03%@V8h|kTytqDpp4==M@xI)k1iFq! z&kO~lBt^mQNESI`ee*Ir#=wNfWyW1Nm%7s6QKQjGXJTspLvB`S63A_Jt!u>(BrNpS zk47rW@z=3+C2HNN>oLJZrISMM5(*6a5=aBXU!F3d#@RVJTP)6PiP_n7l9Cl7we=kN zPSAg2t$DHcV`HL1w_@WvgThdkYlDuwv=l%>i*x9#LkBvVcKbN1mrTa4r3yuAJpy$7FjS1g4gGD-few*>Dl&r1)p!Vvp)C-f9;TOZfJrnH`R+ec9LSmZjb(D**6Gt zD-D@D-k%4kX~mGs>@4(|CemD94(JuT1vG zfjN5uhzIfu6TNun8VAL=z!VnIQcFBA@jv%l-#x4--28P4v1t;-zw%km$IL0W_}y0rJth9c_{tWI8?t_TsrRbeyuW}e z!OQL#2~h2WA<$KY*46SPw?(h(c)8wd{}cv+&%dkj)rm~9tW?V^x~RYi<1R_IzR~Md z6bTY`&9EU1dxHn^#FGRg2_MbBeM|CNb0;iXDDUVEe|BIft6P~+Z_^Nb`#?y^Epj=Q zm<(cL)2a)2@?5)Xd78N$8d+qjWqw_0$u^I5LK1x-vlH~Zb5dli1gW^KVi4}>7atM> zRIh;pZMw%B-5BnKQ4GV!mUx;78Z8|sbc;aR9n>E*?)tql8C6O|<>IYI=a!LJqx77QvOwwVs$v>&M82JT~XkkRSa3ZW| zxpmSfm7}m+on*x&L&!tI<3OD`ju%0>suJm1CV_qb&)O>Kulds*TzE(qE6wi(u2Ww> z`OnQFnMl-ypyKui&x(hZ2;QCtmj6UTV23izVW73;CMFg1jPpBdixfQjQ?id$bS#il z&T!?8$MmkC~-<~7HCMMj0EJ}Qoo77U-37PWzpne7d~s4m_T zyU>-9w=F#*gXiT;6uLBx`@o4Ei%c4h4@-3)zzxU)?ALVlj$3?t>DmcJrLvCGWl3x$ zhc6k~Ot6f!%kQFsZ*&dg9^myA+8A)z(x*tnSTmUbbK{GiGv=0inns?GPYPi{P{Dc7 zn+s682wmwaB!8+;WLIOU{q?ZYmQv1`--2YLEoGb!l$0r20*B`X?~M|2LqQb za8h18yNxhpG6@fr`Rpa`E0pzLnzJ>UO2Uro31lr!)oUhpoDrw+u7V-Pq$9v{yV!Kw z5AULkH%cROgAoC&CERdO-Ptih z53@hqoG$SL5B+K9lkoZ8#b)N8&0&)N*uMFW3fV_S0bg|GFJ206^P9qH)df$l4r>aUVu?k&FIX^&?L6Fa*Y3Y&VL62)#c zy;j$wwQPBuVhzweGbwh|6+adg`Ph`#B;Z9Iv@NSH!H zifkV(+;51&L&lIqE?7NJm)E$a+YOqISwfuL|Gs#{mypn@{{nh8*ApCdhWMr2XldMyuBb3YKiUA-N#z@*aj3B>-&t#cgRRZstsP$X$?|YHROe}W#eXF!nJxi2HwiL5Mg(h!wq3#c3}&= zuNc)(*P(5%?ZRn_(*B|wg6l6L`6`6UU^&YeTfuvmevAb}*{ZoxAOUhes$LLq=HqD` z@E*PlPW&H#?Y_1K0Hs#PH|1v<|7YJmEXD$ug}8TJEo*)QtQXh_(+S&e$LN?C9KKuF zb2+it%eqW>=FUEXylD*ur+f*AO%U{W18)jgT^P$80n?-(jdzJ7A_1(QbDXg6`)GrV zAnz&>Tn>_DsJ~0u3M}*XMEI{7*6l~^lG|rb%pYe#2ntg*887u%X1RwNeotin%FEaP z4+NRryuX)uho+%WWCWFASC+~t{`KWG1$sgD>N?|zC3QT}8}*7lKP1jNv^)$M`zL*^nye7H6>DJ- zP`ul6opx$DYzk#6|5Rj)*ly~&bAhww4_YM^^o^sIO>_aRdU1S){IFY+GVS&MA_1^= z-s!Z&ddH*3mf41!{-L@2Tcr$m&Po{}t&WziW+|!W+y1xqZ?XDLZQ0fOJesu&jG2nS zEWOSlvhq-On7(4MEr1EWOlU5cvw(cop_Kz258{bTFj1F>CIOD})d*u6aY0Wzx*Nn( z0{p^ov)q)?Kw4!4;BT)|BI6n?=<#H!@n;t4J0HKSUJG?P#VY4&%R1>qDY?#YKDBQI zJTgn?NbR6zcK=<;y5sY)$Q!iJTp(B z?%t28xrTQ#m1&kN3wji=?1F~$D71I)HHQCTozp(Taj9x zVo)SD9bcOT)1z9b7;P%xu5XCQYow>C0-goHsCCChxw>DC@&8WS1>3r`;HBFxOP%f& zH%s{De3!PeXyw~X2kqLnTDfG}9;e776d;XYQai0BlKy7-pkzbru+%~VX^~F_*z15I zsSG9}At_NWwAcqc_1$i_?Uc$ITMR=}xBCY3sEXx{`>Lqgt~X?|97f}kVDzt!pWTz? zQ==Snc`xT%SH}NMpa&9t+c{A0hVH=1$ng9?lg`Q0c$6!~&MvR54A;$}<9m2625oj? z!<8Mz#m95$7Z$A^vh(mnsKw+9dbt9tpx*7N#i)!@+1y~nti?zcjL>ds`M3`Ul)(1H zl>ZM+R}~dk(=ET?4grEY1P?m61%kU<(4fNrVS>9ufZz^ca1ZY8Zo%C>xI5hQKisv> z%REk>KHYm))vf|N&gNW6`A^AiC#KGQ$}HXf*HU+LjD7E#t{gHK{##ynfVxQK2VgmJ&&gRRYG}I zoJH-dFBY<*j}78rB&f+NNLzl}*`W(H@_09Y(R9%tnV@qaJhy)d*vBWCWlf=X_}uD| z&)I!f^tMR?A$g(eXg*3wzP6i0iHg8coj7^0x+MYN4^^qKv&x3OrLOR zd{_OWDVMh~ShWp&O|gHE$`5z|^Ii;qqHdDKCp5bMfOIdPm>>7& zTb&-8=XLE6!WfGW0|QYSWlKc;|15ms__Kxi|2|>e9Zp+uhFIVsZhoBb-3=$0jfHE5 z<(Olt>J6_$zQq03;u-i0O2LDq%FH_(%=dwmSVw4*M>3$w%wqy7?0vt)Mk>6Yj4wiZ z-U3Mb-+06x=HEz-1@Ac~Ncmt@b}boNqE3bk=iX7|KB%cPi**pcP0WwiTEd|>dZZ}@ z;w_WneC5AyRz0j%3s6X>l@g{ZWbyb?3!KtwfX9}c*!-^C6&LX}Cm0eZDVeQO#pRYH zQYJP9>Z&DANcfqEfbU3{VN*A37A*$Y&VAdDIyr8#$@2BthNWcyb%O`G%2!RtLIf`LxXvdFD?|-{{X3-1mQnTS`OuD#i(;DRWDyQ1bCER&VN5zOYzXyIU})~d0z;!iodoyskDvWA ztqvos?nB2!zJ(zYUSul08YAbg#1Z@Q4{#L<4*IuW<>knN7hFzxT&Ym0_qdi>eAi>w zclStdxm4LMcBWOX>fRpsY{?co7kUu@aOP(8S9A{e(Eu!(J)M%jvGdURv=(7WG&(xU zp<6ly=8YLKpEG*#wni{Y{swkVh(lr~*xrt;LBdNM{*S$*bwR|%)FOafC?z#jycmm? zwzMNlZVQ3$j79@h$0TOGaH3Bd#oylGF~r}i@7vagV0BJ;EGk*?=~(fgO4bBL6XGfq zrVml+U%9OROLC5LF(mAm7QR7#hy6S|@GzAfn(Unswi=?chTwY+Qd~jk+%V}LJ!TYY zAgm;Z82*eMZ3y}Zo#NI!A+62m=7=2qI%4!B-COZt&VqxJn-l)vsGd(KN+PE-7vumA zy`F=E`|RKNAKxBb)B)%S1ADgdXq=BKA#3`?VQjYLU=&lMC77lPUlUEB)djs{nLY|G zL9t3P;&BGSCfFar{GDmJZtsx?FjD#9%!*=}_kB*_*;C``)Js>r9Vc)7eS2_XnDsQh zrPV;wzmj1oXwf{NmDT#G#YG0N1Z~;i0LI2^JHIrx1)o)pkm77jbR0&61o@(3IS#uR zg$}l9kad(wjoJSAmB%<^xT*jCs4>~&r5=2kl&~A$v!(Wj*M&e#z*(jfG_Mly&C)Av zn>`~-m1!Dg$HnnGBR(-ey-pE7q)~tn@B#1n3H%`IBMRXxY|WpmLp7$)T){4%!#%RE zBS)h48IYMyo+~%Prc;~KfTTcF#E-twT7+Aon5P-3BC&_j#_`iw385(EZfK*t*zY}; zfT^6KD1^HCI&SQM9wPGP$^K*HmuHsgI{|m{F?MIbh2>^D4s^|A0 zfEBc8j}yXT3@n_-cLf%zjQfZ6!bl-V)xGKJ36KwP zVx40x2O&|4>Z}9O1&1F9-4I~WV8e$DhNCcNLPf=BC2Eez8|S+@za}XM+${p5bp02g zphcW4!33y1MouQCuxBitvz2ieq+)Z#_eSe=1n@50+@v=0ee$uXGZl;^-a%xPlVyVL zYZfa)oYxepb~w1X6^ac`5phlcOAaNb{0x?GI4OKIviZ-}6mUZZBxL$Gw&Kl-)N>%Ee)=QZ zRhK;;9r-YvZ$mByN+?rwLZKeuPB+)BXQOL7-%*Cs_Dmb+-49!JKmUR(8IDpc%jXTN z95!vonM@Y#UCOlqraON$aL8GeD_<-6uXA!3UX9;p6#k1#{sOc2kMHWuOqO_k8Wfz1 zO-wYFD677xy7ppG8q46dpx5k8AsO({iPnxfdP!0x_Cm7Y*OU@+Zsz>;P?UU z(2ziBjgo0UU&6&anBF%C%Z-tM_5eLdcK(inpakPoFA^vruE+{ID>B2+a~)}XYSP#g{75}eTY^^ka$J=DOM%g?F&Q2^H41BxkbWwg}b_>PR0r zF3|AR;);qy{zilzIQW=Th{Qz0Ecr{*P7Di%T&;@)Vq}>vDv;Z^?xMjV0ryzV;_ma^L{hcd%yluOLrI@-8dfF9& z0OccIdC%=QxE9e4c`9j-%IEkLzh|5A&0_a-*Zc906)^WQZumHyp-%NN$mmx*GV#8+ zhAP=-%$Y2;P%l{i=+PEGb+V(%a;E-HKv@D!c#c$8P{ENwjTL*dz4`u?E%U~T@%4yr zXjN66PHKt@$YMA!6>a)iST0F+GOUMx%E z-`1Z;_gc@g)X_?{2Ls>~{tH*8mEis{s#vSWg$~zml-liL(EV3tzH?~bdY)7>w6qsG zcl(uu5!dZqpZxnCknC2%)Mp^lU{BxTgZ$9iRr$Pf0!x@Pp5i@uCcnYJ?LYbVh=!ms zHzg})=N>w==Lq%GNz6dY(y{v)jD~d=mS+0<$p~ck!`+^HpUzpGvmAZ4Kgt}`2w>c; z9c@>aPG?NeSmE*sFdbFNioSjqs}2B-?H%_m+{URU19Mv5&F#Gw~A*2}?sfinr8f)OMWUoKvq>`pqlR3)MwE{Qw z8t;OEqQ4%Xvw^#cY(P@27rEk%D%11SasM@k@=2;cpw79CQpg2&9bI-BpIE_3W8my@ z=h9uUjMtu8rezJ7)SR-fXVeOJTBfKsi!0E(^S4jY)iEJ;JoD|yYR($d5&2OFN4q>` zqIyvp@>$PYIsDLz zNIc;;_lU+7N@hTlU|l}-#mh6z;JWgW7yql^J9M(J(4G4Rc&PhW9NMOI^;McN_vd85YZ1`Rqme5$gZzI1gkR zA7;Pm9yNzpCsNSpothodwMDa#MM5jGDMK2@-wp4}gM&X_}j>=L&0K)gI_HaU?eQ$8%1mK%T$B zX}|=7&qJE=7W#y*|FyxAPWzkO!LOMA;^RqrdXjxnzA{P0<$(%X08peLHLtiE6cOa# zJ)|X<6ZFj@2qed-BLmz*s^bK+1%3~ZC69^PyR}T5Hi2}FFMIScFZOzcaQ`tRW2Wva zu-S`>7u$+KceZyTB>giVa#8RqW;-ht1;^MVM%^8Q5ij#Eo8N5N3H!4tmCS^YdT6DP zkjh8>379@|Z`bUM)Xf?hmlFei7V`xL%3oD;8LMGHC5W%%ajj-uHLt0bR%y1|KS^Zai6fi z`JCO}H@4FUp!(5;SCQXgEKa#cEBB0w_B_;Q8wJ;Qbc!(Sg^m)sSRF`PKHIRx3{QNJ zXUu0z;L=;^glu~n1~t~!$X0x;6`5ZjoI7bDCOtWSu9^Ooaf~CQGiNd~b3j*Mms>Us z&!uE$j%&tlCViVGF}*=^ExTk78#>fuPDB&CxpO3o)|NIPFE}lDvQ0A2^A8U(}Q8;Ye!z{^Lhn zReY{)h>2UJJay)FbC<|3pG%81-?8XSXcXloLgov%+p5*uVopazBDF2x{=Ybv(-a_@ z934Cx4U`c-AXZ2gBHwi9-X_-4`(%@L@7&h~Ts!#Yeyu>(n>{@|JP5|8dNyNnntld- z46kMy%0fg(G8ZF0$9qT0`@BOq;zvlt@p**Ge1QYwZyf6osGk=lc8}&q8h6{7;Zxib z?#Swy$N)AUcL`0yzdds)OYH$d?16JKKqz z*^8oCl@5yM%Qg!#-+xV!r&l29o}H2ZigG@u(aW>!a27Neie;H0I|28-(onZkddCCg zO%QB!e!;-EczRoPePPj&XZm-Y!h|w@pf?_cIt5l-Ro^}yj7}I5@o%l9*TD#`Up*B^ zT{AFr?r`CmL6P5XM=wMyq|=98ADnb*PxaB@B|I9`%s4Aam?&OYD}trKNf1mT-{V7Z zf!D)2p@@Qc935kRh~QuG4Q|&95^=Mr+1;40nYL9`6lzI@xxX5d#a;c> zk<+(?v8~I7rVzlovhIQeWAVKlN|zv!xruI$PrSSh_XmM@;>qUjVWcx*J?{in+;EtZR_qvw3`lWH6&UY71AHOR48n9>S{9{Z7!ZXU4y$|n-_Pj(Hox-=~{ zMSVv+NR{8Uf$hdV{Z1MVIuX3)Z5a$}>@AjnM0Tbe3r!IHFRmLzeyc5p#SCXK!4O3o z-f98{V=nU+&yx$EU2C#Xthxtn&%%~XXcPcBx8?I<$+WEAj+?k$p4c5j--XxdT5|-L z=)Qdb+xQJI0j)7;b%23JWT%5b|0qWsPiXS!$mzbUp0yRJ$6Dy+cPAwCw|^lhyub0Q zq}+OBlS-lnBC=01oTuE{<;WOnVbBKhiAQ1WLj{fQQ)Uf0NdeyO9#5DK|ia7pl3PdU6TEV@XGqD8gQ_H1ok_BcU+JxhU zu|sBBA&=3}*BEdL^@N7Bw5zhQX@@{{eHtr)PUcwIw46uY;t5!E~ah~!P zvJRn;+)UUigG{>#QOkIuwqyEHyNCjwV)wN-coc(7vt~$2R#H<{sow71QZFmskXTvC z?sZ415AN=C=r4sClr$350UL^=D38ynA#}d-bvn6f9hZ<83l5Fq&J%2UWf==NP(O9J z4xVyUHRJiSAI(JN?;(MIdZu%MeohQAjNt(}jDuHX6Htd2W>R}Sf->!R%NlY1qRFG1 zLuZBIR$!{L5f*9@{pOHWXXyeBk#VKicyw;f^06+sV^!ZFwvOCZ;%aKykGR2<0*38d`Mf2M@{gq zW~i4jO6^>&;4J-jA)W+gD7+E~MJ52XOdK2uj!Ig_E>o06eXW@Y@$etWTFzZeHJHGo zKbArfPorBHzpq)A=)k_}IU1zPv2hd}tYu?3f63-tW@|IT z&Yw9KRhKuoyD()NLHF7}Jc_!%I8xo|;Vo?I>b<-?lvR}Np^8$sb;VWvO&^4B4wi2d zNi}m%N+~}x`+&F@rC|@-$CnbfBwFy)mkYv~`R8nNBPbX5_hiZTPC|bSfx7dC)nK0F z>qx9Ai9stgHiD0>`q3c~STnU9l8Fky*3TMOi)855O4p%-k*GipRya_IlE(vGV8D7Z zXshgGVejbuw}kY);|fbI?s9tFJF>{PRSWe$YC15knE>+lAfGYn5p~;!*Iu*U^D5P$ z5&A%20o(T{(MIB)_BgT16n`%8`hM!W=CAu08;?9eAlaPPsJO)-tMIvnC?2O< z@-q#H4Q8e+UC|Hp#QOh&4@SS>XGg0tmi*%6lNm>IhhcyHZ6dQTHUTBGYK(F(2kbl3 z1w$*uJY?kLZ#{(^NedgeCRdNQ9_q{#oRs(}YD)|T89c{p`dCMBdq5Y8cmvRo2tQLI znRUJeeC&PyT@w;%T=5>0hU8?xGDJeQo)2$t?|JiOxH@k=ltJk%G%;++ zEdX_(ZYUmbmLq*uFMLfm7RSj>oFkr>m`909#AC-2eL{{ zP#C20f8xd~2R0e%t$F)}X6!z3frUz(?gUX&_4Cij8_YO5DfzH%{>F08BCaobNxjfk zTH3F2U3JTL<;ET3O^*8qH)N+PVX`^D7)Kc|FW7$htnT;g7;Ut4JWr1rrhNPRHM^ls z-=by$M-HDlPh{&q0sksD`~)dwUr6BCE^<&?nbjqkx;#=FMY*p7;#eg{p0L~18u0Dl zN-c~RQAxlELCZXsE*f_mfY5XOZKrar1BvBu7{pR|I1y=}s778bOC7b7r-Q6?a4HHn^@IbUkI z{^ItYZq~**2S^t4G>&IBy@0chgjHDbl3W*Y60I?WBP=g7WI7z(A;~&kk_*_SBzYgB z#o*nV3EC^--^fjiCXsJEiNf~D)e}{NHvK?lwS{)e{m|dpOk?F}ntDmV-l}YF4p$E+ zoln=*wn%5&xi3LLCnVHuZ2a7@Y;|~w`xO#>{`?qa+;dp2O$YtC?eV2>6!n8TNl`V~ z*SbT!I@bgXxwct4g=%>6@A)`DWpYIRDq1%O44SI_YVJ!bF!%KA-1_Fss3xDCAeb`- z7VZiH(G@s1cevs)57RK5+Bu#KTfAOR_zac_H9V|A*1PJ-FOO|MT8`raDw9yoQzFZh z+qi)=8sv&o(?#r|DfFKXeqJxpOzehV+An9}cX{gOvSwsC-f7)+m&4zR4-Ii(T&(0S z#|DG`vU{O=zeqKDy1G3Hk9ZB=Y<46k(Ur{&)o-D8rqR7Alglk+x;aI@TRfcM_idLe zEC0Fup`Mqrs;XVOW1Z5HH?vWw{K!;q)<81J;`+(kqm4ohKh}a+p9RPU2lRG2M()81 z$!r(a#T%=4yrl%pJgb&NM4>rc!lizKGsBa1qu+<&#d8<0!tM^TfS!INeR zCmX3!$*Z{M=TwZZTpy^##v-_C?Yt1aeqV=5-K$*hd+i6aKwG~GO@9ImOo*a~kbC zIA9$gB~=}NHZ3by($zByc;jUE{AC}K>`u^$@)8npH>nM=+Rx&T#~jE$!wP=#`N#^~ z=8l(k`PG*4NA}{sL|E^VR{8Kp?)$vPLe+;!k;bb#t?X8ot-l^8Uc9CHeg3 z%C3~<#Kh$KadmsGoNr6SHqyfB;SeL88s)MJL)t8|Ng9FLchX70hw57uiQVK)wIoFK zQ*08u0eURth4D>fzA~OEoI#NqIfkwJmLtwdjF2?rj!dIxm`erxHiEQ189-oIYo=`iug7(%3;~58VEo z25Y9a1xP>^(ng~vN#lW_m!fLPaG=bpu{747xndQbkQlSB=lhmKX}9&jLsCWn+c!(I zyeYKYf+)qA1Ms*yqI{|8+0NQ=uHEu)F<;o#{zOexRhQ@4C%ll&g+Meg5r2rk$b9ys zJ>Bz0}OqY6bT=gLI<&iGX^FJxr=CS$e#N|FMW<38W7I}GvKDmvG zcc!{NzTP{P(PvasoM7StaFnp9oOC8+#ZI~24Da@_wtxYCp^$i>6neJ?-wup&UR<&m zn>xFvJ~ZjE8MptmTOv~DBJLIS3Bu{!{Ex5Ei)Nw%Ek-?l|2@?^e*(Cd)w5jE6K^}k z7W`l!smiBl?pm+PF5O3u;!_?qs2dw+)h^rvlSe49^=)HjsAq3cIVVrEb7#XNO*Z#k z+2KRH5AlS^Ug&qP!RJ0i{fxaq>^ywMv3uabcqArexzn9Mh%5%{pJ0W6fx&**{)Ri2 zdy-nh$9g-_o0$1SrvoQJARZ(`Na4>P)@+{E+ofHrdu^Hb>fc(h>W?-&C^W7#FzS(= z_&n&K{wMb-GJ~5UEL-B(Bext3fd?FL`OY1TR;b`G8hqj9|kwBx&SMA~BVBUhZ5FE6; z;4~2#@WGc-wIqw`s*4yFopQ2!Pi%#sMeuv9w_-#^e1F;70-EZ=V5$D_0b%hKiYVc% zJt@b_g=l5?^+$2}?_rB>kMQ)*`LQLnO;?-nYtQiwy3H-MD(Mti+6_%k-XSCGifScn zls@;o*c2<&7|7O!a3m0!vMvs+f6+7MdeRm13?tQ>W#vad9xgw$Uu9(O{hNifzTBb# zV=u0-#dHyjfjV$~`lxZrc6a0zaD(>$K$y&uN$NG5)m6!Pm$a=y7JyAX!EL*LtZ)Vf zO~oYacFoUaQHs{xlnZ(xNCsN(xQNAEd#LgJDW7qmov5CK*yyGb#e;0i)M!aC=>2<{ z`YZSzA}HIsZXi0qC>o$$et(OM50+1&@7*++TD$&*BN6uzwZNGR(xHx(9$jCximMr- zjhipuoB2vTm-&jiv*;g<2PdeZk#~5|>Nl6h7!C+n8N)-6TvWb^IcH86JxI;)bws43 z%BbjER$j42uN>uB(bobFz#ch82w_NiqqAx(z94q?JHIfuOwr|BtX4Y z%meW}W!2NQt*%@!_Y~Ud3RF=YHUVjaNJ;_XHPwWeZk4G zBOC0T2rN6ibBwJa#}tMqzUVs zwz6P&MzAi!{$NgooFR~&<@3JmqeL@GDs50S(RB!!)fyk5a=;cU@2m2(?g!3cr zH#s~#N9%q5b)_vZ{oeSpX@~)DNnn)%%UonQT(Wtn)fd&%uB@%?9ZRR==4%-2?rwsg zAuZ`TSuN?c?*~x!?AO}1T+`F1ck|_|8%uShz*kIBlK zfzz>C1+~w(>DC!$Enls@;j`tfT~*7CEolF|bSbMP%-GarpW$ofV1v`JDtO9xz-dtk zc$S|ew4gF?y_4Qe{l z-Lxz{mBpge+uDdaO>}vaZ>y_9H|2Z70hu+-01C9cMkj<*f zO4*hde&9@{fbGZ9p{n6yE*Dp`(oS4?C!+Z^H6iZp5fEY2H#tLsPfk9yUqnVsTwX1P zo(L*VO#DqvFX&h;>{!ihAdk(bhJ){^=7`F!)k{LOPyqEr$*;IZF7}h5z^YGSTJfe2&w1$21e~;Kz2*C<%Sax+veK zeY^6}2|1MF(Ic*|Thfc*m-Org0LP%%yp*KAXQzn8#j_Z~k0@#nsfzl)VZ;(B!!$kU z%JfU)TM18;!dojhOa>j1APIy|*NI1}_$c$CKYUB$O;aT0xT;+hm}1qVYI##bIC1#_ zF=GD`*U8-bwqyOkeI4J5ir-7ay>tHvqFis6zi0C0nZ`)M>t`&+`!G$Ar$eF{BX9?< zWV;HJpKqN{mPI?{`Kvb@VWu{gtMGd>M$X?H`(mfaDHQ(T|MO2$3#< z(k)$@L^VzAQof#_Qww*%0pOEbhL?}nji%p8`HEDAp(^6?5j4@`PE_wy2@uDMdEJxD z7N5TE=Ybfj$pUBTAP#KY4ekogZc=Q>`-9Z}!z@Yx#T6GS;dEf-xPNhA#3;^z#ik&($VYkfN_)&+bd?3NQO@=vXa zkm|Yh$D(sk=5Iv57|G@uVsrXpiD+oi7w8Sp)8^{mH5)&Rnd)JUx!{%YM9zU!UYzn1Qj&r#T4Xn4`U3J>j=b*oWLQ_f(nQ{+*Sf*_ z5?RRGZ_3aYTza3*I)(-)eHAO_N!I|q<-Z$2z`Y$rg6Z{ERMh@s!i6jp*y;8wZmAFG zI*nIy$=GXpPYT{dVyH$N(9ubX`I#v} zDrC3O>Q&V&g+9=T^2)FNogbZCmBIet9a9k9x)od@stvDNYe$#&*=XW2|9q4^q({ZXw5J+}wNivVpwf+4!rCA;Lz8t+W)f(hfLfKIn+;yiPGI zw~b9*q6K#Ov4$~>&rhV-Aldlo2&G~)oTM7KJqXu-5?7&(6jhh~o%OwXW8aMl9hU_L~KxvrR{3luCml~G z=jPU-AbjvGtMM{F7r84Mj~X#!5es-s#mpTo0)1RR>*3=sEyPZEKgy7W!W(q({#jGx zC+qnk+nhc_Vzo?G#OnB*7RrqN3qIuWrIR+2*5J%RC4_nU`*D*!&>nL-IzF-BF^KqO zp%8aI5CfHrM? z|Bt6X!1rhQABXB7nK!Exv=V=pkG~1w^<_;<>+Rq*tyz7B6$)7`53DbDXx4O?Y9bSr zv4#s5wxr_TCIe@D_w_R<(#6d9DCF#`L7Toi{GW0xx3`xMUL9R4D`eshx|W)_A&Geg zNeX~`+lAG3xxc!k1Hb~DMW!s%`Ts%Rd@^%nn|@e$i6eei#YXw}&O)uas(SqKQqUqc zS00Z^DG%ECCcUs;u$r1~ZYu`wp0x3}y>1;%`Xy}#>~xSVNFwRx^KuZW4M9NqAGC8j zu0%2oibZ~2`?CDIpAPfLgH4VI_&?LlP@GV2jOhZ(TU85jl0?P2ug{5@PonNgrYDVg z=+rLydVJ@K5rh>+bnN&n5YpOZyMjXf_>x|t7|srCHIl+- zHGj@>1`2&GmSXhn&ce zm+LF-(8bPw<^qlm7w4w3di{QTTYVSAzljUFj++E5C&nh1|5dfuN-to?4ol0TGey4F z@~4@=@vBmK2k911DUc$=IzJjKTz|mNt?lLjI@rK-h^U;`*g7F9kY4dCw(O}{&s1iN>m z=I|7N;|oz?Vrq+m%FI_AYqDI|3zB6@)7_v?3CyTZOfM%XYnDF=7iQ9&Nlpa&IUv*= zpCY6IiM(y~9{@oLj21J>)rR~%bPB=!QEynsn`qIrtr4q^-*+C3^KF6Nf(WV3BSXJU znQR~^@Fy#_`+XL6&dy5Hi=FO7+^YYH@Q9wVzL_^TLn1XL>1z`udRJCMB;oHD#ivHb z5xAqDQxB=)feW08@%^t#9LJ#xfu>yR0>m@$H574C-%L43bQ)tgP(BuYX@hljmu>#ZA> zfqp=7y7zyw;SxHw=>*mh#^KAqru&9WOTrKiqHAIdBw;Ti(=^2Y938i7v>R+Af)yfI z4fM?+b`golr9grSSTI3Kg2S+|qb&sN$zLvZ$RGwsjWE$ODJ?69D;0`m;^{8~^%I|o zmt{J%cfJT9?OCq=lQj(n6gfcAX+dnEr=Ii#92ADBC@pFqP?VYR3PWfVni}~h9*o~e zpC>8bP~Qf`-bC7;GQMAE7{8I!S!Ptu=MOS`Qr`Xyi8LL?gSdV|j|90|6!T3s8;$YV zImf>3_~t(gy^Z^SiVdMYyg@c-5)|YHlG#V9O?OStZ1d(wZuH=^venj~1WFiXa;>be zQ0bK|*I9weu8!#vZrTkC*Kh(=ACi|XE{x3(G9Ao8r=LvwbkAM4Tx&}@QmHJd{8dg4Tw4wMV z4T-e)T3c9PUAK(!2>c zj?RI?c#ZAR7Ah-kx3uG}ad>{r=r)m$%4eIemu|TEvhLUO8pUy0lYqfsYu3`Bl16p= z+U`n|4X&EJ!0%kf5w%d{$p3o&`z}163f4&+k)whN0)^}L!;X6hSYV-kZ2hUFLoR9m zdE@QH+voI2?8~$(eOGVeUni$sgV6dq7eCv|8XlnS&cgpV;8LESZy0oR%f>~ z9l>z3v&=YP(Q;na4YEQ1?p*swts&qLf^NIX{~f-uVEB59J%?6%?u^0 zZ@BZqtl|pV!P5Vv;ZHuGC0RxxHmfq87 zilr-Z=gyPg3Iq=t1Y^t{1|6!vB-hA+v71LZj3E^2sulpn(O-YE*=$LI1cr$@XH2_? z7#NDX@-cm1;qOL#GH1pMT=Ubf;Z!RYvXBMG^u8YpGhMBU?*+P*rr70vTt(rqllz4z z6}=tX^6LeI<$}p_jqkI-HBx>i65ChlKo+52Mu)-O?GRB`7PD3#Xk4mMO3qqXQb!ZD zZS#({k4uScpsSV@qo?TC)!zQ3N7UGu(%f8q<)1j=XegO@nG4s4cRhehJN$ALxHjFu zcNdA}F4^7b?tKYwv~Cg z<4P+@A~%6zvG*P8$Tu6CS}rw2yzO-3!K<9K^t4)m41Ng|GWO5!(n-@>-@0UG0{mv{ zc$UhLF0#ZDA~QHBYSm{*oG(Fd1|_ls!7+)K5SX87J;yHuEi|XLsK?X0E)ez~v}6mp zN|~`kj?^m#_)yTux$xcLRAmyPDJ3ULY+5$@EwD4WKE;ESt4OT8G(5%!Yw+inDm***o*dbG8waB3k~J6f@VW);#w_HF@OPyA6L1Hh4rItZMVg7g#6yO1XqQRn z-X8sOI(&|_T&YE5BU*Iw0Q%8Nu=^g{DE9%TZu8a8vAWQEU_md$QF_NS+0pdUOnjAR zW2S$C^#Q8t3pOS+?%UFMEb@11I`_0d3OmE$tLiv=pKsgq`qPJGnyEy_9Gm>SQb_?~ z?e6)g$lFNHYd-si1cZc*4)*>s(G*opv%A|W_TSRzjbEqGQ8=Nk6bw@w2X?_dNqx}V z4|&<$mk9EGj9TQ^&Nx&`4wNhZuLWQ;3c1BMe;VV+2gy#UT`5u{lpjUa3b?NwJeADa zu!=NKXg*n6h-xJrI1*<6xjpY;#)ClOgb8)$+$t7@$5e$_si zAFJ|2u>EYac}=-AA=GZ!Tu*ywm;lj24|jkQP!3nj%RCA}>i!oKS3m@l7!F5`&}6iuzB^o8>4WLrYb+nVt`MNOg$;8Y(s^^E}m;nv{aJ> zjK;)3Ec;KQdXJUriv0MIF>utBVxn?C(#AaUaX;=>j-hU#b};-mml|U9#^BA8nMzj< z>d0K871>PPo+o*Jz4njUtEsGK zzqPu&erP}?Hk$t6HvrSPahaQ-X0UtSMX-cNJmSNK2*312w%Sy&z4*0!5ZRja@{ z!!L3&IH9yTE6h4Tk)#4FtVgqS zVea7#Zu9ELsouV-uWs$p+e?6uV&A>7Tmh!@ir*sMXUeP^V#>kCHvse=%gf8c`ubAE zL5qui#l`WijrbBAzEJ;%2=t(rn8;n{ZXd~Fv}#Q=BKiV5v4*yEpu-nIR?eNO9E^L- zCIy2~puaZ;G36nV2|py0*Qzk*=5PrJcFy-5B-5vF?>)9&(o~X!JE06G|1pGF2(7ex zVt*lNy*l+ARaDVH7yjozpja3=74G&|MhPyg>KhUL%V~c$+V=^PGLZXkTx{G<_*nn{ zK4COECZB&5iNi;m6Dl%dn~9yahIBvJtTre9bWz$n@NVm71Wizafl5Hn{r zlPIDz;OkIp8zHPzl`+)plBUW$P%YZy_ZBn}THdO43sX?m;;4$i!JV%Fkd-CG&# zO7g(*75p+~ypehiS1c8YpQh-Vxcjz$%4+J0i}}(Jgl3VaL811GQfhKN6m!!LJHhid zb=GzIJMQCCQ@9QGBHvtiO?=uz>@vMRn9MtWWf`06Cr}fk3**WWPv)9mIK3)Fu^^&% zhiyRXS@23&St??`_)yGvS398&2zA#g%TDokUr=D%-aazjcsRO|e@)U7Fkimyf?o*4 zsV3_;iQ_p4UYHQ4a+@pWTYjEA`hNcXd90)B@{)_v=lXs7J|{PK&+{=T>LY`HFKX5> zoY?uKe2<(hy99@$MVdQa&;p#H7N!GhrQ&bT2FCX1f9=CTF#({+D!`>o8lM5-hD08+ zqZTScjYHWQalc{cb}`b!%kW>QT7K0vLeN0{yoc_sxuK993Rn$)@_)bsAS96sH~kfY zUC0IO%Mq7KTjYFsZA!bVjX7^YM{)o}E@?uWCaZUEg!MH=5Xggh=V>WczxG|hrD;qf z)B(C#GJ%DH1R637#>DQcR#WZ1YF0L**1^6A!o`J!jqPYkQzC(@E6k;nc)pVN>Kr`W zeKVu@;5c=20RWM1svcj;MRpU1AHWPrwSng0&K*h@H31kr*l6o-ve4;(h382(!^)R~^EEIR zOd5Y%pdm{VsshG?ohMUA(za&t+UBqA&LHEp$bvT>oP|4-K|k;B%TzAlLR0(nmbjJj zOsVp#9F4oK|4aZ+R&r&vM|8f0cp1;7v%$N3OJy>o6%>>Iwa=U9rDKn_D{GhJ45dlh z#1|?zmx};F-}6x4&bm^a*a9iBU*{um^StgS%j*T$gDh2lIZ9(CACmlMPy zeN8@-#Tfl>397XN*^Gj5IayJ@Wa-O^;!BrbY2AdY!^jm`PmD@tDh`|?x=6!+dPv;S z^Cj_E068@4cQ1ZojHisx^iiI&EmZmbd7)l`?Dj6BXMCr4)Wz#xnO+`-o114a-`mb7 zij`IsT&V;hfC`--6wu~@L0G5aqFgCN@C9~J7!fK&VgTemkm)tN)h(=`Fw*+e6^d{} z|1p3gJPb+X()OFWD~)v|coDfAb-TOPPQDXW7{e2<2#GC{@|nB$rNyE1k7+S}q;y7? zi7$>mexIrqlpPpb@e1jUnIqwBkbS6lK^q;|47?D-;$m=^5BoH7#s==$@J{2-;lM99Nz`->#I?4(qtE#<@ zN#{G`6k9j1d}OIsr%>_WeP;irb0M zx-`nr*Y6!8kw^2^NNiA;$V;*kze^D4=OgtkDx<*36zs~ORZp{cvRVI&BEmN_a*9=% z6}R_>QS^=&Oow;K295m9R(W7~qL2iOFq{DWGTxjl6xHMBW5yty7|F`^@Jibtvs|l! z_keOplsmSNSUgu6Mxa}067@qO7$-nDvbaG|rQ<4SLds|lxt<#~G~6rBZ~wWp#;A<)0EwS)5=F8=oHn?2a; z{UAdE0s?SdLCLxmQM3qS_?9YrXj=~>5caI7q=Y90KR2h{+V#OfKe+nGJp5O z>8j`FhWYKsItT(xL6|60^E^l`&va^isasH7CAWyM`n7Um%bBpJWbVTu^3PO(>xT%F zw8{o9Q&}Xn(Jj0!dii4byC#NxT407D9M2M_-$s~)-#jU4`-fVP{CeE0Uk(`$9Ouu0 zqwi1zS`VtC%@-$;nQ~r^lly)?J$q+=u07-O9Td9he=Ml_w9SHHf4Vu+H*OY$zel&}fguY8Ug7BhwdH_kS^(=ySq~w20^-{yGua2;k~~W zYj-3Tf?SS-T)zywp?BKuaj`q9B8l10yT@8d?_BEG6P8$u>dXix{&SJYJ7V-XQ-^KtZi-^?tXTBw)cD5)2Dq` z9-H6e&dO$d>U8fC*3=Y-CF+H|e50$QBj8r6`8lnO2?LxESHu)*x^XYsY)E_p$sT-q z609%#;lyDADU15-Tl|qC`sPs71eFO}2ncWC)|4)9vbb462dgC%5y$M;0#%F?wwWGV zXEcRw`nH#-Zn~KsU(9ymfBMu9aM3T{-h^S}LjrsTR%`N(V#hs(U)s-}b5=kH7U?14 z|HQh8)$v*VRvPY>(NMKJabaO62LIYe2)ci!{`0Zrdp+%tSNrRwg(A^S>3XRC9{rR# z;k^v!N^MCoPm80NA33R;iL0=^N|S8Q5iEMY&+Q+CYC`=2BqJ9gPSz@+L_}E(#>1FX z`BK>9sM8t{!b6jAz$}T6VoL3QwNHh(YrDRFOGHhp+h)u==nlX&gpeIva{>&p5m&lq zExpSjJGRq$Qk?-0yWOETK?+UhaVBOfNvO+p5lA>yhYj5fBC1wZaiK#IH(;?a6zWL@ z>YbObgM>7xaGzx&b{W&7KRR|@vbl0|SF*929tECMQRua!aF)w*a^rDu<6+APR#ag9 z^nK)Wb#)ybACLK}jy_YU%4PV>=s;@qNWGJxC(##y7^x~Fh7t9?HNK2x zeMH_Uiy5K!7G60as|dBGBwiNo0-4>da9)zcCi4x z?o>B^wO~Py)QLTlUYecB*QlPzdW#QOF{;lreG3?_Nw}g--+ehW7d(rzTo0lN%g-gd zVoLhhqb^Z^)f$Kn>$!cFN|XV%y59EPM$dlbfACtwLZVXCs`!?K$$R_f9te!8_?&e` z!6?@1Uk@kQO#04&IrhXf0^M3SN3XOlLF&?GQq8xJmNmbWmUZ9QlT*HDzuy(c_grVM zzeroVOg5)!0QE=6z%47Ap-r5nU`EC=fc7ToS~meqQ>E$V%Y4Pw`A`~VfKFV*_%1S^ zYNF!scGZK4iLUxs%bzTTHYOtB&BzE&vZi`X`yU(2+sP&&WRrHjW_?Yrr5SsIn#=;w zJ9HTB2v_5DYO=gzMHp!-Ah`Rg8ww`2tM)i2WwXx2zHPs|{-|$jTdFQHJ9<)SqBr-O z-mR1A{!{nPKcVh}f5tE81h1>e31MYJ{twPQXKaE`K7_b_7Udh)_KB~%c`!#qiqDQM zLo;N9+_j*fs;W1HY^^Xs)CJ!93ckNuwmjI&xd{3#0~daV>oV`Rt;^CmHY)-AKIlq* z02ig~^DtEuPjbt5?6-Pt*n>oR1&xv?f;_euG4|xli@pog%a_6rra5VcC1X9-j4nIK zXSvge=UHdHF>x^Y3PHhYjfosD=q=Zrb!Mr<&E%by7F<1|is#W*E0J%Qtw6I>K3-eoNxr*8O5m4q-44V}cc~92qz8 z&H6+=R<`&oCKNF5nh%wcaI{5O$X%_(yJ==wwX3SLBOLLVQaJy2!_2?lKD2T#NWjLr zby~V3#}waOXq|=_Ad`uYjzs$HVu<A7nxoNA zk}cQ@n)U^kuZ~`K+9=Gf5-`3XjFPkTeFwnJ7=>+u!yOfU0<#WV2}HZy+4x zA>hTYx-W~E->SoK;p6E|(yfkb0l5fPEbtoFtK5!m6UNv7=2R`yp3|jQ&d(a|f8jks zBUBQWcMdOZi^J`n>#J!(dE`8Mx%Uz1`qft?Q@l?}x}w`00nYF;l5fz(4W+JNK?tt3 zYA&|oA$bJ+YxPY{nrZzfjS{-aGT8s+vHic)9csFaDzUKvnJeRhkrGPEAuS^)UH--T zrvS@u@A_3lN{IC{i0JUP5s^xk-^Dr=DAkFCblVt`G)#DMu_bexiswn6hgBOem$y;q zc|uv4qMn1&@#vM{tck8#_&KW*my>67)b=)z=)>Pg7FzA*JNibp-lIPC)%?Z#T^3A< zWYFQ}zJ8{mpq9KFK(7tfJ(c4XG1St`o9ceDC1MoE0z@4ENUO@(H%y`>>epgTvY6@) zhdQ$eEF9@dhTt<=V>)cP#IaGbk{Iv9Eld_nzW zMe&y~1V%Ba^TDi=w%}e3s1XaP^JgRs+R%Np=wmkI1!yHv+K$PU9^FQu>yB1c zoXVacci#uRSO!$;x6t;9Jf)xrDIjF5rs%(f??7lI8R!(NiHns2@*-+VfBj@7FQ-Cx!7YDPa#pxyjMXuLD=@^=D2+|`5bqu1{+0JZuLpy{Lr z&NoohZVBWsAJ%pV_g%VtGu{$FDlR*Hd=W3B4N{>5XTJQ>C#El$I_1WL+hi2}d@siw zM9VC$-D0{-u#A3^USV!M^EusinVXjI8XzrTwUmCEJk~RGPM+- zCrY%qRwkjAA<87=+G0xL%Mq&`eeZMUd=POWb4XbR#@%GmI>N4g7Y+3wRG3p3f(O99 zNNy^K<{i6~YH~}0gx(*GggYQ7k7uG-FVL`Kt83C%cYhS@#EZoa6d;>U*B3r*cUi~z z^nq-?Vu{>w*-?cdOcb$sdn#2|y8OE*V0IFFT}A77o%0bY6fm6s3e1Qd#;H->U3?1~ z8_QT}J%0n+tW8iQulP7?!}}lF{9jXzFGlI;H^AHJ^?1@kj2R{r+Cn}Ec0NSM61~Gt zo;8CAT7m_O*Q4YU?ItA79s}w@=cK)uu7xuS@s_PV7$BQy%Db<~0vw0+;^q1|hkopZ zMit8N$b-%RT?&9K1!GIA^_tXPmU~Vx<4JNH#g_6eQ@;KzRuT-shlCo}s1Xddhq8+- z&{%2CB3CIR!mnnRJdG0OcDUlHC8zh?$~7mwErbeHhs`=~6BOCMdfJC=VaI9{6PWP? z8WDn!?J4{@-jFceXjP=U2m^DDIz@)x(AXGoJ3iQNkOXdKxc`$R6GFFW&;%oRO3uf_f9B)&{NEcZkRLQ*w4ylnDku`3 z1*#RkdlcDj!vR*&b8RjPIWC2?YT*FK6fp}4?^E!}olf&7wXX&~*CNAQ;PXD3D8giV z@CsEeDtrd*(BMUlNIpl8N8s@2xbxi}e>bp}22>+m53@CZvuF6W`_=d5Aoe9(>@G-b z1I_pj-bwMTf`a^iPfAjqvA+KHEXzov9v>Q-XpF0WXTKiWX;@%7o1&YpAl6yv`oF`< zn}AOJwnFHShY#ot-lBl)N55mp_<7d&VsXMR292*=N3IKL26S%>^pS+8RIw>&MiE{mmy4rrGL|zkbO8 z>)69Uf((jLlAo2+l*9N-(HtYdRA)>UyfdZf`Zzu2K;4uZHFu)tq4mF2w9Z+}aG6xUUh;GSv{MzNeuMx}zX}IO5iTwIxbtTP{?8>TZZMcFe zjzTRSF5g5G!Cl>T!KPqMFh0iZ>ETdWix8cxSg?y5LJV9aw>hpr*+g$wf*Bsq#x^^q zYdb?bpa(&h>f-Eww{ep=UpE_?0?%kZDaKPEqao^3I>1p3K!KqeAp+;OESdV9~V6jLKi@1W^^>dxWp zGjRoF(r~D2DyB>sMEr6*9i*xqnin|FSnok6f6{i~jo|7V^7Ir!?uRECUdOz8x_I9? z*UEuz&3l9o>^Sjo&-ZM@=Zz)U*aGT&IGlS@7vs4OFgYr%ZypOx_4u-lOWNxcCOc*f z?1#goP-`jQFp2Z^5sN{$UvzJ-YWBWoYTVE4Fl(Y&8nk}rQ9v({rD8cq1z=nNxk-R!j&CxR z&dwNrd&k2Oz)_3?grmt`0sey~>(+(8xdXkwuYEB2-SE`&_iOw4eeO-1qw{unGj%3GmV?5}Fj;Dd z{^<-^rTu4V9PY9^)1?oQ;o3g%B5b$$D9q(d<6j?|+x9}IVT}fTrUSsb!*nU(XOW;q z%jmyC6Vtr$KFO?JDhu$g{q&bf2X+oIWBDxm>w>mw#pL3CXTYS1UqnCQDqDb~P)3fh z49CrFZ(*@SD?fU1fl+Pbn-UU2qNo_Hv8hd6^mUThM5v_u%qWeZGg{P=J!|#)Rz{c1 zD^GpcWMN&JI5MB{+}AVT?frj#mjsK&{*nCURhc2wQ+bZOrh!Xg+0K_T$IlsDyW8T# z^v`1yfZkr=Qb#Xq7xJ>ORcaXWf_jpc;x7VJ$8=?72r0_`H8F!H_jN|->HImEn&nocrU*>T@WpHJ9 zEQ*sN3M82|HF2U>VWE%Qm7={U)N$%&=>)~^KNIlruj}s@QFixVx2!W@ZV%NprNgAK z#x4&E8on;l1Np<|Ymj~Wt-CqSVz62Tzg4q^lOZA9E+*^QYOQ@(6d~o#qGfmZ@wn^m z@W-0YW~Ca!lY4%K02=nvi9gKXSPhkII-aF#a>Ct{g&0?px5bPu2Hjj$c;eaG5>n~K z!KS|}00sNDzz^BkOkfWYGC8=oV)QZBDomzb`lgJq5TD33D0u}}tIVDgao-s4Ogzs?`r zka>6H)h(n!x>9=k2gZ~~A3+J&k|u&|tG(arzpCzLC#s}}F6jHAXv75PGm0Od+s$Vw zvEU7cV9OQ70j&g5QR6}NC%5?;vv&HEB0;^AVN4^Yp~VK}@of9)!(fBX2QIw~5Nj6L zqq*G5uIwWYqE8#MR1yY2)VTZ*Ju-ZbR<*t+}@#g|hS;DLP&rK7g6UXxmvFQaJ!H ziyX>=A1^??jVB^+X@KL0_Z^B0Yvf=hEc%up_pf)ErQ>2oyY+red3s0drfBxU>tcvo z_~8H@w#fyYIQX;9+wmB`*-rQfT6rQ&BsV^OVoap3%LIt?*R5`c)Y;!IhzsqUc85tE zyF167yx2q9Z%cloWu|vqPOMqy|K>LEyo~~Ohuua(!PZ$w<)*K~ET!`m;urCsC?pi* zi9&$_e>__x3ft^9Ey9O~ojTa$52cw33m)**lGjaMh>^)AUzcT+r;6hJ{E3(pZs(b; zZ4M6BDkUXhtGw|Tyg5EBO%w`j<+As8AS(DWLdh4Igw=5%clMcAO8e z$4^^WAA+jpPSYOiK}>_8K#p!=A(PGDK6|00>{jda(J@voA)yJANlP#|+H-x?#JWqR z;)Jqdxde)vwT}XM;4f4s_9^E@r6vNlOUR5NRy@OBpfVBG#BS||<2fzXd>P-KkB#@k z#Ga_v@5epqDPP9MvT6*0mav;Y=8vAO!FmCyY^gQaY#3@-hQH*kGybAE6pJUN$*L{G zCw**#nV*>!azi%C3M}QPL}-Fd@MRnK9jmmxzhy0|WbY^SAM5;-N0G?vm;2fNaTGK7 zJ7ZvO4AIpTgNX%A1g_HMOMFO@`WC-lrGp#OFfPwixBtbf^X3!ef@V8Dj7__~rzF>% zFcGARpjw zrE0vt;_br8XjUkMSmE`(k3dOhY zVQgY@Y4ksk3?mb(i%WTjd4>{Nm!4Dvae30!Q+%|10BtSmC%FhFdkz++NuDvC$6TQ@ zEuLj=#AtmBFG6;{pI&uC4-etaUH-Vsvt+?I&odS}o1HwU(wNvl8i zr``8wkjEunBcBtDYU9`M03~s!7x@MsT~O^mQcmmI;cdZ3c@$QhzpVNq81yPQi3Fwf zREpdmZK;DCg00c?PKeW8tA^;?S8uFad_!TuO-;9uSKri(jDl5%0%-b^>p;20tV#1v zPqEDZIGzB)^Wlv=87B$G!pdK4MEdK{sB33SE5u;aU{_;w6H;2!j{Uu*S|tVYvxjz8 zDA%E5HL(0MB{FB^b�EW16cnDFP{e%*v{n0FiR=yMB$e77NBkp<^1s%brc=+9hJT z_@P&!VgwzepBMS7eW~N;`-ZwkONPss){KxupU$gLIY$)!m+gHsIYKaR9#(SGa|a{ zwxBbAVQ!2z&^h3MNu>}_b($W!glcvE-2YVy8b)AOhh(eeSZns0ByW2+4V~Bzu{jJO zc0bq@QFs5M8JXq3wSpt1qWHz={>qr6l;-k>5ga%0VTaTHb5khK(Ts6a9lIjWHXqJN zC`c-qZuewy$R0Inb-|Xr0TeYhHonP%r;Ai$+)IJMIBtv-!=Cy%G=EgFR%LMSfrD1< z_aZkMPlh|6kRehKwb+h!1Jr zUpsdDv8%d>2WzY~q%1P1|5ESQF!<=`+jCuUHnaR!^Mo$6uby?uK2{M6@sBOAIh%(Z zSG54B17tRAXR?_?H=<}+^e}*3R`unRU6@vdOnawzRrB{b_qNppQhx8NM;wS>qe`_p z(?f^VT8n-4-mpSdHljJoMIq%J2It)E08rkd5slUMNiD<6DJC z;IYdt`lHvIjn=rkgn$2{w+4>i^k$Ppd4Pp$9VatKVw+uHZ48R7L9!<DV5OU0baLp=(IyaiuNoft>@U1s;hLW1p0SbbbB zYxu~KV*wd%?w8Ry-*H1D@n5KtO@%SRkZlg05uTHb>~bRW*=F=~miUyg`((Qt#D zPGku4tp7Tov=p^%AK^hH(F0#iNPC>g3ZVcr0%*EqBseJ+0QSMWJA-Z+6$(n=cOGS6 zh;j8OwI$Hoj7K)u?>>fQ|NCny((@Rbk<*!;t0)^fnCmZ=E`B@Kzvu_#b{R$MI7@24 zGOka*C`#Ow^YnH9?W5~c;ltj~iM3Vo*Epz*e5a=6r1EE*@>)*tumj2)-Ejm1CQ#b%INq9Y3|G+NtogxG~G@M%z-~ZBB?e)f= z>UEHk8b0l?PO ztJ>w!JE)kM%^wi)bz_9-{D?~4R4GDD*F@Qx5I&H(!-br9-O4=vhUzoID%arj@Ip|7 zjF3HDg9+VGjzlFILap@yMh{q-n}jZSGrX57Z~hn;kvEX4hvz>ZM?L65I0x~)Zn7qB zgPtlgP{E!1a1?-3Gv5Lt#It7@f#Mz)VV)rvw|qBhJTfz()C)R&PEY0y?EO9rC|9L+m5CWwes-wgd*TJdA~XMDBLkJzxI1J|Sj9-dSMgo%QY zfO2Bc0&9jS8g?gx7IiD`TViW`dUV;z6OAsHx7qjT55w;xJxH~*B;+H3*?rdo-&Vw6 z1)Mogzt@E`qrxzM4YdLC>hT97AGFTqP`+%*Zoj0)dGq^~lCth+=Ha(4Xw&%T4=fw4 zzn52Hn~)~1i7>;w*2X7podgOQ-vwhYG>fEd!VkFArmG)IHOX03_426MvK$Ol1y4Hz zUOK5wBtFyDh!cU}XCkI(8wZSN@h?bDgWsW%xtuUtN5kE^PZYg?O%d3<6K~eGNG)kH zhZx&l3|D9i_*g{jcU`^pJIOHKAGWQz9MGS?JJRk_T6GOC*sK#y#*)(2x+ogFep-(O zN=R7T-rv6LL84f{3+m8kYEl+*q*aRKZBwBcw3p}p8ylHyOS|f@tB*KMrzqX0TeIIf zdJ42$OJ~XQ8O;TLpuoa8{+g$=NnitI zs9;LRK$!WGWHUrvZm#|=vQm6_W}R6>F#7Z*H3S>oCkR15u#t^ZNppzZLh$nCG_7}e zpDugT5)u7OR}+3tz zSbhV(;m&WgeN*2cF4nkM;lNWjDwK`Bw>w2>2RxyA823Gbk)-^bAhhQ{c)zcyn?0Cv zypismGPW#~bStP~IA*)_MfOs-4&5x$&V7GZs-i>Z(rM*A8b#mB1X!mhnn)fq$8ns} zRInTQzds*VJec@qdeN{P6v6X+C&WrNv3outtfHF?%!{!(j-qvbb_ISxf|p3&NllJE z@!Ia6=#>9%ZJ6+$P8-;U1J3{b)r^Xcho$#W=(oeDoI!PBYuwn_*(8@#^`~d7mw1bY zp$Y@7oT3>0g##ZzBP!q~2x2Qb8|w%I>}GHccV*|AW$8(55X&2cowbIv%L`hgc1OCF^ep@#?2rl1^f#n*$k=Hx~oR(cWSx$DbK_&*^Q?3g@f&uYZ?h3KIDH0lPIuifj-#=|7{Z=67#Qwv1W? zBzU>w>4?pksrbRe**g#gTZd-7{hLI^G43mNKNaU)_x=x9)NF>*S;p`aGQv*9F4-DL zM}KJ+2zH1Wqw1A7Uia4#5QV+E(zUd3A)B7msyM|V{O^7i+6!|RH6{=3iM~;wUiS%e zDOM)NlwfLJ$^Nr2cuUuD#}x`vGv1Za0KCY>vFx8O}qNRZ3bq^g)s@=U_73V(KCA7B+=pdC`t+8%{yQM(|IH}5z_)X_Lm!MCJQeQkT4EV(N+e`Z=U8KeR)$g#extPgPc_au&laP< zxjAForFRW&xv6fIxlF@$uJzx)x3bSTVBNTVI$O$0uD>;#UKH|Qw!D0dFGbO1k^%J0 z?~9{%HJyI%*KaF+`l*eHg{r;ZNlT8_cdT!2?mgD_S4rMq>G-Kspf-4EU}3pjczCGh zyhIZLD@&NcNi1PfI1xi~9*hL*5fp zBY|rJ;bTddO5r3wU@dA-r^Zjpp!O-2f64X#|qNO$Xovsx& zNfCOaFp%L<59;M9p9sgsl?MMUQi`I9;#A5I9vLW35R{Y)2IfV88~E#gxv=<MQb0&8!hwgWfTW`xO}(oL#n`bLL3)ed4MnWq4NY@P z3>$mEWO#*R&-Lv_gE8XF0%zRuBH(P9Tp%C>oMmeGh1MTA<#?Ol%In#}i&2em**$K| zX;$$9mV)loyYhO)UO-r`{?2#%+On_v^$sw4HtgcNAf%`c}ywfPdJ&@ng+ht1P&F42I!eYPmQK`-Vc_EmsjV3;ZB* zORh6a9Izwrrr7YtOg87{r{v&A&Ke6($~ZGkXN$J5RWDl@7Kda5+#G>O#*qYd+i9LG z1A}ktIgPuFMLK$VX4cjbMm2*?w(~=m;oO!-qvKk1CxBdoy?HRBd4`oBZlBo5-gBmn z6`@pEb<#NiIv|~FZyQvBp7@_`Ag8Qc+;q6_4zj)kQec7{7G;gkH`x87t?6-nJzW#g zDSz`f#1#$Li%Y(fNG=vwGY<~JUTz96Kpd>%dzM6j=7qyh2L0olu(!N1C2fkJaR zIOsorcBxno+P6NnaP@Zpb|H0Z*5D!Qz0DXBYz@h8j3I^w9ZUr^`$LMugV2^?`$vE5 zsO~{jKAj4iQHl$Ah@wBPUb9IQ^ww%0R;I|r%xQk-BZ&ciu>wEJ8ZCwh+0)V$NdIctS{$KwLup?}`nk2oC!c8b$2k z(m)0^-|-gsMqx!x;0CGUs8a_^9>arE0RpOND!xpp`kq&Ki#i8O6gtf9_a!2%mNC*! zeYJee7D*;sYyY--+2s%g%Q3$i-<}QzJ!zF%TjCA5}@(?VMfvf^AJH%kje{@jR`d&irXJt+Pg9> zn-hr8#wr)R`mpk3!()w016V-5UEm4d{+hUaxjq)Y-q{YXry|A>x4i(FJ9mvW5g@@bNm0q{;(tutsl7uYs*fH-%$V$5?-JU<}Za2riw3$O|QI3jjjk zY;eD`Qo1JT&#E7@C+{)71016QHSkhOirB_U%etvw*Z8!0mPASHda78l=M|ZO^UtaW^*FjTMxx!mG+L<(XcZKQ0Ve72ySC1#5`ECv2z6wp< z-rPD*q*~sV*?i81$2WT1o)$07lqV}x4)*T=HcOdNiu#AbR6Btvvkqrg1?<0fi^-OX z$rh=}f@+5G3d(e8HLOpW5YWF2;kx2il$*Tc;^8>f%4jeJ9 z8WBP}sU1x6MwojpZ3w2U|*b4W11aAUNCO82ss^s6=mviSm#Yovj>ApIs| zKNkGM^BbcoSu(BnJkiC!T|k4>m{MdD44A+JC&cNWpdMF5octfy9rz>tAu!al*4i*T zzw6@t)iqXJ&NmyfxWBIqVKU6UPrn8hdK@su=z@_>kT*VZ9GsS-!+B+oFrufm+q15# zrWSw{k0iv&N_?6}PNji(;_Lm_hzpi=xEbN5Uc@g_D^pbc>8pmbX9em6Z((cnur-UK z-#iB@e2bED0H&B!I#Y~$0+zyF*U>icI4_pFe0=`5L@b1_UY?`w{pXx3X23dS#Z%bn z_RvnKg1cE7dwgOnA@qfV^WY|;z|KbCnkD=TQj9i4`#k z>>S@}EsG+>@MBH}R>4)h%SS(+lV!E~LYm@T!TI7nqG}OUmFrk>=5y@P+~6*xKkPWL z^gk_tamx&ezx_C$=aat>uxkY<^|vU+O>>!$jZs>nWt+vNm&_FK&@bnVg|7_=Lgk3F zRF^@(=ktrrv=Mz$$NOA5reynQ7UKb0aSeb41LVKaW11VR(~*QSHk3Ew15IKYt#cqh zW*^xE9i}-{jkhdCCcreUzW}9XPdgy~OcS9^{mX1!Vfk5L59TS~(Hl9FO zj{l707udS(h}DRs^i)Jfng9s4hP~{5(}qaKr0Zf!WF#MyD+sfw`Lr<~9*VFv6_;*) zd03J|%g!s4{rLw=j6W;cwgkiwCfKgq1DXla4Xs|G zKkMvrvCZ<2+_0C~m8#}I(XvqhP-6H3xQNPjQf6rbWuRo@Pxlh{Z_Demmbir- zxU0oIQ3;;M$MSo#NQOf!i*dDam9~SE<*qHuT?Oy4&`Wn#)w`w9r_sBcW=FU3;3(tn zDDFDm_A z?c}n=Kx`YXcD`MdDKk)DJwGzv5pZ6-pehx(8uW~?ezbJ27xd>b0FHgmch+?-O3Fei zT~JFxQzmf7SP_rb0Fj5B4YIxt?QXmv|-C8R8j zqnClW5Y)Hlfn1;;(?u7j81q)UG=D9qe?IisOw#r!Q(8$Z56&Id6o^w~zOI^ajt7SB z{U0Q5k)So*0gOBc1;;=6?L({`nIyBMeq&Q3=FiKBzN(f^p*URju@0N9sC(WW$u+4F z=y=whv#@4d99mAMP$1coA!g5+^fl?Wa(q%lclMRn{Slte7FS#6l0{3xbx_So;wHBp zHA&*C3qY?r%<=QQR|pD;nKM~0D!4hP*~slWkjjVB zq9+dJmZ(R9M(*w>JjaQIdn+1sUsHonC6Wp_D*Qg8)EPmPQmL=ndD1XU?ADh{Z}9b1X$ql(Lgcs+xMT?w%X*-zupfeE}*qu<~_J?LEm z5A_K1d#-tRPqJ+ROnyGCvNP_9#_cZDp4*De<2sZE)Y^p>#9dmB#}xttrSM~ZhuXTjp%sG+o)}fAn_af0`D}NmGJII4 z@&$-a5f5sb50ywRYL!4RER+MAwF81BGrb#~`yd=jTdg!-h;t+HCHn?yIb=_hnZqWHaBW}Ofu zLL%7xPvyqj@pPYA-g<+{z zV8BO`-Cr?m9It<;dE@K0#V9HHk(p5en95RtCG*IyYGa$p8^Npbzh>L|-8<_>kE>{9 ziDde>F-oxEsr$+0X_xD<)~5@2x30CZNsmoV-YaG1cMkLIvXt(*{kbEVv(t7}UbajQ z?ZknQT$-v4Q>oyIzW%hFf(#_83J)9mzIMC3JVB}reNswtUivX>a%kT{P8D+)&_5l} z?4J)(?0%YfO?@%>Z5}JEq?-w%d{=~?AW#U@h9Cm*WcpUWXbT_HN*yf-`7bpcCWd6X z&g=I|BZcdWJ)dp3mUrGZ)w#9wq1hx|wOZ#X+0v~0b`M#wz^LAR`lEm18@tS(O62y~ zzv=eRdw3H^a-;Q43@LDi9J_BQikYm~n}B;nhwj?Qhn1PefsP=C;$)D*qb%S2_Ps(` zgsO~M@}EGGWN<@Un?m}aj(JdaqLLa^U@hxNnliM5(P>pbsIeNzIK=dSo^NLq9Bbat zP^B1xyqQG8hwrQlD4n08T*&9~HgE#(-~ zeZ;Byh%j-gg*~%C^+;M}&oAW7xZ?U5W31;GgU8N%mx z1$Nadxmu1Fw(EBvU++}K%$%Jm2J3$h^hVCn75EX3xJMu%1Va(sN#~tQXKmzo0JJ9I zbSHg;l<=#HS_G?`u9@DrKy8xHO>^(f87b>r(uv=f?%P5`P zZ&$tcm4{?2bs$0+n;=`Z=uW8#cg z*Q8Lf2hO%-ndf6i*b3Rv^15WE5CV;iaBZ;7EaM|We~D;__YrDj_v4#~0p28fv@T?<^b-SuIaEZQXBw8g(bT=;#rU*3^}Y;9-@nK~tG^arWVeFTVAg zVvkH9JzEn`u~83zY!f=F=UC(3AbYuE6)7b!n!T(D4}S(_8+TN=u3T{6J4qCnF40=| zUW$2Vzn-_hhUU%|&m7|ZAr*ceD)}cuIKmT-1he-qk}s%zs0Izqq*`X*yUnU+3_yQP zb)Llp*ZB_^p)f`Cz43cq3E-z2bR`Vbr@=CE8cCX};bj(dQhPfG1PwTj#mk!V#s*N4 zxdE9SY69hayVZ*LF;1OuV7(pdAKUZvYih|SYCEXKyMI4}g;j>@#TlJ9jBF-M%>Gc~ zMAz#x6KNEGlM99dKr~oc{MV$|em?-Lub)~RaEvrM+W1e{AJ@Qc;s_lXA+!LeDouY4 z4p8BZj&dt0%323oYO<{`L<_5)+xn!KorOxU7tgLi^np>LP%I>d(mCF9)AMB>3zBRj z)ypBfZh$Z%ZP0;IEbYT~)G$FcKB~wufO!XAUWAFKJkOO@k=OX2h5q9_G; z?0)Ze$(=uU2W(<*-@Y* z=1a_3jt{2qChn2{Yj;2*C$OCm1S5^zkcF4O)36-}`mQRE=={;CqJe7zhmHmX^8xdh zzfXo3?21f_I*UD6H;(*^7y&)?1~0oQ?3ZP#qJ~4EuUD3K4j%syau{;FGCeAWO4k=} zJ@TD`v8j`{6N)Hb@v7YAllzH6m5sj0LbunI_#TB~Ed3o5g(n7Z2R^yJ(z|S+C{?sM z#`r5HjiK4hX1^6jxd0W-rGHRlF;|#r4BuAU6~rsP;?u4(jHT^}*!^-T14-U~>psjS zrC`ogV53LyxvB8v#(?a-g4Wt6-`1TdzI~ZjCTjsE(e${ zO_@mBI`F@LffWELc*+U1Ma}l1=j<%u#%u|dfAg>QF-&S=<;C2yr7 z&t5UM4olPs*{KK!IlC@1wzE$HS9v)H5a#_f*OH9CAt@-|k3W{Oi-mpLfd7^A#B@>j ziP5-A^1OiX^ZJWBBkx78;J64M z6P?YUbxXL%HHKK=}zQZHjN{qGeMP zyhTi08({0t8U%mrwXku*^QHN>Ta-`xJ^yO>0nMNB| zK8(o9Tv6_p51Uy7IK85hTZa<%8?TiY@9FbA_(CJ1&}0l{R#cla#El~g4_vFZI1Z~_qujHqY4@6CB; z-DfwJW@;em$mZHbnY1d@{m;Iza2;)wOh@_6DT~{Z#49`GI9ot zK3C0g!(qa0)xu8Gk>{U5hF{G{?))!N3CDeq{J%hA(Q@;6>_83$>#-HR&yFkKDW6P$ zZ}_HIf&b$?cGYu*WQ$(vKoEnoB+&9;abR3MFsK0&xue@x*8E+B!@C#CIbUsrUtU`J zG?Z;{gcFjfxqipX;g|c2FEIb$UbvsFazF~C&+sQoSziE}u@J6hzbyFQZ!Pn|B0Y8e zo^_aiO%AN^Y9Y_y!92M1||8Q+!oY(!Qj>zBPwNXJI~t?lgH0D z9)KVO5(5p>9>$qp56kHk&~T206`rXpT_SC z!cLK7)F28dhC_Iy#q#OFsm%??RE_HNy6JwEX-`-qtd5ySdR>Ns)@D5=d22Qr_;0T* zGH7ZHh7rKnVX(S)+CvxZ+Jdf!n;(7}hnmLs7a*+H2#NM)*ph-Wjq@4b0Y*fx|D)-w zgQEKXE-s~X3%Hb|fJ-l3($W%2gGesj9n#(D(hUMjhom%uu)xwO-5}la-0yGZnYqIs z46`%9y`TGzb6$s3!)ENyU3juxCXYF1Q3_Bvg@#Q}e@shDJH})Ipp63XF2uHvA7E8n z``yob(;0iRh#Q;&8M*zluM%`61ndt^JYC3TC5^PA8=w@JtlW0#--KSUt9(j#Scm<| z800*)(Bp^t)vr&diZ^&tOupf?}>JU{iestI>whT3jL9aTVii(Q5ug_aE4b{+5b?1L% z{T3a$_dlu63)l@NR2t6CoFaraDGAv$BB!*nizDLuh9Or zWdA|>7y71WLB>wm3tDzQk{5Yoo-uNCBZFoR-Z}C~0~y=CSLbX>M9X7+qtM9gZvm_G zUQaFr?(oJPRfDmlkXRhbLI3!Ig#SW)s9f0cN#hRAm*N9@-d1-G4@&&w9$S4vF$2{i zSBfXfG|$D(4#&=?Mw6^G0`|SVmS^xtRFDeD5KjnDdP^d4Au5F7bWI05yImjQQ{+N0 zxTz40ELpPoE5Mc45vR1F0xvU2jb?r~&a$_nAll==&&=@=N}R}q<=@dQQZ7&j>E?>d z0gY*W)J-}K9HjlT(65q&>B?XV*dTIAGMvkC}!f?j7p z-$PV_>E#t=)6A`4pWu3!-2ff%(mPwdS%r*%HI4{=VU$OaySegs@V@dVkXB1In9qX! z@3AXAMTmeYXIuB#RJyo`8`~>dAH}?N)XN$3zArd+G3!5Q3nXsQ&4j+>N9x=V`alZx z*<;`(FHsXBVwt7be}2ZOZ3xlP52k%W|ACbISN%kJcjAX~ghu`@Ict|y)zLu;%~0Ow z3@hY-UbV`l;^<(81ERnXIj#{R9^^{|ro61keXiI#9FDNLNRKs{vR2g%~h#^>?HE$Mi%-{Imnn1H!} z=V|-tX7%=GFu~c|T;C`_8!&f}VCJzxAFHwdGsG?*nkDQbA)AxGcem-iqN9^PG*TG> ziTpYV7sn5$D2W6!mRK%l$M$6rN-?OBggqMK_Li{l0O^S1i~a7RL2@>eUw^w~ZF?zK zIW?$SPAXrBh&90t2J2KNiy9D85kK0F3JD=(b4S-!fc-X@V2MC6X@FaoSe?{^rt}fL z8DE2S9hC}Ex_WXxUG1MLinzTQlo(rIr*E=DT0tTTBl;I~`Zk~IqycCC_B3rrl*vAX zJX0qu2)uo!UtJGSoz~A5Rs!>}T$f)XT#7V?3f`fF!5JWUBXwM4+Pl|axWSJY8*9Nd zCw&96P{Q+Qe1br@jje;5u5rM#ud1bgs{dKLzg&anFx~wwb<$HA-ZiMI?8U=tTrRnZ ze)<|ka`8qY=xS|{`)NxeTq@1BbW!pxG4VcsK@*A)MeY-ov&)Oy2ZFpI$tdT0H?@8g z^M65e{}&H&Y7jnpbX*%RFzW`y|KlD##erTV|!7iOQ0_8ZCB%s4#$HS&G6eL31U6%2EsZvyMT}B?Kv zdkU`F1jU9BH!KonJI(+2;5Br=SUa!9WC-)bPP@;Z)EGyQb-~iz*7#_Qy;kS zCqG${f12R%#i~QSMUp43KE7xu6%V}X3s*oUR2_+%=n%>#>5WPvNrSs1wu(W8CSe=a zI!%&kiXfFt(YIAB>`DxrjBuO89gJ4EN>ZP!EUpApPSsIfQrgaep3_jO!;MJ%u8$qB z3XS3zckV~4l1p*uxO-r2#C0k;(fdB>`24FaYBR6E17Sdq%biMAnL@8Xd?q>wIAYxn zH<47lq}p>F^g|=0w)R=dOK}$Kcf~3XcUcb{C`Meg#WtYqBaRsr77Kx36TK;YC4*LP zJVb4cG6~(gS%@uCMo}SWhl(ZW2O2=dzMMH_78L01s4HU(3EN0r$gYEvk?5rywampu zYeYHDnL_6Jxxn6SA{3uqwP_@MmpV0;BcP(D$OZSuReeJx0efu3QiCHo22f-1~lsBAfWbxYvFEc z%wjIQ=uZ`{?AH9`E#8+PiH9|U+dnTPbe>wy>7ODDGd%@gM=|{Npm=_vnqY|)_jD|M zfGf=qQ}C<*9`WSszM!t26%_AJc-y07wKGO<96)lk7XEIwo5YGByRe8;<=$l#N}lFa zmd#3NsaCim9{tem62reJL+eY7FgEp?AB2q71!`d%&c3?1pQ7Y9p-9>hN-M7aF+bSI z-owJILb8t+e{?hg=HQRmpfDsy4;*!*(5yb0z_t!lNP7S9lLmQ?o>rW^L)`26gp)zC zRFM#&d0=(D9DdaX;P&i8$Eu1Rr_)5ivohs$WnX{Y{%lg8tbn!>R7j1y*X|d|t(Byx?1o7FjfB9q5{k2hf(5uJYvEfLS^hx1w)+HmEB9H8)1MUv^UmRPW-;pW6R6Wn%-1G+%f{gx{ z>XMZ}{|6ZG-Fj=hroVberUn$-CKU7`dCM#2+;bu(q+W741D=h&$?AB9g=@Nfg*4h6 zOkj3)lOHGmR1?Nr0!=d46)IT0HbB;KRhhTzC0C8w;NBZjX%2d(tAwUt0D8f_=TOnU z%Y8;5a2b`A2{p8YG9>uFo7Vg7nQ}p-Gf0#4?@oYt+mYHic)vbZGGMEe<@UAjF8A;1 zhuH+?l+oU0_d`}<#Fv|?H{2^N5zS439{Y#CWqtMJkyHY;$bVN#BO|;QrJ@KSzdLcj ztj&d62VqjsRL!p2b8X%5W7#@VqLch{cC~0{9T=-2{AiNf-!I%T79lqxC!au`q}R(l z;%vLvH;xgih2E(G+tNwnKHcDyE>kVj0saG!O?~pj>UPD`qpral&VR4K7|pIcCVBv7 z?lmOgF7qeI3S@1LXG@t_QsyT|rlGXMhz-weCk0~DMIhKuUL9k8bkBC@ zF2WHLDl~6c6ssz!e#WzR2}zRqym+D(XiM?D@E@T=+{24}s7xWsXmO#zrA2;&bAlLlv#Bh`OBR{!BwRJ;Yu9x%7uL%%vNF^-V&p-Iv~5$* zQex26*)N~_!1b#pAbRBh-Gewq!)$jd%h`CiF2=iKtW^Ax_1{hWQ-)f=9dfsI>}rM# z&ev9u!_18>WE$^IL8bX3bz;6VZciS}UacCXC_PIQ9>TdF_G^6@)Ke4jTr9>z_cMX; zA{fp=8221p35k#+swmAg@IJCr&DJj*dKqS3)8PK_H~%p~aormTCi{C?eGsy?(tiU< zza?F@xCnj1IRCaPCDAy{h&dM2R+acZDNEH-raE2o90ZZL`t?c}s6~O)n|xMaP@A(; zOlUm&28lhl^C;#Y`+W@%nOi^K_Nqs6u`(STSOR`YDqwE`3azaAadH2s-~ymzP9H%> z*>oB&GfMtk&hkUqr*^MB9H~eKYk_fzTrZP~i|t^alWS5--n_E{GRfV1QCOF`7VOt! zF4oE@ zE9L2b!fl^*%;!>S>@pd%C8l-Fxxv-k)Rpyp__Om!y2C>&TibSt=fD_3ee(+(BTy7! z1#TSfXST^Ph$WW7bZ=hJxjMZd{?K}Qv7nDh=lPI-?{&sN3(R2w#6+*r&X`gyjkH2! zN`E3Uhos%34E^t&6D-ms;60Uvd=xkijSjulB&m-mt>k9O;fXBwDI0Otqvj7_4EJeW z)*gh+(w1vQ&aqagi&8eFdatjs>i~Uet{G(Fk{L)J;=d9!>Kcl8DR8Zt3;?XkvV9n|<>6t+(3&q^Fm9+W z$)jY}il?g~YGh?-ddB%TaeKlL{pC(d_dLan+MKEK(2 z(zxCO4eQ1V=$iQ%(w%$x>qt5$5HU8;uapkuI{4dY{L$$eTNIQVohJ zdyRGs$#;MT(ka5`x3hVD1F6yC@oA_w>R)OSdBt_f@Wgx~h@OBUA8dOThpvX2+!Pus zRgd{XtZ3LmW=-DV>uZFwZE2CMiVb81=i(m70A)|n@ZF%SKRJaUdeS=qj)<54POBSL z=+#(+RZ)GXe-1znzU4^O*uYU$pya_db#9~Bi7jL0aLn1^C5?dsal4L!S)!%Z&q|{+ zfgk0?Dt}#^_3$PnW0(Is6!Y-t#YYl|O569QQfol}oTX=+8zRD1{2rN7zeAI^dXlbH z31*0*_gyVmJTlP*fb~v$M>L~p2%BodQlsm4tVxjK3CBG*c?gUnEMI-|gM&_=df*0# zA}nv{CEPM?-BmMpyiAQk$K&;#*c8G@_BqO(A9>yu?PHed&(ndl6)!3E7;;I{@dJAQ zzlMED+=x;Z}t~ClCm1Hi!!6m*QuO;MdgVNYANYs(tiq$** z>dFUPMNO^qrnv74_rlb=5~$Q8iCs5l9>zR+QQ`1|KK1u5&?9$;VKJO#uHn_sr@N~^ zpS>>#vC3G{s&pd!U29$mu#}YumW1$n|GYqm4fZ#4ZnWTE8ww(xt{W|Hhvda$c7z4f zC_FEw!hvxb|a3 z$J7-92<7RF9_0?h&WjB~V+oq3y_kvo8b%N~ON(Ga9HBrS>@d z2FhCO6-If1g$i z26HM$^<0BYGByNPR9IDS$-CY&&=AXFgb&Fbzb}Gz+lyHGZTt>gEiQrbYCdDpuK&LH z5yij$`4?ahJYmbPt_X}%Tj2nK{x%uwx1?nAzEC`{FrO29@YtaoiQNSBXc z+6Rm7ujt8#??%%%TADHY=c=Uz+SLMLM7p}Vl8V2|FJpf}b`C@DU&YGVX1N1j0bgJT z9C>nGYZuKDwd<}aI=g<<>|q7*O=2lz`C{#s>n~9>?+oNY8j?@#^RKa#erkRe`R-3E zGxXCR!EG}buj!yqkn{)U>5=BulAD7r$vONxv}gK;Mir{IYpImtrk2T@ke`6f!} z;ob2|T$CMBZJ$}Pft?E)ed!4p2nwPy zr$fPDY4Ob-(-F)gddDW;{PSzNbnOqVfgc1~alCRytVrt`T-%Aqul?2`{SDhXr{j29 zX?Z1Z>SkUHpE=6W(LJ^Ggv;~6*|8s;BY7fujlRApSIgMCq?n_kYq~3PL-d2=JNlsz zV0opUF^Y-p@SMBz4=7Egtz+cG|Cslo)ZtOgEAhOL+`q@+VV_gY8O3&Xhx2Je;I?Nc zAYI)dSqB24rlxsF%lrQp~^jm|fp z99x;k*@Hz@<`&wcj;4V$m=?H5e!=F3K~z+s(Q-T?KtTa&!sRgz^#Jmy;5XJ@WJn!B zn21ls=Zv5ee}WZXmlN^u7F%ZjrzapALs?%wfR-0xkHKMdSl8YK|y3Azv1PCal z^-7k_u^X7{g8k>z1uV?5FE7IoSE}*F#bi!d`3J(1f07wrHR?S}dAkARC<(@$`UTXj z8=L1-&AdJ)4?(o?*yxhQ%9&1jKI4tk`l&*hxEHxF`oCD|nwFZKZxYVN@XI=RanMD)?oI*PHNZq(p*(@C}ps{#JS$1SB5p zPrJ<0Rjpb&GOQR}l$+-R%CSr;5ehWsj}9we`@sxlJ{64?9hq?T%Ni*@USXDjmK`Uo z4|2Y1i~aWl@tPwG?c8cKANtL;$)lX_6QR7X|Kh0?yU0ZocEK89m##Esqy`B0xz*|u z|5>@Q^t`|fuB=hs!9XoD$<_w?b`}noqQd4I|3)z6sr2bpO9$&*;R*nIj-UAs1?@Ry zRSeL5S)6ruG>^x_`ijtb# zlW8#u?(d%z7C^WZIB~5)$lGA3hsVdjb4!RWY>Bv?YZ9LkV}Yb%C^x@t-dzfm&sw+NZYOvz%PUgE5~q>rx!z0fUxK7kLR~umv^NiU z1g0zn0N$1amY*$GVwPFyeq0l;nipgX?)lHI{0%Dgy`;rkwNdRvK8X?V|445Hbwoy# zKn3G?H~RP=I|iLZy=Z}s18=rr+&$o&uY>wyFy!$rIdVvcydY(LsvIw>;LpXL#yv2z z+8Go3`I+mpQ*DvqmRH;frE9Agc!Zvs(SYU>3i0#5s<#0*Sj#w}E2=wq;@;6!g?<%9 z5L!WC_)aMsx6B%8t~9fJLv^UgCHeVpyx40q($bChLjm4Iwf@+AR0WghCS%RqUTH`J z>%@UqVeX!5Z$kh=$e4sTwhH-cHoKr8E}8Z#wxy@n>xV*9oiQx4ZY@pIYZrTznX`%x(p`=T99>yzjNbw-OP>2P$s z;Hj86YR=B2Efoi8oByM5m==jiJuqHM`?7HCL&5|;EuUtnc9|GxezRDi(o*k(0cH&zKpY>q0k!SMZ7Bv{6q>Y{hItd z(4P#tgx?8(Y;99wLo}k+9N(vz1G!@6y2-1>i$~5|ld>@OXqO$|N8 zpjvTDJzBkr_@@t1coRiKOq8W)lMT;EVcR6JJY?xW1YgE*kc&rY_z|dKkth#nHQL&w z)6(=VycrB;0Z{2WOYyvQiY{?l=+3>2x=i6jMnvCRwwVTMyT&5{X(2-_=2fICiN-{+ zeG~SH;FuYz_8u8q)qB3v7G07Q^H+rvyJ2!>3s@s=%V_1g)8{}`BSq;n8VNav;jF{W z;q-~vH`2N{GPyaJe3@0>p2JzN`T043(D#t2mxJ7+C8M9YesZA$&CizNd-lISntnvv zy~51rrZ}!?&@%OCR_oXXYaCSHT%v#ha-Y;6h>Xs?wsZih;I*QK#wGc0YeC#*4144@c*0YTaB!txnPm zC<$9aIR{IQ|8RQ~SfZHkHLE^leggQA=Mh4O{Fp1<@$S$3pEgdkl!m z--q+RlS=iAdi*2-nD0ns!JM-!*j|I0*+6jPveDQ^d^MU6Nu;#~kdRh1u8d5n(B^bL zmZDy5c2EhE`q&rVh>-(n(x;c6`d<+l-Y!I?f&1UCjh^J zs5nu-_`#{rcIUr6A7D7!@3!pJdTdL=qhhiUZ%vF+k8B%`Yi>QslPe<5Qag|Vdap?z ztwp!-Q{##5?|br>OW(07`j(KZ-LAdr%PS}RjKyYdM^nlqWU@pD2gTG5x4NGJb)q1D z@V^9A_0O+_0US^7nRBpz06B81)-Ky5pl@9x)|E70gbZ$()R!cOEE!^gG1u4ygE>QY z`{$Ip3ceiqxucZJ{6oeQ$p&5}#;4rkmtbu_(`PzGyLKlpKwFoP5ht1R-KR3~^C2@}HZ`8M-Q zRc-$LW>4QK{;Xm{bMxOTb$c`Q*XELGA*5bWCUX>Nq2|;p8B5qYVRFQHUPn9CHGt^0 zq7kxj(?F}JNQkO33x$AyBvT`w%ov3%smzYiWP((*m8w$ui74GENSzY~9ifXq?+Pe)N~Y);gI&sDjp7%y6r>Mao} z$I%5=Qn6erE*j6`!lZ?>sb|!t%cku)OPho}(onaZCES+lbZ|<7D8#zJSpyvK_vLeQ zWr;h)D(8tBi6ug%2r%*_hA>PuaVJJ@)=@0_Y7D+t$i+pdQTh_6*f{yEzc&#@sH!~&4Y^SCYkcF9}Q z&WgoYWz*C>Ty%f!P*-ISLjI0+$$~lZ{Pwj8Eoas;#*i?0qPdV1)ngyv@HW!>GYmxE zE=sWw#`J!rqP#4YcqeEt)H6q(l5Qy!xRb=Vx9L&Vx$&4`53^kq&r1}hP*l*eAv(jI zwtWp~aqVVmU~m-!wD_R^xZT8%?M!7rEg#S<-{E$$1x~pSi~~Ezb=2qnNt09*5~x6C zygAiVR2XgiFOPJ+7}#FAeha7dj}TNGzdS1{hYCB}zD&1dEg^icR0{}P;o1x(H~Q&9 z?SGH#iYvz|01imQO`$j&Vu;NYIS5b>$n+-oH>(LoM96XL>Ya^j6V*Kx6eJLj);cIU zlqJM@x6IhCyQTF_!J+{TIwUe8%x@CH$V=^t?5R7{hmCd8HkF%Z3d;)Sl`^VUx&7H; zIm>Ei84r0EL+#_;!I8Hy4bv$Zdt2S$G|&{Po-%HA)37L(mIiYbk>1Bk7gQY&`RQiY z+95t_k*!*)R`H69V!$&;MV<6L>#1nCe}GK=tML=&DbTh~-&w<8hH zN5&B!CJh=Dxi_m!S)bhE*g=Se9C)!5M-*7~tTuyfdP=nwPq#B2YMd5;`ByzSSV_GwA&irn`Gj}(XlRB_0di>f zkJTI98h+h3ZU@%4v}_wZ8>TnONYetUKvfM;tgx*5wv#8IJ7T=)l$iK(So)+wzLL7V zk@xN=6j%iM(XL)wmXH9Pr@3_+tt=Hag;kHE+tt zGsokPiwWY{XWGs;E>g-Mt-FqP{7lPF3Hs3q;!| zCKi$PTNyvlFHlx9;G(Ui^S2F3zS_6qK@`t&;TB9J5Io(Xu`nuTyrxgVeTQ6&o&8Wz zI-C{xh~UF}9^8%F0UuTX2HI!Kv}V`|%SDk(1a!l{Vjh-|y8)Ni&menaq9v;V0TgH& zitf#=4WDM>eJhiQXFYcCD{;cLR*;0>|doo9LhKmA=w;TPAPg>8~-c_ zg8%BWO}=wAI}EI3#qNb3D|Vbg>Ddw}pGbZo;wQXlm&C#pNemf%Cot;6hH8XTvPDRh zpGtv$mqOmtk!+d+#MmiUeS}}>HbtAaz1JngyAOH9|7M;ZxnFXb4O0o%Hd45qh_{GtF7+Ziy?^r7xDbRZ z87=n1Juo;@olY%o~49Ak*m!@Io_T|)1MCnRc}S^ zHGi<%*r3R&Tfd7cDB{f)A?Kp#tE|4q4QJJebEJ~24#1eL-3=Gg2WFW&rvsGcg_(Uq zUMQm$vE8o$Ie~i28}m-ugc8=y6SXLNfUz~$^A8;PoeRd1u>A`a7-)T}a0`}{V(P1& zOeL^>{{0#bOW2buv6d=e5gr#(`VW(uT&~o3^wH(xJi%%u)_0>q>!1=ox{oCM>@oxc z{O#RyoqG2AxB>ro>*U3iHy-E*xG5v8eI#Q`0d^CDXDLq=P~7+QRTK{uxQZ68O19t8 z>*Z*I8|Dz42^y1DQ*U-!uv6vaNs7OX{99dws6Ze^TDy1Z$ygZhcs*TNj_N#=U!Bu7 zgI)m{1PY{@#%1|tDDtEaimYeKNyQlFmC<`8s#F6vmp&&3={v9BioRpFAemC5Z(a(_G*AQw>tG|ysIhH0SfrB)D zfTHg;)z!(qa-=hcA`!&50ZnkHH6N*GKcQ#Oy^Ftld`OJ{&Uj>te7ne zDSqJ>Kc=&(J@KOR@n}B!x5Jr0r89NsgE>W)JC%Gf<-}xm=GP8noQ|$x_Cq$~FUATw z%pe6#x1$9A8~$t9#CGTNDxj}WoqeA~rSerPp+qP; znxl6Gb9VauWYBUp2i)Q8s(&OSEOb1776-`9oUl(HjVReGg347)Ge#vjwKnnPf00#( z5Y1|1+)2KzLt=P_dX;gv{+E{XX4Gr?LJQTCbt|7FG0OWRADyhaG7JVD0rEDAi;K}# zeITGj^Z8AekGX|+F~BZhK^Zzyib?)4nBh)VY zjcHWZLg~cj50_-P-erPPsqIDccGD2KwTLahSw$5jzU%Xf*CBZ<@(wP(Ae3J5h32Q{ zQ-bNCy4H&-ODPUQwu2^fl#_bm!rxkPu>d~GZQlYkMK#BxT5{HP64JTD%;P}}(6MOn zp%4P`>Z8Hh?*>dvy++|C)zZt2k#f>ziHNMj|CXN~-(-n+q!Eby6CB0J zbsT4iJ?R91`y@fF(Z(Wo=ted(WqdYfP&rGV^cB@~u#&=nsNpi#wjy!+V%}E+sgn6{ zVP}AZ2MR@R>_~_g@CO~Ti|ajO|)+@b3Z_) z&vC#U>?)wBZpWd?$@NXtZ;ZcUaN?jaiZCZ+vWfYKE|x;Yx-P3*p4&Qv4F&LW>?_}E z0rQ$N%bY+xJLeNC(n;Hu`M3J|`e-?x>ubMOQ*Yc`hxRYMT}5WSHYZZA*$Mv|$zO`8 z>0@g*AElNn4JztZ!r^Ja92a|nF%BrA^cbU@^PUy+QrMHAlLbq9P`$HszCD_?V&~tz zW^f(tabmxFB*Lj8b4p5s2p||#h=aWSCe5@K2>v^T5bFHxTopK{0}ZW(*iEl7-zS+B z9F>)@f20|8{WR#W#UWQCfPunXoo@bW)Z)D4;(L^8V@u2L)VHh-?R6sqp?9^FITg&{ zSRTPIk4y*>P&A+IV(E`fhCX~*fB*IgqNOLUVJD&pN@fy8*8N6M?;7T+gwan}$-$;< zpgonF@7t6ENgv9APj&ZiNSYr1DKps&o`M|It;gPvd|*Zjqugxy^7fi3?P<0E-==XK1@O;e5929G~wI;JEry^`V`ciSLWtYI&f*_+8% z=zq3+#ox)R&$#3DLs77LMrIZ-XaH5xG*A#kgm<6!)7emYL{cC|pC4=CJT3jgqj~qb z4a`}+{sIMvz^j;MKISW&unH4KF-LJG3>S?vl`EVmdOh#Z%gUnNZhz(H-e%a;gdT7% zP``e_dCJ#=_(u@I0^1b}`Uz-FC#{ygtw{t+0s+30Mdhf>Kk#140Xy|$x3L_X90;)o z%T-d}HHT=NJ`J*QVdYe(LYpMf`AJKowi6h}0iy}ux=Py=M3!#RY%H|NbzP87K~5)a zY`f9U0Ku$+)1xlcp>AqZ(L1RT4Q79b8T9&f6i_$)XS231oOq4f`-&~iT$fks0zeEY z>6_>Y`q#?_v&9!VL%xr3T3N9DzZQV}qqG)Ow&eN=8e$TW;!F(p+Mi-I3J}{oiZ%p} zu~I90d4|X@u8+G18Bo2L=L|E5968>1zd&IVbO`cprvx>BDua`s?Ra$P(6lwraLb}Y z`K{l49>20IYudxUr|t|b%DPPA;&GQM<-jv>h1*bx zP!{_aDO#`b-M2(An~U}*@sjU)use*%4Kbrc2MI)J{B9)2vV~%gS~j7=43nLd36`vI zhmF~l+hKdtT1ns{W@@ND8K2)v+Ie0uJ^?Y!`t9wJ3ob%ku8Ai#wlJYxToOqnlU0R< zcy@~@#kd>L4qgIA6UVvIuC~xE&pEgRl+AwH;{XPNrj6Se%ada-HUV2RaBS(z|2iZL zN!HhG^FG=Sr%?RMi>Ftbukod1({G}?GVJhk)@cPfIqJ@TAWT%5=ueK_b#z)>Oaqb_ z`<)KLw>haV=lf?Zd**b3AfZCiSkLcz5r0qqsiiFu;va45bZPo__AU=p4*jHTCim zU$ekKLV(%GNKT<-o$V$=e4#@+==b8Zavo`ai-IV&SK0?-K^XqW{5B-}8~4%F!hkI7s+ck>$;C9uxBf%UtDr0xaIV!$O7)01)fj8?7H^3DODXM z<$yiU@v*daAEsB3j>r@+(oiHN9_e(8T^s#Cih-(bU3e^M-Mt*N_n3#xPUe#=Cz*PV42Wa8IaKMFq;Rry~#U1@!K==S}BCcH^ zqA+r!CB#Gus0$Q^nS0#~lNj?StdtLJ-m-mSlF2RkLft53sJlGiBwG9aN|d0Nt8Dh5 z2s(@-@nh)rT!oAbzjO^dpL;iE{Ic-PPZ&JeQb^&;*AluudYHJ(aFTyn#|7%Jle#5> z_U1u!x90ciAxR1!b!+DDXt^@;Q9e21La(<7Vk5Z+69C8FNc()bWhhxw# z-RJf!Gc)t%?jlq+X@IE2&qjNcn)Bx=Y8`}*>Vm?3QP3Z67H1sqd_1ySv`n<$umh+z ze>mUT%?OMsC)MxtUu;yc_O&D8O@pfg{H{8IL;B+BAt37;{-w8=a{asSA|3%C+(~JS z;^MczecnoGDLNgkfAl`0f!PDoBbQokcMYr>>S%}pl${fZjtnzbg-MJwC4`EOXRV=o zkg?I-xeB`xrl<_La<5pWj7ckvZ24&@s^*rH3<6m?_+A{p>VvkJ($~t=I^ZN>3=1N5 zqN|&+v(9|)?zt5Ng~MoBW`X- ze#W96X3E4aIRm1^-9}Etr4Ai#63e%H17@85e^l{47+Wa;D}=oy?d0Qb$%3#a&vvF! z8Q4qTYmwEp>#hsgoQLrZUtndoZV5D|0lvrKzWdtZk$&WQMI{O{9WUEUp#$&}=k37y ztj;G~kxY?8gJotF($=+<&}u>94}aaISXssi2iBm|(4+(=ZoL|hFwUqT7OF`-y^g)} z6+GpU67H)q{1;-aM+duMp$D@y)YparFT>y)^z-e`->RzY#37;#bK5TP=-Eh=N z*IMy))6_m~uu+aqScUBTC{hT5&XZIq4LU^(ln<&?d=VLw*~R*68NmFtBj}Gb0C`lqgZ?Ft)wNhFs(8mN4}lJ0>_W-+X;Dc$^vdq=%L&)y zm1BMlvW&D}`qf4~=YErna=fnK#V-(wnuaE+{}^VG#sq*IXsjl?ElMX*UQY4?WN>TA;lHnxTK}*qMgpPgVt+?!|lz8=z9AI#AqbDL>{z)!Iia*ZlU#- zlmexntb-i6U?Y#JRv^sxJ*b1T>ekdMw6D)WR>G5R6XayWXgAL&wON@uPY}E6-w!je zp)ei_T;|sL;bpdL4<0%kOzRrWu<2zEn5IXmh{r#5;@FnILoc@dkFG3U%ytQ6AEao! zNvmmor35B~@ocQIlescOmaHytL6jx07wCGAF#e_A+VdpepQX`7{ z5>j$n8sHtbXR!{=VW*6|%ei92l~%6*S$ATP-90w;b$YtvLjgc^K)PC(^HbqDWncT# zMuyR)Az|&++$)@;tO0h5<@rT@4QMGTq;+{SfW}pc5GF}#0jv;rOS)%LXStQBfsj_I z{VL{O|9J2Ez`Q9OKC;X{^$_wK0BW0NR@}*^s+g&zDNjZ`()2-Nr4cgZgY}WySVb~~ znOWt1N3Dkm92P$ur_I{G$BTE?PFi5x#t;0e;i;*7u7-o>qD3hHs|{GtJVygwWnaL8 ztILg;@_WhyLy#1WDG*;1+;yA9A450GGy`wj3T!D31A!AwAOu};}L zQ^cU9M%#!g#kw>1xbQ$2>c4S7-4ZG#U9`7(+Z?@3iqGKc7w1x`kxchQC;Km_J5F$r@Q^!aa;bI zzCnqBc_d{>ulR)H&t?AaBlRJ9Ya2HwU5*^o8HKR!y$-#=dmM8CXP8?>wF$>E`dyHe21U}j? zUNpwz>-zww+N>2YJGJPthGK0i+3R8{q_t^hja0;$kC0!hI6l=mt8?V|@Sn1-e+To? z6X`dghkpSQE~}RZvrzuu&MzFn%BmBFt(o!F4^Or@U$VuEx8CH~%jawX z~?1&v(xJ(lCR+4@bl|6phmw!mKscTMFuLPZ?OoKf1JC6vOw{|IMA z45DwMFBMj57#c(jJD=har;XJC!B5A=k4klnbcm!vUGa% z1cp2kGBXCRb$5?lvCkcC762HdI`$v1JMDY4{Um^>fXji=?2Hr*SNFv}Xq?T_k+nuS zPl=z?Rtdrn2rT+pEpU3Ek|g+L>Lj5U>Sg>PTqqNp6$e+7YVQ4E$L!i7ijO;NE4N-P z13fO*YbD?|oy@7-10~?=>`lhi18%>9qC(f|+V8z$k;>a8Y1p=Br`V;3qB<$bsc?$; zL#HLxOYlA11jfAVo-TJVqj}8Sbt*$!@8MKg;vA;yPoT(3)f}cljAT~14SPm1t1X9yMC-@v9R-le8i-CL+yt*SR@Z&#?}&(F`-*zP86nk zWMR+`n?h-(v=qc1L5pa;<2uIG^N)en1}v6*V6QHYnugtGn~m7R!G2)6dy zG0esChyE%Y4rgzkV;B?ikEpC1{{9}R5-EZCw5kwP8Im=a1r^??4}NFMTi zcyHe9OPr=CQwZJM>Pm5=yA6E9TzA|kw|Y{46GKY$Nikjxl@2h-!lGz1dwV8sTtl5nu-XxCj5CBJ9jSE`OE;-T3{+(TY+`d=pq!}_ zEM0+rRDhE;0L*x&Ao82k=RyV^5^0!7o*yoy($$nmvAN#sN5wqT;l?IAN~AMu)Smy# zXV4_X$5+}Kz{aeBA9cookC1+#!JQ?Vvhc|x_PA1#DhRoDu_-CbTumZNR5j!D7qAB9 z?8LUkl{%UI1Ef%8jX{Fl4^^BWSC3-QuFf{%z@wOQZ2mJs*Ih}(T{ML9SeM(kKDkN% zy*KqtE8kN&>y9hN`O3p*Q)H!VLhUjegxUG+?SI;Myv@y2qaf9lgcS+Gd)ErldL#v5 z35hQ8^I}d7CVFJLMt^rF7;s5X{GaY2Fg*Lp>f{nEC{=RlgiP_N*SnknSAI%F!&`2g zG;^ox#Uk`$xsf+lU7Bg4=@N6fETq7}E;fbpW< zSL5@c`lM~WWcs%?wm2iTABy` z@hG7I>~vK#AfLAI_KUNN2|@|Sy`%n}&Rp|_i)(`UxmJ}ME>k;Rndpr%^jLSkt{?7b zQ@U}%fIfd@n+Hu4uNbm>enLQpj(fiW+14ejVIN^s(+nE8^{F<2g>;B_XYrhum?wsC zk2ap)zSPE3WW_~RYW2gTNpXU~OpS7UQUM`_mQ$C8ONp5e*|W#=O226Rw+J}37`+S3 zq=1rR14vwcLUHK2WQM}drmOw3bDz#7q9y9!@C^u6GY)9xjJDZQ~xRWzOZXG&ci-$Goqut{%Bh7ktPAj*xN$Nm1B zk`nUBu}JIte>9y1TU2kf#RW;}5D-R??(PtzyAha??nXd5r5k~vQ&K>>8>Cwp89IlO z4(Yn*fA4d@!OVGQ-m~}GYyVbS{&d0ger!m+nDTswo42`)lI>kcc7jB1$By&)+nKp% z8u_x5&qDb|g50G)e*Pq+JjPy_|A9?My0A$7|(gQ zb^=Ud<^NI+J$|qc_Q9g3pHQpNmDKh5%5m|rVN#8)LTZM@Hz%~G-umftO!-^{x;n1cg7)aA5` z>+&ak%zIuKZBdKiMU}1udRmOWjn+*NqsyNZHp?itc&czX`MzrZ4-6N9jP!)zM?NMj z#l*2zmOabF`lf{p(GSN||4xI)Sn;a}LruSx{%y>J1)HX$*%EH}>{3tzCLTnrobL#V zLnU$5u6ZWO^S<(PxG(3*z(u)BsKm`qv%Y=v@Jx%HthhYWITY?gG-qsxnhmQljPP~t z`qe3DykTOUcZAohct0>)<0xF$RAP$%CxjQJE%}=k59r_L$`OK6p+h1Ap0hhe({zT3 zMx0E03LsKyV-@$sf7Fr$Zv-rDE`=#N$+Uax@tU#v_EQIz#OcV{)Y8(@a%(*~twn+~ z->~=Xb~z$>_g3hgF!@(5?2wQ?!{g-~qbNfa&KU}&eBee}?xAHLkT zsr=E5{Gkw9u-YQYH;f-HotugcoXe6STSd}GwPdJOsp9+z%to*7d)-fHbse4gbuaFL z;GBzC+J9fnH}J;)$}=EA;tnPe4-{9s`CAW_x4Wp469vnZ@%~ID-*qc$A3r2o(+7O^ za3l#&AB&i7aJako?YIr`d;^jpmK{CYCbk(0zo&W!cUH*}!!PhDd0cc5U*WT9i>>=*GBwtF{a5$8J?c)y6|5(R9 zeMoV*@>waj^hZ`=2H<{=v5|A?FS~Vzs%H}|fgR3B-2t!3zy)(5h%_iI)TJi`opCvE z#JkVyzsOHy9oIrz5#R%gUW#oGA8djtfLdP8*U|r{oLe2Mi_GHTr4L`$YVjex(Yp4Q za8>i2;`~J@=JC*8Zhb-l?N~SgUcc~n%j3E7Dl2yAa50~nGrHF0zjEx{S_HW2B8fo{ks6N z@SY2n5$m<P^Uw1XIlU&scXxyRCkb-o39$zZ-GyH*)1k#%+{j<$t)+xG z3JlBM=4`7J?FLMhh5;(YFS2d{bWMGGwhHpHZ1giOZ_@$%P*V+y1$UZS6JoHGy?NJW zHbOY%;ol;vNR0Yj?~A0*9|&>hZO|UV@*Y9nW!|UjNDytscjEFIb^SP?hu1Vl63k+2 zh*|Zn!HPV;xXvTPCW+;eVd8*F?~V)!>Q`ko*ysn`PpC?YxYyT{_|?e(;aWU!$>Fsr zM0cPfGGh68b%<|{oDbr@U%5TeL?Ww5%#4f6Ah;uVi@Sf+%q@>}Qz$R$;HcW&HO;lT zWbB_7_vv7{!xu=v$^)-ME$K0wb>ga!TWN`^X#e@V7l5Z(lX(+9_N}6nu9HuZz}l$< z9zy`&NIw_5${78Rtk6!5Pn?}bXDvlV3th7F>f9f_iJY67l%GN#KNimPeSRY5Sb8Zl`#`9{EgWj{5L63B9lxE zzGB2=wm1+fG1SCR1xs`>B$h>3cL7Q;{-ElZ)CBWl0SsmJnev5jsfE>BB7F|bdy`%K zxoYl&1~VY!ba^rTzANe%#sR8fvIQ7OFTe_izZ&vP)D}{MaqZ!raR@Ecef!=(Gqp!` zNFBO93CBq?eQu?28J$U=5Y6Gn+%8`qJW_R9UZuk{2hI(61m+Krmz*|6Uc5Sx!q6}T zYW;I19DtRNEWn+`4(n_AJMEstfQTl$INUlmuhUiB912ytiMyHL7^cw?p5Dj%JivC&p_)#B&JGYk7P2y+rs2-!g z1f=j-e&CS_sqf4D+8dKhfj%cZX8Os<`;EDSLfpun>bGtZb%}RCnptbE;9}fax>_fg zR-*UO1Zl7^-rhVD;C%pVc={b5m}LPxPAWhZ2htfe6&!qBAKd{3VXefFw?q^a|nifql zonjK^agHr`*sLo^UX%wJnl{=iZrVTW!MG%{eK$B1ojf3PnaxBaruYk8UL zd2<;wCvk~Z9k`D}>EF?Jg}%hZd>TBsyz;7yugMqp48lB9qrR@ju>~-&_2DU*mQ^Y! zrWcbtGlWqE-z+jpR_rd0+mow1M?AU2FW$TW){~E#M6Z4dVbaq__!?&BusdvQpyG_u z?E0>G;T6Af>U7Oox^^;#6gT>&e>T7Px%fx3<|8qxQn@l88=*~Z_2y8_t8REtHNS?| z%*iqA&|v)cX~W5o%(Xe)E0?7Ejo22dChd>;DO!KBvSdPtsX+w>JbTCHK-pSi85}Ma zXVb70`iRtM)iYR$rTK~!LW>H)+gtbNxBrN8v?caRc(dK6Xz5^D)d zHvC9sQX{9I3x~G!wR0DOkW=-(eY50lp4HB!cj)YJdHSkzy|>|nH)ix+cBEL^o^2^d z^m_-JO)*mph&iU5*A6mV*K@{V?L%E&JNa>Y5D^cv4UohSB)<4(;I!Xd{K= z^4RA#Fw$~I`+#-ed4%_UeO}KQ@k%E;-Smq|>Mn4}2&A36DpFNibL)@_l>5dL8~y$M zM1`f4ws#W71HDM`kc(PwR>R_3z{4^!x4LO~qa%w9pt*V~Kf&a)J*W;heUfvC#yoyB z3)nO@&#xU{h<4vnd0pF|5MJ#r59i@S>^pi&(g}4yy)K|DysOiWG0lrTs(-mY4=3bl zSbcnd9hN(YKMGM}1DU3#v1?NvVr)yjE|1eUz)YhxoT}l}o*i<~jFh&s2+){{*hWiJ z6-f)u359*)Rbevmt&89ZkCjK?{~%h4J!XoLt0sps1-Ip^NBZ!3||n-3{JGa4Q^8ehoiX1JZ(rv)6l5; zVEeWcd#lW^F)B*|CMH#yKTHIgbs$edP72x78kd8?<&(F#zlc`lE;b;(Si>`sX{#-Z z=fN-yd-!d?^{PxDq#kJEnYAyj-jqZru;fN`DzW_4 zY|YoNk-Opj)%?uoP>F|qPj2ji9H7s-Jm2j607P!uDt3zBgJTLJCnj($nQM3G*uN^`_A?)Y-_(o7w>}2)l+GaLh9It-nuU}{k@bj^7(rRp@_h2 zI>@U|Dr9Be7h_(XdX)KpFTj}{uB?-3dW6lR&!rFe-P8K@ceZKHZe;B%)nX-)BL>B! zSb0_zSkZz5;m}!nkbh>VLCjH!)!ETrr|X8fzvcUh}*08MS~C=dA-u+dlh@AD@y^>X0=!w$`0gfBL3 z+i>0an9%b3o@&%0MFoNXQf43f#B+`1M+v3L^sCf$by&(2Q#T+Cx#sLD>)U&3nY#uM zpd0F0KRqo{x@q;=@Kgtrpt$3mM7z*)AXB3>AFu4dJD0HAUN)_*?VL`F2XsamSFmV< z%a~%InWk>n$I6H-zd+{%u`wG@5rjp-w)(2Bi%|ZmUsu!|?Axvj|0eKie_|RZgxVA+VkWHk<7m61o)ciaYhPiY$ zs5LJYnK2cI@8fjBM~%|?c-)V%C+4-09K{ybda=)N<;H^EZo?<4nwi6(#0;F3)qRK~ z_L8(0yFjy(%k}X})FHfyt?Odt#4Ho7$#!$ex^cYk3HbQkej{rZtv@jCvy@X#C~&p& zCGk=GuG>Gm^4P?@g^T-VX))vCUEhpbJE^`O0^Wf)y#oqxDU4vBnEX{5Wx}r8ZD)iK z8t^l*x|oEa%GN>ovS!&X+47Qr%}V<;-mlEcQMx+@BXItzGdlbqVXrGthH%fcMr(Tu z;VBLk2qEkU%;uA9|8Bb2iueoRY|~1`!s;C)T&3fJ%ZkF6d_ImZ+wOrhM&=^5 zV!j-Y7@>IEMh+7{OE6-(((OCH*&kIg)gCo%(mkXx>hn=8En;%dcnl?G*~*1?C?JT3-2NVU4y_D?NaOWR((wtaly+4|heVSDUy z0I%c)VzK;<0&Xp@u00fEh_9i+3W>$~O(CWRm9pG%=pC2R5-lAUrKnmEzO0WlpMCoO zvaiZM_u&0Lcsuh~C5<=LQt`y(gEhhrH4*$7Fz8eg+crteBRZY^^RhghT@O|rJJvU2 zDr_@AAnX>m(pMkiiH#hVC>cq$l>DZ;h^J_ZiJQ#xQ$Xkpb1j1f`Tr$|ojY)cYV{Fs zdAnB?DlzK3ex_ygmZ)J?_O^PcgO_V>Q6W$hPHx_W_vVZCH#m$+y+oB-?&soxx=sfL zJQ5K*cSZfZ)3DHoPn8HTPqZH%C^@F)J9N*OP0c@ zv7NP*6zz4kP;IKI7>lYqE&(5nIfOx07f|t=4t_74Y_#BllcrB_Td(0`Zt5B~m9=a! zKRfh2_rl`yFZj$Jt zOhc~pwC>qG0*FEfhbM=|dt$bbnZFI+>Oha#NpzTf8=paB3r(__uhTZc7MTni?|!wY z(N)!=U{FW)Q6I$(#7=K}e?6gU@1Hwx-@m*QA`nzf=3_6>eVxqJn@igwQC>7;s+5~b zobiFIoyjtxo2afopa!RJWBip>CnW$P;`sN7U6>T7>n8J;T;m{xWf?pfij%#PK!R$D z(bgV8G-_P0QTBDgZEP~452Noh2TO??y-7NWH+i)h4H6f*_NOHS2T)-ngF1iJt~$Gw z9?ul}CR5;{H)yVxPZgN8yJDKC z*ImXGoIEEFIU^J2@;3?ndCy|0BN+>Ov|bl`t= zpf$db10c>&VXSgeUD!}rBj$t3-#$MZe^uO?CqQMtv(X!U9uE|9jgVl^6B}ap;NYNn z`ZmbiXk~72nnlX#z@tf$Qr*u}F{X#q2jqHsq4XYx0&P|Inlvea(%ZG$>3nrWv^)I^ zUlg2#Zo$47r)=R-f|ReAmp7yGCyaBJJk!AZ4~Fp0== z1LGM(NxkSa`O=(|m{m46J|F8Bo^$C}`CgYxjS|B6bjz7(L%*_(hOuHTHVyP{-~*!1 z@oA@#^G^@7l>Fd>jI_n#bL0e}SPrqwr(X<2V8S|YUn2X#y-EIeQ_9dfjNpan*GkNr zOj{}KZ=E_j)WFyn_r8EsBebVwZ@~V#ln-~IquwBDsW%|{M6VD_ODW*?L`}CLAj){) zhE+m25!<%0RPU)tqC@EH&UW1gsj`tBo8WZXlk#*s@WNNj>%<(Ijcpg*Q8fJ{p(4o# z>PH^Vt;SWy)|acD{Af#Xg{BApaZWx(31L>zW|Q+Ukgf+9&eP-4z??2Re17s@(qc5Gpc9A-u9b04$8F;UJcb z&xUE<@98dWp2d}W1SC0~aWL1FHqHWCVdMNN09>tF1& z__6PEI!)-k{?LKg)EiuMhh;lA#1(_{V`8({Bdpp?m~gDFBK79A6d}83KQm}YzbRq& z*f#caxKyPG9ZoEAKZ#RP)K4pk&0 z)&u!ahIsmTBC#gdEXy~LZGfz9N;V%aZC|PC+o{?)3&}+9s}Ews+OISz+X=tF$CRuH zIrtcW*L}{KoHdGf#vicR-65ZeW9wdm{u)ohuZ3&#GFb}a>&$uVrgnE4@TOrg>o$!| zv4x6z++2$J^5ME;=E1m1(0GAYJPjb|xR7nKDfo1Nn-!D3>>M;Xx_JrpUr%)zgP~sh z&&$YD(>AFGqW`WVzIe8g$zk=MxfM+BarMVqc`6p^c;yOmzjRusF@^_lqRGfqDz;achkdc8gPGe8i9>WZ<+)bZcN7?>lH!Ne@?bKKZ<{ zJKN?X7oRlVb8XuU`9lGi)T-L3tK7^wPF+nFNWe)(Hk-Pvt-`cW;-RAAhhU`ZK>NMjV7Gg9Cu+ zcdJ*dJo*|*z-X251#IH?ESmoOv^FW0hnNQn{ix^;Q?i?`1WPcm)OB)it*{6L>oSn* zOdbEVpczBKulsrXt@Fs=AW+;iv2GZ=WRQ2i+-DSP+v#PXHZd$}IRL#pr;%kQS!Itd z%x+Y(UQQ$p|LV@NFj)`!x6MEl()UC(fTzbelSO2iIK66P$SRcc5*F0^uGe=w+az~a zX5*W#?|HfxK0(AnSn+`F8;Cu0+{T$LL8Gf(G=JJ5J|v9OU-4|>n&DGd_YLE5a#x39 z#ryX!j*s7(fv29@u&BwdeE)n(j?vOAKQpr>8!A+l&yHdnvuQrKAmGX)gxG@SB#kv1 zH_7MHNu|i3-d$W&v`YemG^D_AfzFhROy})pqPSl(g=$I=dmX4-S5%ORQ0iR_q3J89 zt{F4O3M3T|^OP5kk#;KFS*y&6T3XepTer2NS@_6P7kghsfS`%scS71oIKe>t6l@>b0QAk2Qcr$*;i3KLFy*!6&tszdiN){ZBb?dEF_vUiA>ghujOCZaB_>fjP2NYG;=Lj{T0>gc z_<@WuY6h*K6UikqeR`pu4M@zpx}Uh~)B=q7yUF&HuiGaHYfz=I!O@)6_*-C+=0(-i z{-4g1yS!!#B#$9|*1tS`;os`|FZ?ZPA?9jL2rZI}xCTR%kbrZ2%O>D-`R$67xyF1! z1*Q)&XJ=TiHT6cxGa-dnW|MSAFD}ECGi7)iQ~J2*$glK2<@u4#2+@P+^!0wKX34#5 zGHPpVxbSS}p4hn)`f+?s-~D8tOtC?l`3&8g3XC6&Rg%r!?l+BYMRqhZ1&jpTy~qZ;M6aZ4+2fe18V+*bjQ zb8laH`{i{F`aYC(um0jX&j@z{yb*)GgZ&4zHkDlLFJYN{utf;F1qft9;2Iu3vmr@JIS;eEmeOdcP6aBflPZb(_mCjne{S`&#tx6kafgOAPIvy^JT zu>0#1fWOun_$+=c;gfgCpXK4}`dwFx;EMM5V9NeO(b>19>s0xU$vVPf&;wCuSGVWr z*&SAg^ojK|me^E(`uF40y(f;UX7W0pI<_DD2SjcIS}c%>LGuul|Fk`{^t5lMOYw#- zDu)%bvh9QW@04lmCI+IY>1^Xq^pNKCjou7SfiFeh^S_AdBjY@s!kMYCYm+CW|0608 z02|~|8ufGa)9Sc3?Dy;nJEl}IJZXgUk-LX)e2Ie7g6Cn1iI(6kSz$d#qrCNhImc=; zrWEOp`L{(i4lyA)on;+Rm=`qbOL8py&Toa8`L#F1pzP7j$fmNK&V3-02TYEbBVnDP z#_l~<^DL45kxgb7y>tZYh<^AQ>uK_FTA^vkZz z*u3>O#C%~;DrWpLQ<_ZI^{3XTi|M$C<|Ajct6lH-r9rfqgeTt5$QtHGxj3G=d`Ts| zrT1i1h5SImS^%CYL_2Se7B|9Cy(?hrYU#-14K5lH$`LK#x68w7u>55cC!C|Q6=wA& zCyGvq>yUg63zdp4Ip?;}IYaU0D0kxd>igK*@*_(3l~b>n-5ijCi)EKq_f$z9YD$x0 z&}vrArQZ@|r>OvU{+S@G9*uu<9c~B}2KiR__p(N*n-cV!ieQ8+KwTeA!#`*S{Q=7?ih*=^j%ZsV$@Y z4NY1Glkyu|f1h0orT(#>74f4h#U9GREGGU+r9tv)_Ya00I5l1O^?cs7Uu)MCkS|`p zK`6iOL(V+M5I-Fd* z=Nh<1Vol*5Hl}FQK|bCGHjhUE_GII~&gWB}@2`}TKUHlycV(XDdAz!E4KWVTcn#|k zsks>w)D9S2*w*X1B=5d~-`1bR?l0M zJWq@6IaX&Qz<7OPDpXYO(K?41J{aMu5+>6A4(&fv=`e9;Y1YGWAxrMRO`)x4I19@1 zOe@`NXeM<<3~t@7-L@yEv~jjP2mRxG21#-~E?OxnWp1$+PqD{p@}KvUr(2@h=fGPC z!Kw6sg!1bT%hXI1%K?ujF}>_}T`NS};4A>GsEfoTkEw{C+sB=b{QVP3F2TwelGOV- z5|Q0miqqG_#dl#L=$)zM3@1Rg!{K5lg)NG@gogXPe5?<|H1c*Y`BXKt-kMw<1SuQI zlP}j{tT>az*BCF{FHDfnnT!=4;K&>}xy9p&dA=xoF^2zOQ@<|yeMA(`&?n3Urupy( z(tGlc?MYvBHwT^L*|=?xs#|oe3n(9I4=WlYCb3|3%ohtg(sFa-f+7 ze3b2Tx4DAn_iY^q-y0cTAsD0SjUp{*FwvKNyjy3tN#91aqZhfj6z@!p(G=EC=e{H0 zB*&w|ZE-)iS@qj}JJEZ3L+(^FHTAfS+$6t+G;ynPL($RFl|SlaNn4%)!-$F=9zvTW7%TPNQjMEbWtE%?ZQ{@zVgI5%rx zWk~+;chKG2s^D@{nCSUHPubP+RHBRWqIos?=1ct+#mi)=k1LUZo;GL6IZ1-Z6KetO zW5#XCXKVf*UF$#DMln%4NHJw|t3gPgMw705BG_`Kt}To#z>U-5g>J+AQ+&O6hFnj z36V4is7YJ1e&=6Ylth6x3P2Jl@?pC?4!8{atud%3R5a)APTMsyWN+c&MR;j%(KVu- zaIZ=-CR$@QIVQ`Y0$T!HnPfXN zOmTBPh?BqC#BOMxd4ZbrENB3&RH<+6R=3ws{jBgP>1esg(oP(lCZqIOf}g439T(s8 zNv^cXFUDoEp-j#{b&mH@$gLGGz$EjNcJxHy0HOQrmoQP+2^X0RVzQqvUL|!KrE%;? z>y|(7heY<0^fq0UA5S7Zx8RAB_(6h8@$|}p7RjAb#vj{C{P3b_NbaBgNwvTN*0alM z`iGtFJe`2s3g;(|EA{8;GDG01N}v>jw8}{RXDZq%HFOB0Ode6=$h}f<)x(giUMik$ z%f=~gUm6HNo{hFQFsB>__BqN;*=l-{cK2(Qtp97)(QI9tD9qB)&VWsuh(TAD>Ij;# zg~z>bKe`j(stj^PC?;SsQ9LU&Du6798(}>t9Q-bS+UB=Y^O^rM_Fr9QRLFSoVd3Ln zb2absuN$|FEiVEtSCSe+DdIPMYe)3Z8M-BEZoU+5y*56x7H~bjjjqOFH>yy4x{3&1 zoS10EoV^!~n7^_^{gZ}N$sca1NfMJ{;tyd0Z{Bk31S@W=ghXDd#S~Kb34vyg03hoA zy)rY9569MN;PUM_fRxjVr)x4rogvAl=ZIc6ts3bugiXC1`PuxaA%8A ze)%|%UGLh4L00lL0O@kM+Qpj-+wHr^8QNy88$8vL02jggB%x7B+GrKxipwDd-U3K- z2vL+uv;cD=*fN3+Q;7nIJS6()Twwi$paFjK1TIuEF>CnC2RuNgnA>qy>lTxts03Zy znii$NzHoI96yvx04-1@vx1UZ>|FBJ1XVHG7e949+(P?x_bQHV>`oe_X*D7*lsi|fE z$4J4wweWr4B`ITJ2L=;8tKKo{bDqt2f^bwRV51Y9s+me}n^^$;#ix3Ohx-F)wZ=#I z;xZmeFFqG1V=^muWY+%{xZr0XxQf`yXmjm9;CoZ&eZ4a?+1*U)cCk}i=#fO{cc#Zk zwaFRTEq@!6mq$*P&pOl2c1hGomxfu%-vlHyDK3WfWvi82Nnd_ijb3gyV z0_BSNR5bH}Zh!=d8l{en#4d>i8zA=Y99V+2DtxsqKe8{;L>07Jo#XULrP2qi>oMlN86?@@NcWr_R_DbM ztGjb+0X@6UJO7k>3&+=;{R(@ZA3B53%X+B}i2eTd?Bt2L-a5kp8^KP+Kk{(N%zjqJ zIG;BfT4qa=*~f=z=zR?e$%;`IrQucB(+OAIw3EMY-s6POOo8pu(*oW@XD$?Z)O%C9 z>|tKRD|#nl|Mv$KEn;icqE(a4tqX8-EQ`6Docxw0SYaWnG$L_tjYf6!)>(w(P2RJc z;bOIeis5h(+k$UR%x<-=o*6dI9W*=FxIQWg8=r{$_6jrjo{QXQH2VjB@RKCz(5Fg* zT6=@HKx~J7XT8Q$PzTeH$Um3~n8X&sRas~YWgUi$P+<3ob8)SRL zMZmK+8X`r1HlA;64+?YWydj%k6dC!d!-J{+lsJ*YePKa{D7HOnVLllVrBhAoiGL(RH$|7=rF z5ke^JV=f=@f1i{#h|cQ#B5?j;R1LGyxoMunCql;69F!9{r1*?r>}Ef zG{oMLd7k!NH zuxp)m1=6%=|6Sk{fe)Ike&l{@E`MgR+DJd8q*By@klWvTfSh6R27}f#(KJ3O8d50E z0L5CzYUT~N7`l5Hw2tuGxH|LM#0WzOg|6HZma&bT+Vx@y?}P>wu+{1+tb)q9WlNZd z#BqS_H9PTzDBQw>Hem9>0b(g0J||x4>L`2ppHWIHRlSMPXaShq&^mFrsBDveZt;y| z8%Rm2gDIIVXxOt2@hK>c92b6@m@wB2!jl-kEq!*a>pRsudHQ6R_nfRPPgev5iHY=h z|9bVSj(RK`4#}z$QhOEuN>pAl4Bt%ZD_XhT)`lt7+^45U3kb=^yACa_!8v_)sHK{Q zvBNH_DwZ8BM-n`<*W?3PxcO!YoLo8`s(qL`R#4Ommm0lDcBdX!0`i{hRH=rl%^~+H zvBI{7k7qB(AN@%$vrl)k6rlPEob423kXVHcW4nUHONirpB)+2^v*$2uro8Cf&$ zg%~2{*`zM`S=uj79a!JXnf&Jx&cg|;)(lRq?2yZn-e8A1>mAo zMB)%$9ReVK!L@5<&fghAsy&lD_ys5=df7}dNnYvZlWsW0Mbl22#22W;A;=0bf|Y90{jxm2L`sm2;f@HdKpP_N$mn z_cglozG`5tL7ZEDuF;4I&`{dpF zk#7+DI0bC?1SA&g`HJ6s@h;Fk;;<75RtHhQG+@iZvKzi#a^!Cm1_Ve(YqA z3HE8{?tSZf*ot>Av}*Utj*TLmOV^1VuC#%A{7XVlXuQQ6fd;53NH}CGC$qk9!rv)# zq($b*U^dG6S50p78MIo^sM0nWE&9Nz5K89H8{&|Rm|3HMK@A}Jh{UKSdq8YVsX(E= zsY&3;knEResZRFO;$V0F)7~Sy=z#igmFzPT z4{e45FVbSsrV1OwyMM@d>{$Jv`oj`iZlOKX2^YK{1l?8~3#+V=bhu~1vphdxIs!5= ztF)lGqHpviwr2k=wV8rRst~a`P4|yT_7wH>`DsW??!!qpQSFy{oEeef4xN4n4==0F zWPU?nODCpe@X^Ub3CudWEqLelil9q&A(X$?w(A0SYx|7fFYfxLc8UVfQb-foMue7+ zHd-ojROXwMb92jM?cxqZ5-QKJ(WLDz$GFpD!_QI>_Xg%+`TQlQJHg4A^l#j7Lh%v1 zigAEe0p+7`KYws=uiXc-PY7xphiJ*M6N_n-M-$5paQcKU4VDD>KH-N)zL`pP{Pe}Q zlhRAn=w?@>D zdX5e#e-ZCUmj`?y7)an$HUk-I)h!_pLaFup0D8F@o7gyVd;SEz*5!jldS;A+sN~WL zA{;HnGyb`Kw~xqGXBKP?VM+}0blIU}z? zEu#ylyy|zVtAB^hee979)e~o~2ZeE$@IOkr`jZwU8N07ca_J#m*I&PsN0{31K>u^Rp1YL0QK zP2!n$&FoR)wzq6|coVuB;JhuL{UY?Y(5gj*snGad!zVh_geSV(G+ki+0M zaPD!NO`+n~EgXm9ncf^@JW&NVwOZ*gja2%oU79Hb{VZbH397n~0{tQgTU4ED7YNf5pIZt&@v{>)R}qnCoczTsQ>9njNzE zCaOec9&sgAyJIYB{O)He?tqhK>Rh!i@V0#w&}-b1PH~*vT>?4g!PcB8 zFz!5ZrD}r!80xaJdd1PiyEdf)4Z(VCWWD{5bqAP}K}v=4O|=SQh-U+j(qbtyMX6JTXn5Oxagb02A`r39Y*R zNi1NJR*Hy=yV`rC148Krx+Pkv9~nb_Wq7fYQ6Qt;#t7?OOT-!|R+ zXZQa#DEvc1pg2L>fBLP(u(ITB`m3a+c8G09rgA_FBx{bp3OAH1jpyZY8`}LnK~~lf z($$Dk0X}kAE(D4%rIVstk(B+<4u@^3P{FLOg`9ClM_e`B6o9otq&yhv3~-qW`@`|@O&8G@c+)=bVPVn*s3!1OHx6jx)9o?#ZYt6Q|B-vRMHr50S<&> z+7!Ehd<_mE!@`Y&bvd;~0pL`?vC{Rd3hQrjY>O~7^0_^3-Mu>%rNYM{e1PPzsk*$( z;~C>pr6{9=V5z{~O-K|ORV2$$SDlzaNW3#=R&9uI%`%Tfl$6fdfKyO;bv;T)q$p-_ zP%N1Dp9-j<1e~Dh(nLz$LLMo^{+w@THET>!sxh2vy!HqH^~otIrds-)#c)JSyYSTZ ziU;m+0vV?;RwG3+ULnxtoUZY)zM`UArE21C3uB~xolZ-k>ho|VDH&r)i7h~RSy*ff zJz;vMUdKxR?sMF1uogXf`+FnfQ}1Mb?P@_QG$AEsgCY7UIv|Iq)4tNyWAQLxxp)?t@@-QB*yaI^>uZqSOg#vmh8p+I{nkYJq52P&z%a%>Kt9BFbFF+C&?(TD6 zK6+k$`M8#w`$WUQ&{oRA%F1|={e0!0*Ph_4vGvB3OzqonG1R=-0mi2|gF=m`cbhSh z@nbL>$`gbk)S6s-ltJ8AD4!ULZ(%Fd$)6{cX!*%PG1f7UUA7SRA$71tvgUU_5IC%* zL3}GUrDz|=Cqqw!Dx=BQOAnL?T%Z{vVUgPLBy5-~u+~{*8sAw8+FgIYg_@G>(z%`R zV1i5I!I;-vz{E(HAU1_ZNAs2H8cWCjPZD@OAvdz%JPco6TCOL(#Na+#S&e7>iD-AamyO`xAeu{ z)m?h3a_)`-HMo7D#GU@b0e&$G+pi3Ec8pu`HUvf75G2;u*go)G~^lja~)g zs4PIMS!cmfm^*|Dv5#ik7@fHN(vtunCpC(rMD2PLS_!*_z_WLB#+!u_7X-1)nLi-* zzXB9ex2)s;8Ew7U$XCuSrknmoGc{Zf<%>ECHu*)S%p7;pitqp$aw3LLFQkB^pA8k{ zI~r36!%F25mhC(i8_wfVT&vY~0@hrPj)5jXQ1OilfhIY5D&T{DMq*J9BK*4!PKg4~ zwaK*3SMN{UF83`9n2Hu`@Z|^~te`1b=7GtONKfPT1bo$^Z0ylS_!eQT@e}>H=n0kU z4!JZr(MT{t2r+sXa8dO*boCI#_MWCE<8P3mVWAek2}>5js|FNPvz8S@$6iE7j=MwY zR%e*SHbNP5d{K~S$sA8QUg_t~f*(wy%zZR)Ob~BALlsIiYSnc@gyJg}21KP)_hpvvd}$;P7rf^&}(CUYFon z3k1jC8`9^6t&*$cE6(+&O9{bCGT<6N471j9|1qp>hm!>a5R7U&7A0<=0`Oi9;)VX< z@6cc_B}U|kh+WADz;*3`g zQ+~%?|xba)3Ypf2I=ro)Dj7+y3? zsPmoaoDzmi%BuEVHze*dV^(LZ4zo~^pApCvXkG%sG694W?hmbx_Es(yL6x0<0l~C# zm2vp@-If`ase}|pjCXJ|jk>L|)6|jX@0ESC_85M7Ujq{|5^s{cRvD$jQ@fZPjK~7e zlnVp#=#>O7#2z$69hY!C%v{M_H}F{m%2EqLcSknPuK#%Khe9_U#41Q4k>&ICm8Is) z!XW|QPI8McD1VgjV~K(H{-9QTbqWJ$=jTuO70Zd#DMk16`eS8h^mpmeyt^n$Be%O? zzz$kq8c&+tS@nq!pjC`sZ?>eAJf>vn{Z=ZRMo$8^G%PuWX32nW*9ftxtdUzmnsZ<9 z`({Qq_FPqBD_-k!Oe*vqx;;{{f!Fs<8G`%Z?h@Q3 zxI=J<;O_2jgS*=Vw|oA3>sIl|!_3qM~_sa7lqzuMgu-IAkyZg_7(6Ll8w$?WD z8D#l4QinN;DKzfRpJW0><4r%C;QvPUpqNGl7< zOMX`^y%x)*h;hcs5(|jjvxUzti1N)5b{I0+#YwQ1rGz;K>u4bUAKQ zm$VWNoJg%m8iPe%cHqv^&aMH2K8sd1N-v4Lqp5hI7F$4d$#8AmC!4xLwJ-IinPkjM z%b{+UHt^$gEI~_AqWQFBpUgh?C7N~$XgH+nQ%1f z+fAkg$pY}f0SWcFZcsqZXQh4Uc(E){xC0%dqIN+F?Q5m?q>6Yh zVaL&~0|1kGC=RPxpE+0Nw%$W`mYwozv(E+oqBQOD`Z{UxIF}YBjxmW<3XU`u@fsXI z?6=98ASv0*k2UOD=X_OwaUER}*P(iJ;PL6ses$#mv87I;%-@6lM;i6;fN6G)H(0dd z{pJGWP(=HQTPli%uCDj}**j#<@3{sJRIM2A%&Q4KZEEVy@OIrf_haO~cM9dSJMdmN zwkr^i^5!kx!o&!KlK~bNCKFge>2LmB#PCE$)DPa7;VR%7ug5H#G#nFq?k_xaa2v-+ ztEPZj9$e|p|J1(7B1cS$_OVS=E$t?smI9s!d;Y=ipr!8$YeGB=kgyHTFTVhhNIt%H zyF~dqckj%|CjZa~TYgYakvl0Rgr8qp^y=0~64UNr%~r`Vzz0URm~aj;^x0`5EO6Aw6c27S?lLPs2x*(koZH zSX=W9GGiP3z<|BE8t9OX^n#8LFLn$OgeD8I-*CSuWK%Hh$B{gfkmQquky)8_c#_M? z=Chl91Z-4Z8|3ne;Fr&e42xGVMZZS!r+r6-Fsmo@jU=a@>=V4U_c2@@ zop~iJ;MB+*|N0!ETokm^eRcy!2bY18Anpf7^ru88e-Dr>$}4q=Tq(D?ss2liJ{aes z-qR5pOTXNP!bkt6qP0)S0HX!+%Yv&aa%4C(_o&7{J!@I}Q>0NKR-PE*NfhX_5<1+B z9C;m#kROqyH+4CX6p+Zq7a#-#8i=&(@{v@uS;CY6l9CVGVprA5P=(xws!q(yn^w+0 zocCKA6B}Mk`*5AR8pfBh1e{vE7q=*{2e@Pw?gLdF8=E|fg$!Lca4_is783r~4`}37 zYfA(`fX&ZEz?&Di6{}@!`yxN4dmWUzLW>p!Wn-O$KqL6sHf&uYVBJ?prN7=9N> zYDYk1{iS&>!GE@5VOM(C=uJ-ZeO-b-WLx-!V&MAAziGA6bniK1kh2sCg2A6dwnPUb zf$iRUaf@T?U1I{q;IgdJEW3DKjM^~cwSSIs6@M`fOLtD4ASA2{AiPe~fD zZXB;}{Z5EFRJ%JSMT6S%^;yeE%{{Ey0s5);HTGnZNpc-3J@|5Wv6CU<8z32^LMfUc zOQ~B`bq4}9vl9s|Wd^9p0B&+QS*nkjf*@_fWwYc+>H-n`B1hY#4qHs|VeTcw-dOJF zvLHwH1D*d+BfJD)07za~bpc0YYYdV*QSqdO^_^tz641&O6<%ldwU>HvRW-x+ry= zpB=h-834Tq83G9^DRW`N3vAvyPra$)`T-B~RW(}YuBOU)tGKUwV|=|$mD^oN2@by` z(OLr0t%Q~aY7UBFk%pit3l@%*M(Ih?7z1W;#En*1?!kN9hj6a%6vFutZ|S(f z;OhA=3V3q@krdMAjRE9*2f+pzDLd7~;#r15+TPq$1Flu*fSq3d=2+g}Bc5OO(6u2n zSfGaep-VC+*C3lA3=v)coibn@=p!rnf1_>IOfR33pd5^)4rRcaD3cfukE}R6e|vlh z^k|O~D8=Zr=cgisG>reWmG5{JU;mY?n{uB?hn+c&Dig*wkL`tL0wRpiZmH+UnJ%V_ z5Dm4DtN$s_IEt|Wr8OOMXT~s5-d_ALhbiUK)^*gyVm0H&1N+8KZzs9Vq|_|cs8wO_ ztV%0hHlMShh}w2X>|2&Yiu4*%&-a{|j%fY!Z#?2QhM?yppg9rLpnpgupcT5i{?+-Q zot)0$cb0 zkY^Z#Y7B)&n`{>0T2=lY6M01T#+tz;9ZmEztIHVh5p8YSh5M|L{=XIgyHv-iv9&40 z%_+kyB}qDo%1mL`BpJYI7=yyhhy}%sAe;d<4*6Rqzj2FIm<#jrI8?N#lTtH1>KO(L znjKOTN4a8Wa$4Q9eas>#KGB9he;6jK61*Wyu3V=G`{=~k;C>P1>b75Spzy+<1-t5d zL6qft8#zOSt$x#*GhN9%9>4qg!lYTHOYEyF_$h^Pw1)+G-OIYB_YPPw`b~)0w#sJF zMzW10E(Osc9ZN=jJq_9UvEyCCFnUF19bFn%2(GDb=V68D;tL4gw4{tSW$f>sf0}*x(D2J zPRoY#3Km^*$DF7fmJpE8{iRaJzwsqC#^R8SIIzbhB`~3YPTZ*>NY0p^_*xtT>jpB>G6q=|Q zQ?9|&%FwGVZ<8SY{DpN`Pai5`YuaUv|IwaMUjCQ%Vn6%%hk1QcvH2|lx+#|;y^A$h z#NPovPJeOK={{y|X^U;CV6(48H9H2l;SrZQxn_}4nAMQS_mSSfrLTMmbhwOC%F8|=bE~3<)y)-XLfT8xLK^KHVQYE z$>a^yKul}zWGv-D#^pMlf$08aiaI}!4+Kh@?$+B&_dKG3o9JTwmH(bpOl8$wvx{|1 zYdi&_MSi&<2*YQ$n>!EtRB42^Amy^ z#1~ok`#OwnPqsZUylwl9V@qC*(70C@?C)s}V@qxkq+K9WGyp5LFIq_Jo;Tj%L~ybxTA@-Xi%u0!>IgGB zh=a!NR?N}ID=?fZb2wx&+jFBe!nN9Uog;8UyGabrR6N<2$)zL*s}hzZ?!r|B_ml-I*;d%?l^oc&|1z)*nb`NYxcnQAl``TLIOx>#JtYbFnpCb~Nzy9gp+p?i|EUqXtA)g}uFfanh!p?Nv0lHR z5^am;&ydczRh-ac&oI|v40`vrb_Z&EOZM{FQA~U8_5ilm9SimMFM5{OwHI!?GM6Em zY_E+Fb*0zTbe=1_UuR1x4Vxp5$utg8Gn&GLavuRAQDwPOu4z`ffz%9zfD3j9jf31Q zH-Ez=Dl?Y!mp{YqbAdfb+PU5Om6d|i(r|B{;m>ZM6k00gd_tJaga==8`^C|_-GFNsGqRRvQp9*%C1PW?51B7=f%z@KJLjM|6Y@ zSK*rOSD`tXk}H?`bh)<2W8_~1* z)wuU41IfOaClQ^>(~3!s7Hr;qtmfgNqen4$LtRb}-zS3Ek*BD8oO zh?9#+h|8rh=Y**_J)F=X?04i@o&;2lcKq4fH2rnt)v>j#$ng?S7>ijx?;-X_Ru#1` zn?&~9KZXh`5^{&)n!i#qUz#_$u7@tlkOt=do%xZb)%WrwP^q`!Xvigxxp4>POgHKb z3yBX4;lt!3fM9F(@IK8ukmk@}Jg<1wbi35;JxEUN`up~9bXAFHwXn+%VrHKEgs$~2#;Sanprp@( z_639wO5aoxD6RNI8UoshgTG<66zzG9P0C7*y}khI`Hr5Y)F3y$SCQ>&e4#T-T6i$>eh}N5`1>d#?R? zldFW}pJq&EDE42U8i7_VMu57RxRl|yM04H36`afXOpPPQt1=c(A*H#VRy3hiRx(yl z(8;;8V}1f)<>f3;mbtoZq~_WPF)?T)K7D64*<^;VR#M!!g4sQ45DOD-81u^-gaddW z%H{`NqIFsFF;~e01FccY{1{UJD3k z?>%TY*`Ky@p)|jFh78rH&cB$L6or7aaazvZ2l<0FTAr_h9SR47CJfaHQmH z4Y)#g|B;PZKLv;Yab5DUi($`F^mGSyg>@sq+1`@R*8Z;R#dT6s6Gk|ZC(D+26myIF zhaR!R*~*sayNkBk{$yX*>-CpQdelga3=vo1-zS4qUDzt$4sQ>VI_8Aqc6Wg2SY-am z-nGVupGnfnI7KszL$k=>3~SvHI3m3S6F)sD&GjC7wfBbp)CFllc}DyloMG!ufHEQG z{p=zpDLrLMo~R}%?^oX0x!n0AM-%vyUn^*H^U0!xw5B><^x>ZnbO)H~RJa`{AV^ocINWL= z#ORFtsW#+Y_mSho#GvS7B+{i7z!`gsn9Q%nPd^GXd6#lv#Fs8G1{XB|1{4>Mm^e^{ zep-rRu4adwFZgHbz>VPPqH{c_l}(efh5;!-2GrW&^2rPsUhk|^HF)|ER*jMkvizxU z;NQNvbr~y=4H+HxId_cL3Ddm)$o#x~@#U?}*%y;^j7>8$HK=CDymH|H^*Np!aL5w1 zuoN9RAa|e&2b?X@I2-(M_1o)Wp&OPM)m7+8qxd3H!Kpy#l3k|rmNb(5M*>T+N=plP zjs_&@8qF)Nfc?ZMy2|D0Ad|A*6}rQ(1-71GotNh?!LeGJvA}PKqBn1>vI|Wg& zf^_-H(%H;2bqcgmCvH2Q0`jWBliS;^?^TsvDBUU4SA!Y@mjL9`|7GdqBBe0V&2Ynd zRoL5T}onppAyr}|F9E2{*=Bn@gPm{?wWzz z+>L!Df?C(IV0rx$NJoIb`|R$?>p_zmcSI3dwMp%RT&&Fy(vCnnJ~&ie{OS9C#mZ8& zbQNxNVtOHIxFPc`PrVD6&%Duf<-Aj$nwg z3y2>b^U){T7s>0NFUrbW&^F*ctnqom>Gg5VomY__#{rs2V0npox6vK~l!c7aF&!n_ z`6QJqz&|}+kwULo`K}ce@+kby{_T~w^D#Z1Tp{~4YjMykY}_*)0W8F+6Q*;DW*FUL zm-5#^O0=lHP{T1Se$N%DZUOM?(=qX4;{L!0B$$44_mU$6Ych?MQ$_E>cv7hR_% zwb_av8$cOED`A=34KoK87XqjwHC-%|S#zCWP`)Eo0F*46ZG~R`T3NE&e${@v&2ti0 zJenn@1Gk1fZ{1?TS!g1Ff4urE-qmnI4vRc6XTi$xrsM$eSpIR%+J*Cc{6$H3bK35$ z9Xg*VY^er9pKC7|W5gAgE{d18qs&#t_;dR^baC+ldZU+JZsQfMM-;>D+}J{6lJO(j zdYXliV6bXu9`Yl4u$LS$82pXYOXS0!_4BtN9YBSB_ zN3mepun_ZT;KyAfo+aS8hkJ_V)tQh)g|KVl@DZIYeQej|Rv<*~?Xo9q^Ui;z2?y6l zci1vOau<)77=T~`WFv{IEpBeM;XWVk%E9Bk6YY*GGC-~F5sKrsQ1#A2vh`1jvDnmLnV+=MTeFD@_x|?5P2im&eaNvMgue`lfJ1~3YNn|TV>oW|b2GCKVuG)Wd zq@al^BETM%9C!IJ&K_ToftpF4Co-#0REgPxWo|CV(0#FLcB2De- z&18Ge^>h-if9()B1_gv_?o^F#vA+z!9C&Wba*Czv_CPVGsngJ2s7d^gS#py)%)P;Fp^;_H3p3B-gun>v;j?+qkEyYQN$9 z*-koAeRa%;zPY%cAT{T~PmU7l{MS{IJqJG~G#+_Y+egJ@nKN@dldXuz!4Dch5r%+2 zTGpVIB!VZgLl$_Vv4e45+|z9Nkw^CH(2dSE4S!20DXe&sQ7fmG`VRMagBZex-a|$2 z2nEC4#g4%H^Ty9?g(UK`B=VTi^wU~caFu5hL{%BxsVNyG>M>ZqnzQ7SBpfRiXIMgm z1DfRo>KEKN?!p*sfJ(Dn?SL)x9bHrjXKzcVT2dI45Ym!?M0)7b>h?PA8PAR~6)x@; z5By^;`Xrw_p<7{m*h{rlvc%K3%GRDWSI+z6&ZkcoUUv(tVns-VeJ_stZWSXK5KeQ3 z68hgJaQ5XOP)VGBE)7k%Mcwc+S8Z#DPfXSG%C4zO6!**3@rJEXS9J#4Vqz@d`3k&m z=q7&Y^+m7CZ3R+wt9+90Y&Jv^DRq^|<)f*>x%B>{ z*K8r6Mu6j(i#O-;^ef0KZ3r(AT$GOc47)C7q9?<1l`6{OXvHG?jemph8|t){Q8UvO zi-gpr1x7Ch!tX!xkvT&wB=RKTsPpBG^6}54sp=IR?pXj`|9v*%FRcoRBEX=sGQnN} zas65fRp73)*I|!TmLa4qLP`wZ+#^UnIByf{HQ(|(+4;3LvGN51^IpF4+w-GgtN0B2 zP^|!5VNJPVhz?CbY_LA+2yBZQmV0xovqT97#F-`{-j!-%q3f0qU1fVw>%JZ^`uv9& z$6jn~dL47ts3NL-@bwc242aF;&airFBAryhXEdV?^seAANHKyWM*dN;IOU}e!b`7K zCot^md`*sr)@S>?{=5{x)-!~zf2TsI>>xSNqr&Y?0sU0OohgocOhwN2rnLLFn88uD8F+LTiHT{{`nc*?_8IY1Q#Kc=n`aX*Ka)7t z34s&J;q4XM#`??}oe44fF+#oOZ+k}&I8&f9@T^JyN897t;{C(qi=z)z_ARSkHn|w? zeR~BwY_tdt+Lgt7altnz<=u-W!dw$sJ%L@2ft2N*6E~l@a;zEda35UK2T~w1g{iHy znb=-!#){KaqXT$lvm`MTv)dQ)^q+?UB`vj?NlwwwVQTXAp*B(=R3(ex-g<*vp=XSK zYTvg%lPT5^Rh_E4(N!wxZw96ZPl7MHzErqkt+T_^hS^*}8k~obJNS#u9kN;DX62wH zxCS$g=pIQxa<-Zy@cnJh|Blf@9DsI4a4dCGWOv4&-S$G)yr? zr;h&FW#$cL5KdM!Q6a4i0xT!3gM?q++ETqF#f{*qHRGw_`vuL;aaZ4`R;NZ@;(sNX z(liB2x*I%B!58-5f1BNNq~|nez=FBult%{c%DznMQ~?>VgV2$8KYtQX_68{}PFub}iFN(m+M=HY7VyZ=mU|1?+;l8BS*Mp8Cn(=$$4vwkXoJM^{*D{{i zw9-ZN-ml*dZvu+}T@*d|a~9XmMu9Lse0DD_JTQ;7$h)blO!J1?}4LRrkO<2jVc=fzFMhi+5S1_s%(};kO2cidp!vs{46I7xlF|8qh#0x73 z&>0O!tqOZ9r zD08;yaKo;6!di};2xLL8>I}c3fBQ6jHo;#B{uyY{bm6`I3$|@X&PNgmSPtA8tE|mZ zmtG$7Yo3c zEW-dn8bCTa1ps~uAb8D^ok|+9wf5%Bb?-hY8>HZX2$?DV2)GWzM(!RUV=|ko*y{eN z{c=6-`)0jgm*MDh8CA580ar`0 z=>A(QJd2VjBlF`}G)6s;-sB#HZh+?B} z_+vC`rO{#M{+Gwv=RBu1Ytb;kU;iPcJ9Uch=c#ybT8)+cDqx(wZceh;RHh1%Fw2uRjPR4}|J)wq$8~3gpKHCg&G**>EW&SuljenSMX0(3ov;P|3>`{1=uF5eR- z@LV3vLSct4LRb<^drR=)U17(^Qe!gTp(X{u)B^z~%qK*<3DTg{wei#Ni9@*|8?%kS zu%dy4n&V(gZ=~7ODu{8){%YpW0xVEmX7jH{_8hfnp5w!8N-TF7&wA%#{AGKCv^aP) z4@`d;H1bI#{}A5j+NtGZeI6vbE-la@O3QBo;n;HM%Whk|K8w^ZfquAO3Pru`o_7Nnf8Dcc zo0}*0Mx6zpCaG{E6+17j@9(qCb|wN;@BS%?ce`%5N8tj@Q=!XjFN_L~w~H#TEO>(S z=OHv7AuypIdY^J1o8kruf*0=^k?Z*?CGz*{XHb^+BW-XyY74_qZQ$+R?KCmJzl70g zI*3yqb2g(5@XRL9C+RC^0;_;}>)L#PF)6#rtTEyN^ zEtVHTfSa~%5o<z$nxO;to0 zksGB@xCsTjtIkGf*S9-90Vh{Tmnd247m6 zVXSE6$CQ0mq_H8fOWCN(Bh4)7DK2u$g+W@ii+9v~S@OgxN(W7X`0#{j@;p6M+EWlv zg#>D`{gBaw$=Q&#Z|BHRHldqz?6?eK2EqfpEuI105D}X76kUhEJ>)(q%%ND;W)hSi+sZ6r|ByNvb#GfoOIqs}ryR>-A zFow=r%|#Qd6U9uAv;BumGi!((?34ZLB^V#Ypd$SLS^#wa2~&6ok5Je@Kz?`4us3tF z;1KYgR;m`ZJHL3}Cy{-_m3H3gjS_elp1wb?Oj|17tZHO$-%~}&I)_^!42(p&hRP5% z%u9%UUYd=7^_R{XS*Ar<6CRSWH!~L!*yh{w_LQp!OBk0w)9mW6{Zn_p8*~~hX+4M z9nC_bn{P5*-A{x%q|F>#kk@xYJ;`A%-9?m*VL5DRKPkLx*Nr?_07QqmGyrn)z*6rC zzpCweUHw@-aGbMO+Y|0N*G|uwp*)4x9qKc-9t^QnnAif7hQyg7cGVO<%yD z(A|tapK;5cQYgI?6AMjI3lrFD$Yoe=BZ!mmuFKMqPL}>ui3XXKUTHn}G`k0`UjU>< zTc~Y-1oN+zrHj50B@6D`RXV0$GCF_&b9cv_iIsY=BR1zn?ge6}_E9D3HIN8c-B)u) zuE%J3fWeDgykYmu#1=~tE50L!N?dZQ&No&KMAbbJ@n(_rY;5M z(|>U(Rt%8uGRYJetDdd_iyc=w=bgUU?5Te!uJCdiXTN`X(vGs*1BQ z_`A}{)s<{5wnJ3b-RWV?-v_YHwv{^lh1R}Oiro5v+ig_{Sr#dBDU?ncxvQII1M{w zD9L1vOCaLQbJvZ%cCPh;jnqzg4-H@{>v=Hp6G$&L5T3eBcCfX!?&tP#EdQ`(HP`HT zfZAxgu}}Qm>pN8Ovr%e0h5hSP+wRq}FE0rDX$(ovKgKsOs_zB3-bwZ1!DEPLO)qN~VRJus5I?;4IfNJTGr=pb0_4Rr0}YX^ zlA?g6C1enTjz%_$?K*x+OBD-lx#L}TgLOj#ANTEb$xjoI2L25$>?sn%2Q45|YIPSP z8FZ3jW$Q}sJ~ZtH%km0B5Xs2DfBmNqtQF(T1&IS|80_0*35d*!A*T&Bq1 zy-4~HzMMj9$G=HRPrkBJ7hoCSsbKZHRp6n9U=E9A9o%;)^2jn;;v@3Oe;!zWkjWE^ z_~p)r*`7%%lIJWu;(}kt^m!)D(o0rm_%@)z(S(qXSq-$^MC9($5MC>jIG2u61BV;s z`C?_YN*CC5=WTJr3m_H63AE^=n!_!6&)-#XX47u-$My&_nk#C11lj_LkS+ufu$>D( zLapz>JuGrogZ*_n;XS#X@pg9$ytY0k&Yb6hKT07-xk|fmFPYs&u4iaKwhOyP(rn_p zLsv|Ht*^7}wBh~~()NTQMOhxI>V^(*$gF9Mdi$i6?Bzt@^U?sZ?&^?0%=l6lD}N8xXmMC;TYR$kz5w@kuQB$ zIXhYKAA|39%!`4p+bww8uF2J^;;#;YkwO7JFq<`r{wgq9lfQAnh8(gJZcI2hXJI40 zqWw*7w!Fm=8tJON2{RakPGKO{F7Sr8nU|xMrcujNX$8zxZd;ctLKk6T+*sP#0OXtf zS+f@v@~q+17us`#Vh(HMGCy?6T3$?1sS&MTNf@TE^Dr#(MurLCWc_yH)=%oK08+`R z^<~)~bscM>?}i{@AnPD#0kv2lu{2M~5>70D36vBWm(iwDG2@{aX;|kY4UVP!yiYh_ z2ZH`Xl9*G81sLKoddfnsb@z=&ypj;v%`dln5EYY*)x3D zfVx2|8i8xTCqO=;0`@t3dm?LGZ2ZysiY$^hvk?7J09eKR?%zsrYmcz#&8`Y34b*qE z6mIWWOa$z3NfteAgR$FcR52gh-`7hR8JG$IayuUY4}a1-3(6*E>*}tgV2TzP7s{5x&o9!@_MjpBn zO|5BDhryp(t&-#40^$weuj%n$Vsq)hOl+UB!@k>xBEOokK{|16jK~Uf7LSH!1Sase<&`F5U{q|fk(om1j(dMl+DwIoUm)^?JrzB zW7<4VDPrDoN;m47-M?y@`<@C>D-dl&uCg#9&jM;b{_*9OMYE|eJN|f&R*}5<6iAcl zGRpE;Ds$|FY*qNo0lGQz0<_tpI! zumdj$zkH#}e%a2SJ2!jn6WF}7dt38#>pqH30%k$Yw)UYt@0mOANh@{QBkAbYTmcD@ z^%cC&zxe+(&2~OHzWus*x*vS#CccNwGGaS*1!B$AB;0(gJLn`pbSq~c-LrPMQA-)n zbG5WxxiETJLgVpzf7o!~cHIyH(Y-Dc3mNBd6YzisS-S0?vyeOz!>Aa2RIGac+7fOo zKpR*DVkZQ%xcXxZc7s?HVQiN<1I}YdxhiAL{8bPcTFID^ek&5YV!&)81bd5RDJF)@ zt4WXdibP&KCGzN`0gw*AU$gdvF1$KgY!Zw`_EfvJ-q`ME*kTo&`08=ynJVBRqOY%W zX~1_>LA2z56PSz_LrgOI-4Cj7a7RtQYbfUM>M;UYTxkRSm6pdini-^pc=eI^l3jBxD2fpKa0*mi&IxU-?2Ss`!*)cwCE>h}U8d4)sJ zps-LW+Tj_z*$f*|cWnmB|F}}?o_bsDlW&Zt0~|A3INgcK=GspP7ca*fBGD_+X5%lH zO|dh=(KrG8qX_Vy19U|PFVNY&($1*P;|A>Z{T9;JUC?HoCb6&B<;j>fnp&{-64)7I zXTG$m;*6B;qM1t+zF z$7%q;KWV3Cr5qE5PFfPoV+;yM_dm$;#u=@-6v) zqna{clW3=TvxkXsfGHxp#&bLK$@2)O+{?cQnMgZtV*oegJ|nFV1=9i zH2g>x#1i@2Z;Ny=_G7^MglP5_KQp3*Pl1>zsLx(5jRI(TmCB+dvGce^@Ix>=Z$gvR zQ>7KW#rt_w!pSB}|K2LYP1ac@(6PD z9C_+|h+$dd953=gGp!CcSe)Lv{U-SMAppFbk|YnpL4Nwus~aLhO;*eUJC0wk;cc*d z-Uhto@UFz0Sq{!#sY<1QN!#L8C830f|FE{j!+BMg3)x8f1wtuz^W5-zrs~_@2Dtydu317YqtQ+FBS{z zMKYZXP*YFG+NbCWrnMrgj99l7%<*i=fTDXcFhoDfWleXzSGT}y_x_j4%iC$Ydo0DW z_r{&OyV=6B>sAN@(bVu2mF+og|I7)dm7|k; zBbBKMK!vLaLIlCc_fSy$>hnflgz?m$TwYtw^lT|=JsBC{+kg^-)Ymv>IcD2u*Jjy% zW`_#2l=0G+wLtftbT({*HLr(iy^2+;*Q5~Xh%35s6LQt)jPMC82a)8-qp#)bWquUO zZ{qf@d}FQz_o^WP#?j9*HaS@ounrCwSAH>~Ro39V{6B?Yilc?#d1sv>$l11hwE6NH z3BqT;m_rv~^C_-Ma*+~rpbX|tI#{(>XRpjbCaamEMP>FZlv9@qJ)6cH341rAFsV~g zQgXEEIFB(Etaln&4;b1;UBIy7@K2MDfAkn5| zRBBJ3svw9IO_Ry0ZqszJSYNLrD-r_9fPsZyXi|-qnfx{+N(g)F5WI=2R7k_fkpZ5$ zd>jn}EGR(~61>qHn(1daI|C*lfg+oD?$Q|?-)0+MFLZw2*2{4|1{a>+Pfh6`LGsb59xr8B*u42h4=4cR;MDy4I7XXEi1 zg3kDZ_8=W=yVMi+q=cnT1pA4--K(9@luR+E%h_b0aH7Q9B-jiyYSZ?MdHb`R+R*U4SUK?( zadY2mVTPAT+KQ`NerM!x=R~yP-&s0yl8z7TLZeNT{ShslW}HxFGQ-|q!w^U%;q#ha z(7f8WPIa(#f+9bQ=x@VX)QE!cXG_B(VFdfU`H89H?xm>dVMrd2LrwXm?lGDPpfOx(ZzERCUjE=HHz7aUR6R2Cu$OCs zTum6G(i}Yno2G%cnP?d=FkhGPIL9wds8Xr$y8scCq*N(S3Uz|SttP`_ezS??(i4Xp z{nf?)PZh!25-A_t3Tu{?>v{Zif1szoUx}v5caPwB=L^UvrG9cne_oXe?5eYp8>O23 zmR3euF^{@eD%-3vQ0C^AI1~LKxa&R<#3sv?K*)dv#keW?@IAmC(tlkuIX1ScWU7qd zS8p@a3OR#8%rd*$y~qf1=Bm1D-Po;syVa@F&_Xac=TSuKWd}RA$ju#(O-@`NmsR}% z<5MeS{W*g_&CdR+K?@3r<4M}F;+@pT;~m#X{vHwmge!xvER_0TQhW!iqZL5`r;7n_Zos`Cpel800b_T3%QbiB zb+-ELu;!nNpLR|TMcI!D6t2(~ep^Y7y;}`wdf=Sijn} zwMg7?0DB9+4lhb_jXZBzhT-u}du6{Mf$R{r?P>;b)gh?g_zPT0p~&I|3#)(#&~eG) zD3n~TmdMW!*W@09N)p3*nl7(md5Xy{M{C! z4mvI=QBOApuSY(~(B7V)TH1hs3I8ePbZ6Q2Ep(-?Kzj7mS=~t;tIBA(|3#4t+3L~n^mYw1 z#MRhc^p5^b0Q5vbclFs6@#f4o-0`2#VDl3qyX)h%yV%PI;U5_Qwx@?)Q!){?JUH!Ln;isFXIT9b=EwW7rHs)QBH7hGrx8p!90T zju4MkOX)PRxk9=h>9IfcN)n=klyaRw-DmTDt z=7bjj4&8bKS~F-HnSy3GKe0dzHxFO`GFS3+70VE9E$l3tvW!6r?@jZ!M2|0hvO~{9 z148*&r78jQNTGIh-310I#vs?;P5MdbHV2m!UgD^U22(~+9pI+Moe*I8cN1dE7yS4; ztne4#IT3|OjT6r5BGZFADeU+j)!s2|u!#|0!TL{?C7VS4NxM;0nSCcnzt!5z(Z@7X z5|fZxTLuFj&OtqXzcbz(him>km9iNd_SB3_Q7-2i3Q2SHAn~$r(?gmPKxjq_H4GLF zEwe^nt_AYPRaXQ_k!M|K6*V4?(7b;w#t_55FN^vJ{DwkEP-vY-a#$~Yne{$M)Y`!_ z$bvyNZ~5PHW7Yl71*exd&~K9P)NIIO)_|=u>v;Q)>Nlr)(h0z`It(vhQA1IYe`!r8lm?1j1#5{H64%H&D`k=&7I!fS58Rt}@ zhWz^S<`fJ)$_p4gW_RC4vn6u#kefKK2#-aFVGnRTzzvHJd{_pnS{E@O(`28uY z=NI=<6CA6&=6fJyjq9}rfW;!8n6OwP>=xCF%B88slm@lIF@U0WqpD$ZD6w+M{C=in}tCo~E;Tw3zUYU}c^ zqG}sazMd4tv_<-?emDNIo%QsG>sQ%{bwUlgp<5$Uf!GM4^R(TqmU{hNss%o8|G~lk z&~%nTZME$dt^&oaxVE?lg0xui60CS}m*DPF+@-jCkW$>exD%vkaCa&0XTRUfnc)}1 z4+uMX?q}U=T?Z4VE{y~Gi z3{2PLd$+w{HA`nLnN#>e#X{}Ce-^xz*JCUo1HD`jD0b+|ri&;g}cTX_w#b(?w&B#%HVa6KPzp5g~n*Y@Kk6ACz zVfE#&5MT6MV(pvtlbXAQ*(&C9W2Khk_Zjs-X-%J`v~(#>b@f~hr(z+GMlWkqBW;7- zp*NZ_bZBy(*2>k^+PnfOb!V;PQpoAaD?KQvJK0-4f8x(MSOC5`=*#8B<+Gk- zOBF3J(ljf-mUOMF+I2QW=DPu~4_%m{Y5&Z!ADKSw?Fe{fvOUojOYu;Cb3pG1Lw|q!L4F@+j z#n*Pr4~%cq7>#}B<~cE52^VO$gBt-o;+N{F7PERrD)uYma*uR^D72#V-L%1nQNq|; z6V686cg`zfH0S4*#8(mH+yMg2{y9FCfcHE+&yTJnA&vtbBo-G$r2tG_r6)a z;?*PbVLw^DCv(d|tx+y^G^0Yv;WhhdhWDpLM&Xw_MibNgqjQam_g%JQ$LO0s4vV=j zHwECua$~VQIC(p!6jCn%XCfU)q$p^s5m4R$?T1$NBy0EmI&OVHIpL5*y%rM_Sz2&; z`q$Ll%U_+d&6jFap`zJgsYj{wDi9FApj^_H*ItCLT+Q@$=7|?QmcS|1c}>mNR9gsL zz4`NjQaR;Z()oVA@qC@!$IfWM&WJ@5wQm~)di;I}6Wm?}c__9>Q#{IM|) zx(+O~6t^E4x#&A6!1lK(Z7CUg13_P~O;p(o`!Lvo0ty*_m9TiDsRYS2-QkD}T)dQY zlVf)Bo?FvobPhvv5&pXW(L|`&p>iY0`vYbCfvfA-+Wmxz)%h554; zn$!Tt)Np-l6Ahfxs-G71HCaU+7sJOT0M;^}mv!Dh99& zS6P$FO?{ohpRM7sMrz5DuL;;XBODHvPLf?_-;S()fiM#0bf?c(RcN~rt-k3;>gT*yd0|55FwyYET`t$ z19F0vbU!?3qA84DO2-)%m#eYk(*pxb7IP&_CcWUVI~qPk|=-8um3l7UCVpvHRh?%kqzHnIRFK zd)E7xVFwdOcWyAwv>)0`WDT*O*^E!*{t5KEEb68wenB~6RpD2G^PTMrWA-!0ON+$O z{UuAM!IYj#2%&7mg5gKV5Ei>%6$+^4e1pUza5jH;>m6~nefy0DO#>?a#yt}0;ml8_ z(^}v`M;W##G@Z(;zQw?oIse|2IoM%~J9Rv^%t`rXEl3GRLA=4X1iABev+VKQF?hny z^b++V2cPCiOxNmDiwfNRb$@-RNx4P#i9TK*-W_{$#)huB%wV1teV}UBhHAjO8I>$= z;7OqDh^KP!UKT;}sWOw6adeAkYhf&T(KUhwGbJN4tnR??|GfZz7OCfZ9d{NMUG*kx zfdWwbicGV%^}&BZXd|P<-;+9v+BpRZ9(#}#;!Kn?+>K7$WPbOvs^3gtWo?~y1`L3= zwS4cbDLgN51cpDz<2GmVXmEObSAqZsUXP+SI)RP93v;0mi2L6e;G-vxSi%N}`J+^5 zOXk)Ko`X$g4d`Go1AlDUqm6JSo^oI%9q;yRyPS3UPh3({=Nr>l1F0?odkWh3V}!IlSw;*ha6SP!uf6`t3HuVOxcnkK|M;)T+SAP?&M0qzui)H zJ|#M&vJ4|Rq_ekKt@c}5UQ)~dJC&mQiXGaAx)0mIiFv&FQzRdXuJZot_X<;^c>)po z9PJh#TCG`{(aR@ZqN`b`v3XghY= zShTcCj4b^U+l+;KIq7r|2n*tfxDUFksTj1Y&i}?AEX`3C_3Sc(JfPlHOGW_CTzhCT zVL=#rSoo*zLGudi=quDLjn@)YGs4fAa9?@X6&!tG4ANr$d3Cpa7gwn?)TLd1ed`M7 z1Ay_pNWP|~$bWfVRz<%4LhPa9Q4L4j>j5qe_X(NNd-`y^)Zy7!V@DWA z1loTlB~;D+r?f=%_K~OltUp-~_VOKPv|vrPv-9TTwN(`fWnsq4X% zN?!Pz*7O3`BO754v`n|!$)AN#uof#M5g{pLCJ14)LJ$#6TL&5t0ftVp&#h^ z+S9JNsGQqJA-j(?KMVf3#M6GNH$dl!dW=%f+6jm>E7PP#Csko0wVfk_=i29DX!}h4 zCPnfo75wg+E`yOKL){>>ng6%*r!YMjV-j8VwV?cf6b;p;MB+P!UwDZ_yH{VQzc+P6djk6u8#1R2g1z-oArp3Tos}2bX&5W%@VE*!G-}+ z+xEdF*JbI!I;cx}`W*{!&*D*K$2CQ4zE&ezlw@JKFg0a~;EVpLgo$p~&0%a>D48UU zZgf5!_TeYhl?q|t%T?b?%3OsdjW;+u?NU3#&y^{; zz?~X>m?jEOjevA+YqO#DZfkAfUW?scdV2;|(|#X=HfKP{F1nNjUys z#)r2qBun@?Aah4eWs*se_hlsQE4gZv-g1LpZfg4Y?n#QjlF-y`#pq?;BpK!H)$B^* zrP{VGGtx?*cw*OROQ@7`7l@H`C;jV z371jvg$MO$7RD77DsAbP5f94_7CBy(a1!P5m4}K7ri%dVerC=)2;Vb$N1yQ(s#j`ot>zEV9tAEI#-QP_75wFITg4$wyZC zTE54brd(bLdedhLdckz^oZMsUl{J?9Or56D*YbRVNBK-PI9P$xaXVWq01Uf$ZM8o@ zj+AM3g0+L%G*pafyUacuI}~{#EVwE}X?`#*9UJ!Z8W- zsq?%6P%Y!I9+z^;l165n5Fuon)c!@kU*cKJ{$CW?2nij8V}I2B3IuYCHJx2vnY}w{ z55n}zf=-eB&&+-!w9FBuo|97_;avVM0sJ;?VZd0MJ*z7`7NhItr(C3O!Z{R(7&cXHW4OkP*tL{D7E+oMsoS-V#izs_!~%r{ zZ0`HW@Y9EL_ES9JCmRZn)tCQRsO1b_h<1n#vYxHJzMit;aerzu+e3N@JQ<{pT*^*r z-qp-BgER3k5NzQJlWWI4S{*0|v!eRcu`G)T7$Y(!XLi1D%jH+qhHEYJ9~}m)GOJpkB_zbYqOiswRB0#*DqEowI#P{Q|ikC`EKs|iQOjDLt@z|cFYBdxzn0@OUqE?A@hD$3`0=!pE$Mx+^R0%IUc+iChg@6> z^)yjQR`%~ZQOcI0!<}qWd9@_0ixadha`Z?#@F?}wXwc4*68 z+-PL@60k1jU?6-OfaqwU>R$e_4J3z)$MYl+O}in1jtdD9kC7_YKC z_V2$3_lfuB7YkTN=W)-{VH#${aiREB(A^pX5_2%TGaw%i9SUrMwXo=_!7v`xH`ksL zxu_ogn!0}OBnHMNh&?Jc2) zH7sIRHkFUR-u$^e-)TA@`=IanZ@4>PHpX|A#@&OIa7_14yZqmpI0l+9)YlDR;UO!{ z4hqmDIu&}00qwj!bs%NGB}KS>pBu8 zm1UA(xupZ$;+D&l%pdFwuq2I*FdGERb&pFTqbdE8D=P^$Sm#YfE{hVyKPaSu#i}k5 zQU8FQGsw|fHsCm-k;?d?`XMC`wCZ94&aMpoa?1v*kZ$Q{NXfG%D)kr7y-#*Sb~{T4 z0_;i&oWXI#Nk&xXrJz(I$GRSaKjaN7eOOsONxi)iz|KR&rsdLTDMV=%39B$ z^26@1o>88znY&3)cL-*ctxwkdaZ|cxo#>{mjaptz;a-N2Puh6Q8Nc-}JXJC{ZPNcS6_|lIY?6#Y(EXl?8P%^&OF2vCYaa1hPxG1U z)y(1J5wa0#nt$3ajlPHYI+%B&FUVz-AW~aa^luZ{9gkal{Y5!l;ZnsE?z~5m0W=Hl zM@JxDI{P^TkCj{u_MTD^#-Nj;zX!^Msc7#l@E`R*puA!!-Q9a0686m6S;xX8-w6}u zlO+liH-Kz?KEL>;gd37>Dg4(t-ll&=h3X}?1TkKGd_e9v4dc+LcM!pgDX=;3l#T^I z3EVPj{!;=|FvK-~gg}BZK7Kk+vr^>CIM!IeSI{q`5_x3Md2Yp=_0K&XTD>80^A^O7{!K9cKAHI5bhU zU@zaM!|2qTaTvv(U`BeePcd@t<=z=6U22<{Q^sw#^ZvF*_*us1%1kJ@kW;iHYGl$+ zcxc}uzPFbalGQII^g#V95mlOOwINM>=_;ug8!$e3Jbn8~R6G_Z4pQX(GUY7a?mAaFGolh3fuV1L%wEi{Q?-6+;`Z0R?3lX(6ZWl+7^HS#vmzsG~ zAD;t_Rj@SLlo5}LZabY76q#mZjpro{zw6Yz{Z??B@~*dwnpbzNYuHzetkxd0)ly5r zWdso-AXEI8`TIv2yNY1&AQY@jKroXKc*hxd5JCda79M`^QnbJMONpgd?R!1YklO4{ zNv|hp-|g<9Et?i7JF3pBBf%jT1s+E7(|k5V@BT7KmP-mwXZ>}#WPyR_Y1T{b*i8)< zA+wSP7U_VRGo6S=#%E`|;fUkUGF+lArM@1=H=n?nHSW}W)YmL@v;H|QRdk9inFc@S zVBoryl8$Zy>@Bvz0mHx3dKhu){xT#wQAmze@iFnA=D#oVnBq8^MN#Ein}Q#8sW}U3 zgGa(1O_7I58boz1^Kv58xo>x+gaTn`T{eM-?tz;ckX2W=)#Vnq%{64VjnR0oHQV;k z@;!m8UH+8c>StP|wzqZn@A(}wUAyo694oY?wm(fb%VZV3X&0Yj8OzjWGwu&szhS0l zP-g-lwwF!aZRcYs%{tXtA&?2lGCQ((j@`TnQJ*&UZZFzEBqdW%$lUI)sS*ub19j8E ze1fryO!Eb~Mw$MU#y!yI&TY?`zDNy)xg)#Hu>gKUCBi^rh=$ma?4K_UWZ{#Z`Bhz` zyp#p!T^dBy+;QKPt{uR?XZ^UU`hh7*rz!@@zH+@i$- z(!Lyr`RlZCaMZR%e2-q&U+Pou!tKI$UX&HuU93$7_M+CmX0)`x`%}HxEjC06OcZ5_ zCV&30s$!>2ltyc(?=Pt8aYGn^Q^xJ_yhFz1`So8+L4V&T2~&zY+JA>#E*Tps4a5-X z1PJ3S6T-()9xxB_nmPOf{O*KoEY+3Yz^GpPl-X2UKRb;Y=8A6je4S!@l_OHNF?for zU#6MHisvs?vD1ZfTGS2Ys5`a2Q}ms}mZ09695Zt`XDQMyTWy#WG&$wk?i1lh)xtI+Iauy&*!!Ct z%~I2uRYbBL*5$-v1fP^`aiu`aGNp62uPP+r8w7sHY0pR_n*n76CIC)jplv>?%INL*m~${w*LK>~#0Xlxflr9_Qx zAyC^>IN;aytK>0@f%#d|0(;0BnRhAynvN7$o%&R2EDmrdxMSLr0of%6psRTL7=0$u z#X->|uldRYBHdUSdUeSz=4s8K4j~jtf1+~7eP2F83Ym+Z$1@KeWbW5xeTZX0o^ruX z^Mmq#eQVGlh)swS+#93o6||+6JntRCsCp2JBY(&rWS#mKLLn0oK_l&NjZk5FFFQqp z@=88~Ph`GMG1Skf2|91y49F&PHt(h!7}V+QTTu)5utV(O^o7Opfd7R@V`KNR!4Yoc zs+`S)wVC9a-te$TQYf)3FxGS;D7~(?I$H5)$=3St-lCx`n{Nu)D8 zVmTmVC$2nOu}qCU9pn5FGpi`~fMn%auf4xvBP4{v_u(1~_vWQWUcFAWOT~Y7UO`dc z^Z85{`a)f1EY3o2y?4X)IBCHNxNxB8tgQ6ARU*siHzo9i(!R)fn*v$;wx!f(kdsJ~ zSx_9hM3PXXVHXFP3ijtrwqp}xi*ETJCN1iVb`1DQ8y5@dIoj+X&tl0YU6CnGZ5wPx zxN=Hb5KDlUxT^9vz#+BX_y{Y|EQ_U)*ly0mpm$=ryzC70pH{6+_6huc{aL~!Pf~AH z?NUmkzed#)7jenwz0IPmjOUg$eC>OKUa!^XK(;PxI5+mK4&bfIXMOH1nKHX^&A#Q* zb-U%x7^1l>Y4V#`mXA06R98ZbKDBwVH8_hz-YA03B?6{ z;;lLYf+|ZkqGV!iK*=K$48{Kk3u*g&rm$~tP*C35&ET`q4bk)bni-#+%-Fut>*2Pu zQe06KV6J!I>3DI_9IRqknbTB0+|$#ePbV=2X4C!-Q(3r`5d1H@PdVQpXgV^TlK{NN zac-_O5-{BHmiig^$1+>zUn)#J$xs=mVG5{+i7zrW*gsmh@rs+gwK`%111u*MI#H3k zhqPaqu81WV%)wLs1@#LGw=qF8G4M2^Z}{9}boLl4l51#?(D){BGJ4T@ z?36;C5KmNM0;a%w(1akFjf0zeFs5w-XN;ZAVSSTvTsFGxj-XT= z+yv37w}oxDNd*Fk@0H~pY&6oMW!pbZ`1Ml9oipY019&KYk=4BZ&rW4cXG-U?_x^pM zN$k!i(a>DavVD`~mL;}e&>cmFIH*|{-SX;@^6n_)@fo5~Jm$8AtN6|8YKm{8&P*Qn zjxjAshbJYLQ%X)YkB+XBgmqb8YbFVik)V{oY~r6&oV1Ug9n#8h{u})@cgu^*LFY^j zTt@mm()3&FY^6F*8^?u!-DW>%>Y^iD@GrA!;1Ac1bC9l(OXPWk%B%8Di3=REnZ{1BzP3kmAwO zrj;|OHt4z2qbnDHi>JfGfif08wqQDE9m)%2cD5|7Qpm$hI#?sUEQL$`wrM4;V9DHQ zp4Uh9Rk)nr5#Q$CHt&-UZ=o6~%t6oi>|H8JYb1MTav&(ABM=@{|pvL`?G+QkeUA2=r)t^xqZ4V$=cadhWDp1!u~XX6oTTZ*>X zmp!TA0_ll{qKcwXt?)r}5&|vA?H`C1pE*>RNiEh}qU9_D+*x3#?-?1lVvSv&t32u? z$&kMnhLs1`w9HG`Tq|u8!G%N8GJ?ImZK;Ds=>6Ef71m8k^12iy`;2Vkh~}j8n87p6 zEF5sB9QYis-khaML@(R(H``SDt_WmK!=kXpJA@KG$Vee~Afo8rM3)#`_&*8g#eX^W z)PPBg4$h~cNK;$95-DmFn*A84f4lhBYG>h4uHK86S2lfh1nUeg5W;0o)FLq2R3sFo zkw%AZ^v?>-BpqZlgX7E(Oxtb$@EQOwOF@YwOlk3E5=?%vM-mKbWNbjNT5zMu;kDi% z>up60Dxj0^0J}$@<|DS8lV;AIx(_l&g*!!qyz_B1fjJZCY-gw670CKkO4;1o&!_$6 zYq-=LNNOAzg0N8mLury!KS)CdiZMzlVvsQl{|YIo9GU2hDztP<#I>1+X)^=sBpAeC zZZ9z+yj1;a9D{sV7oneCKeqT2wK-R3f?0;@n}+`{g)WnYl!7>-U=R%@Mo{Y!U}pa> z@R~23^!tc85WB!#Qg~=$>$DZ(V{h^*$n8<}!p!#v(eJmf#3Pk@XElA?rjxgWR&-!rPqoRxf>1@$O#wQMQ#0tu>8s zSUXO&_4NL^TBwdQA&!!Ky>dM(t?rVN!g2)Rk)FDw-a&wj>hW}VcU?Y<5kF-1)H|n@ z>6(c8<&v7G1)FHRZkl5VD^_z^^%6g;uwh2}`61BpmfA`#2XiTqLOgQv_aLmtIm19g zkoG6xC3H(es8$#MeN5~QK8b^A`Dy#fF33zt--hmqlC2s(y%>w%YKxslJ~tV;1t{F zQAWwF`ZwvD*J_8{;Io;H&Dt?E{Ja(qY_0;U>G}d@jh1nhwo{UX7^-aPGvxzK2#@0{ zlNe9#DS<;bt*};0j?OHi^Fa7MQ~gu-QzvN1V*vhKDC1cd`;7rp%U% zoSvXmBHq99^khfgwzVX`KzDsNU~O5AmM{dH2tl+MBZtU2$S>vDkCg-)CEZ#V7j_xi-CJ1Ok@; zku9}(#%3M-nPMmF@tI?&=FoSi!toj}yDQB*)=t1paGMqPZ6Mzw~6War7N_=DS1+t=HU>jS(yR?MMFax;eu9?WRbd8OBmlvuLEl zM`eXmcCoVGugFNHuG=s}7+DaaQM~VrTu|gts-1}kGJ*b}JPwWY#9iCkS)Ff7HeUu2 zPcuT)U$%cW5W*ELgqxR%Z@q{^21{bz-+gDX0Ch* zSgy(%`Mt!hwo2*%yQVgNu_@k!1yw>0J1ebtxKdDpcTz#R%@$b=KaD*gbP1idU)v#A z8!B5DS4$`bM$dTVIrzCG+SYO2J|$u~VQ^rO?{GTo2jv-r*1cOpTH=siuZ(p(HuywQ zzhR)s(`=*t0neLt?qV9RFMK}4CoG@xzQ|nkbiGKp^Q`06J8zp2`;MFRj>z#b{(o|O z{bQqIY@Re}zXsY1C!Hb{Cg7$BiWIF7MD>Q$eK4|H_k9$|mJ{Z5%Fw%`+}W*vjh$|L z-J}?r&z5*+o;n**#geJU&#=Ijkk`@AiEi|538g#K!ej?oEeKoOz^l6@A*RXYYwC$6 z)yvp|Ple96&c)hncuoy^ztl`6zWk)kDTu~?siaHSWT;6+E50@`1R(Tjnl7|~h=~$o z?X5L};y3xDckqt8(`Rz=j2s=B08i-gmt2XL>%)3Kxag7Ai6NiA;K68?VFE-VA|9Zw z9i;0IX8q3Wa%9bO+fiLfPKL%O%jlZO2N5pO1KP8bJ@J5*a zutA+vIq5~3N|{NW5YC}lyrGK zPFMK6XJE>z(~J^8=P8!8vSVtF4*i(0QAT|EQq-+LTE0Yyf?4sHnyjKHy=d%TVuf#n zDQ_N+V1!Z}OO(A}42S%+lU5t0c*<2;#vQG7muNn5V7ewZQZ?LD;Aazzfok8yT>CqX zG}l7r5AkftiX~ApBz|WfBO5!}DY~$=JzIh9y;+6$9z?wLfTQ%dT$PTkaZX;s2b9-f z*6wPjn`JHm_jPYExckE_=YwPj!$|N@q%B&4Xf8&EGp|^d47d!1Bta?QQeie?ABOEe zEr|wSx@FN%GIiUU{7wW2KnC+X(ixnPGV>Ni^MaCAEAAd=ojA809?hgF^+LrjVL$y6 z#uXjWHl(_YwpzP;|o!gG5O@&w`hr>D0I^TBs$^)GN5zxkv86A^l zqHg7=1QGFm<$SJKTi!u;Q08PzVbDS{x;0%zvPJRXf*(*h?Jw%JJ~{7$pV#0|{yVyE zLCJc8^7vA+e=RqYp_wg745}()ccSb{Lw;o5!ta2KqjZ9m1<)l;`sR;kYAF*VK*-Ct zgF_#pn|uJjMuSQxqujXmJNL5^b+;p_ib>6;X5x%3lWe6jp>LK8p$y>z)ju@b0J_qX ztKKG&6mkq2zVNdi+AHC%))9M~?}1d&ulA?Xc{?YZqiCdO(Q8#Ygf-B4Fbhj;A-(Gs zAlCS4v{ItJMoy5aS!nl*hFZ_}!ve{TS>E$Qz{#@PH};122uVC((STS^&rpR5rV>44 zW%xAs4A8`W_B&gpe4pU;|USYc1)9nsO4v&!*4-c=v=Q>V* zeKN4_OB2OE!IO}Hkl7=38Vw;4OIVmzdE_<7Gn7ScTy<>mg2r{l-ZOVyr7X|Vzn{V# zrDLgaric%h`URtXMjqz`uU=r?y#c<&TvAm@M-#)LVTKSPjFA)=nQ%p&@|ifby?dO&z4aSfkO^c z__swAZrS0!O31E9>ejinuFu{3Ww%?5&t(%s)CbUpk3(CZT`J5#(MHWn$KQC^rE#lS z3MQwF^q%rNHWkkGh(3?8Ke{B^(2F0G(6%lCYH|6Ak!|PFtiAI(4Y8MQ^oD-g_8%NA z6p@zc0`2A7msU&T$ejOak-WdIV-`h8SEq6N8I_f}C$s8((h8jd*hDI4EPg{RYaoa) z>~USFxSvKx9P~QJM77T4;3ZIuW8ZL;;B6_CBylo{(jdTz=v-3!Z8^Ec~&Wwp(&mS*?4td5I3(9oF1 zY;EPab55kl3v^N1vtOi;i)<55dnB^V3nDM`4W|B9m!2|YlfGI={U<<){s~bpF~0QV zh?|!Zrqp%J&rKB=GA^m3hpJ8Jyo>U8KXT}yC0dLZC741D@^3wY-Qh4X*YiL{5R94!KR}ckJyX%^FUhmL< z&crNC-EapqPSTENGU3hK+>M9B3YfS^IP}Pie@s_m$~lffbS1D#o)Q6KFRjK2rcS&& zHr8P2rwik;ZR9l_QNvD?FWNGiZ)uSHo)is~wzkbaK9^tHhvgH&5vgy!jz{x7U04<< z+V-(Fk!KMaPctQ_=GH?459?eK>+A|Rq= z+G>?A&%6d&d-K*@NkfJH2G>bT7ObH7M?y z8;n`VmYoBWu1}lrE8|a%o<+ZT;1SR{;sk-X8WnpK!E-3r0b$SCZMRaM#wCgPNuftuu?ac-Ok;j6ZEC9_6Lb$|^aY~oz zQp;87#K}z(b4wk!YO5!%Wh-UzmR2OLyRdx; zWe;9JoMUqKjWGXSz6mXR?eboVgZs7nn3@m164R>{a!uYqY+%b0P6*H5L9E?HXrgRBv11ur}R}99tRH@Xeid)1)GncBc@Q&z(k5Y?#(5wK( zL-N`gARCufSO5(_R%ek-G|)n{@IqlWVJGY6FFbo#MeIdPWJhGJ+(#a~Lh$I1Daf)5 z8Pg2a4C|Pxs;fmyj92e_d!LfC$3kbM%gM`mZ}%E>4bQ6k>Q4^!MYkD6-0vyy>a8b_ zol=+7t&A_4NzeCpR*qasrXS^C9;emvopQUQm^*h-9d z^?%=pd})~eF_=k-e*G%Mn|}ZM)qdT9VH(CNL;9#V3S4T%nZ5B??R*vp%HsEuKDk<0 zq;=dxbQCPvaDhOb`7uHe0KKGh;z9WB_dys(JvD}my-n8-CE|(iqJJ$Px%0+`MEwaj zowOoQ4DgRKrNb!`?6sc@T`4H+9dkjU@qrF7e@#M^-)Z#_#=Ty~q~$*KQg&ij=Gy(} zNtcf{9~nxaBw1n3C5;=#G#JgL9@h_G^DFCU?;V=_ZBX^SrXCRIoR=# z3@S?`&?H5S4Xl(8Xs_8$>AeCPhtZAXBzdKA0T}I)jca9&N0!uIgm(}v^_!zawJKsF zkRjo~WXgiLw?a+utEeM+1x07+b!Ou4J0;u;-RV2|xBWoP?g515IY z0CdIODm8<8ed~7JjLNHQzG&Wu70QQB%5O}G-!(MWj41DkR_?@4x_2v3uHMWCEZ!%1@;&~MmKV13_oNg8Vo;KPJ)xv@^2!kJ z>8j}i$F_a|7sY^KL3$vG?<{34|55S~9|B2$q%QK-ZGn>68|E5pt*<)m$$(P1bAiRD zAI3%|L6BZ;Wn7PKGPt9~uCu&g!cQ~(dDonc%g?nl-=oDyZ1p5WArej6Bv$2satR4b zxLvKXX%H)^zJDB4g7`zi0G>H4lRr_5+OnRMs8AZW*Yob2v{0mIs(W8u3{dVg%aqC! zki!UOod+G8nCsuUCvDvED6$g^&_!;Nz+as8VBxIXpngVZr--14#F=P&cLDXTz(p^% zkTLu5(CjvI<(6FNVVH8e$q_z*=J`EZ!YVYXvxlJf>(OnoYX_y^r?$fD3W3`FZ@-ZE z%Ed}FyV!3xp*#@r$VLOOKL1$ktAZVOzG$vpr%LN|`G%0DC^fy|>cQ$Lk*m=Gh7=3M(Py*AmbkRI9gIm-bxh%rK@QUg( zY>%JqMY2Y?-U0%{EDe~ca5XymS2!Xug1^J)Smg&O}C4_E% zcw+E*-lfjgZsdwwa|H(VS1RpwBL~w?o{aH$m$}Q|a@a=^$(3N&{>*EOe^0S6?0i}q zUVFi8M|j5{BVji(S!4u)|8>JGDU1e2YW{lhodDbvS`y}nQS#LQMcd5Pe|Oq@E%Db0J9}0SuDpg}Y)-egN%(PV=&9xpK*={Ij-{E&WB08c@?o*NmPo9oXFgM$| zWUL%bUpb|9CA#;-P;`G6#InwFMn_lIuc7I7ki7Q8;gx5PtSET})uM~8YV*v|`&D@| zAgv8As&Wg0-9|WR4YTO_1j(0*6xGQV)kThQtyfAV(VD}M{Q7lC9;5#I#IYzC0ijEH z8y<+P-rlkm$uD`2&Neyx_wO0Y5qz+LyEoG)YFI)^KQ0aVgQ)O zVSn{^7wj`S|6D@yd&BUymOk&j1acfe8D$XBmaI#ZK(cIPj6KvQ8W`L*)wcOy%?9^{+b)*)FtRg+dA{ubNQ?`egtN7l9*oye3l=weT|+0Us}RiN#i z9rx2tJV0PU@{oZC^E>nUR1DnH@?v7WJ_YUy=4m z=J8Pv(v0y;XS`_5i6l(;$w{w(2T2627e~zWT7r`+^ye|%>BTIAOc3I26fg(|BUd2D zSpdM@F`OSOuQiQ6uKs8PJcH(}#OWl6f5Vg##KCL2Q_i2@j@4iqhEJBSokw}#dK5Nm zpS-}Lze%auYbL&?ZXhFUH+C&z}{-7&g&VIH{eql>oUa zN7vV?pEIt}eI*t!M~2NnK}xwglzJU_1N z{CB=RpJF}#>5U+a;O=v&Kl)KtCrU2(E;{0LM%6{!e`Zj%Uo@$(Ffv>RC0G0jtNQDzK!)+?q5D^!0^tzjn zPl^A*trI`S!YE7!u@dPYhQrIsnT#UF32JeVmV*o?GV5F&A$TutroGG0&(CG$?q74i zeUar8oo(l^+t?kl!SADH_&!yJ>5@sq;p6MMxSR?@#RtsrmG1o=8zQ7kdBR!5BfJrD zsPs$4X28z2=L#en0sJ=b$0Neq1>W{S;ip+Cfb|p|c4klUcm)JjY?R6s7VE7|fgVH% zbTnH(W`I+oPLpCGLpy56{i4fC9d}>!$5FVm>bnz^O!f0jhMVTYv4_ZAj*@mU@ z4rC$nE&Q7#RtO&7^9JAUGo${S4dEwz%7<0tCcCv)_tz(sZk})a;L|>ioQQ`sLeW2a zEwQ$~v)^K=&g}!|ZrnZmc+*me?8VG6+II*7%%Kjo%#zRo9O}F+73<_ykq8kpD z*^7uklakNrRGe@P)LLp5-r;a)VtD%lA7Y>#T+SU-E!mQY#Vm11ZaH5_N< zNlLs~EsP_QLK924zgBLYV?in0t0#1n14E>)!o0ElRb}%ap(uX&4DYy5t8xJ}vL%Ac zIv;!(nvR>ggCb@PRicOGO#qf(ZPJnBOOH)=YO&@8nomDb3>vj z+PP`wuKdAKB{8%0)@<~^&KM;%GxII#yez`yht;=#iAw9uGxZmBddvpAJsgt52pg(E zKf;7l?U?(M_Vh&1QZG7)nYPumV74Z128JbZmo zvi?BD(9|>l_#TL@GV~HHLPl2p*sC;EElvJokAsy(yu5EsncurWV!!4)LGFZ73H(Xx z0I1F9zxwk821GVrw*gQ>0FX6bw zv(#U?Spk%d%V>k4Q(|Nz<4^Z!>;I$aEQ6|g-!80zh;nEok92o;NOyO492)7CmR7n! z;E>WK-Q66z8|m(P_wSwg&oF#ucxLbY-0NQJT1X|P1Yuh_%u+TSY?PD{Mxrv(S$l|` zKf(W=p1_Ycc2jdL5OWhOIgk_FVdiXFhx_1z&V>k~3>4$q%XebUE{$?j;)7*!f(4Lg zp_%2t;*e<!7-`!UnC-fI17Zn2dx*jhx08LXTQHutW%V@@N#^tIyZ2zxM&3Kk^WKxTkv^r$VcA?EJ zwQAQZGqY?Kh|+{GV_gqc$-f%f$m7cJw+EVQQ$znyZ}38YoNN4axn+&Z51FnMkzc^dA+(J8GU#1Q9&9 zH`GPy;CE+?M%jgS7odn6LeI#Uo8M$-NuhxrD%`NJT>ah|XDyXqyAX>kLVoaJ)o<>8mOy96HM+8V&nxbB{@>2B{R|y67-OBXxIN z&Sq%i;NWok+^zTFcKAY?%`~;vQCB77%9Xi3X^{NTBjLQ3x!Kg&L#@hZ!t~2C z)Eud=pjoh3 z;0@q14vWLs!cPrdN~8~WdfK-ma#*5_1pW-e33Di?7{+{U$+Ui2)!F%NZW zkU6rMF%q=$tmozzM)LqoBCNG00gmAiPG6nRhkI+VDVt z9_%s>wi?LA;j7u$#LSmke>`a_=>a|(H8r|_EgV!*xm{`dtL;z-g?dsyC~iEYDLB7{ zlBEqh2WKKU&HtV=Adw{l)&yx{1N>C7k)3uFJ6}It&dyTJeeY>~VDv@Kr8c#;wv~E) zIT-J#hF8uwu~5$a`n3Yn_$0UB<~R_-r)It7^CIitAIa3(g{deIxs`k_^SNY86@F)f zvy(oW$L;QogU6X)f{L6%)aBH0h2sg;9y-u*kOB{Ysp{GqLS2>MkB4QSwUI}4wA#kV zRp4UmPKVyq&ocY|9h`s5qpD%J+jnp}$5Lv98BDQe5e{zpu*aKr1Sq=z5Zs&R>0^UkVAmL+AR@Mc$2_W-1yKYzi@G|obwcU z|25!Z>~VriKnUnMm)V9ym@kQ^$IhlCweI=O&57CoOhEe4GufqdKD2jTj-!QS@~VLD zp0$S#|5gMsZ4|}ydL`R*;4(v{mnvEn)ZP4od153tY~ch6@vW)hzv_5?`WH^+d9tkd z_cp8M>C(M@ywyFs_nYqp`N4-z2rF)wn1A<1J`(;twP!RiSbw^|%;5D5l-kMn&T#b> za0JIvN8LR6*2uANu2#tXWenBERi}X>l%)bnXR?8g1;jHe=)>W(HJ>{&;#=VvgzmNy zU1hQ!`p~-X31OjGd3B*OAy0Q7LET_nFMWBMGi`hJFoZwZJ{Qt24;8OzK_5_Ac?6~7 zD1plg+sNoBatxo_Y@kC$>sTZbM^4@TJwZWqk=pMi@f1q&f6(u=f1IZ{8ETlATD_Z| z$n2T&r|z;Ee%B2$M|FZjzM@HdtTS@J)EDm$YcAE7m_wmVc$dk-(@fNUq?!#T8)w}$ zNZYy?#&K%F@Kb6utyU&;OXgRs`cegrP;E%hNf^Dm)9LMGj`~gL3&qkb*E3mbvq>n- z_RMn5AoTh-T|CP56)JmaMGk#n^G0 zz>VJD^iLbUBEof+^c+06O6Pd%k2t(yZr(w-zq!DY6>30pmp@fd#;$jg4g2ctfOIa+ z>SdPu)(1hN=YNtsem-`brZ=m+6kb=D}~%Zax`$YMgK6LkDXy_bHttNPFHM;E4}jpG3JhZ!lFDqC;Oe(dsl zRT_$_FPQBuN%FO}>D`4fj(5}O8rVsx-jJB0#PtvA8Tu}B1Ww+nwsD_LRb59ImPwjd z;Jb^qnsgi1q-Y=w1Yn-(kb?W2_gY${CfuTeEawN_QJUj(*DIavtuJeqsHX(rhSPyI z6Dt_Ik_sub$8Br^;&%3wJ5^OOHKnE3=>!L)i($5C39_{sEN6Gc-o9JS0(Mm5NsTmkN3J} z`0Rbsyk~#X`bb|-uzoLS_}C|O(eZqX&TTQtEJ0d9$T-b*a zB^1;B_3?~>?jStgYSJVcm`bQ&eKwnOpOERESQh(kZ1BdS!YfX~L(l~BmL0cWk#wgo z2X?E6%{bz0reAsf8`bwmJe6Wx0ga_XrZ8fskk2*IUjQ;rrHJk9u)D9Cu}#H41{bu~ z>an`ao`NRwwIS$w$n$F9G3PX^OdU_^`_TH|$sv|aiAp)RIcHAz27Tjo1wDPd0?+q9PH`Kb?C|U|>GfPj_$^JIZT%o1k;T*-&*!c8 zB>IM1Ky9vC;lMyg3pMlf+*ll|kfnQ*uX%mL>#gR>{$O7c3PE|mp?l6QZd0i7vn?qa z`(yv(lD@y1A=f~S8nHjCHYRDx;otS z%#uu+ZH`e3c5)Jq8e|Z24fqqx8wtxTC$0K|zIJJ8Zt6edP0{zRQQVGRrxXN?IMaLA ze)&ttDr?0!iqpFpaw3pGbe4ZsAUm>ZkDPCgELkGVIV-g3=A0EbBLt`!$gTlR$sxt$4 zeCJ=PDOkWc3OXD)((04SK6Vy(Aa&^5Q$J9X@L=}dA(CFVRQ(Q9Z@8a$+*v~-iQD%9 ze{o%zg}#*~V9!|Ki2+_KX$MLAch*+OaJZo=$jAk*KGv*L2 zjKv9e!-KJG2fM&LH{axb2&3*C|G1C8U}rtKl>mR%x?D_+F63RZF>d~|8_o<@+wdiL z{PM>Z*gF{q#-D5kiNOJcHM`%}MicDgYxt%nJ1Py80ewVLAVC09b6;s%qyy-BNT8sF?Pf48<)-OD{5K|H}O4}#^W(0~MS zu*)5HWMUT&X$-{#m6_#Tl1)w-xk={}ma!}(QH>jRU2CD4`9G){e{#zU((n;dI5XX9rhN5cGE1^j!zqQB&Y_0o|`zjMUpA z#Tkcr7Kd+ZSn-bqKe~T3CNtJJ?!Plo>Sa>5_tu<7uRsBM;M>H_kz5n#gW|v)j}!#46%+{gS08$)@r9~`FJ{u#l(u$L@8^;F*f^d< zuV`|adIqJ+c=&*5^DzGBt9UT4Pn1p>=as;m45kE$bes`Br7#UHA_*V^MFG@}vFAIC znUcXP+xK&=RW|xN_^?3sF{kJ2aSj$_xNbz{gOVi6vPmihQLKOj=J`I}jhEMYq}t0K{XR-tiqGQxro=VD zh&cG|Cn$U=FRln;!gR`R<}nw$$)lNyvi_VtF;vV(AjM(mvSohy)QMU7D7j;K$Nsmx zCVFZiH=*3I|Mf|%!MgL)$riZ%ksB!)JH>k+!xI5ehmWJMG$j7~g3=_iSPsh>HhRNW|^<-TS05>_5wy&(jvshxP42)r{6d`Zwi=j(102__ zwrstN(6dmprZ7-Ub|8Tl9u$rLw!bOPII6$9-YGh5E&je*jn)_!=zRwud`@68XKAHR zj^GddPAQoy<5QcYfOn9U4Mt&ctJyI3K;CiFQ!t}P@}{aPMEbC6OSp&S4?PJAA->1O zAE6=@8rZ%I9+9CgP@LnlO-8h_=XbJq=9~SWL=P|A!PRz;3?x4ceAf2<;bFG5->3lb z$T!`q=+9gRLN3;fDQ){KawNkYCJ)HF<-k5GSpiNDPt{$Oy>rwU6t*W4tvxq*px4W0U5j zeXqPNZa$N(s3cK>VAB;u0r(EU3fZZoAXSZ|3N&$aAn>V`#8D*nUrR)RnWseaO5bIR za3zZXTle%8`*0)@JwqKX(QWzCO@1PA%=^%f@sVGy6kiig1#fU8Wo5y9Zc$8r=aElG<1h3;JKQH!fh)9j|5x;(*EZSY zTmfqy+DY5c=|h4w$$s?RE`Gg6vHH_DZ)ENfC*Pn{3-Jh!=`AmNaKa8z*p!@g3DH>atMdR!7t@Gw; zH?D?^={|i6@T87XohNVKb ziG_6_rey3{hwm+@B*+~j#3XeYZ!Po-DI%DX65Qn&fK<^Uh86l1eLh(R+Id}EM;UHf ztHWl6DWXJ_{q+Z}(91bS^4{XyQzmUOWQ0p8o%bH!s@2o`H>0MKg9p+gYCY&~m?B%j z-GfM}Vs789x#iXObT88IPSIx*Gkg7)B;m$?%YaD3CsN>8^)7rAF5-Xh*)1Gwd;O%u zjYg=i!snK*wtY8i9=*j(3+}6vu&KLAT{d33MW2(jiDsoY6Z(!O0;2t1+8Hb{aS-C| zXAcZ}IKxj3{mP8|D(8=V}XOaEG%1{xOQ-OLM#BAC0^j`}4NjwlMM- zW}sFQ8EiBj$hZu36E({snh-MRE)SxV#Zo>K-b35kNKYY6)GtDO_Os^#ldYd2O`x zilW;25M}QDBcn2U!Dt+L4F7;BS{qROBFrqvCJZ)r!H?uFN3z;v?qo`q-ohPr`$VHe zQKe5r@wp2P*LNe3K)IX1=`asnx87QG^1$Z!4DHHomY4#F_}s*txgeUA~aTl!DQhyvGzCZu!DVV<*272M2U;)1{&=&rA!dDIwvY6Huj>L zwQ5kbb&@$Xlv&Prb{L3)MgW#){p2(MW zSQ~mYWFp6rli7n|)qsH3cB#0wY1)2Y@z>>?RLJMa39vG>cL`XYZU#J_QlKx5LbbT8eOuW&QgiNncEm%#cWwy|*-=o13$h5heg+xh3De-7)t_lx2E%;Sls z*e7n6QTr85v{6#&9~7#uh?7=?5pm#w77aj61LTn(-5!oHnHC=^wqcOk!5YwTy>?r5 zpy4N}+@D41o5`~5$?12((Cjyu+~ty4P_6o<v-LIyC!2z6t^}BZew3+(wLKWZ!)?I4NW4smg#Zb>&~jD1H!kBicI&!w zK?Yh!t8GQq-{mYFzuCX3SI52xHx^<nrur-fc zI8_bTjPon_+NPzZrV1Z!048{52IrhRm-`Fwc(!+l?_)otLBwYb-WbglbEpk?^wkdE zMoT1nwaQ^xXlVp%uoy4rg5d#ggUukS1qkaZG#78 zocWZ06FQ=WA?H_H12wn8YfA%_Is`F>>W%mpw;v;Vq@eXl@Js$K{v^*3Tq`I*o9h<< zvJuhd>1Ggx3Rw5GO>MF+b)sFyH|}p&hUMQn6+Y zecZLOCU5YMCx(}cnn4)5D*c0+V4k&Uuk_X16|0LQttuR23-$pxO?nvo+f0oQ?P|Ya z2S(Z`t!^r6Xmhpi-QJgS@<`Zyiz{{6R$~7!7EvHpXHNl0MXzZ9hG&eG@V@7Bd#wZja<}f!Q z9~SX($lU7~rF`$!UnY9%PAb(@r`IySuB$df_}Z%H1f2qJ>)DNThAT>cP28Az0hQ9g z8$$vy$e?+&6?F~Rr6yS04Az7%e5{=v0n?Xw%U%xa`561n?IC`E__eEawM#U29fp|e zYSo7v@=a46_85;`>`-VVVOQD_&7r!r`mmYo{qhtk=B;F>O^uV_2rF_63s}C?*iV231O!!1GrPw(NOMwPQk zGQAvt9cB@!@=s)un(@-j*O+?iit+b-T83PDzJ84@t{mr2kxb`} zuXj8zqwV)xaG%@Br4bUbVbvZmrlj*WJWSP=ImI+p{?{kgLIq^h2pe`26O2tn9b_Qd zts@H}ldvHoadSG>TABFBGGJ7p!TaYxXRg;e&MtTD7@EI1u-|P4nN42%EVhEkbY{iK z@u>buxOuYkTqZb^5E8ffK~VM*r+E563=*t?P`~%9kEQ&u#+uNI4-mM4C;ZmD+RXCHKGH8KlzkIzdK!9~!lv`lW?U~*G`MspyfLDme28jE3UFbnq%;x2^~o+r@ugKXTI_)R6H#oeL4=E zO-qyzV*wjpJ>7T-Y;yNG+YYG{kbr7K4JzateH_QfM%m>T>FoLn3|>DSmi=G`J*m78 zS^v)frN3);an91i<7gwqJh1EeKyU`ElbWfhatEsFcnB;*~vwY@CJw zW1}drl%Y4+ce=k2Ke*0KEJhQpDpI2rQx;1y7jqJeqx8tqq~62Bmhi{SuigA7K!q@s zEJK?gmqURM2L~t4@EGO>0uD zm!{S;|18y-hP*-HjUqB(`l67470};H<~%s~sDR-nBDX{yts2MO>GUN{b~NCvhjX#C z5(CWck5LL`lHH`v3C4f=DC+PH&|Q;i$z5(JB}{;jWKQNB4p~_U2*U`0w_zd5|KMLP z(}N!>T)NV^LIQCi0huM){Z-)1TRJj2?p(b~`basu<$)5jx1J2wS8yQK`XjNI^0@C) z($2b9X9u!N&uI5W7udKk#E{ncYUCF~W)f3N^+?+@RmHuI2qI7}w9xJ^G-^@f=$(ki z)IOE3cN3oXgZm>M0UgY`u6Rb~F4W{nNU)3SiAc2K`clZ>vficzKVOZW@n(QE7Vbkt z`bmiy)Awo6gGX`_c1l|o**yxTo9Iy8!xvvuZwB0gki+*+_l8dtM31AdN&K>tGLwh3 zxPWBYc-xxH9xi>!#{}e_NK{Ia2I7uF_3|7j`zU>`WCnVXnAijb2ano(5lI|ZOql;J z9mnnQ$k60clY&HTmkM+M(mp}~WD@~}Rh7EU6g=sILXYvb{=18vI-^Yj zLz%nN*Xuq{UKY-Pm-UKV8xFCoTee3YnOT-HtiP__hMKxP8cV&u&+gti3M9+4GqRt# zO#vGeJoOL~jn5TeREp1`+C|}IlsFC_Y`dw+2aVA(Do|#TltGrd1p#C37LLM@_ko8) zs{e97`Z03#)rJKjX!f`(d@Y&FuOgPX@@Ka9g&78Ws+wwx@2kJ^4eSH^i1P*=ye)jW4AmiJpuLX&G}HMpzi;?08>y|{=4;6i+jB_itw&q>_?@- zi1htCQ_x5-j}Kz)Zq=z@cAjJmvj9hcN*w<<;*z|9;_cqtXOd6m33g`i4jS~sMqW)L z+h*bS_t@jvy2jQIZ)U7NFVz>%9RN`D1ag3BfjFdDiX=nJ$bb7OW{=g^EL87v0Mwu% zRi}&`ngZNOjO4PL?UHA8A|@>Z=qekaj0H8bGN)F*#GpzpUkMgxe-QWVQy~j zh)O-Cd{*w>bJke5=esqCXO!okIE8UJ1g=eE=F{ab0Heuv{L*}0SdF{7tuGA-+bTOw zrL;gYAOBWYbY)$ZD!|Q#h*dXBt{jMyky|&_$sUOUbIS|adUVmXn_})MOVG+lFXYr9 zI|$is>^SG|GC&og&Z`x(ss!WEINJ^*z~c)H+^vmhg&KWpvAQ3<%rK~kJoHL=#`{#p zku*{C1z&HVCTh?Z_+9}G;-!;4_3lE&?y?^+51o8*=G1eC`(XwYLP7pJcP#Os(Srlxct~1MPFI!P z$jeq~``Yze$wnq>W*(l8hL8A$n>b;sr^$ZO%z}c^kTf8)-n`O%smD0V@ryN2?VGm2 ze@BE2!;+#Yo)gHQN(q&Q9>f*!#5gbM$)xAj6;w^-O-^R;I(wi=0X#x*|JSwqrnTUJ0Q#?EgVS`&exEz9QtvicPI z;bb10D(BxvbX!QZC!H~F;KIVEG7YJk#_vPUeN>d_p&i%0a!Y+^2p6s9P)9oO)Xj46AUbJ@3}iP$1Ga!VHG8=tPvofeN7bu8|nv?>+Hz%qe zg?}7_;$jbVW84U$b5`uhT+uQ?~43DkN<8$|4q=_f|)4wG?X>8V6>jl9Gy}JofDW2K;*8PcWM5?HuzAIVy_~aUHr0fd`ZA^4x*79Zg-5XTawgm1ik~;yU0_*^Z!kXaI=DRleBx>M3 z(a-r)Mzz=j$OEuP3+S)AeS)$hA$_@6-nttU4YD=D68CjK+-#z|roe_K=rywTxA}Ve zizcaH!}XBar*!RTUH~p9)HUFWakut*rV8loKggv$ZW@W4kN%<8jwpX)+uP!Uqj3h_ zokY2f5gzF7!BJ-=x`Vv?*`EO`ub+otT?3+!TipM(S(1@=i)O~KEbM4 z7#z!C8d&1!hR;Kq_hoAj3;{Y7pI_;E zJ25}}Qprv1s|9#wsQu27Zl!>)M1N0m%`0%fTQ$Em#lBQnscb^4C2H>jHI4LURE`>{ z^k!Q_Somzonth^aiiUr^A}TFn#ZB9Cw94WjX`w>)Z=EvIV58TUXKI>8$8%C==j6!} z+{3kSK7af$x#RS<6DJiJ`hJm9VT${DBuWi*5i~WQzz9Y2KXPTN1xqKBHX&Dw`nCYk zq($HTfl!&7S*Kp!)G6!0BavM?6us#YpiLwF98p)t#X&23Q! zf{e>kU;c>N2>iQ!e+J~WQ})Q$w&X?oeb0gj68SW65;iFp#+yLzP>M8cg5qA3Nj^b( z7V>~sL>zg-5ap-^5|q4vhWqx2PEKxaQYLOV3MVck4dva(ekY(%Ea+8N+n|qGMF!f6N(oea59&%n_AK&XwnjXRr+)oQ z_Z^RG|7j0{uaC+8z%aG!J}w}Y>eye;t!(S(eLQQ2F7>D1RX&C=lQ=^`TU(nl!izg5 z?64`wjiTQv;+o;?qc?g1UV^}nPCe;nCRjMrYSPMZ(0!24^nvd^5Q4`#lOR|Ko~ z>k~DX{CnF1{o!7dY2IFiVTX;i1Z6KRp@YCwkh6_`)3jaOb1i@$$q*dC;o%tfLf^WSKJj~m1-IB3@=o>aR$Shw_Sjgjk!jo&Ce10*e#-14WclA1~1egzD zR;t;{zQS=!oGDtdTf9KJ%&tYE0u#f{+eMdT#e#rD&bEK47Q|;_$t)MYAlkoQpTx{C z3S0Az%fV7AN0xm%Hr}w{KeO(t{E6vdP4m%F(=|iW!RU|zWiBrPU+-!xxvf^XcfZh| z*VIR^G8JT`j6Mi>!_E0{5v&+0?Yx=et9BQ4G7RgQ>OBbwm}-Zh31FUYfd&S2c zFvfN%cjmxpUnR1tij}E_SrWRrF%R(Z*aT04CUCpVY?rB|zu7KG;>0>IQw4rRlx6z))@(Y4fdu)WSrqwBUe7p<(Lk&5`F_=sMnk)lHR9qip^hXy0|hs>m0VX=u1Z~_M^(30 zt4IR@VEWNcdWS#Ey6?t%;2MkLH)Z4l)?q*$zeOsRgBEF&!Yld^>F#6*d14Qr{|g~0 z-^!r@9|^2=vjgr$er_oY2)od00P0!s>!m6^1H+_!!?|zv+RO2OdE?mltMWtNwRX!2 z-+kXyj`&2mu1a!};IHsx64)d~$<(F&kp|}j>cMcgSZalV2G1lX{-$i7;LKT}SU%#s= z?!8Qp8!>xlbQ*zsrRlQdnuz3v^Xv7xE9HFVx@{V@>g8P<7u)7OCGFx+Cm>DJ_A|?U zke~bLOJtsphnIRZW=|Nq#T^BTWuDU!YQ8j6k}=lNcx>|a!LLKuw|$9n5zWx#vyz7m ze6HU9r2WY}Rst$fvzWi&2$|hFvF!!^0B{&LB;5|jVQ0wZcD>%~b3(4vl+{4FW$>P7 zk8*IljH?5+%_BSC>nione;_!%7*U^X#96NP!M)gF#nvk*N$8}%Qp196Ii&O(I;k>E z9P6Y87bwVuw{;^lw`SqQ=O#vh?T^0mfE}knyqNq$rL`}GGdY0X=Gu3#w>EJZ`-!fWg7j@P2 z1TQLWrKAMfs~?W;4L{C!6&~Z>QfNN@4>N%bfu^1$2HmF9QV4$X>FVgA;j0(0iD8r6 z_2?Zo9NV6rP8-KIJ>V5(S{cm}YEJfEfcYNPFEJQgT375jC=36XZ@{rrO#N&6NU18t z5lK0wz-rc!DttQ7Yg77qq9#yn6XhaFDcN*8m6;rH`hYu&@{|;2D|_~G_rg8+%ELp$PY#pELi=EHQCD=6B;et)z^q#K0x@t4l zZfWKARPRZKf}ofg)cpCEUu##^-bO>T3D5|b6!JA-!Yg!u&jtIp8t+P-_rbCh&;??* zFqQd?*o_7xfp_FeW@w`&ewYHCt?Y`7$-;9vleWzK31lELIarR8%h~e}wIMM~>3Erb zZ&4cYbxA2`(VS13JSqvjj=fwXf6u>vXQ6Ki$knN!Sl3>eLl^wbZi!l2>`MT z(Su;JvP^ESf|9S_2aKOSL>W|+#m{l*nGr<=9}~1zF8}yie|t8sItmL9JpR)P4k`Hk zhT#moX;L3`PD5Z4nUyAt7_n(pL?i941~@Rq)7Fw9`lH%>IjyGX?}RyLhrb8Mn>mD-(mL z$pfg#js#`-I?4_k_5A#XCR&`KECb&JKPRXRa1*DG=i22&@(Zo457A+o<^pGkr(`o~ z;cH(rN>pF=(POG{!F!uy;d=-yNQ6L0y3X(3-D&F=_sjS}d52&1o zRgIC2oj<@%dp^clWCj_EB`X{0VGvTb6rpva4ffOc)UacWOTf2}f_tWh81#K}f_v}L z0%iw6G@+NA@W+csl$fl=Rw<{nONi^?WBRUvY3??{;2oqUKX<-pbD|TB=5v)tw8IBL z9Jp3J$eh4H2IcM|xvi(-WwC+;ny*BS7K+Z)^esTB(fhh??Lh$naW;bvk}1+BHGI&P ztb!m@$DRGUgu=~&kDNUuGt$#jLSrMjpj6!RCo)%B>FGr#}1ObU94*l>wYJY zUct%P;9Mv2hMJ=zyp6X0!ndPTI(;7WGr?Rb)zHYpWIH&{!oFL;RQ=&nFhxtYza|$; zV#Qj#3>)J?J=o$m0k%j6k#@1F^m;RvWCXzwjYcV9h)8jB;|b{I-Ac4`=}cEWR-S2N zxxn*3D+HR)Dt)#~Nl@im5~d%yKdfC5`s=lxHUw;&pWWIzmb_Lk9}Y{WZI18Z^r_NE zG2lDXI@{G1Bjc56_o>qnu~cY$g#Kwz^K$*6j%ezRu-Pw?=IfsXb_5RxMsf628SR6OTHD3XI8l8l|d?7M>e)Q@HMuV#f?)or$EV{C`K-7&sF)9sb0?kh zqvD5xr=;G+I@=8RbrhRBty1XX9@oEd-#*Nv?qb$xWl2iHW*I?S+BePmTj1K9=aR_e z&daERwfIU%sCcsH1a|I(@_h`dJVdHSm!Zk1?Ym`F$DZ<({hx^ zBK?(bKSn6cBfw4*)Ur}Y=&(^)avlITxvCS6cB~MAw9>xYx7CT!gFzfo$20X zDcmnR(T+Sx)Jk9P`#-=d*!GIHKWQMjZ~R6Q&oKtWgRyaHe&GezGLsr~u1gYtV|s;5 z`IRN2yaH{oDl0FTWHI^Wz3YN~t*krQej+}$NX{Xz@%*7VDb%b#<_i$gqp;AMp`{)) zeZ2WKX!cWum7QN?_?kw)DIVt%xvgv5)zE**PJ=7uO#r+6-;KQvcCQjLnU77ZB5(*- z#-7FD5OeA}-AWRO{>g~)K~qctgr14vw+*9ccWOV+QaG&fHEkBt{S6|CmSFvIo|G#u z9z3Sv*R}*I!y!x$K|0yU=_Jh`BFP=jlP*XrmGPZbZ+*jaf656)#~-`~p#=Wm=4_hu z#iHC5r=H0JXmA?yjhEZo55Z_>iiX=rEq~H~zx%r#_v5e}7VxdXq|#UN;~X*`5z~~_ z-QCNlg{aQWP1YXX(6Vz__AKrf8qD6opBobsXvVm%OG!R!0ExB1LGC%MC$>TYtXL@d z7t;q=Se765I4!IHTqwFOTCm-GeBoWO?VeaN*F@^ycUZ*@CAs$c5qsBIoM#aUA(aU_Q8nz^%cI!zi)ChPBQVYgoHIJgLgeuWfLC-g;Mt3&ffV3Y_`f z0-&G!`m=-aJ4Iu=^lvXb{TlYph7H?F4oDUiQhyeuyutcZO3^98a_^4SYrB$GI0Kq+ z5yp}}s58~7mng%oW+wVMY7TI#gc*~&>S2HFzZR>($K6Ujcw!>E%EKOpWDlBF^PUn$ zEt>I^Ui`_TLdaQwV z4p|gp4t#8=n?K$b!o8o!vgBO@p6UY@R62@5Y%ZCf`4hF`ISndBDtHsFJp8>mUK~SUL~q#>I3@YyJ93kjGHRi1kVe&P zN5Ho*=R79*=)EQyLbCZQtbjYM&$DdBxQ%)m}*;wzC#3N*c+1^=+P#KQEtnarkfk92UkEPM4tyz12B=pMp_C%61 zogz^N9bVYof($WEMzOHEQdy%eUU|~>3vf9b*H7O##eGYdDKJo979#&y>Z=OFr=S!y z3$$re?rWe&!8h6Vg{_=~}QyC+?Qiyz~2<&2FAO?cCh4DSib^EgUq zIl4G{s$A$?+f7}|gL=CZZ~V^9lEWS#6$1B*90)FK<#iwiAY=8Ft+8gvc zVZDSUv)i>7byUC$^r2_`yOEj_GV~^* zPT>iii*TAED8W^`vlB@n_B;tv4;OQFu$B(_KqNz3Z_BXxi2fiJK^+BYWVqnTgzlJ5YZ51N z@VMNud~2l7nY4bNAWP9j4Wx^Pc38_aN>`F;eyWs}s{CtOWvfk5s7QMj_HUHbx{m%Q zi3SgFtDx0Uag3Ppc-4)glZ&<34GW}+c(pvp+yVpKq=t-W2ydI5{0PWC$+NJlca?e% zNd3lpuHb^wqd9pOHAWZYF}AT!cB_YnNy7(Ia}6_8!+B1^r)d{l~{L`4(y{ zQ8o3d2!2C=;;`@k9o$m=c@P?!?GlMsV7O=vXJsEZeT*`h>7XUzyGpsQ=ZPZwFzw#5k=qSRf~@W zS2J+Ws_5xWd%)&=?3YWNFByX@5X+=k;tpOP&rCe_+(rGEi7xwOkqz1f$m7Q;Ba|(T zgm@7t6@X-6C{<{sDt7F0yE~dx?RhK0&SY_037j!*mEK3MsPG3CF0SG2?f3z-m50I! zt8a9tCp=GPB^ZV8CTA^A%`TBeyCDtgP_|NMjIAxaKw=S@kOH1RYWQYs>z?vA$LSR5 zgUrrF0rt50Yy|12taqJlz z@4&$0<&m{HL9I|QGNo5$T0YwKE38Tt#jiBP{uBFX{!9@IKaWhS3Yq4}FBv|M^6`Of zMB|?x;KcqRb{mH3dytBBf?7(_LYt)RSlykTC{2;Z|Iu`g(Q$Qc18&nawrwX3CuU<~ zlE!G9G`4NqYTPtxjK)S|+jb`Acb<2x@8|rRHD~rdH?K?YRIQPJ6n~IyDidd0kxZqG z$ykRxWc%rNUu5;eX-E1At;_l?QPRXk+~aH^I@mQZz@OM7=0NF3n~C;;Qm&l}GM0fL z7Q{_B=3%P9M1b;PVuI6S7>Af8^nRU~Jv;CjmpYZ%{T%`lx(nY;F(x1L4D#OkM5qkbzl;BvlYFy(SeJIES6Hcl3?ldCUoLxbp6w1N9U%` zi;&lmON93zKLM><6^FEWl5Hja46DB0iSF;!Bwz4&SnV09!^Z#Jkt@4BxEC(vihgHH7aT`>4>vgDFtX zrF5%j)@-W3!UZI&DCv}-1=1mTTp@GYzar{)eQ8?lIS{(%6}rhsy$Zx_`%s)XQo#(` z)+BGTGv|kG?S}5k7xVlts8p{eM`*9?u&#`YpVBq{`pgy$=4ns(*q<;h$v6rLE^~dNS`_@uD4s4|l zs#Cq+L%u{dZn||4vtG#N@>Vzy?m*spRcuIh*!)c7v+Qn|+*@|7RXIcKy9j zTF@_<2k6C>_%Hy$a4FmdA`lxpN?MQRp}5-yMcC-DK1rvC7>ZYtaDdwQ(ihl%=wwOc z@hDw{u^wPH*!8Gd^WWBr1tz;Q{)>^jg_%L$GhJ74P+PgunQSJTQ(BXHxz65D$! z%NAt8u%`z3L&YZ;U9@u`DWs&YYMs{IPRLf9~rcq5wS5L45x5d}AZB zA=a+9xqR&GJ)d#UjZB=e$f3D6yg69BmPUcn^qN;#38A=3_-aQC@#%rSdd?qI;^~(C zWAPt4^byvatai@~$7vh>KbpdRWJV>jZsyng|11Fhr0C|ZJWo!&7!mclz^mqpEki4N zo{Z?&H2?X^cmDFFUEPl+L`maV;X81GDQz9Cv!dKYI0rvOq9^6e?#2>FiZ0tfD9~lg zhkBZZB$T0NHsF-iD_B~GKgq_3w)oo~4$+keaEX^s^~mrKN3UhhmqUpEo113NkS{9@ z(S!>~lAU=}NAKf>#^V`qPP zDWRr1j@N_CX7JIrfm<;qOoJYvG246*Xi%VPlYxEfsvk1`EDoYwYcxvo>@QpqJ zUhTtfKGc~pe2q!6$=S=*8ChAz6S>1lUJ%lCSie^p+r9Z*tq9St*XM3_>%aTTOl-&| z=^bJl=jxNe(XpoC#u?Ij$1PQ~5}gaedWV@%wr_hzT{BquN5LKZa8%21#3d}bvisCr z^1eV)?y+sr!1ps*G*vcS54W)K%zgEKvhSEEAUSbQHl)0&HS@n^A&VNV!PKE4WwSEiN^;1%(Jf|mF#+ZL32fOn4OO7~gSG+Og>d=srTNu@Q@d1R zu4ZQ7cQyXC%k=Qw*y%3>dI`QPDf);c#kZh7m7&Q+kp7GW_cU~eiP?pU^Nfk*Iawx( zD4u}(eGrz^2F#tE;^--80YA~5>-=5r8HBAAT)clEEH4c#Rm*;<<+MBP1l*E{hWQ+xu1cs~hLnh6+V}$+!pKHPV zCf{%|>%I22@`KC2>vKPq@k}cDH>#_wPGSXfWY}H4$y-hCgEnu_o=AF=`n%(;2^BDt z2bhwf@WtLu+C&+`Tp|@yW0sw;HE~4gpRj1`iK2| z;j7`Bj*OPMWYl+%-X&YV#c@XDHx5)b4EVG_>}XTG4P@zSL)d|YfnXS2icJO2c!?M1 zK>Zhy4sgW0OWq$M|~j;K_zCD2u{ zs9mqEoU;!0WB<6E$mnAjv>*#T+pUhgpYpaDOa0^D@bFcm9@p6Bp~)Eq8^BL;UvA;C zZkGMbqUksRUaXvSWpJ-WvQvI&{4u8IlsAp{Bsg7qZWJTEm(goJ6P57DVhiwrA4Y54 zZ_5qF098Xd(3A#t`FeVwdV70|!1O32i&BMCWO)-wqkEbHTuL54qHQvaCv^o6^4r_t zsZ+*(>Oa(lPoqIaB(ljKQI)t5%B5QmMITA5mI$0W3x`^x8b}YL)GL5zizqsyxcKXs^t#8em zA@lb4GlsrfS@)3{%S2}Lnanr-FTjxKC2@fHA zPb$GY1VgmiHcetA{U&(tv}+6e_BbG9LYRnRQ-JMd4d21ruw%4cf|Wr?rXFuQnOyc=vLC0@Hp&p$Wz5s)`BVfIoq;9w{3wmqYb54 zHFkHn<-zp4nt;rOlvEtTpu@82*(f}MU%CYM3ozi8VthDBm8JRdmNnT6L)nMrb=dikp4G z=I0AD-c~gGpYB7vef=DB+D^Paj&^L{-=*sc6UUFE#&A|5`P3H8#_OX9vmFtks7d+-!*$*8*Hs??5GQ^IXx^*pghKGSO~TV zn{~|qiI}o15|$iHHkS!e!U#&Dq!rtl$yjV*k(|Y=ptjVEcaZ?IarsHO>t_`Y<{OpQ zPXU$$&0lcq{_rtQT7VwT-8y>}xL*Zu^_pY-2fDrNWPu7WLcphH+MAcsPaOwrd@jB)lPMCo{NHGD zj_QMCki=*sjpW5HY^URhb$V*It4gux+EOP@19*Ypp(LeShR|6ZWv13)TFZo};Q*W1 z?4AW}5dAh;tni7oI05R>h=ks__K}HO9=F9-Z5uJ`euMDp%}ea9nlyNoi}LYq3}wST zrB_$AAQLB3IAq15hLt}kiTP(yUw!uZ&-bJ4WN1v(x6Q26=2Kolb_?1##dfgi#_NWW z?Yo#R1X4}O4U#Qy{1=<|iXChrbVWbTD$AgKi^Gm1=o5Ls2p&jpRAfjyW|UI5laMxz zwN<{URb8VM$;Ul-u3F zvpH+5%@xq(VSYc3qw+Hz0~%^dgPbeKkQqIsT(J#6Qko0mLK5;Q*tNpv-H72nwx%|J zukN>Lkyli_IyDy#<3DdslBW?XpWA+WzMxGSCNq^6O6!Mwio}g(8&`=Xz6@pWZEG!!M zMHgJAk3gaphyRtC0XweqTB)vnj!YTz7s%o3b4@l#(Q~KhS4p)#(~&iJE*=af8O8_^ z8Z;}nXdUSJ$8LDZT0CV4Qn=#h4}DUf_keNnkvyBAE2BQbIJMua`@3~G5rb=*VL4=BkYF07&L zv1y%6J<+@))A_u~c@k}he|D#TC$Jv|-BF||&#YK%6iC(*fY;i^YLg6RVy;wXD9-%@ zT4?E}qu-hkf)Rc@;-g>8d)3OzvRlvY%=uV~vo@)v_4|%#@)Jz9?5cW__oH<*m#uA) z8eG1879q5Dk7U{HLU96PLF1XYbjafOPgRx#9S66+>an9Fhz7R+uz{eQoLt-Sx9aUi zJD;e9_H&oBg~MQ#Y&sDexn08rM~j$(B=Ap~60&Htqi-Lv$+5uLy!d67?W)Epd%d<6$o5jP=>tkIogM3akHO{2TEXhyazT6T+isR92{E7#-o3nSidYy`# zB(iUYtFd!NS`BID5Jwf0hSTU#l+fM(v?-qm-5)d^3D^~MdRiO^Jc4ttEqIq`bIfub zf$5JS)zAtid}-kwK|ozy8sl zkYucNg>u1F2ow5C=s?)Bx+MWJX@CS*)=fPkv@E@|UavK*G0=A8=NjyLz`SoK_1q=9 z_kJe16a16*Aoz}&x1IJ#BRm7i-gw;DPvnhBmBNy=5i4*-n^qDs>6%G3tNdD}%tINq z?+-zxr&b&xzkyAO*oi1i5A$<}Yg!j}pbU;RWF~e~L;uXYywE9KUmLzGGQ*oCGxdYh zEAbU9;|uxHIb14qOJCLb=DGg7uJah=_VSU%dkgXJ#P9)Py*BfY74=4^p9k4iLGZzW zKwNFxTyv01wuAJGSJ5mA3x>SKG2bhWH|gIKfq?=0)m~X;%U<)keeSeFm+*F)CO8{|HG`|)9cTB> zG`Ju46X}z}BTrc@=yadr66%;SW@bI?&YApDJ6bWu2=BzppjaNJnwYNqf54q7Vy zSW2P*w@ue~NXg{Tv11~S(EB+Wnd906bcScO2Tp-bTjH@&bBK3BEu|2S?S$a@)70yCtwygi+?JZwh+rE2=GiVC$k{GQ`WJDm9+W<&(8 z$+opLTu>3wDd*@2Xl-@PGie%%5km4KFg@QQ$gqhJozE){1vp5ZzIwW_fOah9SJ<9) zgEo9wM_Hnuysy&x`CXgk7nKCd0ASH@i36bvI0Iswr&|5k{3ShIez~HM)na0bu7cC6 z-K_9yVQb%_bU?2cYMrxlf^%bVdjQjE8O4ntcqs`IZ=pt*K7WKu;~~qqv-*~oIGncR zdsIh{6tl&3BH%sI^tfO8mc8&YP6~Ntd8eFc-NIfxA~K%Ay*%@Kqf=)Xb7ArGnef<_ z{sZ#zpE{Cju~!OO?STDLfwi!DLj!VhGK*gem9i-g$RYSO_@TLy09S9xV7q$i5^Ztq zH#8L?q~Xla0Sl~?Y3|;(c!4EI_gQ^J(x8m}nmcdP?>g%xoY5;6veMZSy=PLR+R`To z%90$$+ek@Q57>Kz5w)PhuCp%!%zi}cUeGIS3E6h?UlA>Rt zUBI9WPG~kPALso2Q(3%T`&VP9a;H&^jn2Pu;uA|J3{hn}ko)_yut>YU6kPW=4eEfd zyULZ7>N@xyG+w^eDt0!GnG??L{GiK2rKy2ZG}Re8YLyY_Z?Gjw4_+3t1cy&$Yx2H6 z!@CnGB|O_!58%t~{CGFLNu$}sQ#Y4&H?k1&P5h@f=cEGN(*8wbjoXyr`ukd!jgAb0Zh`uca(6z%p8KT zPA*S*;R!**9s{oLsp{tA$#0D6*S*ioEx#ma5$9DRFj}WL)oWGDUu$x#{<%)Cf!!EX z$znxoA62{;q{?e#w&Zd!cJFLa$!xaYUM4LK^doy0(a*ldjEJ zGQz3eOJdnm0T=kI(MaG0FUGD_CQ@NbEEWh>e>>q*#Fdn_f+5)S{4Q}e<*LcWFi>R{3fC1W!(`7(75Ju{o{vYU~e=MSYrA!YnlGG z{JARtD@-q^>CC>xT;kx)Gzm8a+1G*T`)ndlW)GS&GUs}eaQ|oeVbdkmnc;ju#?Cpt z9(uHt3S8@Y3SQ4TKqW4}ulOHy#cmAaE%^X$^dDo!LZs{xgI zK-ydXB{>rQQ(VHZ3ezYwwAhZ=8cJkJvFUWi%tgRmav(f8G^Hy4$HlAYgFid?6XXb= zz(+&|?}Kry0u9KtDdef>DIt`)^#`rr=5m?&;QG%GI+I7MeemPf-T2>cwl;Q_4cs}r z^l!ji#;jA;pt5Sv-}biye%tc##;B)qmWIravddVqgc?L9L^Hn^hSC(79IL8l>6ta? zUe|;#2VY2u%;fIb6oQ)CJnnYi{5dQ1u=wg&t^De80xE2itJT1-@oX91;MYrSwvrTM zkNkj=qrRHKmjqL$(XGq%CEF9V&A%pypN~_pWeZI~3X}+xk-ZX7!eluz#>Gsc!asR* zd#pUtQzL8-`&6P03FykuXiqSFQH->4RIt8t*yoelA5VdD21eLZeY!D)9|gn#vDmX;_2c?g0^#lEd!*h`dSL#;W2KOmUM`p%;E|`=>@)~u z-?X$ZXz5#nwIb3p*QbyP03Tus7}zhFT1V`2_!saRw}pqWGMtBvt+d8EiEPaIScVm= z`m=RWbc80e%ITp7AH0NBVvPR4R#wkqmi`UUSE#IhN1kFJvV|OG(|ul3p)==2XNYz)i&`Qn>ho4n8Rf#Q4B&jIasbzP zq{lHZ_IGpq>gw*E9uXnqYT)phd(9a$PVf%zKg`imjWMj9*UHKyCvkD&*v78=ET;TF z62Yq4W~}P0>%7*2aRQJ+p;mPsBtV=Dn*Cqm7(@cL}C>nlFQZ!=&+!e0V()gGyRY3v z@0c`hx~=EDnSXwxDXCsP%TFyA7$I#x`qTi->LiR5}d z)Gj$w%+ON*!c)L>h8|7m0a%2x(WWf0ykKZ+dx3s+P@m zUB-P~mKb7P&=BSmd(9cEIaU+iPFJG|N=)pEs!=s%KvW2xjQ`!gt&2Tcdv!gyi6S`sQwwC3H4$aj)e?Z_x$^x7n)Hnr{o-A;N)ZO3 zg<5ps38MH`W>Hd!m?`?c8TY?SgoJ;;i8tQxCD1cVu0pxn0{(0D15QNa6|N;~Ktcd$ z`G(El1O01c5TAue^Gx*gervmTbk!sYh9)B5#1_o`IK(|Y9%+}hY}$bIbp*)^iEWaS z=lC2WS~22yJCK(}dY^{(HuT3o|A6tjMo%*}9$*?~iGzK4S@U=sq*geuNEeu7UCa@5 zfnS_-!^bBT9l$svx;+Or)_yaxsp`0G-emacc~w^}{7}Qeb+C3)rQPexgf2D9Yf1gb zagEplfsh`AR6n7f#7gCFZatriXj)eJ%=wv^JQts~T|eqRUvn2|WpSii%x8gqS31e| zAC(OiwN?^ft~@pIeA5tM;-9IMedri;ES9aDmxn^^f(ZPGf!W)_oM7N5eUKyBqFA4} zxFzx%t)57fwdrVVE|qn2n7nNy$c#1A2Hef6_)N4RNh674X@9aokJEIGNz^IBszjMo zvHwi&dNF5HGn-@Pc`>C$u3w?`Sy^L=?3b0#GD<$a9>J}hb^3*Noi*hnufP}0-D;KL z0lYRkdmX}D{v?^2w)$Dft4^v!F?g#a%XT|Mh&9j zp185$!l6>re#c%~5JzBoc8WWG!KW6^aJr%?ad(3^eC0Yrc)36TBvYd)N-u%;5d78e zXf7iIAAA%}1_vV(B9x6joRRlDw{ccyIA^IA>u}Q*)EvWL@Y+{-+Hq$pa6h0!hZOUX zkcHViiYL-SJ8<=kg{8M$!}BHlM7)EPc27cdK!+rwQLhag|98&f=hG zY85;~-uao|#f2TyeTq4YKX?5<(#jFR?vB3d@WN7w8$!$W+J!70?KI)wgM3K;*xbfX zDu+PnI@1d%5?W7V+G0wm#L2G9>0e_AT>?uSF#xmBsHV?HxHS&Y%&gy5xv}x_$>uA6 z-@p7QIWUmE4fnjb?uRV=EEbZwhn~RxPU1TEwdBEz3;UKvtm~sfu4+7F#idOb*fP=SmK$FB z5awba`-c$|!z@}c3#n9(QZElNwAghnWYnroF3_(w%p`ZfORR+zC4J>Feo8sv-r(bi zdr6NVp4i+r7tAB{J0o7bn;_jX5W0rdb$^7kJmKm`?O8L=MN1Yd7ETM45;3PFimP-@ zYKCeOfHX4u5_;;1kswzr1Wn(}4~li3gyw&J=1~l__A*52^=FmE;h&krOar!M?=yEH zvQ#1oA6CQUH;tG=}sO`R0(Qmso2LXz5H>-gd!UDW|wg5uQx zcSnM^kP=OjHA=A>PihbmzLrKtdd|#|tN=VR*fO~4-a0!3&VQU~1rtbdWpkf4hR${S zo>^iZF491c59ncW#5FC(OS{5n&Mo;wj$*u2LdY>hDu=3cadyY4xwJtCp-e2#SaOBQ zVd|LBD(PxeCKcg5KMCd4QqwGFaWZn5ue(ssX*Gxh8S}jAoN)Rtu`>7ol{>I(_|L0XXqW9c{aX~6D>TY z%CBf`h!$Y6-_fJoSJSDbW@3e5@Ou`kEd(rsZfxVXTbaL3nmC_A#|*rkbJ#!Mx1>zm z68Y|9BkR9L_9wlqOmHWIi`enoQl%K$g~-&|6QFL^(!DJM&BkD%Wo3X;CR+s-ghTGI zRb&RqciBB%v_-mni7H3NP@5+AM1_QY%Y(#qgj{C`vzfWYh@u<-)Ti2@OQEM4=Oq%R z7!s(Zr4HjLj{h_7^2h9V({l{Ds(WSQ5)_5o*8G_t>$EmES#Q=v{2QXnfL(vFF8Q!( z^}TQ;F3@_p8=}jev8zuG>TWEvdFkd~|2iU5qpMZ2WX;aO(Yw_f*0P%@H)K{P@N`HS z-N1-xm64^lvQM=Y7l*|zWHpFks|Pe?`yN31KWRB&D3 ztOoC9J??hq&jL46)SfY?B+Udd>?vLHKO$X26YEUxnpLL@nc`__U=E+p%qtE9hU6Lb zbT3g(QpF+IvUH-X>sZYZ$E}}j2KRKoo76W(>Fw}-$@9nwfDlxsAf%o7k~mC4MOx!n zE~>Z7lyBYQRpuZDcgR_q6s-IadRRkI0q0tyZlOhkGor+d3qVBa9OGRkvguJ&hmSNv z7Hi~KOca3oz0_Ly>}`MNH>v(;FM#gFPWkxBQyF1x67Ap+?YOK+3wBh|Odjdv;i5cz zl7LJjWzU`n81NieWty6VtBpf!EU^-I(5Y%rsD0C1g|z>DyeSp#Jw0Ut%Z7%AHb3rX z{r8j;-wl}2ljY#+O3`~{qi_Mk|RSxVAOw0=hq9_1NxeRJ?9I`7|Ea?rm@5`pV{%V_8zH0 zdK)6&zjtZD(})^4-b@OSbUdG&w!Cph+x$&VF%HAeSRXdN_m26e9I!gcY7av#l;^)M z8)MdcL6Dh^7@V)vk=!qH3nMKG2P6e$){(mOa%D%;6)m$G#~>?Y`IT;~dAyC<@(T~f zL4sX5vGOS&JhXlcy#+QV*x;Wk)tLPXp<#-DOi#aD?E3SM+g)l1h8ei8AqYbXMuy+7 z4#;I?!T45U1_WJpl*R-0^Wn>S>j zN+~X95x;4zaIqzgSur?51&G!w&S!RnscQ*wtbCKUE#|RCo6IrErVtsp0E|EY4O{-- zjP$u%JK@?SJ^{gTN0VhHh~SItjt>K-Q+o;wHTCv7DOpJqx&8x2a`cBvVtHt)<#ocs zqd+?A@9Bhumx4LUvibOYznqL0h$Pq$fnYY(*wL{;p^W=u!|%q!R%VVcR5s4D_%RyC zbB7|h7q}H6?v5nYF)cV6XS4ga;GnowDL&!8_NG@qH5_w~dE{!tryf1)&TWPYwMdfD zkve&-V2~AarfrTYx#ea9URI{G{47^jy#l~~(fFr=H?qYg@PpAM+Zn(2^c_-G?QY#} zPsfHFNl|cD5p1fpHfCP8Br-!mbO6oe|NczclOw#z{Xh_P!^hjPw*dPs0+X7}Y%am! zy+R#J(!|j+aC3H?#2M$Lq0-UQOWC24Tf7v*XsO(>v&=bwCw3S|6`0e!#12g;uALNF z`0^tKdz+^Z^jyDheia^r%P>tz&m;O`nt4^?1t^)RzxMqQhfT_}6N@o__+^XXNcNA*b~4{|FAb`;hHJ$keQ#LQky~X6$?xk_bJg? zNDi#NDlq-$f2(>Mb;BO5g++a=&_~wC!P;WMG|~stMNXEEd#je#gQjwu4Mh<%u|0qAm5_DW8Ovho+5Frxs|D%dVJ1k$Es7_0cB@mnIiYHmb zeq{2t{g3WEPd~Wpo?tgDcRdGBmO))T6C~FBeMOCX(pfLJ^8FXxAv{YeBkMHqWyvty+zzqUERe+{hPY0 z_xRQ%_Gk<(1!eBRTjPZrK0p-oOrlcJT#?s1UIGRwgDA02>%!}84rT@OX-f!B`RyM^ zV3cKLgz}`|S{!xC=fp8phVllko&uyczg+BBKUlsYzE>SoX}nBAb>8epNp%CaiQ!+1 zlmu$r5+4=?445$31sNu0%=%Al-XDu^V&`x!W)3naiog1l)ofF2m}5fs`Sz@;a?-Gr zZsa(HXfC_?(O?wNx0dFflRvAF5FaT_?oZFX*{BObFfsi;gWP zRn^ziX&u0fT(!@c6+Yn!mAGRI(Tr-;DWRNKV8l_zIwWr%!DkodW=_g8(aMq?$r}@I zC@`4x1x_}A`!gi}ej<=P{wBw_>`%HZ7)+_FT%HE$K3e z@v<)0$(6F^VrW!wGrg{!EUohd5lc*?;XD4i<9x57x4^Id{Fd+HgyH4d@K|{-P-8mi zQ-wZFX26sm98iQglo9$B3+9*g36Y#qm|=Q-W(@Kt_zytcdmDP@IFIT1MvG8H;41|5Gl$*2NMI!b`4Qbo^0yrhO@g)Hw9BxJl0b3Mf#WeXF zJ&f-Ea?(pQ%h1BeWnF?566w0eu+_QBQ+E=J;ng*e(Ve;Rc!jgH=&1pipZ?bN+Wo(Y z$JrD7H2p?%>IC?lt}h2IK)!>Xq9V)YvdxoQhDW6Po(qsS=_Q2Y7lR=f@)ng^=|bbv z|5Q*6+z8*FC)Rt1s>BvsK2~`g#iV6bHTIcI8!Q_i4W9U#Ae;qBirbx6O&7HR6X&GC&VOy3{h-bOi`2lBbF1s>u3W`D~Z-NfT+b-h-D) zCkT?KrNwN2+%1}8uW+`!?ECz3*@s2AA)B^HEGCw5phrUb3_5|kR|^oQ4aycTCqV&- zsA(NH#XuZg=zRywjJs5O5zif?XC~#vyK-#qJ z`I$Y1qBy`14*-c)nw#@wme8mC@R+fBbd|7D04BuCOHbF_zW3gL*S?Ds_sJ{)oI7Nu zSyO^12L*ujxlt~)kqZzEPgl;K<$74P3FF59+zng zLA`ddJ#IO1TfYZ!Z@51NG}{EBEyj)pp$h(MSkOfVc+bLJJv|hU-Xwz#&HKL@Ettl0 zA!2L_S+0cx#`i)2hRgMtsLEw1X!SmAZBZl68n7J(BWE+_`1I6T1cvFj8w1CpWYn|A zKa=1_ujcb&{``LLcynyU#eXpv(t{Z zPLWOZ=1@|Bpd6m^`_ge!g@8`wxFcsf^W%Ga+Bvlx2a2wPKV7ssS6@R2!Cp5z;tT}n z2b{D3Cl6RjLjO!2(+|_%jZinJ6wi`6R100)b?ew?=zq44CR(5tn#CAjtRkgZLf9u` z>AVj{^Cy$5i`wz3=KmT%TEz6_^G_QZ+WU%Me$+sUwM3}DP@+gA70!j3w1@ncIv8yh z7ntto*D2;D1s=ic2Wif}ZVyM!8>EF6w}Z=KJiQfz){ zm9um{@Gc+&)^n79$+P+y<+^g@gKyJ)Ju|08B3zwNQY>{R^5-nJnkBZWXwo?KdbXdqgAD| zISq}n{rMMhX6QwsEbnD**F%DCSAFfM@r=m!_qaj>Zf|>jSE(Csc$;}~z3!40 z#THC+Q_G7giAgGl9PC{b6>Kin5!ajj#^x+VRKpm|g3kVANM$G}j&ms*AM9@yRR#uVCbhF6B1UTtl@H?1 zZ#bcr`7b#7=i5Y$Co>1ShUqvec(=oz&2a zT5Nhx{wP77S2*>9ou@w29|+#wA9C+6oBW=e+TLF;4jzGR#IvT2@fhy)=IL!pocVIFiUSm_8h3b;Vff$mNKVyn z8q6+=pQV$aXKLYI(JDcy#x*>Dr90Af5-!$b>5476#Eu*MT^T72h`zrE1f`o@_$pXQ zWCEOS_&~S`C$06n@v*VQ5@gpi{H|IhVh}uicu%vcBVdRepJ}4bS7x@~rLNu`lG7iZ zg6-&~ykG5iX?kNsa(Zsy{s>A<<@*M2e4s}Cp%w(l9&*6Tx7HR-#=1@RBi;J`R5H>@ zAF8c$p9)?^-6r3r+gHcAJ#D#=njzx^qW*?(+kXPi^r15^LS^!GX(CmbJC9|B-a}ZN zHULwT1pI=5*Oxjc2$7I`JkuHpL{wBZ5yJX+s&t}XJX0Jn2%cs6cqYK;y6))DkCx%E zR?BWNSt@xSTYS@vr-E@Y1PXx(A3p6aWKr3V-|FgFaiQz2RuVf zeskM9UHe==e0;Q;i|d1{+B|PY?vB&JMMdTXtFkec_+lu_)9hAtqR(nlFb>(3IUkRZ z^s7_#8X{#B6NUBC^Jov~PgNUuTn?yg55!g{um#=LJj`RPs?UaCP-Bq_Z~7fXai{xS zb>H?74SF1`tJXIA0lgEladNQ3vZL)ze{pH9c&>59V4X{je zx8wPIPtdI`3;@&UL!K7w0W_K$2_4x9%J=HMzTp&j(Dvfake&DE-g_+}`%3Hj*q_z= zE?+0LF=60mR25>0t);wIxx=gD)bvLZpNfb&y&$OO01kP>qU25kKwK`z5o`Kc&0X+i|zX$E7?y zo1nk%I;h+3xXldY$hs_H8bg@%+QGhAE?^eXZBLSW;Y&2Yy#3Xbeh{!gZN3Snhen8O z!IEDQgd`#=5Iy34L)6L>Iv}XzEZIYsTH!cq$jK1aFBQ5-Vu>^29bF*$WEpJHpnbKV zonP%CgoIq}EMyam_B|8EfoP|dxzPsFao--t;&UX|C)4A0{)X~jJM-Z&@7*I9P2gry z3}|!DCCgIpU-#eIDAKlkXG}>rTZ+5Atrqct-->Yw>sF|hr-;F8)(pL6_T8qVgfk+D zNe6NMQVYc+V6Hy#pVUT&7V0218d8LEuOxcamMGV@i7+$H9oD11E>%rFHCn=ns*_U- zeF}BSa&RbepWtYC{5%c4i$c&gJ`Fv{F+Ngc%dx+&9UW8oHni+3lKC~$j8Vm}ZmCH5 z&mSd6#(9ySst^4JJF0I{9^4lfE${O>lt8z`bHZjXAHmYoa15Dv0gx7MJnXv-VIxS> z4`Yw=tY@AUtM5WcHr~bsAI|)DXiL)bvZRXfWe#V4f5~rDA@CxK=D(i_G9#-yJqa#=!vv%?X|g+rxhf`t}bQBVSZn?cOWDe*KS)rj-IP zFnhQY$Ii76X3A}0@;!u2hKZz`tCqJOxXby|B4UzZrddyTy9;k znm^XO3pvx96$J{}QKlJvhT*`1MV+#_`>)7o(PS_g^cUgH`LvGUV$Yyzza9SBADkuT zw1Cd{!`D$N3r?29XU(Yi#7R32%{FN&x91yPRA4awU%nXOT&ob7 zLXl7EYAVQo@E2(EW6(D9rZJs7G-g+>zxT^KOb##}D_%B~d0G?H7-LgqfS9flb%V5GI{1P^UBp>OkZHABDx?5 zr|TSnJ5{z%{Gm|fH1;gQ{=+l7o*fJt+Vj+Z}*GDfTV1k_! zCEz?{_Yxs7U}8asVl3QzB^BT{fd<}B(`4H8)8bp$p%!yuMWFDP^rs%A5=(Z-tiUuY zU_kw;;9(y>Fb&oaETvr1!vBr-_)(ucEXgUNH$5O9K?Mys*rAqylD83ZiZs}WC<;YT z3mx6Sk8JooLt)!FhRK_VlEeq@ahsH{cqbWcQ=3L+dRSDh_dlGsaNg^wc}8yTex;qy z$%wJt-!rbrentL@`Anm-*@Q4bhioa{`s-#)TBi))E zn_9jEK3t;oW80!4?KtGfVWJMfvc-X>IUt=f&aZzJ@fgW~U6>t@@-OD0hAK=|LbRjo z0M7K{u)=#vB_c#at0(py8^I=S%)ls#m4eCJ%n&1&2ejXKBS$)c31HF zGj-=IF9V>3jt)r$UbWrKb#1JYVtzt{ofkhB$R0wd>6Ar1uj3h~_g0j_uG0C79L=B< zJ~1)%#WJJfeE-OYjOji@k!jm4US`T?w}c6gWQHI-28wmb4CYFHFul*!sF2S*Wl`Uu zKIW-uQWmGrQtFJ2!z=-d0r@EVNYIYevLm$9AZ|kF*z^mLHog4H_F>TA5cYMjufHkb zVyxKTB_j*(aF7hZQv}W*mbh9dL(Xqn;-EU#@JmN#U>FY|&#eq2ik)zNl=#i|Z*OOW za!+71B|Fwo_oE(zm<@br7_TX|2*Ngxwntv>!PRe#_TMLn`S87HgAVFY@Q2XBmcNw? z3*{ZbtZb$?(3lo60#~5brVsB6N(rt$U+TG(wcssJ$s|ePSQZW z*9qV*AeFBGa)hMf@9F#}Cg_b>L>*@LC9l6Gl9^N=d?oWIc`d`Xeh8P@tdQ{`Aj(BK zCEsDO`E5&0O2rkPxFkv0 z32hkWAOikhpk1rFL@UReIw5+YFtC6bBFnBdfzY-&!nJ&O=<)-k4nkKvoC2#^!JUzr zVQ&9Z)a54>1Hi`?Lly3URCnfrBDkGB+m+$SWp?mpmbD5#`8;K7v=Tn7;x#x+E(~^4FbR>FNx?LSa!v_-z=k9NO^dGW9IA}0081Da6nRW8 z7eJ3w!D8cZ3hc5|#=pcPbQ<2P;6SK2soB43-T&)^U%hU}ep)GXkdSHgujX+VKInbt zU~z|@#G3G>=R7{J#;0myCBT=pCN!k%b1-X@^NdeEkoj(l*y_b?)tS0BE>Xe~hUVbV zl0%0Yehk#MNiga@{3nZt;P4%(TYuW%$&Kh)GHT^fc_P!;%gFaNXwY9#pMjk6W68Iy z&)7!u6sMwBFXkKdGr&|HyjeEs_b&8ZE4K?jNdB0xsCxJ%;9ZjJk5NMV;3} zH9?{#r>uG4h)SB`7YC?JgU&r!)BllF1F2q2zXy&vPRr?#>A~x3MSp$TTBt@4qJ4ZQ zD#d3Ta$f?c{XfW?9$)z7NAs{1gc?K#_0G!G9>jxj#2jfMw`lig4(GPtpN^e z5lL7%!5`Ropr6RaTcC!oJ+uqeJ_q4Ua^HE=)MuebL2R})ziX1rC0yl>Olbq4qgYI` zZU-cJCzrQwkix&7V@NF%FvnY>C=fGEE;a{cZ2XOA&|UI5XyehWCvPopyEN0_#rt1p z`|`FR_p&C8_gh(VXNz!OENrtS-JVB(^oBRjApe~$=~eQXsNcdQP?*VV;0iseykBYw zhhI@Z(Ql~!+r7b8QktdfG*&F)COrijuEhf`j#@|Hl@*PWm9BnoMFYKM;D>h~1#bk?SnRB6r=pjPI0b7VZ zbUsfvOTpjnpKNc9W4NOYUB@9{0t;g6GTx)5|D)-ggZt{fF5aL)!^UdR*tTt_v2EM7 zZL_g$+g4-Se(&>}d1sPL{>n`5_ndS0UT5vkiXTc>rp{+LuWD_A|7{4kFqp8ij7EH3 zP+mu(=s4WR8mZ!jQO;YT~mdT zK5p3ghY2$RJ)Y_3I5)J43Nf!k>tx8K^z(56Ij>jR=%QeJ02oA?o?Q*j%_w_@hekMS zv?y0ZRoO2|-qhndx=!EN!!c-g(%eRovKCJ87AGbwf&&GkK`m`4zq12dO@#S#Hq8*d zPy%F2lPJy8fSBF)-F7!ppB{8q@#%CMpRf6i>wu`q?P*VJ#q6)@3X#|%@?~wW@A5ba z!UQUs?y=o(A+mH_ToWtDE8$F88RKzg{PBeYjaUjj2O&=eYw!*ZFt8{NM6-_x7?B0J zPd1AsvN;jSfEJaG!AIFyl#e})QpBVfLxU9bv*?s?iMTSJFWuTzkSK}JEglHWr#w- z8lJ3d*nuVh7;6Lap%-kF&@)p!Bn7jjiq*7vPC^7WH72qk<19IUQu=&8tOfr5^P;VJ z$=ih3&K!MyM#hBdZ8l-}1OPj%fAoKdk7cO{6RF>?XUOpX@3W{6MVxBF)L#FQpF8-x zRe5!jnQcwS-Wrp@$ZKK7bei~sCArhR-Fv+K*=OBmAHhv@+Cb-_n0V`cyc6pmc0R}* zC|kTmkd97Y1C_#efufZ)gXMkjVxxrV)eY<<#oZ{GW0?CIh^D9Blakx)d4+6e&9NV{QF=Yj>!6%@pDRy31WX~Tv66(gS{3V zY=a)3ORneM1Ce~krx$9QH?IV_rA4P>X(AFghw~Z>>CCY*7(Hjy)In^20of+BLLF5M z$%=RsjE28LI+;Xj&Yf8!0|l7iIeP>4aMLoeNzzzofiK&M<%sn7N!kg$G)%oml!`--r}S8-SRN_CEWh5Uklt`Gm!#uEL~0dG{Bzh^Z2#3X{I&EiAQ~ z+D)qMCoOJA4X(<1nl~K?6IzBLdFs;Cn)G+?gxbv%%ae4ozfho2dnjy+m^v0fZnL4G zTvaxi_W}Inr+%Ha%pCIW~xmn}^ie%ztO|;jCKb z_J989ONgO(-g{g}YcY2z)7lBs8;q<)kM_XG@}_<>&dwHuvJh=#D-s{*k#ifDJ~cMM z0*n;ae-Ye>= zWTf@PX5)+t%dIvoZ{pFrLo=+~{JP)Xe0K9faEmo*?!xgt`7;H=N*4_|)A5A$uvvYw z|J1$SpEy_}f}SNF+8m`Y&2oMGgKbsFj_Vw}G~VFHl7w=0nFC{$+1Zzt&mbIM$dp0va7S%P zDe7eFD^V1B^w2aSA}@v#tlBic2MM4@mBx^Vv&^T}!p<>g1&J?+MJwcb7|d1HU|Iq;;4 z?It?+58pT^3kc3w+mA9sHhXR^c?Ni;;BDL!X_qgO9iB9>ao=Nf9Bgh(g*?MAKX6^f zc%RO5`RtO(YP9p^6nmC3_ce-TkZVv$IXRocsYx_TqmMV$b_j^ZY|*v8W!v1<;dzoL zAn#GpQ0M&=^DBO)R6#NL?_u5mSJUa12yu}8;0=a$Z9^m30xC=5zl$Pb zq19JSE9ql+qg=1GTP{#brCDNHGlBF}AcS+;(wTps%W&49fxRC#i@>Jn-$0_Fz9;iK z6)dt>Kg^8TT4i>{hG4on zQ1#bUWV4u(Q)@P_S5+|UtrX9e&YCXK!%aS`W@}cpFz7f`jbzvkOS8Ca7~V~bGJ1bq z22OKl*$uNIeGWe-tRZ$!nOaup1|ex3`qi5n5D)^?N)Pw9hu9>8F$A zT=FJf&*i)cDPj{gY_z2p!-*xLfE?x|GDMIJXDwWo?(gqQ4Ur2LbevItse60AWe{s? zP7_4$nGm^YkEMwJ4Ul4qsRl>>Hm@iG44^dnoc(C!v~z|j5#U*V=Hl3a8KYsl$9Nn!^?X(QRqZOdCkDPv9=XB8C*H^__} zNjqOr=yM)^HzV|T;0aKh^Kz!`n!pJF_T6>0sdPN4Q|6r#`xe;SM>0L>@k} z-Pn!B>VW@1+k0#BzIHdO8tpj-f$djKix7)X^n^dJ0x}|$`|Wz}sGgHJpZm~%ZS~?k zRyaJsXuQAr!*s5h|v?HH?mV`wT{6~=1ZpQg(!u)l<@DtejHTVXhrsg2AzDr9pvI)C)J?< z!mcRBuWxb1Gyl1E>XU#OxXlUaR*>yL^@xlhCc>DO!V{#!B^uSK;p?T5_+8b{!d8tj zB+dcLTB@MLzbeo_?k7nM?p0ZQPHH?ivqL5G#3cS@J7ld1Z@wI#OAP5agdarBow`81 z)U5UJ^F`?3V5nx-z{)d-=JEyox4KHn6qul-z=}j9+9N$;lH|@)^DHCG z|G>r6wKa6IWu^>Fnf(r(Rt6|syU?F^FjoJ4=U3eE{Gt^_5&r0Xo4?M4CrLg`M(kUW z{{!tiW5dAF+Gs4SmL5j}T9N@Rk&wzXIl}Ngf4-|AkpxN|7G7-s>mBkG?-{E3ZZg}c zqhoiO*A+IZN4-LC5&PLAL`H{MhB446LD(#&>h-%QmTS;&osZLHOgy}!nNP}=_c=iv zk6W{7Zl_GT>oR!FaJ|*S^@&nz%%mcWV0`I#C$(Z8uUAb?K=u59y3>3JFn2wj-BWFf zI9SPK;|O6Q3MRPGkRB5ZU_!INY4OAp-21hSmDD?de1`&IpBU14X{U^+uO=s$d-r`| zvRRixEJ*VPX9a57$*d7<>|pV!w6S>A9BCLjSnnSjJUeZ3{(Iu|k=kF&edgL;5ocYf zI#_znpwv{p@`^VsH1(Ve+)o%k<#c>8RrMcXzk~ER62l2K?af*_%WG~(cqI*X3-8j1 z#QR3^Le17Fmrsbqq55M72i=mKshI z6UW%Lm}Grj_ZpmcGJ$JK=zPH|W7ResCC}se8s#2lq=KzmGznt>NV{kouQ%(hdt^vc z=8V+f-Y)KTHdkFdt8G$AB&9a)*A!L(EVPKI)Xsw}0B%2j)at*4H6PD*Wctm+&N)uA zHgb=K)8QyZ2VH<*PizUc|T0NfJg-ejn7}dtUwSLj5m9^|vz~wTa-^(K!WGZw! zXA~q3*$g*)q&hPSN@Um@1@6RwCL2{MC309z{IrYz$7U^?KT0>T01V@KCqWnzO(K^d49kCo9FB+P}DO;`-BAJ@aN(8cv%m8Icwii$eaXGam z`pC2FA-H}bN#q}-ljj$$`4Tu45YPg!x~VY<1DnYk$}lg3vi*LNGa)qmRtjk~RuS%2 zWuoM!s}0tG*+D#6SGD|tbv76%(^&h~9%h<1f=76h931<33 zBrZ~bJ7X%uCWA}MI|>Y?D1Ly*_+O* zO-T&l4cm{O!NGqE6|5Bt+Tax=8pfI?ph^LO109}RdM&ER0ZHr|_(iOznQxGLMD6TP zDQLZQ(kMcPq`bOB&0a!yLe1*tZ2t;Ug4PCX+RyD&sDfjE^A=<6M zI;z0)PBgYAL5!+bL~-)vKeU;h9%=g?+|5?|%zjHXY%!j@KNor>b%ph{0;Y~Jakht^ zD?^Pb37`}_c@10*6F(p!;uP>zC|Fj5mltJ-^Bw*yg~AoNO3w>fNTUcdVLO>O5>qM4 zQ)wtgxKUZWX;!oT9{U&5m2y35fXQezxL)1((n={+=-cf@WHc&khBN(qr6~B`OzCxL zf$3RpeH)(lEP(e4+=^pMO~_Kqks)Xu_pc~`cDu>oRHr2WrT{ZYEe-+<4dU|Z2J4R! z%D{kG{vW=}n6FHo0|fVMUZ(8pGd!*}2aVqfYbm(+Yt0B3hkj@oLC73abP1LkNut6} zcP#*8fDBENie`dQmHaL|dv4n=MR^L#yJnC_sdO~z&@>xmd>Qv$(^ zdOsx7b=oP77vee&WA~ZgU_Y<3BWarGA(mmWEPa%t?=42}$-YP1=rlO;0LXrU8;i*INo(M3kP$zi;rbh#k- z+}w!c7P>sY@xG7J2a~#c5fMR%r29|Bs)f_BR7+u0g7??9*EO%}&QrqKzu@S6yt1Zd zVu+R}mdH-nKmWr8EStQX=aapJC(9v#jO8tcI2=Baxq)OeCHBofAAZ?}06N7GDw) zF*ynsGen?_(J-$bE(WB>&hqfk;%rK-*i65Ijjnol&D2=mJ%EL@viD);g^OyU_ZfU# zrIf5pzg;@FAaaa8U z=3R31V&nNnMeAwgwb`aX7MW%S(e+HdX5)o?%CuY4W?B&cZO1BRvWia1o;}9n%FCB< zSsUnIU}d=+Mlyj9m;#H%gLsQx??lN#F6(E}r=>XeASa zyW4n&5-`D<4n3R(r)3@~kuvP$za#4**0O2zPomajO~vTz6_4JKb_utt>w8{-7x_&# z-Uc}Hp%AfMPOY&8c_##@Xm=f)v7FHxAPZ97wk8|Vv8kSr892%kT{y!Wy**vC;$iQ< zaaI5K0S!+CpOL5=82)1C^U(XL#w?$)Kr;8ja@kbVb*T%LnxUcV+A_wy{lO#4^MWE8 zttpsp?D@6z)_U1SxZb7Xm_}y0=jPSl#^dD-YL+fn0qf|Tp|N2dUrcU2MGz)XN{tVf zKqnnLhi}SUb_i2SMG^{Rd3-$f*$l9;M@&ul3DNl*;gLqee*=x?iS|6^xv%8yFqYBd z4o)mo^G73XjLmN7=54jtlalg9lsetxmIxp%hLtGN{$5rgC)9PmNXNDkmw&1(QD+Ec zFALf}b*;G0F~>v*tB*CA=uTZMM^iSiMH=*MNc0vTL84CuPA zk59sQdl%CD^|~kf6k{ArYhA2%A(r-0b_8YWH6ef!d)YM?pPWRsa}b^*I-I@Yjb0*8 zfOKYTvoP!@^Eh3B-q@I8$dsq(cZThFU!qWC&iH9f6Jk`YrQ&>`%lY-AAF)V)!sm0@ z)0fjd`)jY8X?W!_3NncZE6{J&JPuAteu0G>t&CGpcRh$o{5l-I+UJ52h_Dz|OU>CU zBh3Mnq-bDQT45EAKHev>VFvM)e)0kC6HbuvI_MAEaWLrP203E+NJQ;r@>WH+KNNyx z6@*i911J*2N=;o>bI#JnF^hJ0K)3cC5i=H&Nu9F6h#;C5I!eR@xm(V}x(!&TvmUW3XS~mZO zZx}f?hG8ta`>vT_1PEiLi=ewufsW)!!EB!5ttCYk1uTn3c5vT{2!JMsM_K_(%q%x4 zf7Sda1a-1`1e>!+*3xU3y#G7tg|i>rolyrR@o8%l1Lwn4W9yZjW7flNWcYvJ6Hy*dMjmStiPv4`%q zAJEqkzugOw-ulu?=&#y+DjE|hbMo2r;qV` zvMYo(XcwJT*K1!Nzqh0eCCu5Wnm<;KBf_LeXsL1;!(EsP8!34`@)?A5b(!|!y*+eu z{>9~Fyv3L66y7@1^9wUyFY7k%n_&b`awm64M}80K4^OH2{Wgm#P<+c~nrrzic7g9G zKR6{K57`yxf0|ageingO`YIO$Wl+wmnmZefN+%y0lP5+bmiL<$A(9%6 zH3oyJ$RdS|2RniCgAn{~a7IjM*Ry9Gvt!p{ikm)C{mY8+OXH6tgLJ}wn6Sv0nCobl zj;!Hq*GLVYYvro8Qwm&*u06GB}9e)x71>NIpvu zNX%(Xh|z(w6!v_Y?W*s7Kr_4NHA@J>X3FiG3#sRESK@!a4s=i5Oj%fIXY2es*@JsL zY*M!ODXF~(2=nN&XZ=sbVJ~zfQ<;88Fi&R@*&-TOD2|?#*T^(*wBK&!T!G=kd4-j= zw896Gs}5R`$s0yFHuT5u@jfT`eChYMu{D_X%J@V44JCa;krAc)g}T8+7Y7%gGs(Gm zF4ZljA?~ro)|$1BsYq+PL(8H)uW^XZD!)d!%GUYR^uJ3zkxW5yb2ALr7aVP#;eV#6 zmCV49_h!l;oR-~h;wT1dOTi#fh*{2yBhxjRDC>+r8HCPchW+ZOT3*nEY8TQJSEOh( zEnvw<+Whgyhih!Md2n6-fx!O)l4`Qq#y+05rxj(n2YdKPF^zx(2pE!L)>0`$3Sqo1 z@Oc~lbbq~SoESv<>+>U;#w8&=2@E2sX{OmV;~I{E5!Yx>p6&UjL=tj&oE^5QHV}_- z2Jv{5aYQi#FJqc<2Bl=V^2O3cv|6eftKRESQJ(IHw~&aq^=hWp4~YbiLsXwH)v+#x zqc@M$UV;s(0h?ge$0uR+qaP1#9Z zWcYNs+40nQb#U2!bqKgY_v&*#fKsp*hRyaL-_fF|XzIS{^c{;ifbPN%8J1(+27TcI z?i$L~ltHs0rmP985{>opq}zWX5C3EP?tIm1*w2@D=PKMOFKV%Q6G(>U0UBlBDu6SL z5jJea}&u^&xX3`jJ6pXhBQSR;+P>;OCI;efaE7_D7 zIebH>p z!RXsi23z6$Uc|su_qFE)X3f?O~n6EOe z*s{c_o?a#3K&P){n~%^3)S)I)0g1JU3#ToZb?E-U4;AUyVlx-(KE4q&Igsf9CJ`DM zT`U$e=hHmklqAKh>vhtrZ5oOBT!{g_Zffp~GH)EC)OnH6zV=7Y6%k#=Ud~z}TP2(E z#*XF*w*Phi?{p%22?A@dSn!v60TbZ%dr;@g6oc(AQotn5(SgHH7N1Aiegb|>-`Q^d z*@i4Q6Ui!uj<%|Xfr=+0kk&^_K}$d$3dIiw3Cs&QMKREtEu?z3)70<4HgkXDh8f!U|9-CzJjP zrB`rhX9V}q5lN8Gk>Vayb^pElu0416&R8b#&5+D7FElet^Z;kTIL%Hn|BUDF`A<>m zKqg>3j!AK)DPRl<@z>G3_u)a>yym_jF*Hx)E2DUSR~2Fm*BA!&$k1f9^TzY?emX=Wj^zE;?32;_IY-OD%^0DFalYA} z661YefWzaNnl}n(Okzx=wsbSDAuQOH;Ku@_sg_5_I!TK)vdE_m(CN!;i4ceVj#f;M z@)aTM8;6slxazy(I+yNa^_UJ;m-a`EgPGSNnpZjL4$ac|G3J z?Pt?>h>c=;CPx^K;84ID8qDinoMA-r91!XZ*&7*v8Jb%{AB}4Y%Y+eW8M){>+(b1R zZ)pkq0VNw9`{|Bxc9YK*oAEX6KPTLa<0bDxWD*Y)SCbhp4Ab1*2X7xi*u6sOxsCkd zVQ22Xx$|awUt3pMib<|lqRK6wj}b~3EIatK`Qz8yUO@*QHi9_qHHrxe;k#PHx@Dt& zw?t9qoY)PA2W7N>Zv1_jqD+~Q`#htSD}#X}M})AV_d#%uXmqSctj8EFm_rS{{9+Nm za8Z??0#X!Of%@7DuhJmUQGSfzw26G*D{@I?frm}E$9FS;?|0zFhecYARCmqDh~Ezb zMfjSw(PSi#b2g?^vOGFXuH0*_6t>gKz%wOAW@h2e*?otcHyi|>Xa391BOadjX`aZd zx0NtxqF}EHy86*ACu0$M=EXNp5^1?%8N-7_qE(b!wMZI}Ulnk*Lv!ZC6;v)_io)?f zL_~(zye*+lEZ=z|>50Vs8UKY2Zn|tyQv2s%PjM1?JUy1+b(@J8HnmY`I%% zOq*2}ZHixSAW4u*rROgHMT%C>iN)-+4mSMybFqZG=hwz11{taW)U*gtfj0Q_M zt-82|GeyUam2_zmPCyFDrx+K6;Xzr}14#`Kuq((bivvB@)5$+X5TcL|K{OK;iSM3~ zLt8Nikhh06-mHa=bDE>fKBy$(3yV#3Gxj(lqoQu!y1(8gCMK@qVmt#6l8kWOj|tGw z(8w;wK|{eZPoPPPP4?M)!K)%#Kdg^Mptb`HD=#Es%_A;Il**lqP0|y`P{Rl9ZeKiO zf(;n$aOO>!ma3f`_;%cB1O){P&BD*DTlCB-!}e0uD zaQ1N~I*s`s(@of2BB(9h~sa9Tubl6rC(t`Re=6sxFo+6Asd3CK!VfaDZ`LZWb|_) zDVRTgbGc8m4O*gtl$7*LMW;}`Jh6_eLo?UKn(psYN3*4MG8f8>R#v=C=Kw-d1nW09 z>`5T2bM(Mo)k16z#e%x3Kv^S`&n2DfHAm;r!L#OQWgK`Pkr5R$2<<(tALDZP=6SC! zTd0&{<~h=i%ivB>+y`^qK;wf1O$kB9GPPjuzOzooFn2Fs}VtTS_f~% zc_^Yl^J|<@HAC75!&-!}L)r<6KX_4-=tn(W6bAn>{3O=)s{>y)o~XP(P_uzW?ZF_U z5l@1gBMNQmbbqPwuF{CQ2!*Uj&fL}ji%yp|S2IPXeI7kSI;(<2l}HRVfKJt57CC{e zvUZVJsHnpn-VOx(KMIcUnVR>oU21Bo?rY~ zL|}3@o(L+gG1Ho7N?kI&u%e=3#&k(+KCq`5heuPWYy(>Xu380KH&>M$QIy{M*dPjI zAUiAg!yW1lgmudajF#6ST%=JDvCB<(wVfr^^ba=R0Nu*30(PfH%Ce$k`h92$!AMIIN`5HpN(RYl5 z-$svrwx9$UcyB#V`UD|C05ip6P3K`B7zAt!R-wF*ULEh@jcUfGiPR5;B->0>eJwt$ zh|W(E49vZJYjNKK9ANq0RzzMiPILA5=e%)7<8}x0KFj*_RKJf^*VNVZneg0UR&_r9 zH$!~{j%+fWKEpB3N;DMT{Rn{)9uN{;LFzXZLLcnhE{!u>el)}FK&ZJ~q)>KG6ai#; z03;3*lVj%$B?=HiLYhH+=m&_V@;~S*t~(wjwm30t<_frFa@8zkD&Z}DvI{2+Z8nK5 z*n6+I0OY*%mpm>_+-b$1)rSt&qR-2J%!(ba?-mOw8G$eFuZ~aNq~*m$5zuD`%ct*0S@Ge31QE4cX*;p>$4N~z{ zRczfwEsa=>vdh&O5W zcHD8}6aAL1L3eVhQyL@2ih>~g1h(<>wH_cq)-2tg*H7PGeQtgYoy=F?>?g*H)pd^c?2Boknrp$G^19w{aVvG#h1g8TnT@iS%g?0k5FppCI0R0j& z`n+J(HO<%xlXfC*=x5d0&g;%=a7WH@16BjppTxa*A*~M0Y^KxQ7Z7DJx^(=Bym{~w z*LKF#8Fj+MZy9rD%-8SV7EQWCvwlanpL05T0%b=<(Y*LgCxe95rx+BM4`F>470tCy zmzx8yD>s)?!udm}$E#d&9it-x8`Iagtiv=)6o|hFJ$AAg8>}~y<+3$8{jo7^x9#=x z6P%z`Gy19f>tofOjeQg(`-1(jk&%wEJ(Qo0gF~cDsqbmJauv%8NLBC(PLBGX@@Fzi}bx0A-hO)!zbLDTg7BAaQF1rVkUDUu4e|_C>F(mWPcd>+r=@d*;vL%Jm@w-(WdE%iLCRiIuc#f^#JHl$dtT#$E`S4y zWc30Gq~;oyVom6@RI*(*a}~ESs!5e;Y%Z-2dkj9tKO=~)Q72y!$fA@&Iknz<#w)h5sYRZm^co<_FmS1n zojAZ>a0J96Wp4WM>l?a%R2c^;WDAhb%S2w{?Tv&9a=qQds21eK_(PL_kKR~Osc@pR z+%kF2VEWz8koxV~0mPd|*R*e@V#y46)un6YmqsJfjNKsGFKd4`8B`LVHnBN>*_Q#FJoSXD!ic>$U4+;?Jf$mZFP!LRq-BF4b#M}fhNC0{ex z=isu7q_Q4&dkH73V7B+G8P8*F3~*Qgj$)`QpRc!<$?bRPp{EN@6Wh%`f6=a%8%>M( zQto9!sDNxC8H`}Zb}dleo(GTeHna39^`0d)ZEX@*s-n7-Nq;Ek5{L!$h`o_tsA@Lg zM*7?{*Bx*c8;veJk{Bk-OkCPT(m->ETM4wyDC7cz*ottzMFTpbG>vrQL51Iq!9a8gB?%qW2W!rHk2V-Ds&9dVV#Vzg+=1L#gi#HU@jUqQY z=_Khu!eZFc2tc)6z;B^tTx|v(QBv#)5`__#hXt$HvqdSK{xIyP z1oY@y+0Ulo+AvvQzcuy{zBxR6!C*hV(di7ROByjXTQ_G=imgRKkvlA;v@4~wvq{k3 zopNO#8AwauG>)c3G@MC?6AG^CE)(gwdKx+%CdyW&5?+d+gh&*Mha-XxJJGFW&a1l+ zoC4m1R)(dOF8cxdj&GH;oksS{kjNR(FmCWD(eWhEjYY(NBgPBGQ;1HhWbPk++Pgf? zcj8vi6WOJNmE8c#yg31h7=AC|;Jmeh+k`Ab#=!jRz~khqY!pjVfoG6Lb z3rxe&%=;R*W)wAx6w%|#$WKvoyxk_IF9?{GJaC7E)D?NM5_`Ey<>+TQuY_CH#oZ((OoNS*@ zw<=ECZ{jR1mugiSyo+g!YIGp0#!KoEEUz8dqLs`;7yyX7o{=$-ogYI&Bp6IWlvMjG z<4)u^ie&wtA71XXs?FTni6|Q7?v~cg_MN($_*7I%Kry^4=f@N+P6eeY)6En^sMVlN zGMnzXRkZ2~oE$MS3W13zWB=g=`;iIL%)*1mRMUvUZM_hN?`Fh-x3`_9Fl+R+!-o+z zwy2iS^}G$+O$rBE-ADrQwn#jT^`$#? zixX$&Y;@y#xX9v7>o{{k0v*1}Hl;$ll<5yO8zHaFeJa+C)wbOuG^kJx)9t~LZ`gy_ zPE+GiX*KS;&j{s@4@ia>ZUcxg-hl+HTv~OQ3ZyEM9BAHBBNsNN_<|)alN1Qyl>Eb zezx*ju(RvX+1*X1amu!;lE~~jY}CdRPxRr7n5PfRU27?` z76GKEoU<9D`V-~mM|BUO!>zS16D$x5I6=aqi8%5RoNo0f@B=ip)GC9>LHYP)naQ~E zAjdUo99C?@b+abmPRlXl4;}g3O$~?EVl-KW^mRX%y2&Pp1<3g#+Mb4m_#Tve$9=f^ zwoUJk1BM{`G@|G-8k(EFC+%DY4yQ(1i?=JhD4|B_b7{x_sULMMP^2-8C;? z*pS9a#0veC*Pv%;jGPrkR26EEQq}I`zQY>L>qocgu1(gYDO@zKgb58A!AbMJCFPZ< zRo(AJ;2G&h;GL-ceA78tTDK0`nIOKh+#I+kX;vL}uW|-a_2HK9N+YB5GneJepKPdTQ4L@@q*J*ZUDu~KPYeT2?OVBq zFm~CdNVLo0{1WMd(`4VdbB>zbqdUKJbUI=l6zG;_Jm0j~DrJ^r$p&7P&c@kAy;COA zS}>N>(M*y}tC&h@S#5FrW`l_qQEq7-%oFCsp#AzV`ey*IaGsPI+e$6ZI1$6Kkj?|u zh%X43Hm}*7k*TNQ_>Mw5v;{TL961+6q3p3u{Z^ON^+&`M{r6qt@dk!KP9fLHX1%g8 zSrpd|T$KGkz~>B*8O6=^O;_I^%%QV)AdRtec-SuU1bmLAkHkh}% zN3=DfZfg&+CI!u_i}nLinJ|v~RKMP-ROY}L)^ZX0p%P^oNk6h<7tbal*Q+Xx24)MQ-bb2e@>)Itc4m3YCO5;fwMl0h-1~d(F7+VUk(j`0>pt zWaKQFXoW_U6}nk|n1N)OlC~FaJx}AjJm~O4&C*;c%^k4Cyku=SA1Op-oOPa<$q49M zztvMnwISW4MC2PG{jhh5fDb~Xnyf-R6m@64639)|XTl+tL83w2He` zY+gTuzz779N4W_S?dlQyx+TD>gqT$b5vdS?XWTl=Wx)agV^$>r17mo)wtcL-z5 zK9VV{J}+!(&WzPeNri3=m^fMb$zK(^1g$`Uvn*HweOavgZm(Xt+Y)gUltRq3t=K!T zVd0P%@;2^$rmt!MG_j+C>*Yz`Lfh3M=2u+Nq=1HD35!@oSi%sr9*ET%)0x~@cR2q* z==}T(?kjHKk1n$}OfR;}d|!xzFmo$NIcs!kZy&y_Aj*^}NUXxo5dFpa?9- z2wG>i&zF>+pnWq2`j)1hDOq`X=d%`k84ppIzOzREh;w-d$78LG+bf}_X>~3nF>TQ- zKtlGcJ)7@>7^?8}og~sp$c78#H3V95Nu{N_x2C-n+X}mfDz_yK- zWfCpradyq?MvscJH%{L9N6#+23tQP|wm2PWZbAjY1%s&Hk)ywFLW1fqyPPy|KJ&9@ zM5a^ja>N%UQB3nZA<1tX$bQ~WyKQ@19_@$iIj%KYEstbQjtL~;v;I$hhB3{OBm47O zHK&?o!}w*M^p1#;wRsk}6l&6)19#MMQ>l?HsJl!`WaE9YY5l(&AvOiO{wN!uS}06Z zQu!Nsu|5pawe66dX4WgmE{piw>2GZTP-8#*@Px^}i%+Nr8dUTgBOa)}I^|y8dZKdTwF5o1G?Y>>T@j-_x1zgkQGBvgSUOK(MR)A%CQ1^ z#D#W|M=vRj(dTKp`mYO2de$!RfvrdkAhKgCpLyfq@U%fhGG;EYga&EX?$oJ>pqk6V zP+^VfgM;i{*J3vK4%^bS3{5^BuY!%@p~E52<$oqnyM(A$9{j-hnvn|{`6xm>iv;Qy zA$D&1?r5)@+HFW-L3yrw+Fx!}y7^h@pZQazCpN?@gge5DLl7`(Qskp$n}0q00X)C7 zkW$$zG3ZU91#S&Aar$;gCWsI%m(;m5pXq=GHLu1aO3T2`9=4R8VbkTNmH8p+b1%B@ zkHgCj^xj=F4%si?Q|P$5W7W@49wvAR5>SALy8=L_ANVT1z4?7QI^252u!&zkDf2u^ z4%vj5IZV&gEpX)ka!3PJZ+3v4zN*2=U zlPuY1x>5q=+64`#b&ZM`l=RNBRDiV9aT3NsO;NzvZhQ{TzoloY^jj#LS#^j0v#kuI}_%kOM<6Hz03u;^U#5Yq0y0 z{gWH7(&p?z4o76>+lg+gr+hPA@&Z<-l>^gA1MC@yzcfGFiZk|3NI52hACD6RVyZhb zvo=3UMCx)eeVIrb&1pJVE{nB76{Q)gIcyB-i4gSiwk_CyP$##?)}!Ys$z-uu@1-J9S!@u5AW3HeAnfj z&(t$;f1HTiABl4)??VgN^!dil8=-@C>J?sJKre;1&P<9Ammwv%d(IaPn8lV56za^Ts=l4+|&?g>+-=PjGaQ0fNsfk+guD-U0p=5g7N1=(5~ zeY{EIgn1JgMJhBsd!!L#X-jyLVp*)lN}D8%sl(?&&Wf zCwRBv3w+IcmF{4+hu_AIun_?pykXSJxtjh4!-$Xw1Y^XRA>LT^nxZn%1UNzQpblT_ zwRkOfVIXmjnsMl4u(9f;$|^0FYsgg971w}(tI%>}-NV4bF*dLQ1v6h__bUJ|`>N3j zVN9OMf*Gge%i0_0f7nupqREoqss*mx|Fz%?@uhPi;7ok#Ib+>q4cEAIg2~fZnfx>jB#O1N*eEYrHQoz+X9i_kzItbqAgaNGd*Mzuo`e3lO<0;6OMr z;QjnB<~KJ&9LZT*6C3s3dTUqYNn-qh%3m=m|P3OR!N85Jc*iIVT zR@2x?W2dp5G`4NqYMeB-ZQE93+uuCjTJKu-FPNEo=Dhaa=dnkg^m311P=t4Q2z595 zmhG1U(j7r3U6K^$2jN5>2bHzg)X?*NWcg52HGEs>8w_7-4etGt=-!tlZ#CTQUY~0`fz6ch$c? zhNvi)d?^ce&~u+5h+bzx0fj!=)+3}ZOYlxB9HqTeN+$v* z&C4(L_G)Qhj!+7U2O6lYlcb|f4i+vt2pfavCkGoPa@!|8qKTJ+h1$I3Pk$)+dC!Cr z&3$kembjc};{$&#;D>axO8qBqDv+2^;?KEaVP%avqSlP2T-I?+x)QkK)o(d0#yerlq^7Z0JmbNX5TsO3 ziW!3v4ez}9z+v8*j7W$$mGWNy;bIG+BwRuvK}P-SU(F*7agCA?W2{DoxJ;C-MmjV1 zpkf4@>~gjhirw&q>-9=A(f-R(&XGSfp}wJ^o@uZyy%6KD|Kna-V; z`#pr|LzjUQs8yiPM!XgYijuBsOh3*2&uyw1(-G%i`5*z*DjK4 z78H?SFj{9Sr4aVPu|Zw2et(go$!LVKFzj72{{i8HqVIn=`17*u&V~B|Gh6k0yJ()G zgITsvMl_~D?H82xf2Ps9@%CZ4_qWtol!RMzP=PD3ub@U{kQL$quj^qHDUzt(waDu5 zA#AwdIO+(GzgNv04)A)fbE#>Wnf>Q6+CWCS>~DQG!Z*xmb& ze91hCtTJi&O(3tZVEbm@-Ol-fsy}6M&4+gjRAe>e>0xTkv=7k_mH=ELQa-o1sc^Ce zTTl3KnQ$bzyjeEib3&($!4|l1eRYciiJ0i9#no>ij@ywdrnsTS;ffM#>=fTZumgK% z>R^e(tRoh{q6g98@+gqN#Es{fLyY~Fpvo``Scz+)K%a#TYDRKau~IB;_{E&NgqjHe zvu-?+t|f-_gi%2&tAI`0@ZaKh2m@6A-nx44X*m|+(}wHL-lTlM90IdQ$TF&!MV5d} zzTur?>48xCQP+yNMA~(CVb$+*Mxd1=4#|XDka} zzzd;!Wlu}vcMf4*_SNu%H;5La6|r!8-tbMr6b|RK$9LZ${+AisJ9<{zi0fhxs_Xr& z_6y{60Cix1+RTzJO0sMTjgs>F8;>P}ViMvL>X?q6mzkN_N^|wVoYK`iPvP)$++N-Y{GcXrJl~XIZG&?F8N~&g z5Vg>vm>cyeI~ascCMig?5Ha&oPIFk5nlIY=`A5`>n}UkjRc--A^(k)E$S(r^hz`3j z7K~u=pU+N`uza~UWpM+z+9W{83asDA! zUpr_zG{VsDwaW{a zMRk0NMJ@UXjzV0oZhS5vH=Hu?HrqA_fLDRV?8oPrEN`Ud{&6Xg&6shG{5Lqm-RGRg z>ktnjIW!W`=ef;O=MFQS8z2l@%N*!^uT@y0E4JaxaXNw_+*&R&&o%^;FM$HF3buY> zqh3?R&^CnqyAkLi$~5%pawTz+a4lrbn{|R`q;uW$b5YLs5*%-uep{&@G~mL=bPlbO z=!N4ZCwFP=(??t~W{?y%`xXc9ys;+RJCYn%r7DoW=vN>uZ2e$N=fo8}_zkTU*IXj= z}~Hmz_x9cFlisd>e1$VNm^461k9AU<$aTRE$w@dv%#x_g(9>D9#^_6DJjMauf4mCP6z+yul!2jP05p+Toaa?1mLJheJkh^?qE9nkr|C}4 zclYW2)Km(4`s=Ac2<5FvVW!KrOoEOg4a<6e$bw zuWVSsNMy!5&g=0CHF3W*)8^0RKOCG*6kS(t0%G)%R-58xb@eneLsC!q`7Kmf4HHA? z09a6R_MceNoQqHn@XaxkzrxMau%mTceYuIW-smszJ$}rDaX{jNV5^h95pb$HtohMl zfcXdJlk2cS5rrC@6sXZr0|uzcK<5HLT?P_=&#%kfQ#!7j zl4hkcu;ZL}6Si<*n3#~zkGWs1g$^i1a9JLxm);yJ74U*EfwS&O=-?lU4~bhl5bRmf4)gfP)se%oT&tVHa2LLTajlD1pny7H79mg32a^y zKFqVL6qFc&4JARHVS|M{*@OKV(A!B)hb81)8*_$yj|QYxAS)o5j$;wexnQUfzF}|a zi7ND`;cBMF3mZ~B8C`iI@1a>X#uS)0d6cg&sq??@6YXw)tyTXw3iHUw%ChkDPcePn zGAVnV(tuE=ogq^GqxkQ-@f%kTW^sm(94c-y4n2WHvJftboj368xB#{GZ8bsvsb*IG zC}1Zo^cBApSu?Xf&*7O^o%IEb-jMJ0m|4Eoc!gS0|Dx$T1rfPnj8!iKa9_X3UHqv~ zADA_kN-RAxd|Zv`xe65u;_(#_woF+Eu3$}u(U`ru6$wk*!w;cTj{<~2u_h1^3 z4(wP8l?v_K9>85`#7ZhAEZ`0?mrNNrhH#UT|Ko8xK6!@;`;2R#OG!ojz&27Sx6T?W z#OHO2+kUOwHgxbxC_1D-BI1wQ=L~z1@$!y=dCPBu1xHU@ae#Dqu|jK_%usgL9I{^* z^dO4KryL>yR8 zHvFzqeux^8N~8?qM4uo_4+=w@Yz7`Z$u&!l$@w?I!a0WoHkE)xzV9KTwtove1U1p> zmHp5T&I`B!T?QLy&&M=k3C4 zKXZF0Qtutipvn&-$LqDdW52514f?1|hF;q$)&RAL_4W{pMKXZXi>y>_zhs(y_PY?`M)Kj0W%G+8mu#T@%ijz}ot&?s1r*KN{(I!P+F2N9y4!G^ zz8f%#y*W)^{e+_|md_@cc(Q#ww5n({&yJ&0br~S?a%t*4I2ck8sQmF?$1|W72*f6> z-c3$Vvv94xn0c6Ehw`W+DC7@E(uzTWCi60%ArN6&k*!hf`}lhy=WCtJY9 z@OZ6Z4FdGBSWC#P9=}OAOa^}CcOwl3``-^TGO~B%?rZq>xvzKWXCa9MatI;8O4Z;| z$)O{r5>`-ZXvcT%(rRKrLsiRuWhTENdDn+r`AF7dx-V1F`V|6QW(IOpkOSl@E}+LZ3@YdbIaEOspyKc*`SpU-*6B zuFc%H-?oO;x?fdtydO0_caT5PPmYhdtmU*+D5Dlv0z+p)W2^Wl*Z7pHROMgEP?t*C zZ=mJmY^A&o?OrEvVhDJK;>pBY->TYM4~sK3w6pd{fv%cq>vL)AEVK~N#5ZKc>PovS z@2A~A?pN*GgVUdpxqpy1xhB*q;y}78!FF>?21UHiGcQfkXPZoknxX zcSH1SwF~swX@x#_h%J%hNxC@{Q~^SQ_QC3ZNT(*baja`B+Df|Q0nbB2a*t7DpA6gE zBJ*N1YEWbZ$}-;X2d?MN%x|J!PkYeS+5NcM%R*r03LV*`{kQ@9B_j46S$~uSVl`13 zWD*G5))&=cBsrGv%{^57FH{rLQ+5Z}Bo(9QG5y+vXCY3APWfp(S1rM#AIcL|Eb)o#`gP>16JPH0#hrjQ{PYSeGZ<^kZ~`nHmX7 z;nAwTQzokJj+xI1ARixF2E~bPx`|&>*piRKr>qI1Q+Fe|6g;C`(^7KNrO1GFLiq6Ks0i2;V1mswdnct0RS!p{vy@Br=(;xU(UPtYq zX}P&3R#pYpR)eDC<%?yzUr&IFqI`*`2KGZ8x9R7@0QqJatW>Obtdxo}+E1@tq`w%c z{*eQYQ`RPM@SuuGmo$-wpx|2->IF9)pK>jQ@dh^wY?Yc>vhli|hw2EA$3Ip)FNdL0 zSAJVEv@-v3Ovyf9-+E;C*Z(B{x`GQdywz%Km6Gt#(qs{6sRLvPQ;aVb?`}3cmqV_jwhWgPJ6_sjt|DY(tgY8 zj)0^HxpGLqvzHF1*B`*dI3n_OS|ZtwNa%fU|6hj>NJ`>xwNSN>kB2I8fuqy<@JUne z-I3kL6`2W)42W%qZZG!ayCpn?=Lixeu`Fo>^ze=2dM>KE=5H46wp|>6R9>VM@B30O z0DOBlA%O2ok85zSw6Z`GPfveDp zq!236+ReHkIdSU$T{HOhBK^UR(Rk2Ya zrIX1Z1xzDIp)Nt7wFIE2DV0f}JbT?~#n#(?fkL2>Q1mJCKHSeoMI+SLv- zZ#*uoGgAU!&isOk2)AA*F??ARadhg%0eDlpjnvVA2o}b{d}|(NN|Vb*cPSBo6ls?m zN6BK)OQpAgL)Wyr%Dt?c35hs_oj|^;^VFTGuT0};;FA+R8r?0fI^Tp!_VwV1|NOP; zc}Lt{_11OgIJLRGR^6^wZO%3W0s{si0k(mqNKRpyx_pyzE5l{a>u}zploS40a}-FMyL%ND2i;I zP=4O0YTk9*cKgw0*Ldquvsd@__8T(q@K>G9#8x)6U!t0cFB5chp3044pr?I1?4X&h zDC1NjPfPB)A~)xMV#m#BAFA+#H>9 z(8HZw361M+p43Lz^vE@4rdWC}XSVtcd&je66S;i-h;NT^L3}-bR04$Tr?Xva8|wPV zeDA0g|6=3f>l=1RRWIjtX=_nj>D99T{pGJ~Mx<}o$)$aTEsQw|7FkY(^}8XjYi6MC zgF!%2H;f#P203~3kmGA5*dQQ@U#^>?V)?AH3kxEBLM@{hCLRsKa$9d+XTwa_^dHgZ z_fOkT!tP<)YCP9^E_7S|J6ZsMV|-;3)X|ZzASz>QnAJn_F~Enhokih#{u8b$l-G&O zeVHVIrdCp6PM^8d^3RVeO@D@ipHDHpalawg>uT0lhMfI5&lT}YeP-Hka%$a*`{!D} zA#GfcF{)=!XOo782o>RQ?81$Mf?`(+Rafgv&^!bBB|QII`t&V)_qC&X%4FGm$xHP1 zv-9Vh_ZznNso~Z@a@S}BUL57fAqBR^8O#iAXkK_rh*tI-CoqELGi#^~t`0rGl920G zMWxJ~xTIm@9Ul4qD+$|+Gn(!mSh(~)&)5>G*By83R6=XiN^>eCI4!B;oE1TU~YR zcpQQye7z1`a=z^hG|4B984543r*98Gn>6GhVHQ@cT+uH5rI@MJ)`ef)I8+DuqQpO* zWX1YlN;Lxc!43zp3A5_-^cnk&f3-o)av(e=W`pwzb z`+4!@5pvfvwm84H-z*+GyFUdv8(8F}zv3+qt$HuW7T$0f?<<=m%OB5YF4v`- zS^KlQ+ACRy$CZ_rO``1A9|dZ=^?0qY{F%th?_ z4PhsWrJ^F}d@Z@vMoh86BVk&N0_60;#O2~vZM2!LO+0|)D|+}D=aUch%=6@{(X=c~0!R+c>xUzi;?LRJF9ZM)gWsc* z@V^}bpfgPTV%0I8_dJ;n{ZB)P{3paxAFq<7l|`PcDkMuA*u5X=a{j$f^?d&wyjF%~ zeROocepq4}fih1S$0_~9lw#R0Y<$8(b$V6>#&}9pVF~)-{pV3-ARdQ=-{Q{}E}1}G zjz${h2}dwoZYkrI+By6KFDQEHv0ob@3N?ymiP&Qmfy086c7e zlAuEDIw#eNHMP$bDr2fXD^xH+U`QkiWvQg>^BG^Vv@4|q#X3|c*?k{JE_g>T&W7HJ zzMALp-Sr(OU30#s9DkXGT;DQM>A7XAeO;RP+%|t@BHHHWn`a_*f=2%H<}jp!<6+^v z1bN}`SaG~-ar}`L{1f+SGkozv2p6rLy>pbdOd*I;yHZsW0``QBEx~;AD#W97ACI8MX$+so{b&n9?nvsSVa3fJhXi`WrA?!N8ep2Pxj@M}l z8VZX!kur?w>BK_VmX$lOt@|2C|DVuNeiU+;i=E%(*YPi6BD zhwoDzH}C*1CTUT$wN@caj_(b{R1V+x%r#0sICv==xf-pJ7JKwzk+VNU$FTmMaN#J3 z1*;zlO%+Gv86Toy7=4YK*%*sOLR~|Ra2}i2A+jxMp`=V+5}8_y$G{mlw5h7^<2#7; z4$l#;*U8B|Z)=h-!f1HYw)=-4%nypz4R&`UROzmb>IrklVG;M1Sm(sw*qZlU+N z#2z|IpSK>dKW@69OCMpzU9s|1Dcnba;n8b>jkDQc4{U!Wx=G6d!>2Sw#5Aw`W!aHL zc|Uo(OP#|qLsF8+DGVvvT#pcr$V9UAkrpf_*b~~YDqXP2YMOQUrnQyPxQOM?JZ;h# zLn|}O@&1sDB(ciL5hqw7vkSyZRJw76%s^9c_8tz54@mor;+Cp$;QadxG(QiQDVLP0 zmUG64pg@>cx}Vn$bK(tSsZp};1XxG)axx4P2o)%42qP~2jEmSC~4{xT?-O^zf69$w{2oCPga|v5RU_C33s2ftKV5RRQT96ZdQ^v zOt~x@d>G0EE-w@OlV9)Nk-qllZ}0G*n{6z<{~Q}9SGi0i_E9L#_7WU$Y6hF)KC1^DioWsy(&Y>xvceYX@|tMi_MZvCNLm*86PI#&^K`Y1EXbdGq~>#|w$f;c)%_gV4K#j> zhvkO}_&#b}dPLf9_Pzh?*M%@b7;CCMGGh_H5+mSD`i2{q7D_l&*-*R2p05sS9p}0k zt_T$$bi6{0mC7vt&M@RM8!Hg=Q6}FrLwqXmfm6&2v5C19dL<47?YDVjuEAyg#__lk z(?U*2;jt+AF+&K9EELFq&0P|8-~Cp?a{OJGgb-`ywH!}SfNiasizsFBxY-fwQVfx@rut*kQf8B1OuSnEN!y{deExUAtSIF?e+(E9 zjdip`katt3H8`mPcWbl{sF!v#I|`$s#Q7L=4L25cyM}60-Vf^Pfsr-DV7Wv58hIA`vSd#k>bQ+bUS?!UOMv%CqzNP-BsPs6bOB=o^5&ozLyd;)=Gp zM_HsbkM_CXTu>vH-RUP1V}mcH$_-JbLPg(KCwfIO?1=FBry|oHiA^B3Rl`x9CV@Bq zo0J!sw|QIF1pM!|A;ouFM^mFeMnA)A6{A>WVq)ju zJtw9Z^qq=f8lo*xZCjh(?m|ttFr?f~U9R%A5lWe=YCJu#V)@v#_pb8-MK@6j znEuVKz2?P|WI7v{2cJ7DKA6nmA>D6p;WOYD=;Uv)Dca%=>-61h_0*B4qb>A6`o`uh zBZl_{37@=@gim=sDVtav4IS0YA>4NOc7z9$H{c|iJYcX`JRCRQgfwI^X2G(qOY zxSMF$9c`5JDz=+!x-@(LMt{f4Ky{3?t$-?STvodtXFR+CGuR->@=jE8PwUMaEtmS7 z`-qYemNHZd!nmg#V`lN|_QhSN+Y@E6Zw&g;EqG%~G`!jj?Y?|*pz8%2l?OzvH#?+d zHmcQ+Ep-D_VQUzL#?ILQM9HAct94`|d*f1rmb2A(-;G0|B;ZMve^0UIp-whj*Vr@6 zG;fJMLq@ZQg*~o>Sw}q>XSc5oJshyKg<(#Hdp*t`5k{SRz75RU7KH)ZrixhhWxwXL z+33#oyle{v6p^mS#%jg#MWB@Rec{vJxp$!Nwg^23tM`cofQQ#H6dwLrSaYRS={11G zhL-7;4fko7|H@Jb+vNoVC5KrTo`~wbw5P9FWT$%jP87;1_NajA3r8m0UXxx1Il+#$*Tv3Z z7kunnAQ)sCWYXy!@bvxz`x#W44zakz#qOhGugX_~rj{TyHKsF6Sb3wHXx)DF5Zs2> zE{@6PCerIsnFs)tdyNJJX5;fl{i0bRbTGg?3pQHWex^N5DFBYFLoJNlvMcn$3TOa2 zKtuv(&!e7m%l&(Y;;-N8IeG(4n`fuJ)xU)EI=T=o>J`cxaR@qB7Hlcz-Un}x=6`1D zwhv0jAB=MK&nosZsF<&z3fLRocMZx{u0O`ac5%!(<3FfhW@)+hX8Zh(xpf1z zsLY->H9{S)qe&ItYDNg@MM;!B4rgMn(0{?4L?#%Jw&~N+4%&sSPz~)vpEjhTIV{O3 z@wpP!3N!+xyE@x^SkM9$aTw0jDYN_2jz zIeU(Zibg#EM~cSZJB}~txILuD1cWye1ULRr?T(kuvQ-8P62o91E{B65M$6zM|a>)Zf_3sAX5Qzu$oIQuPTlQ?_jB{f|VD?0EJ`7SamQP)z8 zwq93kMd7509I-oCI+~Lv4lkhEPp9~~&HXQfU+%1~(@>TbVTFM|^ie+pbNj0q5_$N< zJB%PonnWMIUZ)2VjRqD;)|v@OaR8k-SWeh*T^k*(0Sdb%h@M_>1-`aAFc?}8ZTNhH zXKZJL_^1e1jPfsb_9~W?1$ronC-O9~h*+ZopN!2tNeL9bTR2M?1s|@^FP}oZ__Zuk zL?HO=%vrF*!kOgPgc_|&tpB6{GRPJfQ1HX{3Kjv**%X4n=@Cfiixhw_4>lgTVM-b^ zYm!`CgT=%6OQN~msZ8t;o4OfE#rq%4oHVJ$N@o-oT8vG9o=>BNvQS~kE9sRv{@cK5 z+hlwKc5JBcvWz{Pqt^Ds0$@=pF&{a)ggvgn(?-h{pBicvXs7>Gmp!a~2|pD%p`j3i zK}*E*g!*I0r>-=gPqtw6K^ZUUKG1zJ6gR>ci+-db|9m!xCzA! zjlnh51O0{TO=TSGGP*QAYePRE0jnNm0f?FGBIg$2Q6eBA+fR48-d))G5YXhU{?=uO zQb**7X2C9C?(Z+%rIn%!n#Cru*Y!d=TGtcV{$k#n@>G=gwej=*yX#e>-uLiwa{F%< z&Nw+~M#jUWk@c9;j_kCxvvWct^rb7m(M|DPaB_3{o;Y&dHcvzk90pa&mO0_V_kiBP zR$tOTkLBOJKHL(&9&X$TPvBMF$A^DJlOGHt)0sM;n&slCbNriZrvI+s{nP~jCzR@Q z+O!4c4ey5xC~eE?yy|*a&9Ks1U7_PlQu}q!z+ovFAs1~8q(r5tNe@b+d7AL>!uOxk z^j%@GUc!O8{+lb~MFrE3v~-4E8)fJi1i zY9Tc9TMZYjBjR|CUj<{7BehlK>Zk=f8F=#ttB&luRZ*9C<1#p)X=UDi;ENE+xU|fy}Lq89|eqX@)^Y| zsww2Nnj}SyC-A*C<)eG=IAeh-Qpvjv9A-8~`*Cym%O~1cM=R!WXh9Uc&l0G4vbho) zM+%yb^)*jo3lttrOaVy}76nPbX|(IUi0S5jUj9EHo(1Rwe1GTle7YQLvcBxNlS>H+ z#W66@VXmzqZe@*K@w4{7(9h+JNnZ=Td^5l%@GI+X2fxj+|4g4p=7i{h9G0aX7zyqe z#He+|wtOe4h~*8NMMG%u4`s&d?n+WczzFQ({eaRMY`XF9tHXacgdBGM&)6(wVyg9g zVx$}vlTZn0(EjxorEkbCeQZF>Hy#oSiUL9y=KeEqWDI3V3Gt*ojOdeKVv@x5LMTbP z^cH39=}l z%l2pbai!i}OdL6?L0gU^OPw!D^+J9##`lKmiGkf8-%2WiJT6j%odu{t;<^gCb`7Fs z_qTnB6ZI+|%!x93({=J+C*bMd=j6$>tZ#>Pi#lDQJIfReF{FwM#o{}VRp87$;+p+z3?>?qW z_pL;5>$;Y?Zta6cMnxg25y@-#bd6jN!Dz|5iuhM+Fe}Zq?h=Ve+(ta zB8jmIqB$mFH#;*^(dzb*t*%@QSu*#WO+(MJ5`u$M<)j* zQk1)GWHC7|MYve)1v}5vq`?HMbUlmo9lOPEvcmc`Fy~5Blf9bp5o5^dZD2MAx(rpv z?wwFk$n7Q8)Z+icudJ`yaFnS+1ZNEjw2$xQZWuhr+Pc_fCEa%WMA_a#pAB{H?>;T< z9klV=ckrhH+bIXuN{CAojIGqCO4Pb<$OCuAHWVbq!Gb%gcWmNFJM3g$>EOe|z7Hnv ztKVB}@x?<(8oR%qBpAZIZDQQ4l1g__Gf<*?^;L&AJ3iPDw1qJ-|I{vY&=!XiK_svh z*(G~vF~(X|p$bmUsFg)MGAEolQ&+UwOBp3Y~1~n`v)#zxhO#EDR^~x9S|; z7y$$BC!m1>upz*{cLbnOAaYr5iPPSfju1jUSY6kUgzg8ZVq#+0jj2l%SC+O7tLiSB zalH2|S*;p&=Q8%NApR!HsD^aeWYHR$Lkqu;)wTx&I=bagR?;-GS)kVKYY!S*8P|sf z0aOwOp7OXABgR{N$4tkn8Bd-Ks<8e_PkFS+aNOBecPGjhEH!lt==o=K~w2` zYcC3FpnoZ~#Y{hCo}(Mb_*)6=6a#T#a1%xH)u-RiLt>gzjIn;)VXQYc1*C;*aLai- zoQUC^tVQUU0lH=IQ%XcE3xG?zn>kIpXt?eEN{ND}2 zxa2B%=5VYW5%#k}@vDi~yeeij&6L9R3;j+LLSDyz2)>VIdVBveksaTk?Ew^AK|#TP zUcZsCc>??eC8nNjJ*qD~^GXi#5HSxy(oyB59&YSTOG%tVdD=DZfZI0~{urMVlYzVs z@9LUpAsC?@O(#zhTuJ`xYIwQn2RIVQ7@`>)b`*;-a3T*7f!rgYL18aa@72-gd^fa| ziNRoD9SepXLk5NfB_)s=WA;fPs_NHF%HT_h4C{};_i#PIu4{z+#U6?9hraJ4jwJ?9 z{Kho$+{{t6TkyleDB}AAv)HYDXr9Onf9BZl%+P)x_0;L$FL#^%{bs*Vz{+c<@)r%{ z;RR~`&6TW3v^ow%FNd>!tPyQvyW2 zNrX|ai#n|(>u;dRDn#$n6E7zbL}6irEF6+kF&zwfjN$-MXXehe?17#S;w_{o?)Ue~ zE3&;X;~HUGue9qPUBj|4r!dTaI?^+=BzBCb>hL5m{g*sS|5{W@f(qA96e_GfERP&e zgoy`CT8IR@TDoYBqVim9Vsy>CO$?`dJAZ|QUV90Z5X@Rz!X1)IJ38}fB@_d^9Uxe^ zkeYH62vUSVD{J?GCW*VZf&>FE6LEATkpMBCke=D53S(i->DU@QDY9_J%-nDmxD_qy z&%(^9OCpOQ{2Tv?UXpj!cUr%X@HW^i9@zOxz|#`Jh=kOd>_)^gL!#=GB71tisw;vCs^Y&&n7k*gG$vV z;tdksvgi3XAbBof@SsJ{(N=YfAG+H5Gr+6oeS;T$-)P~?87M+}F$^~?=v^6MK2G`t z4@GCvrz;T$4-z;B<*5aG>g}IBp4T8-GOus!l*D;HYqP-Rbc|Bn{fL`$HFK$}vFjMv z8zjn}SxANs2!FJfX4Q3gYo*xP$SAJ9Fczz;6>$UVW^z5-K6u*5H)Xj~tj5t4_XCVk z%o=RN5b$T52 zr>(8m5hvlH|D=6y7iRno8AiCoi8>UQ!M@y9KxCjG*=0-mMrH|&E>Fw?Zl@!3pgbYj zq`Rncq9|9SU5_{@VEy79Ykd<`R3DKpOpIn(P-|10q`&?MTB3PTiYK313u%gnBx)9L zqcY&weOBw9#K}HMzS!W1zA(P)IW6M|$(xq@xyQGKD&)5Y8IKx)c_ZX8dsV8NUs;7v*GMKs8``-7^d{6)i z4V7HBX@}lDZ~FBMGHo z_H^=fO%+4P?LguYx!NK9Ujb;V-*&w&aJu@twK*=cuN2W9dGUvhoV-GY-nno)zcH%B zG+C#{zeC8`pD|fg2i>7H;H2}AlMe{bWnb6+^}M;_j|xnNCDaF=H=!3>!V>2v#kJ<` z2-i~x3x0Vs@nnT31yXd$7L4?Dkiqepa`Yl<)!P9bXX{3YE_fIc$$ew3;diuag51t= z=f}&mLhoUQa{mGDtXy=a9iQhHtKB4~%1NzO;h_)g<8ph`jaZ%1u4aF!Z}%9gy(XM=JJ*=cV8Ll8YyF_Sk`LTx<%bORme7eI)*`mubhlNsjugw|{LHM_RVF3oay4)&`U=#Ckr2 zG!Uonj?)rz3xh6Ih(!5_B8A7RkQ4LMyK-`guU8e>_kCtEWdgAXs!I!Gk%N7wXPfiN z=9TFiEOOP${Y~^qEWi?h%TDckA|vMUqi{ZFo)ROgo)*vxoWvHR z2qji7!ltQ#vge6pfbm^{u|O%f;owyBPMkm8fH+#1l1hvk!vRR^E7~@5eI6v<_r>vC zwh(+f>0(`8-;d}GLIEphN3QM;;PiOVJ1kX1*?Vz7U)%@bpF0Ae8zvp%}L6EO9&))`3F%>w|Jymq$JMk27&$ zpy1B#toO0%`x=}seZ7n}#`o(L7Ex@a3#YQL6>ulpjZh1w1P?~V9h7wQMgl3~Fh(*T z{dLUfHP*q~rD`Y~@IJKiztZcR$o{7TX=B8Xmo&7CpjBx~9#jQStwgHbZTdWDuNu91 zvv=vn0(T^kVy_!OG}F_Dbl<0?9fpS`#acr7cek`AI3bdP+X38D!vZUE;= z&mEX)@%Hz=PvzJ&s2=+{YDzE-OXZPTMhIO;cUoTu&CkQ#H?dsqx8yL-r)piol21$4 znWxcIItWmX^9;w??Qf`8Yp*}c;52gu$H4IjuL48GqEuKM>k-=d&0H_mYZ8{)dtdI* zAv9+8Kzx2E*QB-eG#EB;cX;q8&rv7WcrMGOsGS~!&^q;}C5r_r)sAckM~jMVxw_pX zFR!w&4=HuZ?YseJQPc8Cb>}c@g!q)nkrCzx(@X~vX<@p`8*SIk2ggpJT_Iy!nlq-q zDm&4f`1~H55RYwz0O5aGfV}0iIbGeY8BR4M%BUeWytEUXUnkj5RMlJ8Vg*hSIa|Ri zomd74q~Ro3`kgnpyr13^@jSCnykRPO1IHMAya_7198RFpQAi5hg5_zyhLS=(5MnTo z8$BnoZEBUY2BuSC0{T>>ZB6_E=#I9aF658EA;U~16O{2O!kv_495YFp8*d^Kh-fkJ zmO`0C*!}=Cy}=02!XfZMXqLbPXkU3Uu+$RaK;chKt_Hxue7T|l@GUsg%Xi~ zf%51F1v~?YA*#<8c}2Gma=ChOC4#;jK5-z5I{YBzL>ZFS?j2$(U|~!$GA_+jQy_;d zpw`03$|^Q|0M9R(Re_e?460u<273F+gK9)(ha-FagpQ?adDKeOYWR43qrUGW6VInt zciPWskpSf1Bop%IF_yQbJC}MMAUEZLVlZ50j(l1I79>85zkSj^^^Yfq z@1qPStjHmaV`_a8&PW;X5Yoyr>3FXNP$M6iFSkEK#&Tv*$-X+6W1|pve}0?TB`b}O z9?`>fp2pJylq% zV_3N4#LGdsy`K>4%VMRn?6&X6EQh7pc?=s59^ZBb64J)9Z1kQR;LvSo`@J6=V>BuakwPMD ziN5(ZPoB9|7h{_9_7L4B!&K5{2&d?!Y$OyhO~ZBWLz80Dh1k4imkH(+{y zftiCb^QT+Poj!*Y9)7O0VOPhEB93|tjSXG31zN{>)&Eq*v!hr`+@UQ*{brDV`p-kKxHIb9OPFEs~PuW)qmsQ483kbklWMeerSZW zY1P~0i&d5vR+v4t$iPsQtqy5fbebK!;QC3~bzR~(#&xr2kd%_+Cyw*z-#yCj{_gLxZ)P9D5)2Lv@|{op{<>}7NiYFmdR@e` zPoZzv4;OTCXyu|+11Ya%uZc@Q8pOdve3 zx70vr&5@f9kf@lIW}99w#3aSdYn9UnsT|s znRD}ujSSQ6L|BewtUAp6;u6Dy6@1SnjADj|2I+(mo^9hec4lO1+t-YMg)xRSedkH2 zw+$www6RaUN-7-~9D(G$Wv{zQhelMVle9=pif{Q0`c;bM0aRtEuiY+5fBa{$pM4s6 z@(t+qkn`sdFC9be+y%oUm|PBo$b2x~ZbC6O#*{F+gjPLL*=1@ZlJ#J&oo&`vAF&lPdr5&&HoNW^iB<$x2c?{A#bYvk&aull^2 z?p^&^qWSRX(}di%>HEBm%|T3(NzjrYrKB+#&>X*yT;9wDI~R8jr;GvpIy6l5%>YNXVdL=FKTPD#5?0T7|#RW$9nAh=$$hcB!(m^&12aO zgt*3~(2WIJf-qntBJN=pYIyp2#`hm$3TeQ>@o5=58HAX8q}1EIUfDNQ;Ni2Q3Rq{jQv`k+memU}XSf3={piL~G6T z)D*2&n_!1eFN)~(dhDDWXKrDUG;v5ZJn_S485jJ|C(rQL3WNXg~avQ<5k(lcvih|wMEqfU(^c=PmjFtG)oG3Y+=x+67s7Uj7n zLx1^g;+>N$-+zc)`O>#_8bx@y+;y=4*9dIugO`B579mWEDHNgAf%5f3&fN@j+6jK( zU!6tB`wVH>ByoKG1QI~6onW*kiBsI5fDkFh^wqzlh1#>3rHy{&by%!n;uz~=A3-lHV(QDVdvDghvpAo%F}?I0 z)_o75Yjc#I_*>|2nR`@;FSd@y0z$k$$kS6)ONy$`M4eednr_9+&+v!s`? z;_f6(&b3aGvvat1wg@&_W&MUiVu~fyM?ZyCTR;i{1H;H;Pa$4BhBY*V8J|QQxCImB z(K>y5j)ieBri{@gV%0;)F4c*E@ttLw^)BDq>u-I360H)P-1WhgIFF#kG7c4P$23-jo7y=m=V+{pZ=n zAdNxmx6FmE!@~RmsY;odnc*W3eS~tQ%<=!>k@ee(cRt5R%O?5AC!jn8=~_33RxVOr z3x=T*j15r_-3&1&PJvR${d>^QJ&!*20%D+qIB*D2$Yb4hGtq$qG}{S_Z@vMy+)L}+ z8OCmZfa>TlN(;Q7{v{g6en@$A98oNxY!^8^f?k+IIu543f;Bu&`ux+lufGC=Lzu8b z{^(t(Z~rBwP7@R45$$EF_ddkb{NF%M!o)PnbMW@x#hCLf?hSiLoB+obxC6s343%?KN5*;l>E|fs0zfc1GR#1w#L3fV@qHi95jd_#;0N@= z2;cJ%WGzRsuOzqGLCE<^nSX&2+t^rE^~kCp+3S(&Fj||8f4c|5Fl2IKf|W)S&vPi3 zHMQC@LxTmD>uqM|=NT-QdFiz`s18*!<3Mc~9;`4|TVi~)iX|bA6=S1STHPML>k{}L zQ550(@7`eWGBc4tAW3)cMV2b)cUbDX5cOz<+4kvGdCbe95!X4>I>mH(&w9s7qtQl# zl$f#cESn?*=9W9KhN|$=^T@NOVc$(y&;Jms)k58L7-8AyTrMkzaw(%c0Vao0IZ_>? z(jJA9P5D+Iqh01sH92?k46d8Q&-eAM-v-8LEL)N<6|PFQw7witD3w7Dm(ct~km^twF;2G)XWV+`{P^ZefL{T_Sv>{nT-0o7b^;zviv;ic%7^#B|%xNifUH$Qy4! z9Y2Tu#y7#T5&0bAuA^8Vz8`t?W`yTtDs3VL+aSDzlh3?Fq6D+^3l#DJ3(q~x4SRMm zUt8hnV=uCM_b!sNv)pmpQC4Q>dGob57@IkSD-Am;Bc!!On!ENh`H|1idi@oKZ#;^ZbH z6!JM1YKx4IkFip3Qp^Vo50+S5Zc!Z`#E}+Z5>pu{(G4SVeZimeRgX)qkfmi~)#f0` zqYmzP*HsCn70bQa6$1(AFM6Xz#?&M^dFhHkrj*pr6bMjLJCVEgAcO^4BRvORJ%xPk zNzC*N=AlnwCov}KqAEj|mz*^&#<(O=5u@waZiC60B0KgBu~O?Wdvcj}BgM~^@cc`Y zSHo_L>iFn`D z^BBT*(VzVBRW~3Z3|b8$MHeBjrU-_BRA9OZCQJ}H7jxzu`pG9TXU;&ej2JE=$420j zpF|E75v5|5d=k1Z+5lYOV`PlR_iPGofuX@lX3*Ea?1n2PKJoB_u8x8a_^l#UUfIX6(B(p zpz*~YRp@%})qP97cfY^o`$eBVM(z{;1IahO%*45Kkk2Djo1Q!Fr|1Nq13~V9(x+g5@>BGW_>0`$9UxNr^x4g zv~=js1q=`Nv#_*;6gHk~;rkvzkfGLSlkuI-MBHH8))g&7TE8E7UV0vV-^1@Xz>f?K zZY(!Akji!s_V=Sy8gAY)H9@6PWnyHA)k=kWvrT_*5AzF4_@0B(nir0pV0dVNg@q-G z#XOEBsW;m%PbP!``K_;F28J>3eTYl)dw3a0Az5iHUi3F(4E08xIEg9b3)mM#{9_$a zPby@bOD`|dDh6VNw1~FdgzOtcES!gYSDL2!`j=DI+Ec=8*^U~U#t1Mfc}b6jF_Jjy zA&z>m>?XETrdYD*?i(hK1oNj?I6pg!>*olv1>^-8ly<95@8FgdOSWlpXPzGS`YxOSjW zv`ibzxR}5G8`Q0Pk$2t*7ev-9+o9cV5r#2dkR?eHEGe)Zuj2vYZOA6RY0Yg{2vNI< zm%VR^nxYOm?bMbvIkEWNX`bJBu#)4~lRgy_ezDkzmk z3=9U-JAhnUd5Mq1tHBshMqM;va~y{~dv4{ofBSb>US4KqW`+kIcmOxPc$@ZRXC~6Q zh2F9Q>)EG}wHi8~>jW|_w9;?|R533`N*>UFV`Hjy^rMfX&z^&775is?2DxPtmKHI$ z-+}DOBYJxQjny5Hu4s5Q;^a6E2(!`iE-r|cuLn>I7nt-0nG8WDvmwn2Fw);cq7+-l zhfrFfR6- zVS%+qh%E)`Zlc#=B>qI+FMlW?uL$aP~iew zi0R1*k|btwY?MZ`iEUYEV_r%ogtU-H4q=Q&Z`poHO-`?bwrXKXn^YR8S6 zI?!+txll<4m1Gb?VY_8)r^?v2E+%&LvwXhB{Fzn4rpC_}5JJ$?--YeHIrXd6Y6~yu z!FJPnwm6Q_+Thq0vU5YN*XtNUa=BM7V{wGFk@+0keKC=G!R)|4F-v>P*vqec9alXP zV)9+xBopJ9{m-Dcjv{+EuZMhBo^3Z~v0TaW!Wx-;fmW?WtKK44a9CYfAYUxdYBh;N zMJ5-}Xhis4N-~77a2$&`(YUUMkQQ2}&cz!Ne{Vs_g)s)pv60q0Cn9^LU}|*)2GQ3K zCV9shwY^cSE>>~9cY;}_NoA2QQ6BYLfe_$l6grVW1*I=gbHYI2WA@yE2t!0?lKxuo zJ%{Dh@=N|cIXTIp=MK?owa6FpSkmIp|Nc+m_~tU!>*$#<0z`K=L?Jo|E*hg&MG(ut z>wV64vds#R4n!g9#4P6I3CzMG^48ms<3s318#y_F*s=|}a$rm3eRp(%OPbf?KjQ`& z;%0)d1yWkCOVZWulmM*iA;ivjMxdPhS+w>M7><;QQ{U)@b6`y$G#Q zameUE4-4ndl5uSo=Vqx^Ypj;bJbv&XJ-vP0;5xL=o?w2d!nwKgY~MD`gn{tHan!^O zRO}i0_P&dO-Xca?xbOWCs|TN|4a7jP_z??^O~ z?ye&3FiZ(x=K+vP++Mlt$GW0aHnW*wdl@oeBaa?NlzP#VTQJG%Zy0i3MxIg#L9tN4 z7=!yFM{0qDvrIlm#}|xTu|qOC#-ds$OzoT|4kM&3P_d@f2=Rh|%IX@HEzwF- zD>ornHq~oBX5I>VcsRSu)EK8!a!F4_jp$iTJrsVH^ix%mwoaA7f4<#3+}>^gHCiSb&9DSi~%?V$RPar>7Bv z{g_97h_M{x*eG&z5K-#J`Pc`*Xs{$3u?#*%b_$;|hk+4~(-Hyp*d>XX| zUXUkAG*YG|sO!ES>*jT7z)4+H&GA~eFoU@MjL2W0&gADNIsusdUAp| zPC&=Fwo7-`V`TRZ>Wvn)wPjji#LT(#WPOMEXP;tnY=|&1>^pFf@zF7sj-BG(JNKfG zzQFzi&oMT>6%n@>85+Z1T4bfzOaG^TgW8E>l(y|4$P{RdPm|rUjpW=cPX8dN1nQMk z3G2uq+^yRYVlVmmSYzHy54beBmN8WWm?K3Ax5=Hjr zTWKrB=-3v{9X~=ljOm}=0!c(HJ?78OvRZGlWpWJ1^*Ot+%Gq;sNGTW@8D^+dq+Bku zw6cohdW;VA<9Z%(5>snNxRxN73pS3q)@ktYavseuA`=3k4eZ$J(fKuU|e zTcn*dH@`s$f>-D}@a+utE4cT*9&APg3_6L@vZq{*_`we%W=|qpElf`za^@uRvF{`E zMNFxL+I1TyUrb%NRl@pYOeHx~l0(QC+o@nXH70g+Gj+qdX;K>qFeXO443T<0s8m|G zUUtJ`K8|A&rI1n}Z5xE3)ofx+L@xL0=0y^LEiHtB?*4?5UuC78rnKthSbM69c<71@ z`#RnhNbmLE54I^?0tu+Y- zS6Vb{bsT?!R;`T?1|y)lQo*vbgzbn%rA4NYp|ZS8kjWE9ZQ?M&&t_@WYPdl*EwMu5 zxEbOk!gD=@6c}wfq&X!fLI~opPOk7yh%jGC2n+)G(T^hY>pc_K6|dGIgrK}q!?E8P za=B61rqEq@?FFwf#9>0CoKWmNrg_9Wl?W7E^Z$)hV$po z^Mx;b0mpIJx^*i*`_n(mH-G8-FtfRwG%*(%=UqAs_ToII9g^(0af3`~?V@!tRf!TW zSIMycJrbHRdZmn6T0vx7Z5O{k2s34q$E*_sMW>`0@jww*q%)i#Z=ZB6nnB%*QzO>v2DuBOJwp{+RYYHy11@S z7^nAm)$vJjTo{19kt$EPV=+8}qEkQH(~Z#gBaS_fc>XYAd<&vlL7baGPi{e%N}X(lN}0BHh{Imu zuoug&VY?MD4nodgSs`)Ui{s28!~jCjN!Jaab%YQSA#$W?#@BwR)v6JNVhP7_P%0rw z(sN?l)`lNOyWK`5;VY7~3t?-pg(N|YnSC(vdJgM#TouT59!{##KtF#R z`<9)E?3E8suh+{;DL1a*Oh-||>Di3@6}m2#CRIvd?VKQLN7#-{94CbB5Ia9f?R*)> zHbk+aRcqpB^OTn=o#>j!+R`GqVu5O-g=5=v_4X3AV_g60H1K(QV895(+6rQzhu2fe z@J@zS3Sk6BT`@P@8aU9|}#u=M}r#9F0mlsG>Kkj9ghZq$j zmRI1+ahRM+m5~5roKD}wMSGoc{zzdeb?{t7Ay533ufoD2L?Pn#JCQrKV!iu5uv*JN zw*UYj07*naRBU9y2hRsfL3aImervK+j+^d_Yg@RT;8XwTCh6-RN#{HxQzK|?FiK-N zHuXvk*Y{~Pny5I&vK`9H6)anl#0jel%j8SlR9BbqIufN}D;g>5MJ2gZ9$X04=tLz$^ zB&TA|dRc~kL&ehJm z>T(%7OOM}=e2bdn)>WO>>+<69am2_dxIRK_>@&v@CypSW+lTQ3)I%RdWU|nzp|Uwl zhcT-pk4o|#x5xny3Q$C?aU6F6rSb^T#&J&*$9>p#8QVFH(Y;9P9MFqWK2kQ2vLDbG zlORNadaZ%&1Q%o_BH~VolVjUhmQ55zL}7z`;nMU;M%*HK?Gp%_U0drsaeDK!bH}pW zA+uC$KQp)V+$xsIy|*7})=G(7Ts)IcBhmVU05v$b9Z=yqyjJNiJ#{Mu6)E?AWn`{rmUR)6+vXo8`C@T(oYmG>1{U;BsRY zLZX5It6ITox6$j8?gF&xM<;beI|o7{GCu0rLzsO}W2!Yov4H(czliP_0MH+nva>aB)?s}UNe8tk{`^lY?#8HA}PZ5V927v(Tl`3A~ zQ!Cer+6lIsWo@NGCgam=wrEzH1cf|ni)&_&7u~rm zu8=sl+|C*n-Q$zUc027e%;X5&06UX~^XIU3-;O$Z2!K&pi7y!o2j_v(G&7r}S-mFWIh9?ETMRhDSTv$X8|p zVo8hP+&IDrR@#e%s(n$Nr!5@{ZWqJ(aSHC+qw}~?&nN{XVM;D0w<8C}kY`V(Ka3!Q z{O;EfwJP?=2uc44dSVLWco>~*Hgb1r8v){IU1=kON_qf;iU$Z=rb9kPvFsJJc90^E z?Ji?<9z+e>Sz&F-$IFdx7>Q_2r~c5|aKUc1T7+SP{(&m#1Jc2m2q9ivZk48L1yGbJ z@wjP^1OKpj98S#jFliMK7PNFiAZ;2ZNq>Y=QZ^C3uxRO+1_>S(O%tPm#Ap&gu>P7V z46T3brN{$c$LohgbpF|#IkKOkpP|dMxLSzBq&GD3Z-7psV>^xW&vbV^!dhXvW2w_uRsnFARsS)j~7b=M< z_7pqMu4|hZy%@IZQ0UQEb_SU&LEN+Pnec@HgE5+9Y8vbL16WZD zWtSk15VnV$TS1?kfw@JDuyB6*BalRhiAiK{2{Aqj7Kp(jVxa2+zo2)1rqOZJ$+;J7 zmTY@L8faQ4BLE{)L#RXn0wEx3hq(S0DytQwlqjXCuGaB$KDD(PNfP4+Hp}yKL4whOft~`BL%me$EuvMq)JG=CcJ~s^&EoZx5U$JV zg9n*8dYHo0HWH;N^ptRfMHIF+>>9*#fB9L{CPRMwZu*a(BiMci$&Q=eaKFUMp&FH0 zX)U6(BGw7EWzpmJ((U!WWf_UfMOv1WDnrq3VIO?~jvPXCmr(b=4|)7~44`k=jgc}f z%K*>{q}XWYUT;LYR4AobTdUGLFigIaVpA%j)ofuq9-il6jA3cCVcRJ+_UkW@ADq!TkWl+5s%kS8EOm?L1a`q zkrmKTF?q|StV7UgNle8=xI)l2387I~LekP{^dK~9!<~D*GF4rVrd~EAlAU%BmDwtP z@CSd&Z%q&K?@llB{`cR{op;PLvm$ zET65>Hx{$FT4QkF=8exRB-ZgGh&V>wbPI{PG*iZEt$`5^!^6W!Dfy#6`Xd0gY}rDo zr$ldGFS%Tf`S~n2-+b}!dH&PCLH76m^=0pev|Ze03win|`rIs9gMQ!x$e9yZ&prVI zBZ%=)tnFLV`ePD6cB&h$<4WK{0rbxA%)=V+&nXLiwyLZ=ZE&6M?iGy2tMz)Ai;k`)H%V ztULQ%MUlN%g-B17N-$DlNe7g|e)M~Yb2Csbqxas8+Iu(FlaGMofiRd-KWcmm$}8Y{ zh&V)e0XoQHRE)G7v`RX?6=s8YRI4?Fbm|xnugc!t_1%&7UvOpCf`Z1;scnFcl=ye00j!YEdf-$@lsW6?vLeS7L5`hwimP*K4 z4rLu8w82b!Dk&=>)va8O`;vaD&)_FH(*d+w&YKX~m8T?YX3)$<%%K1uv4lNC!^Om>Yh(KC6KWGF05XfX8#qL4#4 z>-zE60icqIryt%=S83?&9?BbrQVCi$*mcLQw|gj89F0oC^N$^8|LkEFmzMaEH3UW1r()`~Q#2Qnmq*!ooXr0Q2M{;0Ne!J25+NM*ALqa2DzHgYYg%AmcjTTCA5s z#ZipbVB3;LtwAR6SX-^4;s|Nklvk=ao<|gh)T?ds#SE)U%LG9d4X8N5^L>&y#&$fU zu+c{2dLAlHkhax%c9^%t|3-IuK9bI>5Q18*MmC#atz4y8%!8Zd+^JJMaL+wNj>qcS z3MWpU`Q#@)N@ZmUFxa-^QR+`!CZn*4Se<3%{2V7vJ&bXS3~YT51KS?BqB|gk zymmOm20HH9orspwF~YJ*-t~Uu`E!V~r(kddv_>ceb0=V74sp-Bk;QI!><5UMQ{eir z^9GXJ?m?V*0qe+NbWa~*+YP9JVRW;Oy|#?2ErQ8OkZ}K>+|LhZet6MnPOhEgOV59a z>EaX*|KdO3<8`thbY2A*7Z9kVxRDu&RN8PIwWk=Xd>;#i>SQ6#Mg!C;5k@;$mO+Rz zNqiG-u!6KSIw@j1XE3H8Si-i?pi~jdK7=s?VCqQAK_wZaRY8aWl0;zJ5n7iJqK1@t zEF2&tD?QfBuX3Gc@{DC)loT8oHVKxH zBqk*~Y4?ZO$b`I;dOsXt;TL?CR+stY?wk07Z+sVka;3u8zx^=fMuks*`lE02D6b7f zD&qL^saGWukoHo{R?gFv>82~_devp$5*Q1!wuWkkI6XzK=9=oa1NBN1$Gu9jNN*5v z)TVc!>xyc}UoG%54(BS%Jn`f~a@hN-)|J!xhA(I~A05DGv(b+ewcBjJd4hVig(W3% zqG(jA1o=GW&HUoWDs z4~#)r7V$mrLNptY%_E{V#>*h?_%Yjb35`2*z*A^|X3s32v4v?NL;Ao`G&A&Ca*q)tfU66qAYj}Q<-W6Ttm)kLWb(yAk+ zLa9L<_dHtVQE`mp9U*KF;W$STGKW?Q%dVqU327}NL?6bq5W+@?0gO2h^a37+5LXm1 zrj5X(Tl!!WdEss(Kza!_h=Ktkqi}_!ZekoP5;PSZ;TSt&4p`9(?f5w`pY89+ny_F9~+6XVkPYI2YW= zBNegSSf$_>-u6;W6SvX(_Ja*(tQ+B6a}k?26*5vd&UzowwS8LP)S|;s@W4aQ*Z-c8PEt zhgz+MV{IM-Aq19{ny<~w%nEal}jFgC&#tSzsQ>nf(#vh5&khd7GxgG{G)L0-`F;dXke z#6~drax&=BvXHh%b!m<*W5c+P#lqq;Kl;&QU1D9X>!M}V}BC(F9 zYV*;*`Y7Ms_OGy>egdS0ykQr~t#@NR^B7{^Q!p?H`2za>_oW$MBCSEqi!2ZV9=Qu1Bo}5sLZk46MQ9W;8W%~`LWIf(m;*pa!wq@~?A9^>B{-?iSd~_J!_nDbJN1>QyVq*9$8_Tth zYP&|1T-@xq+Ne9v*mq8vMCL7!1XHj#{HevA8Mp zvU~S#?zrO)KKK?W{OhhDr%u`vK$Iax?Dkcdd{A`vmOw9z-D6Gcy0@|$>uIpmib|({( zeqQJ*@z~>!GJk%F-tGd+Yc;yMdwB1I4-j}R7--jP8>6+)EYvx4y3F)&o~gkc6a6{H z`?J`c2V*whOE%w2sjp4{z!a@|o%t93hQr_fw+!F-AtrA9Bth}|MCGN}G|V%d|85Wt zoos%pqLg?5n1s;vs5WB!T#+yC`{E^k+au>5DiV#^|Y( zL}&+u!f}>~!tFTjd891UZf0@Z6R4yYX{}<}Euyds*INPxft9q^!vqLX2l}yff|1~f z9vodq$~+}(gn+E@=@l-BR4YjtgC)}JN5e$qgiFPQXp{at>%=69Mp%-XiExdeEeygK zl1^*6!H|$9P32J_I>Ui8sOf0Cs`iq2L;;5-R4XL)8U&Z#115zajG~LmIUp^6`tXN8%tH@7M3N*NKX#P6@41&R{-14*&2E;& z{ph=z`(DR>>0&qWPyRGU7=+OnweEy%gUOIKUBCG<)9WtYNusfBNf;)$u1&St!t-ou z)i!?Mpc0K`TX?P{jt$wIOOj|T>-9yquj7qjJ@Y6nxe)-(=F@qb7i<#IV&BE2G>#IS zo2O_sS{ufH^-7IQ;8R|!5``_K9WZz5EW&bW)hlTQzp#kIHhw0Lo6U0Uh39$ydmp4) zS)s4Dho!YTM~)m}@2$78wlITjyJ@d4VE@#8*Pb}bP)~-bp&UC#^9+}= z6tn3K%XWNFsy0vUG}rfAuREubc6`zsS(e%ac#Lj+dfZYmmuicxvgH z%U<_O=f1_S?D^%+4?Y7bL=TT5Mn+i=;s_z(rah3v%v6uO;{1i3 zVzzEYb(N4uo`+%&I1a}5F}VV|UO{H_5VkRn4VD8*8-tG!pjD=09;k_;wCpa9hFPCH zCGk4D9|TfHABS7gvMN1>lvSi4h^VA)A9B%jJ5gWHSMkN`-7kf^%hM zh55O8#wW%RLh#g6Pw|B>e1WH*{spF{zRj`Oog3@^u(6kSJ@O;eefM70cN(p*PM<<7 zFQWGB?ett4jCN5fL0XqjB+|Y}Hfr^gL}6KyC`_(<2_nLfHhITt42+{zY*5JC<27$Sbw;t;fyTJt#w0^@BWqkSCWfF*0^D%|?Y2hyGul z{pxJeg~37@6%U;-8~4EOyC9ChaS<*g?|lf7?@AS`dioJz6YjYm zV|$2d8J#OYvw;>M+if^=3Z}PUuPq=Re)(Oo_0oAz|pX<@IfK)wsz)!mWfm6%pD&GvLsLPi>lHfUW0qfx2{t>`qQPj&XX zK(wI%I);!DM!N_RBV>QU z!I*v=Qv(y=8Xu3e_oEMmlrG?*b%M6#Mz%s3llFAzn2fNglh7~`1>v%)+v{hRmPrss zQd)0jR|)2kA0i)oH}5q4`L_yvxn36QOBYGP+CpL@Usf@>H(PoONB0Ua64MSbLLglW zqauWT{ocC{As~sWSg&L9cC|qW2-{VTxY zKXQcLt`fJ!F*_#*(n-0#JThTfvZI)oJ`j%{J<3txRps^U$6E>8v1!$t z6nj!~A&^*3I%jbGEajDXrY9$OdjBCF-*>TT2tUt?8cR8$+F$4HtrjGsYtl(EFme+IEQN7C1a^fDk)uMTT|4pGQ-4E-X^ z!V==lDXgw;q~oH-CUO72KZ8VJTo-xA?U<1X#NU1ex_Zz$M(nx`GdzYk@dC!~_(Knj zV7g1NFbBN@nCcp2vfy}_xSdM+swmBZNRirx=yakUcN)=k?32W)v$Se%*5AhAG)5;x zauUm`f$%Uo#&TMyWEk6Cz_QyUv5)N@#;6{YtRSU}N_=c*5vBVPVi{L<6Gu7n&MHC- zQ8b#OPzaGDCqsl-H}Fxkv>^}{Akl|jKrbvIYYjxU$aM$g%SX{K(4Fbxe0A|P`(8ZT zWwV>Q!vVrdDg=I38=OH4241OUq??OFfh;H3ob8XtY}ti(N!z}{)71GHjK+q{Ca~y|ECMB8KTw!Cm!C^Y&WP&6~ zFvc)u+f=Jnx_ic`*XwAl$>l80pI^myJ)$t8IlD?%KH%`ec@}T7=l}p907*naRC@c; zQtU7a>F&|g&ce>;`MqXhXu!ulevp98Il8jFk_XmW=C__EvCwR?`4{XZbAF4HK_(lxvbAzWU^NwJt)sPeCW?@8{yeSn7^7~3EgD#&3}oO+FD zQm4=1k&eT+0uq?sirKOqqhf^RqA-a29)S0M1gdM8TmhNH=!ZUxv0PZ3M{mCoD{jN~ z8!+uQva*KuJgBU}nG;xRYp}M8dFVqZA+dh=9avg|LIHKpyP&5Rd;in0x{Mg?Lr>m- z?&*c{8gh9N)!UCQm5|cKm;_m^Kv$_VX44^DI-SHBgEmFb24h@wn5NYuHIep$193Fe zQNkKWhy-IS!qzypvqln6U^^=SB;hcQw?Mnqi|bXeos&eZ0o>py&Fs6!>d5lgQ$A!qEwL;44l7z1WAq1nv5$a)sT3CO@<#KL@vF@?AUBw9i z%Rzttdx(`~*tQ*R+5UEq=&FKJifkcEqt?QhkjiR{Y#~c|WrZMkahvbz@Y8u+g*8N?0oO@V*D$!v}i1 zIP&a1dizSKV#hZl2lq z75cNEVX?8nv%K1( zP$MlNGv(S zSge(6^!9fV)gz=2g}h6vrO6jIf3Jb>5GRTtNGH6T8JM^0w|f=AsFxMB3vxN0*|!g6 z45Phy`kEm_x9q0a(~FP}?M8z*eyNeGNDlwmYZhLvR70Mht#D+f!eY6_YAs~Pco%!N z^e|Ei=+1fg?ki7DP96ObCti3MD?h@>O&_OwY%h+N!_E9-Q!+4Ul@PWntj#_}bMX}C zPkfWC@8j4G`O-8ayFWp(yN?8y?f>Zk&eYGp_GSU!vN^c>SIOo3Xx5g<7lx@f7RY2v zv|ANCKey2Y?Ri<8|LgA<_%DA?lb5EmAN$L%vu*qct4n8a-GK7aiL`mz7#8LZ(>rt{ z=V$g4bWb95OnGgNkzF66xqOUV|4zC_ZzTu{bdTK1{uioz>)|=tq2>b*j&bkpgS1-> zv`)ujjJiCn?T$q4rrg=ZPLo0ij7pHUx8bQRlNeJiW4d~fQ3yc}F?$NJx`fQRsGc!Q zzJPe-yU6o%se0A;Bzj^B`&)mHD6fJLsO>v3d+)>g%6|jT!!#SP_g<3iJFp)60aoCn zqXaWLi5VJ!Cf@>cfNw{xST!y93TGWe|bg5d8t@gDYLw^#^~4}*=ztD zp;;S6sm-jfRc~Pb;5(R7FVXFHZTLN14wOQ>ptyUWhG@C6Hf+&ozYzxP6 zu^pRYCXelVWU^UQlHj;b#}F-*D1N&od9MYm6M*%MqDm69jn!rbnl#mRgvxOO1HUc#^i`^7!LVQpo4fgdmm6l1!)R%A~PdjTO55 z#kj0u;^GCIn5c1Ntj6q8o5fm(e9B>hCqrO0^vB=1EAE6v}Q|lNcGDYGs$-c)cWb_#}^jE3P9>sH76o&WUc4{QD z16avkJf}%^U7Ljnp-i+3AQLwNyg6ZU;fC2lde(KxrPD4g6bfM-=-|9^Z#DdKThw!tJ|}TdzYo zvLDWzLiF|$j%*+tS&K4u1}bIz{ysEAC+zBnP8*svWOrYbkRDkrAUua~*)LweCB=rK zXeg}~(y|CuK^R=bixwfsNcm~5MS`HUtN}?NrHi6i%Om$UQqujU2xUmMQ={W`2xas|l#OS} zTA7!B^6Ln{Y9qh?9b_1yY}DU;SNvGvRR@J6OWxj%G zDYRNPzU`sMG?wNf-gw~Y)SGqU$s~|5>Rr9mk0}tg5O$&*|wMH`KWAsSCg7-x&A= zTOa&QI*leqJb~x=WU?6oKOmFMpeQP)X`+aTD)Pf`GW_`B{O99*s=20VwA(EdMG%J2 zX}5`48kJfT-w!YijY_3PHWjDRXrKs5Dixz#u2CqYv26#_(n%*Z?6yxb6C((h19y`; zo*Q78+H#Zhe53P6d-`$kp+h8+`Q^RE1!#srBArFln`9N3H%(5RI7zG3V%M%+gr1Az zw4ZmpS5!<~jM;LBBcl~gP1UG09GV@UoojOJSevJqvB)P44E;sAm{Kxv_DROhJcgbf zAw75_sh+JQvi-!;FDwdvqapCyc%H}XGvAIpvf=pVo2V}5VP$M}s+?|((>JNUt`u=mtgpLhSAH_mhKU*G$Rj`dtftBc82FOMH> zF<855sDkFS%Ril@x2_XUP4tQzHg!%i-chs zA?j#)6W`0D>9d4kH-ZX^nncP1P(p|z5YZHb=tj!YvfsKw!~=`{*iAuR9R#x6!T-S{ z(5jLKcGO3qqK!^}3)k>2@(xg^y5;#7p38k4u z@?Bjt8#RzBR?MK)@~~niz85udG)>_9V3;O$yUMQHuDfb$ckMRc{run?aU_Ef(S}g(*oeai2sUmd$mL$JGy1ZJmXgw9m10ldO3Lp`;b%Y8;R|

    {s~k{O=P_B=9^B(=@M%h2LZdd>=)PEOdR}$1n^UjRu;k;5ZJp?GUpJ%GDY% z%fRz|YPA|&T^SY@%H;D&2*LFove_h#;}DA*n1+hy24r$^9LGmfl}ofAulMK3={THz zW*kj5Uy$;gO&7==dkU{nr+o7r5K45@#BMe5TxXfyeJQTEm^cqV2swPN!jW@jN;R8u z!=Wb^W5??F(kA)jOHC_gm^}9+)ye{?{+%R?TZrY>lImUmhMQK%FrYqrlt$?^ zmB}Zts}pn;hsfso$mNHzVyP>#f}84;`GqI`lm{11Typ=;>yfYt=~ zoePh@=oiW9G|hA(6;XE{)>39dskc?Br20#q~6*(|CSBD!-cf$*1Yt z^e)_X1tXp()3*h$T_)AN2}LTP8>G88V%O)0=SQNv4;i9r7BUQ?;^3;_QeHK%EanbT z6fMexa9uDXQm_yTwCX7BCbH0nM50udkW2F@?I!dNLRSHC@&w`7C`!GK+_Hmk>rRx% zA4GZPa1<`Mej^wba&{VJVGh~T4_!t4y|+MV9(864S?GpD5}EHJ6cVLgBTQ!iu^d9E zL;-9fnkKvy-Ri}0p@>t|7GaP;RT~5WAao3KhEB79m1v;pWx}8fMOgrm0_mWrHZsg3 zlm&$7A@E&P4W!J0Y$B92L13Y(ZG^}Y1m3bskKol8kZ(Xp4S%sgc>EM<+(5m42Pm(c zQ+^FU9Gs^@dA5V9D>$}?ls>9vP@b=%=t)AqLA&0;uyktG7TH3IfmMBPGMY?4;2-1c z;bEM%!>a9(?YFAwsLd9EWg-=o@D(IqKNky&WwN;@bEG&bj< z87BGJY2wcuqJG1zRFkPoSq?9PS6xh8jLA}q!{^GJn{7~OxY%C6mXRErSLNtV8}wu? z%omwf$S`Dj;xM!0M^IwjSoyV>xe+q`+ezdv&jRoDhLj;rbCFJCo~6-8SQ_6?GG>sl zVibEfkSz?NX~tE%;7ci)cj^RTNUxPay#n4S!1gV>=@4U#RhQhaD3Y=Jzeay|=Y^m6 zvJjwJ1li3vT8^cqI>%0w86HgV)R77wdTTdntqk?iD?EOL^8#YmX`yN+Vc^lMFAz)Q zSSpQ!PzXGmT4jn@B2Q`dB&uqmT1h6)JjTF=w^3O*Ln1ebmF~xGl_`wu#dq6Su?*?n zt=NqP(tX?TojR%(M~meM-6nc0!)rCayp)2qQiZ^BYC3_B6hsCFt_?;EQ7@z5B3*$< z>If}`JaYoksDa}Uq|&fyE9(9C!2C><%$-OQeDGta_x&@pTHt%gb(;yV+XE+$p&B4V z4VlU!`v;Mo7U%|eE>Z|E%nJpF3|H2CCEdaZ=QS`FlF=2lL*OUT^d+Q>oQX8Oh3{q1 z^f^@3#rKow#sa?IjjAl7sA&RULs44@(T9|C2$4gGBvRH8qKK3&gfM_OQaT7>^207b zWN6TC1|-ta1S#-!R8@fRxvc4e6!@p+kze^DvQR|5^A6OFgO~T*Yj{K9!baxRQ$Bz6 zFpu3U5DYVFyy>At{o0rCZ@3w`YAwO5C?=ZCHeRSOJpA$vxZnFd`1D0A&8AR7 zl|X@PHcPA3A{L7wL}WLwY5FxYkITS$Yh6WAP!t8<_fQoTKL~JLmv}r*wNgPh3_Q=J z)ofu}2DNGp!_W!BfNEul?qZh8VuM6BhM@>-$0b)t;JG2Ht`Lu@IF2NpG4Z@8Xz*g~ z$Hj1Lha-<2Ba`oW-g@Kd9GSUE%!zRpZoG|lt#Vnf^QsmT=V7}6N5`r>J5i%l?XXbo z(4C91aVW#8o&>!)i$eOvrw;YXEDN*GQmZYYB>GSiJ!Jc@BR{kYRsZ2y%m%)L*QrvS zJwj>X31oADur*K5z-GF8H(*)`4DzMd1#)84pb?2>3sNYapKM#*h^P_j#r5D7dt7#m8nLfI)|#8IGqNKW(CVi zurz-LMb+@!4&{YWa=n|G8QV{)XDf5oRPMIhdO!)OEs* zTM?>;@B>8HBJ>0#(uASEvL+dxpK!p1&HGil^epQ^6t#utT4=hDBIK`MA&97XA%s^E_xUa?*Rpx$UAh0egh;LCP)|MD;46Q8(n z`xp3I{^na<@V@t5@%gV5=ZnZNh?+QI7(`hV(#LTF6cNzrc(|U2kO3Xr#?Um{b{oqu zu$?xhY2t@2mT4k{jNV^W5{v1PHb{wVSUuNA*Q0c7fj|mDz1AU{O|rODCuN!_rbVUN zpr@-qqtzjvh!c+|aBPQEI=!M(NF)-=U3QBg2v8K|$0AEYO3C74iP5uX+5hBIeC%g_ zhOVxc@&bGQ^UuFe=d(a;yMwM9*mei8Y=v2?)i5oKcDs%5xLB4(X{kaclc3YF34(x3 zI!3eBAX7*XxGpFffooG*Xb`ikD489BrYay5(pC)Ba|u#uI_(yoV_(*q#Y12IoV;;! z*GeGW)yBj^ixU$yCQD7`DjhnG&&I(NgT*96#U#Vsi5Hz#grU#;)CuNiPC%?1Ur7+l z57D*iW>Q`2UX%4c7g7dfNnb=P*-$!rXdXkwQGP(ZOWi3|=FH}qj zVElovzN)E2kl)Sz6CL*Ludridg7@6fi!frGoOH;>1wHB{vOXU1;eW*8*iCdJhTUl_ z3&1UwO5<3u6piW(?N$}jOfWxlf<$Hz+i6g*Ez;G$o$0fW(zE(TglZ9n9@)N~IPDs# zo;9du8WDKphHs!#n<19&LkbN72hB__>n&dUV66+a{49ywika1~EAn zxnJoDB;thYHX#liKsmUdFq1(j8o@_@5%sYL5M!s2sVsE&670SSW&A8O8`+g<_nh~1&9zqh?E+t)>tkqswhfG5SVEC5@C== zQL5WZhP6se)F5~fe&1`{T{xp13b_oq{SV{ii!_E-vskZTXd15PV(1zo3<&{KQ}9Aim8iWYr9}L%zy2wy zsVdj4&2j72Zu$$aO;^3`_?(`qGdkB~YO%%CVvDY{#p=E!gIx($^(5)Zz4#m3sFzq= zI7hu+#uElosub7VN!PkNQB?h^u2sqa-)+-e9HY5#oY|A#M+;gcQ+e|Feg;-uw>;*% zx_KEvAbIN8C|lO`@xcBQyzAEOn1+rYM05r1B?6YF7b*;Nzr5A1dh;g{wdZ^1|Lpt6 z_`BbKYAr@Ayo7zBheq_Q}UX(g$ar*Jw=;+bA1&pbx&`a9{==Mkz&x_dp1 z@&vhoT?B!GW|?G1cH@+1Np-JZ+5DTSJ_5UTk*)H@UH+?c!F_(`NUT`y3RRDE>75QT z7DriHKo}-6kwHw2A({EYPp$LSsJV`S?fre)Bow@9Soc&<(5+#KrU1ckwF^o_%a zIJmaKzOU>jnMokjklkP=KxRr`>(+7 z{_bU+YbAHW_X)y~FbuI4X7E&vie_RvZ9LZ}3YQF!QbSQdQ$rM0Mc1Q3AQsb+Qeqey ziVzrv5?K!~7YOkBW=gyiF7$vdd>{FKH0fx!+~{%J$nY zs?`>zVPcskwPuHWK1aLN!HQX!h8YFmrILg}H1Ri0gTN0kE$b3Dr5_f3)$?4A96roL z`}T3-*^@|M_wMVkJ2r!Z1N`8DecZVB29ohOZ+-ha$mR2|`x=4geQydO@I5D@U^Sa~ zdX#U{YBsTAF&d2qj%}ms8jVH`!?3U&o6z^sRR!_TKYdOrbI;FT8OMe3zxtIF0HYE!(Ey z*ra;4(X;+eQpGC|YLa1qV=rMh7nphGJ9J8?@fvgF^1ZBDe-nlgBayoNG1ZG92*VYv z!wXg1|L+&R&%gS~JNW87Px5m=aVt{7H|{?`e|L@>wy#-vT&wMnh(~X}jA zb?bI|yE1efhnQ(nsn^LZyHkmkwL3VU|0qS3L*BrQx+=dmZ}F%_3vw@B3X6!_1#6#H?&B_eaD zjiFmKn@gywN#J*A))&ytB<0c=Vc;W$!qV(XQiatl%|DA8D-ufa`g)Di$&(qH;7mkY%7Ykd<_=} zp&%-YC|Za#(u9Ud*lD00e+JQMBD#AC)~rE1^9<_IL(#;dZ-C%EA3{BP5b@Z)D6?Z^ zHDcRNbyXjwDWX+Z$Yj^k2s@mN9_fPZQPuxx@Js$b`DK_pM zpuW&%c4CPgZ`sP317mEvWgGYZ(}S$vxejM+j1BL*nM__s0*4+rOAv%?y=gO6Tp*MV zSGM67_`b%(vn6~-;@TbhR_7`7#|S)?(rlZa!Q`#tK63y7AOJ~3K~%Ei*EL+jD}f{o zj?ijckCfos5Ckrz5)Ue=d`mhCfHYB9dhWOTN{=xmch+N3uhV|8ze^#f^o z^DjQFXf+mT)aR+!%T((XY+us1>D}~idGBR$)Wg8X_if7KPtcw}$->x!sG&o5-v;uz z0lNC4j_}nK7>&)8I5%D5mL2PvtJL`By$AT{dvB&YpT>4P9zS%N(U}t2bb?)5R)K(@ z{FVQkTd&_pGH&vTkGze0A3I5_+2GKLaem_y@8fUp-p4%;AL9dWyPlh`TSp?H@YK;s zI!=eKY>qAK2Kno+KFEeuy)0H5eCikP!qN@ay#3?YZWLJZ)K@=???;8pp%dp=Gu+3g zK7JRyT^XJ^J;gnb9HE#`^9vuk9bJ3Q`=RK_LVb$s8&?liFC87iewbR$NqS*Bi{#Yz-doH>DNB#<&>Zsu9~ z*S&?gvHj%wcVOriw%wv@_y#)d7V&&9vD`30yGm|w4_?S%4CcYgGCgs=K~qSskE3Q>V3^N;_FHVZbu07dX4$xBJ?nP% zB55p(&R>D{L+U(w-!n93TjaVE#Nrv+^#(iNx|!+IGc3*3*?IeB49iD|EA1R#({=p# zp+gu}aBU6G?Wb93V^Wu$MMi~jd(n={!ORT1VMlR;)w*dZDUzhWVODMCGqk_NVq(e zdTx%%n++=hY$?I<0vs=3|EUuDPb|`Cd&EqQk)9-bH+HdQG#5cn>Q`U0I+g~g>=N~I~%1G^a9{x3*(Z+zb4Ta`(i z))Lc4zCycnl5{#pDw(Bsa4S|Ujc&wWv(CWGLWTPtJ;u-c#4UXNzJvVUpM8UW@s8cR z>(=cI^%eO1-4C;FxQB-hJPShb>0ka3|M@SzPA;9`-+tt+?0fPAr^e>F>$V+aa|!wj zSss4+6o3AO`}vRm(@(K}q?^zDKVN2as>J{P$q%q&!!YG)6HkKO?(oNd|2?*@8(^rf zz*p~il8?UcE`Ijce~syVU*h|Z9_26o@dy0L|M77`DNt3Fr;eWG`;Q*w;~#tr2acWL z_}N+h=s*0z^In%s45Flm7%wU0i&@T$R(N#(6ocJ5KXJ2#XpVu`dQINbA9u(wL@c{D z_<@J68Psd@n6WIa#ypOr4%#*Bv`qoGo+w@uOIw$4x(d7gCv{RrA>Y-IJ`}J529Dk^SF0z>RnHV8jw= z+7v=bEO(eZpa`;#P*Mbb7DcU~C|!V#ls5Gxji>HC#^$}N>0jMV7{I=-9$@wM5j4Z( z@PkL_-PA{Su|WUY0z$ZizDi}jMy@x7s!Biw!sTA{837D33u=uT3|8Tp+_! zw4194!x&*889z2gx|pXpkVl=IK;3sQ;jX=S8#W;?XF`5C=ag`EY?7^8wquwtPg71O zLmI6M=PvbaX7+nuA`vsu6ctrdu`B~gxI)2suGQvw2q92Z69NYz6@1Q94kcFnESlbn z5I2$g!~sWhw1v#7_mfB!P&J*`ieDE>Nuy=sc|Lu`EPfbp@R>2%9fwl6#(VGB z#r0cO;Rhj~`02ND;_NhQhk6*BUPM;~w(W7<-Vu888Mdt-;`jgJTP&1n{F|S?lUTn& zE}0;iFd6R8qiHJrJxS8ZIJ-Bm0$^&s%<(f*JaPC8le0@~S~twj&8ztCLr1v(u}AsS z-=3q|*u?sgUUqI8;j7<2z#X@2V)O6-k34;n>G?9Q7gBAyEG#uRH8#hFRlOHppipr2 zKAw8I#_91UGxO&t6k`1J`&N-lfM||hk}GiyR~P3KEQO+=E724&osE7zrg_0uxzN4l zlIJ;2o9(;ajnk$?4D)9c zbi)D}a{b${=g31xsV+6S;jX=?hKlcc_(4c%YJn{`Zf5e-44rlpBbLLkLfZAGNu`UZ zBE|ef9bJ1Hu4CiceJF|zXh;Hdy@uy*K-1?@)dr3mLpRP4$}C71ryb(i9+^TNNfU{n zZ*7{fXGSRw7HC%Lq!S~Ydg>^yvw`7_!`%H}?`F-;5sp6AV)xs2QeUjGFj*p=wHR7A zz|w35Ull0$6npwO^Yj$GtBUjt7x26erl}DG0jd^6nhe57Jb&R+&$UU$8x<00;QKyd z7-=+x5cIAdLe)XhwCI|a&Jym}h4h@OcV-!qNhPrz`?89O?rvyY5 z7f28anRJSF$03zUqKJqpWLg%!=V6$y4HM|KhWZ~q`TpO2E{#W36f9k%n6cO}kY>+@ zE`$(_&NVqRQ|HLJ3Zn_|yuip2q{lTUE+{y!wChx8Wu7+JN0k+nCF&G%!*QkRuP z{Yv3@QPt~uKL6i0ALSpv^8|-ZjiOr_{u%|`8OYaD-&}|)SDgl?pRAPm*(f*e=9M|;LpBz9}-wS)Wbh~^ASG! z-kXS-2KPRCjG?}6c5E0%2>8Tr{RNxW^z*C#^4-iVRH!vt{KTERdG~EQ$fV-@_17L` zeyPS?x9wohwl$m_o8@=@_-l;xcX4ubj^3^`3*|Zk-Fc9b54`<))QdVrGS)-Yi!(Ln zaO3tg@4h9E?Y9`8Y_YyqLVFewT)i)ZYq&blG#w!nbR&jg#?W<(WV##EN|G%M(N!EF z-!;h4nmu$CM;KbQi;=Z^NGEe_-SvJfHKeQ1M1Q6w4q#{2uK-5f3!#=AvFyd`h=Q_%w&<475yzkWHv{*b^}5G0O9J5 zgrhvUPtA!C)P!dUmqM`T>nL-9L9wXb6K@uXv zfOtAa*FY~@_HIDaG_v^u$!r2MrV&cP)c#{^Sd}9&&_^hv#N>D?$?Vw~rcO^Wym63p zF@0eeAT^{^Kxza*0#FEpG`^oA3={ZX4}q5^@C&HqIlli{*6+HNFbqL0%lGzNE z`7%fL9mVZ9^o;a#@Szh_OJ$a(T4;Kjb4RA|Jp&^aM^$wkTVZLsPApYG5g}44gn=Fv zaBsHgg*P1}QqJSLHjXn4QYVxWMG@$ximGd3?+58W3v8Ttk;=(R+MrZ*AdN{)LCR~zTIl^4X^ z7m5(W)G!Pc!_Y{kEaGvUOg2U~7blrA=<7=pi>nm6Vq`J~v6!T%Cyr;gvEl-7Xw}LX zhR@vGJe^L1Mx)Ba#021R_RJ`r>(FdASXx{n3DPAabR_Fa8kx2cQq`6h=>E%Mm$5+^5X6w(&k zSLfKVCP&=7x}31?j74|GVs&?dJ?rw!RXQ9wSLX29GG}HQ+;d=tts_~kUtf5h6O^jy z#I-E(M3!u>pY6Nff6<8jwL`t#MprdH|BZ*KR9k%T?R)t1f4q+`|M92L4V6U9Wb@hq zzW2ycs*N@~H;!=keNXYx_uRzTvR2}!-f=5mzwaP>wyvh$XtPvqkc=Bl&zH$(lbjlx zW!KhKJbL&vM^8<&dG#QDT^SyI`V_mjtR^0_SgO`g6qqel$)@7e8f^|eJHfHjQ@mx* zCMvZS&zv5|4+VR+tzmAV%89d67`n;Y!6LbIoDC!0JaW*W*68rdAG?`iK8=t9Lx0ZC z*(y?9kQ_bJVfVHSVJJ!J7Ool~f)*mYR!F>2abDw~UgTVs&PG8u#oqNR_w^2Ji7sU8 z_5k2}Hao8W0PR+p&0BBBwd-_R71j)`WpUvghN|P0k1>1hd!%wh9D4Y3By%I6s4UH$ zqHq13ROe5U?%R%L<7o;&r3 z(nQBe&`{3`yzLeFd#_hkjXU4hOH1r6diBvX6Wrl#FEHP2jU5Yt`n*%A|69J zHo78_wgaJz#N|g0BG+t0JM|38555=K0z)ngDg$ri%pT}T}XyD4w6X6G1Cd+aqY5FOrP`92O-cC z27PP#89zNicYhaltHtc-JU6}fR_bM&N~w%iwfDRQ+%kO`9DAR+rE)uX6zv6j(mq8^vUGOe;w;UBrr|$#+E)k7Dmy23PGOm+xoY z<~!)_Sxr}Qm<^k6N5^4!cq>NOLONwKmVwb~qBP3P&F$mF1Ajo!nC9R={}y(2g3_t) zF>&l01nmm5ryj&^%wRW4v=&dJ#|qd>=RnbrsQ7LJRksKO@A5_F7f(Hq(cfW!)S}L+ z)S_U-P}7jbB4Ij1m@gt#jWC@-ZrP4MIE1@#JE~zIb7|z>J0O!q?A(UT^&%__p$Mei zK@@UO>_M5EMLBsKapVA^vV^~WJz8l2<=bCFIeHkS*+gXXh+|J9T1{xR&{}nrR1DBa zwkjB&jZCJNIok%RZvzTKi`?MOH&~)^ew4m`@y}9*0f}^)GY3yIKR%1ocGz(JCi1;` zPVPTJBA297?{MOY<7~Ws6WL;xFqEv_xruZ>N$*HM2kt%0wwrgN>IP=Khh!$rk$q>F zJiUm-K*SYt-8sS_#>BG|TzBU>gp#CDUSj;j0tg??)X_AJ=`%A7Y%H?lrd4=ugR_Sw z+5Pr)$Uu_JNrWgPM2sNtQIsg$Ny^|&m>B)Wfs}2+@EpE7gy$5A3;-Yuqp&nZ6$qiC zkDWs~b{M&3J3%JL)i*p4G@5Oa$<)gVumSGB9}ZrW z=|@j*f>c^Z*Fw6x{iSPVjGQ?HfLHJ91h8SF-tw%ua<+$f>z(5RHrP98(dPEivI zjvr8~)o`82=DySJV3-E38)?`sc5iyI>4&IS=4BXov?`O>ojK~GPqJ|89x|CO)@*zW z`Qpg)o^&4dwnwGuaBjB2k#iMhm)hh~CcT9u+gD}Twkm`1A{MW&79B63W&12tYz~|* zap+8$n4w`ADqC0OxMfQ>J-JuMKWue6fI=end@5JH)gf*g{I`F)pD%vnQQmUHCT_ca zBRe*Z@JpZh@BI2NzK3_-vJF27c0#7iT9H z_~!=>@ZPsyPrK=m$>qo=G_t8Asv0F5R~v0qMI{k4sI}VUQVCkNL&CbSwr1PLG<1ZB ze)ty$5q2Dxm}&4_f$R%?Fxnl5n5D0L`Fei9k&_ej_7+I!8rk%Pf=#B@GFDAct_AGg z(MzZ&dH9K09(ZJmlm$Qa&LYG4CZaihN$2+(F2$9MCp|xSzO&Yw6z9WuF8=to8jI*= zie_z&AaD^vp}aJOZYF7zCu!A7#Iya(jP0j;_y$_dGM?{}>)AoIbeh8OZbGS}8Y;Pw z>v1acq`KFl>T$xrkCM#oDrTZ^=^Cz3WNx=S=BG;Jx^kooF=nP0ku9H0cN#06#PdDe zW`|T)5=~R_y%60r5tR}_I)hrT6Qr|fwhd>WMKMfdvx#!u9yoCnxwrsf2(2b^&yCQm zqwKpMX~hw>3gL%;9-%sjM;-w)L8z#NH{Xs3d{~@EB$CKZ8#%HbNeHfkP&B0PAQI^) zQ^oU96cN4Os*0f*RF`U$=c;6iX;S$Fz8i9K{|RQtW*OQv#MT?Pa`cho3~d@9ol8-g zE-`v^6h+lg1gzV;p8LPBk9Ym-J84#1Jp0r!ZvWtI%#JQFeqx-hH*ez1;dA(|$BlR0 z!qnsxbEl^0>g%O_0 zSAtr-iD4z_e(u=e1@K$H1)u%wh1Us zF^i_{kcubp!zlN}GEHpPBb7?wc|N9TkV(bqI01=7A}S^>UVzuB;WSG$7Ed$t%(rOG zA7$7+W@OB^kdw&aCU&{MFr$@yj21>&ks&(vVg z>0|25BlK^48%`$*2}~6?;B~5G`nRKm3K$mIzOA%t(09bVa0o_+t;Zm0LIHY%g3p5o~q+zkd}4444M5K01H!V5_t zenS!nq|?i8>-*zqG&Z(lV~;Tq z-`C6~ZE2lz_Fh|i@AW*-{oHq*NIFC;6J_G~G=<3mYtCPZs;fA5J7`fCScR79P@Jw1 zO~uf?P%oL7mPt4fKtV;ipg9d3RY&vq5Umo5)x@1BfUe=@x=_kRl#yW=I|Uvu_GMR~ z<);w$-T{Rf$admxIUj7hT@9&}Ae}|7-;5K9p&r=N=CNn95KDqLfKr}A+AcDkS?~f7 zXi^}6)`E+z)v{>&F1nN}bz}=lv-5QHcLEOk@7qr-mqJwp(vWm5$)QM2=M6Nf3$7e7#oM(Qjz`2)gMJOiCn$7aRVENh1}OtT2}Mccx|M|>B!P6>>Q~6qs#L%EYAwGg z+O(!AT8#{j9Y)GC^jOPwz-cd1R82*nodvHK*JB_J5AJg`r~B_PTbL&hijq!eo_6f# zJ_ql6-@jhtYnr}EKbXHo1XwlD9gJesL#RD{pTSB1Uwo6kH-1uq}jYY z$;^C>_B<^WOHowTE?+{^v^g>~%ES9laqX4c zP*sh49z4qSO{#VPtBaD=*ISz1ya^Y?Ghf z*gP`gBI=bFdQX2PvH#G1_8&UP!@C}#FgM3XKk{*;Z4(N|7BB9n>hXDK{|I{y4O45h z7At4p_|g6JcV~FR6C;r4YX zrDSmB1=v;#MSU4kx-@D<)}Q-Q3i*==r3c$=P@daI*c)PI_YEjQLl}PceD6WBecPFv zK88Qui#L>^UYaD?yOrAfC`K?xD7gfyQ6km<61+YORkQ#fiL8fYXB;71R81k>lOWTZ zLQxeQ$3an*$I)3`*P&7_gLH_bql}*%!?qn9CqXn3VQOTS`h11nwf$f>k%||odr${r zNGY+Uf~f@vtX&W1Zb9JSxC*kf2j!)O!=rU|hGG@B^d4(RAwkid1IkcT}Fq5AxA za1ZX~uSV8tDBt}$gu*aaz`5%62*W@eJ^-4AVOhv?x1fh2h>200NQ8K;ip+J9$i;B$ zRfI3Vri<2LD;m0PAYBVbIv`=$#^tCQq`Fds6H%;IjeYkY!s9XMUDMCZRGv~{o|&O( z`qm6!+veh&N!h-3q@aUTO6VODmBNk*QZ zGNzPZI}%lahmIE5eY`-uWmB%1sH#F=Hpu3|81-tI^(&VwPMqVo6pB?`=@RgHs5Bb< z+qduHnk&xZh8yo>?TTJr_tH&V|K*?3nM=}>jq~Au_$Kdq!==3DvW-Y2x(f4^CU1P- z=lJI5{(#P8f|hAftkj7F{ph-OR)eV*6u~a6_!>@*)YyAqhD*1F85*w9v>moBlW4V5 zZA;S^B^;lCR;$5|haTelKlu?8QxkX$gHR~M`P;TLHZe{#5~ZiB1KV-A^um|n^*p|* z`1`j%!d(v?=9AaG5s#tMXqkNB8@FTVD(`&#C5%tc(c6_`Xe>_v3_?q?ioVW4AT86 zLXiM-(-jmTnhD|BZd+YSlSoIP>I$yoAf!;vC#y2r)8*Xf#kdlgMZi z#|XD6SM?esk|+xqGgrC@DJhn#L?U6NblQC^(&hP=j%^16r=87((nL|~xK0R7o57U< z1Wj~f0#{}c6i_t>*9oAgd8FHeWDZsJB19*yJBbi+gfNh@ju3IAY%TET1>kVHk@Hs( z?dw7!qiA{vMR`%x z=|wzy{NP{zhMwNF?7H`dh+>8FeZBO(;?0=LdN@9k$L9~85g|ECct-L|s^&%2ykrJ1 zA+_`(q-}Ei{x9&Iul^ZJ`qt66?0llJ4pdD;T~Jc-87fOsewL*C4CI1rT$ZsuTbBuRdlLDgx5QJzq)hGBh&6)~(xV z)+$WT~a{@sVU?wzkf*Hr%Z-+qluB0^6`f=0{c z+E;C7MQ@th?%&6oU$u=JZoHe{x_k?vfR|>=qR}*oMFO-;8(kBWs!d|yz~esmzoT&+ z93JJ~2aoZ4*Ic@&m~^_@R&TU$B!v9Gp8DC3#bX`3HNAa2p#@J5uRlU0-lixdQoTr^ zW`ZU`*DO}7zL;jC+?E?$dl7T9qjV*=QY%l>EFDJIy-eKwNqnIUje3#N{5Y|WwTz#* zpU%OHaD@-oX%OpJkJT*VPxN7g(n#AR+OYxEoh1;@AcOkI)pj&x`>EE?4+u8@S?0IIHFHeC!Aq>#9d%iQD~wNjH*cM`+vVdnTGswRkL z!>9wxFk2>S%SMkS5L?c}u?3p1?cXC*4OdqY`b9{`MFfHf1Txo&5{-dbL(%PaV6yW* z&<*542f1MjN-U1J>voVXqBxIx`BliSUepKfM1;b`EepA96;3pYIz5FN3*eR;$Yd5N z0LR2tb%bq$rY)50okerRg%ipz7JRg?19ze7Azd$y+fI&IX2-&q2)31J`(w!5!g&EH zm!jzvY^w`Zn?q4cI8GW}&m$BM(y`EtV>os{iZY5&LP%FdD0QUFfUKgZK7`03Wga17 zfP$1JLil*b&gRbbpd-8o#x#dS3tJA&)1TG*e*-z%h)lx8Y8wnM5rgU9bf8Ja^5 zEW_D&9=2;fPI>M5g05>=)-$6~o&CxL?PJ_>K5k(a#Dak%00P(65c=~+@p=*e10Xea z-|}59f883I{cHKr5B`kD5_4f z_dJ%J{~m-d$x|7dXqYyBPrHHoY(oM!-L;EjLu0)4mFLo#^dki9IW&Z-C@fu);gA3324?2U{LwqE z;+j`%<}2U7mkTznpx!Wf^vEf$x^yG4P=M>daubvJdEW5Kb#!MlTy@C?MkfoLJT=ax z=dI?-i`Ekg_=tu5&$2nTo$+!V2camq3lF`vMx|KHVo2#OsFkQ#W&>5#F&DntRtuph z*meuowUMrkY1UB`l}5dYrhBPZ3uu}_tu~JkN?X~+lGxJ0GTV;Hwr#a(HnP2(ecVDa z(8W+eGC5*K-YD;Iy<@e{0kWz7$6+3W@+t_n>JWRLvk5 zPPV11<6R`v{Y2uOboXy0mFXwfwTi)&7ZLJ@Sh@D4_;r<#S0@pPQ_t^17cSMY9ZVg$ z9jfCTy!Ed!%M*<6{Vt>XzE7ht%-F84Qm;-@oj6Qk@*t=xt>RHY!8Yr743|hMgRZ#f zUJt>jpIAJ+*yEw7rxl*s$DX=9gS&1ca!Eh*_9J@+z#|}$YAaHu zGLY>=SSHGB9x*-)lM{&EB{;f%JA?FkQB(!>q5DxE+JRawq56X03t$w+ z5Tj#ghK?{agx(IY)OroY7ecUL1}WOHfKb#kkKSK6@pXE!-8gmt+lphE2?SMIW)|r-aODh^=|gZ5SDLtP0U^e49S1lDxY(A7 zqD&!#4=JmFg%F+v>Q!6K>&!m3pFK~WG?0KxJAh~+^wG0OiB9@+m?Cim{O@wA3tQLylZ3mjtZJ&d)9AKEHh2=OzqtT~L zVhRDD{`8q`iQrG`e}(z}KLqVr25dqgf>AIG5Fme!sh}Bi2=SYhe0&klHv~uxS+m*w zy|3Y)oo8y~81ZwrkzIKX!-sZJug)`acqe=A{u-s(F@muyfpGGy?ZILy zb`c2WC>KZYhcZ;lllc5`nvF85sv{JIS~*W3)=e>gjCf`lg~>yNlFJcx8B@fm&YvU@ z4B!d_vpP*M-c4cRAnERN$&c(N-LrwhuP^Dou6Z0YhR{rQtU>|817%EmZwVtg^sn3^jgCB#DkTBbw2-s1d?%TWYe zym>hzlLf}}1=cL@#-kf_red6$n8mbgcI-JyA{ylIiE)0m;{c!ke}9J~L*snn3peuj zA9@={ z@)Uts7l~W|WCPXXVfltZ9NR_H+s)s(-V7eUflvgF4eIH{(86NSbp-R%^Ms;d8m$V) z9yv}R93rn--3Qf`Qcr}EgA+~M@X(5ad zxGfaTk8}Q|D7KA6;AGM$XebVdU>MmlAwShNF}(Axwx@w@!-g%mtJh=v`~QbXWsuDV z^4u-Z*9-gifHwfG7P7k+nMgsgfQUqpl_D|}M=C1VErjO5aZD6NMM{Z8E-s3n4Wz3s z%-b131+&!+faRQ_=-6iFOtZOgP}ByF-G`-8;ohqLWmu*|i z=f8d{Gjlb#~ z2llag#Q;}cvVnCgm(Y_-Jm-C~Z40Es`0%5Y$}`LsCNM%Br1~z$wp*n7Urw_;PG%s3 zW!4C322%APoffG;46`;*$JQPi)|7;U*65`gTp*}Xqa^?didFn z{lw!T99N zn|3gnpJQlzhMBoC9z$i_@+JJ~yIw`W=jFOj{Ri)S{l%O!*p2DfB%(o1jn7bPn#4mM zB0)d%r5Zc-oZzx;D|ydfe}(0J9aQTLF5R}8-i{>Kee$a$5HQ z(4A(@vTpVs8DYns6TD=@GFC0^L=jJwG5ys>+$X?y_Ng1~d1%jt;c3&+f}t~6rqkcY zlkLT)bX``ixeUu}Al6)pln%A(9BWs7-~x;BAjqWU9*GplG-rtk&V(JU7bs)6B;VKr;$-XN}H6U_t& zC;g}zNTIXxB`aywOpJgZSDFN({>2^-%XAQcW~d8}=92k|B4*2^d$5aoX^ycYV+3LW zasw)cM`w0q0#)%5>x^PqE}8;TRd6qTIRdbob%fzV5fb;+uSPb3S_L9&k+CWj+5jQk9gk0EL`T#vVH2>8eYh@s;UjUm@>!dbc!b?#@6ortro)6b{? zj@@p8c8D$f{kTXufTFf=ogNgmimF=Jb_PYM)3i6Ds102Aymp}C_M#{@uB$D)_L(en z1+F8R9nPbdCrI}7u_PG>pN6|;Jwj1&g#=YY#^Nxr4B=YH{1i$dj~E#SRl&{X(2gHP z9Nvd))S`-T_x8-)D^OFN^i=&5olUt@Tx!mi_U92hRrn+r0~ z5vC^{pdsYqU#oJc1v?t5I-*ysQ=*@-L}?^O7EX8A3=r-T*sy7ubFOD63be zxL`{HDV8!eR_223DdMSK#t-}u*VjkIE;GFQ79!cz?Av<-zCaXJ_fVZVMz&`o<>ENu zaDqTEj$^e*WCk!>H9Wo$zCaAK)gT;6W0_4f-B{!}|1y-XZr?S=_Q3$R@0#SYja?+d z&yQHZvxDHG&8v9y&-$HGtsM3MRgD32UC#b3VXbp(7~ zgn&0*v5k*@?mKj3V*K$tUP)&<&I6Ag=iP6*j18-LICx@=uYUSH_bL8|41~mlEb(BCBb+viXNg;93$0p9up_-qkHwsaV#5zO=kJaam+G?KaMw$ z!m5nok9Cpk@S!g3pQZ~Qo6r|RknV|Nwk#AyqG~GfTneE|q@q)qYfzdl6HP}zI%q1m zwrn>A>8LAHguZawZf=c3$mM?0XX)sd^# z;;veYa^eV%s-RjnZYl$b6wDWp(Ku8}NUs+(1L;@@RYjgolMC^zdp}MG1Fqv)_!{DL zKc?fJ{#oGhV_ofW+fVXW)~3ZdF2e92T?Nn1JE`nCOhT!nWimJe%aCRZ_cU`?5g;wx z!4@6f;XcbFZ1fT?45kRLfpz;lX_KSVUq zMP%WDrYeHIY>2*Wh(d3SQ~4^VrmGB1wGHw5av}P&L3+|bmZSstJipkkdkmdR&tJhe zzQ1FUS}{9cVfjD@r$%PDWZOC9QW54WHKdfRS-ON=GE62OCmjnhTQRwKeU3+u7I^e{ zfrF>!(Nu+{xggP?msHHhn%*crLq$q3^fNbHvsJ?~8;qUW%Uod;;fY~{yU1;PC!x#= z41WwoZ8s`D8@R5^)Ks1oD^>!JKdD~t!s0J6 zv@0kVZd$=?v4){*v`mYOH?JU*3}ZPCD+W4=M*>I*D+f9l8lPeF>TYyRrLQx^1CJhK zzEWfB+Fl%2Vi-F8JvqkmMOF{CsTJp~ALKiK|Hs_=;9maazwYEy*S(QMG{|hZ&Y_`c zUVYgXrspd3b$Ynz?mg^3KEcjCM;Tm_Woo8KBnlMJSp?sn;MBML0Ir zweNs>9d)jN?CHbNb=2-YWVr;I(OxK5Dk$TlC}XFfTtaNW2qzRp-Ej}%=t1c0!8vCg zvcC`Y*m0N~$IfI?Go84}48n0>dJH!jMTQ~^XH6iRb?|tAcAuS4ly(pz7Q&5%9=xZg z20c}9A{PF&v;RUUh~gZ|_$Z<<(>9)4y#YC2VCjaHXng}%$rREykwPxMMXV?lKQ03ZNKL_t)>x6?pFd4`prCu_o9Ha_u;Ui*|#RNU@fv`hy= z(|GJ0J9Z4mJ%B14gm~@@h!^pj2o-lc4}Kr&t6qiZNF#l4eE)7nNIWmbT`;Uxr?9>$h_>s5c_2?AJHR9pGqDH@z4z5%drCe>t zMY@89WwZNufm8V^wT8{uY#k(6u0u!M&x-B{$*_)BG*BvssJ1H9TPBJA3rO^C#vkrN z_r=ayhFwa@J@@TkYHEf|CXLtUU;Ozq$-JnlN-ik2*^94h)az)vMmQWn z(^N`TALp#hVc9CK(*mJ#-_9vqtIo!?A%=!e;y5;uNEFj-k;|r$DCn9(Hj}1OsS=At zux$q+z~eD+92Z4MgrectO;aa-g%JAw+(XeRFTcgpXejwMtT-{9iSD|pLQ z+xe5f{RS(#J9+!-FW{1Qe4KAz|3`FX6V#g~U--stT>l?G<^6BFf_Gng8Q;12Atv(k z{Lx!qj-m+O_2GZvf{n|0*BdTD2!U-ojL**FHw^yQN58~h{lV3YPM5g;D>w1Y|MMR1 zcMmF z)j5Lk9;Qz{Lb7KQjam^YG@`i`G)fbMIyRuAA$6Tt*G8J<2|~#Mq)TI%_^EF z2*`#0>4kf`X`|{Yw&_rm&7Sdlo&lSLb4-8$I=e! z5JI>J&5x*6 zk@-d%`vidNTBoO3s$sw%>@aGz&+@W-mG2_X>8CV0FERYNq3 zD2|Ogo=0jbZtqf@>1l#pOHjN|zkYbjTj1+oKePRH-pm``s$hQhZ`*Tbc-u0Yr`HWn zs1`lx9=DY*TMd+!i5&`@sW<_OTE*u-j-spp@$1_&_9C7qNCWH3-vG-(^!A}$ybW~8 zz6WmM!JEIu6>q(c&Vg0TP7HI`cmItCZuWQz!Sz!%{4eVSz&m(%1FLSxo)v)NrYuxQTqEjiF+Ir`Sj{R4?KE|FaGCk z^mS!0bd9%PeE}Wm*b~M{33HVuEl0(&TEv1L!u}`rZcNWNC^v0Ns|5^39>`+a^q9v#P( z`2B%Jg{ad3gAjsTBt-n^eoE;M@`j(5`FJyvzP>($(3zZWF_~|&bJr9r2V-=1MaZRn zWYQk??Ac4TTE=xH%|;zv*C>~3fJD)|ztI?53V_PO3e~?%# z)(%2)nYK)+st^nYXtr7e{JwVJu@EH-p<*>l=-x23`B9|MQE(_t9mE?IGS1nA>q-jt@C+j9Q;`WyMJSDeS2uGq}SKL0(gz3O~6uIxck6cj~J zs?_NB7k7r%K2j%)F|S6_rsG`t?2Pk!C|`Z-Bzga9fQ|(U~4UKrr4^JQko z3dAx|BAEnMt4V#nMkF1>@Cq!m-Po?+AT&?gL&E_@Q&Gw#q(6jIK`qSS0&0G`t#}nn zq6{5Hyn=-GB7y!^sfc3yAJ;T@6T-i1MlaLR{jM0Pu`1&M6tGC0;-O7;s}neLr*W# z@E}zU)oS6m4$>PyI5v)S7c;=BI4QvKV8pu5rcHZ(W?z-_yOphGnW8d11FVJRM zoGwxVxQ>IOsx%udJRXB)y@}(v7+#(EnG(K$L9JY)QEOm$eH3Ts@CE$Xruo7K6Q|Lv z5kl`5A0SVwo+b z^E0TL!Q9*|<#LrkAi&tzD3M4Ek4LB3vIvJmfFu@8wtd3-(}x~5R6*68TSQJgOlkH?7x4eAzTvl&d&A`}V`42Ed6nxv8m z>Wu~-!$46KT(@2IK&aSe6-Ck8%2|~eg0W8KM|L7KFRfahdSRITC#sy7s!E|xn--hb^mFecNBLiGei;w#Jn`8S=GT9ii?^;q*EDjOI6HP7hUk$Kg-kbrn93!6&}(J+AwmEBW|8-^d5vbrq4| zGpoE#&J>YSK51g)e+o|18e6Rzs;c2S4)uBwe;`I7Kh(beG^>>7C-4Rm%uF6eHG)WB zW_&-{r57=E>Jg&Z)p&w&tY(>LZVh&;i6`2LFOtJ}?W3?q$n+?R=3~nTf;#$aX5^?kp%6tLx zQwYGl@^x_R5Mr)?)HFmYgVWQGGI|nWR*`iJ(m9-5C$e6pzV{%$l}j;&&hbZwNcCii zqympKO8ixXZ99}obvin`FcvC<|6LXTQ=ftle(=ophxh~^@BU|;um3x;(ZF548h192 zcH58JPVkiy^4fReG^%KK-wxfq&}bkcQRv8FWxJ6=Ma@s43?DW4Cy-fb%V`U{5Ia_Awm3sCbY znRoCMXC{cII-Y*u)8KSc({UUWUf{~a&%>22Qzssxl0QMFbAWWF4+9(7%p)5!j~go@ zy?pi7BRu@@ZsPG6rE-N2T=$0@eCT#UYJ+UtOE%^^v*`Z?F*H>nH?Rpsef*8FR-UC) zm_Tux#DfMwzXuWQL1x!bER--^70WbfwOZ7xB?5jw2sm))C=-)Y)M_;*CMNM1I=D8u z&Tf`1TS_z&pogGpXg}M0>UXM*2=b>7y6OBelB@+xRU5?@LbMSBhk4G|@ujBKm1OqzRlwfLl2HSov-VzHQ z8?J*Q6l}*qx;C2bp;oP;Y6{J!iDR`;HH}iKjMwX>*=kX(*2t!ln2c2)f}#;L_QVqg<&H4EWJC4cl?>`8+s|%O^hdSvGIp$je`L3AR~7_k^ewhR}Tx zn&l~4^#YnFz})C=e7cXR*$M96Z?P=h;Ew%|zm(pzxsF>tLOj)n&mY9GEfVQ|Y^#CS zA44|+IF3amn!#+<7n@^GXJa3iGI$IM2>Rq9Pb{$HhLad2E0 zRcW73RZ$jbN*1o`QmizI1P%5bn_y&Oj`P+pC7p<1I}V?{;U#@pYYzdyo}HO`%ii4w$-c{=-}Y-ahCRXuyIAtS#Q{$H(}~h{>4}Cr78*cXXUhYx>!K?%?7Ar)8Q*De!vqh34Qk z)k|C0=O6xT7pkK0%8S-N>AuvOEdu{TDOFDf>9(E2rIgrK3*GQhUT`vR)aGb5D;S2K z!t@DL-9x=PPhn<=M8|3-haV=AUXJ6s)N6AjyEjlPjuA`^;xVE)ib5!N4t8S>f214D z2q0aHV4@$hK9Av#w)a7vsav_u0#!f}Pr9geESI^d5}FR7c#O%RNh*aZiOx8w?l^_9 z5{0QeU8}kX2K@`Nsi3H*DZ7%wSdmyZjH+u`rj6^m=(>UTrtjiJB5?ktNL4#ylDSw_ zkl3b8vu+WHwC^o@@7j;1>!fb>22sc z?}HeeXlay?aplmY}}$eDJ^Uij%)G!9=~$ zVs5@jFyJSd?!fEywl8Ye2CE8I1-Cwp(`q0*5!7%uo6fuV|7Y(!p@bxm1VZvlAdm!b2!Vh@3m7oiV9QmKWm%GC zNvpQne$Jj=r_cLgR+42E+qgn}eUf(1nR#Z;>~rpNUDwSIe{>78#aZ6_-uLr@D=uf_ zy4C#TXImJ`hUiZR$t6Q9DnuB}gdckm^UzI)xt>aXXvJAyW1BjS>NKrdkyJz_nTR20 zRv{*qV7k85pQ-n#RI600RZ__W@mQ2&6VvF1LAO!oq5b=5wz^oBg|7F=q|<1s#Dd{L zR<2%$D2hbFK_cO&r4T{egb1W(!r7>2`ZqmPIfaq+F?xPNgsm9Xv>9QZ$=Q6h&qG{X1B{ zZY>+uufw!Vvgs6vKCL2|h@Qg%jM*3-151}_pr21AdJ9;a93pZlvZT~#kg_wGic(NZ=3*p)p>B0z| zR+&gFhk%FeKp+sH*6fgsg>hYvQoYB~nHrl`4?LyM$+HF1vQcCa%l5lVk|g_yh~seU zJr7au=oHd%1YpIYKEC+P+nFxaNyb97x;lUMyRYI;{{HI>_h->mnQqVEhSy%jXa4KQ z3=ZVD;ni1gbh5HJrkJ0P3N%pU0>fjdgORvP%JIKK>(fmq!oi?%jGGtXj z6cl2G^%$*5BB{l`CJg~ui{QE@qNvWV1)TXr(zb16MaJk_=v|#~B7`hUm^};i5ti!R zrcP#g(zW;rA#Vbz!>^lCJ@A698 z2Oq}E92ZC*r``%D#O;D0%;y;riX`DQstCadjw~V9N;tZXGByU4IXM3kto~tK$2e_0 zYTyux+C>ysJ+(LDdHh`PJeQ+;x3T4a{+&u`ieMzc(DL=fGksk0;@9%=8?NR(pSc-X zRtbcokA1)=1PS-h6z;Jp2#1hH79ykqKgS@=rykFGGU2)|tyY^#y-A_aPd1x9D@ou3ldUV)^RQh9RXV+e+pd>rRHjj6k<{QSB17vC z1eHfl7cG^FG#U*80S!~vX|T&v}X4Z3Z+{oU8Gb~Q`u#`ne z`aXK%5b=mi+sku!PT{=4F6&mVz_x8f0m9J?mf1rKMCK`9$445U+nM1P1&_Xpc2}p} z(aC2LxUNH|YjE$bL$o_OS6#B2R6NXFwaKS%{2_O2f0*m8zJQlpzK-=P7Ca;Coh;V) ze;@rK%NArXObbm__~<)dPcWd;Y;`#{T_zj~@S%UaiPv9yDXT{YdEs0Cif{hYA2L`- z^MOx(4M~RIf8$kr{=e@cn~wAT8(z-uee{dG?fMt6arI)}^;cgemx{7&_YwZ$o!4{k zgNM0&+g`4_dLu8mcn#S^5CoY%;2SQNtddToPty+^OrCO4c1JWSn02`dPmKp^Pva|psS^1bwA zaCB^nHS5+R9-r-T4s6>7mt1o4dM@EU?qw6*+kb+ye%;S;_Tz;#7e&@UR`9xQJlnzx zhH+i%ln#X`ngl|lh*BOw_`geIe6FEYne}PUy(Z(MdocAbdZ$6R)u1vv&i0@D4}bE- zJ4odRANydB7oLiJ%ND!`cOWcYjP$}Q5K@o7Q2un{SxY87&qLP@s*M)GV3>S9f6~VE z4A`+_2RDEJ`}Fts^U7CVM=G7>{qKK2cip*#TYh{iqGxc|J@;|+$Weah)fdy8+0Sgf zN2_abaH`1zqZKU252hCNMOZ!=cKop!53u~a(YKvF2=32G{#fWo4s%Me_fY%b5jg~OP-;a9jGL-hMZk`P%5B1;m6 zE%Kw=MmaX#Bpwynu(rVDOovM^UO*)1;MmqF?{gd%NfNPb8^?7~6@_}Wj1~-2t2NLK z15p&1n=7NJ0h-MQ^?H+VILxu}ak7~dde6YLY!ZnW&1Rce)UUuJO2lGOEYm{MG$dKT zbwO1%9LGjF%ja`0IF7^C`|f3Ec$h#S$mr-Oxm=E=OP2rwwq?xIt^8@Rw(ZjEcF{D2 zX0zodJAz21QX!Yk&~CShM#2Qc5e&UYU!j0y+k}GwGVur<%b}3ZVHgIAq7n)QFfEJF zeAh#qpXw?I0+!K2(W11glT6LjaI6-t*(I7PP@me#*8Lr(XG^Go2to5GebQb=mMle< zRq8Xl>05X)_0oQ#@f_i37SrsJ$t}b(4T7O4kys9+*Cd%4M%P;?O2FrwyXU4`{W74| z=#Y#*bDObg*<5)2pK|Aa{W<%`X8E^o+|I||{cGr^!H56xCe|)n2$=k6%fo#1UB5;w ztnty$e2Xvs)!PYZDsTVLzw`QQH}R6o)^Y1S5AmgM-@(8B#SQ%ZjXz}h!UC!y^OJk_ z@Oy8#h9$!Vdb+{k$ttgX=Rfd~Ke(Pv8<+B<+jnut_I(WZXBb)7&xQ_5Kitf?dBY!q+nYH zopyy_C{B5H)TderX&c~mM*?1o8ZC_}f| zr8GH5v)o|mc_V1CFq3t z4bi6FXd#F){r!VPBGEGjz`CweDo#@<^mE^R_aZAY%a$)=a&n5F-F^q}eee5-$D+LV zz3;`gZPu?}&#QmsQoPPM(U3xP-hFB1P=Z%(8s_j!i=Bt6l;&lIKRSS{nUy5xRw2J!?uu#(@ zXo1ipgx3C=B%sjepT~7<`UZySbUJjq9rF1M3l=S=Se(VsO)V* zJtz=Fk#@)6;n5l^mgTwfvZXXzI?a~O*s%&n##&r+xpzjx4ryMiBFplLhb)=)9f3lW zBLx2d03ZNKL_t)clgZnng$quhI(2(GS6{iAR4EyAHNQ`0l#b6G6QM3iJA;V?a2Cl-z1o1%+^Ljg?FLem0x_-pswghV!;f4;w7 zSs|M})!tQ6eR@bFdUDo8EEWSi63O)ZbK)>CFo0?3WOG?8%f_-SBGCxbGeu-sq*OF{ zsM{kJi*e6=_Y;ly_rKfiP$=}#Y&J=!lZ3-jT*o4xNnu(R;b@O=Fh-^jBArfQ7zVm- zuzmMos*MUSdCAMT@ci?bo}J~6EqC+XhaTdZD=y&jSACl5_=Dum57KMQV6;mF)G!m1 z+mPijW_^t6ecvHBd_KjW{Ri2?2%;oo>vd9v<#gL+;_)16FoEaj)L36=u<8-f2Qzs2E~>K%A*3M-3P{b!9}Ym)jF(QHjJjq+`eruD;5@*nyvHM4_(EP z$r1;S6zTPPG@5OeEhr!e{^av^*Qa&?)LUH^_U8}~*?)M7S6#i4P*CGPzI!MCee+iS z;LR^4n~E`8I>fJEyNOr7=t4pPg`aJEnDs0AdFPv6PBI>*+-UKk-@l%2&)}~=_gx0E zaYRYtKfikytCkG#tsigW_ulv`93FT1!5up&*V+`zP5$xE-a;W0XUE>7JTy9iqR71R zn)3+8mre{h3!e$u8k(R%oPu_ zc<>rJjUw&VL6kt0>I46Z5{%R9)M!+vNcOK`>*0IoTXF?bAWbg1jQ+_k-Ng&2HWid` z9@l7+99WC%dI*k#qy$gw(V0vfH|5*wM$;jrV4mUS1IVh3shcG7NngxuJ9x5q%JsRf zM|rYBuceb2$Y5JGmT7@25Y0qT0}{QCffi7oR_%o(iFD?>|BnZco-=WT#dHZF@7n#8 zBonUdAi5szvXzMU-;0&B;XIBV8)I;Ah{cN+A-X!|kvjW4f#R_}^u<65WsnNzBZSVp0r=J5vu|qcb_>t3a6Bj$ix|3rtjOp+or8xC z5(G~~HMP;DB56|=HE96gzj9167e}G+QW&jA=QvS}h8>43ksS zEMByb(p-fDqX$^GZXJF39NBD|uqt68k;`V-w||tiYgYLkBF7~d(0sa;==-vJu7l&6 z$a0WwZ2~ozpi`g3Hd=^En8wU*)L@i$`4HX8F@lK#rK9(eNH3w+n#Jjr$quZeGV>6b zzLoPnG+k9x8(g>iiiTpr-Gh|k?jBr=Q!KcJPI?gc9s}@rYco_tvBs!qfgfWk6wCzU!sv>v9he8*N-|8(Z(G$kg zTCCtBQw3h<%hn$+v)Tbc4$UtU$40{>>(`SnYtI|~G2l0$wA_IDc-BBm)PlE7$BU`L z;?=GLLJD7~t#!T6%PGNI<~T{F%PA^L_w{DNDW-Z=!xE>!gv$BasLZ;z@CVJkzIQhq zil@M?zlgT4+0=oT*^bFdV6WFvRvCQ6+H!__p+5!h4`;%^^k!7rD(h^HfKY>u%LATH zFY<#R>{9y@D>rkb8F#j?Zgc5w|7cz0Nc3@jVGPMcQj~pdsR})A9j=wAl&EYxJ( z_935kqL9~>nUv;lzV}VDl!37m#T*@xVm2trb8x>L;ukOI(u@(nD5=EDQS+5lw$7r{ zPWA|wHTU4ja6_4)8q(fq;AxJscSY1R=OGDEKPQ>Z0MgPH?)2`FT<5`~t2pTpcpg`3 zq+sJx3I}t@nPD=Gfk|J2@8ux|g@pH`(8K1)`^F%5`{oS!T5i{M*n~d|K+O0ap6`@r zVZRb6b%gsjm2#0`nJ-2lmhy%Q;4g%FyLsS@p(Bk6MxC)<0Dy5s%gAq-*l1Trh*pK4 zyK9nJHo}t7uf6EjMRB|aQ&48vK0&`mg~%EOiY7bl{t^${;ah!5EpQsjU~b9f9*!HhFp0S4VwZ7USv_%pU>c!s?igY(L%0WGT zF1Sh4ljyexd}`_0D{J5HWai}za1*WezNRqAq1$*|(2kY~X}@VT61{%1kDXbBXBvLQ zbEe7y4_C_oEcnjWx4g;YrQzieK49vi7cqQ-*@_ygy8@E0QU$g?k~CGJ+7o zu;cU5V2vg--sSvG&Y{gT&W~rzvBQ}^0`dUwn_uj7fcybg)mZhsK9X*eXDn7cdpcv& zFwK>|ZHEHBh>T8Wky~QE1EsRMhj1(#e!Z($I z2ketaTP(xJk}sc@PkH>qg#gqQ)L(`{M@MucZp#N3aF;r`Yis~Sm6)-_z8c?Qd0>a8 zbT>FjL(jFCp%86+TSUJNIbX8488$(HTbhwa&ak5Jv-rJ`Uln*~tKzWG2INX24?S$m zYWuDe48&8eMHNaS|1iUg17Cwfs$wahJO;XO1rj-hF!K)}y5y+?9Kk{IAj;wj;(3qU z7MIut8p*7TaY2!nbHB^#_26S~zrayti&*!nrTQF_u8wftj%|)R@*K1InGbfz>-SAY zTgB&o=ymA=_p4n6i5<_-Kco-w_x=$o?FUfZ#y{QqKgJu*9}v#HS4MR@t&;wy_-KDK z&vbeW|NJvQmMHH*3YgFMRQ7;?<7raH_B z^Z_Z-)lkZ=8yo#0I>OOp@=id90Vs`B8mK7*l}b^;dljt>a1tW=qlm0;WVx-frKt*E zhV-`z71nbV@@p6^4sF`j(^@NsfhyfhB*c{ekQr8>dnTxvH&C?TuFp7&j{jTtuKE1! z{H?0{Ks4~`J#e7livETB_Y%rfe$l@_ln?5WN;p5X26BmqbQ|!W(TM4EKNVTcUJv{h zL7=*v`?cjQBtx}Dp3}b;2vku^USN_r84dNa`21!Guj0!A(d9W+CRp)6iJ-x~3V-b0 zoUX1T6!Zzx`#p$AVAy}~w#Vsrys`ng-XA|%?}$_s7(fdsj<)1?t1dk zs?tY!FdCdyS5Ny4rZ&kd&wGznTOG)`HWIILe6&9B0>gcb2OUMD8K|3)3@Y>Vp;Mny;bns@(shq7~9{W zj*=-a|Jv+z5#T<+jyo**SG)6{CaI9wW;9$bE3wIqRpOgOoRs3As~`eAV=07kbVfZl zTvUN?{r2z{7VcPDMnV`NC#L=>V}A-a+@}s)H&0z6tB8L9K#(|WRqimP&sOB%isd?2q zP~)7z7Zn7w;>Zfd`kXwRI^LY$JX=mt7L}ol3J8+ojOmQ<@bL93WG2&WBO1h`b0cP) zQ6W)Gv7l5rpAPaP4VU$gI%1l5q);&KOI4)lF=Z6&>vbmVs6FeklL2_9I+@74*H1$a4r^Z0_pgrVx*Qp*u^@}^8i*LL`TaaM!Nod>Vb52Q3)Yv>$c;fUkrB+MlWm2K_B>IqYg8<7IB(Z^ zo!xsu;<#ugo93@8Xu&g!qt_#yq0ayk)5=zzQAhmOGoPgDm(vyRYv1?u&#by~Ez1%a z;3rq>s=!MyF305e^QU)221vp10>jQW8a##>33VdWT*OD3y2sMCTUec5u}~4uH^lGKhkeg%Gy&RNxdTeEiUH#SuPTb0U%jPVqUgEO6+^(tUQ zDxn}%o!HM|Y&Yap$Po}~Qcn_}u>Yt?KVqTfwbYs9ymj+V-dgjO86{F^xVIT7&Pu6k zI&@inYimj<*fy;3bB?mB4KF15ne(^*0ilS&c!|f=)x4@@e}I(K70c=8g1tnJM8lTT z_#PGp`RXVvh!ys{Dsse}%Auj%(R_pp4&pIlhDHy)?vC9Gm6SoKZ|V?-Y7WZf6O5En z&HttoPs?Vx{D?8np#C`k2MmiWptbSO5g; zrkp5hoea*6akZbku#H3zr9AAiMM8SY{;VxWyZtjK!aN)IBO=o%h&&cMk)Az{j=+S)D;H0Z*@7;td4H)S zwm_~sD*zde#YVZx=7LTzfm;4Dn6VAE(SoedWv@~z7E6M1VBwVzBKt2(h*{Fex(oZ( z2pB0KQIyziPSaKzRkGt+r(kK&)tKmY!p@``5HV2Y=m>xI2P1q7U%W@6Dy5hZanY*P z^<(uKOtI!{S26L=JXAm64cp@+uVii7`(YS&sPym4v(Xz*lcR4|ER@xJvPaHgsWz6^ zs3|))z>R`Li*>uTazZ9orITjs0NGA>9%zF4xMW|q`@BQ>^c2Qzn|jjhnK2e3l5i$0 z@5eT9u}vCzKStfm6W<~*I$_j5ElC>_Y2khOd4fI}-Py|xN#z1CM2b{IM%sJm0AMEG znJ7r$sI|#bWRx8}OHQvao>NvWn+V_Gn$ju`J4W$J5HI%v>S|eQlrm%{BoT=eZ1=N- zjD$6mJQT7lDk4c=9(38Lq4YCo>@I zZx^5*D+Kk1OCPu#rrA0s=>?Wz1KSw~w_)6w;TT0W7rz2*ekU>G`HIw`Q4X1C(tY3c z_)AL)zZ;i)QiKmZ*Q)m?5{qplTE7ODz1Vex^}+Cy!o~3Ezb3x_RG0nYBvKxg7jSZL zi5lg-b$bYL67Js;2~#Ad@>)&5YzZ!-&HlrboBf4IEls!H=|k{li+A*It=O)ILz#zb z(Pzr0mxr>K*D}#@WRVLIm@NGGk5ZmLvb6W4?^~A2+uDZ9`e15LK-+u~mo@^Fjy$&L z=ig6=h?Cbp{W)5AxA;P|&^*x+}f5aB8`V8S_+G+5)>@r}U`x46CxTBsXu-c@8oDJcpAk)3! zi!k37Ic@65W(x~EJR&Y_5JT^ju_$a>P-Tc?_y`+P6s(mVhrJ0q@)If;Vcb^#W5Smf zJsMIp)tt|!*+_6~>WnzC1KGK`xn+VqbGsmg45lKO=LIeN6JD%aD_K`6FqWNzLn1Ix zwAA{6+7&9i<^5)6>C-(@6)8HRKUk}1H!783o-@u<%LK`yJN1Z^5|a3>MNgi%)53D9 zoEZ-99WzhYVu!>Gl)@FddK8M-LfvZ!im+cQ`68z{OSkGkbJ~pTJC5}2?Ss%H3<$`& z{I_DYlVvdH6!UaLZpJKM#*;AroBA*DZL~duUWlP*#{LOIb|-gQf*loaGtvr=^B7P0 z>KDZhWhO&P!k8UCo}*Qh);y#wSyHtxPGqReK;a(oKp{5f%!JS1y?`h}_ktet(z#ZA zVGun8*e0ZHbWIQ=NqJCqpzoK?>ZJYs>E8d|_;dy27OPWiL#M5e4jXsC^QY13i@{@- zzFNDgW+#5Ao!+yZ(F7~OE+x($0Q0nB%Kj*-R?&#+FQPWnfuPaa-_ILfD9?A~l2=k0 zzoY7IC**u0h8{CnXt6O}-VKnW!RGj^a=-~ZzK2bAix_(ZQkKQ~G=uwunIj^%9Q^q& zv9^KFVA57g-XC9LQF$=GM0o;#@29qg?Pv@rw?!0Lxe0PF|K=$AshYo(xNch{jjBl6 znR(OgEvtts>8PgTgUAA>$ENJEg-00gEHQ!zNHLO4-5pY47a$MvC69}r{Nr&dVB@NJ z^Fgah39JX-vg9Qt3 zaTYuhkgq=jzc#H+nr9je&TAWSJHEq=I$GKJ`IPC3ScwRek3+}aEb5p6p=Wa*NJtq; z6D-nc%IG?nll6q8Er+-t7jAA4+RnOC^?6h}1GDTPz*Dv8fnve>Ss72)A$S?xRRUVF zdD$WEt7uLTjSG;ym5{!HRM-FJTm{2SQ2pZI>y74w*Y6p>5ZIfTG%+3h;U}*f_NC0V zZilyjZ~}vu-HL7rD@7?QLGP`Q!{ZTE1ac}ahbm+Ga4AljyenZTSO|X$CNqdBg8kgA z{Cw$IjlX-0uvFO*>^$XrsTpAGz@eJ}+RZ(cJaz?j^5i{)P#|1C;(O_4G;F=%52NE? zV4)WDjNh7^B>LxwlXEB4L(n=>>sKV{C3JDGPXcvK0>vBpf8_pFY9JDJoaGfF z;p#)*W1Qmi2()MmBbHYc@`1JJ0et*Fu2`i^B&sr>m9aG=LD`ed)7>1{eX8Y{rXxY0 z_^KqC^80GhG`OQqgAcvELb{i1K6d>)JfiFAF83XsY&@eSMy;{9r2KG7U>mjMN+!{q z_|+lbWT`Y9?FZMgeV*@mj>Q_cE#V6HM6KrQ$(nN-tpYU~Oe*D&U@8-vR)J4oM{4rk z^T`Qat9nE=`;>$IH;pvH+2eZO%l@6SC2X~|NQXS zj|lO_fQ6&9)iUCUb!j#D`hQ@w;&29J1|{J*P6{p+@|J?tZ3XsLcSUW=u3ZD2AA}q7Be?Nnwz^}2Z+wqd8bNG$< z>j?AL;oY83c5B8?d;bL|c@VpfHs}j|0Jh`!2n024Ts^FR4RHrZSO{d`JPF`-b5#PU2^bd8eX#l* z9TD1fE?QtECz|irCSa? z+Bz*e&8bE?jNYH1Ew>9_AN%P=dZwm;@zSBN)BStZYbTS>$vAB?;EuC>kJ%A2TdGjQ z6l=vLAevh=)c?TVO_d&1EUYY1YwwY@%EMm!?=Oy)pFv-#Mfk`atMI8m z#q%b*6g9iaB`7wd%Gk*ZWvQ2PWbTLzV`XNk$@g>9>9@j4LB1-5KmjSx?$=2NofPVy zf19f!xhNpbE`;>0K>GIoCfNaC&ZxvK!rcvIvPpI)gAb$5etMx!E~3!`CYFl3q$|B_ zXdqp2+!un;7^Hl};WChVE5!A_!xZ-lqV@Ywu!di+G4^ojuvD&X4V-MIcZwuEL`jJ9 zrCe)DBOEq(x9DG+Sq{3T>dVMl@rQJ$jv@e z5opJo<@7IBy==nrT&PzEM%C_2jyHf=@4K2nkmW5v`WhE=eQ>IFv|Ni01%U>z5Du!_ z=}#3&)WrpFmw$*ejMXXH{3_~0UR(6qt9LAtSVj~QL_)aRElHN~TY=I&VH1(#WZgbl zr#)&K8N=mqesr9sf2*&1!?meA1f%L^n^9$w?oJ2QaZ9{#1#|l22VXEA_|eo5 zdU~!w-C#9Xp8>8~Me)yBfCLiMo_gfT&t)2^{xLB3;raQxadMJLYE_bx@7^9!S6sgh z!+NjiAnoFbFJFUWYYVmP_!d9mcv2~9py=DDpAQqBoqcPb8}ST)_Wg!x$VTU@-&JbC z?tZSLg_TtlEKfq@wp^tK(ud@6ve*NY>56olF4gYQha9+gW2m2FW7r@__7r?(bNfYZ zdLKZpH>C6DP^c&xPCcC^`fdJau=UFR9KK;uQ~lSQ-BO|1HktD3mTtA-ln*(6aha4gzvlk)L{PB)5J{Qj1k?H^{dRMe1LDQY)5m`J#Y!A-#42uk%i z?X!8;$KMQTqvl1)zzU{WZpAM!4UZPi&}9@@GEQY8X}p91#?G}FNC^#=#s1WT*~0hL zt#QLgM&w|}uM?&uQN=|hT@jzx2w#m}Ws(i7B$Bf0$E)CGer} z%!HtV$r%Sv*!u7lq>!>t?<|;T`+b^~TG>sw)c|+iv!Rw56|BjCf1nDhfHZ7cW~h~@ z;gaDhnYQz^a&HA~vzL}y3|q`BCd5XHG2!=c_+NGw$u1_ya1r;h-QZ{lPhJo7C1yI{ zp@T6YR~M%xL4YUju@>8yLtsW8Z#cs%I~XgEAyzOO6)GhVe6C>-~^q z+-V*BzPXWI{Ac{hU<8*EiXMm1d7rSh`MUr3qsscR`gGg(3A0oJ2cF)Aq|oOWvXnO7 z@IDv}OWtlZdBSX^*Jm+ z-nQDGRzZ{g_BqxDa}zwTKtB;N-F;)hv5Px4kt%OVYrP zVt7##^u)q`v3lv2D>vJjSnC?-2UX8v=TyHog6ad7T;;v|NmUrLt?FCT_W$m>dOsl} zO%hXjbMn3{I9^^RzH_JB#Cvu<8`#0zBIgfz8$H)T4(*rH7^HmNKQayf z-a?HqAH@3>7YWxKa;2CQnTWk-B;-2yM{AI~#I4Ugbvy60olI?s^lP``s+lLpQxq+f zHQ4l_TW`LB5s-iSZcDLKX{p&y55d2gP6g+g%U9>Dvsql{Sp+e)__R(a72sNrlHz_I zmiBFTGCZ37*P%|0b4Y3XF@0N&%_54$2PL_XAZ5}5MGA+nQGqF$8W*GBd$JJLVyRr+ zn)Ek<$EW;vdMW@g9zk`EExt5?A%-;fr_23!#@NP}00CIv9s{^nmeY%PC8%O@Rp?3`9UcFsWf{ zb-+f;yBXEOeQ%McOX-K>NGLHr#83A*{dIgJl-SZj4gczIw|a5ndMAjUDqW^rn3R9c z=e6iV!oPVeAVnKCUs>oGBdZtlv>S?G7Vcmfad+||WCX&9BPd&nOr-yaoiJD3b9P2k zuo}6XE9p44xn$1~4ige8@qGi~$`u~lZ%2zTDafdC`L&ij&$$Up@ZU`UR`3||;#Vqm-7bR;2`6O^vlqiwm+!&QK zxF!4SOj`|HqA77wnOo5lEmr7oGjtoOx|uiDhBj408V>f7TO+&K$zA0pU1#lK0WAs|p8 z&jk~PBq6pw)PKr8z=d!+F}lY|b3sjw>94O%3CQGLLBGE?T}7+-eN&_x%@=Na+z}06 z4ZP+J?DIaz^W64N*m+pU@QEB5A+j3+<;4{XYX(eQA8HI`t==+kAJN{RR|hJ__q0q^ zWjg8MnC)1e0UmmO6-b?sRL`C*akbJR)8)XV;0}v!=tC4$5u?U*L7-1J`;FL*7^$SK zDZMGz!w0i&r+o5mNp6hM=D9y}r0H^D^^3rXqa1hA1k)XUjHnc&WC9^OsN{tZTp{HU zo!)AfYf7IfGs_0o*Z={VF(D5eM#5TO?ZKxnDPcQL%F;0)Y&042oiWS7OG+5kW+pet zhTgS7EnBar1Q$%Xri?svYp?co9^Xc_boSIlcVFm7g}eaX5T_4em6#BDu|^ekqV(aB zF!4CXkw)C*rChyOl2)CZwL^k2!`RpjR|?1^3r4rQN>O9kG!W;MK1N4^AYbvPb#M#v z|0R!_!=~+Ih5o&>zjT+ClR+Ry6(!)N z)j&h(f1~fVGxUdEB^KbR$a%K@QYbTfi8@;@;L0M?}yNGcT zZO&$gI&>Skh8V(FYK?;y;Y3O@%f*ns-@IL`z_42Yk7E+(u#g!_DXZgy3XV1Y=Z+w^ zGt_kZunhIMk_mMC5bH8~lQZ;3z?~6i1tqLjXHB<)6El@eU*Tw2cozu@3zyHezk02l zx}{6D%1|v51Jwc0KY;K~@{PPRG@K?D1nvza`?qYp9&I-UbJuU^IHE!C57~kHtfDU; z7D{peTCZ}ezYZ?zx4pK5{~LmrqjjMc2hIT+nW=3=$TXdNfedWIOCYQoK=iy()>(h{ zCRnEV=(BJ08G0u0@T_zT-RWJJQ{MwDn!_1g*^iY+p3f(`A(sT~1eUja-zg!R5CJ+dKSW@tE|F*IqyJA?n)|<`&81FD0`c@iXh8(fCabEF@7P)!+vB0;m0~VwBItymy&DD&6 zMtk+jXRdrdNRTR@pK`@CjHLcxQo{f>dMB2ami}X(tKzqf1Jk>^_M!8#X*0UaD)Bn6 zdy}*rZpW%br7(?_=(9}!ghq#j^qZ)3k~s5l#Xdj0pLBSB)A#g0e|^gnuzZ>rI~%jh z)Y59A)K@dQO&OU`nL}( z%6NQt*#})Yu5_FE_zZ(eW#{yGV#gWMpDy%svtyzujXhcvCNEV%C?n@dxXdB_47RaI z&JZk;<*~t2L4bsK@pK_uk_-dfXyeG<^{d1veY!lA+zd|0+=TwoLqK;TtPk-^VDgN0 zBhy4KW0G8mxgeIKLAMGM4-Dv*&DS7wCYpW)=pJ>+P{mY$dD)#S;x}f+H=mQ05rWTK z7%HU8)}&`~?N$by?YNW*r>$fp2@y`UQl+RR>vSbG&D;!NAUb){+?s1e77l3!#lpg3 z1Red0Zq*DovzwBshX=kv;mS6n!#T>}vr(IBij zP&&>;By4YlbqDAk*&(VE%}aq|Aq zqqQH$8J{4N0S#TfdG9kq%Lfd{#lifJ=V>l7sJpJ7Asug$sfR;CPmhqrq}k3Oy1w65 zU03>lSxdYsE|hW}47ci-I~qy{rMZ}w6P~a1YgI#zZ~IyzR|ML|R#X9mKral)A=M|O zwPm$>v+Ri(Lx~}3Ros6=6yN7-P}ayvSbgCKqV0!$BBmTAkljD_l^|NB6J&cgX9DELw z5@d2dAXBhg6B%600o4uJkcuvEZjZ{#+I-8yB>f?zW$ZO4=4J_WiOVnh{tqd|#%X2T zw|N&#GIGTEa`!IWW7$<>e|vL&5O_f)((TV1M_twVarDeskjIuK0J*kk8<9?rI?|SB zB;HW=(3=v)rf~d8#mGsE^~X1cn)kfK52{9X9InO*CrYbKMVx{D9>@(~lI$jr)Z6)7YM3_8wne~_F`-kB+_b&y;_*qJG%Wuqc{+XyTov|p0~ylkUyBMI(h>*3LJyo9L_OJ-t{B#&M^X zFc;#{89bd1i~t6&wPVB4^Ns`IUwL{%Fim+@PL6~cuEhB-JJ zt5c?Ux^Y?jyM&U|@!!xVTSN0_In%2{?GkVget7&Fa-&m({OlPm&jmT$g=uti<*_P)i-WoXkk zAHYFxRW%VuISMC59UBDu(epgYV$Zz~E55HELJkEoY)x12qoqI$lRxSn3MGF}m+BB2 z2Uxe9gFu{Jf5Zw^jnDc~^hGHFaIga$HM9d`$m~`m)Eef0N7}Faj0rjR-mN9FgVK^G zrpnW?Gsi|JQwK04E7HkYx+3I{IBkXcEwL)$<53eR<=5rw zilz6cvPMOr_|~mc+lOMPn?X0 z$i(u991`+%`%d1ugzQI(r>TPL-ch6en;Wh~Aty|jLtlOFTi6F3O;xlDCd!w~kq6fc zss{z3Yd|OrcE;|s?jpHNu7?A}`aEj2wi=(O2GT7y^|15yh=p@~ z$sjQ`4e}MT6e4+=oQ-0Uu2?gNl$N8&Xv@JUOBr38Z<{$k&cDqoEF}phB0DsbM3IME zjP~A=nnd%R`b6p|((*gmpx4@1l05*xGGQOSlqn^RQReYQq)uF%i#C%SJcz6d2`C>f z%H}q1t0+_ZzbYh61pNZqt;UEpzznPrs@P$VRAC?hS3DbN+3F@#dotpVL5>c>@BzC* zM1fE$KD1&yco-WABjp4bppHqU5siu?C-HNxd8juAY= zx`JUu^8?3)P|2h2t|77-anCt&*JFTK!+L+CfwZ*Dhy}8;FE!LXs~~p|)(4gCd)5*u z`dlZvw`{vHEQu-7&)fCLJRutRxoOn}HSqefYrpll%GBCA8MVn#1`rG(Tx=Y_sVRmT z8J(?w2G5W9h|xWtew}eVpFe?e@-3`hz$K`uut)T8FuPoE{2yt{9Oto%s;tbxXEV2j zj8p`O?4-*>b#)Sd{Vq(U=}ej_Tqj(SPL$xjuWJ*^guweqj)Q~K?}pwN1sf2K53`f^ zja^LA_T5%dWdCb6)IdXdGP#!t0L)29( zsBej?#XpR!L;UIQFL{EJ+uZZEfiv=x2zCl2)P5;XhEjIB8_+=&ryUxTG{XyPW0#I= ztWAS`iV@*HhQp0p#F7bmOgY>FoLlUMXqmKa%s4+Oj>258>cnHtyNk{ytuf}hOxh&< zJ1F}HmMDF|NlYDm{a$y2f474pZg$<6a3-x0MHN}41H(?)hSfvHR5AjP%?MSd43xek zI{`VyJXmt6bfm(K4_zx(Y)Z5Lc}v?ZKpf%2_OQ5);B=D@-f*qh*;iittLcuzkujuv zW&jm~GX4{Wrl_!)TyLX6=R*thayn61tPTArEcn!I!b`u}wDx{V4Q8HaU8=FygkHN* zhV{b!T)*9F(Vj}fTX~jFH{=wi>)ftKqsP^Qu6{9(Al85_)RU#Q%wt%_RJj}b0|sQ1 zDvc0gnNO*a6eelh2*AUGXdUvD>58~e94TV0*ra||+-&8k{q=n)#j7g3RMb^6+i3eB z`jE&SmiK}|wmxo}C_15FfM(;<= z9>0FQus8$e#eCrUh>1U$>yVAzVwS0u*MF=TTW7u=E+eI%Y!rkuFjnEe+0iBZ;dx?t zf1;SX(d?Wd_wu;a-u^$_V-Uj{tRTLJA`Bn9Or>%J_JMx1{ zze1#uSQCFF(@6gp@OCyKBXboZBhtz`07vU*G=Ee)+y^g&FcQ#ZxYLG zIB|T`XczQQtdcs}4!YpvIIEsufng11H11YiP%)sKS{>U@yc~Ph=J#81*Fk9DYm7E9Vq!f$iAX`n~%g`i;u<-c8 z@2~tWy8xrNEA5AFWD&8Z*`BDO#U@YD-yV^|&lpa(^V-$q1PCGxdU<<4z}pdnst~IN zod<7;6iuWu!`{s~1-`qf18a&-^iW23S0ZgfGnc*+*B|N$sC~e?jxndlBc+##$EPq# zYbo@>r&_o@hS%q-Yg$sMrA18yHHxwZDfwDQ!Tw9=TraMH=*0S3B91&UJiM;rteMTJ zp8O9g4KT#dFDhR3C&-kv9%)2*6n6PgK5dr|8k`KnmW33(vQRuH!G+(_H{NO(9Li*$h6~; zY+5n3`tzr?hLD21#L{>7+B?n*TQ|g|MX?D=!<$4^TEUkuLzg<}uFqxg74P^}C?`>M z-uTr5j=5tQAX0FlXdfXoxt9Y~!g~0qfR_k^XOSn(W>MD*w8~4=@DKSz+cO;T7Lg;- z&eB7JlQwT#xWh>CIHt&Lt^3e=4!y<`-Ea*!k zNn5S?!q|=5Jsw*gT>cK1^wdWhSDk&zTBhcUTIObpAQ~SuWsKQdmlulMs)N9@$KKh1PprZ(489rf zXv`U5K#FLlj>g_0yrMe(^O;@x)I1Fv}#~Wr{s(FAT~5LO(G?z>byGrT*lIm zmAd?!)mkPtH?mi*Pp84>u!J~6U{O?(Y7nR#P-G$d`U&BA8WmMcwsIL0=${v<+%_w& z-t8?a=@h!YiIXGR~ocU4!`e_)$j!F$k`x3MDf{jOp@b)1QSB z##yiuN!$bta>ns5y}s?qhwCs!9Jf}s=9qC1>FzLoY|-bbonX#P1_fiq_P+(6vvX;P z$#SFw%@_wOSIh8_{D5^e{j6}AaQjRp2cV(}hXcWS3ny`66oJAd-Z_vZ6-)`ru>P0! ziQKAp0Y~2z+^**{d%mhiQ=|Q75#&3v?n}fKmi8o#e@B@7utPf4Bf085lvlzj2a7#> z+$?zKUum>2p0}wnzox?=7Z{TfeNsb!6TO(OFMA{VsliAp;`N`BHqj@7=p$l@6ek~d zGvWA^%1u5pTxKQPGqoFy{JR;dF$+Xy{9>OMaqJ}yE#GKm`<#~xx_!*IpqU5o<}JW4 zSHjs~W27Rif*t^$_%elSQLQW_5(FA~=!~r(vP?I7Q~3733uJ1V#_x6CvBq;_NB^=Y zlZ{V9Dpi7f>5*@*+2N8EHpWE^@87q^M8~ zxjJ8~V?uO1c)@^e1k)iPOZ)wa=a)sew9Niu4QP&G=?&Ba_^r#i-VAi(#jGfw}onG%Xz-}UmQf1)>mz7VRYZU zcaQbzi<;Pth^61t_S#WI))@zwn=SYO00mCLXnN%G1p<`bph9leq7^+l1AP^twhWIx z5N~U?8C_4u{b|Xx4q}5pV@dVx^Xwvyy_l zwuImMLI%qXt69kknpQ)TES^2AwNS`DG5#o*{6{HPN1qnp526aapu!y^xA{)Ly{q6N zI`^6sy?8CsE2h?N-_Tasa+z{P-2&hTnT!K;O$& zQtOsx=$oxoCR6MY)>09!)tPeDn(6XzA%aVzz>#d`<@K!vk$}~Soh(}#KEsy9vC{%> z$bPeh$F!KHUeF*eD*-fGsgbP=1(jC9BCem%ut_4~<++`E=m)>5E(fx*z6BEkNRr9f?vrcD;5&Izm4hyn$!~mNQwT*7I(B zz#b3X(@_wWF(J~W*Gv5d?EHa3qVj)ORcdug#5|Q1EL6?b*yHLBUJCUF9O_oC(UH#{ zx%oEdD=4b}Tp(tsm0|$tjniG~%>8mxiq+s4d3h1asoGk^XwXAfg6bL?o*7k-UG8wA zp_v_dv^M7x@OwSJ{qu#~kmOBILr4W(7Uat~!wOYubfi+uu%+XAr+{k?ky~G|CgUF( zBB~&IJmnf!^u&q426dUItu=&dKlCb{OSZr_V_Mg}Y$@5eG`DB3|JMSr`g;dY`oF>A zKL;zb385%Y%7PsU184BaBj$B>!tW>iqWT?5zK3RZotU@pYa50_q(q_V^5JG2 zBQO(`W(Gci_p{*oMEC4w4{|{F$qCBc*~;i(gE|^6hvlme{02Bh(+>&)z?o^5eHDyJ zVVE{pPP|}-)7L|NRy8HkQ$Tha6YyagSPd2=%=h_lI>;oynKZ64RY3}|GULp*EUplE z?D?cvCr9`7pL!Kyv=j#PsBl2*@ORgDzmo#25Vqa^Ri=%{v)?b7$Lmtm$p+|owjO$3 zRbaYwuv&m}pQJ7gE@SU8xXRoIhE+T&=1$?pc}kGEuu(8+(Uuxkb~mfQjrsy3i+9|s zuj#(td&j)0MmDtvVu|hq7_){hOKz{#H2e66%oGQulP~nuogSQ@e#k+&7aQtE`n}?2 ztnzca+H*5IA;_Xn6Eyk(1Jc`19KIMKzpOP*k)T31JbLS?ytrLFFN`A2JrwF=Z477S zTD6~pGaKir(EM(6QX257x$(VNA{AV) zkSi`xuy!?NqRQ5>04(wxEdwPcr0dm0r;Ysad4o!}G}#sYVUPV~n+;MOzRQQOn2AlXn7gUVl>cD+?5*4DR= z-FJDC7`^?2dfhv|^HjI(=gjZe&YPE(C8o;J6ES@=47}72nb$M6fbv?CwxwP#7)g6` z=^Y`9N9{fJ-&(?gitn6GSYQi954(i3w$x(efc__f4w4@?Ci}-Ijo$)A8cHWk1yzz{ z2X%D*L2d=~+rc|E2AE&U7yc-w+VRBBl@+1myTIs$y)P(WO*OMLs zXx|>yzQqB1inWGZ;qp&)hTZ>y&yhju*7}t&K|*iTr$uEkf%HLVJ6uiJ{=rXF%%3=Q zij(T1*xdmb7S@?KN1$AQ(Rn_5>QOxBq1*c$o#sr{&9+@u(os#iVkPB~{kclprOR3Z zxb*!W@n7qox|IhPq-NlOdm%G$bSbCAH-p)E#~H1Y3|OcK6*<(Ji&)L7@EmqqMGtT- zpR$N=!qm9&(x_mq3%F{>Ns{6vyDdH*6k0Q%LTSZB;#7;`X#80n!z$|A*jk@rEbbH) zV74WPwcRLPx-wSmKoV^*(`PPXrG*0CaHyj)Gy!v#zd82HkVNYZc(FpdMM$b{o(hJl zE?%uZ&#N2-umGyHfe)W~S|A(Pm)W5px#oax(D!Ai_iQfD^~A<<+)|}_`NB^PVzi7H zMa5tI^gA*B&v#dCUC-oi4~g%9I_S>-9;s#9YI8fcG*-XMSfPvVP`{gEiXS>mB6}@D zlcw*T{-gyWy$j5_!xodB$zD%UF|YIvq@;Dh7G_5ai8vp#r#%1I%vxm&jb|G?1gmT= z&sk8=3bQHt2k^!e722>@%wn=NzJ1IYjg+%g0C7q#YDKVX(Uz|9xQd= zlY-=WuI=6)C@4xSBX@U1!u4Yep@Y}3tVcrrJ5EB|FInwzgT02eeFWbz?aaKZl%4%( z%Kak#=_8L$q%hMG=?Y5J&GfkXafIX6(&c58p6Q9ikSh)MeJ}8(83AlahEegcxVU2l zx}o=SsGYUI3sK~7hoE`_=~9P1*N^~gz6h+o=x-N_8AQak)ZpQLZbpVE!Ei_hc{7OSIsiwi$ zSgv+aqoU*P6m?7$soC}rV-kpD#r3n+q%FLoxWtxIDj1Wy61^w zW*6cnw@s@clTG1`Gzkg~72l9RUv#9Fi7f+m&l%qk`8|5lrf;V!)5v{||EBW0#E z&FJk!r^J6U!P9FLMSxO*Q8-O;<%LF#*Be0$C?SYQ;SQhi)!|YF*mJ4UY$s7t#!o=}JlN-vVj-d=({G_ts$h0^{jM1CZ50KX|G7lL zybTq~X)s7V5%{B>q-25u$7Ds{l>SKjsoMEU zy{5%Y6J>&TA1&E<1Oan0BLH$-6ELN*$^$kGd8&*)M_rj-Q<6p6Y=uMx^Hbe$6-Q7V zoH|7zzXTP!!H6KueJUje*<2*Kl+99Ys0;5? zy@4zUVQgZ;8IF0p)ia)@ydf=k*OX&IktL#{#$~_Ix6^g{?)k3nrLU>W`BSyuRkqW|~yrgw2;{8$)sPb)C<+0-@&azgkBL_OOW9F>_0ZG~6@njPX9F z0#`9Vwb||)#?;~yV~=qRy!a)t&U!NO)EeFoGWlOw#_=NiUP(~JpDb=6(Xo2V8%Yp} zb0Yg738eZQ<1f6l8JjwRKbBM42PQ$BzJ^$lW;nkw2me>8l{f1sRTr@pKQp(aG z@w?t8PV<9AI5x>jT@0193ojmB9Mi@5K_h!zSCmJ`f3n@s*QN?9;$;Y2QlG0i~1#mSZVpzQsSVG|Oe;*K(RWo4rd z2~;eeGPZ1$@G}We6O{I?30!0Z?O|vY#y$PUNAKXC5VxpK-gH(&9OJV8Iio)(E(sTY8 z+NqN;@dFj9JH^Udh-HltC-13-UBUB`ED))}oN897@70N~W;*q^q>o?gOF5h(bnJaO zo`e5Og6j<%-|+v*9M7*1=;{+#UFmN{8zdn5uks+40Qv2`hz~ zYX5i8JREoBq;)<10|3ka_-Db3J;h{ZT#K3V_KWPUac{qqo94@DS7@Q$OHQ=+C9g^UJtWn7Og*!Mdb-nx9<;`eZfv^14=L;3Tl90GR)BG=jD~N$>Xwc#J;i- zqZQ+^p_Uzf@{qoaQAPf9+pzLPFe%1c>QH(&e3UV^R)>knbn!Jb(6I zQdXNFzDDQwQG#@2+<7kNE~pcj31AVfWc^t`o+?QO!uaV?f%x3tZ>n|@<-kKGY>8qT zEmGBsRCtQHmJD$RhJ7yl6O!sF?46QvN7FX$!v#1N3+!EQ(r7YRW^PXn5OiG}lRqC2 z|7fygKi8hlB=fvAd_JqoF*Py@^1nYUz6-v2a$h;ScK?-cB8G}ATwOse87mZnye(3ltrH^CmlHYn;64b zIUk--4>mInQ@BFj3&h&SSdlLJg*ahn*tGo-uxB;?3jaMFwyRGuycM-$c)f3eG*Y7T zqx&YZFvSBi>1b3biNx%Lm0oP#xSs?hsZeK_w&Omy$yA+;`hI1dkt;;E;k%ifb92xdzC7^dpTD-OYwcv=jJPtNB;pARukqKY*IkT^@5Cy zPgex__u%RU)eN1Df`HK4RIn_+lLN|VWDM!b)4i>Q48%Ou^xdj6i}(9Wt<3#tED|^s zx=-rPO+IbdE*HM#Owq^6wxE9*dM4o$bWqa#&Y3)pDZb47jVzr_*_8?|Y( z!kKR$i%Rc=yLmjW5UOMVCm|`Ky7qpDe!RW!#cK1_YF95!nr_cn zB+h?i!4@#!Z1tcqZ-o)t0a3hFZO6PmtDCC+FE=rYa;I0-zOmtCe(8aSuk7z)n?Q(U z8EPBaj+Xb@-|SAh*k5+j=-5MPmIrQsgZwb=a}EG3B>&He=iyb2%!D0%;Ji8AYcL!XxMciL6V1AH1N?!1?{xD zEPkHOK$k2w2PCK?jbN{iNbn~{W@d2(>>}yPl|B}i?H&AxK_DX;hR;~NB@YqTqarJw zwPNMs0zAIJh`^LK$kz5<#x%%pNWWAUsOeK-z@Q8zvxOBZ(NFHxM-FcG8L=)L0m27I z5%HNA5}T#mVyp|5%2s%`9F1o2wIXhYkgBTPL=6fEC#73Gf0-UzVzZub4 zXPbp=yYHiCU>2A6)Q(ml69R;}MndI?SJEn=TZ+=5yd00Jy@_TIS5r~IPnwi)8XVAl z0~AO|bSNxMre_-zEgn%wvq{F2QJ(rPWMfFikvJugu zp>qN{=+5rFLBC`0E5+sh&R6kq59!%p`j(~qU!k!*61BaNWUasf;A6qNMox~21dtZsq4!u{HwuKL2pl{x& z#;A`|AoH8teK}OQ==uOi=r#Bi84?D=_djD(&}a7>$$vSImDR%}`0a ztob2S!WB`S-GXa-ud#ec=f}VK<&fIAqT(-(r*<;L{_iH(QG7zrQ`2x3@N{bBYI#Jy zxl3)su@Sh&X_7S>Mt29;6qvtxO(^%g3L8K(2}jiWp&!Iz;xG=%ETYh+&BcU>5x@nSgQlTNAfu3Z+1eNKrNag?AA_ zpmD*Xf`e4(Jw%9^3L-I!ha5y8+FY_gB3f|DfI9v8W`jn>1K%KswJOiz%e8<<(7Nj; zP{G22-{FEI#dRV1b;+XTS3Trc|vKma~3EvHGw znfLaTU-D-B^!$KXT;tEURiiq}-L-j_zZJV-=Jx*g>zYBbO<99`Y`B5HfFuU_#>>-- z;27{uG6#NaEBAk!oW?of2{MHQm-c2oV1kz;Q}Be_%k9*}tqG$+tz zi)yI7SuN&K`)Mw*ZeObQrVXCYK@vHh9LcjM7v|ORd(I)!4*nZ0UtY2ertMmJ{0+x&v7lWtDf*_O`b^91o^xOQN67A_QRwo#7QF zW8;7FMo_QJg5M%t8|!dgdBt{kUswG(l_{j!k*}o89;W!jP?kppnc)ZSd$`)abS)_$ z5eJ_2i?#sZI%R={@H&dBuDKb)`(L7)Af+z1a7$0M1JoP^D#EkU{_P@OpI;}0Q+L+3Yud&{t_BkK$UyEBj zS?g!^VwKn^{V3C*6KgCP54y+L%%|>y=GOy_$r_Dho#vF%42A?7mqbGYEM~@tJ$P>B zk#<)sWrD)ShIE1Wc|(HH;U`7S+iX^K@kV{@yJsZX`&eNTjTA^dmg zXaYEx1$Rr5xd5gMh7uL2+lvygDG>=P=V*nC%P);Rf6*N^J`ZB`swA7uKaBa>ZDc5*ee|DtJ0( zhg*0^k%jmLGVD6?BwVROnZlxkdxvjE?8qAuII&Ldn>mpCVgf|!E0HY+JzhAKc+gUqh~~@DkZgp< ztF<_J$H}P_PM^*R*`94&a26bM!B(F}JItd>Z0$>k=rPjeom6cYvM*@bvWZ18OiF1*B=H@e`_V>jI2pjp zO&wiNa>UAKan-sV5jnNINls1%;?>mT2U+E91|<^T0``_D?0L}57#Z@f&q#xjKbU~A zqxRL}nT5N~ZkbHS`~aIghq`e~tsIrz)gUYR@sr`F=Exh-uB_7?NBCf@(YgwH+ulK;um<6=|ip9Xs$Y9Imn zgW{baAU8$gz~mIkjVt)&suFzvv@Qs&u6Z$>c$i1Icfi*BnfIysqE4QNy^BsR6B>BT ztjVP1H!?UYR@kDHf4V;EhY$_!eTM1sK&bQzxGq4EmlU1WK?xZ=Cr)0mUnqos_g|2N zMOi0)AVrogLM_K|>FTRPrVOqKhVvbWJy8hzK_^FoyXny1n1~lD3j`L?Su~Y%>^tvf z{yy*dUGh2(lcnRtO@gZ$`-WdJbry;+_>dd|T-J&OkzCfF?ytb}H>xc%Rq!L{0( zbg{|4c=70$`-J}U6W=P31>kTOtuJR;BFtd2qdRz^WUDt;7VqsFPzyJ zOv8dA{-M;r7UdjGDm=q{@d_~#+3v?To3E$c*oeNS41w`j-$bMs0D08~FdYdgRJ6Lb zQbsab*5=oBaBzZJ7NbCL#T|tZc0n2pf#jFnGxQ$QF0N zrb|*_ynv35o*+ldDj)6C5@MMF#*t>*!;O_l-uM;?T?VFedCB~Fs$_-yJzn5W)w4#? zXbB`Fv0yveEK+6581rF7Rs6JK=sd}zU--gl^XY3|ifGRTKXPzM334yFqKN++ok|Uk z$~1&3{HGRdE`omusI~K|pT&LQxv--rE$Z5h02-7)(A1VtqFi=k#yP*etL&P$U}n{( zH{sRy>f%)F9K#ZJzNQH&eo3Jo$ ztXrnmM5+{~jTXGJ>(S3M&L39Wb{z2--cJJqevPm=CpR_#@rRD^P+vX+YY0nswLvcR1l=p)Le5AKS_=S6#2+GJrpkLy? z4{vndHy{hdJ?@Heyg?p-=i{M*JS@VZU^SEI?{W`38lx*@gc_$nqN4igl6UJz$m;!` zvj=Al#j7)D>sW}&7X?*G54Gv(&yX8X(2$>8CY2fS^ipSY?c^;30wP}hBV7jSX@ zNsp?kYV8Sc^UDI{&V$y+6xeP5r;_TgpT zdxAy!_v!%S;`9@B0p}qY5h$9UpinuI7ph!TsAFG4{LGYK`0L52wwJ1o$Z@C&- z2M~#kZGt~jgTaB=qK+vVI+nq1=5B5(H!g~UWmQ#=ekD*54^6Ch2(4X*u18~PyJb~g z&===$O(g>Thjt`tab*aouL?)eBIRQQ!rs+kB`syrTz!pjhn;fyP5O_Tbm+;Mw>^>A zKB=&S&cr^e8=otGwc^@UhJXjT?;vd=p}CzCQYdG!ayn1or29~8PJq?-h@e;bzr2)U zP}&pxPDU5v?chLPLQwahP1EppEy)k4xCSR z$<#@1EmRPA{gxtI0cO{fK|tPn`6rmo9mzRs!TvpfV7US%6Mv7QDUrkx%#utg$PZ zM1nLf?)VBznE;q?R7IDJ07C{?WB_PBZw##{(JK02o+Cvy>xCn)s%_O^(e%}Z z*NR5gH|CZbRpeA@~@tM8v@A>X11uX=`-e{TfIrwss>VB^ARKhbWum=@xxSAJNXn za87xLu$rq&X6AFnU^6NTyGk$HeHe;5uhksc2(O`qKsV0^{heuG?9n#*+(A2%BwenY)orJ0y6~OV z>W<{2!ODN#y2+~X^W93%4hsj-Nb#<(WAJUq?B1($vhb<59*N^}O1t`T#~mcFM9Cd> zCPt3quiXkN?<(tfBUTwFF;!5qw-XL>4abqm6I{N=(&j{jg{IpP-8v40(xc5~3no<< zHIsssdv0`xwj+Z;ZYyHn|7=j?R(_RjI$(J?Srz@8Trtm&L2a#lh_*!&E+;`vV(>P& zTcbr;j78pOw1>~u?aH7=pRO1op2IC}WokIfSp}tOma~F}+mO?=k5SSXCHD}T=xKe|7P(b%#iql)F zw(oI?q?POiy5lXC1gV<>=N?>==Ravdg9>1lKC5EtoNO7m%L-|(2k`Y4L1o+;yCW+A zF>Uc7>z%Z0lGmu#jx~383~rXlVjKo$tBYD58$Z>y_g{5c%m4B2h4$c#1utGcIlp7}f!=i7_{u3Ns+2NOm7^{zgg+tCN*AgCJ-*nPVLK0>2HupF z^|^>@$9?HB96D8sl&I_Pv&aCw7Ec{EW4jcHPc$N9e$zYou}H;*B>Zd&tD;JpEtv}7 ziaRB1v*c^vIpr@ zqw#4YNt>vz2S1}?tXNmP_2gfqUMvb32rS#-ED4ET*1ZpLGEUo)Ab!ExESzq~&L&Y9N!& zku5r$OqjWXD&?!}>Yj>@FI&(LVGV3tcy>4}gEEncx)g9SQ4V{xlZ!+Y(;Eg*S&uQc zE_uMf)y*F4VuXPfhD35W{(f=K_n%$9a+Q9qrb^~Y$d6b%M5D}-TyP|=nlEGkf4hi8 zw_OzWHcND?i~cEvD}f4-g#-|KiJ%ZBYQaCwY^eDnsMo5&6t{1!8e;M^K!p+An#wa@ zgz2K*fLp?aGa?jzRG%HYcYN}?YuRyH@!UDf#q>+y?%b3A0hr(rItTHeH<)izxD6CM zU2Oh|-gd^%A5HJoE8|AWIivi0ZbO;iLF!WT`m3p=A7eqX@H=1V@r|~g;qrFfFn-RG z#@W26Y0Ze<&C>XBNBl3#O~gwG0R7yYokEv&pIf;dt}}LiS~4W+hp|woIEOgJ5g%JQ z!s77kTU>&SHQOSVrB9D`j+)7%Sxz-I`oGGCD{%&!J%PsWDNO{#Z2h=>xqosvQpMiC zma$f#=4+2-IUR~65C1+EK>m|ZT;FD|;s4+1qUs;`CjiDedE6{LBU>DI^D*oRsVKoD z)U8dr7$&Z+UN$T4qBq!RtkZYC&mX`z>H!TevIJH#UH0rcWPne!wuKS6Md(kM`S>vU zDM2X9=>S>`u&@z{Vk3CDs`@ADKTD=3m z-T3!#xAuA(Z9DInUwUktR{!94-KGJ<{(sH_hrPnI^L+`d{kkmR znKWjD$O?e{b~BSFIkM?dKgQdWa#TpOwP5KMhnICgvb~Ga%eii6(yBLNaJZbF_arYW z58RZj-8@egnR07qwzJ8fQL8)FaMi@O<*Ru}MS?Oy5iJFV6668}PcnXXfjC^_Dd6Ku5|q z+@UmXLkpq&FZIkpg!?n72UI-UEwG~=l8AJ(EGv*Oxs@DA7 zUn@@=6>@~yyVYa%4*S>Cwh4qXA_&j}tan%v3WGNrIYi3eROwrLhf}NCIaqR5Nam+WW@g+qrVp z-Losl*UvKj*!C@taL@TW`){Si$>U(q6IT#iRB3uFUAwBKbilrgD|XUr%aiX<@!M5$ zu&e}S>^(%=+h`Qn*d@-MQM`_b87=;52#UD*!d(GOed`xjfy$Ni{R0u zOFb<7jCH>O1p&;I0|eajGk-HFh*_>1`iBa>1i~iRSy@Gz7HP5-au1{#M@@W82w?RI zoTPe+lY1^7aZ#J?0C#ht%B5|z3oX9&YpS7wBo7gYN>YL;rY5j0eK+AeRga)dfL5DR ziLb#ypQk$!&hk^g`n3Cx-mS`~8dOf1~+ND=?#rVJy|9 zsSj4rB+d+*)(%Np(0iF-3Y}7hNW~;T2z!vFu_$ptG+6Tf00%Ata(HrupXI!G(vZK* z4Gx>YEFuxOSAB4D9=D1;U|A~=Q^UZf=Y?ukLEfM|(w5=-lO45E#$WamWCN06mS4H< z)S`xNcCT&E=lNwD7>2*UP843OC18kW@!qA_lZ&geoZ@UNNRkGo{HP*BSNYb|FBU=N zK$le8vi3*0wq>SPXhas4`0p!zY@G^X>0*_d5`hdbkVLR35H?B;&}p4o5LLAxmTwjS zQFl4~uP!19J3J^w(!!nBvBYpyM14yO!TyFt#nNX&j4(t;;95s0=Uoy7vhK^<>}r3# zf1eB*6LNA*H*pSM&DMj+yaF7S5g!w$c6_i{PVbSEP;!mpa3!T3CL_iy!qamRL5 z!nO3Ra-Vl~^Y`SYs-oG3GtqRY_8O+(o$K>HwI&Oz%G$>2E!Z6Dfjb`8-x_I1JMvB^ zn@L*l-}Hr|sZVn^DIex9GjQ+i5Xh`L9@va)Ojq6r4G|97iamdU^4vj#!R1=p*q!85 zkyuyzeh}%x#j0Owd{R~Iq5HWHtWm@S%Pvf%XR3)wI21Iu&*MlfcYkPBF85t+giMiH z&(Cym#76^I(w(B&GAVF4_9KSDo%B?QuQzf(_S}g<@?OzFMRz@nv`7MjVnb4HLss8z2cPggt#aKC7OTRc8~7$G1C8iCnc{9Ns9f z5|NHkTSZ-44=09V&s^(921)2r9OJ zl@U>|bE7Ld((m$xB6$qN2qv*N_e3fiAq=H38~5G%uLY`z$*{T-QQ<`=;0Y*F6za4p zH#`M{=%;PCkZ@vqKjM$#faGBsMekAMd-tyh$Uhs;`%driWP5p1ZQQ-~5~VhvABY|7 zV_<|qB+N=Ix&_=-{+MRywWXw*CQj^Fa%F8fX`6ge*kZzyz4U&1{Xx3_LbrCF1n`2< zqt-H3&kYK?9=q`mJL#p7@*QudX4&UzRI4)LeYx98=GiMqCL|<`6k24#fK#JJh`we% zO$-og!%X_B4o+iEkRq{@z!Jwgain`{M1h~bwsIXpB8Ixhr)&AdRXS_Epgh& zypZKnJP)d$c-sI3M6b<_RfTLFzIxqA&GjX|?#$z1LpY+UWKM(mxk~)CZ(DqkrOP-5 ztNWJ%^Q%c5hNG%Ts1zs+s{<;|m7Tj{lOSJ!Yzh>`Cg$>Ar0|x07a_Q>=fmqQe1mpz zQBe1VD3->jNs*p@##%k8RUv;ia=D8taNj6aZs2EaGelG!;3rnr(hv3R6JQ&a2*v}~ zowT8%j{T;EYC}`3-Z3e%x0JxaTUZhJFDwQ<4VfQboqNa}opBNHJIC0SM?yy^P_RXI z6DN~zq0wcQAtLqIomVb!#yqLD`x9cHJ^K%x*O;_>mvs*$cn~a8L&USpa%AS04@+BU zZLgYbEW$Gnkc5J$WlTkV!tA&2rE~r_Nl6_&B zc)44K!5SL{IK9c+h+v_RxG5hje%Ay&}b$MwJu0n$JutS(<}4Il>fWIf=@TO|2yd2lAavu`r2&cRzRW?BarI~=`f`)7+mR1^?O zlza&89kLX~F!Ed86o#^h6m8MZfoqqJVWSao!5$~s5l~5b;bud$T;vf~&2`D2p!FX< zw92^=PQ5oQSB$N>6gh5q`ndtM7lM!H$Wi2zFjYDErlCTUu%;?=w+Tks3)ksTbYo%( zM-sHQgJdSK5qI%dyOvN2WS*DD3;zuaBG zh2^pTuObNwrvB6GdK2hSnc-hDLl2uz)?Cmq=-9dLl%rK8Mj5gKi1qt~nAL|A3)0z4 z`Fu;5)pY`mMI-4p{@azCMrB-gvWigiCoO%cW(8(9+VlGvykcc=qK0wm{RXat-}~`? zUu3J)p1#P-2fbSA!6f39pq+UW$#{wHCV4EvDt?{IvZ>;A9njdaA+1LFV&g;wx{OR- z2yQ44O|j(jPJLEOw_>`^)@?~SyW4tM@^Mz0^Q(IM_%&L zAy8pOi~2S^u{(5uLCI9p+6<1y&BU2B&42Gy_AaB^rj0cVdne6z-eNkyq-yT3&UJvDlRJ2Z)`ruZlRz`Rp~1V|b^J`q)hQ zfx_-tMVdF3i;@z8)o7bn0^pYBG)=~(HGK}25ngp7DyqQ9SqINg7@xLi8a9JTWo_U+4FXA}xWKU?cE^7aeE|T#yWTTd@3Aw1nkum*$h~ixMq8{QI3qio zI%|CT0N9FXr5eX3kz{>-h44FG?0vYbIKL1?eZza?a6TqY_Oc`3d!nfPZiJ{*DND%F z^{_dcRFo+0eN23evOOmu!-vz304ZeY5+dkMveZ7%|CXdyj`i|@Y3uTop_&kf{<`0N zJuw_5P9RPx;v2(#;-??AoPky+H2Z&)%8wM{-6`p!30hDx8{VSZ^WZ2e zd-plU&`Q=yn@GZi<36Vso$yi_t5(a!dC1zITu~LUPo@m#b-sD zu9Nq<(2mwxaHTpd3+|~U6+k_(H8EZTbl%tZ1qW4BJQx3NamqF55t!E<)NcIA+c+m4 zt4;!7TP4O!1!^k+^bFw39TowuhD>6&y~9iw&m)?0fkAfra>HItN}c2okAb9N2%iyd}{%RU%Khr!Aq86K3iTY;DENe28p0UjV&; z01;e_?|AFQ?@;kSDKd)j40`j3IWRB?LP)&tVf4QZ#5@Z>@fR8-bAMD_(8m>b%xiKp zaRfTN;li&>)M-!Og0-VG*VZ$95#zOGwYNVrUo;571L+|NCN?k#jFVR{c`~~A8);o| z?w*S+S{_IpTieQgc;^C$(`Jl>7(xaQjleDdMnOeUNT_zesZmX2c(Ni%NJRE;@(?}D z5Xh+CyJ1xM7!0g+2nflx*T&E#*nrhetfgkzh)SKb3fxiGJYkS(19J>Nb-6EyLKs&6 zp~goAxUOZ!#Ke62innKjCm(sG+zad`?9%Mq--u()HUBm@u}Ifw8sC*dnYc<&k4&}aoC%sQ%(}k zyuh5a9;0S>bG6qtIRnO`Y>>1!8ZTl$^(B{|opX3BpQUQ>;9LYx+6|!+Jk3_UAJ5>H>A~t%Qd$Hv+fRmO22xJd(u(LP_4Fa zGaWCw2K;w$uxRRSJOTA7ar5<2HCVy$A5GcBCv)S6qVE<17f)8lg?#RtN}2AK+Kt^w z@D@%k{=z$BM7jEBF%?n-bO zSG*wyzVJQDVW3Z^hYctjt5Y*0AK3dURXg%HCRQMmHB_WoXC=|Q!auOG&;hP}hdoT$ zLs3w_t;Rnn%8m-IrS{N365tL44IWZP$UN%CiYDM92YKvIu_yA{J{qBz5JCvg5|I)Z zE)wLhD&}9+#ysW|8*Wp4AAt;JUv5tFuHFD{qJe4bxW(cG`TQ4d!KGx8bDsj@DshV$ z6lTBoel>L`e|Y}e%XI##=j3XCJd)Y(_R!@UH%iLO$!``~6w<)7IkU!F?j(d!rbP0|S|v$xM2t)t!08IdECnp; zWfHbEMEDNMQXMN4reMnkJ|MmpSk1q=bm5gJ2t$5@i{{x{B<|^fym}*TLDZs~T4f2e zJVhPMN!7}=BozK-BOEvPbnyy%N>-iOcLgi2rRT^0D;duM>SF;Gc{TDv2s;yztRQ+m zkUA}*iq4TF90=3kexDb>LeHBM8CrJ0b2wKM98SK{KOmn4%y?+G#Xw5D`;sR<`AdHM zFD-+uP4Z_U-P<40n zZ*IQVh5MLj6Y{tYf7&~*#WkN`K0XGZDaFK0sa|u47pV~qxOv6IqT@7kC1sjaz<;;D=+D6Q@p8I~s4#SQq4A}& z7ojYdAo0-dy1lQiGbWMSm!!8<^2OTbSB}*t7AB++L4msX$!ZEZbQAs{zwl7WDyl-_ zw@qBJa&82x?&QfN&vn+PQ+1?CZxM#scn1jv#V*wW3YiAlAN#b*j!lDh_ zNOE2VPtIh`$tOk?<{*VD+aJ2FERUbA2hV~cgdQHs=j+Wv-dm46_BPoAJ-3}PMoi@UjX$ z&Vet*cD_k<{(+PS$oHTiR=L9DpWjvIxaUorMyOOEPL>&UTzrtqCq-`Jf5E%V;1x89Y2E#T&XS^`%_l3bkZ#u@`5(w4Ayy_V zVeoaguLY>qC{KdO*hv-rmkg9{r#L+zFk#QDnng;v!bBq3gkfrgPW%>yocX(V0PDHF z-ph%lh$PbycbT&a=HC(R$&dG!7CPflUi8O_R&@`CiS>!1Foq2@vhda%6)*lWT07W` zkRgfysRi?q+no23a_W0(MCQ|xgshPCplz*P=Jf<1*t%IoBn81vYU>HYw>hj;88ygE zEuOxlUv)$b(Dyf(i|i(lEkKIuQ6^YfqpXp#?)xtc?VA<>%4s3B_gJ89-hYiE2@C`U zeoTq7C=;ExayW0nS6XP#V0lCBdCP9;i9K2OKwlfO^Kj|S6_#k?mn$KW)mq%N&k*D76(G&V9DMS>#D-UDS2eWDW1_dy93 z^i9hTPRh7v@dghJ=yXajhs|!%M_Dw;)tiK^uVaH0m-v~XL()khCvAuAXVtrM%OSX5 zz%c4DAuk-9tUp2B!9&ITHL>09QnVK)PORZeQXde5t_O?1bS6aPSqM)g?_S!lNoR|p zxh6@+s&I`z?=iqGT>pG=WshRK_!Iy9*8dzjx_ha+^78VWG2wrDBsczduHEm)fxUOc zfq#9nV&~2K_7~XdS`)MX7xNq^j`+hIz=?E2DtOVgBKjp~6RAmPDArxD=g}xSS#fTF z?)g0Hu;p5@)?!aWW-JtqhCr=GtTP zljaoWnm0Fm$dpDwP=?a<*UiHMm<$Ihn%>NqU!%w-U8OpIBX1CEJ%k zTYg=Va(3^5aK!;nwvKN&o?MZNJq&K2oW=7xA#oOWe(Lj_S@z*6o=0rq`l<*nHop3 z&T(`etXi}B2s_)2t0!sfOuX?oOLA8Da~@SEYjTdL>WtU4qQ3dT9RFjaGqPJsj{5WA z1b<$H11J+_3BXjZ+u%hSp12~cyBuZ~YGkG+Fi(#CWblRc$4bH2Nq6b@ms{vG=Ipv6%zj5&qFMhARM6tA*6BS5ob6JZnnT6_dhQkVJmgH|MmTf z<nbj8P2_XdrV66;z|&0_0VkO&p6zur<8$_asM{qyz{7pq~Tb?n>B1 z(1Y9()TwU_xL8QkWYQlyd`>Ess^jl;?)8@fu5F1$bQN}wk|$kTvlaL~QQzD*#uiz* z=l~=S7$o|`F50B3TP0tF))pjAWw?ulAm($psSSjTW}!_Stc44fevgA)NEP8|rOK-) z0x@S%VBmXaw@Q~SJ!Q!~RDd?dtbzQ-C|k-nGNh_js}d&^tBRaWs3WK1NNLsuyDVz6 z_0onISntSN7v2HF6WsOVmh+{TV_amJCI%y=W?3-Q2T@!d z`7Hq{S?;{8D&rP%dxBB~&{Fn|rNJ|oC_#+Mgd%t=K_wGHwe|`T!wrm{bjTdfbuDZm#|M+WMdfv&r`ITq#(J%fR!=(}*e8+2u zqL2sfzlVG7yN3t&?51N`yy3MMam>-DQp^ow3<6>kiRZ~?SP((W5+x_F#38=?F9+Cv zu*>T%EOF7x%1q8X1VVzNiY>zWgU`<~Jq}h<#lw&w^pRziW@8RLk-{>Uu)0gAnnA7d zD2NiC=diS}m*SdJsm<;}&rOiZuEI1c6jz^&P@SKSH0^PcX`dlPNdebEz4G4(PdJre z(~dnVEyK^$mYjUHJwa$_{mqdMTID}hDgbA^Zh3O zas48z#tdF@!5T)&NrrSAp*soY-1Bo%zhH=>aKNFKX*FgMM46u1q+Z#Jq!^g(3f0O! zR&Bn3c4HR3xPjuDQ}G?2%MaT93(V9SNQLR$MjglX38RR{QXN&(snu(kriCbov^y<^iX|$GH4>VN?*{|APaJ&Yc`k~g zqH7wGEOYwl+qw7NdkKPofB(0C<>lv|&xb$s5kC95&yv<8e(RmT$JF#8N`(@wc8lTi z2!Zb-$r6P^k#4t5u~5QwoH(ei+eH$@I2=xZq+zTiy+5|lc{Yn4$8jJGiHHU6LL}ga zAyE*aCA7mVaeKWUGt*P--m{P0dv?=lcW@ksY&Ju_P+;SRjjSFY$4F-w9UDcK6(m_& zIo@y(=x6u)NTM`wrV@}P5#Nu48C6X~dmN1jF!;S6C)GcbLh!Nls3?lHC4IY(swh}? z4@nRS!T>)An4C;7HrhoH0({S<+v$=?r)YLMXo`XYbRCQVzg1bmOVg?Vy?0<~HlO^xr{n6@PnMGyo&q9|b`bz1EXV`F33mPIC;jdMf-kFnt* zJ;x_s$dOKG@jZufxr}A?DCDysNDu{-N=2+r7bBA%ANS8=w%XqFuCO1YDhD0m$*q`0!eY@Kun~n?h#a4%@xf-tR zv0=>!x8Adx%U^K@K^XGQtMB0J-}w=5e$^S=`M`b}ZIi$M#P4wTg9kYI=ymL#oa67V zyqov``X#I#&9K<$@VT#kkBEqO|9=jEckP4co6vTV#&ha3<3dFC(GBboZ<3c8s+-i8zgm^H(#8E)}zna*zF}eKEg1FouXug zMr|5^p4FgInIxfQXtx(=E*)ZY(|Oq4MU2u0a^oiv_yL)rbtJN@@m-6Ak$-{D8FxPr4XM1-~QRcQnkYE zJ04`$u7{BniHk2fpJR^Rx^hg*_J}>ZPovRfW@etP+m2>*bc|Z1N-CM6)~XZrEl_kS z)dgfliL)-;K7J4(D>4i7^8{hUTP}YKpZw$>lg{S&gZI9d+1VMczWQp8-g*p=?0$sV z`8g7a1pU5EGHIZx3UmJdc!-L{k%}2@OS-NT<>yR2flCkkfN` zxTLZfR7F9OWDGrp7sNKa{eB-ksjt|_Dyq8j(s|03sE_lDolctvAAFEqyLK@(br1l< zFxa?Z1M4?zV5~e$CY?i4RU$$ZSw&ACIX9!(Y!U=dYzUIi=MSTqg<*(o^>BSJ)3i5lH&hU zRfXOlyi%4G+N~zJOqRCUC6`WNXbO%SBB~@QI$01?pasG+Gpg9<%k`IC= z-M)ivBw4K0(FYS4#|uy-frUzyR6?QF?BY3n!VnghVqH_cR*Us`qCl-yC!I>uYPVOy z3?(Vnjpzv-&vTF!l}tK?Y4#W&DbsgdvY8a=bc(*?F*ZJd>$&8!X-e5FmeXf^e2iYN zkE$x@dIHaNQPjhmMBnx3bxcZQt5EeLPdXb*bvo@OO2xvHU!=#ocA<|T#!i5Cw~CU? z(yi>qcPt_V8V7GhQj<8H3X2EtW^CPQ)DP_-S6WRvH->91F+6${ijn|9pg6pKCD2b4 zr8p1ZXH<{pdOoW1WA?<%!V>rIp61LGH?ntfo-Lauxb}xTx$4II&{Tzs&pL+FPuPqs z2~5t_r|yIqWw!oF#r^=s0UvNFY70@w3NQHAE- zpF3^pbJR@45SuNOYrg{_22OGNiF<(ju)2oW3o#VT>dL!Jb3ty?E_lkF-kY`#!C99M*RvG&&ZR z<1?H~p()Fp-=D1h zuvn|1>pInHl_-kn_gxm|XDJkm>_0FGQG}u@^m;aWB0;CyMH|pv9$VD)ojyrjN0wxQ zC?uUq<9iO7Y@R3#NT*W>l8mmZWU^TzAeT;~Y6&Dop_I*G_H9bVAwnTO7ei0t`W`7G z6^n`!+6n~?pjxeP@4ff3ckezbl?uf|fh}7$vu5o&jymcnR7L%XWbvmmA@F@4*Kr24 zvnb96LBR8UBqRh`AajJk)i4NYciKX)gIRdc-eCJnNC6A$L?!x-$6}ic>O-2ZxSd;Of&vI_3S=9%OsODsJB}r z6R|~d$Lz$mw`LE+&`HQDQRt9Jr3Vd1gsLh8K`f$Q*+20uysW3__2LPP=eyW;tZQ0W zSj0#eG};Y%wu>rBRBBaJMWNB^U|KyCS*E%eXN$C2O*}6^Q5DRti87#K#rIA?K9{4_ z?l3wsvO-~7JyymIB8vGu`D_L!@R=ANr)N7fT5Yy(KOM`m$Y!(nzK1L;D`!xxF5-DE zx%86o3|)r`P8#uRNXAqs7Cvw^&;woz9^jfoA!lmFpM zc-rutF6Pn{{ce@c?7d7s_@9(V*0b%j%So;|m-{D0_8sVuko(;AK$qXVY?O853FM#y z_5y-u#WCzJLYQWkxoU+@w@WdXW7Xhgkx8fd{NMZ~=bwEp$86hnm>}z0*WJxMyC(VA z@4o?6k@16&J0F@vl>|;Z_VGgnUvQr5pyTm9hd9qbWU;c3Fp{v%8uiLPlDP@m&3UX| zm(lfSVfQUkrF9fHzKpQjAX(agqUQ($7g_z;3F(tu7y0Jz6Dca*1(!Ujz4X+w;?xt+7l+>UyL70Krm5p)_h^`$v(xb=1_l`5y4auR2sc{&MQrX#~d9W#tJp-$0AVA^$;bI{rmQ@SgW9_3Z-HWP1C3?E|D=ZRO(ftFv4^Fm}jr) z)R*c+#FUSEy-qr9FuzbmPwIG{7hCqqGR`26!Sj7&NyPPhvf0caSvrF>5KS9~f$w?b z@_C{tB9qCYs49vqBMJi3)6*>07HPFRBoYbEefc>Il}c>cwk=M4mt_)~j_bMT|4sb+ zbg^7yKcSme1fJ^>1Tp=HNFWkILN7#+1U%mx2+ohttVhu8wsG9Yw;B}%fov{!MB%;b zy4XE?U_C73d4BBXB*cqAiuUArAxF}AJQ0>n4Sdfd^g~2h!s?l5s!rEzwRrgHKbWhJdL((Kga!5uCEkz`y zIDjBW5o0^Bjck|r6d(b7hymNlA&104axvr}aFFO-TtdVBBt-uGWnNC`2mB0{7{G8l$V5)1TP zR^0ZRqz_mE_i12hnq|;P5}qGm8adjnHku+6CIYA1#kOrOU0FqzReHS+?N$q2Ram-w z6_5$m1-W_CpjL07DA`m<*R}Obn<64f&~rH^#>eqIkEzLV@>T&!mYAEJq1kL8%L)_K zGEo#$tyXZo03)XjT(&k^Qo zDrMB4SJyGCim%P`=GzWuS3(~D;m|>L{KIZ=XO^ z$BAa=_@%&iV-W>iQc~K>C+S{0OOjvUiaWzok5zd4CyV@aDZ$L?6il5*cbSyZ3z;SC zeTtsb? z;xym<`X2xgCxS12`CI(OAAg3uJ2v0)^^U!Fj$NClF>k}M{$M=}}+uzlMn*#G!rY~D1tk+=K-^jaQ?|qCP9y!dHzVwH9uFKc|?9bW0 zeLJ>obLiPa96WgNw%1MKh*R&rOW5l$Ge3i6S+{J6`-NVTB$HiJjI(~N)}UY)xmH^x5fX6}(rmWK83v7dJ)>s&0kv9c6G+il|b=H?~Rx?BA4@bCvF0@q(RBJhLE6oSlkEKO2mO-4aRQb5)8dpZ=k(aa!C z1d68Oxh|TPxl|=lf~qNWx*ar0#SJ`K?G|IB6|Obv*p`VdK@dk23PXf(jG{5BE$iW0^uqnM_FNCb1U({$Qx z@`Yk1ju%<($A%t2r73X|p{hDg<07hV<2$Q3wM7)&rg7;AZq&n6bF9AiG83~85_)Th zs7G~bH({_wVW`UJ*k*jM%kaoFsYo)XHO=^c={R`L(DF$3G%p=ZK^1JDvv~Drhw`Yw zp(o0u?Vo{H|G4jRL$Kk^1V|{digM~C^3m6cKmR)<#o-TZ8Xph(DYe;VAg^zl5;Bnf zLeQ}!Nd`&d$jN2a8g=%}Uc)qt_}&`zj>=NK%z<4#s&j#%yg?j!=(+rTyKp2)l5xaM zlQWC&bK=w~UVQ0$$g)JaT;>a(`E5S=&?AGBm_PZ;f99EkyZMbLAIjW)9G~C+%HQ)h zfBL&vmVvA&wA)=K$4ZP2XQ%gx5Paot|CO))(PtSiZD6?I24LXz?R5ql#OlgvNK;&= z#mdq<42>@kxec7ar@G|{;z&>^&oDB#pU7*FFU_Iq`Ak5#0U>>=tf8L$FGSuZnwloP z2jhm*XU_7YH;!=re5OAs77Kjp$%8!f;NC1@d4rIOl%KtInwcH5Si>eO%PYM2@++)d zS!Lh8eLVg2rx`8{-`%y+l*6yS%0GSQJACbHUuDWg4wErmnMEZ=h*9f#=fcIhdwFz0p{=>h-cfIwWLCB2Hp*Ib-mf zDcCkW*JWb7N)$&F3q$L93Nq#LD4y?At&WpZ6;erJdUA@jwKnDIIIn?NlEl*lDV0d2G@}*CDz;^z=KeR8 zrPJvQn(CWDRTS)keFLrMhVL&CL}5fClJ%lGMUoXXO}nQ_Q2(>)PqBQ@1tB4865UP* z6_uXv;JPlhWz%RjFmpPZB){76n>KHyUaOG^LA_o_2tmOraPiUw+U+imvqs=~sG7#brAq@UV5if?FbrJB zK~@yvIHq9RIIc@|tU{WCuBnVw%YTR_U})C4`pWvEmluW1BHLa|sF{9is? zTwNyH5~IU9iwsMVB+?{CIsZPAtU|AY*uE3VbF$}@ zMi5~DLnYEQA&n!DRqm%oLzY#7DB;CdR@t+2h`@Rr(~20KC{Q6_Q)d;YS*NjlhI7ZB zXVbO=IJk}g00WjuL_t&oD=PdRkqDfpzA7!kNlM9o_~oie)>@kAAOHaGh_VK zm%l)x zdY|L3eUs6deYkF$D2^H5@+5JRV2#c(GW!UT(qENTE*H-)5``YWvS;BV2_)+~?DPvGUDwcoAP8ApJkO7hpP>PP1O8R2pXa$|@q2A&qG^Tc}!&X1zv=jPHA_ zwcF&(JkjzpNgU(49<^GXyqRAY{p$GZ)T|^)FpM0&A5bXRSvG^BV%avX>oPGhj^j9# z%M~P-2g)j;z6pI9YfSET3Dd&os6}5Mw zx+#i+ZQCGSryq$#4BV(vk>0YfH+2I^fItkWXNkx}^0J&60*EBNX$9ap9)9Q#3{&Jj z^+=LX6%{#^F)ibkE=c{tz8~r*%UJ?>U+0pytif{)BNIQD($T^DoSK;?3`3+;LQ*80 zZjVZJf_A4(9L1RVJXh-tG+8E2B?7;m=_T4t@>U*M%JeD2MT^7_Ni~hUkt0qLbUm9s zbh<86ld}MfmdiAoEyl;k(RGtTA#3CMPG+be){8 zQW>ifhXG@iGK!i562>ZJ9M_{@XCZKDn%>3#`TCxeGqZyXyL_F(Tbj)Bt5T7$LssxQ zSJ;v(5O-JUHI^9B4eFQQrsXtI6^(bk_jgn#cag>pZflw9%pQ`+r%)Vacyx|1a43~$ z25YyTv+j$%@k4fb1_CH+W{AHiYsDW+epnd Date: Tue, 30 Sep 2025 23:10:55 +0200 Subject: [PATCH 663/665] resukt --- README.md | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index b45487c..cff2317 100644 --- a/README.md +++ b/README.md @@ -236,11 +236,17 @@ To extract images from a `.vrs` file, it is required to install the [VRS Command To run an example visual-inertial optimization on the demo data downloaded following [download demo data](#download-demo-data) (Here the intitial estimation file in the demo is from a run of [OpenVINS](https://docs.openvins.com/)): ```bash python -m example_vi_optimization --output demo_outputs/vi_optim \ - --vrs demo/R_11_5cp/raw_data/R_11_5cp.vrs \ - --estimate demo/estimate/R_11_5cp.txt + --vrs demo/sequence_1_19/raw_data/sequence_1_19.vrs \ + --estimate demo/estimate/sequence_1_19.txt ``` -TODO: Add two plots and caption. - +

    +
    + + Red : Optimized trajectory, + Blue : Initial trajectory, + Green : Control points + +

    ## BibTeX citation ```bibtex From ae3a5be0de276ff9e5ce2b31e0dd3dd824bc720e Mon Sep 17 00:00:00 2001 From: Anusha Krishnan Date: Tue, 30 Sep 2025 23:11:48 +0200 Subject: [PATCH 664/665] red --- README.md | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/README.md b/README.md index cff2317..36475b6 100644 --- a/README.md +++ b/README.md @@ -241,11 +241,7 @@ python -m example_vi_optimization --output demo_outputs/vi_optim \ ```


    - - Red : Optimized trajectory, - Blue : Initial trajectory, - Green : Control points - + Red: Optimized trajectory, Blue: Initial trajectory, Green: Control points

    ## BibTeX citation From f7746b7b7c6f48a6df02e6bce097267a6fbfe842 Mon Sep 17 00:00:00 2001 From: Shaohui Liu Date: Wed, 1 Oct 2025 00:29:52 +0200 Subject: [PATCH 665/665] fix vi demo script and remove figure. --- README.md | 8 ++------ assets/optimized_result.png | Bin 362054 -> 0 bytes 2 files changed, 2 insertions(+), 6 deletions(-) delete mode 100644 assets/optimized_result.png diff --git a/README.md b/README.md index 36475b6..478209a 100644 --- a/README.md +++ b/README.md @@ -236,13 +236,9 @@ To extract images from a `.vrs` file, it is required to install the [VRS Command To run an example visual-inertial optimization on the demo data downloaded following [download demo data](#download-demo-data) (Here the intitial estimation file in the demo is from a run of [OpenVINS](https://docs.openvins.com/)): ```bash python -m example_vi_optimization --output demo_outputs/vi_optim \ - --vrs demo/sequence_1_19/raw_data/sequence_1_19.vrs \ - --estimate demo/estimate/sequence_1_19.txt + --vrs demo/sequence_1_18/raw_data/sequence_1_18.vrs \ + --estimate demo/estimate/sequence_1_18.txt ``` -

    -
    - Red: Optimized trajectory, Blue: Initial trajectory, Green: Control points -

    ## BibTeX citation ```bibtex diff --git a/assets/optimized_result.png b/assets/optimized_result.png deleted file mode 100644 index cb7f42c8a75d4f2f605a08b4cebbad7caa6a438a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 362054 zcmV+8Kpek`P)M00P+v1^@s6%wBvp00004b3#c}2nYxW zdZgXgFbngSdJ^%m!CUiwubVG7w zVRUJ4ZXi@?ZDjydb!8w^WpE%fFd#BBIxsgnF*qPHFfujxfssf603ZNKL_t(|ob0{X zlU!GR=l411u6c7`YG1H}AP9f}Ni@l3HS#P_*rsXjxKg)aq5;TtuQ9AV6#cu@z9Ly(;&-%Q?pnSy&3FLKT1nP$28` zQdOBZ?>(87_nh)^;c4|M>I&hqu1^6<*l4=howY`L{p9^IYD3 z<5dKL>A5+^hKC+{j8aO3?cfTDlg=QN!aIEucltV={V$?38K^E1XLH1^M-+9?T0ivl z?uXV2r4-Hj5}xOhEd=CpS@Qh_9M@TK?96lnV{!}(4z78=*_mmST4Hc0`&h=?3yk@k zR$~OMGCez|5CSPJtkb6uAH9cp`&%UA+t6C|>>4*|)@#g9-=JBq;rjuep8_EeLaaMR zKa=O@@Bbsme|?;>u@R2Ec#vJ&$2ocWJd2Bqy!OfwqE4&lV}4vDNlX-W=o=cLRjX26 zn8WdW9M4Be3n>Jw^SL|-S}CHiP2b2EnOweS=Y1BbF3hqpJ%#J1ky5UDOdQ9YI(?Q; z&tG7CWC+jmsTA`}Oy1!9#jE@`|MH)#dHy7hXx8W1`{Ju>p8sj0wPAj;Mz)y3PrCp} zXlC>@$k_ z0C$!1-ig!(=NCUgz4RI?o57gd>xU2tsq`5v`#E6c=X&YPC7SgF*GoO{=kZ0tvTf4Y z0+9xZz$6iND&QBte2*6o9^i*R`Z0g}hrdU4cIs&lbyHxBA&Db8ttN5U!FC+{AcO6C zoATcMBBQm&`jdbCU;i(UauUb&sJA+VQHW>TBymh%e;;w8c>jYB*|B3MgMFoEYP0a5 z7^6uqE|5C*0m;Z1;R9?WKKk`1NGZ88ah=OouaV89@jREG{Ne)+KEIdY!2vAGBAL=uw`3 zZa4W%icT1D`RX-NsT2d166zUpG^iv&2pAY0CsQa=85%(dL9@C<9JWD#kP=wm*xJzb zRD#k81Eb@QKKN&xg{f(@(m1ZW<}oKupJQ@*mT!FZD~t>eQERkVsyA>Qm+yS@tySll zn+PFLO5^z{T;G2jZ{d*$TQRc}a|F2*uHW6<8)J|`7J1@h$Q9A$3U@oRga8yIT9LV9 zE$MVRgkgB=Z(|HnNZdO<-zbV`x0|F=_xn5q(s7~E51tFQv%;7FfwWpk%SQwo< zF5$SF@AH0=_?aBnr{{^|h;pew6tzkDKDOuc*MIW^jvjr5z>%or*_kUJ2S#hcc9T|p ziLlecvK=z{5~*|+%XWG)=Wg*}2qC!lu6{s*Y@VO|?cedv+izmIE+mSNe)S1sVI*30R}q^v9j3>-|)vzo#CZJ``Nv78VuR0jKSJPXUZzo!epaV>1y&}udb(&<%?aUBQSPtjqmr8`b} zh)O@i5ki|)=K<+J6h|0iZheN9v=BnvavljGkk-oYYBranR-0dEWCpZGOkPLM+`xS8 zox7eF7_EVO*F`_@upNOh8X>-%9%UgVaiXc!suc4%q-FE*@smhl6J*l7`;B+lK0e0$ z)U~HQ)Tf5lns%c~r`<#diRY(DWwKjQh)u#H852SXl<98fEX(Heip;fQaY1TJ<>2Cj-5C~CY`3g@@y=iS|xM}MdUlbi7u3I6Gc0zt^2x*mnX<& zGK>rjGB!NK-km!@z`y&y{%;N+c%E{xu%YYUOn0#@8&@TWYz`qHef+05QspgrwEF%X8E_R1y&0+^#w!Q21sYq_-P;8ez32cWeHqY(rUNYG$y2F zVcS0KcH=1;6B=ltbrqwVXyub6B~+5enDvdON4>WE)juMX!W?}AtS94{$>a)Tas^b9 zFgJaJ`RN<@o{#INke0n7T4A)t(EYw8aYQMfCYQ@%q7dElDA?meD}_=Cx#H?`lOLoR z-o6X7&9FE-&Em`y#(?Ab*p7n`@_{^OS}Bq^qS)8ptGDpXA}vX~UB~r;HIMoD_(@)P zZa1edT;lwNi^TEm&Fl8DQ7&A%!qw}OT)jStZQHzZ_yAu$`qGO3iS2rHT1yyH*mPb_ zA;58Lv;rY-2Lq+$z{{^ekVZHTBr$hKC(=Q{+{6@mMBj?e*p7|od2~7*gb+B6gMU{< z#T7&@`YbcE^SpTI0MpYm965ZLR(y z7Z#rxV*((FW0G=r!I#D$q+IsItj)(KPBJvu$54MC0IutB_1YxqREm`E(P*~Fq*qxu z@9-+wmW}PFaM~@>$3DQSF3~#j72@&jG`{*aa%PH7zCaR3s3ch)Q|~u##u&m*6BWn! zfkUAZP#PE}l}>e2VIE;o&gC5D=a(oJi)*GR>E~BuNUb zvZ!SE2^bK!aU2hEV-jIo2;YbJ$$I)N+h$;7jDe9c>Pw3(&P>s6)VuS8>vhw9?(#T> ztycGY{0tcq#u$`RWb(yz7cwCPrT#%m{e!d{4Hjl@(5Nor`6+DI+i7{ z>$=2BqYbP(vyN^iga0}GZ?dkz;O2fi`NbFb^~q29yPy06 zzyDjm!M3rHM;T_%2*Zelr7A-MefK=4k_e*`(x3c_s9d2_tf2JTo4RJJ&B9`pgZrOb z;jRDp#3_ab`}y_B(_FhT&GxYo4(#iu$Os{kmWAVbSdN3Uuz)vtkz`;9q(p`tI=l7| z=L>|LHc8Y$doH@!;BgobDv6itD`G4Q$^!-RrTlW(+Gf=i?I8#Phlz;=;y7N@mZOJr8H4z45hZiDvRXfMhF4bD)>GoUj(g}$MAGE>DfY&Y@tXJ zM=VTFu{b-8?RvPLkF>0np803UkN_~tQHet3-uwT4q%s*sGJ7yuvp6@y;_MVcNNm@` zvg|dZ6_`c7M z@llQ*KFF~Xr%00S!f87$j@GzQgt0YRS~yV$dvOk3DAFF=M*Hn=k%S>}5@DLrs@HuK zj4>G9-QYx>HbK^>Jdh=m&yvY!9$W6Bkb+_M2q|wxD_V^ji?h?T8&xdF!?sPOGc1 zqe*|s6`XG3*fw#efs-lU_c%j0ig70|zj%OSCr++-EVVq>-c1rm6f6BJY6~_KLU#At zE5{}?fahagI0WrBQd%f=dmP5t zXk%lU7KoK8tF~iP?k_VpRl^T9uPWc;Kx;)VA5hBYc>lfkn44eVr6UJ9a^xjurl)!P ztv6}c*H4>%mWjg-olc7+>L8>fohyFn3-X^e9@?1DTG6UkdG+Yay!F{q088?n zZ@r6aIS9wWsV z?L7YU3n2uVjLWr&1qKEOS6u{!5ClP*D^oWZ9yW+xdACd(V=i~=K#~!(8pdc3V>X94 zfK&#gg=p3>OY^A5P)Pr%wo;F4ZQkf!3CCIhh=*E!pTx{DWxg*VK z|8slzw}1BMD-Jz!X#c9Guq=l--n@|s=%y@Ty7Qcr-AJSs@81JI0a3MI5&YtTZNs5acTbrY5FZ@oYICJhCKltmv;@x-OrBSQXX;#-i$umf&)ui2OppzKeb;uU`u(wh=pGh7{ z8dgY2kS*Z2E=nb|8g(kA5-+{@BBxKEW@vbns9DE6z{X~BYKF@b*Esn6a}@Kr^!qLXU>04z0t&TUEcrrIH%5>Xa94%SESt-qp>^>Z{`LED z5=V+o`v6*{F~;R?o%E-Nz&dptvABR48OOZ%GHMg24q3KMCSRa3G=h|pW^IYE-R^oi zm*r(Q>jq9I2}u$&IJUi~V-!*nWU`b7hH!nKu-%~3YNB;a5=9Jc-?gPyvWyUdR=rLX zwy~WxgcgLLn9p$f+~-8g={$RP?I4O{E?-@#g!8-Ke)nEM2xExC7KKXxrj&-gNfIim z^WCWbO=Tx3C5&%}Vj1H)tIB(KbI}w0RBBCm-PH^YDJAps^P~g+zTZb71Tu<{zxXln zk(aqUcS_0-%WfmYy=%Obl2)Tl6eeGq8X?E?NoVpTS}jL>3<5)`Tw!Kz9x(Whe5Rzc z*Topxtp>Hlc~lbOdOn##nN&KrA~L(hv&BP2CW1_k`NbuwwJO<6np`%AWmzOf(LXpy zwOS(|_z%=u;^X5d85-z+s%cHlR-4o3KBK>KZwUC}v>-Jkg@+jbK?e^1^w<WwuX8pb%a^Lega%evv z9y>u8hP-n40RP{A`tgcmc5NTW_f|1TgrL)DlF9cvRkF7TX_%j!r#P4=o$JoULI}kC z9AvW)te%P|rNHQfD2};X+9Qc$I$=nXBuFVq2LYCS+fd2p^E8`H^0~F0ea0-OI^_zu z7cLO*Kd{2lrBnvE4BT4>X*)K#QkLr%r@u4}?1Xf=d~K5HscClY*iMl0v1~~;n_+%o zk)yA?Lc6-2EblXbF(|F*G?$$Lwo4|L$MI5I&XO+(54BRoQAEo3xH?he`t?bQ#R4hc zr&_I%4g#`ipX330ON3Fx)$5bI@#@R>)FM1djx85IzxUCvxN_|}uN*!|xmaLfu}T<4 z3=i~^NvGMpV|9sAfH(~4?AVQe>2us#osMPQ)x$w>=!Jb41HNTbay_>9_v6gX5Pb9= zsD#GXzKJo0PPsxOmnZ48(ONxG!(lZn%O+HYX07qWjR}BKCC!b=D&#@ zJmr$YaeCwBkk$Z}wLp?Q`Lw&W5r`X;n6Yh`Lq{NAcqTi{d#Myd+jcOtZ3j!UGc3$Z zp|yT!Db>e;)*7W0#qyJJbXc}Sd2slNT#Cr&lW1e8 zH&)i}z5L>VdtYZD3|o{3dXvibII&%u?FUA0sW}0ddJS>>Bh2^?D6cIN5M%n3!ugm~da%<$+cbrTL+Wsoui?ltD}HCmWqsZDRjNyiq*5vNKfjN#-6DB_6sHrX&N4L6 z&(!oRABM*n9von7oMd=#V@>3Y)lwu>tuiO16nV?MrYpvV%J4E9+Bsg)T_5co0}+g zMM|66Vx21VTe%Y_igpZ^fq zYGH=Q(BJu8%oCP`?KOqIehPidjo+rHs8<(pm!lPr()jIB(MsWXF3xJ6>@A)+mHuI7 zZd}E2yfrr@nIPbsUw<8?6z4y`gl$mK*G z=x+8cRID({V7nH$F0`5m$HC}i&Cka7JnGAmn>SNcl~T(E|6PnR#LH6RH)W86binlV zB&E{*(~ylZnCJFG6fKWoW&MUqTx@6c{ehqINM}>D8p)T!n25tR^Ea+j%BJ}CH{T(Q z6_>AEVc+vFkO@3m&uHPbO5$!7L$g5=$7J$Fa-|BJW&PZu_dHb11avpeao8d5v?&z} zjEsy>D&&a6HgULdIaq*yc>g2DMuzY`kB^R@#Pi&q$iaqT)NQ1*flcrE&o8mCROQhA zeeB(}gOR}j#z%)h2>$j*Kj($#_AoxWzPGUJwULNI5veu8?xreuK|uD}RdT=j5NQmm zZvc!Y=^v!sKS*p0Z7B(jCb`uQV)LMqgs9U(sfcEy&ghPNRZt!`LVzWq)iPwVtEV~% zA+Q~XMs0~q*6)$?Lm))Aj|66Oq@7rCj11D?`A{s93=Tb!x|t_|?YLx%CCURs7-Og} zE|5gwa=(i1=Hy95E40=maY(6u@S#9V+Kdi{X?uJ4{Z#zT5Yn~?5$!~Ap~(0uMlvsZ5uyz`#UeCq*1HldCvNE z6H`;jU;G%e^EvcghgxT|f~yUfqbV_EJ~k4io%v`PruO;psOQYzy)f+XsY z#P_C2Z)V~+q}{5~s#l3S9n$#{xniZ;Z)nSq_(Ic@ol)3s5wo~ zxon!(j~*e6dXxA4!LeUcEEIU*u0rY6xS8TK*k1v<-YbAlPM>3-ue{*~dfiFZU^@=M z#m~^%5V;OIoyDEFjB#C(e79?G==mh&3M!5xsHAp}9jXYzWDfx)3QRh@i4#r&MYXoKicH)v@Uv8*K$J=l};JqlJFV_p0VF+GI{ zQm7YSekN0#*5l5`Z>>h1g_$Xu)x}%26;C2sp;dy>ifp0ySg*6i#t}kLtPF6ic9wQi z;|G}yZ8~@F+{W&m_x9{CM$>B6C{+3>_Epw={mJ*fPb!n=}U4eE_1 z!vp>I9Q*O{lMM8gxpHliPfnksTD$i~7eZh;E}rX?@q7ZMu$0DHT*Ud{XApK!*&MYa zM_K&p+f;)zjp_nnt4^eKqZJ(hN6_qTD>p;hIb5;JmYDbUv#wA zbXpCT=B8-XtJrpmd})AuWdO(Xw+x9d84sQ2wAndv>I`v`&}_B&yPy67r8J|%tM@4Q zF%s&y!k~43tvh`2n8mkxCTV3uj4x z{60F9Ls$AR=?w8puTk?nI$?)ME21debSX?)E0QRr(`q1OLavmif3(8r&QS`L0$$3; zdaPZgH;$BoPAxa-Xf+x|plkhjwdHL`^wL)*6BH_A16@e`)5p5gN84=4?6n zkfLk+2!W_Ku#dfuF`8sx{pe{NCm00TY;IK<*tIZPQLoiVr|+NgCxnIW>qAHjO68Rf zGh<;}(^z(nRoh_$sdS2&Ytu-}dFGm1evvWDQuOU+o%+%|7(p4aUg^t1=L z#Z%!6dzT(Naf;!=eqKI&fLC8Wyxehj^{@Hqa~CKT3(U?htnj+HuESej{R;c`?Bch- z^$!2jzy4QLDiv(kBUkDpYXpT;$4Sl3AS@f%ZV^8B0%4_}cBjRHFw9jKy0r#TxT3)A zY17>(wF%oblDJMPBiVCk2m6lfVSM)(g>nJQ-r&Oggemp~H0t&Hex9Xrg=)3ELP_M& zDdYNAdw9NwK_X8a!}*K<6O%2F*w&_sY&}VWY>ttgd)T@E5ZQd5cB@9%Y7mDZN+pjR zt%0s9mA&x@gC`2Xq=9(L0&`K@$=;=lo2gi3ZFnWJO z0w9S)e&@gXH?(T=jO}@e{_%ZGUp>p;{MrA^{Edr`>D{eQW3kEkW0#2I1abLuL}g=& zbE%X^tyX*Bdqi3`LWm8$P7IDgDp=JRP`U`Loz7#7p-{;^aQ)>LkB>MCsV^-sKXo0g z73KcnZaswOZOVPZ7EhMVQBB%oCZ}fElo&Yx03ZNKL_t(=Y`d!pH9W-F@X(5GsCRPa z`~@ndA~&XIId|bA!-E67^R?G-9fu&5A{_(>X<<7qjxqT2vzTHDB?NZV!D-fEeuijd zjHSazNsJ+hBlIRzVbDsUlp^djk(QxY$&oFT$d~fB^u(V9{FFnYYD7_lzeZyz*L4w= zL)eK4(ml$%6)9{xTJAaVbUrV;(?(vqjM=#dCAyoVFFVq*C=ZTM9vq=jTVio`nohHh z?RZ#rx4Ghj)>hmsyzU#OyWD2J@A#qP7f)d&uMpWO4

    {s~k{O=P_B=9^B(=@M%h2LZdd>=)PEOdR}$1n^UjRu;k;5ZJp?GUpJ%GDY% z%fRz|YPA|&T^SY@%H;D&2*LFove_h#;}DA*n1+hy24r$^9LGmfl}ofAulMK3={THz zW*kj5Uy$;gO&7==dkU{nr+o7r5K45@#BMe5TxXfyeJQTEm^cqV2swPN!jW@jN;R8u z!=Wb^W5??F(kA)jOHC_gm^}9+)ye{?{+%R?TZrY>lImUmhMQK%FrYqrlt$?^ zmB}Zts}pn;hsfso$mNHzVyP>#f}84;`GqI`lm{11Typ=;>yfYt=~ zoePh@=oiW9G|hA(6;XE{)>39dskc?Br20#q~6*(|CSBD!-cf$*1Yt z^e)_X1tXp()3*h$T_)AN2}LTP8>G88V%O)0=SQNv4;i9r7BUQ?;^3;_QeHK%EanbT z6fMexa9uDXQm_yTwCX7BCbH0nM50udkW2F@?I!dNLRSHC@&w`7C`!GK+_Hmk>rRx% zA4GZPa1<`Mej^wba&{VJVGh~T4_!t4y|+MV9(864S?GpD5}EHJ6cVLgBTQ!iu^d9E zL;-9fnkKvy-Ri}0p@>t|7GaP;RT~5WAao3KhEB79m1v;pWx}8fMOgrm0_mWrHZsg3 zlm&$7A@E&P4W!J0Y$B92L13Y(ZG^}Y1m3bskKol8kZ(Xp4S%sgc>EM<+(5m42Pm(c zQ+^FU9Gs^@dA5V9D>$}?ls>9vP@b=%=t)AqLA&0;uyktG7TH3IfmMBPGMY?4;2-1c z;bEM%!>a9(?YFAwsLd9EWg-=o@D(IqKNky&WwN;@bEG&bj< z87BGJY2wcuqJG1zRFkPoSq?9PS6xh8jLA}q!{^GJn{7~OxY%C6mXRErSLNtV8}wu? z%omwf$S`Dj;xM!0M^IwjSoyV>xe+q`+ezdv&jRoDhLj;rbCFJCo~6-8SQ_6?GG>sl zVibEfkSz?NX~tE%;7ci)cj^RTNUxPay#n4S!1gV>=@4U#RhQhaD3Y=Jzeay|=Y^m6 zvJjwJ1li3vT8^cqI>%0w86HgV)R77wdTTdntqk?iD?EOL^8#YmX`yN+Vc^lMFAz)Q zSSpQ!PzXGmT4jn@B2Q`dB&uqmT1h6)JjTF=w^3O*Ln1ebmF~xGl_`wu#dq6Su?*?n zt=NqP(tX?TojR%(M~meM-6nc0!)rCayp)2qQiZ^BYC3_B6hsCFt_?;EQ7@z5B3*$< z>If}`JaYoksDa}Uq|&fyE9(9C!2C><%$-OQeDGta_x&@pTHt%gb(;yV+XE+$p&B4V z4VlU!`v;Mo7U%|eE>Z|E%nJpF3|H2CCEdaZ=QS`FlF=2lL*OUT^d+Q>oQX8Oh3{q1 z^f^@3#rKow#sa?IjjAl7sA&RULs44@(T9|C2$4gGBvRH8qKK3&gfM_OQaT7>^207b zWN6TC1|-ta1S#-!R8@fRxvc4e6!@p+kze^DvQR|5^A6OFgO~T*Yj{K9!baxRQ$Bz6 zFpu3U5DYVFyy>At{o0rCZ@3w`YAwO5C?=ZCHeRSOJpA$vxZnFd`1D0A&8AR7 zl|X@PHcPA3A{L7wL}WLwY5FxYkITS$Yh6WAP!t8<_fQoTKL~JLmv}r*wNgPh3_Q=J z)ofu}2DNGp!_W!BfNEul?qZh8VuM6BhM@>-$0b)t;JG2Ht`Lu@IF2NpG4Z@8Xz*g~ z$Hj1Lha-<2Ba`oW-g@Kd9GSUE%!zRpZoG|lt#Vnf^QsmT=V7}6N5`r>J5i%l?XXbo z(4C91aVW#8o&>!)i$eOvrw;YXEDN*GQmZYYB>GSiJ!Jc@BR{kYRsZ2y%m%)L*QrvS zJwj>X31oADur*K5z-GF8H(*)`4DzMd1#)84pb?2>3sNYapKM#*h^P_j#r5D7dt7#m8nLfI)|#8IGqNKW(CVi zurz-LMb+@!4&{YWa=n|G8QV{)XDf5oRPMIhdO!)OEs* zTM?>;@B>8HBJ>0#(uASEvL+dxpK!p1&HGil^epQ^6t#utT4=hDBIK`MA&97XA%s^E_xUa?*Rpx$UAh0egh;LCP)|MD;46Q8(n z`xp3I{^na<@V@t5@%gV5=ZnZNh?+QI7(`hV(#LTF6cNzrc(|U2kO3Xr#?Um{b{oqu zu$?xhY2t@2mT4k{jNV^W5{v1PHb{wVSUuNA*Q0c7fj|mDz1AU{O|rODCuN!_rbVUN zpr@-qqtzjvh!c+|aBPQEI=!M(NF)-=U3QBg2v8K|$0AEYO3C74iP5uX+5hBIeC%g_ zhOVxc@&bGQ^UuFe=d(a;yMwM9*mei8Y=v2?)i5oKcDs%5xLB4(X{kaclc3YF34(x3 zI!3eBAX7*XxGpFffooG*Xb`ikD489BrYay5(pC)Ba|u#uI_(yoV_(*q#Y12IoV;;! z*GeGW)yBj^ixU$yCQD7`DjhnG&&I(NgT*96#U#Vsi5Hz#grU#;)CuNiPC%?1Ur7+l z57D*iW>Q`2UX%4c7g7dfNnb=P*-$!rXdXkwQGP(ZOWi3|=FH}qj zVElovzN)E2kl)Sz6CL*Ludridg7@6fi!frGoOH;>1wHB{vOXU1;eW*8*iCdJhTUl_ z3&1UwO5<3u6piW(?N$}jOfWxlf<$Hz+i6g*Ez;G$o$0fW(zE(TglZ9n9@)N~IPDs# zo;9du8WDKphHs!#n<19&LkbN72hB__>n&dUV66+a{49ywika1~EAn zxnJoDB;thYHX#liKsmUdFq1(j8o@_@5%sYL5M!s2sVsE&670SSW&A8O8`+g<_nh~1&9zqh?E+t)>tkqswhfG5SVEC5@C== zQL5WZhP6se)F5~fe&1`{T{xp13b_oq{SV{ii!_E-vskZTXd15PV(1zo3<&{KQ}9Aim8iWYr9}L%zy2wy zsVdj4&2j72Zu$$aO;^3`_?(`qGdkB~YO%%CVvDY{#p=E!gIx($^(5)Zz4#m3sFzq= zI7hu+#uElosub7VN!PkNQB?h^u2sqa-)+-e9HY5#oY|A#M+;gcQ+e|Feg;-uw>;*% zx_KEvAbIN8C|lO`@xcBQyzAEOn1+rYM05r1B?6YF7b*;Nzr5A1dh;g{wdZ^1|Lpt6 z_`BbKYAr@Ayo7zBheq_Q}UX(g$ar*Jw=;+bA1&pbx&`a9{==Mkz&x_dp1 z@&vhoT?B!GW|?G1cH@+1Np-JZ+5DTSJ_5UTk*)H@UH+?c!F_(`NUT`y3RRDE>75QT z7DriHKo}-6kwHw2A({EYPp$LSsJV`S?fre)Bow@9Soc&<(5+#KrU1ckwF^o_%a zIJmaKzOU>jnMokjklkP=KxRr`>(+7 z{_bU+YbAHW_X)y~FbuI4X7E&vie_RvZ9LZ}3YQF!QbSQdQ$rM0Mc1Q3AQsb+Qeqey ziVzrv5?K!~7YOkBW=gyiF7$vdd>{FKH0fx!+~{%J$nY zs?`>zVPcskwPuHWK1aLN!HQX!h8YFmrILg}H1Ri0gTN0kE$b3Dr5_f3)$?4A96roL z`}T3-*^@|M_wMVkJ2r!Z1N`8DecZVB29ohOZ+-ha$mR2|`x=4geQydO@I5D@U^Sa~ zdX#U{YBsTAF&d2qj%}ms8jVH`!?3U&o6z^sRR!_TKYdOrbI;FT8OMe3zxtIF0HYE!(Ey z*ra;4(X;+eQpGC|YLa1qV=rMh7nphGJ9J8?@fvgF^1ZBDe-nlgBayoNG1ZG92*VYv z!wXg1|L+&R&%gS~JNW87Px5m=aVt{7H|{?`e|L@>wy#-vT&wMnh(~X}jA zb?bI|yE1efhnQ(nsn^LZyHkmkwL3VU|0qS3L*BrQx+=dmZ}F%_3vw@B3X6!_1#6#H?&B_eaD zjiFmKn@gywN#J*A))&ytB<0c=Vc;W$!qV(XQiatl%|DA8D-ufa`g)Di$&(qH;7mkY%7Ykd<_=} zp&%-YC|Za#(u9Ud*lD00e+JQMBD#AC)~rE1^9<_IL(#;dZ-C%EA3{BP5b@Z)D6?Z^ zHDcRNbyXjwDWX+Z$Yj^k2s@mN9_fPZQPuxx@Js$b`DK_pM zpuW&%c4CPgZ`sP317mEvWgGYZ(}S$vxejM+j1BL*nM__s0*4+rOAv%?y=gO6Tp*MV zSGM67_`b%(vn6~-;@TbhR_7`7#|S)?(rlZa!Q`#tK63y7AOJ~3K~%Ei*EL+jD}f{o zj?ijckCfos5Ckrz5)Ue=d`mhCfHYB9dhWOTN{=xmch+N3uhV|8ze^#f^o z^DjQFXf+mT)aR+!%T((XY+us1>D}~idGBR$)Wg8X_if7KPtcw}$->x!sG&o5-v;uz z0lNC4j_}nK7>&)8I5%D5mL2PvtJL`By$AT{dvB&YpT>4P9zS%N(U}t2bb?)5R)K(@ z{FVQkTd&_pGH&vTkGze0A3I5_+2GKLaem_y@8fUp-p4%;AL9dWyPlh`TSp?H@YK;s zI!=eKY>qAK2Kno+KFEeuy)0H5eCikP!qN@ay#3?YZWLJZ)K@=???;8pp%dp=Gu+3g zK7JRyT^XJ^J;gnb9HE#`^9vuk9bJ3Q`=RK_LVb$s8&?liFC87iewbR$NqS*Bi{#Yz-doH>DNB#<&>Zsu9~ z*S&?gvHj%wcVOriw%wv@_y#)d7V&&9vD`30yGm|w4_?S%4CcYgGCgs=K~qSskE3Q>V3^N;_FHVZbu07dX4$xBJ?nP% zB55p(&R>D{L+U(w-!n93TjaVE#Nrv+^#(iNx|!+IGc3*3*?IeB49iD|EA1R#({=p# zp+gu}aBU6G?Wb93V^Wu$MMi~jd(n={!ORT1VMlR;)w*dZDUzhWVODMCGqk_NVq(e zdTx%%n++=hY$?I<0vs=3|EUuDPb|`Cd&EqQk)9-bH+HdQG#5cn>Q`U0I+g~g>=N~I~%1G^a9{x3*(Z+zb4Ta`(i z))Lc4zCycnl5{#pDw(Bsa4S|Ujc&wWv(CWGLWTPtJ;u-c#4UXNzJvVUpM8UW@s8cR z>(=cI^%eO1-4C;FxQB-hJPShb>0ka3|M@SzPA;9`-+tt+?0fPAr^e>F>$V+aa|!wj zSss4+6o3AO`}vRm(@(K}q?^zDKVN2as>J{P$q%q&!!YG)6HkKO?(oNd|2?*@8(^rf zz*p~il8?UcE`Ijce~syVU*h|Z9_26o@dy0L|M77`DNt3Fr;eWG`;Q*w;~#tr2acWL z_}N+h=s*0z^In%s45Flm7%wU0i&@T$R(N#(6ocJ5KXJ2#XpVu`dQINbA9u(wL@c{D z_<@J68Psd@n6WIa#ypOr4%#*Bv`qoGo+w@uOIw$4x(d7gCv{RrA>Y-IJ`}J529Dk^SF0z>RnHV8jw= z+7v=bEO(eZpa`;#P*Mbb7DcU~C|!V#ls5Gxji>HC#^$}N>0jMV7{I=-9$@wM5j4Z( z@PkL_-PA{Su|WUY0z$ZizDi}jMy@x7s!Biw!sTA{837D33u=uT3|8Tp+_! zw4194!x&*889z2gx|pXpkVl=IK;3sQ;jX=S8#W;?XF`5C=ag`EY?7^8wquwtPg71O zLmI6M=PvbaX7+nuA`vsu6ctrdu`B~gxI)2suGQvw2q92Z69NYz6@1Q94kcFnESlbn z5I2$g!~sWhw1v#7_mfB!P&J*`ieDE>Nuy=sc|Lu`EPfbp@R>2%9fwl6#(VGB z#r0cO;Rhj~`02ND;_NhQhk6*BUPM;~w(W7<-Vu888Mdt-;`jgJTP&1n{F|S?lUTn& zE}0;iFd6R8qiHJrJxS8ZIJ-Bm0$^&s%<(f*JaPC8le0@~S~twj&8ztCLr1v(u}AsS z-=3q|*u?sgUUqI8;j7<2z#X@2V)O6-k34;n>G?9Q7gBAyEG#uRH8#hFRlOHppipr2 zKAw8I#_91UGxO&t6k`1J`&N-lfM||hk}GiyR~P3KEQO+=E724&osE7zrg_0uxzN4l zlIJ;2o9(;ajnk$?4D)9c zbi)D}a{b${=g31xsV+6S;jX=?hKlcc_(4c%YJn{`Zf5e-44rlpBbLLkLfZAGNu`UZ zBE|ef9bJ1Hu4CiceJF|zXh;Hdy@uy*K-1?@)dr3mLpRP4$}C71ryb(i9+^TNNfU{n zZ*7{fXGSRw7HC%Lq!S~Ydg>^yvw`7_!`%H}?`F-;5sp6AV)xs2QeUjGFj*p=wHR7A zz|w35Ull0$6npwO^Yj$GtBUjt7x26erl}DG0jd^6nhe57Jb&R+&$UU$8x<00;QKyd z7-=+x5cIAdLe)XhwCI|a&Jym}h4h@OcV-!qNhPrz`?89O?rvyY5 z7f28anRJSF$03zUqKJqpWLg%!=V6$y4HM|KhWZ~q`TpO2E{#W36f9k%n6cO}kY>+@ zE`$(_&NVqRQ|HLJ3Zn_|yuip2q{lTUE+{y!wChx8Wu7+JN0k+nCF&G%!*QkRuP z{Yv3@QPt~uKL6i0ALSpv^8|-ZjiOr_{u%|`8OYaD-&}|)SDgl?pRAPm*(f*e=9M|;LpBz9}-wS)Wbh~^ASG! z-kXS-2KPRCjG?}6c5E0%2>8Tr{RNxW^z*C#^4-iVRH!vt{KTERdG~EQ$fV-@_17L` zeyPS?x9wohwl$m_o8@=@_-l;xcX4ubj^3^`3*|Zk-Fc9b54`<))QdVrGS)-Yi!(Ln zaO3tg@4h9E?Y9`8Y_YyqLVFewT)i)ZYq&blG#w!nbR&jg#?W<(WV##EN|G%M(N!EF z-!;h4nmu$CM;KbQi;=Z^NGEe_-SvJfHKeQ1M1Q6w4q#{2uK-5f3!#=AvFyd`h=Q_%w&<475yzkWHv{*b^}5G0O9J5 zgrhvUPtA!C)P!dUmqM`T>nL-9L9wXb6K@uXv zfOtAa*FY~@_HIDaG_v^u$!r2MrV&cP)c#{^Sd}9&&_^hv#N>D?$?Vw~rcO^Wym63p zF@0eeAT^{^Kxza*0#FEpG`^oA3={ZX4}q5^@C&HqIlli{*6+HNFbqL0%lGzNE z`7%fL9mVZ9^o;a#@Szh_OJ$a(T4;Kjb4RA|Jp&^aM^$wkTVZLsPApYG5g}44gn=Fv zaBsHgg*P1}QqJSLHjXn4QYVxWMG@$ximGd3?+58W3v8Ttk;=(R+MrZ*AdN{)LCR~zTIl^4X^ z7m5(W)G!Pc!_Y{kEaGvUOg2U~7blrA=<7=pi>nm6Vq`J~v6!T%Cyr;gvEl-7Xw}LX zhR@vGJe^L1Mx)Ba#021R_RJ`r>(FdASXx{n3DPAabR_Fa8kx2cQq`6h=>E%Mm$5+^5X6w(&k zSLfKVCP&=7x}31?j74|GVs&?dJ?rw!RXQ9wSLX29GG}HQ+;d=tts_~kUtf5h6O^jy z#I-E(M3!u>pY6Nff6<8jwL`t#MprdH|BZ*KR9k%T?R)t1f4q+`|M92L4V6U9Wb@hq zzW2ycs*N@~H;!=keNXYx_uRzTvR2}!-f=5mzwaP>wyvh$XtPvqkc=Bl&zH$(lbjlx zW!KhKJbL&vM^8<&dG#QDT^SyI`V_mjtR^0_SgO`g6qqel$)@7e8f^|eJHfHjQ@mx* zCMvZS&zv5|4+VR+tzmAV%89d67`n;Y!6LbIoDC!0JaW*W*68rdAG?`iK8=t9Lx0ZC z*(y?9kQ_bJVfVHSVJJ!J7Ool~f)*mYR!F>2abDw~UgTVs&PG8u#oqNR_w^2Ji7sU8 z_5k2}Hao8W0PR+p&0BBBwd-_R71j)`WpUvghN|P0k1>1hd!%wh9D4Y3By%I6s4UH$ zqHq13ROe5U?%R%L<7o;&r3 z(nQBe&`{3`yzLeFd#_hkjXU4hOH1r6diBvX6Wrl#FEHP2jU5Yt`n*%A|69J zHo78_wgaJz#N|g0BG+t0JM|38555=K0z)ngDg$ri%pT}T}XyD4w6X6G1Cd+aqY5FOrP`92O-cC z27PP#89zNicYhaltHtc-JU6}fR_bM&N~w%iwfDRQ+%kO`9DAR+rE)uX6zv6j(mq8^vUGOe;w;UBrr|$#+E)k7Dmy23PGOm+xoY z<~!)_Sxr}Qm<^k6N5^4!cq>NOLONwKmVwb~qBP3P&F$mF1Ajo!nC9R={}y(2g3_t) zF>&l01nmm5ryj&^%wRW4v=&dJ#|qd>=RnbrsQ7LJRksKO@A5_F7f(Hq(cfW!)S}L+ z)S_U-P}7jbB4Ij1m@gt#jWC@-ZrP4MIE1@#JE~zIb7|z>J0O!q?A(UT^&%__p$Mei zK@@UO>_M5EMLBsKapVA^vV^~WJz8l2<=bCFIeHkS*+gXXh+|J9T1{xR&{}nrR1DBa zwkjB&jZCJNIok%RZvzTKi`?MOH&~)^ew4m`@y}9*0f}^)GY3yIKR%1ocGz(JCi1;` zPVPTJBA297?{MOY<7~Ws6WL;xFqEv_xruZ>N$*HM2kt%0wwrgN>IP=Khh!$rk$q>F zJiUm-K*SYt-8sS_#>BG|TzBU>gp#CDUSj;j0tg??)X_AJ=`%A7Y%H?lrd4=ugR_Sw z+5Pr)$Uu_JNrWgPM2sNtQIsg$Ny^|&m>B)Wfs}2+@EpE7gy$5A3;-Yuqp&nZ6$qiC zkDWs~b{M&3J3%JL)i*p4G@5Oa$<)gVumSGB9}ZrW z=|@j*f>c^Z*Fw6x{iSPVjGQ?HfLHJ91h8SF-tw%ua<+$f>z(5RHrP98(dPEivI zjvr8~)o`82=DySJV3-E38)?`sc5iyI>4&IS=4BXov?`O>ojK~GPqJ|89x|CO)@*zW z`Qpg)o^&4dwnwGuaBjB2k#iMhm)hh~CcT9u+gD}Twkm`1A{MW&79B63W&12tYz~|* zap+8$n4w`ADqC0OxMfQ>J-JuMKWue6fI=end@5JH)gf*g{I`F)pD%vnQQmUHCT_ca zBRe*Z@JpZh@BI2NzK3_-vJF27c0#7iT9H z_~!=>@ZPsyPrK=m$>qo=G_t8Asv0F5R~v0qMI{k4sI}VUQVCkNL&CbSwr1PLG<1ZB ze)ty$5q2Dxm}&4_f$R%?Fxnl5n5D0L`Fei9k&_ej_7+I!8rk%Pf=#B@GFDAct_AGg z(MzZ&dH9K09(ZJmlm$Qa&LYG4CZaihN$2+(F2$9MCp|xSzO&Yw6z9WuF8=to8jI*= zie_z&AaD^vp}aJOZYF7zCu!A7#Iya(jP0j;_y$_dGM?{}>)AoIbeh8OZbGS}8Y;Pw z>v1acq`KFl>T$xrkCM#oDrTZ^=^Cz3WNx=S=BG;Jx^kooF=nP0ku9H0cN#06#PdDe zW`|T)5=~R_y%60r5tR}_I)hrT6Qr|fwhd>WMKMfdvx#!u9yoCnxwrsf2(2b^&yCQm zqwKpMX~hw>3gL%;9-%sjM;-w)L8z#NH{Xs3d{~@EB$CKZ8#%HbNeHfkP&B0PAQI^) zQ^oU96cN4Os*0f*RF`U$=c;6iX;S$Fz8i9K{|RQtW*OQv#MT?Pa`cho3~d@9ol8-g zE-`v^6h+lg1gzV;p8LPBk9Ym-J84#1Jp0r!ZvWtI%#JQFeqx-hH*ez1;dA(|$BlR0 z!qnsxbEl^0>g%O_0 zSAtr-iD4z_e(u=e1@K$H1)u%wh1Us zF^i_{kcubp!zlN}GEHpPBb7?wc|N9TkV(bqI01=7A}S^>UVzuB;WSG$7Ed$t%(rOG zA7$7+W@OB^kdw&aCU&{MFr$@yj21>&ks&(vVg z>0|25BlK^48%`$*2}~6?;B~5G`nRKm3K$mIzOA%t(09bVa0o_+t;Zm0LIHY%g3p5o~q+zkd}4444M5K01H!V5_t zenS!nq|?i8>-*zqG&Z(lV~;Tq z-`C6~ZE2lz_Fh|i@AW*-{oHq*NIFC;6J_G~G=<3mYtCPZs;fA5J7`fCScR79P@Jw1 zO~uf?P%oL7mPt4fKtV;ipg9d3RY&vq5Umo5)x@1BfUe=@x=_kRl#yW=I|Uvu_GMR~ z<);w$-T{Rf$admxIUj7hT@9&}Ae}|7-;5K9p&r=N=CNn95KDqLfKr}A+AcDkS?~f7 zXi^}6)`E+z)v{>&F1nN}bz}=lv-5QHcLEOk@7qr-mqJwp(vWm5$)QM2=M6Nf3$7e7#oM(Qjz`2)gMJOiCn$7aRVENh1}OtT2}Mccx|M|>B!P6>>Q~6qs#L%EYAwGg z+O(!AT8#{j9Y)GC^jOPwz-cd1R82*nodvHK*JB_J5AJg`r~B_PTbL&hijq!eo_6f# zJ_ql6-@jhtYnr}EKbXHo1XwlD9gJesL#RD{pTSB1Uwo6kH-1uq}jYY z$;^C>_B<^WOHowTE?+{^v^g>~%ES9laqX4c zP*sh49z4qSO{#VPtBaD=*ISz1ya^Y?Ghf z*gP`gBI=bFdQX2PvH#G1_8&UP!@C}#FgM3XKk{*;Z4(N|7BB9n>hXDK{|I{y4O45h z7At4p_|g6JcV~FR6C;r4YX zrDSmB1=v;#MSU4kx-@D<)}Q-Q3i*==r3c$=P@daI*c)PI_YEjQLl}PceD6WBecPFv zK88Qui#L>^UYaD?yOrAfC`K?xD7gfyQ6km<61+YORkQ#fiL8fYXB;71R81k>lOWTZ zLQxeQ$3an*$I)3`*P&7_gLH_bql}*%!?qn9CqXn3VQOTS`h11nwf$f>k%||odr${r zNGY+Uf~f@vtX&W1Zb9JSxC*kf2j!)O!=rU|hGG@B^d4(RAwkid1IkcT}Fq5AxA za1ZX~uSV8tDBt}$gu*aaz`5%62*W@eJ^-4AVOhv?x1fh2h>200NQ8K;ip+J9$i;B$ zRfI3Vri<2LD;m0PAYBVbIv`=$#^tCQq`Fds6H%;IjeYkY!s9XMUDMCZRGv~{o|&O( z`qm6!+veh&N!h-3q@aUTO6VODmBNk*QZ zGNzPZI}%lahmIE5eY`-uWmB%1sH#F=Hpu3|81-tI^(&VwPMqVo6pB?`=@RgHs5Bb< z+qduHnk&xZh8yo>?TTJr_tH&V|K*?3nM=}>jq~Au_$Kdq!==3DvW-Y2x(f4^CU1P- z=lJI5{(#P8f|hAftkj7F{ph-OR)eV*6u~a6_!>@*)YyAqhD*1F85*w9v>moBlW4V5 zZA;S^B^;lCR;$5|haTelKlu?8QxkX$gHR~M`P;TLHZe{#5~ZiB1KV-A^um|n^*p|* z`1`j%!d(v?=9AaG5s#tMXqkNB8@FTVD(`&#C5%tc(c6_`Xe>_v3_?q?ioVW4AT86 zLXiM-(-jmTnhD|BZd+YSlSoIP>I$yoAf!;vC#y2r)8*Xf#kdlgMZi z#|XD6SM?esk|+xqGgrC@DJhn#L?U6NblQC^(&hP=j%^16r=87((nL|~xK0R7o57U< z1Wj~f0#{}c6i_t>*9oAgd8FHeWDZsJB19*yJBbi+gfNh@ju3IAY%TET1>kVHk@Hs( z?dw7!qiA{vMR`%x z=|wzy{NP{zhMwNF?7H`dh+>8FeZBO(;?0=LdN@9k$L9~85g|ECct-L|s^&%2ykrJ1 zA+_`(q-}Ei{x9&Iul^ZJ`qt66?0llJ4pdD;T~Jc-87fOsewL*C4CI1rT$ZsuTbBuRdlLDgx5QJzq)hGBh&6)~(xV z)+$WT~a{@sVU?wzkf*Hr%Z-+qluB0^6`f=0{c z+E;C7MQ@th?%&6oU$u=JZoHe{x_k?vfR|>=qR}*oMFO-;8(kBWs!d|yz~esmzoT&+ z93JJ~2aoZ4*Ic@&m~^_@R&TU$B!v9Gp8DC3#bX`3HNAa2p#@J5uRlU0-lixdQoTr^ zW`ZU`*DO}7zL;jC+?E?$dl7T9qjV*=QY%l>EFDJIy-eKwNqnIUje3#N{5Y|WwTz#* zpU%OHaD@-oX%OpJkJT*VPxN7g(n#AR+OYxEoh1;@AcOkI)pj&x`>EE?4+u8@S?0IIHFHeC!Aq>#9d%iQD~wNjH*cM`+vVdnTGswRkL z!>9wxFk2>S%SMkS5L?c}u?3p1?cXC*4OdqY`b9{`MFfHf1Txo&5{-dbL(%PaV6yW* z&<*542f1MjN-U1J>voVXqBxIx`BliSUepKfM1;b`EepA96;3pYIz5FN3*eR;$Yd5N z0LR2tb%bq$rY)50okerRg%ipz7JRg?19ze7Azd$y+fI&IX2-&q2)31J`(w!5!g&EH zm!jzvY^w`Zn?q4cI8GW}&m$BM(y`EtV>os{iZY5&LP%FdD0QUFfUKgZK7`03Wga17 zfP$1JLil*b&gRbbpd-8o#x#dS3tJA&)1TG*e*-z%h)lx8Y8wnM5rgU9bf8Ja^5 zEW_D&9=2;fPI>M5g05>=)-$6~o&CxL?PJ_>K5k(a#Dak%00P(65c=~+@p=*e10Xea z-|}59f883I{cHKr5B`kD5_4f z_dJ%J{~m-d$x|7dXqYyBPrHHoY(oM!-L;EjLu0)4mFLo#^dki9IW&Z-C@fu);gA3324?2U{LwqE z;+j`%<}2U7mkTznpx!Wf^vEf$x^yG4P=M>daubvJdEW5Kb#!MlTy@C?MkfoLJT=ax z=dI?-i`Ekg_=tu5&$2nTo$+!V2camq3lF`vMx|KHVo2#OsFkQ#W&>5#F&DntRtuph z*meuowUMrkY1UB`l}5dYrhBPZ3uu}_tu~JkN?X~+lGxJ0GTV;Hwr#a(HnP2(ecVDa z(8W+eGC5*K-YD;Iy<@e{0kWz7$6+3W@+t_n>JWRLvk5 zPPV11<6R`v{Y2uOboXy0mFXwfwTi)&7ZLJ@Sh@D4_;r<#S0@pPQ_t^17cSMY9ZVg$ z9jfCTy!Ed!%M*<6{Vt>XzE7ht%-F84Qm;-@oj6Qk@*t=xt>RHY!8Yr743|hMgRZ#f zUJt>jpIAJ+*yEw7rxl*s$DX=9gS&1ca!Eh*_9J@+z#|}$YAaHu zGLY>=SSHGB9x*-)lM{&EB{;f%JA?FkQB(!>q5DxE+JRawq56X03t$w+ z5Tj#ghK?{agx(IY)OroY7ecUL1}WOHfKb#kkKSK6@pXE!-8gmt+lphE2?SMIW)|r-aODh^=|gZ5SDLtP0U^e49S1lDxY(A7 zqD&!#4=JmFg%F+v>Q!6K>&!m3pFK~WG?0KxJAh~+^wG0OiB9@+m?Cim{O@wA3tQLylZ3mjtZJ&d)9AKEHh2=OzqtT~L zVhRDD{`8q`iQrG`e}(z}KLqVr25dqgf>AIG5Fme!sh}Bi2=SYhe0&klHv~uxS+m*w zy|3Y)oo8y~81ZwrkzIKX!-sZJug)`acqe=A{u-s(F@muyfpGGy?ZILy zb`c2WC>KZYhcZ;lllc5`nvF85sv{JIS~*W3)=e>gjCf`lg~>yNlFJcx8B@fm&YvU@ z4B!d_vpP*M-c4cRAnERN$&c(N-LrwhuP^Dou6Z0YhR{rQtU>|817%EmZwVtg^sn3^jgCB#DkTBbw2-s1d?%TWYe zym>hzlLf}}1=cL@#-kf_red6$n8mbgcI-JyA{ylIiE)0m;{c!ke}9J~L*snn3peuj zA9@={ z@)Uts7l~W|WCPXXVfltZ9NR_H+s)s(-V7eUflvgF4eIH{(86NSbp-R%^Ms;d8m$V) z9yv}R93rn--3Qf`Qcr}EgA+~M@X(5ad zxGfaTk8}Q|D7KA6;AGM$XebVdU>MmlAwShNF}(Axwx@w@!-g%mtJh=v`~QbXWsuDV z^4u-Z*9-gifHwfG7P7k+nMgsgfQUqpl_D|}M=C1VErjO5aZD6NMM{Z8E-s3n4Wz3s z%-b131+&!+faRQ_=-6iFOtZOgP}ByF-G`-8;ohqLWmu*|i z=f8d{Gjlb#~ z2llag#Q;}cvVnCgm(Y_-Jm-C~Z40Es`0%5Y$}`LsCNM%Br1~z$wp*n7Urw_;PG%s3 zW!4C322%APoffG;46`;*$JQPi)|7;U*65`gTp*}Xqa^?didFn z{lw!T99N zn|3gnpJQlzhMBoC9z$i_@+JJ~yIw`W=jFOj{Ri)S{l%O!*p2DfB%(o1jn7bPn#4mM zB0)d%r5Zc-oZzx;D|ydfe}(0J9aQTLF5R}8-i{>Kee$a$5HQ z(4A(@vTpVs8DYns6TD=@GFC0^L=jJwG5ys>+$X?y_Ng1~d1%jt;c3&+f}t~6rqkcY zlkLT)bX``ixeUu}Al6)pln%A(9BWs7-~x;BAjqWU9*GplG-rtk&V(JU7bs)6B;VKr;$-XN}H6U_t& zC;g}zNTIXxB`aywOpJgZSDFN({>2^-%XAQcW~d8}=92k|B4*2^d$5aoX^ycYV+3LW zasw)cM`w0q0#)%5>x^PqE}8;TRd6qTIRdbob%fzV5fb;+uSPb3S_L9&k+CWj+5jQk9gk0EL`T#vVH2>8eYh@s;UjUm@>!dbc!b?#@6ortro)6b{? zj@@p8c8D$f{kTXufTFf=ogNgmimF=Jb_PYM)3i6Ds102Aymp}C_M#{@uB$D)_L(en z1+F8R9nPbdCrI}7u_PG>pN6|;Jwj1&g#=YY#^Nxr4B=YH{1i$dj~E#SRl&{X(2gHP z9Nvd))S`-T_x8-)D^OFN^i=&5olUt@Tx!mi_U92hRrn+r0~ z5vC^{pdsYqU#oJc1v?t5I-*ysQ=*@-L}?^O7EX8A3=r-T*sy7ubFOD63be zxL`{HDV8!eR_223DdMSK#t-}u*VjkIE;GFQ79!cz?Av<-zCaXJ_fVZVMz&`o<>ENu zaDqTEj$^e*WCk!>H9Wo$zCaAK)gT;6W0_4f-B{!}|1y-XZr?S=_Q3$R@0#SYja?+d z&yQHZvxDHG&8v9y&-$HGtsM3MRgD32UC#b3VXbp(7~ zgn&0*v5k*@?mKj3V*K$tUP)&<&I6Ag=iP6*j18-LICx@=uYUSH_bL8|41~mlEb(BCBb+viXNg;93$0p9up_-qkHwsaV#5zO=kJaam+G?KaMw$ z!m5nok9Cpk@S!g3pQZ~Qo6r|RknV|Nwk#AyqG~GfTneE|q@q)qYfzdl6HP}zI%q1m zwrn>A>8LAHguZawZf=c3$mM?0XX)sd^# z;;veYa^eV%s-RjnZYl$b6wDWp(Ku8}NUs+(1L;@@RYjgolMC^zdp}MG1Fqv)_!{DL zKc?fJ{#oGhV_ofW+fVXW)~3ZdF2e92T?Nn1JE`nCOhT!nWimJe%aCRZ_cU`?5g;wx z!4@6f;XcbFZ1fT?45kRLfpz;lX_KSVUq zMP%WDrYeHIY>2*Wh(d3SQ~4^VrmGB1wGHw5av}P&L3+|bmZSstJipkkdkmdR&tJhe zzQ1FUS}{9cVfjD@r$%PDWZOC9QW54WHKdfRS-ON=GE62OCmjnhTQRwKeU3+u7I^e{ zfrF>!(Nu+{xggP?msHHhn%*crLq$q3^fNbHvsJ?~8;qUW%Uod;;fY~{yU1;PC!x#= z41WwoZ8s`D8@R5^)Ks1oD^>!JKdD~t!s0J6 zv@0kVZd$=?v4){*v`mYOH?JU*3}ZPCD+W4=M*>I*D+f9l8lPeF>TYyRrLQx^1CJhK zzEWfB+Fl%2Vi-F8JvqkmMOF{CsTJp~ALKiK|Hs_=;9maazwYEy*S(QMG{|hZ&Y_`c zUVYgXrspd3b$Ynz?mg^3KEcjCM;Tm_Woo8KBnlMJSp?sn;MBML0Ir zweNs>9d)jN?CHbNb=2-YWVr;I(OxK5Dk$TlC}XFfTtaNW2qzRp-Ej}%=t1c0!8vCg zvcC`Y*m0N~$IfI?Go84}48n0>dJH!jMTQ~^XH6iRb?|tAcAuS4ly(pz7Q&5%9=xZg z20c}9A{PF&v;RUUh~gZ|_$Z<<(>9)4y#YC2VCjaHXng}%$rREykwPxMMXV?lKQ03ZNKL_t)>x6?pFd4`prCu_o9Ha_u;Ui*|#RNU@fv`hy= z(|GJ0J9Z4mJ%B14gm~@@h!^pj2o-lc4}Kr&t6qiZNF#l4eE)7nNIWmbT`;Uxr?9>$h_>s5c_2?AJHR9pGqDH@z4z5%drCe>t zMY@89WwZNufm8V^wT8{uY#k(6u0u!M&x-B{$*_)BG*BvssJ1H9TPBJA3rO^C#vkrN z_r=ayhFwa@J@@TkYHEf|CXLtUU;Ozq$-JnlN-ik2*^94h)az)vMmQWn z(^N`TALp#hVc9CK(*mJ#-_9vqtIo!?A%=!e;y5;uNEFj-k;|r$DCn9(Hj}1OsS=At zux$q+z~eD+92Z4MgrectO;aa-g%JAw+(XeRFTcgpXejwMtT-{9iSD|pLQ z+xe5f{RS(#J9+!-FW{1Qe4KAz|3`FX6V#g~U--stT>l?G<^6BFf_Gng8Q;12Atv(k z{Lx!qj-m+O_2GZvf{n|0*BdTD2!U-ojL**FHw^yQN58~h{lV3YPM5g;D>w1Y|MMR1 zcMmF z)j5Lk9;Qz{Lb7KQjam^YG@`i`G)fbMIyRuAA$6Tt*G8J<2|~#Mq)TI%_^EF z2*`#0>4kf`X`|{Yw&_rm&7Sdlo&lSLb4-8$I=e! z5JI>J&5x*6 zk@-d%`vidNTBoO3s$sw%>@aGz&+@W-mG2_X>8CV0FERYNq3 zD2|Ogo=0jbZtqf@>1l#pOHjN|zkYbjTj1+oKePRH-pm``s$hQhZ`*Tbc-u0Yr`HWn zs1`lx9=DY*TMd+!i5&`@sW<_OTE*u-j-spp@$1_&_9C7qNCWH3-vG-(^!A}$ybW~8 zz6WmM!JEIu6>q(c&Vg0TP7HI`cmItCZuWQz!Sz!%{4eVSz&m(%1FLSxo)v)NrYuxQTqEjiF+Ir`Sj{R4?KE|FaGCk z^mS!0bd9%PeE}Wm*b~M{33HVuEl0(&TEv1L!u}`rZcNWNC^v0Ns|5^39>`+a^q9v#P( z`2B%Jg{ad3gAjsTBt-n^eoE;M@`j(5`FJyvzP>($(3zZWF_~|&bJr9r2V-=1MaZRn zWYQk??Ac4TTE=xH%|;zv*C>~3fJD)|ztI?53V_PO3e~?%# z)(%2)nYK)+st^nYXtr7e{JwVJu@EH-p<*>l=-x23`B9|MQE(_t9mE?IGS1nA>q-jt@C+j9Q;`WyMJSDeS2uGq}SKL0(gz3O~6uIxck6cj~J zs?_NB7k7r%K2j%)F|S6_rsG`t?2Pk!C|`Z-Bzga9fQ|(U~4UKrr4^JQko z3dAx|BAEnMt4V#nMkF1>@Cq!m-Po?+AT&?gL&E_@Q&Gw#q(6jIK`qSS0&0G`t#}nn zq6{5Hyn=-GB7y!^sfc3yAJ;T@6T-i1MlaLR{jM0Pu`1&M6tGC0;-O7;s}neLr*W# z@E}zU)oS6m4$>PyI5v)S7c;=BI4QvKV8pu5rcHZ(W?z-_yOphGnW8d11FVJRM zoGwxVxQ>IOsx%udJRXB)y@}(v7+#(EnG(K$L9JY)QEOm$eH3Ts@CE$Xruo7K6Q|Lv z5kl`5A0SVwo+b z^E0TL!Q9*|<#LrkAi&tzD3M4Ek4LB3vIvJmfFu@8wtd3-(}x~5R6*68TSQJgOlkH?7x4eAzTvl&d&A`}V`42Ed6nxv8m z>Wu~-!$46KT(@2IK&aSe6-Ck8%2|~eg0W8KM|L7KFRfahdSRITC#sy7s!E|xn--hb^mFecNBLiGei;w#Jn`8S=GT9ii?^;q*EDjOI6HP7hUk$Kg-kbrn93!6&}(J+AwmEBW|8-^d5vbrq4| zGpoE#&J>YSK51g)e+o|18e6Rzs;c2S4)uBwe;`I7Kh(beG^>>7C-4Rm%uF6eHG)WB zW_&-{r57=E>Jg&Z)p&w&tY(>LZVh&;i6`2LFOtJ}?W3?q$n+?R=3~nTf;#$aX5^?kp%6tLx zQwYGl@^x_R5Mr)?)HFmYgVWQGGI|nWR*`iJ(m9-5C$e6pzV{%$l}j;&&hbZwNcCii zqympKO8ixXZ99}obvin`FcvC<|6LXTQ=ftle(=ophxh~^@BU|;um3x;(ZF548h192 zcH58JPVkiy^4fReG^%KK-wxfq&}bkcQRv8FWxJ6=Ma@s43?DW4Cy-fb%V`U{5Ia_Awm3sCbY znRoCMXC{cII-Y*u)8KSc({UUWUf{~a&%>22Qzssxl0QMFbAWWF4+9(7%p)5!j~go@ zy?pi7BRu@@ZsPG6rE-N2T=$0@eCT#UYJ+UtOE%^^v*`Z?F*H>nH?Rpsef*8FR-UC) zm_Tux#DfMwzXuWQL1x!bER--^70WbfwOZ7xB?5jw2sm))C=-)Y)M_;*CMNM1I=D8u z&Tf`1TS_z&pogGpXg}M0>UXM*2=b>7y6OBelB@+xRU5?@LbMSBhk4G|@ujBKm1OqzRlwfLl2HSov-VzHQ z8?J*Q6l}*qx;C2bp;oP;Y6{J!iDR`;HH}iKjMwX>*=kX(*2t!ln2c2)f}#;L_QVqg<&H4EWJC4cl?>`8+s|%O^hdSvGIp$je`L3AR~7_k^ewhR}Tx zn&l~4^#YnFz})C=e7cXR*$M96Z?P=h;Ew%|zm(pzxsF>tLOj)n&mY9GEfVQ|Y^#CS zA44|+IF3amn!#+<7n@^GXJa3iGI$IM2>Rq9Pb{$HhLad2E0 zRcW73RZ$jbN*1o`QmizI1P%5bn_y&Oj`P+pC7p<1I}V?{;U#@pYYzdyo}HO`%ii4w$-c{=-}Y-ahCRXuyIAtS#Q{$H(}~h{>4}Cr78*cXXUhYx>!K?%?7Ar)8Q*De!vqh34Qk z)k|C0=O6xT7pkK0%8S-N>AuvOEdu{TDOFDf>9(E2rIgrK3*GQhUT`vR)aGb5D;S2K z!t@DL-9x=PPhn<=M8|3-haV=AUXJ6s)N6AjyEjlPjuA`^;xVE)ib5!N4t8S>f214D z2q0aHV4@$hK9Av#w)a7vsav_u0#!f}Pr9geESI^d5}FR7c#O%RNh*aZiOx8w?l^_9 z5{0QeU8}kX2K@`Nsi3H*DZ7%wSdmyZjH+u`rj6^m=(>UTrtjiJB5?ktNL4#ylDSw_ zkl3b8vu+WHwC^o@@7j;1>!fb>22sc z?}HeeXlay?aplmY}}$eDJ^Uij%)G!9=~$ zVs5@jFyJSd?!fEywl8Ye2CE8I1-Cwp(`q0*5!7%uo6fuV|7Y(!p@bxm1VZvlAdm!b2!Vh@3m7oiV9QmKWm%GC zNvpQne$Jj=r_cLgR+42E+qgn}eUf(1nR#Z;>~rpNUDwSIe{>78#aZ6_-uLr@D=uf_ zy4C#TXImJ`hUiZR$t6Q9DnuB}gdckm^UzI)xt>aXXvJAyW1BjS>NKrdkyJz_nTR20 zRv{*qV7k85pQ-n#RI600RZ__W@mQ2&6VvF1LAO!oq5b=5wz^oBg|7F=q|<1s#Dd{L zR<2%$D2hbFK_cO&r4T{egb1W(!r7>2`ZqmPIfaq+F?xPNgsm9Xv>9QZ$=Q6h&qG{X1B{ zZY>+uufw!Vvgs6vKCL2|h@Qg%jM*3-151}_pr21AdJ9;a93pZlvZT~#kg_wGic(NZ=3*p)p>B0z| zR+&gFhk%FeKp+sH*6fgsg>hYvQoYB~nHrl`4?LyM$+HF1vQcCa%l5lVk|g_yh~seU zJr7au=oHd%1YpIYKEC+P+nFxaNyb97x;lUMyRYI;{{HI>_h->mnQqVEhSy%jXa4KQ z3=ZVD;ni1gbh5HJrkJ0P3N%pU0>fjdgORvP%JIKK>(fmq!oi?%jGGtXj z6cl2G^%$*5BB{l`CJg~ui{QE@qNvWV1)TXr(zb16MaJk_=v|#~B7`hUm^};i5ti!R zrcP#g(zW;rA#Vbz!>^lCJ@A698 z2Oq}E92ZC*r``%D#O;D0%;y;riX`DQstCadjw~V9N;tZXGByU4IXM3kto~tK$2e_0 zYTyux+C>ysJ+(LDdHh`PJeQ+;x3T4a{+&u`ieMzc(DL=fGksk0;@9%=8?NR(pSc-X zRtbcokA1)=1PS-h6z;Jp2#1hH79ykqKgS@=rykFGGU2)|tyY^#y-A_aPd1x9D@ou3ldUV)^RQh9RXV+e+pd>rRHjj6k<{QSB17vC z1eHfl7cG^FG#U*80S!~vX|T&v}X4Z3Z+{oU8Gb~Q`u#`ne z`aXK%5b=mi+sku!PT{=4F6&mVz_x8f0m9J?mf1rKMCK`9$445U+nM1P1&_Xpc2}p} z(aC2LxUNH|YjE$bL$o_OS6#B2R6NXFwaKS%{2_O2f0*m8zJQlpzK-=P7Ca;Coh;V) ze;@rK%NArXObbm__~<)dPcWd;Y;`#{T_zj~@S%UaiPv9yDXT{YdEs0Cif{hYA2L`- z^MOx(4M~RIf8$kr{=e@cn~wAT8(z-uee{dG?fMt6arI)}^;cgemx{7&_YwZ$o!4{k zgNM0&+g`4_dLu8mcn#S^5CoY%;2SQNtddToPty+^OrCO4c1JWSn02`dPmKp^Pva|psS^1bwA zaCB^nHS5+R9-r-T4s6>7mt1o4dM@EU?qw6*+kb+ye%;S;_Tz;#7e&@UR`9xQJlnzx zhH+i%ln#X`ngl|lh*BOw_`geIe6FEYne}PUy(Z(MdocAbdZ$6R)u1vv&i0@D4}bE- zJ4odRANydB7oLiJ%ND!`cOWcYjP$}Q5K@o7Q2un{SxY87&qLP@s*M)GV3>S9f6~VE z4A`+_2RDEJ`}Fts^U7CVM=G7>{qKK2cip*#TYh{iqGxc|J@;|+$Weah)fdy8+0Sgf zN2_abaH`1zqZKU252hCNMOZ!=cKop!53u~a(YKvF2=32G{#fWo4s%Me_fY%b5jg~OP-;a9jGL-hMZk`P%5B1;m6 zE%Kw=MmaX#Bpwynu(rVDOovM^UO*)1;MmqF?{gd%NfNPb8^?7~6@_}Wj1~-2t2NLK z15p&1n=7NJ0h-MQ^?H+VILxu}ak7~dde6YLY!ZnW&1Rce)UUuJO2lGOEYm{MG$dKT zbwO1%9LGjF%ja`0IF7^C`|f3Ec$h#S$mr-Oxm=E=OP2rwwq?xIt^8@Rw(ZjEcF{D2 zX0zodJAz21QX!Yk&~CShM#2Qc5e&UYU!j0y+k}GwGVur<%b}3ZVHgIAq7n)QFfEJF zeAh#qpXw?I0+!K2(W11glT6LjaI6-t*(I7PP@me#*8Lr(XG^Go2to5GebQb=mMle< zRq8Xl>05X)_0oQ#@f_i37SrsJ$t}b(4T7O4kys9+*Cd%4M%P;?O2FrwyXU4`{W74| z=#Y#*bDObg*<5)2pK|Aa{W<%`X8E^o+|I||{cGr^!H56xCe|)n2$=k6%fo#1UB5;w ztnty$e2Xvs)!PYZDsTVLzw`QQH}R6o)^Y1S5AmgM-@(8B#SQ%ZjXz}h!UC!y^OJk_ z@Oy8#h9$!Vdb+{k$ttgX=Rfd~Ke(Pv8<+B<+jnut_I(WZXBb)7&xQ_5Kitf?dBY!q+nYH zopyy_C{B5H)TderX&c~mM*?1o8ZC_}f| zr8GH5v)o|mc_V1CFq3t z4bi6FXd#F){r!VPBGEGjz`CweDo#@<^mE^R_aZAY%a$)=a&n5F-F^q}eee5-$D+LV zz3;`gZPu?}&#QmsQoPPM(U3xP-hFB1P=Z%(8s_j!i=Bt6l;&lIKRSS{nUy5xRw2J!?uu#(@ zXo1ipgx3C=B%sjepT~7<`UZySbUJjq9rF1M3l=S=Se(VsO)V* zJtz=Fk#@)6;n5l^mgTwfvZXXzI?a~O*s%&n##&r+xpzjx4ryMiBFplLhb)=)9f3lW zBLx2d03ZNKL_t)clgZnng$quhI(2(GS6{iAR4EyAHNQ`0l#b6G6QM3iJA;V?a2Cl-z1o1%+^Ljg?FLem0x_-pswghV!;f4;w7 zSs|M})!tQ6eR@bFdUDo8EEWSi63O)ZbK)>CFo0?3WOG?8%f_-SBGCxbGeu-sq*OF{ zsM{kJi*e6=_Y;ly_rKfiP$=}#Y&J=!lZ3-jT*o4xNnu(R;b@O=Fh-^jBArfQ7zVm- zuzmMos*MUSdCAMT@ci?bo}J~6EqC+XhaTdZD=y&jSACl5_=Dum57KMQV6;mF)G!m1 z+mPijW_^t6ecvHBd_KjW{Ri2?2%;oo>vd9v<#gL+;_)16FoEaj)L36=u<8-f2Qzs2E~>K%A*3M-3P{b!9}Ym)jF(QHjJjq+`eruD;5@*nyvHM4_(EP z$r1;S6zTPPG@5OeEhr!e{^av^*Qa&?)LUH^_U8}~*?)M7S6#i4P*CGPzI!MCee+iS z;LR^4n~E`8I>fJEyNOr7=t4pPg`aJEnDs0AdFPv6PBI>*+-UKk-@l%2&)}~=_gx0E zaYRYtKfikytCkG#tsigW_ulv`93FT1!5up&*V+`zP5$xE-a;W0XUE>7JTy9iqR71R zn)3+8mre{h3!e$u8k(R%oPu_ zc<>rJjUw&VL6kt0>I46Z5{%R9)M!+vNcOK`>*0IoTXF?bAWbg1jQ+_k-Ng&2HWid` z9@l7+99WC%dI*k#qy$gw(V0vfH|5*wM$;jrV4mUS1IVh3shcG7NngxuJ9x5q%JsRf zM|rYBuceb2$Y5JGmT7@25Y0qT0}{QCffi7oR_%o(iFD?>|BnZco-=WT#dHZF@7n#8 zBonUdAi5szvXzMU-;0&B;XIBV8)I;Ah{cN+A-X!|kvjW4f#R_}^u<65WsnNzBZSVp0r=J5vu|qcb_>t3a6Bj$ix|3rtjOp+or8xC z5(G~~HMP;DB56|=HE96gzj9167e}G+QW&jA=QvS}h8>43ksS zEMByb(p-fDqX$^GZXJF39NBD|uqt68k;`V-w||tiYgYLkBF7~d(0sa;==-vJu7l&6 z$a0WwZ2~ozpi`g3Hd=^En8wU*)L@i$`4HX8F@lK#rK9(eNH3w+n#Jjr$quZeGV>6b zzLoPnG+k9x8(g>iiiTpr-Gh|k?jBr=Q!KcJPI?gc9s}@rYco_tvBs!qfgfWk6wCzU!sv>v9he8*N-|8(Z(G$kg zTCCtBQw3h<%hn$+v)Tbc4$UtU$40{>>(`SnYtI|~G2l0$wA_IDc-BBm)PlE7$BU`L z;?=GLLJD7~t#!T6%PGNI<~T{F%PA^L_w{DNDW-Z=!xE>!gv$BasLZ;z@CVJkzIQhq zil@M?zlgT4+0=oT*^bFdV6WFvRvCQ6+H!__p+5!h4`;%^^k!7rD(h^HfKY>u%LATH zFY<#R>{9y@D>rkb8F#j?Zgc5w|7cz0Nc3@jVGPMcQj~pdsR})A9j=wAl&EYxJ( z_935kqL9~>nUv;lzV}VDl!37m#T*@xVm2trb8x>L;ukOI(u@(nD5=EDQS+5lw$7r{ zPWA|wHTU4ja6_4)8q(fq;AxJscSY1R=OGDEKPQ>Z0MgPH?)2`FT<5`~t2pTpcpg`3 zq+sJx3I}t@nPD=Gfk|J2@8ux|g@pH`(8K1)`^F%5`{oS!T5i{M*n~d|K+O0ap6`@r zVZRb6b%gsjm2#0`nJ-2lmhy%Q;4g%FyLsS@p(Bk6MxC)<0Dy5s%gAq-*l1Trh*pK4 zyK9nJHo}t7uf6EjMRB|aQ&48vK0&`mg~%EOiY7bl{t^${;ah!5EpQsjU~b9f9*!HhFp0S4VwZ7USv_%pU>c!s?igY(L%0WGT zF1Sh4ljyexd}`_0D{J5HWai}za1*WezNRqAq1$*|(2kY~X}@VT61{%1kDXbBXBvLQ zbEe7y4_C_oEcnjWx4g;YrQzieK49vi7cqQ-*@_ygy8@E0QU$g?k~CGJ+7o zu;cU5V2vg--sSvG&Y{gT&W~rzvBQ}^0`dUwn_uj7fcybg)mZhsK9X*eXDn7cdpcv& zFwK>|ZHEHBh>T8Wky~QE1EsRMhj1(#e!Z($I z2ketaTP(xJk}sc@PkH>qg#gqQ)L(`{M@MucZp#N3aF;r`Yis~Sm6)-_z8c?Qd0>a8 zbT>FjL(jFCp%86+TSUJNIbX8488$(HTbhwa&ak5Jv-rJ`Uln*~tKzWG2INX24?S$m zYWuDe48&8eMHNaS|1iUg17Cwfs$wahJO;XO1rj-hF!K)}y5y+?9Kk{IAj;wj;(3qU z7MIut8p*7TaY2!nbHB^#_26S~zrayti&*!nrTQF_u8wftj%|)R@*K1InGbfz>-SAY zTgB&o=ymA=_p4n6i5<_-Kco-w_x=$o?FUfZ#y{QqKgJu*9}v#HS4MR@t&;wy_-KDK z&vbeW|NJvQmMHH*3YgFMRQ7;?<7raH_B z^Z_Z-)lkZ=8yo#0I>OOp@=id90Vs`B8mK7*l}b^;dljt>a1tW=qlm0;WVx-frKt*E zhV-`z71nbV@@p6^4sF`j(^@NsfhyfhB*c{ekQr8>dnTxvH&C?TuFp7&j{jTtuKE1! z{H?0{Ks4~`J#e7livETB_Y%rfe$l@_ln?5WN;p5X26BmqbQ|!W(TM4EKNVTcUJv{h zL7=*v`?cjQBtx}Dp3}b;2vku^USN_r84dNa`21!Guj0!A(d9W+CRp)6iJ-x~3V-b0 zoUX1T6!Zzx`#p$AVAy}~w#Vsrys`ng-XA|%?}$_s7(fdsj<)1?t1dk zs?tY!FdCdyS5Ny4rZ&kd&wGznTOG)`HWIILe6&9B0>gcb2OUMD8K|3)3@Y>Vp;Mny;bns@(shq7~9{W zj*=-a|Jv+z5#T<+jyo**SG)6{CaI9wW;9$bE3wIqRpOgOoRs3As~`eAV=07kbVfZl zTvUN?{r2z{7VcPDMnV`NC#L=>V}A-a+@}s)H&0z6tB8L9K#(|WRqimP&sOB%isd?2q zP~)7z7Zn7w;>Zfd`kXwRI^LY$JX=mt7L}ol3J8+ojOmQ<@bL93WG2&WBO1h`b0cP) zQ6W)Gv7l5rpAPaP4VU$gI%1l5q);&KOI4)lF=Z6&>vbmVs6FeklL2_9I+@74*H1$a4r^Z0_pgrVx*Qp*u^@}^8i*LL`TaaM!Nod>Vb52Q3)Yv>$c;fUkrB+MlWm2K_B>IqYg8<7IB(Z^ zo!xsu;<#ugo93@8Xu&g!qt_#yq0ayk)5=zzQAhmOGoPgDm(vyRYv1?u&#by~Ez1%a z;3rq>s=!MyF305e^QU)221vp10>jQW8a##>33VdWT*OD3y2sMCTUec5u}~4uH^lGKhkeg%Gy&RNxdTeEiUH#SuPTb0U%jPVqUgEO6+^(tUQ zDxn}%o!HM|Y&Yap$Po}~Qcn_}u>Yt?KVqTfwbYs9ymj+V-dgjO86{F^xVIT7&Pu6k zI&@inYimj<*fy;3bB?mB4KF15ne(^*0ilS&c!|f=)x4@@e}I(K70c=8g1tnJM8lTT z_#PGp`RXVvh!ys{Dsse}%Auj%(R_pp4&pIlhDHy)?vC9Gm6SoKZ|V?-Y7WZf6O5En z&HttoPs?Vx{D?8np#C`k2MmiWptbSO5g; zrkp5hoea*6akZbku#H3zr9AAiMM8SY{;VxWyZtjK!aN)IBO=o%h&&cMk)Az{j=+S)D;H0Z*@7;td4H)S zwm_~sD*zde#YVZx=7LTzfm;4Dn6VAE(SoedWv@~z7E6M1VBwVzBKt2(h*{Fex(oZ( z2pB0KQIyziPSaKzRkGt+r(kK&)tKmY!p@``5HV2Y=m>xI2P1q7U%W@6Dy5hZanY*P z^<(uKOtI!{S26L=JXAm64cp@+uVii7`(YS&sPym4v(Xz*lcR4|ER@xJvPaHgsWz6^ zs3|))z>R`Li*>uTazZ9orITjs0NGA>9%zF4xMW|q`@BQ>^c2Qzn|jjhnK2e3l5i$0 z@5eT9u}vCzKStfm6W<~*I$_j5ElC>_Y2khOd4fI}-Py|xN#z1CM2b{IM%sJm0AMEG znJ7r$sI|#bWRx8}OHQvao>NvWn+V_Gn$ju`J4W$J5HI%v>S|eQlrm%{BoT=eZ1=N- zjD$6mJQT7lDk4c=9(38Lq4YCo>@I zZx^5*D+Kk1OCPu#rrA0s=>?Wz1KSw~w_)6w;TT0W7rz2*ekU>G`HIw`Q4X1C(tY3c z_)AL)zZ;i)QiKmZ*Q)m?5{qplTE7ODz1Vex^}+Cy!o~3Ezb3x_RG0nYBvKxg7jSZL zi5lg-b$bYL67Js;2~#Ad@>)&5YzZ!-&HlrboBf4IEls!H=|k{li+A*It=O)ILz#zb z(Pzr0mxr>K*D}#@WRVLIm@NGGk5ZmLvb6W4?^~A2+uDZ9`e15LK-+u~mo@^Fjy$&L z=ig6=h?Cbp{W)5AxA;P|&^*x+}f5aB8`V8S_+G+5)>@r}U`x46CxTBsXu-c@8oDJcpAk)3! zi!k37Ic@65W(x~EJR&Y_5JT^ju_$a>P-Tc?_y`+P6s(mVhrJ0q@)If;Vcb^#W5Smf zJsMIp)tt|!*+_6~>WnzC1KGK`xn+VqbGsmg45lKO=LIeN6JD%aD_K`6FqWNzLn1Ix zwAA{6+7&9i<^5)6>C-(@6)8HRKUk}1H!783o-@u<%LK`yJN1Z^5|a3>MNgi%)53D9 zoEZ-99WzhYVu!>Gl)@FddK8M-LfvZ!im+cQ`68z{OSkGkbJ~pTJC5}2?Ss%H3<$`& z{I_DYlVvdH6!UaLZpJKM#*;AroBA*DZL~duUWlP*#{LOIb|-gQf*loaGtvr=^B7P0 z>KDZhWhO&P!k8UCo}*Qh);y#wSyHtxPGqReK;a(oKp{5f%!JS1y?`h}_ktet(z#ZA zVGun8*e0ZHbWIQ=NqJCqpzoK?>ZJYs>E8d|_;dy27OPWiL#M5e4jXsC^QY13i@{@- zzFNDgW+#5Ao!+yZ(F7~OE+x($0Q0nB%Kj*-R?&#+FQPWnfuPaa-_ILfD9?A~l2=k0 zzoY7IC**u0h8{CnXt6O}-VKnW!RGj^a=-~ZzK2bAix_(ZQkKQ~G=uwunIj^%9Q^q& zv9^KFVA57g-XC9LQF$=GM0o;#@29qg?Pv@rw?!0Lxe0PF|K=$AshYo(xNch{jjBl6 znR(OgEvtts>8PgTgUAA>$ENJEg-00gEHQ!zNHLO4-5pY47a$MvC69}r{Nr&dVB@NJ z^Fgah39JX-vg9Qt3 zaTYuhkgq=jzc#H+nr9je&TAWSJHEq=I$GKJ`IPC3ScwRek3+}aEb5p6p=Wa*NJtq; z6D-nc%IG?nll6q8Er+-t7jAA4+RnOC^?6h}1GDTPz*Dv8fnve>Ss72)A$S?xRRUVF zdD$WEt7uLTjSG;ym5{!HRM-FJTm{2SQ2pZI>y74w*Y6p>5ZIfTG%+3h;U}*f_NC0V zZilyjZ~}vu-HL7rD@7?QLGP`Q!{ZTE1ac}ahbm+Ga4AljyenZTSO|X$CNqdBg8kgA z{Cw$IjlX-0uvFO*>^$XrsTpAGz@eJ}+RZ(cJaz?j^5i{)P#|1C;(O_4G;F=%52NE? zV4)WDjNh7^B>LxwlXEB4L(n=>>sKV{C3JDGPXcvK0>vBpf8_pFY9JDJoaGfF z;p#)*W1Qmi2()MmBbHYc@`1JJ0et*Fu2`i^B&sr>m9aG=LD`ed)7>1{eX8Y{rXxY0 z_^KqC^80GhG`OQqgAcvELb{i1K6d>)JfiFAF83XsY&@eSMy;{9r2KG7U>mjMN+!{q z_|+lbWT`Y9?FZMgeV*@mj>Q_cE#V6HM6KrQ$(nN-tpYU~Oe*D&U@8-vR)J4oM{4rk z^T`Qat9nE=`;>$IH;pvH+2eZO%l@6SC2X~|NQXS zj|lO_fQ6&9)iUCUb!j#D`hQ@w;&29J1|{J*P6{p+@|J?tZ3XsLcSUW=u3ZD2AA}q7Be?Nnwz^}2Z+wqd8bNG$< z>j?AL;oY83c5B8?d;bL|c@VpfHs}j|0Jh`!2n024Ts^FR4RHrZSO{d`JPF`-b5#PU2^bd8eX#l* z9TD1fE?QtECz|irCSa? z+Bz*e&8bE?jNYH1Ew>9_AN%P=dZwm;@zSBN)BStZYbTS>$vAB?;EuC>kJ%A2TdGjQ z6l=vLAevh=)c?TVO_d&1EUYY1YwwY@%EMm!?=Oy)pFv-#Mfk`atMI8m z#q%b*6g9iaB`7wd%Gk*ZWvQ2PWbTLzV`XNk$@g>9>9@j4LB1-5KmjSx?$=2NofPVy zf19f!xhNpbE`;>0K>GIoCfNaC&ZxvK!rcvIvPpI)gAb$5etMx!E~3!`CYFl3q$|B_ zXdqp2+!un;7^Hl};WChVE5!A_!xZ-lqV@Ywu!di+G4^ojuvD&X4V-MIcZwuEL`jJ9 zrCe)DBOEq(x9DG+Sq{3T>dVMl@rQJ$jv@e z5opJo<@7IBy==nrT&PzEM%C_2jyHf=@4K2nkmW5v`WhE=eQ>IFv|Ni01%U>z5Du!_ z=}#3&)WrpFmw$*ejMXXH{3_~0UR(6qt9LAtSVj~QL_)aRElHN~TY=I&VH1(#WZgbl zr#)&K8N=mqesr9sf2*&1!?meA1f%L^n^9$w?oJ2QaZ9{#1#|l22VXEA_|eo5 zdU~!w-C#9Xp8>8~Me)yBfCLiMo_gfT&t)2^{xLB3;raQxadMJLYE_bx@7^9!S6sgh z!+NjiAnoFbFJFUWYYVmP_!d9mcv2~9py=DDpAQqBoqcPb8}ST)_Wg!x$VTU@-&JbC z?tZSLg_TtlEKfq@wp^tK(ud@6ve*NY>56olF4gYQha9+gW2m2FW7r@__7r?(bNfYZ zdLKZpH>C6DP^c&xPCcC^`fdJau=UFR9KK;uQ~lSQ-BO|1HktD3mTtA-ln*(6aha4gzvlk)L{PB)5J{Qj1k?H^{dRMe1LDQY)5m`J#Y!A-#42uk%i z?X!8;$KMQTqvl1)zzU{WZpAM!4UZPi&}9@@GEQY8X}p91#?G}FNC^#=#s1WT*~0hL zt#QLgM&w|}uM?&uQN=|hT@jzx2w#m}Ws(i7B$Bf0$E)CGer} z%!HtV$r%Sv*!u7lq>!>t?<|;T`+b^~TG>sw)c|+iv!Rw56|BjCf1nDhfHZ7cW~h~@ z;gaDhnYQz^a&HA~vzL}y3|q`BCd5XHG2!=c_+NGw$u1_ya1r;h-QZ{lPhJo7C1yI{ zp@T6YR~M%xL4YUju@>8yLtsW8Z#cs%I~XgEAyzOO6)GhVe6C>-~^q z+-V*BzPXWI{Ac{hU<8*EiXMm1d7rSh`MUr3qsscR`gGg(3A0oJ2cF)Aq|oOWvXnO7 z@IDv}OWtlZdBSX^*Jm+ z-nQDGRzZ{g_BqxDa}zwTKtB;N-F;)hv5Px4kt%OVYrP zVt7##^u)q`v3lv2D>vJjSnC?-2UX8v=TyHog6ad7T;;v|NmUrLt?FCT_W$m>dOsl} zO%hXjbMn3{I9^^RzH_JB#Cvu<8`#0zBIgfz8$H)T4(*rH7^HmNKQayf z-a?HqAH@3>7YWxKa;2CQnTWk-B;-2yM{AI~#I4Ugbvy60olI?s^lP``s+lLpQxq+f zHQ4l_TW`LB5s-iSZcDLKX{p&y55d2gP6g+g%U9>Dvsql{Sp+e)__R(a72sNrlHz_I zmiBFTGCZ37*P%|0b4Y3XF@0N&%_54$2PL_XAZ5}5MGA+nQGqF$8W*GBd$JJLVyRr+ zn)Ek<$EW;vdMW@g9zk`EExt5?A%-;fr_23!#@NP}00CIv9s{^nmeY%PC8%O@Rp?3`9UcFsWf{ zb-+f;yBXEOeQ%McOX-K>NGLHr#83A*{dIgJl-SZj4gczIw|a5ndMAjUDqW^rn3R9c z=e6iV!oPVeAVnKCUs>oGBdZtlv>S?G7Vcmfad+||WCX&9BPd&nOr-yaoiJD3b9P2k zuo}6XE9p44xn$1~4ige8@qGi~$`u~lZ%2zTDafdC`L&ij&$$Up@ZU`UR`3||;#Vqm-7bR;2`6O^vlqiwm+!&QK zxF!4SOj`|HqA77wnOo5lEmr7oGjtoOx|uiDhBj408V>f7TO+&K$zA0pU1#lK0WAs|p8 z&jk~PBq6pw)PKr8z=d!+F}lY|b3sjw>94O%3CQGLLBGE?T}7+-eN&_x%@=Na+z}06 z4ZP+J?DIaz^W64N*m+pU@QEB5A+j3+<;4{XYX(eQA8HI`t==+kAJN{RR|hJ__q0q^ zWjg8MnC)1e0UmmO6-b?sRL`C*akbJR)8)XV;0}v!=tC4$5u?U*L7-1J`;FL*7^$SK zDZMGz!w0i&r+o5mNp6hM=D9y}r0H^D^^3rXqa1hA1k)XUjHnc&WC9^OsN{tZTp{HU zo!)AfYf7IfGs_0o*Z={VF(D5eM#5TO?ZKxnDPcQL%F;0)Y&042oiWS7OG+5kW+pet zhTgS7EnBar1Q$%Xri?svYp?co9^Xc_boSIlcVFm7g}eaX5T_4em6#BDu|^ekqV(aB zF!4CXkw)C*rChyOl2)CZwL^k2!`RpjR|?1^3r4rQN>O9kG!W;MK1N4^AYbvPb#M#v z|0R!_!=~+Ih5o&>zjT+ClR+Ry6(!)N z)j&h(f1~fVGxUdEB^KbR$a%K@QYbTfi8@;@;L0M?}yNGcT zZO&$gI&>Skh8V(FYK?;y;Y3O@%f*ns-@IL`z_42Yk7E+(u#g!_DXZgy3XV1Y=Z+w^ zGt_kZunhIMk_mMC5bH8~lQZ;3z?~6i1tqLjXHB<)6El@eU*Tw2cozu@3zyHezk02l zx}{6D%1|v51Jwc0KY;K~@{PPRG@K?D1nvza`?qYp9&I-UbJuU^IHE!C57~kHtfDU; z7D{peTCZ}ezYZ?zx4pK5{~LmrqjjMc2hIT+nW=3=$TXdNfedWIOCYQoK=iy()>(h{ zCRnEV=(BJ08G0u0@T_zT-RWJJQ{MwDn!_1g*^iY+p3f(`A(sT~1eUja-zg!R5CJ+dKSW@tE|F*IqyJA?n)|<`&81FD0`c@iXh8(fCabEF@7P)!+vB0;m0~VwBItymy&DD&6 zMtk+jXRdrdNRTR@pK`@CjHLcxQo{f>dMB2ami}X(tKzqf1Jk>^_M!8#X*0UaD)Bn6 zdy}*rZpW%br7(?_=(9}!ghq#j^qZ)3k~s5l#Xdj0pLBSB)A#g0e|^gnuzZ>rI~%jh z)Y59A)K@dQO&OU`nL}( z%6NQt*#})Yu5_FE_zZ(eW#{yGV#gWMpDy%svtyzujXhcvCNEV%C?n@dxXdB_47RaI z&JZk;<*~t2L4bsK@pK_uk_-dfXyeG<^{d1veY!lA+zd|0+=TwoLqK;TtPk-^VDgN0 zBhy4KW0G8mxgeIKLAMGM4-Dv*&DS7wCYpW)=pJ>+P{mY$dD)#S;x}f+H=mQ05rWTK z7%HU8)}&`~?N$by?YNW*r>$fp2@y`UQl+RR>vSbG&D;!NAUb){+?s1e77l3!#lpg3 z1Red0Zq*DovzwBshX=kv;mS6n!#T>}vr(IBij zP&&>;By4YlbqDAk*&(VE%}aq|Aq zqqQH$8J{4N0S#TfdG9kq%Lfd{#lifJ=V>l7sJpJ7Asug$sfR;CPmhqrq}k3Oy1w65 zU03>lSxdYsE|hW}47ci-I~qy{rMZ}w6P~a1YgI#zZ~IyzR|ML|R#X9mKral)A=M|O zwPm$>v+Ri(Lx~}3Ros6=6yN7-P}ayvSbgCKqV0!$BBmTAkljD_l^|NB6J&cgX9DELw z5@d2dAXBhg6B%600o4uJkcuvEZjZ{#+I-8yB>f?zW$ZO4=4J_WiOVnh{tqd|#%X2T zw|N&#GIGTEa`!IWW7$<>e|vL&5O_f)((TV1M_twVarDeskjIuK0J*kk8<9?rI?|SB zB;HW=(3=v)rf~d8#mGsE^~X1cn)kfK52{9X9InO*CrYbKMVx{D9>@(~lI$jr)Z6)7YM3_8wne~_F`-kB+_b&y;_*qJG%Wuqc{+XyTov|p0~ylkUyBMI(h>*3LJyo9L_OJ-t{B#&M^X zFc;#{89bd1i~t6&wPVB4^Ns`IUwL{%Fim+@PL6~cuEhB-JJ zt5c?Ux^Y?jyM&U|@!!xVTSN0_In%2{?GkVget7&Fa-&m({OlPm&jmT$g=uti<*_P)i-WoXkk zAHYFxRW%VuISMC59UBDu(epgYV$Zz~E55HELJkEoY)x12qoqI$lRxSn3MGF}m+BB2 z2Uxe9gFu{Jf5Zw^jnDc~^hGHFaIga$HM9d`$m~`m)Eef0N7}Faj0rjR-mN9FgVK^G zrpnW?Gsi|JQwK04E7HkYx+3I{IBkXcEwL)$<53eR<=5rw zilz6cvPMOr_|~mc+lOMPn?X0 z$i(u991`+%`%d1ugzQI(r>TPL-ch6en;Wh~Aty|jLtlOFTi6F3O;xlDCd!w~kq6fc zss{z3Yd|OrcE;|s?jpHNu7?A}`aEj2wi=(O2GT7y^|15yh=p@~ z$sjQ`4e}MT6e4+=oQ-0Uu2?gNl$N8&Xv@JUOBr38Z<{$k&cDqoEF}phB0DsbM3IME zjP~A=nnd%R`b6p|((*gmpx4@1l05*xGGQOSlqn^RQReYQq)uF%i#C%SJcz6d2`C>f z%H}q1t0+_ZzbYh61pNZqt;UEpzznPrs@P$VRAC?hS3DbN+3F@#dotpVL5>c>@BzC* zM1fE$KD1&yco-WABjp4bppHqU5siu?C-HNxd8juAY= zx`JUu^8?3)P|2h2t|77-anCt&*JFTK!+L+CfwZ*Dhy}8;FE!LXs~~p|)(4gCd)5*u z`dlZvw`{vHEQu-7&)fCLJRutRxoOn}HSqefYrpll%GBCA8MVn#1`rG(Tx=Y_sVRmT z8J(?w2G5W9h|xWtew}eVpFe?e@-3`hz$K`uut)T8FuPoE{2yt{9Oto%s;tbxXEV2j zj8p`O?4-*>b#)Sd{Vq(U=}ej_Tqj(SPL$xjuWJ*^guweqj)Q~K?}pwN1sf2K53`f^ zja^LA_T5%dWdCb6)IdXdGP#!t0L)29( zsBej?#XpR!L;UIQFL{EJ+uZZEfiv=x2zCl2)P5;XhEjIB8_+=&ryUxTG{XyPW0#I= ztWAS`iV@*HhQp0p#F7bmOgY>FoLlUMXqmKa%s4+Oj>258>cnHtyNk{ytuf}hOxh&< zJ1F}HmMDF|NlYDm{a$y2f474pZg$<6a3-x0MHN}41H(?)hSfvHR5AjP%?MSd43xek zI{`VyJXmt6bfm(K4_zx(Y)Z5Lc}v?ZKpf%2_OQ5);B=D@-f*qh*;iittLcuzkujuv zW&jm~GX4{Wrl_!)TyLX6=R*thayn61tPTArEcn!I!b`u}wDx{V4Q8HaU8=FygkHN* zhV{b!T)*9F(Vj}fTX~jFH{=wi>)ftKqsP^Qu6{9(Al85_)RU#Q%wt%_RJj}b0|sQ1 zDvc0gnNO*a6eelh2*AUGXdUvD>58~e94TV0*ra||+-&8k{q=n)#j7g3RMb^6+i3eB z`jE&SmiK}|wmxo}C_15FfM(;<= z9>0FQus8$e#eCrUh>1U$>yVAzVwS0u*MF=TTW7u=E+eI%Y!rkuFjnEe+0iBZ;dx?t zf1;SX(d?Wd_wu;a-u^$_V-Uj{tRTLJA`Bn9Or>%J_JMx1{ zze1#uSQCFF(@6gp@OCyKBXboZBhtz`07vU*G=Ee)+y^g&FcQ#ZxYLG zIB|T`XczQQtdcs}4!YpvIIEsufng11H11YiP%)sKS{>U@yc~Ph=J#81*Fk9DYm7E9Vq!f$iAX`n~%g`i;u<-c8 z@2~tWy8xrNEA5AFWD&8Z*`BDO#U@YD-yV^|&lpa(^V-$q1PCGxdU<<4z}pdnst~IN zod<7;6iuWu!`{s~1-`qf18a&-^iW23S0ZgfGnc*+*B|N$sC~e?jxndlBc+##$EPq# zYbo@>r&_o@hS%q-Yg$sMrA18yHHxwZDfwDQ!Tw9=TraMH=*0S3B91&UJiM;rteMTJ zp8O9g4KT#dFDhR3C&-kv9%)2*6n6PgK5dr|8k`KnmW33(vQRuH!G+(_H{NO(9Li*$h6~; zY+5n3`tzr?hLD21#L{>7+B?n*TQ|g|MX?D=!<$4^TEUkuLzg<}uFqxg74P^}C?`>M z-uTr5j=5tQAX0FlXdfXoxt9Y~!g~0qfR_k^XOSn(W>MD*w8~4=@DKSz+cO;T7Lg;- z&eB7JlQwT#xWh>CIHt&Lt^3e=4!y<`-Ea*!k zNn5S?!q|=5Jsw*gT>cK1^wdWhSDk&zTBhcUTIObpAQ~SuWsKQdmlulMs)N9@$KKh1PprZ(489rf zXv`U5K#FLlj>g_0yrMe(^O;@x)I1Fv}#~Wr{s(FAT~5LO(G?z>byGrT*lIm zmAd?!)mkPtH?mi*Pp84>u!J~6U{O?(Y7nR#P-G$d`U&BA8WmMcwsIL0=${v<+%_w& z-t8?a=@h!YiIXGR~ocU4!`e_)$j!F$k`x3MDf{jOp@b)1QSB z##yiuN!$bta>ns5y}s?qhwCs!9Jf}s=9qC1>FzLoY|-bbonX#P1_fiq_P+(6vvX;P z$#SFw%@_wOSIh8_{D5^e{j6}AaQjRp2cV(}hXcWS3ny`66oJAd-Z_vZ6-)`ru>P0! ziQKAp0Y~2z+^**{d%mhiQ=|Q75#&3v?n}fKmi8o#e@B@7utPf4Bf085lvlzj2a7#> z+$?zKUum>2p0}wnzox?=7Z{TfeNsb!6TO(OFMA{VsliAp;`N`BHqj@7=p$l@6ek~d zGvWA^%1u5pTxKQPGqoFy{JR;dF$+Xy{9>OMaqJ}yE#GKm`<#~xx_!*IpqU5o<}JW4 zSHjs~W27Rif*t^$_%elSQLQW_5(FA~=!~r(vP?I7Q~3733uJ1V#_x6CvBq;_NB^=Y zlZ{V9Dpi7f>5*@*+2N8EHpWE^@87q^M8~ zxjJ8~V?uO1c)@^e1k)iPOZ)wa=a)sew9Niu4QP&G=?&Ba_^r#i-VAi(#jGfw}onG%Xz-}UmQf1)>mz7VRYZU zcaQbzi<;Pth^61t_S#WI))@zwn=SYO00mCLXnN%G1p<`bph9leq7^+l1AP^twhWIx z5N~U?8C_4u{b|Xx4q}5pV@dVx^Xwvyy_l zwuImMLI%qXt69kknpQ)TES^2AwNS`DG5#o*{6{HPN1qnp526aapu!y^xA{)Ly{q6N zI`^6sy?8CsE2h?N-_Tasa+z{P-2&hTnT!K;O$& zQtOsx=$oxoCR6MY)>09!)tPeDn(6XzA%aVzz>#d`<@K!vk$}~Soh(}#KEsy9vC{%> z$bPeh$F!KHUeF*eD*-fGsgbP=1(jC9BCem%ut_4~<++`E=m)>5E(fx*z6BEkNRr9f?vrcD;5&Izm4hyn$!~mNQwT*7I(B zz#b3X(@_wWF(J~W*Gv5d?EHa3qVj)ORcdug#5|Q1EL6?b*yHLBUJCUF9O_oC(UH#{ zx%oEdD=4b}Tp(tsm0|$tjniG~%>8mxiq+s4d3h1asoGk^XwXAfg6bL?o*7k-UG8wA zp_v_dv^M7x@OwSJ{qu#~kmOBILr4W(7Uat~!wOYubfi+uu%+XAr+{k?ky~G|CgUF( zBB~&IJmnf!^u&q426dUItu=&dKlCb{OSZr_V_Mg}Y$@5eG`DB3|JMSr`g;dY`oF>A zKL;zb385%Y%7PsU184BaBj$B>!tW>iqWT?5zK3RZotU@pYa50_q(q_V^5JG2 zBQO(`W(Gci_p{*oMEC4w4{|{F$qCBc*~;i(gE|^6hvlme{02Bh(+>&)z?o^5eHDyJ zVVE{pPP|}-)7L|NRy8HkQ$Tha6YyagSPd2=%=h_lI>;oynKZ64RY3}|GULp*EUplE z?D?cvCr9`7pL!Kyv=j#PsBl2*@ORgDzmo#25Vqa^Ri=%{v)?b7$Lmtm$p+|owjO$3 zRbaYwuv&m}pQJ7gE@SU8xXRoIhE+T&=1$?pc}kGEuu(8+(Uuxkb~mfQjrsy3i+9|s zuj#(td&j)0MmDtvVu|hq7_){hOKz{#H2e66%oGQulP~nuogSQ@e#k+&7aQtE`n}?2 ztnzca+H*5IA;_Xn6Eyk(1Jc`19KIMKzpOP*k)T31JbLS?ytrLFFN`A2JrwF=Z477S zTD6~pGaKir(EM(6QX257x$(VNA{AV) zkSi`xuy!?NqRQ5>04(wxEdwPcr0dm0r;Ysad4o!}G}#sYVUPV~n+;MOzRQQOn2AlXn7gUVl>cD+?5*4DR= z-FJDC7`^?2dfhv|^HjI(=gjZe&YPE(C8o;J6ES@=47}72nb$M6fbv?CwxwP#7)g6` z=^Y`9N9{fJ-&(?gitn6GSYQi954(i3w$x(efc__f4w4@?Ci}-Ijo$)A8cHWk1yzz{ z2X%D*L2d=~+rc|E2AE&U7yc-w+VRBBl@+1myTIs$y)P(WO*OMLs zXx|>yzQqB1inWGZ;qp&)hTZ>y&yhju*7}t&K|*iTr$uEkf%HLVJ6uiJ{=rXF%%3=Q zij(T1*xdmb7S@?KN1$AQ(Rn_5>QOxBq1*c$o#sr{&9+@u(os#iVkPB~{kclprOR3Z zxb*!W@n7qox|IhPq-NlOdm%G$bSbCAH-p)E#~H1Y3|OcK6*<(Ji&)L7@EmqqMGtT- zpR$N=!qm9&(x_mq3%F{>Ns{6vyDdH*6k0Q%LTSZB;#7;`X#80n!z$|A*jk@rEbbH) zV74WPwcRLPx-wSmKoV^*(`PPXrG*0CaHyj)Gy!v#zd82HkVNYZc(FpdMM$b{o(hJl zE?%uZ&#N2-umGyHfe)W~S|A(Pm)W5px#oax(D!Ai_iQfD^~A<<+)|}_`NB^PVzi7H zMa5tI^gA*B&v#dCUC-oi4~g%9I_S>-9;s#9YI8fcG*-XMSfPvVP`{gEiXS>mB6}@D zlcw*T{-gyWy$j5_!xodB$zD%UF|YIvq@;Dh7G_5ai8vp#r#%1I%vxm&jb|G?1gmT= z&sk8=3bQHt2k^!e722>@%wn=NzJ1IYjg+%g0C7q#YDKVX(Uz|9xQd= zlY-=WuI=6)C@4xSBX@U1!u4Yep@Y}3tVcrrJ5EB|FInwzgT02eeFWbz?aaKZl%4%( z%Kak#=_8L$q%hMG=?Y5J&GfkXafIX6(&c58p6Q9ikSh)MeJ}8(83AlahEegcxVU2l zx}o=SsGYUI3sK~7hoE`_=~9P1*N^~gz6h+o=x-N_8AQak)ZpQLZbpVE!Ei_hc{7OSIsiwi$ zSgv+aqoU*P6m?7$soC}rV-kpD#r3n+q%FLoxWtxIDj1Wy61^w zW*6cnw@s@clTG1`Gzkg~72l9RUv#9Fi7f+m&l%qk`8|5lrf;V!)5v{||EBW0#E z&FJk!r^J6U!P9FLMSxO*Q8-O;<%LF#*Be0$C?SYQ;SQhi)!|YF*mJ4UY$s7t#!o=}JlN-vVj-d=({G_ts$h0^{jM1CZ50KX|G7lL zybTq~X)s7V5%{B>q-25u$7Ds{l>SKjsoMEU zy{5%Y6J>&TA1&E<1Oan0BLH$-6ELN*$^$kGd8&*)M_rj-Q<6p6Y=uMx^Hbe$6-Q7V zoH|7zzXTP!!H6KueJUje*<2*Kl+99Ys0;5? zy@4zUVQgZ;8IF0p)ia)@ydf=k*OX&IktL#{#$~_Ix6^g{?)k3nrLU>W`BSyuRkqW|~yrgw2;{8$)sPb)C<+0-@&azgkBL_OOW9F>_0ZG~6@njPX9F z0#`9Vwb||)#?;~yV~=qRy!a)t&U!NO)EeFoGWlOw#_=NiUP(~JpDb=6(Xo2V8%Yp} zb0Yg738eZQ<1f6l8JjwRKbBM42PQ$BzJ^$lW;nkw2me>8l{f1sRTr@pKQp(aG z@w?t8PV<9AI5x>jT@0193ojmB9Mi@5K_h!zSCmJ`f3n@s*QN?9;$;Y2QlG0i~1#mSZVpzQsSVG|Oe;*K(RWo4rd z2~;eeGPZ1$@G}We6O{I?30!0Z?O|vY#y$PUNAKXC5VxpK-gH(&9OJV8Iio)(E(sTY8 z+NqN;@dFj9JH^Udh-HltC-13-UBUB`ED))}oN897@70N~W;*q^q>o?gOF5h(bnJaO zo`e5Og6j<%-|+v*9M7*1=;{+#UFmN{8zdn5uks+40Qv2`hz~ zYX5i8JREoBq;)<10|3ka_-Db3J;h{ZT#K3V_KWPUac{qqo94@DS7@Q$OHQ=+C9g^UJtWn7Og*!Mdb-nx9<;`eZfv^14=L;3Tl90GR)BG=jD~N$>Xwc#J;i- zqZQ+^p_Uzf@{qoaQAPf9+pzLPFe%1c>QH(&e3UV^R)>knbn!Jb(6I zQdXNFzDDQwQG#@2+<7kNE~pcj31AVfWc^t`o+?QO!uaV?f%x3tZ>n|@<-kKGY>8qT zEmGBsRCtQHmJD$RhJ7yl6O!sF?46QvN7FX$!v#1N3+!EQ(r7YRW^PXn5OiG}lRqC2 z|7fygKi8hlB=fvAd_JqoF*Py@^1nYUz6-v2a$h;ScK?-cB8G}ATwOse87mZnye(3ltrH^CmlHYn;64b zIUk--4>mInQ@BFj3&h&SSdlLJg*ahn*tGo-uxB;?3jaMFwyRGuycM-$c)f3eG*Y7T zqx&YZFvSBi>1b3biNx%Lm0oP#xSs?hsZeK_w&Omy$yA+;`hI1dkt;;E;k%ifb92xdzC7^dpTD-OYwcv=jJPtNB;pARukqKY*IkT^@5Cy zPgex__u%RU)eN1Df`HK4RIn_+lLN|VWDM!b)4i>Q48%Ou^xdj6i}(9Wt<3#tED|^s zx=-rPO+IbdE*HM#Owq^6wxE9*dM4o$bWqa#&Y3)pDZb47jVzr_*_8?|Y( z!kKR$i%Rc=yLmjW5UOMVCm|`Ky7qpDe!RW!#cK1_YF95!nr_cn zB+h?i!4@#!Z1tcqZ-o)t0a3hFZO6PmtDCC+FE=rYa;I0-zOmtCe(8aSuk7z)n?Q(U z8EPBaj+Xb@-|SAh*k5+j=-5MPmIrQsgZwb=a}EG3B>&He=iyb2%!D0%;Ji8AYcL!XxMciL6V1AH1N?!1?{xD zEPkHOK$k2w2PCK?jbN{iNbn~{W@d2(>>}yPl|B}i?H&AxK_DX;hR;~NB@YqTqarJw zwPNMs0zAIJh`^LK$kz5<#x%%pNWWAUsOeK-z@Q8zvxOBZ(NFHxM-FcG8L=)L0m27I z5%HNA5}T#mVyp|5%2s%`9F1o2wIXhYkgBTPL=6fEC#73Gf0-UzVzZub4 zXPbp=yYHiCU>2A6)Q(ml69R;}MndI?SJEn=TZ+=5yd00Jy@_TIS5r~IPnwi)8XVAl z0~AO|bSNxMre_-zEgn%wvq{F2QJ(rPWMfFikvJugu zp>qN{=+5rFLBC`0E5+sh&R6kq59!%p`j(~qU!k!*61BaNWUasf;A6qNMox~21dtZsq4!u{HwuKL2pl{x& z#;A`|AoH8teK}OQ==uOi=r#Bi84?D=_djD(&}a7>$$vSImDR%}`0a ztob2S!WB`S-GXa-ud#ec=f}VK<&fIAqT(-(r*<;L{_iH(QG7zrQ`2x3@N{bBYI#Jy zxl3)su@Sh&X_7S>Mt29;6qvtxO(^%g3L8K(2}jiWp&!Iz;xG=%ETYh+&BcU>5x@nSgQlTNAfu3Z+1eNKrNag?AA_ zpmD*Xf`e4(Jw%9^3L-I!ha5y8+FY_gB3f|DfI9v8W`jn>1K%KswJOiz%e8<<(7Nj; zP{G22-{FEI#dRV1b;+XTS3Trc|vKma~3EvHGw znfLaTU-D-B^!$KXT;tEURiiq}-L-j_zZJV-=Jx*g>zYBbO<99`Y`B5HfFuU_#>>-- z;27{uG6#NaEBAk!oW?of2{MHQm-c2oV1kz;Q}Be_%k9*}tqG$+tz zi)yI7SuN&K`)Mw*ZeObQrVXCYK@vHh9LcjM7v|ORd(I)!4*nZ0UtY2ertMmJ{0+x&v7lWtDf*_O`b^91o^xOQN67A_QRwo#7QF zW8;7FMo_QJg5M%t8|!dgdBt{kUswG(l_{j!k*}o89;W!jP?kppnc)ZSd$`)abS)_$ z5eJ_2i?#sZI%R={@H&dBuDKb)`(L7)Af+z1a7$0M1JoP^D#EkU{_P@OpI;}0Q+L+3Yud&{t_BkK$UyEBj zS?g!^VwKn^{V3C*6KgCP54y+L%%|>y=GOy_$r_Dho#vF%42A?7mqbGYEM~@tJ$P>B zk#<)sWrD)ShIE1Wc|(HH;U`7S+iX^K@kV{@yJsZX`&eNTjTA^dmg zXaYEx1$Rr5xd5gMh7uL2+lvygDG>=P=V*nC%P);Rf6*N^J`ZB`swA7uKaBa>ZDc5*ee|DtJ0( zhg*0^k%jmLGVD6?BwVROnZlxkdxvjE?8qAuII&Ldn>mpCVgf|!E0HY+JzhAKc+gUqh~~@DkZgp< ztF<_J$H}P_PM^*R*`94&a26bM!B(F}JItd>Z0$>k=rPjeom6cYvM*@bvWZ18OiF1*B=H@e`_V>jI2pjp zO&wiNa>UAKan-sV5jnNINls1%;?>mT2U+E91|<^T0``_D?0L}57#Z@f&q#xjKbU~A zqxRL}nT5N~ZkbHS`~aIghq`e~tsIrz)gUYR@sr`F=Exh-uB_7?NBCf@(YgwH+ulK;um<6=|ip9Xs$Y9Imn zgW{baAU8$gz~mIkjVt)&suFzvv@Qs&u6Z$>c$i1Icfi*BnfIysqE4QNy^BsR6B>BT ztjVP1H!?UYR@kDHf4V;EhY$_!eTM1sK&bQzxGq4EmlU1WK?xZ=Cr)0mUnqos_g|2N zMOi0)AVrogLM_K|>FTRPrVOqKhVvbWJy8hzK_^FoyXny1n1~lD3j`L?Su~Y%>^tvf z{yy*dUGh2(lcnRtO@gZ$`-WdJbry;+_>dd|T-J&OkzCfF?ytb}H>xc%Rq!L{0( zbg{|4c=70$`-J}U6W=P31>kTOtuJR;BFtd2qdRz^WUDt;7VqsFPzyJ zOv8dA{-M;r7UdjGDm=q{@d_~#+3v?To3E$c*oeNS41w`j-$bMs0D08~FdYdgRJ6Lb zQbsab*5=oBaBzZJ7NbCL#T|tZc0n2pf#jFnGxQ$QF0N zrb|*_ynv35o*+ldDj)6C5@MMF#*t>*!;O_l-uM;?T?VFedCB~Fs$_-yJzn5W)w4#? zXbB`Fv0yveEK+6581rF7Rs6JK=sd}zU--gl^XY3|ifGRTKXPzM334yFqKN++ok|Uk z$~1&3{HGRdE`omusI~K|pT&LQxv--rE$Z5h02-7)(A1VtqFi=k#yP*etL&P$U}n{( zH{sRy>f%)F9K#ZJzNQH&eo3Jo$ ztXrnmM5+{~jTXGJ>(S3M&L39Wb{z2--cJJqevPm=CpR_#@rRD^P+vX+YY0nswLvcR1l=p)Le5AKS_=S6#2+GJrpkLy? z4{vndHy{hdJ?@Heyg?p-=i{M*JS@VZU^SEI?{W`38lx*@gc_$nqN4igl6UJz$m;!` zvj=Al#j7)D>sW}&7X?*G54Gv(&yX8X(2$>8CY2fS^ipSY?c^;30wP}hBV7jSX@ zNsp?kYV8Sc^UDI{&V$y+6xeP5r;_TgpT zdxAy!_v!%S;`9@B0p}qY5h$9UpinuI7ph!TsAFG4{LGYK`0L52wwJ1o$Z@C&- z2M~#kZGt~jgTaB=qK+vVI+nq1=5B5(H!g~UWmQ#=ekD*54^6Ch2(4X*u18~PyJb~g z&===$O(g>Thjt`tab*aouL?)eBIRQQ!rs+kB`syrTz!pjhn;fyP5O_Tbm+;Mw>^>A zKB=&S&cr^e8=otGwc^@UhJXjT?;vd=p}CzCQYdG!ayn1or29~8PJq?-h@e;bzr2)U zP}&pxPDU5v?chLPLQwahP1EppEy)k4xCSR z$<#@1EmRPA{gxtI0cO{fK|tPn`6rmo9mzRs!TvpfV7US%6Mv7QDUrkx%#utg$PZ zM1nLf?)VBznE;q?R7IDJ07C{?WB_PBZw##{(JK02o+Cvy>xCn)s%_O^(e%}Z z*NR5gH|CZbRpeA@~@tM8v@A>X11uX=`-e{TfIrwss>VB^ARKhbWum=@xxSAJNXn za87xLu$rq&X6AFnU^6NTyGk$HeHe;5uhksc2(O`qKsV0^{heuG?9n#*+(A2%BwenY)orJ0y6~OV z>W<{2!ODN#y2+~X^W93%4hsj-Nb#<(WAJUq?B1($vhb<59*N^}O1t`T#~mcFM9Cd> zCPt3quiXkN?<(tfBUTwFF;!5qw-XL>4abqm6I{N=(&j{jg{IpP-8v40(xc5~3no<< zHIsssdv0`xwj+Z;ZYyHn|7=j?R(_RjI$(J?Srz@8Trtm&L2a#lh_*!&E+;`vV(>P& zTcbr;j78pOw1>~u?aH7=pRO1op2IC}WokIfSp}tOma~F}+mO?=k5SSXCHD}T=xKe|7P(b%#iql)F zw(oI?q?POiy5lXC1gV<>=N?>==Ravdg9>1lKC5EtoNO7m%L-|(2k`Y4L1o+;yCW+A zF>Uc7>z%Z0lGmu#jx~383~rXlVjKo$tBYD58$Z>y_g{5c%m4B2h4$c#1utGcIlp7}f!=i7_{u3Ns+2NOm7^{zgg+tCN*AgCJ-*nPVLK0>2HupF z^|^>@$9?HB96D8sl&I_Pv&aCw7Ec{EW4jcHPc$N9e$zYou}H;*B>Zd&tD;JpEtv}7 ziaRB1v*c^vIpr@ zqw#4YNt>vz2S1}?tXNmP_2gfqUMvb32rS#-ED4ET*1ZpLGEUo)Ab!ExESzq~&L&Y9N!& zku5r$OqjWXD&?!}>Yj>@FI&(LVGV3tcy>4}gEEncx)g9SQ4V{xlZ!+Y(;Eg*S&uQc zE_uMf)y*F4VuXPfhD35W{(f=K_n%$9a+Q9qrb^~Y$d6b%M5D}-TyP|=nlEGkf4hi8 zw_OzWHcND?i~cEvD}f4-g#-|KiJ%ZBYQaCwY^eDnsMo5&6t{1!8e;M^K!p+An#wa@ zgz2K*fLp?aGa?jzRG%HYcYN}?YuRyH@!UDf#q>+y?%b3A0hr(rItTHeH<)izxD6CM zU2Oh|-gd^%A5HJoE8|AWIivi0ZbO;iLF!WT`m3p=A7eqX@H=1V@r|~g;qrFfFn-RG z#@W26Y0Ze<&C>XBNBl3#O~gwG0R7yYokEv&pIf;dt}}LiS~4W+hp|woIEOgJ5g%JQ z!s77kTU>&SHQOSVrB9D`j+)7%Sxz-I`oGGCD{%&!J%PsWDNO{#Z2h=>xqosvQpMiC zma$f#=4+2-IUR~65C1+EK>m|ZT;FD|;s4+1qUs;`CjiDedE6{LBU>DI^D*oRsVKoD z)U8dr7$&Z+UN$T4qBq!RtkZYC&mX`z>H!TevIJH#UH0rcWPne!wuKS6Md(kM`S>vU zDM2X9=>S>`u&@z{Vk3CDs`@ADKTD=3m z-T3!#xAuA(Z9DInUwUktR{!94-KGJ<{(sH_hrPnI^L+`d{kkmR znKWjD$O?e{b~BSFIkM?dKgQdWa#TpOwP5KMhnICgvb~Ga%eii6(yBLNaJZbF_arYW z58RZj-8@egnR07qwzJ8fQL8)FaMi@O<*Ru}MS?Oy5iJFV6668}PcnXXfjC^_Dd6Ku5|q z+@UmXLkpq&FZIkpg!?n72UI-UEwG~=l8AJ(EGv*Oxs@DA7 zUn@@=6>@~yyVYa%4*S>Cwh4qXA_&j}tan%v3WGNrIYi3eROwrLhf}NCIaqR5Nam+WW@g+qrVp z-Losl*UvKj*!C@taL@TW`){Si$>U(q6IT#iRB3uFUAwBKbilrgD|XUr%aiX<@!M5$ zu&e}S>^(%=+h`Qn*d@-MQM`_b87=;52#UD*!d(GOed`xjfy$Ni{R0u zOFb<7jCH>O1p&;I0|eajGk-HFh*_>1`iBa>1i~iRSy@Gz7HP5-au1{#M@@W82w?RI zoTPe+lY1^7aZ#J?0C#ht%B5|z3oX9&YpS7wBo7gYN>YL;rY5j0eK+AeRga)dfL5DR ziLb#ypQk$!&hk^g`n3Cx-mS`~8dOf1~+ND=?#rVJy|9 zsSj4rB+d+*)(%Np(0iF-3Y}7hNW~;T2z!vFu_$ptG+6Tf00%Ata(HrupXI!G(vZK* z4Gx>YEFuxOSAB4D9=D1;U|A~=Q^UZf=Y?ukLEfM|(w5=-lO45E#$WamWCN06mS4H< z)S`xNcCT&E=lNwD7>2*UP843OC18kW@!qA_lZ&geoZ@UNNRkGo{HP*BSNYb|FBU=N zK$le8vi3*0wq>SPXhas4`0p!zY@G^X>0*_d5`hdbkVLR35H?B;&}p4o5LLAxmTwjS zQFl4~uP!19J3J^w(!!nBvBYpyM14yO!TyFt#nNX&j4(t;;95s0=Uoy7vhK^<>}r3# zf1eB*6LNA*H*pSM&DMj+yaF7S5g!w$c6_i{PVbSEP;!mpa3!T3CL_iy!qamRL5 z!nO3Ra-Vl~^Y`SYs-oG3GtqRY_8O+(o$K>HwI&Oz%G$>2E!Z6Dfjb`8-x_I1JMvB^ zn@L*l-}Hr|sZVn^DIex9GjQ+i5Xh`L9@va)Ojq6r4G|97iamdU^4vj#!R1=p*q!85 zkyuyzeh}%x#j0Owd{R~Iq5HWHtWm@S%Pvf%XR3)wI21Iu&*MlfcYkPBF85t+giMiH z&(Cym#76^I(w(B&GAVF4_9KSDo%B?QuQzf(_S}g<@?OzFMRz@nv`7MjVnb4HLss8z2cPggt#aKC7OTRc8~7$G1C8iCnc{9Ns9f z5|NHkTSZ-44=09V&s^(921)2r9OJ zl@U>|bE7Ld((m$xB6$qN2qv*N_e3fiAq=H38~5G%uLY`z$*{T-QQ<`=;0Y*F6za4p zH#`M{=%;PCkZ@vqKjM$#faGBsMekAMd-tyh$Uhs;`%driWP5p1ZQQ-~5~VhvABY|7 zV_<|qB+N=Ix&_=-{+MRywWXw*CQj^Fa%F8fX`6ge*kZzyz4U&1{Xx3_LbrCF1n`2< zqt-H3&kYK?9=q`mJL#p7@*QudX4&UzRI4)LeYx98=GiMqCL|<`6k24#fK#JJh`we% zO$-og!%X_B4o+iEkRq{@z!Jwgain`{M1h~bwsIXpB8Ixhr)&AdRXS_Epgh& zypZKnJP)d$c-sI3M6b<_RfTLFzIxqA&GjX|?#$z1LpY+UWKM(mxk~)CZ(DqkrOP-5 ztNWJ%^Q%c5hNG%Ts1zs+s{<;|m7Tj{lOSJ!Yzh>`Cg$>Ar0|x07a_Q>=fmqQe1mpz zQBe1VD3->jNs*p@##%k8RUv;ia=D8taNj6aZs2EaGelG!;3rnr(hv3R6JQ&a2*v}~ zowT8%j{T;EYC}`3-Z3e%x0JxaTUZhJFDwQ<4VfQboqNa}opBNHJIC0SM?yy^P_RXI z6DN~zq0wcQAtLqIomVb!#yqLD`x9cHJ^K%x*O;_>mvs*$cn~a8L&USpa%AS04@+BU zZLgYbEW$Gnkc5J$WlTkV!tA&2rE~r_Nl6_&B zc)44K!5SL{IK9c+h+v_RxG5hje%Ay&}b$MwJu0n$JutS(<}4Il>fWIf=@TO|2yd2lAavu`r2&cRzRW?BarI~=`f`)7+mR1^?O zlza&89kLX~F!Ed86o#^h6m8MZfoqqJVWSao!5$~s5l~5b;bud$T;vf~&2`D2p!FX< zw92^=PQ5oQSB$N>6gh5q`ndtM7lM!H$Wi2zFjYDErlCTUu%;?=w+Tks3)ksTbYo%( zM-sHQgJdSK5qI%dyOvN2WS*DD3;zuaBG zh2^pTuObNwrvB6GdK2hSnc-hDLl2uz)?Cmq=-9dLl%rK8Mj5gKi1qt~nAL|A3)0z4 z`Fu;5)pY`mMI-4p{@azCMrB-gvWigiCoO%cW(8(9+VlGvykcc=qK0wm{RXat-}~`? zUu3J)p1#P-2fbSA!6f39pq+UW$#{wHCV4EvDt?{IvZ>;A9njdaA+1LFV&g;wx{OR- z2yQ44O|j(jPJLEOw_>`^)@?~SyW4tM@^Mz0^Q(IM_%&L zAy8pOi~2S^u{(5uLCI9p+6<1y&BU2B&42Gy_AaB^rj0cVdne6z-eNkyq-yT3&UJvDlRJ2Z)`ruZlRz`Rp~1V|b^J`q)hQ zfx_-tMVdF3i;@z8)o7bn0^pYBG)=~(HGK}25ngp7DyqQ9SqINg7@xLi8a9JTWo_U+4FXA}xWKU?cE^7aeE|T#yWTTd@3Aw1nkum*$h~ixMq8{QI3qio zI%|CT0N9FXr5eX3kz{>-h44FG?0vYbIKL1?eZza?a6TqY_Oc`3d!nfPZiJ{*DND%F z^{_dcRFo+0eN23evOOmu!-vz304ZeY5+dkMveZ7%|CXdyj`i|@Y3uTop_&kf{<`0N zJuw_5P9RPx;v2(#;-??AoPky+H2Z&)%8wM{-6`p!30hDx8{VSZ^WZ2e zd-plU&`Q=yn@GZi<36Vso$yi_t5(a!dC1zITu~LUPo@m#b-sD zu9Nq<(2mwxaHTpd3+|~U6+k_(H8EZTbl%tZ1qW4BJQx3NamqF55t!E<)NcIA+c+m4 zt4;!7TP4O!1!^k+^bFw39TowuhD>6&y~9iw&m)?0fkAfra>HItN}c2okAb9N2%iyd}{%RU%Khr!Aq86K3iTY;DENe28p0UjV&; z01;e_?|AFQ?@;kSDKd)j40`j3IWRB?LP)&tVf4QZ#5@Z>@fR8-bAMD_(8m>b%xiKp zaRfTN;li&>)M-!Og0-VG*VZ$95#zOGwYNVrUo;571L+|NCN?k#jFVR{c`~~A8);o| z?w*S+S{_IpTieQgc;^C$(`Jl>7(xaQjleDdMnOeUNT_zesZmX2c(Ni%NJRE;@(?}D z5Xh+CyJ1xM7!0g+2nflx*T&E#*nrhetfgkzh)SKb3fxiGJYkS(19J>Nb-6EyLKs&6 zp~goAxUOZ!#Ke62innKjCm(sG+zad`?9%Mq--u()HUBm@u}Ifw8sC*dnYc<&k4&}aoC%sQ%(}k zyuh5a9;0S>bG6qtIRnO`Y>>1!8ZTl$^(B{|opX3BpQUQ>;9LYx+6|!+Jk3_UAJ5>H>A~t%Qd$Hv+fRmO22xJd(u(LP_4Fa zGaWCw2K;w$uxRRSJOTA7ar5<2HCVy$A5GcBCv)S6qVE<17f)8lg?#RtN}2AK+Kt^w z@D@%k{=z$BM7jEBF%?n-bO zSG*wyzVJQDVW3Z^hYctjt5Y*0AK3dURXg%HCRQMmHB_WoXC=|Q!auOG&;hP}hdoT$ zLs3w_t;Rnn%8m-IrS{N365tL44IWZP$UN%CiYDM92YKvIu_yA{J{qBz5JCvg5|I)Z zE)wLhD&}9+#ysW|8*Wp4AAt;JUv5tFuHFD{qJe4bxW(cG`TQ4d!KGx8bDsj@DshV$ z6lTBoel>L`e|Y}e%XI##=j3XCJd)Y(_R!@UH%iLO$!``~6w<)7IkU!F?j(d!rbP0|S|v$xM2t)t!08IdECnp; zWfHbEMEDNMQXMN4reMnkJ|MmpSk1q=bm5gJ2t$5@i{{x{B<|^fym}*TLDZs~T4f2e zJVhPMN!7}=BozK-BOEvPbnyy%N>-iOcLgi2rRT^0D;duM>SF;Gc{TDv2s;yztRQ+m zkUA}*iq4TF90=3kexDb>LeHBM8CrJ0b2wKM98SK{KOmn4%y?+G#Xw5D`;sR<`AdHM zFD-+uP4Z_U-P<40n zZ*IQVh5MLj6Y{tYf7&~*#WkN`K0XGZDaFK0sa|u47pV~qxOv6IqT@7kC1sjaz<;;D=+D6Q@p8I~s4#SQq4A}& z7ojYdAo0-dy1lQiGbWMSm!!8<^2OTbSB}*t7AB++L4msX$!ZEZbQAs{zwl7WDyl-_ zw@qBJa&82x?&QfN&vn+PQ+1?CZxM#scn1jv#V*wW3YiAlAN#b*j!lDh_ zNOE2VPtIh`$tOk?<{*VD+aJ2FERUbA2hV~cgdQHs=j+Wv-dm46_BPoAJ-3}PMoi@UjX$ z&Vet*cD_k<{(+PS$oHTiR=L9DpWjvIxaUorMyOOEPL>&UTzrtqCq-`Jf5E%V;1x89Y2E#T&XS^`%_l3bkZ#u@`5(w4Ayy_V zVeoaguLY>qC{KdO*hv-rmkg9{r#L+zFk#QDnng;v!bBq3gkfrgPW%>yocX(V0PDHF z-ph%lh$PbycbT&a=HC(R$&dG!7CPflUi8O_R&@`CiS>!1Foq2@vhda%6)*lWT07W` zkRgfysRi?q+no23a_W0(MCQ|xgshPCplz*P=Jf<1*t%IoBn81vYU>HYw>hj;88ygE zEuOxlUv)$b(Dyf(i|i(lEkKIuQ6^YfqpXp#?)xtc?VA<>%4s3B_gJ89-hYiE2@C`U zeoTq7C=;ExayW0nS6XP#V0lCBdCP9;i9K2OKwlfO^Kj|S6_#k?mn$KW)mq%N&k*D76(G&V9DMS>#D-UDS2eWDW1_dy93 z^i9hTPRh7v@dghJ=yXajhs|!%M_Dw;)tiK^uVaH0m-v~XL()khCvAuAXVtrM%OSX5 zz%c4DAuk-9tUp2B!9&ITHL>09QnVK)PORZeQXde5t_O?1bS6aPSqM)g?_S!lNoR|p zxh6@+s&I`z?=iqGT>pG=WshRK_!Iy9*8dzjx_ha+^78VWG2wrDBsczduHEm)fxUOc zfq#9nV&~2K_7~XdS`)MX7xNq^j`+hIz=?E2DtOVgBKjp~6RAmPDArxD=g}xSS#fTF z?)g0Hu;p5@)?!aWW-JtqhCr=GtTP zljaoWnm0Fm$dpDwP=?a<*UiHMm<$Ihn%>NqU!%w-U8OpIBX1CEJ%k zTYg=Va(3^5aK!;nwvKN&o?MZNJq&K2oW=7xA#oOWe(Lj_S@z*6o=0rq`l<*nHop3 z&T(`etXi}B2s_)2t0!sfOuX?oOLA8Da~@SEYjTdL>WtU4qQ3dT9RFjaGqPJsj{5WA z1b<$H11J+_3BXjZ+u%hSp12~cyBuZ~YGkG+Fi(#CWblRc$4bH2Nq6b@ms{vG=Ipv6%zj5&qFMhARM6tA*6BS5ob6JZnnT6_dhQkVJmgH|MmTf z<nbj8P2_XdrV66;z|&0_0VkO&p6zur<8$_asM{qyz{7pq~Tb?n>B1 z(1Y9()TwU_xL8QkWYQlyd`>Ess^jl;?)8@fu5F1$bQN}wk|$kTvlaL~QQzD*#uiz* z=l~=S7$o|`F50B3TP0tF))pjAWw?ulAm($psSSjTW}!_Stc44fevgA)NEP8|rOK-) z0x@S%VBmXaw@Q~SJ!Q!~RDd?dtbzQ-C|k-nGNh_js}d&^tBRaWs3WK1NNLsuyDVz6 z_0onISntSN7v2HF6WsOVmh+{TV_amJCI%y=W?3-Q2T@!d z`7Hq{S?;{8D&rP%dxBB~&{Fn|rNJ|oC_#+Mgd%t=K_wGHwe|`T!wrm{bjTdfbuDZm#|M+WMdfv&r`ITq#(J%fR!=(}*e8+2u zqL2sfzlVG7yN3t&?51N`yy3MMam>-DQp^ow3<6>kiRZ~?SP((W5+x_F#38=?F9+Cv zu*>T%EOF7x%1q8X1VVzNiY>zWgU`<~Jq}h<#lw&w^pRziW@8RLk-{>Uu)0gAnnA7d zD2NiC=diS}m*SdJsm<;}&rOiZuEI1c6jz^&P@SKSH0^PcX`dlPNdebEz4G4(PdJre z(~dnVEyK^$mYjUHJwa$_{mqdMTID}hDgbA^Zh3O zas48z#tdF@!5T)&NrrSAp*soY-1Bo%zhH=>aKNFKX*FgMM46u1q+Z#Jq!^g(3f0O! zR&Bn3c4HR3xPjuDQ}G?2%MaT93(V9SNQLR$MjglX38RR{QXN&(snu(kriCbov^y<^iX|$GH4>VN?*{|APaJ&Yc`k~g zqH7wGEOYwl+qw7NdkKPofB(0C<>lv|&xb$s5kC95&yv<8e(RmT$JF#8N`(@wc8lTi z2!Zb-$r6P^k#4t5u~5QwoH(ei+eH$@I2=xZq+zTiy+5|lc{Yn4$8jJGiHHU6LL}ga zAyE*aCA7mVaeKWUGt*P--m{P0dv?=lcW@ksY&Ju_P+;SRjjSFY$4F-w9UDcK6(m_& zIo@y(=x6u)NTM`wrV@}P5#Nu48C6X~dmN1jF!;S6C)GcbLh!Nls3?lHC4IY(swh}? z4@nRS!T>)An4C;7HrhoH0({S<+v$=?r)YLMXo`XYbRCQVzg1bmOVg?Vy?0<~HlO^xr{n6@PnMGyo&q9|b`bz1EXV`F33mPIC;jdMf-kFnt* zJ;x_s$dOKG@jZufxr}A?DCDysNDu{-N=2+r7bBA%ANS8=w%XqFuCO1YDhD0m$*q`0!eY@Kun~n?h#a4%@xf-tR zv0=>!x8Adx%U^K@K^XGQtMB0J-}w=5e$^S=`M`b}ZIi$M#P4wTg9kYI=ymL#oa67V zyqov``X#I#&9K<$@VT#kkBEqO|9=jEckP4co6vTV#&ha3<3dFC(GBboZ<3c8s+-i8zgm^H(#8E)}zna*zF}eKEg1FouXug zMr|5^p4FgInIxfQXtx(=E*)ZY(|Oq4MU2u0a^oiv_yL)rbtJN@@m-6Ak$-{D8FxPr4XM1-~QRcQnkYE zJ04`$u7{BniHk2fpJR^Rx^hg*_J}>ZPovRfW@etP+m2>*bc|Z1N-CM6)~XZrEl_kS z)dgfliL)-;K7J4(D>4i7^8{hUTP}YKpZw$>lg{S&gZI9d+1VMczWQp8-g*p=?0$sV z`8g7a1pU5EGHIZx3UmJdc!-L{k%}2@OS-NT<>yR2flCkkfN` zxTLZfR7F9OWDGrp7sNKa{eB-ksjt|_Dyq8j(s|03sE_lDolctvAAFEqyLK@(br1l< zFxa?Z1M4?zV5~e$CY?i4RU$$ZSw&ACIX9!(Y!U=dYzUIi=MSTqg<*(o^>BSJ)3i5lH&hU zRfXOlyi%4G+N~zJOqRCUC6`WNXbO%SBB~@QI$01?pasG+Gpg9<%k`IC= z-M)ivBw4K0(FYS4#|uy-frUzyR6?QF?BY3n!VnghVqH_cR*Us`qCl-yC!I>uYPVOy z3?(Vnjpzv-&vTF!l}tK?Y4#W&DbsgdvY8a=bc(*?F*ZJd>$&8!X-e5FmeXf^e2iYN zkE$x@dIHaNQPjhmMBnx3bxcZQt5EeLPdXb*bvo@OO2xvHU!=#ocA<|T#!i5Cw~CU? z(yi>qcPt_V8V7GhQj<8H3X2EtW^CPQ)DP_-S6WRvH->91F+6${ijn|9pg6pKCD2b4 zr8p1ZXH<{pdOoW1WA?<%!V>rIp61LGH?ntfo-Lauxb}xTx$4II&{Tzs&pL+FPuPqs z2~5t_r|yIqWw!oF#r^=s0UvNFY70@w3NQHAE- zpF3^pbJR@45SuNOYrg{_22OGNiF<(ju)2oW3o#VT>dL!Jb3ty?E_lkF-kY`#!C99M*RvG&&ZR z<1?H~p()Fp-=D1h zuvn|1>pInHl_-kn_gxm|XDJkm>_0FGQG}u@^m;aWB0;CyMH|pv9$VD)ojyrjN0wxQ zC?uUq<9iO7Y@R3#NT*W>l8mmZWU^TzAeT;~Y6&Dop_I*G_H9bVAwnTO7ei0t`W`7G z6^n`!+6n~?pjxeP@4ff3ckezbl?uf|fh}7$vu5o&jymcnR7L%XWbvmmA@F@4*Kr24 zvnb96LBR8UBqRh`AajJk)i4NYciKX)gIRdc-eCJnNC6A$L?!x-$6}ic>O-2ZxSd;Of&vI_3S=9%OsODsJB}r z6R|~d$Lz$mw`LE+&`HQDQRt9Jr3Vd1gsLh8K`f$Q*+20uysW3__2LPP=eyW;tZQ0W zSj0#eG};Y%wu>rBRBBaJMWNB^U|KyCS*E%eXN$C2O*}6^Q5DRti87#K#rIA?K9{4_ z?l3wsvO-~7JyymIB8vGu`D_L!@R=ANr)N7fT5Yy(KOM`m$Y!(nzK1L;D`!xxF5-DE zx%86o3|)r`P8#uRNXAqs7Cvw^&;woz9^jfoA!lmFpM zc-rutF6Pn{{ce@c?7d7s_@9(V*0b%j%So;|m-{D0_8sVuko(;AK$qXVY?O853FM#y z_5y-u#WCzJLYQWkxoU+@w@WdXW7Xhgkx8fd{NMZ~=bwEp$86hnm>}z0*WJxMyC(VA z@4o?6k@16&J0F@vl>|;Z_VGgnUvQr5pyTm9hd9qbWU;c3Fp{v%8uiLPlDP@m&3UX| zm(lfSVfQUkrF9fHzKpQjAX(agqUQ($7g_z;3F(tu7y0Jz6Dca*1(!Ujz4X+w;?xt+7l+>UyL70Krm5p)_h^`$v(xb=1_l`5y4auR2sc{&MQrX#~d9W#tJp-$0AVA^$;bI{rmQ@SgW9_3Z-HWP1C3?E|D=ZRO(ftFv4^Fm}jr) z)R*c+#FUSEy-qr9FuzbmPwIG{7hCqqGR`26!Sj7&NyPPhvf0caSvrF>5KS9~f$w?b z@_C{tB9qCYs49vqBMJi3)6*>07HPFRBoYbEefc>Il}c>cwk=M4mt_)~j_bMT|4sb+ zbg^7yKcSme1fJ^>1Tp=HNFWkILN7#+1U%mx2+ohttVhu8wsG9Yw;B}%fov{!MB%;b zy4XE?U_C73d4BBXB*cqAiuUArAxF}AJQ0>n4Sdfd^g~2h!s?l5s!rEzwRrgHKbWhJdL((Kga!5uCEkz`y zIDjBW5o0^Bjck|r6d(b7hymNlA&104axvr}aFFO-TtdVBBt-uGWnNC`2mB0{7{G8l$V5)1TP zR^0ZRqz_mE_i12hnq|;P5}qGm8adjnHku+6CIYA1#kOrOU0FqzReHS+?N$q2Ram-w z6_5$m1-W_CpjL07DA`m<*R}Obn<64f&~rH^#>eqIkEzLV@>T&!mYAEJq1kL8%L)_K zGEo#$tyXZo03)XjT(&k^Qo zDrMB4SJyGCim%P`=GzWuS3(~D;m|>L{KIZ=XO^ z$BAa=_@%&iV-W>iQc~K>C+S{0OOjvUiaWzok5zd4CyV@aDZ$L?6il5*cbSyZ3z;SC zeTtsb? z;xym<`X2xgCxS12`CI(OAAg3uJ2v0)^^U!Fj$NClF>k}M{$M=}}+uzlMn*#G!rY~D1tk+=K-^jaQ?|qCP9y!dHzVwH9uFKc|?9bW0 zeLJ>obLiPa96WgNw%1MKh*R&rOW5l$Ge3i6S+{J6`-NVTB$HiJjI(~N)}UY)xmH^x5fX6}(rmWK83v7dJ)>s&0kv9c6G+il|b=H?~Rx?BA4@bCvF0@q(RBJhLE6oSlkEKO2mO-4aRQb5)8dpZ=k(aa!C z1d68Oxh|TPxl|=lf~qNWx*ar0#SJ`K?G|IB6|Obv*p`VdK@dk23PXf(jG{5BE$iW0^uqnM_FNCb1U({$Qx z@`Yk1ju%<($A%t2r73X|p{hDg<07hV<2$Q3wM7)&rg7;AZq&n6bF9AiG83~85_)Th zs7G~bH({_wVW`UJ*k*jM%kaoFsYo)XHO=^c={R`L(DF$3G%p=ZK^1JDvv~Drhw`Yw zp(o0u?Vo{H|G4jRL$Kk^1V|{digM~C^3m6cKmR)<#o-TZ8Xph(DYe;VAg^zl5;Bnf zLeQ}!Nd`&d$jN2a8g=%}Uc)qt_}&`zj>=NK%z<4#s&j#%yg?j!=(+rTyKp2)l5xaM zlQWC&bK=w~UVQ0$$g)JaT;>a(`E5S=&?AGBm_PZ;f99EkyZMbLAIjW)9G~C+%HQ)h zfBL&vmVvA&wA)=K$4ZP2XQ%gx5Paot|CO))(PtSiZD6?I24LXz?R5ql#OlgvNK;&= z#mdq<42>@kxec7ar@G|{;z&>^&oDB#pU7*FFU_Iq`Ak5#0U>>=tf8L$FGSuZnwloP z2jhm*XU_7YH;!=re5OAs77Kjp$%8!f;NC1@d4rIOl%KtInwcH5Si>eO%PYM2@++)d zS!Lh8eLVg2rx`8{-`%y+l*6yS%0GSQJACbHUuDWg4wErmnMEZ=h*9f#=fcIhdwFz0p{=>h-cfIwWLCB2Hp*Ib-mf zDcCkW*JWb7N)$&F3q$L93Nq#LD4y?At&WpZ6;erJdUA@jwKnDIIIn?NlEl*lDV0d2G@}*CDz;^z=KeR8 zrPJvQn(CWDRTS)keFLrMhVL&CL}5fClJ%lGMUoXXO}nQ_Q2(>)PqBQ@1tB4865UP* z6_uXv;JPlhWz%RjFmpPZB){76n>KHyUaOG^LA_o_2tmOraPiUw+U+imvqs=~sG7#brAq@UV5if?FbrJB zK~@yvIHq9RIIc@|tU{WCuBnVw%YTR_U})C4`pWvEmluW1BHLa|sF{9is? zTwNyH5~IU9iwsMVB+?{CIsZPAtU|AY*uE3VbF$}@ zMi5~DLnYEQA&n!DRqm%oLzY#7DB;CdR@t+2h`@Rr(~20KC{Q6_Q)d;YS*NjlhI7ZB zXVbO=IJk}g00WjuL_t&oD=PdRkqDfpzA7!kNlM9o_~oie)>@kAAOHaGh_VK zm%l)x zdY|L3eUs6deYkF$D2^H5@+5JRV2#c(GW!UT(qENTE*H-)5``YWvS;BV2_)+~?DPvGUDwcoAP8ApJkO7hpP>PP1O8R2pXa$|@q2A&qG^Tc}!&X1zv=jPHA_ zwcF&(JkjzpNgU(49<^GXyqRAY{p$GZ)T|^)FpM0&A5bXRSvG^BV%avX>oPGhj^j9# z%M~P-2g)j;z6pI9YfSET3Dd&os6}5Mw zx+#i+ZQCGSryq$#4BV(vk>0YfH+2I^fItkWXNkx}^0J&60*EBNX$9ap9)9Q#3{&Jj z^+=LX6%{#^F)ibkE=c{tz8~r*%UJ?>U+0pytif{)BNIQD($T^DoSK;?3`3+;LQ*80 zZjVZJf_A4(9L1RVJXh-tG+8E2B?7;m=_T4t@>U*M%JeD2MT^7_Ni~hUkt0qLbUm9s zbh<86ld}MfmdiAoEyl;k(RGtTA#3CMPG+be){8 zQW>ifhXG@iGK!i562>ZJ9M_{@XCZKDn%>3#`TCxeGqZyXyL_F(Tbj)Bt5T7$LssxQ zSJ;v(5O-JUHI^9B4eFQQrsXtI6^(bk_jgn#cag>pZflw9%pQ`+r%)Vacyx|1a43~$ z25YyTv+j$%@k4fb1_CH+W{AHiYsDW+epnd

    2-KBXlKV z4NFUHa{0Bp5*wgat&+=my)&AGg^&}((I8JcOVE}!`Pf-Y6=YKFMQok+_foy}1m z815F0wi>q;=fwSMD~vHDQAn;>BFNrfQ-6!ihY$kCaj-0jp9=7NzuT|Gxxb|8dN{Vr zz}P;dWifU6Q-*iF$oA)755#f1|;$8kLdx4qEAcXWSDtA+jZAHw(! zjBRgtEoz4$mhBJ(E1R$;NkY9|CypW#rLb-L*1aO7WNvPbwC}AeY$9AAd3^#|U4-ZM zuc#F?#=&-PAZ3BI>L#R=D3#Etwy?hhJtv+v#u(x#q*-60(`tec1eqM^Tmi@Z^2qdV z@o;?MA`>S*J-Zy0*jVnUloo-PLfST|D8jpN7M0Br?%WGNxMv?xCQB>?ow031oi;|r zunG5ZNgNSJ5yr%LDT~pa{iJhgJb&{PQ1=SgcQLd`k_2}R4_OcdC~cv%?qLC~gAhYF z&J=O<=)F)jijWd9aT!soVs<}wtD)h|lm;Ozz;yGOwZ0<+EfAtxWZzBcFx}T^z3dPa zH;=mIAkz@I&Q4REpIwetc(+oZ?p!F1>83ap z`!-X@^DQ<5eItA58`;C3{tvJ7-~O*Zq*0ya^6B@1ZjH_K)zdraxs>*@6QNtP zAi@y+;V+4mhA6^3Kz&cj_h{4`R4TW-WhZe$v)LfJ+20_Fx}pbn$i!x|Sz4_YdH4Q8 z6h=Vu##_*AEDv{O^SUH1VOcGNSUWW=Un+3p$_!fjPgO#C`l5d>(!_Crq;k1gE6|B#uUc{S&u>`N1;-{5B#q3&ll92Af>=h zS=4IP6^r4W2q8$Pvn(yv>Fe)RZw!GD1#I^saWuq}icVP4M!f$sgzKUA9|EJ1!h+c; ztY!lVnC-g}*RP@4O{`W6f;4*X^DsM&voMEgG*BaBh{0h@t%`N=LRY>qoy81~AX*K$ zdqpib9O*WA^RGBr!&7jO}2Ier5~|$MxtR8K-|_oZ8|%i!)Pn z!WOpUVcQNucKcSSB*72TSoYIX?b>4Va{cq;pI_rJg5Im>o9@W$`=>{?w1 zfTT9ppiylRM-d~t2e52`5Egd5L3Hj@>~DS-mCIosC|W5H!mLPV62cJQ)hJD=uJrQF zwZu=QSZJ)@3&9wJl`kOLZS?Z%R}^j=z(n`8yBTTIicN4VZr)5u|J1M1*&OY|M`^zDI?A?*JfEmh1H`6FB{9aJl9)ISky7J0lD?q=#l9krXMd@@ z357z6$%%zEjR}B!p~&Qw*&Z4b03Mc=$Fggvq|n3ju7yC(&vl~`ue}LUVhM@-=zYZT zkGk@U#S&`A9>m-X_SsJnOAD9-hmpf0h>0tRPmXo#1ulL@^auYr&b6z^fBYrni{QKH z@^2wN{RA#wL}~@nLhalIbF)|{e~p-(hV8pxU=TTZ4W@5ED!`14p||b8#1TeF5G<=~ z-OPpFoRYPhtIsE2-){{9{2nj}lF-%^X=EmnYaC{rvv6!Fq7~I|m2nf=6uYL_ZFo@O>QmoMVoxQ0$=XdgL>u^sH|SBY~4BHJd3dLt>>YmCv$ zstO@tr%fgwQ0gxbWYf!vBwx-+Kx@O*%QXguwvkE&YaFAQxO$07#p+?t34nQ`utnJ3 z&f`dHxD(5=v9C=aCa+^g$Kl2VW^6kmilEg*_YY#y8I0>7jle9Szh-M2^ zg0U>n3X#oYIvs@TVCEN~R6Rplx=l^Rq0@PUCnfM(*19Y_Y}NbedIK^*P*B zhO;04km)O@`TFnw$t|^~N5Qfje)JbVU-`{fm^gopg{cJ&eeD1& z&SQc!*fwDl5w#Vm?8c*MNurovtTHq_x}s-KyWOVUZlkrvbzRcwV8te0E6tfRpE5Gs zhqX=(ie)+2-~0DatdRW1Z=uwkQ4d3qIge#;XRW#k=+5Eij-MroZ9ISVd47wHk;D;8 zb5po}Kss00cwd$+wpfRroB3C-O)@qz^i;l}!$X4z(bdAX9hU=p_Tb&Pju3)mXoTS0 zDO9dNQmT+3NIGqr**q$VFwrK{vtABEMqvvf3`rc*H(X(GdT>V4iy(?Kq%RH-eGG2*+Jclj4rL zjyq~UjONZ-jhkr_x1}$|a_plwQILGOk9@grOKx|I4dJKr_~~xG|10nQ^PZktDaFo% zJ9zJ}KVW#r5K$O$_TzJ$|J4P)`g^Zq;t2a^e~*bn;y?IjOkbHtE6q@<56j+Inu={( zwA&%(u84;3`?u=Qx{UzuQgp%)1OagrWBK=2SyC!SY~P7huS2^H?w#wF!DtC40kO6* zA*Ez==NO-TauLV%wrVFH0n2s}(!%xJttihHJ*B7Lri)i5IDPH{xonm~KHJMv-xnz@ zgtTyM8$SvW+MrVbvePDY?o)IS5N_Ya!gv1&Rj&~VF!d_h=&sJ_CZXF@DM3h!+TskE zT#8bEmTVzQVI5uXFDrh^W?`{TQI*zI7fGcvEX*xX$g3U}qB}^L!nT{l(c>~E1Xdiw zhrfh&2U94K95{p+9z(efCW+Q~omu1O9Y>gz&zX%JV+=Qy2b9q$qY?Q$LM52dG2}n} zFOba^bXt%vz~zf@@&qDCBd<>&-gp}^aS1*<3&k=fnFGA6<(qFSxf-&bDo z__5@RR|&wjMlq;tK@_5b1#q#dqZn?)(L<^mW5X|A;miGrRwV@v_t znIVqK>mU0N2qBS+i-?oQ(QkbV_8&wiF|c{khHgd{0F=@w-$kT+gi`RrA;h60STj>7 z+d*V9h*}j9FAEw(5wa5^&z(Wc-oSj`LY6A1Juu|{Kj`t3v)OZ&Lg7`vRU+3zJ{2a z?WS%S4XHF{d^@Jo2HVB7n_bO*&skPHF$mF(fZR^ox-%NGdFw;Ac=qUi#}uP`hZx#9 z!0X?Ajj$8qdMK8Lp~57%n7nO|IDpudm5|Jg5z;)Fl^?r%^jmwGl>AuWtnxPE}+ zdf3L`pFfRNuhBkmn51t2l}Ztf?VuBdB%L-I(4AJ##?UKn7E*_uI*wVMB?{%j zvRviXWVsQf6cmd-^?H?Zd2LmvLa|JBsY?Gq5BmlPA1MveYN1u{b9sd^h@}Pez%Y7X z2%W^sGOe4N6$(#@LYK>c0F@w*eie?sfsQ*^u8#rqo9}kLtO9U7j1cgZufg_Rs6r7d zj4;^@V$VKQu?(3kCJvFd1GxhF8{YwybT=xwJe2w&jG)$brcA~nQti=VeZL|C^-*O19UsSh(a1fBI{=4XT6rp=(Aq*;>zhI8 zY?>hB5{D7Cv(?1zVG+yyBigO{mNBtK&v+VqOeUIh0xi2-KdSx z#8HGwBBZ6s6FDbin&?SK{q`L0Lvn|vl!F6S|)F~cKBDZBL<807X{n4#gW6mA?LEDJTZ4O93%$mS7C z^O*iYgp}xmM=+j?2)i2lOkGD_`WzDkh>zY!{j-0CxO4&e-p|02NXth3&L1JKT}4b@ zgQZ2t<}h!56RX)keEJEdUPTTL!3&4cNrd(5k1;|Za|O({9bnstv!7xd7qrIg-b<2B z z7Qt~**0S+qI~X)Z-!?|J*klNa))GH#ap|Meod0~5eQzFNXjdP%qG8(5tTvFAAYDjp zcqy@D*C5gQUSs0seYRRB>`W%Z^=nr##q9dmQVC*k1byQg=HQEWJ(U4*9vIuuc>9L? zxO#p9+x8x}?!~5{yJrZoZD-jL(Hp!}npU%pN|LSm%Po4seZNJ=Pn~A>&K+ce+t%xu z^A{+U3N%}7{^CFW71>OhKmMKXaPssyjvhHgrCg#?F0o^L^pOT8gurn<90a!32+JXL z{3G0JSBS=U5RGobqym->zk*H@l6LEsmu54ewL&XJ9EBJYlP_njW6nk1+#X zd0S(lXF;1XqWlu3-awZe%-_41D2*07VQvoPr7{0$08qat+fv4zp`Azh}BUnHAJH*mLH}CzO zZzD#>kQdGqk8Q(hG%&dW*fvThx69kN42-9Uz;#pnq+Dk+ zYTKB60XZ{;BP8*i_o-1NQ32NvVV$}OfJ`ofAGjoOgzbEByJ8z-h{86ldX-{do`sod z3VlO8>j5F8#Pw1%8#Qu;-er$$@#SUBSzu;vo)e#*rN6JT!kGB@_$kImhdF%UdB#VE zXtvs1p14LnpWATP>DB2LeOZo+EhV;}LUuZ2e)(gJWz+onyL5IvM>sl8Sm`H@LXvh9 zqtxaK+b=J?aU7Dw9fSq0V==mGfNUYNWk5Uz9NWT^hIXs9rZHjLHb|RBr`=Oy0^tBI zwlzOwtWVL@{7qQ&PIty@2D{=T@l(FHoa%42uRfCj*7 zbKv+YkNx)m*f#jSA(et4^)kMzNTmhA_YA2(;9KLQQidP^|3kZLjOc$#katK;bnqKK zDc=yte~F(Gq;#F2I)dMf310p$@!PYcGZub-87EGVufBmbJq4D9^gLLcN1Qy4_k+L0 z^bL@_{Y`Y=0CM6AmhE9|3kFBfMs=e;x1ty88yHCfN(r6@=v{`;=ux{rg_V#RSc&!-jG4vY+IMn)7P!i|aYm7F+m1nqGxu{2)zraemdv(-vDiD0Y%0oIZDfeS3HP|LnbYm?dX@ z=lgjpo}Bu0PBT4uB+V#G2uYT)5JDg@_L>#g#`cLM{fn=(YL?%TnzMhwOsgcOVn4Fj=o6Cj7VFhG!IZloDlgkDe7fsbkAhZ-# zWE9`eqtu0mj5S?H9NNc6zj_8T8dj zL$6L>zs|(O<@vDmeJB~bmtJ99mZj+*vB^upHEUJh^ zLlP6!e}$OkBLhkBH#UACkkg$6j!&Rlco7?kLEv}HHwK%bdG?0W%`O3~Ea&JQ1bkz3z(D|W=D z=ju(Qa%r6E;ypn#G-giClWIs{tkF0W0+R6<^Ye3LGK*=+)#`Gobfpx&=P!^6fQW73 zdLEI;*_|^A!oE1OGqqI3#but;f*vh^SX&)LGLs?_Gx0nZ(|YyPPI#_^=T?X(ZQ3_( zB$-KJnBn!`($&hTk^NYa=tWat(hU>C&?y&YNu<}K6YIDz7<={|=61%S2zUBfhP1Dc~3*9t{ z6bqP>leil<6FD(}In;;SvlS&3K7#UwP57>ZD$ZYa;r8$b>*Bd(1cE@iv~O%Do6n#d z#zmANUB}swN=4}F9me-NRwWaOM1teT90LDhk_iwZfzY#Fx3 z-o-zBw-dg*xa4vr6H>z5oW|UoV0Kn8Tbo`wZ*ERwc23~Bq37811bz^<%BLtyw z>U)a>!Sf*S7nj$^E;VG=u{J0Lm5QKJf$3%5&6S)TD@9nY{M_nNNpR$-!I7h@kI7^d z?QH?=?X`$Tjbyz0U6-~OQ5dln=(>TJIEDW0uYr`vd+w*Bt&4P9BW}f^_b0uK4V*;N zHBt@H1uwr0Boikl(G8t+ex)edD&MOKG_++NYRj@HmluUgG)+TWB0DRDAf8AvJ9Uaw z@@(Iw!1WLVy@+Fn2;TUX)0Wo@x!1P6rfJZ&p_Tqa!x*M@MMwJUb(F=qNgA5-bZ^~A zED>FHtO2ZuMZPUZY0kl3rKi%lLI{B!iBp)JB$mvqM<>>CK`{30-OtW#n>lo>mm79n zg|6%DJ9vba=0-Me?B?q2TNyn$&W5fIo_OlVy#AIOh{qOB=I34v3$KSqPvW{B?XAr; z<(Erk3Ly|8j6hh1fmx}b5-Eh|l6>lMWGao{+(KpRPKsN1;-HY_B7yH;UMWn}CHoXk zwS-eCkjZCBH)P4?v&2*JbCcLx$3=ruipHiSv$HcaH@B?#8z`k{ZEa^}dY0x^>mo+T z1<-_H&Jg(X1i|?W4``Z(n4aPvzO(g=WvOfv-}&|on>PhCHC^26qEHA8{+U^E8WE_y z*XGrU!P0q!!j*l#+qR--V?aYgDF3Qyp~qI#-ZfEs*I2fE>ANNrLP<0s5lZ1Yib@5l z6%iWn)$mnyG|E+-s-sbH^~mOs_&=8eUg=99xrd>Ux^BKThIEOStqkCr;R^;3q zC6S2Dz|aWoZHsk|hOU!{$EZ3kzV8!_M6m7UQ2@ix5kgy2nv66wbjyT^aWvOM8jJS~ zDI*}J*1o|)kjkbp?NR(IJUTHyGeIm7;krAn#WbxmNJJf)rqRBkjf2k}#fn5PnvG#v zHkz(cEfIvxVTnulB=^3=%UbN%2S8pF$ zZy%J);JOIU2j2tF2hT%`$nmX;N~c%_=k*QJ(@O_@f*qQ2SvWbl6=xke(2Tz`<90cF-%dkU`vYhP)6z5ZOWUI@`t~Z8 z?delx6BYVAw{;u0J%uwW!rG}o=-xZO{WmVxz&b?b5hxbBp z?8Hf8a*$I252g14W{K8HaTA5%#W?jAqYokOpG6xLj(;mPtI-hXf4;KI_yCazby}pQ z=xnm066@n&!ClQ{IGdaurJWL@-0m0peY}{tF+OG?`1o_6c2ZaHeaT1k(6^x#V&c#@ zP_??o;W!Q(wEctg#U@TVblY-yn$HzsbMu4=A^sKEq1){i?d{=^;Z)nl_Yp*Gu7?zGjx#$8mIEK4#T?;OPr9+= z?>9@$Otuln%dkWqFiMnD?=*XY64LRCxTUb}_6P7iDAhJ8NJH^?`e!Czyt(Un|9bzz zoQPCl{Au-mk~L9b(9+JHE=xZDfCMo|#HC-_bMAbk$HLmK2c$?+Lkzqqymq{S=Vf}X zE$x$l0B@|RmdRh)2Lz?FyF`&a*qRsSu*A=kn1(9DudHzK>hvxmRN)fSBlO3)ekP#M zzvv^Rja#-WfiQmf{(CQmLJf!8RB^V6{7Qw0O!ITyI!NfNx4%vqb=+}7vFFfP3`Tn$ zp4Y{Cu^kc}p7cESf>b`YYMg<4LDX3(CR`CNS_w)YYtqkzd}O)m4=mISiBQBblikq7 z4KpGOehJ$i=89S|V&YPYH>ZvCs!)Wwa3&E-AqY|m5(-jodYVh2Bk1z!lt_|1^!yfo z?fU3Dq=&u0x4>tT=3B_Si!V-^U&lEz{^a3kW_q7yDiMTnBW<^H`sY;GSa&eY_^Eh3 zD7O9;(eH7Uw(WGScd8lNFl}l9$L(ulG4=8rzaJJBK(a|o4>WpPZ%JC`o==}Jq&rWG zPJ2wBpCS$G9SV*4>a^hYOt4q9moCh$C@vqupanJW*>mOlw&Q_ZUjOdUHW6k69W8 zds!mH^(Sv1bp5qr#7vC+&yknUL#_VKTxNwSz^|m$Uu7AUj2-I)>PPdrg!H(GGF8??K{*{`65C{5KUqV z9ZvCQ_&?wJ#?Xw++=jh8exRCn;c z0q-PdJGA6$3~q-8xdXX_j>JD-@>E2O>Y&(jYT5wcGmZ{OK}89~L= zAD>8_a!I_oslN>a%Q;#-;U!;?p*PpgLy&U~1@HNmjzKT0x7eDla8%X#;+k#9z)0<9x9htUXT00KUWREH556?veKRHyUBnS9Tno_2!Xd{RXkp4@ywM` zu*m%zTx6N%2EWPy5xS*~O1B(oT!nD*z;(oC4sY&|oCy)GUw#=Lm50bO;h{8YVYJiA z;mAu^9@x>7M6#3yXbvWa1tBU`TVA@^c)P|fPSYYD9LC^6bQEG!f#!QfH4@|E4&DkqrKC$ppJhBWb^;MPiGm4tY zN*Gw~P|+boss<}a)g-)0`K|WL?o2sH3eL>>6#5Y>=&$lPh_xjhPOU-3-E2xnZ3MapplE|QH z!v&{spZ=wGY0SYs(p}dhbK7a-gn~Yp_b%Wx!_xj%1oAUk`uedpsvhG_eunlCYy`Mg$@1;`_l|cV z#ovT(Ur8}vN&nfhf_9w+U$^}7rjhJB9xKj17%XbmlOT;dpSO6&r9^WtgsHQsF4mAM z2f);j3n)WD?4O3HsF2|P?0UM;qWzQn>ga^N=n8kv8~}DWG$GDqu(Z-zb^av84S^~D zUGX`=WIwacN-m{hmMQtcl%zmqicd^u&5avKB~zuT)}(3vRf7+@2b-dN=81~=)nLQW zbnEw|)p&%Svozu2YNn{|auoEMPI={vV=FG;w2iP6YBv*V2fXiuqGLs};sk}<9zgRD zT;>;aC^gZaV;2>sFcw1XN#rP zKajTDY#IB6cmC$4)Iqi_Pq^)@9D4+mK_gyNv|h2K$lo4t>)P6HAy|Q13dslOpZOc= z3^hrZW@)lC zD0sE1F>@~X|BSgw#=lZpM>KxITUvv~&#y=2*lRj)9S#Ui-!Y2W=s|DTBn#E{?q0Uj z)F1M$4VpYunqq>Ek}NEgpfl47bR^9iUZeL1pD{WeqFls3i6NP60Mi8Iyfovhs`ZNu zJ(;14Doo$_ZW8rqsz+0k%C|2IgKcuD2AFJk6Z@UX3QjlgPj>NrHR0w(itC z%f*s=%Rxp1R;V_>E|8OUPztfl1E!eZyLl<#;PGe8TX-XRT%a zaP|`3(v&}VANxaWL5hiL%*_UMtrery`O=p5 zY^@e8S+fLKW4oNA&nu^(^dQIlX)JIPh{SvILEJo4!BRY#l2FjGrl3OSnIMfch5`B& zxaIzuFN@Ssd+A&OR|9&E>O3^6GV)Ch0>&u@!|x`J(Lstyhd>2Yv^SEizvdl1d+I=F zy+E5Hn+$n2=Kx4`q)5vV(r+sUAx8cato9zB1e_)IzMOFc-jAYC!6fdTLct8Sm^2fl zh}eQL7#7^$RRWR;>3~@>CU5k;IegGo&C<1)6bZ`s`DK*H0MwYrV=unuOZnFD6~_v5 z-hbg%8P))WBtA{GW#`;bY@@bCl6sy5#%zXs>EHfsgHZEbjVEZtOtqPX`Ri*Z4|}HQ zuG8j%iBmk9&WC|6{<#248s6)!A`10CH`Xs(K~IbNehKT#ujZ%)G<@aZcRNi3(l3nN zIj@pY{!fpdCrdoBFZ+$Em`@~!Wy~^>XDiH$19*?w{1Vp6r15Fv1J+(&2!khLu@?96 z;_sRZrz~2eHasolD}(^L@FF#yeDX35%qpSfqC42YDmX75n?3#pe~9V_#4(uiONSwK z@5i%RMprWGrAfL?Eo2=a z>;Xb=3~~qI%Ij!)C13^m$Y)I?c%9{&|EFi z<2Dla+vqg?dqKLd28+LS=kxhnuyD6M8pyqF@>G-Hm?r6V=KXJYVkWP$mz7@c9n;n% zNb{o{PB3?&xj2ybK{@YPKTg>v-BG%CeN{3 zkZMup!kh1DGO%;Y%h8c?N(zl2a;~Z;a`V8bu`97ZiQtHi4&g1;NRQ)Vgx?jJMEXzO z7IuTJM<*dyEQ-$I17TBFJR47Fi*hAB)9vjNMkO4~Ph8@%-$w&~Cs+?pEiDFmVwjx! zY^dv&4fQ_)xNKiwMtUQYXrOTQ#J$Tg{&DiNDRaUorF|uH+6H5%5 zPoNVda{BzzNK951%LBe645lt?hFj;tgCpP1E~mG}U!lgxRYH`Q2xXW3z?F_h+ncC4 zaE+9kn?#ZQsUxOlJL$0@>_3(50gES&}%26T5y8$iF2uo%E$oA)&Wb< zzI&tC?5a`*p(gTDy=+8pkblk*p$%~ja@!>^>~}8uvflZC_v*Qx^B>T89XwSroc=1T z!QrtX^qJye7fGX?wbg8vi&$nLY`}2@H{O1f)%mRXTkKbHsKge* z{Y|~Rv^A2NB1_?#G@$crAqsQFG2&HQ*rdy4V+E=)_dh+2Wef#7kz1Tf;qR#ibYg`h z{goQ_oZ_wU^j4MzQP3wUgMT`6l&A9YW5WygH#6ZJ5M@@bDO|zj!&~?F)8V`+GEJ}^ zbK1INgj_X$R0I$WD(#X#S?ev5v&iF{-6K1(iSZ4|yt`c-uBIoHk|V44cJ)z)R*bnr zje8a+D=1YI0UnCEFK@2jP!=*H?Zty>ak6@DmmPHpN44%lNg)!l2dYV2oM^ZR4^v*T zKaz%u2rN#&yuQ$?xT?&eY@IyDk?Rhz3K&3n0u>126@u_ZSA8kv5E#W|g;ggJdC>VV zKkx9mtoN@$d|@}aV*9Er0v}Eg)ipA||990bRT%Jx*@cJvUrUwGy&qqqUi(ik{MipI zM6`x4P;*|szwFL196SWMW7!CK+Xkr#m*@m;ix)GFr7(`;b1DRt&)Z94W8FncE~xkQ zmGh;gI4bEz{|oOg8D2EKsA|bg95y-A!R!U8>!em#BGJc#v!Cy+wHSqTVk^?`P=&bh zM5n^d6lf*v6qj3ZNR~;`a}LB2=0<58nN5FuWi|d@<>*bA{*=tVmoP*(tth(j2vh57 zkD2G`y9*#x`_VO9mx0*RdHgpm3C&(DTe}d<7B@jJ%UdK{lt2fD70I{9d?ZF;oVP+P z67SXJ|Ai-t^^W@dr#fhL@D_}RLVs)#82V&IK@bA<58qhe>^mWyqIlJ)`x6u)bza#? zJiQWeC0JMTb!sK%Vx{V=aj#t?gQ_;Ll!*}T1dMSLObY(2izaQqSG`RQEw ziEZ2djyO2MP}Q|ifj?_&rUbdArDgxV2WJK$LIzZ0v9W zfnOdxl+vl<7!MNct$#JQBd>B)dfarz)OOPzFLDH6nVP(b@HB~&l#Qm6!Gf1nfvdvi zcExT#>{>wTadsR-^0Ovg^tt@A_W5>(Xt#&V?dzw2D{Q?VRV;WBXQzJ?LQ{KAeNJC@ zK0Usimu-XKOJ2>xzq?Q8^T}r4>HFcGu43wpDC!LI>-o)8$OE0TSig=QaKwc{$43b5 z+f6^jn0~7Arq3*&|vWPugNLTKMaIk^{dq)1!)Fjfw|_0641QB?5jOv}k(pommW%cM^q2AZ1G%LB?NWoX>s z=Uu}GjFRN&ajN;gHAdJ~?|&H>-BLWGO>LZNp%#@08K-8XL|;N-^hl0vR@ z3&wEZk&{62TsC5aBNc~8laiM{M3lYur(bGqt}37G>kgR0`;mF<&G!zEEXH^ZH9xMO z`L5@8R>r0jk%>7h#vkh64X~dNb#+#>=-`sXik#_EG;MlGMMU0D2f0A|u_h?};crFC zD?&PBTz{e-T7J4dl0XVLeFS(v*nL`2z;=^ngJhu&HA%DzbF$cJQ!uz*j6dD%X-4+q zUMe(9d1~eF$i@a1E2|LM=IkxMc+?%uP(91_nN0P<|ep zW7YQXo4mAH??`O-);BnsvprsK%*j?HB_<*&sOD5|)+yAfm|B?`3J5}MJ}4sf*n&`A zgz~lpP`=)Mw`={!qqp)%!>i*@9u`YxI(S2_pr8;pY$ir4h%~h4goi4*w7i_2o^7-| zM~;SpS#3Osf$;FS*x)N*Y@F}nZfoG>6|t8>AXkVpY=WaZebrxIA~ zrhejGQ{3&IY+uRrnXUp)+=7GDk*eeD@(Og~e1(0#uLkMzwwO>6wpCu6X2WKqj4(%Q z9CQemYmlC*RMh5O|I9Ks*nTZnhe*&Q$(iCn_zIoUW#|IY-~`thjF#~t>5ZxxLyY2G znEQ{9$rf!w@5SDZf~JF|N_1%AWjH3%uuq(=c0;xOYsXZTzai#w1HdKQc+Rw#E2*sFv4qE27dn1($dPz z&M))?T_`F#y4v-KAT%s&vDz20m$uhtwJmxx9@oXy{gaT8q#%JfuR1)RLtMa_c%Dw6%{An8tr~{rZ(B)KqU2If*jY<-1mq-M&t4t*D)-m=+e5cBpaWu zNlxz6uJlC6q7d*ft$PQfP?N(cyH7FJefPEH9HeNxP6>|@Zm zzf!MXD7C%3_*|}tNO@eK%gfT<-U1BDF@QRL_D;51^H+U+ba$?(mlu!I*@j_*&57Y_ zK#3t0djj1M0^ELIu5n-uB{)3$F8vG=(o zU3r~*^n6G+Z+bW+9~&FXMOKy1B{p7eDEB$_jy*5pUG1IkJV!tAAALSv?#wwkVH?@y z65U8tDn9sk1Y25d^|;%V_E=tC8@Z+MjuJR+3R+w9^O>hkodk}&rIppzMy~jZ)8)9} zL;IiyRLFkkUdVf)-J4KcymzODSa7mfljZN++C)69bko5AsmDz-tm!&M8yL5TwCrwU z?&AY+a6D#aFpHrO^2m^)_|e_pN%D1d4V<5Z#zUh?iA6pS06$pV-kx2+?WCZyGbbe_ zWvZ7Vk{U#=3k_%3;){`|iPz-ViR_1iNH_(Q%|_oPXTK{>9R7%H?=RqUnK=quofP+} zy?j0!qOCF>9HG?tn3Si+h!Z_H$z*EDEyKi=EC(<8qsY?Sr6)Th!^qDq!KZhz{hFU- zps_R5%8tJ2{u*Ai-A)WAnsR`{`vOC;D7Y-XAXKX$s1UP+*1T^~Gx(15g_JTZ9}(+ov4J1O>uP7Hr-6u- z6WQWIl$CAJ06`LpO2pFRNU>vy+CVCa?LYF;(AL30=(hxf4BT4%aMWQ4F#3mXfQ(+*!cW7Qi<{$NwhD|8H_ zW$aLCrKz~lPu$%7!0kxS$t*4|4x^REsP(?Ji=hx2m?*8-8j8=iSzhVgIAc6e`?KUs z_y1l1lwJ^^S^O7s1qJ(3ShYW|Ee}p)3GjIV$As6#*~%zTjSEr)bhP4M+#?JO4lFcT z;y(L6AGcXCNXL*Bw(f-}_2D8>JN!gh)Om-yy$t}(WaGhD=Wn()=F*6@wY7a)j$bxC zF`9Ld|JltHLKFNPb>~!reha0m#B)uYI>9xUjbeK5>XOx|tX)|vA!a|CO8R@5!#jG9@ zgauGWDY{}BoH&QzyM}W)m7>S6AX(Zj1Ma1GsI?}fP@ARZgFLL7kJyRExKZeeM$!|N zr8oR~0!=$6fOG23Ln(v`Df0K%bd`_;Ft5w^!9uCk8pa?8m6|}cL>Uo9Ds;6ti4h4_ z(-Hz#O^z=vAYF01y(u$u?B{mI_1^Y>7{}5t?>Rq(Se=U5?o%(cv5sB4{u$Ep@GP%K z7scXmb4noB(5*d8lPerMGhkmO@DG;{kucANhW0omJb2+2JC>);8KiPjz2f48GLyJ0 zyS5IJ=tZxV*$g_K`D*4lCp*SM74YWci@aB6vRYF`Bn;pI^=OmLW0JvOwqztL@L{zk znsbPe$@(o2aB|~>yz-?6+pY%?(W?Upt{h`@5dJb`$bpN@L)eqRc8 zinfA7JBloUEPw{>DdD$h3H|EGQ5IL19RoaUg*6LFY&eiOnZ8tR->-6%9d<~~W zfN5l`c9}Hb6wr=Yw5R{hiZQ3^&1r1cBdlNYwcHZ5`1ws|xwg4EOw-37N@c^;9I}{0 zOL8qq$TPKucAypyhZHHUIw!w1PQC@eb)4pMic=X6QAuIZ#fu8aA^&sj179cc14(X~D0HAZC~OFJ`E*uN+_c$p@+EK>#(swed5=v>{waXhd~208+v(V_y{YP0CtTCoO8Z86uo<+lJIT5 zQL7I|=buOul1EMd)H`0=$`*pnecYRMfQHvMEX&)cuYM`+?H@<8g(3$pYum#1o$-aw z3j z=9EcS98T5kb|#C(%N077vc=c_Aw|B*4>MRtt#U*yNSK+u@L`X&Ovc*UibIArSp2gq zyzQbIR_OgRA_0~YERLA+Az9|y(I%;)sT58wat<-fFd_M?ki}v!IA?k{U(L@(k{$=n zD=5%n-Bd>f)$I+}b0>_Oh7aUd$|-MIzZ3qIyF(QIhL}&rk|v0*BS&%=IxIeZS@7lV zZ5~JL?<7_9=>4Gfv$4c*IpW1NNXA;Q)oI^rGong0{797w3DzAWJ@Od8C*SMF_a;_m zmOS0}4Yu1}FQ(ppa!lvGvh`X;TIF0K`UV{;1!{~OTs$!_M6%CbpByfG%n642o&>8U z608b)*kAru0`ym|@08z2fVhtJF-3tWhE3^0j^E z`{>s#TuO5no2W{^>!Y^Itj;d~=Su%78tU@IsqTQc9WS%~dnwxbgV{pfO)$kt zSal&Igw{;(iTs2j1s=65U_VAZ-?Z&s9ExJG%n-7K@F^BDrY8E_j|$(e+XKjU>q+@M z^Z0dh*5`@vML<{ov2$YKg&#y-ptYvy7Emw`c19cTLT&qWqo|!X@-3{wGV+h|wQWV= z{Os-YRP_7B<&en({$#mymy2U~EhfmwE_NYJk8>(3ZcnLhvAOPe230T>G>$r(Y_KE+ zGLTYyG;>4~d^XHoINZq7!Ca`v4!>AL#-JQ!Tykgn7^O4#F&6a$F2K`xQ^?)#hvxZ; ze=1q|pa9h=@~HB|(PKJ$69C@+lHN5hI=0!G#SNMJbVM$;DE&S=Y>z+OhJaHb>;@RW zR}y%N-L?xmch?IFm%=VV<06orL&GeXz1!-7|1 zP7cuuNY&C`#kKlA_eV}!6boQ^2nNa$q?sV0SctFs1#oGOSPs1Q@{S}b@AN} zgUGP7$iv{(^$iaETPPH2D4}FQCgc@tUD@i_yus1ut{~;&3EPNJ z$>&O1y7?Dk6QhH)hX(i#!61o;j?Q0a^)71%ap1X(Y1Z?n(q!3O%Z$;v+$8=_83jnK zGOdwPZ52mXS7|=~tQ}6SPJMP@yA3%>6BqXvWb(m2l+Pyha^^!oK{f+U|7nMmKGBUV;>*`d7Hi#S$sO8NWCj^ig1_k z9nnc|xrVUrqGe3kf3t*O)enfnZF(V%N}vQZ!z}sy@Kl+oD_eO=|2r!|v?(|hEFv-7HnE}?~{mnkFF@`Y2uUl87ARN&qLZ<~*z zdhoSG5bbbPsO%WaVqY4wkGY?pJ*T`U8Rag|xtbNB(*lGZ~`p zyat&DTPh)#A1He>in2rn54Qp81t>IiTPs9IrsCQkGOShP&aa>%Tc^U8jUL&P01J9I zBI2Kn>30@X*U)egAL|1@dAWabOqZ;55l{ha5fB`D6ghjlc9HT(L{47FAu@RS`a)S{ z3{w(*RetSr?|7_SaXKpZIgr=iX_#-1u>g&9Z6L3COtx#L^jE$dR$jCNIbjsj53<$) zs1!>*|5e`et6m?KpMdhf6ZVgc-y=@oq%HB*f8%+@ZTV;sz_cOv#2-E|Oo5_VwHq%s zF<*IwuS+^NBlYhDr-6qfiyj98W*obOC_jB}b=Q}cw?+l7D165xO!&4lJuPkHQ_elw z>!tq_X2(r^r6T~GSOoMcj`9k`_DB8AC-t-WX$vJDiVKI31N<}2F>~MgAi$enHK=^_ zAa@a$o_Bfb(kEiL`V=CB*86+*GI+hxaw)1e#J3++}jg?X&ROrH0B44!tEizpZ zs*|n~>F~3{aU3i^8h znzgb>n!iQw8R|POku_s5KWH{HZJvE-r#pjFSQfNKxv;wZan_|$p{JwJ1n5$7dD=}{r=Sn;J^ zr{6iym8&}DTlEL7+@wGFsv6iCeRbUbp&1hAw3PddZ~RSMn{X6z_&>gz7~tMfnc}Rk zlSz@!T#%Mx!Q~zx!HYqs9%FijRcD419cJ0~SKe$hBE2)&N2tOCh79S8kSPaRZF1nX1b%HwIK^xTTmE^1NN=VJ^yGNz6Kv&%u&=uHzo`|8ZerX^In zPWMqy#}7?~*%p(R>Q@pPrL(37gdL~sj2KzMCocAN+kECxmxA_-e1&+)a=T+smrJ)m zl5uzEo!9ke&3T$BzCXwxYxKTyCrptij#l@7MkXF<>rc_^KwMPr_T{Y8 zH;wkc%71$J9j0JcH1Aq?Qi4tc1Q5UDdl3Q2!PLSb+@>Nxy5kb*)Jub~(*OAg(r*+M zm2Kj5q3XA*;h$Wt-N?zu(N#Msq-<`E7%TY1e!N&4CIjm6y^#gd*z~4x62jC&G*0^IMLHZ7Fkw!wKL#A zLX6x;b%ZYPqon{Ay(uQrkf>Dn$VHbSU7KRln-1McOK;~BKt#LJ{e zj1+R(^yaog==}MJ(X2o?7=_pa0KhPHNT01%t1}%KIS-P`CZRL93n!_0sUpUNS!kw; zK}8r%0Q&NK$Bc3$2O!J6J>WLu}rK#8n8?X3hP66`OR> zak1%h($Y#(HRAg1!5>cnLK@yu9olA{cdMj4WldvcOff%?uCEhJw(7_%=3N0g3N=33 zL$D){p&oDm@-oQMi3Rxp6YJENT|+k=TSWCwBYau{+#Z@*0-*8&OdK8LU z!?i6qZ?%SpK#I=Y#;m~`L6lGAX6EMiW9GuWNA{grVV%#cE&Q#XPv?|?S{<>?2Lx(z zG)zqA<2%l^i#_jf2^+NDodHt2o%2CT^W_HHrx{%l$!74&>!SB5V{663@oTMeYrEp< zVf#W2;GYZR96-Q{62A`#ZlJQ4fqP4~)#ZguPfZsbcUA$fi5!Q35sW4G26{|{#-?d^ z*lulBVClYh<216?DKgRSZU&;Yq?50Sf_;~_b~#;jKXslE+SSepGhmePvPnuwG0Us| z50oMK-)rPZAa##?vtDSn#zYe3Nu?!Go?2cWoGV`j+SsS-iM(RJ&uzL=V z1H+TrVqRWEget|n9loWhHJo{tg}LPKS;TD&K`rv3-;~nPS}d`B;sO=>qqv^f2Ms~vM*b>IbY@_ zXys1%Fj^{bV}i}2_Ys0bgK-urqLUIF=mbj>Hzu*W>ve-aJTcz0Tq08g`tL$RbS|ky zMq1W)sXOd_14fStisT1R5ke$tq_JG$M!%SegC(KfG!vYThw(R=uRcF-U%o@@CU5Wv z&k}gMi#u-7DDNJ)VS4Xm>UnV^f~(lXDSsrPJfrz)6pJIF`!0X&sJ$E!C>A0oYsLSl zA`u>`?PR6(Aq$lsLT_~WcIrFOKHu*Xe;)4`(TtP*k)xby`mPP`MsOn9(*4e>SFaun zr-SyDAth?6-2yu!SEMq{PA^U62Ye0Vw+hvIFApWSNz}X@u>v%X(n~5(Ff8{o53^8& z8PV@-;l9`x#Bwm)sF>YKFpBh~j|BDxt1PbNL1LarpLNLUFt|yweGs&7K#p6;=8LqQ{CfXHC8sp|7qY#28OzjH}6Q zs@b9}!c`n$%lDg4Va`AP{DGjYErjdYU@O5%yNm~s*cZ{uYd%=<68c*r=KK*YOG2&G zKrve$4w0Ho@r;Qx%+{M)lqp2Fdf4143ca`_MHlT;u%Q%ZISj@PiiIH{{DAR$RLB?V zbfFy9xz=Mvgg_X!FDahz(J|LOhXRF>kaJ!IqoTVJMfM|q%|@rUi2Cun z=-!TYS!v;!bKU(foAQvw))L2e8&s(laW4D)un(7_!4}J%DkDxT`F#l!xg7f>crip< zrr#JNP2n5t;`P&7--TSj-3E40oU;WJ@keR}1KjKsbXodOa|pO(Eaz#Mves|a>!kD5 z&+o3663jxtiJs`dr$C3ZIdtxqQmNUUP$=&?T~F${@$%Sw+HvZ9wU1r%xwH8*g|ce- zf@X@Wus)zLoK4621@}i1*4nQN+jZR2|H1=g-!O^?;$kIq$6Lzw9Q_w3RR8Ds94V&$ zhwG!eyFn2pKC;5*&;5~=ofL}DyG_hfV;h&G9FZqR(*GLcWiBprMEVd#?f})%%cGZ6 zZ!)i6-UBAEKHS*xtoU+it-pIdn6p7kd5`o_z03l1IQbs7ttm2}ep2#h$u+-)ZA*ha zwk&l3ALYFmb?16P!!;ht`~Q~5zI$fbKQcb;cm@~*2Y_8)5@_M`dm>U)9RJDhnP9*n zBb?grrc1Mlly7Y8;#TK;H-t^Vs?(RGB`u>E_3S^^Au0_0LZD zv8+U!6NKxd(XYiJzTUTIBN`nM?@|0e!x@7!$g(2&Wn?L8HWzN>6g0f zizh_|3>yi4X!n8+m-9o-cLH`jIYHs9yn3zj2Y8egQ4YMHCn|DCAvAym?X&y`E9PLs z+>8wDbVtx=UuHt)SsTZ1K^;1;1<$eIE4p1UWK1)(`m1HZ43gwlaL?u2ZBHGdzB%a= z4aP7FE;+y>-0d)B{xgl;xCM^-d^E-B7neu&7beWf$gL&TA9~IdMMe=o=oUf2L!pi# z7hUcoRl>+4V3X3lHIjIBJQED>k0)Q15icF)ANm~Gr>ihi>I_(yk)i=!_eZ_^-s6u*pGUPw9A8hH+Fn`pftS^wIq%80fFJltg z{ZipB`*Kdn(D?6DTaL)q>peRHVs477s+=mL0&F5yD!*3hFqTq-MaSdD_^xHXo43<* zLf3b#yTP{OGV8R;_2`pLlh?bW`AXB>Kioc#%jT`lab|CheLwoHFPqMWvWtg*CXJQ0EzC;zr+x}~+5N`+OMLNNYTY}od4g#t?1+{@)3QYPYHjLwa zL-1m?NRnm=24lt)Fw}U8rCg(uyS8_Z{XK7)xnbQ>asf%AI<4D7CuY)s8l7+yeTW;$aU8Y$Fw8N{YYR%)aLO8&N#E4gP zjooKdO)S-Jy9^Aov7895I0A7iRu=n>YU910Qzi~>>fe#Cb$33nV~_{Z%ai2DG6AL< zwbEGx#Y3BgdephB?|fuGwCzI>DFq+XU;-pA30?D@FWe1ws{{HkyZYl=d(I`-E)zVj zGy4x}utvLrd8xN>OhO<<`=s_6(v?C6(#3uLM2+^6b~R>fh{TWy7oZw*@^dM0%}RVo z6vc&8et5v?{_gT zf7E{Igi1r}8XKMWr$m9Tjogqgf3Nl8?!4>owOR8K5_vg~ZQ4yqt@2%VBVgB+qRx?? zf4`{`UhR^RoedCD{9_NLJb?Sbtzz8=NM|QIOVOmCy^i@tQ`yaJY=S2y>@MzESjWff zg|Q+fSma8y^76~G6nNwT+eL3LZJB0A67KUe%c1sANj$ZdwiaWG9Q->`7hNiP;EepV z3IVE$`okkt0C)y=zlqtNn;;Cq;twb;d942U|6YK`uK0Hz_8uSE*2+595BP4z$)C$mt5qc6aJNVK6VnPsRUG&qSTOcT2YR*P>Sns6U2 zxEo&k&bQ&w!hhx?FRzOPG&_?zU3;xCHIx+*B1tO!vXoEPOAv@f4KWrl8LU-^QcxL6 z;T(ITPUX^XdIURv3Q@5-Yd(m|8YEU375*L(y)u<(SD$wjEMOQ;m9r3|%^b&$ z9ym(^p!v%Cj;RKWb4qSAhApXNb zj$&gQ8ygZ=C^YEJ~~zu@RSZPms$?~!;s zSiZix(*9<1DhNWMkh7{JD6d~CIfX*~m-FbEmxIf&A;XcCBT1WNy z@`aY;T`8vA4~Bn%%8x5!#l(Xpw zB2^jju*7~L4-rQE=i}hu>q?-P|Lk)1Mm~kj`1PgT=SX{flN@l`d|MviLjS<^o#5)) zabx5EXgbTND7&wXE8Ps;-67r0fJn!HAPCZ3lF~>G4bmM$3?e06(hbrL(%mg3@ZQh6 z*8d~(VP-LN?sN9J_I3TX>|B-cc-+bI{vn{{+eFxKDwJ;Dy7w~Bsbk02xF0}(v!o}A zh-0z!3oaFv5mr3bybtfNNSvG-yZTEfTPml1_cP+-hZ-;R$J?{Q){?ZOkPsv}Q;GRL zPX_~tk~&td*+#e2e>&@CpUOh(7aHIuu-SV-AW)piN{G1-r)KX)fLLGs`1jNrDC>bS zzbWs_^ju6{WS5qg*a$JbrWmNB-Rx{4a!=J8&K8C;XUpy{;sd)+8rQ~d+h6=YxjZ@^ zFSe%jMW^uqUy=ZMp9iJG0KB<0a*IX%XTXY>=gDdhT#ei8`katgWBA!}5pLq$ca#}`Phn}1Z za|Z@%9N)!~(S*r|;jTV2Jg-O3kVzpE8zEx^>wN@WYQZH z?4QY6C_#~lqmhm)Rw}4=6F$krud4z^toC>`9aVydhaRn2Yp8k*hx&@b{QhNE}KWa{jY+p$k*{f+ixQgQjRJ0f9urs8*%qQXZ z`~+nx@MVCf>!7cn9h6i29+bo2qq!b{JV}TVW_uO}hLN?QH8>`XT8)dUD-QuMIe`IM zQY`%FoQ&Ast6#R{=&#h&)N1E4S}T`rGI3BsYNsmOuZzzo+>UzfmxPnAH!<1*? z^~EVhtzT+44$Hjn65cf*Ku0D1-X#Iogw+3J#ko1?-qQ9ZvQLYz7f=;AwO=Sud!3j3 z@flI^I=*=0u<$uW!!1+!b)vQ$L%CsfaGvBf|Ebsg$@4;5dvZyhH?aP6c|}ANfrVCs z1^BG{1t}_byYil6^!~U2QsV4&c?0~eRV6TD+@k!=*|DOq$n#^i4 zIE+#}Ae)Fo_vcGzz=O{tDFp?~Y;yONp~O5xLIhwN)Sp-$s3sWDuQp>s#XYs2><+_< zj{#ByE=H)uwB+asLst3|tzQcV;%ofwF>q+45SD{O8*2%ES#9koNU5qsZf8STI()5TbAc-;f0k#PA|swHwu5^{wF!Q( zznmw#_JDM{96)o6;4@DBucKo-zWuY{z)Ub%UYq|-&%YjX4vO2t--@Z#N%{}Eo~Foq zsX3p2aIw6bD$hyG)DfggwX2Wn#!Z)}pMIb4?%g}qU1l36^&E5LpilL@r;o&(pP>G; zf~*x|&>j3Z>e3X^oK{13YW{?*L0&!)Fx|&)o?uel&MKYs0SPX=-JHlhETT?CL1?mh zlM@F7-!I{w-eo%)agp?y9|gD6%TEbDM|5Qlf%F` zV6SWMstWSs?$1+-Yb4yNLkI8<71;U|>KvHmS3(_@g_PL z(C}nV$`EpD_$}Xt3mYS53eR&F>wSi|dOcVH;XNeNRd$(iM#Ce~pVZwY<_dXp;#DMR5D%5u&9f15$GG z;?~yaq!7gG>uVkX3Hgt1{EL1tSW(V62_QF`x^t@8tMHqfn*)6{Ua4GWym+m8|FBaV z0kBXOLyB_Z(8DNv(IHNrUJ3S%h4iP44RB^K;=@01K9D85hJ6;<7T!V$2DHFRboZXl z1}cQtm;;_XZ>G6j&_66RXuCyO7XGXFq`U16#0SV1DLT9j<K+KkvHmA1kn+wnD@}SGL%juwz7}vxlmL~E4F^+OI)@vCOZmgZGz#DZ< z@0A;JRJYYUinal>is-X#*UYYjz5fx>CXR>50y@z8wH!!Q)lBBN=P5sqfQFPXWWn&> za9qZaOYy*3oSi6KxiqGXFvB5kZcZ1WOS91S1DcC$vGPs$hc?1Z)lJ(zGZ*z@xeQe} zEW&{lrTT+|?p6n+RI^lvT#}%cmo4bbYv#SpxV)tgvmqAZ=L3j{pV#FLwQg-x+jGOo z3Z_b0;`okc=l(wHl$*$;v`jt3@_ZXucbSHj5k?i7+&Nb_ELhLiJv8E5E#&yPRL(uK zgnSDBb_Is$PO7` zGu*(+LokLXL;oAWy<%YUIibj6VDR6+R(1NJ7$x9oclXkK16e48b~bt#kw_TP1ju0I zkFXDQQ=Ezq>u99h6QFU`G$X17{tXVjYVwN^uGg$sLM#4!JdBJ=!6m#qUZVo_xp2f8 zeCThG2-7wSWzow|hGusEDoTz6kt-_!T(f0`YZ|!`b=r^1T|9U!Kt{U9MtBW+y#F^N zPRMZigN9^u_>}iq4n(o^vr(E^Y1EO=wyXYTBqK~Q#zN$G0n-TAf_FLwn`L2F^QR=5 z_yKDX!rI9E95!)Kq&!d*l0qjz99h^&f`3l+`GKY$C{}@ckk?BnPTs%G(COh(yVUe$ zC+lT2=t2Mn6!_O7Z%P?=>{3=wxd4&zGX(!mLZTIWiT1P)rjnI4+0(`hD!s)3JA>Ww@A~`R z8_M4&*tAh1)GgAXWGz73VhwtLI1CWph(yK>Q~xb3NtO( z08M^Q|I8U|uJ`%mkSM1jU3!E|jQwi}L^N3Vvi7E>5H7tTfHUyx%F<-jS@9&?rb|G%nAVh*#y(U?rrdjKqr#|M1i1 zLR64IJvm;0(wS999JN@~PWRnys``*nIJF0T zTsGiUO|qZ|94Sb4V7Hdayy@3s_Y1EQg>2SvI-cwluQeWjQF!%5vfs7{y`Fw0IP0Bl zr*rp00xqzkVkjlRn&J0IGCwkB-YW|f;x7~SP(xRx+S(BI7;At>L;5-G)v4Sn1&?+@ z4b0n{EA(kTQZO)npN@a)7;`DJAL}ot)KNy_KkRpNqOH9Pnr=`*E18RbZ#;b!C|(T8 zERU_$8WwX@dkv=3tUtNj6ZLODu%8>4*>jVfX>|K5Nb&elnpk^&#v!?mJdkDH-M>o# z9enlAyY2@~lc=K_9i!AqeI)#S0w0gL8r@;Wr$XNN33gU8`Duxw@)K$D@69W>0&4Fl zG~^_LzL$D)90&$0?S+^LX{`M~{&0l-{PaWi`6BoA^T9$HJof&qaQ`Nb z3g&Jy3=no9rNIHY9)H^nyg>68KM|~P>Dh{T;;7zIihea{q0G!I6@Q36M=BsVSKaY8Cy2t4N*k_X)8vYhyI#Ic(? z!(O?*r{1}U|1CpukH5tT%CWS?kw*qzPL$&-+tS;!*O>b2(lVhec<`_WHx9FLPkGo^ zgC-=8>59SGqYI~I>`@H55ZUCTd^_my&ZYVhy-Bkl`cCsU22&^;FPa4%THx+^3!BBd z!wiB%`ANlZ-Q67Dpd2s8{F@G&v!c-E*89Q1nFYVkzOWw8-z#s+Ezh_`UIe(=s;rbi zPeXDa+I4Ew8lhk=anVb_soxShKogif3dnJ}{;iAdD?l1gN?u5B6KH7Q=k9HY;N1Uu zH#&bAkI1F<55Z#j-Pb$pq~H15%8xR$1bE0Qno`wpmkMT z40Xx|`{e9DuvRWZvc|1X6KY}-(FOdG#*aFAG&aSk_I-%Qqw^`=7qQ6p;+bKMJ9hKD zOK|$=ILex-1y&+368=^bnq0BpFJrDYt_C~smf+Sra%P3;V5m`4R)|LIc^23bcxnID zCNND-?{xdf^V_s&IT9Yf;jQG(5P$9NzEVD#CO;jX@QI{FDtJ$*@IX|8JJeJ}@t{Bl zL5-r%?IUkFokZh`@pNo{7Ew_NojhSLl5#`-!4vCZ?A$^)!W93+%_|78Ofl#IZR$uy zSbej(;yKd^t>@hCNf%GvpQc<^qLD;Rg~5{4sA^Lw2!@)#7Y|WGJ7I+UEja3l_5bz> zZRPx14F+G_#K1QviWbqB>m`r@yn$KK7SSbCC@T5Q{)1A{vBLC}mlM7bH}Dpf;aYt2 zcT`2k^3xg{&2OFqT8LZFA-Z_IvN3ckIPTNZX`w=K$*6%lliU5RX4TI^2gS9M<)NXhgrwj%m5! z%wjptX!}a^)74QGy@`QdIX~|jzl*G<40>_D)^LxTq=fL{JMALT5dYFofKn@FQ2mwk z_?@^bh$xQMIe=_)GEdHvGPMHSPzQsQ8X#WnIA!YEWafY1+!DhHGb3B}P-4sioR;$R zE}xcgw6j#K`46p+T+(CT9Jucm){0V*M701-NUn5RjW=FK699C~X&&$g@RuJaDeT599AR8QO9UuQoY;}KJ`|AmY@!b36J_m#g+B18w z9I8#e`ca$Io$JW|w~@Me?wWpTn)f#+cpvReI2WU`$UZb2BK!PALH@GWdE+J)rvmY( z^f@b(L66AS!J)&ybFifAe9IOIB4(wK2eBfWCJ!?Jb63|mk1|3Z(m~2ZAbJ!++g@-o z65gx#$awOl1cwIhQ=yu*Lz;gIDH z{kh(XHoc46w<$7!DOB(!@6yg*>}wc=DHLtKq3e3SyrLpGHoXDf!EFMx3q+iDIqh}r zmy7HkO~z`hEM2jF2*vC9j#oMkEY7+A>-YhA^mimD%!_?0AJ<-%`cZH0{@^TaIoj{1 ze$q5sE789=FF)HqgFU^paAh!UnV8zz4i|SUhahJw=h_u-l{1ND!p&o1=>qOCd#mNX z&v|aYY251DOn9#Q0HfZJ;I`RdyYGjQGL(5q*?_(jP-jJdn7B1fS2G3?&{1 zNPOEOTYuvvbS1Dspud3E{^pD4c%9%CoZt?HC1_nXO8_0QI)O&b(p3E#3p}F}Dx2ZH z%H(m$MYpfs)@JIOcers_%J08@A{ytv_`{e>QhFn$DqI;h0aAvER*tvmuy5SF>GeAg z|GxDOF9_ti0+6>zV3ZW4=*B#i)vJ~ZWd?P>3@g_cal)e1U>}M~OUYJvfIdkm7^Z+e zb)Rp@rOlN_VK-4*Dn72z<^zWwJY++Z0W}iYTJ9?}HRvo~1W3hlP6LV{J_hoT1s`LQ zQhz@HxwWI$V+8?x-!h`S`T-Yvj9Ti*5Z|d=YK_ekIoapDdVVVi6V!Z(q zC62k?4^nv8kvD0}ZY?4*BG15TB5VWi`9V8x*ZBEnQ{GJ|466chNT8C#L5QB8WCCnjW0f6Q#lqasNuUsxqm8(`e|gwZ9(|MS)Ra^8((}dEctW9Ahi*30tVgAanNsk6 zTP1MF*fDQ0J7?nZ-&5+qj3xRL%m)q*4y8JMRo;j3T8D)**lp3@R{g zOub-v?7{4oMToL$PQGyvMhxI@V(O%-{4qKWs8X?g#GdYf_jR`VhK4GfmrU-SHN$lJ-&r=Pf zoSbr4rG4!2sE#2@P8o{l>C$LVyu*g%nZNUvm()F@;g^-|^s1$Ll2Rb!*Okzvi%{gb!2aK9icK~;eXh@HuhSnQyh2ads z5^dW+mc`V6yXI=bcJWBY+~I~eL};{}BWLKP$&&_wlYUuqBh=$CrMgUyqr_=R>I0+`d0_9WgA!S6AEnuR5C$8Z&g+0h`#6RP!}_QJ|WDdko|!)70vSm-<>bVfC=}S#4w<4bW%(A{A{rLee(v~ z&`{X&sM$r!8s^}b0ao2(&RsHHMqa1bj5ADvKHS`)QQ<&Zy0~OO~xr*PN!Hq;YTvK&Pa5<-`s} z%A;nk3O1({Jj;~6tXfO2BDZ>dibLv*+i2Sp3;-VB_aPwk&6N4=s4(-Y=a&nB> z*bdD=>OnS-Nr+EUj7IL3I1N0`pyRb;Pjm#1<>y-}xahiz`@B?*<^E@JAbtc^PD^{4 zWv2dj!{E0*ih4KJI|6s?*~@Frn0R>E9&c|0HMLurKcD?^@ z>qDT-792ED9+Wl>Bed~tU>LUStszpC!X=tg3Ccj-ja?U$m^WV^eARq`ugl|ey4L_g zlEWMB`~8dG1(|^`_9E6fFzw~cqpG;D4N%U&%vqN1?pVtn7mPM7yeI9Si#L!@Rh#Z^ zDlLI6$|IQ7a`1SOE;q)XXm-0#I(E*m*YJ5t}$-suCQMkuGDp=Eq`G93)k~C{4J97Rf$N)O;+r! zzo%r<4D#iHVi2kEepxs5uv2A0klU|UA8eB3o`umH?SpETc)poem8|H&FC4uv0VU%u_`0;O8I?w{jf+|!Sw za>3cO7?Lmka4aQ!CCTR3a%SZ$oIz8@NFLr2Q(Kt5(cUL30pHcxDHmW;jk;*=AS{{V zGC(!JA~ExSg7^2kTeoJvDbl}vlesNsSos{T+#GcxMyT?>C^-~tiV(!(|AuOB)|{ta zf9XoX^K5kp77{Mv`47q2d*tIn;}`DRRbTGBr(8!QijU7*pfPIJDZH6Cb z_Q!ZMAj}1IhE*%gEXHGm1)m96@aeEyev?Yl62S)(1j8)|r^|1+Bc>nqxNHuhp%320 zNBTur1aYTuh(QFI2s#p|AZo&0;LR%$Gy_c?kQuge3SI$j2W4rrydPHbnJO7Tjq#3& zo1^gaS9N2?ciW4|!}g?`%iqc7m}?k~ePabYtFz%U5xSu^eHes16|xdlG4_q7dWj!k z=!UICYGr^__G9uc^RtGM63=oPnv&Il0{RbddW(u+U3 zH~W%rOKwH0Sge!&g}G8Dw15|fhK80pzSeD?8fdo+FU^)s2+Hyb2PL|qWbLFxkVNor zyb?`zmBn6Pa4{?);5q+Q9IMsNpv7%`sS=ocRG@xie!Ld#>H5n1CfZ~Ye`eG2yCp}$ zO569(XvKu=c(;qJ*w%vYno>t-~ELGzbt-^aC!XrhgNp%kpZ zQZ_LlXmUd1@FF~@haK4_+kxk)2py5SaWWgQ=ngq~r@7w-ogtxVRn=FDdMPJx6Os=! zXtMGM!TD!1(m(B9A48TuHl%;vPx*Nq?)E(PSQWTeYvA_Zf{-VqE7Eygn5+!Slhua&&kL~LJh}8#8DaiqOU$v;qQP%jPMimk zSyx2Sg??mKMUUWaM`QAfL`cgHj;p!%56dk3mvg&-D%QKf66VHZAlHg}q4&Y~o;^h) zutun=lgDFtmTzO=8007BOyqCDIdQmM0-oS~^qpH|gv)PlA0v$GU)HE8d{_ivBE z8mhp3^#S*GO9vTdvl*Q0-K81o&>W#%VUk-hU`9=XoLO0Di;@Z3(iyfMokQ)x6LMJS z1n3o_pVz;RM|j$yA=L>Ao2Fq{|2s_yHP*5QZ`?}jXt}=9AXns$+CyM-Gv$Z?t=*pM1*u55sf9HjNe2yHi zZ*H_WiP?ywfzBX3InLEwV|xma63r1j`rP1nNrf7(${Y=8pEe;yiPL7X(GLa73aD9M zbbsm~+!wVd{7&%%=D0^nFu*gadc~EwAr8u{1ks}}pe6MFln7mjsMHJc@sz!a6rd zr%b5gojig_4%PlZTz*P45`%0J>eQ9j-U>?I^SifPdsTv9io6|3fCL{{@L)}&FiUz9 zteZc{AZ*PVF<_n?#YDe1^IembiP!T)#+_S+ksub7J%L4wSeLu@&;kCQT1L6x^2!L8 z0L{n?svxW;u#ykq8WSf-BZbA#21`+p=`R$BoYl$ICTY_P)s^f=trXn52qyyFGD5lXJY>;&-OPM z0hlY`tutSnT_E{m5(^@!j|mOTph1%p?drjRWt2GjqV3E-{=cM3xqdA)t>fR0!@|!X zqgKzWhxztYz;L&Jct}r)aZw!~kPNt^|33>qttNc2fg6|(7#s4ln89f6|8}@*0Xv4% zuL}jvqhrE=n{qj^9Ok@nhU8usJHKs&rH>FaHIvN#@+YD+a#-q&Ey}`3{dF{>ZWYrxE z#%jO!@Oq*c7ZZvY)9!dIw60&3*uCiPpYi=9xe1`zqD;2xL6~@EbZ~FVR(yDUYsPMz z75xPWOycmg=t*3DSXkOdmZ1v6#+}|yR^mK;E6hkIcky_}c_ADquK)K^^!eNE`xok~ z)hg4M=d(E>S=zQM-?97A1+%f6;%@DIKqyF6j!+ZMxAPB!C}=`ZD=KMUx&e*$k5}At zPsqN{zP>2FhrAiOD?uS32Cp=Ek*i&$$9?APN-b$fiGa2TBxVZ-O+G8+QGMM+9FQ+!0m#{r=$e*Aoa@aP^Y(H+ zrbSp|i9w+DnFJ?#B%61*^l_A6O6jQMV}-!JoQb*DjUD8Tiyi1&_jrEu0y3Y(_GFdb z79VPQP!1RKp#>44;bAH4AL_sQUHKqE0noR^zZ~bcmSouo^n3XvLz=s#U#_HUy*9wB z&*B|DgXf^Y+b@9w0Dt9fk2?SeD_%4Fx+JPvr;&OT1&)=TN%MjGPE@JRva?@FX)B%- z&OXywcbfpJQ7mWIoaT`<@Z~meT)6!LTgZ9!_szVqbQuF6I75_c7CE=Jwn$s@b=V*9 zFD^jvgEG>``p)SNUt3D_wTby_`pnO=$&+;$;3iTl95wzK?~;nYWL5{j|CaC_}?oTya8)OB|*^3IdS@*YmqR2j=fWVWUrqa8vh z+!3SbjGBMf_9gXxd0hT`nmLUb+e`nl_p;t|;f87`0hNGahSs>Zzp z96Wd36`8v)+EHONRnDL1ocW~z7MPlsby=+GO@H8I+7dZl zsLlZZ2xb2PuH1cM&H`VgG@}6HEZ_-?x6SlBb<6AFiGdCasz!AI?s7hYfGtf}ItyNW zLQEKsT1W$Np7P&IMk>3p5M707OtcL%gMrC9<~(BE=$V=L*DVw7u}V8@9JP?f!m^A< zU~PKe`kp%d`XVNH>~6i;%}*fyB{L>oLrgQWi>OHY5xv5bmA>kMhM(tg z%aM#g)>nD;zSZ*i05gf4^uP1R|E$CG&&#XR6Yg7;Z&-O5XV)gFj>`bYL$#+Dmxc4b+`8kJ7KaQQzw(-SIA zO~8r);MW{|Gb(X64X{%%N#T*^dXc^O+bTo`AAv3!6MG6@saMSQgCNj_nwDyNPO*jl zj@k?2r+ZCN%$Hx|<@9QvKj9O_R5UEPzx;3-tqy`-Dk0Aq!wmEy~e?t_#U(lew_5u@gqE4)*ug zai7<5?|^ijT)mw(P~gmWPiaWrGp;?Y-hQYz6Kz}xKuxu*_PQ_=a{863DH58T_|e#t zVzeUQ=|I|l1JkQ=`?U3}UqG$>w(aa9weeRN!9e`QjJ5{9h*zTT={*4uF7l}IrD}m! zZ)9R)f3ol4`34c%HyfC?E!xxK+(i$U3kAPcm6WkpLFj-zT^bRAMbdT2!+Lq3AcI#r zNNSBBGlq4#F`q-@X1(+0rva}Wj#CrB>)4JQ(0}M|w_t0jK3-sLHj;YK-(y9My1q1t zAEWMK^*!>yLVfugf2W&KC`hqX6JmzKdHf^RHbbN#nuy1R3SfCq?4_HMV|$X$yYQ+a zj^9jNlkc@5tV~ekHCKk4?kj3Mm`g0~x7v~t2*P=oo>;Yvwl&dsPkgl*Vw6iWMVMF* zu8!tk=6D6kMS&Nqg7nMFMc?x7S>%jvg(1GJ5$$yT*Tq35;TJU)7F^hR8IwcKkcfeg zh5Bu($KFwH_1XS94$g}W3?xuIxC9PXH8}%!Y07Nu zI~ZXFYorD+a3?w_x{rK|bENy?k7(`>jCvP>;hTS7Kb?pHlot!ocVRIY6tuNv2`Oa_^UKg= zRBS%R$I@?#>lN?_g%>8%gCf3h+!Z$x4KSr*05%+>6};gTjJ7s(j4%W$s%RI=@Kdg6 zvr>6I4YYX=QIA8yaGad{5*8(2-{bQ6Msx9^@M)}@cs!McPwwv!Ix(Pw)>BP!u|y)$ zEY{R}&s)JGdOJUK3mT>ogs}9CmUg+mR zi#=XvP)N9~t?l1OgFIADbq~X!vC!`MK-Q4V?{6_X-3pt=F4D=%!q+VrwdCyoqiPhjGX(|t@qN>9|(C4c+a=4&3m0eESVb|GI9^f z#0ix6rdP+mUB4uaj@zz6s(YU+9?_u;XxQ05(&hDrR>#}#PNlPnc9r~RPtPL7r5{(`487TExG_>G)A^yjmo4_A_V)Q1de*pN z2b5Bg$&8V`E{;ps@rIMIS)0vWx4WEI9OiJ$Ci#sfp$dg?Kj38t(^f7RjhO+8G81EU zw`Xk~IdxcpO6_8|ixHnbLDd#w6r=i2sw~f1HNaB3Xk#iaMMGk2Tj(yt(Y79QDDpw#rJjd8-wZhdC5PRLisD;2P z(AFAzRJ7;TA3!S@iq#WQo>M%1{EegOE;l}-ddiWIR96{?-;=m%w(CvP9aUaT4jl%4 zXgX84E^`RLnW~IEL$)}^G6fZ&2RZG_YsI8gqy2idJc{r2noK;)sj#@s(k0u(@(q}~ zvxYx3K(T)e6h4U+q?*Xc)DRFc%hbfb>>eTk8BV@Np@UiiGwOAPR+JdLLn2hpjQ?Rl?d5@)dQU(rpqtie{C_OpZ$ zHICot5`h84e31l2$+hr2D6%pLi4H-QzE%G#YuAKeH>>=-hXgmRz4*S1>gj^pOt>&U zhin@_co@-=MgcaZ`a{xtaLe8Jj!`!)Hu*k1w#WzF)FMQ(k*;XQ273Y|I{OC{^x$u5 zS%%#_7Wr$iMJK){q1iKIafeM`YA3FDq@ks>NeU~%Gp3yYO^9FO|&6HE4OV~Q}=j%!T#z-1|66=R>u-p*; zY;enEMJANlz3z~(Kb|%oLQ;C;T^>XOt~Ht8+qMES9w`tL`@M2mjH?*NTu+;5kEp<%Rs{&Y)x?H)(Z$b)Gho@Nio((lcb z@>Vwea|K|23e7AP`T!-1;;yXYfg@n_2-q%LzntxM1|b3)S)&sb0Dj*d#FM&O96x{T zxP9Ed6a^T(_X`8hX3S=owuJiZeSkO~bVh(ejS+UVAVQYp3Jad-#e7Fy2V#1IWlv~y zg=g^9R47Pxs=rsQh_BSHzxk$^aL`d8^N;7zD5Z2j_Gp&ymN)gR9klt0@`~bT+8RF~ ztxfg`WK1ZrF3@3fGf`m3h9HC)Y?b?SB312}8{j|>-~~;UP)H(pkx7XjV<*4@e~XxX z#o@I@4USU5XH5TIQ~An?cZ6>joVb7Z0v8SiN@a(}@J>vZKNvwIiKD4Xn@C}R^ASNK zaVUAe4qUE^UPWYPfDD#?Ef8uoWy?%zm235;v(B~dkgg@6a7CHqH+X->pJs(8Lu{qL z#^ErDy2Wm$0Yxv|hY*jf{6owCu)k9N;T#qvdENX;I zKjU*GWoSiC3*?Ak3|dh6ouM^k^_;m6TGaNs81w@JuL$U{qa^1`j(iPj`0pkp z^JvejsnXPIgFbRj**5$%3Kzke9(URgZI3@`5wH`Cl9a4F!p{DsLKvEl4n%^l5gq1X zQtyj(4vO_F5;%y^o?gLh4}@gDo`?wicpuf)CIJ7jJ@Pg zlhQ9<_}G2swZG!nO-p;UPe3jfKQaXOLt{i z>gFuHjruI>Es6JK7h>}Kb@jm|hVkQ!oT06QtmodiNE`@aCh>sw&?_=@B8}WI>bts< z@s62#UC=KjZyT=hOm*4u?{)4O?-#Ygz37D(1a-KVIM@+>JqD4alT7_q+ z=j!7j7`#ca838IL^WQPC$>>m1lME|858eVpuB}HYWwxagA%INtQD3gYicjiO;Rn_4 zI#v{Gg*=;`Tc{Bs?y!!jpDPmDTi6!(g+_z2zC_W`6c4Zcjdu}Sp&s_(ti%|E|2?EA z2}&{Z#Qnm2VPzMTsHpN+jjvK7r@c?K!(xj+^Q8x!YRQ)pm9)QSYvX}{!eTyd>1!=P3!rAY zyFyU48OW!%&o_F0-H$p0aKX#{!uZ5dE3fru=L^h^bIjw_`si{0Q@7(qH!?u8dn0kT z9>VWYb>=bkFrCBI+&JrPs~C!$*eu5eS2{6l1?5C3_J4R zw8tnG5NJa&dy}b4|Aeuey|Qx_K=l6GJM{YiFyksqAO$L~QzsH=CJfeU<-n+80vHfjYc|wQlHS4!VKoVC4MFBs8 zuLB{*^zYHSGpiZ|CZ@J0(IQpW8yxzSZqMl}Usd9PKa`W$S9DG=zo5C zy#L$SF$%?|Xu99cI;hZL4W$Ek`3i+Wwxl9)(K`5RS3?$@Skpz*2kYHBXX(5WV^jiD4%mQ?tYAp((#k^iQ+6JMJB~O~S6C^^ zxfd7gAt6MRC83VX>ChmjbigGP)rSvct|=wmlRfNJL@LMjC$%;;d&VTCt7H0rVeKg{ z=SymT!1u_ayCbi)NPn6y>$czSP%m(S5}SeFK@9AmAZiK`BuP0t{+VB6O4;3PV+=bJxUI z6P`>&I_V7X`fGcgG>}l$PUgKxWTR(^L4@+e=G<0RlrosZ)JS7|m4*t6_ng%FfD zk&7W2E53810vh9e?sb8H(gjdIfPSnbKS-JFzw4rgu4^KbJ{<57RH50LyS1xaLT*BF9TTuy)*MbqoQF z*)QJ906Seea07FY(R9Aj$Zs8yCi{!}(OgAVsZy10S>5s*gtfxygKutBH5pjVW;i{Z zZC|(P6m0N+(ES|(&VJbP2 zTeaj};VF(z?X_81Qj*VB>rYiHDw0j|&&Z8yMh3+q)0*CL2#0)6n0<%#D^!Ht+)9>) z670Ab6hVN55VpC}@dr51+6S||zPCh|N!{GaJNpoL&gITen`aVNa%d{My1FMncHF#q zeu9O6S62guBv>J=ZIzbfS$Um^#ZgK3PfUQ)&Q?a=>$MfMMrc?)F}CpSfr}gNO85x8G#@j+at+ zWX2*VHy1%W={ zu%m=4Gb(kTpVP{MYE651PCN%otCM1Kbg-~0i*>jN?ttmu!0RZ0xIS`FokZz(34+2* zTldaNnidAdxNb_(v;ScVH+IY<^z!zBgYx{Ij(D-LxzR-Y?pT4rD8(gy$hvdP=TrDB z*n`bnE{Q)audEal)PK4>0h0z>$)(X0gV%!xe5*~vhC&&siZnv(5(kko6uV9Q(#8RSE8+i(izktH z|M#`raeDe=mxrOl-aoO4cepg0R{%@pv9dLQIg!D#`@b#f^a~A;N@ozrdP5CNn)r{A zqgkfzVrCIa;p``v3BP#0?a1Q}yjS_-wG|7bb7lclVZ3V(wy>+6LySUO7XdJ_peJ6U z`#*xj{P+`Rvtiu)+GWzOzq|8zZ|N4DEIgKa3Raw^9fZ&k^E_L_9G4d|u==v)jL$9& zh0;(Xo!m7cCYJF9N5r&~0tCIZ${A?9)@DT3PnR`dsl2W2p~(#7ct>%8@j>WVvZ!P{ zeu>+S%B#;$v&jm(^R9EOvbD%ASS0(1KlHLl=cb5N%0BdsyjH?b;vk0HFxp>S=44u( zZ_7O%eEiroM6n>6wX2hq+eIDvjdYh)=@_tf{Oq6YPB%93y4c5i%qFDXTr ziZp*-Nap!<(Va8!rAE>_=FZ(XaTFC7+6F@wWf)BJJ7fr1%8l1F)(5bvXylorHg0Tb zk}FBRL14DiTksJxQ_=&k?4cs_ydwjL)hQLy{%kS9v4co-Ao$&9nAvqD5pM_!%{Y@K z$;WHUA8i0ykLf4@B|#^Zezvo~7ez_8^^NiJK)$qO4!%L>d9naK^9~JA25qwTzN&2f zYuA1oGH`zzPGdDc=6LU;p`g?V!Rwsa1Eeueo4Y>@oto%ya?_Ma*y+;$Kvar=kv`BXb^ z(^=}-1>kNBx7|K789yC%TmpS^B55=m0djynk~Fd-;$cTwO!(im@;@wE<_48Whj!iFkwRe`7LKkBO3vQr$R`{VH)3dEws9~D zx^+*67<+B}prOTn=dxF5!QUWkZ~DI0resr!eQ{(?fw8!7$WvL~*y3 zBN+7mfd zY7BBr+P?bEs+yH8s9PRspsbY0Shqyw$1TsVTCSS<+*M~QTCtJ)1YCuHySx_RB*2+* zmY!Y&@Mg9`S$}-b+O}Oqf&M(MdOU5s*iO=Ly*oGkkCj)^xC%sXvj8l}f5ieoDdQY5TWK++jdi+j*C?FqycN3( zidV%qWQnfigrcyIq?f1S_LK)lOx80)MS~#zMtzC0Q|$J!(Hl5Vu3v58u|XBO>?2-M zOe`5+(){1k`0OKOM4sh@sLqh@u@E2_+~7c~Gc!K)v5$qSnw7^?$Mlvl>J48)jen&a zdd0#`V_9=W-+Y`$TVK7`~Y?TkH@?b|2RR0i8ZiY4I6coxCOFGM)Bq@;!+6VVd0L) z;6h(3SM&`ld==Cd6IxO6VB-w-Fe=e;<#Epo(Kuo0GCNuFh{+@0!ZiMepQ9d*O(FDo zbhc{!(7v+YUXbT~4S-}CUT`Gtl z_6lYRxFZyAaAb}vP^mOVNL6Fjc_{qBYB$I@>!h(Mh2M;m?5S`MVP6q*q(#k-&y~*- zi6s|}YB?ZALcl}%&QT?MgG-M^(Cq0bjL=$xp^9 z{dQ}s_&Y__+_`VRefsosNC2jzBS5tCCW(=TE}`6b+2?r#Alp)gh9o3UGe83y<#QQj zxC@9@+$z}4gE-!ghVLhi0IWrKsooSmPUMXjK-pm}8u|;7yj_GPr~>R>|8(FdmZs$Y z1nD@@KR-^4hWc-HxK^T@B|1)*KR*)h;zVaUDXEwo6RmIxta95^8 zL|EGzsA?U+PV+;G)3`lW!nLre+F5sy-e3%Pg`%<94S12hIncU%$@SjGk0l|JsR*VG z|AvGLP528TL4wC-ckH9KK$c>KfO}C~OnwZJM6F?*YUF*_aFz`9n}}cL`w7X$cqVW` zU`76!s+?=JirS>(>NM-uFPaW#V}q&BBiFV!cEn!@eZ#b+)A0~biAaO?MdFb-L>$eO zLT0JM8anNCrT5Kj_u>A%~hh0;6EM%JDbqkDe2~L`kSrNowrPj|yhnu6w#sl(VF&7P#N? z6v={9xwBpPt&9v+U@UKnN|6)}k)|!)GKt;AlyDWZu%Z%eUY#7+kdX#Rnr09gTriHbJz8s<7 zjyxEN7l8>)Z<2HL>)>@5m@*}oSTTpd5>h&OFbSsQ3)?GCk(qrtpWv6a$kX%Z`cN|G z$&Q69iXOr-Sq~H-`hC%o+qum80RgQea12+3kJS4&5(HWez1+7r31qw9$ib4~27kA$ zxzE;QF$YIn3DH;Giu7<5IAjyUTRImG?)^lDM`v9+YSngy&-NGIr^{Fk9xH#L5{4Qd zixr9in1ZxRP0*Cpo}m@7s%qgUDq1aN6$B1?hff*Ua*M=i7Tl2YhipN1P}SDX{&>Zr z#E@vd2k;K@`uyW<0f5+Hs9&~wAWF`FZK1(+m3w{{CMl_GRGS~S^~naVIjfA{DU$b- z<@~N@J^QyS&#tQlM+_;9lEn^!@iFu;U<#oTd%Ze|zx+=gt25fK0g=&*WFu@kE`zF8!z0L)js=02K* ze9cI%u**JxohPVxYXf0=(c}C--a_eRe88@IPSS~<*5hQIj}DA3E-%m;eMYO ze7xvj$BLIW(yEWtm#*|c(^{1P3R}2z3Z_LjTSn6q&8BiNkIPaP9Y8C|nJG9|F| zh_fItbZQl=@+hYkSqFYMjQH&yQ}1QwnRXk=cl@ECdiQBmMTP3EjjmVypU)p`T@B@lCn2jM~G`MUbEKer(0i z5su@^u6y7*5ly)@(lDfr$q|-QeVH!PsY)7M0`$WYPzH)_^R$)D^dsfLnpUR)jhyNt zxStik@gBCtmRfh*Yx#vdpLgd0l2an(mPqG)=gS|*SCYSe&!;a_=P%5FkpDHccXRWD zkWip`yRWG2_OdfGOxw47Xx0S&Um@hv^Q9PK_3*kZJELHcQ*%e)5J z^Fr;)D8@afgvmunTm|Y6X)vM{hn9WQ*S!!aYSYVp65&Y&o=$vODue@alje2p&sXD& z&YAB%TN4AV^V!T`YD|$KJ^LO5;IbG9Hi;CH5*Ha5W7gyMVg9Q9`^nXN>2*v<@Oi-5 zuGPnx-nG)UxTMs`;=7qXboUVjoT|M~0!zNoGpETb+)wbGK4HDH%mf790yp*EiKqJ_ zB5pb!k!&Ek@Gqx}kjB^SsdBu~2=F}e)^E~S5;4JRPMh&&Pocy>^pYES>18E3Df@<@ zS!jx{883wtZ>90`K)8WRl>3@9nlYY<_UD3gvhAtJoH}D21hVkJ4{O>~SPUO|40ltW zYo!)BZLoI!t+(dDcU_Z~DaIsCA2>C9RylnCt#s|#8$XH=Nl+jHPPBtE&!6uzq$T52 z{sa_T*f3NR!CT5`qL8XPvbr`nZpWZbtt4LVu`yC}ed;{qoMnYc?) zgt6jBZO%2(a3bse#$LUvpOGXi+r0ZJbsdRid0vsg#L<00$AT>ld?+;T%p=6XVLa0b z&%DZ4H19ISUM6Km{jacpcc5}{fL_yynp3|_B}b1vLDu-&#Vm#3^OA~J*qG0r<9mpY zQov&O4nOj*)u3{itUF{1^Ay&v(1$DA0;NL^0!cM0J{85gRYjcsMj$(^x?%Smlc_c`txaOtZpt#t*)#v8<%H@&<)IWE z11aZO?y$yNV?8{f172mVi)q6LOh>PN`>&+|xYb0)K4eB7r((r_y{1q~QFhg_$rbYk z@Ps~|a$j=QNscjushWoAx>LVRM5?=wL$+LjyVWP!B*BpnP z`^U5%W4zL)T+rlim1!v-i%VYX>ubH}nArcMNg#gq?G!+yD!tz*{YNZcZE*xt*sG&w z;mN-}01Z3Xcw~1MCdMnrXI*O1)eFQo0kW26b~n#Q*9orW!5|-CEdxk5|Jh_li|b(#)U}?k)LA8V#i|Q!Gi;2e z>wim5_#+$9b_2_DGkL|Z$vzEwE+A#D@2ZXk97OWPinu45OwTDuz;31!$Q_zut6qPl zFr~OfX16juX5iq_#m{mpN+qbQiJinn5l3i<9p~wKB?YRULVBuH(eieH|06+~VRM-K z`y2}O&<)WTG+Ibk6qY;dm0v3AateQXoASsfx%=bx&EM|zFCC4 zgACo8B1S|N>|{fVD}#Z*I_QdYb6cm+O8=diw&X%EPO*$bg7P~bZhv|=`!D+}QUnWx zU~_HDgxLQAQ3daoOaYUo@IxCK(?zbaX>Z`i{h0tz|>TP7Jwtz(k zMkhsdT5EK;NR;+4KG$9B{W~#fv^Wkf?onXW)RV0`2s})C!ML2f4|-;Q#8%s|W*sQ( z;7ce4+y^W@75@&e`D|kO!;!qwx(KBp_w&~M`wisJDdL8L$FrWER7`YwD0~gE?@Z0} z+RetY?G{Uw$4Y89$Mw?T4S;V42#H{uo5amHZe-Ic7jjw|sD)Ik9BTh!hxglm3wFF^ySwV0&g&eJaX>Z!IXarJKLa`9ZvWx73t2Z?Em48VC*7_c zu{O^bsuTIL6z!}t_0CA(EQt|eFjM}Xto-e+xygofH51XJhQ8}^+uLZQ;h-k z>t|x0Lt_|%y7ot|^wQqT9U7~J(w{dt%A`+h0FNHY={wBM4X@2E-WG~TfCU~p%*c3M zAlK`N31Z1Ek`ZZ|Fq~NU`E#%ec=(z&jR6_?)@1dr@QDOa93shG^bLRdAo5mu{?q%( zSmiz8jAoVsB5@+Z3jH`KouktPDp1~?bnN(IHZXK+YYF!!DnfmfrkC}^%Ik{))}b^! zEx9C`_2`_<*i{J(9aVda2>f_0)d} zoC-mqPf0}BknlM-R0=JRiR-JvG za~8nQJEBciK&r!Es4BqK*5+0%HoH-sxPJZg%;9?V6ZJbZOAVe#udmS9Y1QV@C~AWz;=(#T|HZ@YL_{a#ZwL0~bnjZJ1s=o6+W9xJ%bBI}9b^J9yJ4 z%2f-9f@tbsZrl3Oy6D;yT%kZxNhtDD&zTs4OlrtSO*3?pADpu{SK$vsD$%Nla@DL% zL9Ed~zYqeGW{Y3?e1<3ri>i}ufWeNuI$8=_Iz1IoNUfz65fUW&fvW*zRus2 zo75F(H*b5<`b1u_{(2t3PRoy(g<@yFn<80p$rYiTb=+Hd!IMpq%y`%LHiAJZP)Vjt zE~~8^e@j!NKfdmU9Ci!2wwL4mo^-4!{pQ=MPP`w~K=)-KMZiM=a2Mew?nW6Tp)V~v&jV`V-viEJAkMYEWdAAJLK{#_=oafj|C%9DCs_(-rnwcjZ zkGvAg(`&5K&{Tf0IKA9q7?IyGx*Vg*r)^%clO@h74N#|fW)pR*YQPNI3`Cp5HFKhs zlcoxAC#hzYtI-}H1fokU&Y~o-UN|A~9Vcmwr4SP=@GDMH%VE=om|I>52s^BoXxl2& z;vBiGe9b@>N7!a1&vL)ivH$Lwrr8;!`|ZMqM2+WX!)L!?8ZDPYPND4VAO`~M@xfZ3 zo$a4~ucR^3ZB{MSkM~1=CnV#%oqVZF)izW?pB{-q_{^Z@{z+bn+bD|vpw?740oqX5 z{9?dwM(Gq?$|77%8;j*+c)m%4%`tWq8p)+&I&&wR-L}4H|+eSwQ~D z*RCb76gI!L9Jtxbn{(>Z9JNiZd4`F^fnSvTVi-KK-T%7c`rH(iZ@k$j@}j^Ilsair z{n**J;$p78C`~3mB9R>5>pdYI+ta?4Ns$_bX_T)bDqhkx`(E8TfE>W_N0l*V57TBnPtgr6Zd-M z>WnFU#FNHSa3pUO%(O_PKLD3yv&0-us3v&X(-Nqmlv0<**B5)Wf$Cer6pJF%zJ*iB zVTO5}#(&=st@H~KrI(w|Bw~-CyZJ4f5$`%@A&#A{nM)Z9SZ^?3F+x;HT!IqTnLbX*r!7nv<20P9Wf_!j1(o zBbUPjtFjwZEz+eu^SRl%wG&Wr&&N5DrKi@Llq3T3WeKvvqV*qw^o){}vQG(H%fo2j zZ%>#ljU-SJMv>G1`Q8!}KmS2nZfhZF!yls5JPhp_Tao39RX@R?RHiL-6-=D4OMROX zfb!e%Wo0s18rrjb@FqU^B>dEimMC}$6Z8Hi67N-+d&rNf?foa3UCt! zRT|9j;#OvMX+5^4?T@t_PxPsu3aoh_8!M%$*cL9?;25aop(V}e;k$q(M=45wjLc~d1C>o*jiHp1fXK`rl;?X z(V@oKFFTe)BCRtIYP9tZ(^as6(9Z8Bfzm~&P%x3I^|Fq9Va*83%SaMr!ID;AIBQ~z zy{uNS#TkmMxs{Q33be4;5M+ZzhBk^3bfOkPia$Wtf{-DDFHAam$2 zhhFSTZ(1j9-)!~ar>$wGThIPN65ToCR&IiY+GGA`;ALtO=!{?hKq&mzzel#dPk2L6 zQGrL50%Sk`{R6{U)PKunG^TA^IXjpFW2bEuBB2i>J%jPq%8QZ{RVze=NjO@nYo!rw zMA|mrIyK>aG5+t?7RtG)qIZ@4BQZTR7EDQ7qpMBI`}mJ6)V*4Q8Ur#a+K)}yB_09u zHHca;Kb-d`iPJZcW2Se)2ExawJ#6>2Bj*i~DHiBAEa4uke|tOr@AB2l{tT1d4@lek z?H55G#v3de(iQ*g1$X0>5QHdyI(=YMcSKWv%5dw{RHcapCWt-%HXpac&;!RrS!B?n z^9cvdnI;rImMP`*9eF8!O_gdbOB=AwubXKgwLLg&JPz(svcRX(sgnItM^niKI6XG` zQK4ULzY(SJDjuFzY`O~CF~}cw2Lr;qcbHQ)`f#L8XK3=Le%4V7dv5z>{;~{DYh}=6 zl2wRHZyqIECU?6C8BA?fKP$M9Hgi;%(c)bk;rNyx7^_JaDVD93w&)eNB=;ZEvkHk6 zgXG1LW*gx`m&JH=5Qu{R$gj`}`4r@I6r;nD0g>k-nA~P1c31H6Mxz zKg(g39o5Q9v3&bz)h6b<&AFe;6y+DE`bi*bZy*Bl;UFcnCMVO3Pp!9=9ZLnf-K!gDRRfQ-O}Z1AQz{e2<8@;#(&mRz9rZm z9ae5<4jUu#R3)3aNtch11s5qZlLD@%L0$fg8BUbMc*XXZ*_6$5UC8uqd7K^@onL`9 z;Li@&piXLHIpVt;4&jX);p2YPi`D5A1Kw-|sN}>Oji(U{_5rcyVc$$#oarpEY)0zA zJRy^h$Olej28j~K539|%r|;-eDvP8_0=C{{1KJi&2ja&Q8Dv?V$`YzU$jeGPc32Q`h zcx-&8E}J`?1x_46T*SyKpM;L8)YAdp&Nd^q;@~*rXPY>j zHAg;V5RMaRSuW3%tSa zxsp^Jm$;6l%IrVBS;*@LQHTh}CM+!Zcp@rXE0brzL5+2W^OBzqXASzl-EyBSEZ@X@*+q`q^Af2ZshPeSdjpFY~cCK+aeT9 z-hoNu(!z}La$2Zo3ETRZY&8`eJPrHRUQY<)(QDEAVLl5Bq z5===%Rl3MQ^1XE~vtJdTUrih{t)cm*uj5q{N6o(J-&fO0b7zso?%=B$XYPB>g(8vY zf+AESy*d>;4dnOqeB(^WhM$1{)ArVZjU2pRWR1~gAOR6_(U$-`eSYYlt?#z>^n=nV zF~air#eFNK{?Ns{refHueo}xyhMMK&ST2wc0ZE{irIoL)uC9;g%s*Rz>$F1{%j>rw z{FAdebsudXH5E)3t};DSe8z`zE@17j*SD9pEmq%sqS`Y-C@i*ZkaOJY%hq z#)XE+WOlOd*L?PcJfe_Ol+0uw6Y+;6$SV{HPh7^zl(w<4*?ZWbc&E_Ii}cgo)SIF< zk%n#(F4iBk*hZ(U^a9cmPM zQHIfYSZ`A30{?J+fsCPheTjatp}6}_ngmm~29ufWjGFQtBZHE&bST0wFfufX9Dp?y zvi2cK1dBaR{t{j#aZf%Y*|Wtf$E2DlM@h7uyBFK&61s-tW-+j19F zBqAtJh z3xO>7BJ}`QZQ>a(2OgRdjEnX_9w^2s*b3A=Y?F5MCtFi*wIV0`n0!Ey987BvFW6Qa zHFM&#g~aD~eh)-=Wprw}0w#*t$iBTBH{7(*ikc4fn%%iFedg%!l z@-=5>f$<@6BysTXXqS0CDzt`^WmepP1LvDfz+F7-hBRFjAaolwk~m`43wIz{D8u&zbCeO_^E}1Ce?Np7OMQSXO80i+ zj|1?G&;5Aj(+)-OjaAEJb2!M?F)!Lh)GRxW#=i}JiOdm5bF0RM4n{|=CfS_7BuNr9QH{Uu(y+PxiZIS}P{sY;QoW>7!XWnP3j-S57%AhTG zpOs1Kmt}tCc2?0vUS>DrsJ|fRH-iK&4V|Wl@(@7PD!0Vqjzh z4+uKVsHj@6r`YXsp8~6u8}aA7Sy8cc z-bK6}38)vf*FE2Jf90)I-D|X)F&UT{_du=MSs~S)>P%!YHA%^t8^V@qr5A6jvWo}-Lr~?yvE5_h z`7@9LQ6)%j5g1)A$B-zj3z}hvyerdxu25%Cuj2CApu%q%E#5wSntSH1rTm_Gr;_|B z)RS1MzLZJ^(j&&5h;?AIGyg>zeu!3SLC#ztoJx&%fj-ol-Ni3ZO-3mJJnUqX=wZVr z#REW^nB4>w@nC*o1`{T*BD2~hks=U$n!i8oj1hV1pT3-aTYmn?`>kgilGk;QA zQe+nW)ju`N?{}vD)3|TbLNEbRHKj8vZ4oqif_?jw-j{+wChH|Ssq@F57TO|l8PAsrLuwUrIv)NVnZskXkt;)o&D<+<<|u>I8N>>{l3Uj(#+&1P<^nzBuBva? zHqfs4zjeNkwQt-yaNDnga`?0L>9yx`%2cpg-9kD6VPB)BD!d@zv-x(+rOHIe6aRxYz83pCisg%9j_`Pw zZ@cAQ-2GY3^9z_&1ux5t?>PkN7CdrPIx_9&c6ME-BsBQ8?VLvZm6GFQf}s@Nl;QN6 znQuPrCqH!3U`Yrz)W%?qMtuyPJFx0h0kK@_Xnil8lQTps&jht{hLqNwp>{an+jVv# z73?EaLOPX~KL_T$!iLk-Dy#jshFU)g)tLs%*H)X9H|Bh?nRaw~X69j*E^z*LdVZed z`t{tOL?dLYKu)kloEwXdt+h5^GYF)iToZn{QQ0%vI-kc2cKs=OI)FYLiy+)vH{G?^ zBdTuEp~7Y#{1JD4oekU<0&A2T-T;I zcK5}euSMP|>%UePWS)9;3e%hzWx_=a=t1*Ism!>38IC}Fry25)f1*zerUS=u*%|#*%N7HuO+uiuL!&(gDlo$x*I} zN1E|QR-d|GEuP=3A z56wd2(EUs3XEbj&`-5@AH)fItBlVR=W!8k|I;J>55+rkKY$+)a0KnK6e*bof4X9$hjPV^5@CCb#ZQ^2#^DI!Gqvl;$o(JG7V8pgd=FpIu0y(Cpp-0j2*-_HK&Ij(XyU6r7~^~dAE6+@giBvd%(dHx0Hpq$=!4U&Ax&@JZUwZh^` zahzZ?)X-@7f*(4q#O$3WfV~z#xvLR9c=&9l=Ffw~ml%uU4Ld;8RDJJ!>Y` zXx6~i+LTc}ut(5Zdon5KD~^o^ggX)q_hz^a+70{!_8NgSkp-KOmtD#lCVch^ywKXB zI;(gTm3jInFr2uGax!mtjieA7q5FX;lhc>9*(j`~2yBFaWU>WNL>unRT;g64$s@X2 z2ozxHhW7Gm^L%_0!280BwO~-o`au~RXXBcpI|7BjUX;`GGxe2~H^H-T9tob=y}dyB z;t9~FYvDGw^n2`@%4EP;E`wP4yQ(J!Qc#yTdV@(|Uh<|z&l>heV!uWhmixWUK|A_< zaI@FF_^S#s0g%!OAZHVuGTO+%LhIctHM`Y@7@srkxBU}C%i-9ZY(dw|PH(qgrq6Cy zML|4Is*e2F8m2bi1MQ#YVi?nc)X*}BnBwhziGqQjH9;ziJ`v^BC_0Eh`tO)4lX!6e>V7H z+exYO;=-NIGd<5;OAl4_w7HTt+*gpog9{e>p;njZpn&zzTUo*Pu~=6j*sAxZkf7zK z4<-f^~5Ayf?`091G$|raaw@X5eh>c2Pw7+2x9vK%Vdr0|T{Rwe;l$ z^5_q;h;7zn(Rd5rQ_?+se`$9es8%H-N+@H<(@Qyiw`KR%(yY>;rlA37f6k!vT1f<0 zK#YQ9C+svXTv%K;dC`L*;tMD)LN-edH%Qe$aj}OQ7moWP68MF|XvJFH9!uN~R>uks zbDTzmJH%RwNpK*bXAiPt9&yPo)5 zCFSixlRQuvJVtsyK5e`*_1HNsCJxyyeiVq6Ejctbno@&?ChYz$iXf(|Mc8GS=dR{P zR~{+)gzC@~XpA>Yz?dsZPq5{hizN@qf*S=hM7T8L%W`U?!xmZfkObMTZu_G1rkB?`;wxrPr)(iF+mQKr#;zX!mxf{`Gs%bm8k`lt5u zRT{{Up?fW6q)M=*aI*OmZ8dHmYtPJWDEy&^;BiPidt%D1Z{DgymH^uqQx+!Z{t4Ga zeFC7yzbss8O?kdB>4z=#U&^C(oa-Ag<%VEK=BKl8&KE71g&@FcwEV=vHyOo_v>=~< zt%AZH29@2vAoc70ZdvtIceu zcz)k}{Y5kxf#X4es*HM3GT;dN1ScbWFnTu_J>3FZIeov6UWnrrM@>x)84br%3rGy)cz^!uf0c^-@I9*ZNOwtcl(1Ru0p=k2HWrhsi2bn@dfZPPOj5D-%Y-D5}UFNJy1qR^Z4jrn^PZu z^?ADp;EQ|T9wC|V-QsG%WVP2x3&#kZggw$R9x^E}oyp!Z>GXz`yEJn zGppW9xN!m3?6^9%450ybr)0t7qGmuZLt2!;e%)z%3nEd*Q*hC;&r0n9iod1TWSxXks)!hbU1!iA0Y z&Iit15j3U`wLvHI%kvwCjOONzO zcWd`b9{t_Um)nvcH~S#?bHlku=;_tXHD*G1G8n)?ay$X-{jf7FGx|Sj8Sb8JJis}W z=Vx5<4S&)oGH}np!!M??z8-=%90qoQHUGBtN3rCRrrJ47Rl|vw+v+@(9brOHRWz`q zCdo=7U5>*K&1tbQjmgnb};b964jWG!Q?wlo&043dmE@O&k=l!~5%4dDJYj?Sw2Ds?-;VgG3b& z4z~`fTnj?i4JWA3I;;L`b_7Uf8?nMRDdeH04XxdAmbu=sqk6Fkz@qpi-k=GFKIHN* zf7AB>Nq%SjbpiGodAo-RNpu*z=7nz-jojs zQ$86H(-#-n!^DyPo@Y_1@hLy7dI?}KHD|Y4MyY}eRh=aw2cZDyi`jJU+Rg3#^_aK8 z)X^_Xxnk8{x0j_~C{o7~t?m0G%Pyg5_pUde|E)AdX>Huw{MFfm^DoT8l9M$%{LPIo zfFF1uOZic31_Qq-lbW0d@sX(S_sUlVgn$F@L#=Xle#M;sg1>i$W1a6Nw1w~L<1YVl zggqQ zX`G0K=OE0AVgIxH*Y+3_i5^({#>{T-^t~wP=HA75xXYI^i4It??mhZ-u+(CSmLi_3 z>W5iivs6E17LE&CD{NA(G^8U40c%LbXAsIgTJku~-C1YM_ zC1$%vVCyR;3Eop@EBxzAdzy;_9aUxl4^0^tIkHdUC0_m4Xe3-XkL?PH#uhVx^w;wr z*A!?nh&A>mmYsc$A$dFV%g&8%Ziyp}q#;8)aU!55y+R%BiM5W=?-;ZyAw2{se2B16 zJjI;Mvo{5_99#S|bD@olP#YQduFdvpj1ycXoC;AaK3msjzwnt21eK_hwhO}EVI_hj zz>10hp{n+@`wzJmxdsjymH0xuz7{-IP!P|s4@+=YR|=m}1j6Tk;P=#*_hipXi}wutpb=(Id@cxfGob!Y1Xg(_`dlX)v$_EiEl0 zCYhMbp#8w9jVFb{d;5rcQ6;t+hMb#4DZ&I>I6N+)x(=NsON%;T87#QWq}}<%gB#5-!Fx28Db^P36lwQPF84Po zwDVc?YtMSEzQYjSu*%_2A=SC+%h>9=rBX6 z@Tud$B$r-cUwfkd^`z;3OhEhf+^nC?>zUZ;eK$qCy8E>A%pBq3Gs!KBtq~65CmqFdC^?bvFXb?Z*hA%$uHEcA0n0Y3X{b$>wwZyy)t&6XXc9DRl11vTR35Lys;` z7>W$-xp9*4d?xAUy54B6h;Coq=-z?>bJnm3B$6O2OuQ+O|JvkqdVaERBM8NTZ3{#( zM42(WO^0~u*Dc}`5Ny9ZUI!bC`a9mcJSOz+zbRrDOw4vW=y{3k zTb=2AHuAW(GDm|aV6a1tFCLUouS<8wN6ge1o(Fisv)2AeK{$c45z<|h*K=QnlE&=2 zKGmfN);-uhQkfUkRk?P-gDHoAqzN;6+(#QrYQM*Ie_mU&f7uc7%QJj#io*m3r8YQ= zuFGvW%=e0XQ^W{?wE0Wjj-vioY%-ein%#T;uQ zDe%zYjy1Y55C7_Nf(cBW;;bab3|>RPAe~Xp6@Za|4nFsp?qEtX##6i(dH8khj2Ak9 z$@X^I{fJj;e!U$vEGpS_7a|_u!mq&SpqAa{)*XXRPYb2u9xt?ZH*PQs6{w&C~NX zg`7fX{`In|Jz?icIUwA4pvGk}Faq|=YO${8;84-36)eqCSCml!t0r7C3}e+h^Eq1KO;B)P3fO>8(C?iUey#D^D;DC>d}8< zIDR;S@S4Rv38&HSHo2ydt>I$Bn*Np1`r_L#kJ0S*jLQFe0UjFQ*Y9gbsvRPN#bg;% z^3$t|DtYdGe;Oc~^Xlthq-a^C#+<+k`tS1Djhm<$l2m{Ly=tO$8MYP}WS9RrX)E|l zQ>2bmuazeK7%lj88!0he%a)IZ4>w|lxiz0}0RMbESmSV*JoMd}9zKxt*y*Jx?j1u( z8oRUCbvkB#eHC(XcT;A- zwH&9+`nzJ)eJ#)(bI?k(+<}&t!=1G z*F8e_RTT+bVW}(`jDVX}V^gooEf!T`wkeXXffac6Xe>8k+;cNTB?) z5M0U4fpr4gqBAI4Y;}GJjHJ_P^87NtG7gn?2|qnQm8X<_%duds&pZs3>(n&-^(Z=K zmCJ-%s@$X)ydA)qAQn!(7ua8qOm*o&H0)#ntER3|qE~zI;vDvf_WrhUy(ZH&{=9xK zEPQ=5{q5{8-^!{$_@K$|uyifoL{(($H=%UAkghJzK*Zb3kE7BQ8FD6gMZgfPl*Q4W zf+|{R_pm+*uQIasq?ld%?-h1w^NV3>=@A&b52SbP_AYjQ9;VDwVhV1Zn@bl|~2C_fv<@ z>IyO(j8Kb~tNVV55qPCvXmYHL1=9{*HfI{#!C8!7Hfk_DgaO^@yYX#`bMOZN^O=>k z(DU7R)rjI|9!IK<15(PQ39W--YkHs!Xr{y`&$xF!n7Y~|Br$uQ($D7ih0|C7HkgG` zgj}%c|+f+T~uv$8o#^wg^1I1?hwF!9|B^7!{pKd?`fHxn$vmY?2H$M$W zz{sa{Rd@X);D;dKgvxN1pT(wr+tUai{E_i3BzBN-Do><$t3NDYB-pl;tU@!&C7o&9 zVt8sz@GZ%b2TTFnsgtj%g3~L`ans!b)#Y)!%AD>VU}J?mlM|3Ae#d&tdDQ%M zI?u7&Xn`doDy0r{vc>5m{W>op4gnuGf%^BvPB1pEF;M=mkbmwH`CGmriZqOwp4G=(Q>{vI(4dhbY|CI zvEXoHzJ6mBD&^2IkU(Q#6v@oFp{SLr}Vj z-(BrI7wB&)l2{THEIqHY)+b0_dPy$OHeTSHrDOEIHplF=>74}8MMnO9#u@Q-C*yJa z_`4$O=g0Kah?Ig~YP6q$rKEh?g!ymuDLS)SbjZ*?)26GblRnpZ#9Q7XKFLwg z&>p$N>II_oIX1Be3O^VKex^k#9|H-nmHR;MUS;Bk`mhmKFHf!*w2u8fpB<8};VMJl z4VMcemAb`C!8p>3Sx$iHWjI(S@@m;}TV~KwegD9R1-0{sKr?zdHrj_abuY%OJ$CUZ`+EYb+p|hjZHp;zrRV z7>6(Qe3U|mS)%*31!pIMY;A4d>smLpKS2nNj_%z=xN&1TeLO8~ zqr6wX%*soobAJ&5x3l8T&K&zy^3g-m3pV5&R%F~7pLljjbq3`c^7f<=^+@2>uXGi; zZ0gWv1jTBfB*`ybv(4OIriuZT15{*j##B*|9OM7cbe2JJHQg3Y2yP)*a0~7-xI4ie zGPpYg4Nii)y9OKF-3jgvgF|o$?tagEtG=rF!yl@qr%#{VYp?yRBqR2eFA#2_bpl9~ zHJ-czYE4U5N@KK}Y(KljWY!-?B7Min_s=*(%Umrj+FO=5d8IfYJ4}AxME5NUh*|F8 zN%4_A#>>xPrw>R!6*4@}KcwX5<_^)Cc|tW1fALqOt*)&p@U8Wfs9B`E2-yH)LVrnX z1XnsTdG$6Oc-iZMD9A)9XY+wncye)bkwE|OQDk1-v+369&gVzXZlf_A`Om3Z1Awg#daw}BAH<%+aB%*O+3?IGf@Su9p%Gj-3u76t^B$$k@p2?Cd2_*4b0t_+p8A`01%H zkSsG1O{`OO{AA!@okS4i{eDf?GyibxG!a!CelpteXy_~7Q`^DXOax9_!`Ned8s)J3 zWqfN`B7p6k;Qztu?uLPH|D0tv={($6L^vTYgEViQCQps_bDIa4d&8DA+MmEnNx_+b z$6{$mbkIx3Tox0=Lh$gueLH11qtYILrNS2N0Era*YyYX553L z1Auk%^6jXyw^^yG>< zLtyvS2auipVeNiP`;i91gTvcR*ZJ*_XVA;b%YW2dV*W-zq@)|^S!RO~me4655JDwS zk_vv0jWTq~{HWhLJemplT9A^@)rSZoUSI!{m8P18Dg>DSy5!b`Wqu9AM@~zYI270)6-ayQ^(ke+fzZR9%>rrb6=O4_;Z1e#FmtAIBo%lif7LK;& z_PCE~aG$E9K-D)s=Pztb5pmOw%;=~WbF)eu0(^?}Sv_|G&#k?7{69A5i07LG_riXMSD9hIab%Xj=!72sp{>n!VFJrV2kG-qpQqcJ zw+Vj7W6q-_2;Dq*+l%=yx#182i=OA^9X>L)YdDz<1vZ?~vf&a6^RxKIV70Nc02^RZ z+po+LxS30ci~{7d7(b%PD?CzSY3NO{06ocImlT8nReaHdFt35wDt)Mu`O)2Nf{ojm zHBN?RDoW|EzE8+)aJ$VQ86Lb z7lr)gRSat<{O~Ni?&tt}Q{_2+jJzD$r|R21)?~YjQZ3@mLE%?6QNZ{iGJDO-PYIy> zHVN1JOoTl#{oqCr%D$E;=cyKRs&Bb4VQWw&kIl@iOIwZXK9G{`9jHkUMeSCuc-az( zsVl6Vw?RttKHZDEMrKNGsch zovTL})<=P#ShDdY0|859h%%<}u%c@3ccgL;;q8A{+uZ59*{;dT@%(MqUix&Nr{rwkUu+|ip9`L)n>1oj909%r2|UF%LxU4eM~>N! z7OY7Gma@)Q`#RUz}toP2`}eYfprZDoG4~BMAk4 zfT6$MxIm{>c@B183H7}1hhI;S+UN6*8+=_o2bbRN3VuTUPqey_vTCa|ftS^*cFXIF zvKZ8>IMPT*inEE<8AW|^wtpB8utcxxGwId)49@8ZY0YoG#*GR!i|!&ouYF$CWBxRX z8ahzRG?B^MdoV;hYzosGZSsvP7_-*yirRjoF2mEzCnavZJn&bHeYwKGHz*Fa2NSP8ucHQbvJg7cfj$WD)08F|>cWY=m|9SH5p~(9PK^K&1F96 zi{&4a_!4X{hmFbY7*gO--@)T2;=wKeY1HP~5D#Q|))&%;l;;@)VHpR9j}P7?gJHFw8j15Y%UG6As0%4=ZDPP%0w0%F&_skk z?-Tu~v!JOx!7p&BT&nKGYb{kSOS}+BVMVQBjIfn+lUxf9&-+a~5?)8GU@x?w$NIk7 z?@eDy8ew>s`Q`&48O~eRmCOU@KOiLI6BBo-qNJ`@V4mH5KA>1wlO^^GX>L%|We_1vK&6Mts2WQ9o zr){TOfWvWTdeB#%IcLz7STT!t{MK%zL@OgchC7@Uk(Cjv1wM_x2$R*@DZU#GLqd?f zhc&Ll=lw3Oj=8nqkK%1RenopQP_fuk&Wy;WGE5PiWUuTi13FaFez~hpPKb zmlt5be3B#EI9Homi2ir_UayNjwb}h*k3_hu0#DbAq9 z!%MK(r_@G;3f0!zKMMAA3%kS~`@~*64_j#aWtwPh{2d~@d>hSsZ>_30v z`V|`>*hP8ef%c3haSh1YZvOH*AAdP~KMLXycnJ_k%^_VskN6Ih415h}IcZazS+X@3 zsH1~9QL1BIzFq|d*Ne(QC7v=(p8(0s!*F(W;BCp!80oSaXvE7impS`xz6Wf!csJJD zu63AUI2>B0V{@htK*d0pQuHNj>%_qqrR(y~$2`P8Id6V%5xPRsa?}ddia|{FaG>7b z;1Vvzk!qqX{485(qWNl3?DwLZe4(V?2q#P8)gp9qc)N$*rdw zoN;I{1gN@2f?-8}T7ePQD74-B{Y4OQkgoJoGEW}2 zD)R1Sr9|!h1~s6gI`h42b3ZESbw_EjtspnTV`t;~iWlDC$YS?Sfm^0vMFzs3hL^o{ zcqTkv@};O4n|lx4v;!50$sbH}bAJuCM-ppphRxFsEGBs7R&!lH8)$ycb8 z6(@Quoits&y&9>>a4Efhpjo|CU64TQgE|Aaq(M4hKC5{cdm zgYPD(Qmk2;swI=K@5IaHusoImu=MD(=-V&X1At*!$J5oNB_WJnR-^#QHfoG*lhA#1 z@`)^Xk=yH4r$4YFtyED~`1k9VNm=h?ciHC;T@%ip3OMj}OR87#`s;0v=7-+vjl_1} zIcD+gibc=N!I}i@)9wst-x7kBV#}*E&OqUL=X>0O-Cs6*U2} zsy_t^untH=k`&p6ZV6!XD`pg5^{2=_TNV$<^~WakW2~@$(kkYg1Q~w#zSontpHnq< zcxfoM?k9}lp%a*LIL49$z^tjZ?q8!e-Zjr(h{v>Q<%5}2(nhxDM-;SH2qPhc*hR87 z6li7E-%k(TwR|GYjSf(cyP+@O7?Oa&{nkf~SyL8i^5blM{8;~vPcd8IPsd$nIFKHb zT(RN-1W&_Cm;{sFL$zIH3W&ucqa@H4+2cd>P7K9lhvg=_>MIKtG!zO8>)RTWcF?^&N8mj@ig z@`@^BTFvfGsrw{8(Qzof$70qU6=i4|W|Ex(tq^5~6mz-0APm#GC9@nQ6%EwUo@kmH z6UXJ&r{Q{6Ou2$;6C`Yn{@N||(eci3oiJDa{J||Qgwv%#HNfI6c-Ky(q4AYEA&&X> zT5JZS@E@u6qN3}K9nk642{rZA%hWGQg^u7E)-c3GEs=u>q`7Tn;X=etL7MVK6>V9` z(aD59VJKt{;r+#>NB8#C zw8@k-*3ct^7p4rAqPkC_7=|l+s$Axmr%ys*w#Y>Upbl!l;s7H#o1Y!Vd4MqMg2P{! zU~45koh>?2p@K0x9fm5tLqU<(Xs6&MGj>x1FjR&5HoM=ocmp8jM(5Wa$wvD%AO_c| zW$f(b^vqwIN9H}^wxj!%(wF#QT8`;81yTdRlX!zl?LBE>`#n>eBB&G}_SfW&W!$sG zFLk;2`+_S<^e|MEVD{1pM0@*IBH$LrA)eVsIUa z+C}oN`RgBs9~kzG1bDR@4m$vun%8l1*%^-2>x|kULNftNY-n(v;^c2 zD$mO$j1G0f>FWs(n4H<}kD&Dq_=lB|W(>;@Nf_U<=|M{p2~*tXK^0bDXu&W{d7)KS z-k&`|;yyJYqp4pQ)8j1J{DGH!CbSWe3cwg#y6FU2;f}@n3&*O@-P&`1(JS}ch48b5 z&~4Qlr<$6FFA$!YQ(37f6^sz~cPk(`mJAJx9w$&4sc1B_&+O0m=5Ia+Kd4i2GDG4e z4rnbBI|f9oP>1A`H5`Ze!6F!skf;z`x{7fTKk=%Ffs%p93@0h#NFTG^40NXQXzPEt zZNWNefC;fRB%un{^X6__nnrpESQ%V5nD-=~S;x%+&YhKNzO;Ru*F2FHVGpxqy^K=MG%?udXRGr#K40{3d~Dw zmZ4^n{4Ly9Vin?P+`6+5yglWD@iSX;A5|{V7#U*i&QUxrP_@$abLDaa8UreGI38x8 zB_3UkE{=#M z*}*%?<-H+366;4$+AC$09hcf~d8g_-~(wb=30EK3#+u@0s8MS9? z8;{SU3$`{7di1es+5C4Pw=>79lh;~t^dK$Ot~+>1Qn3O2B~CZmium5X`R|86)C!sb z-5=SQOcVgBrpV+1SL5n>Odbw|gM$3>_GO6wBiVS+Xa%ZVkvj9lr=BTL6twddt$mx= zVLL46Indx?-XOQ5Bf#Ks*WgRm@Hva$cE0U$eOPQi6xQhAi_S7e81_9$Z4sgRO>3Ls zQ}*PX=_g6H6zq1Z)~^Cd{q?n|2B|xP8@`#q#cp#>({F!Gu}`L8n*sN0s1DyBm#cP& zRiDc*yYd;SVvIgD{7i7ep`J6!cfC%@&a>?{ArtZKNVLej46blx;FnZoOc*Pu^ofV7 zmXGMnb^}C(@oYh_eL+ZFT|$_5nCBXKoOTTLycxuR-<{=Wu)r;m}~+Tc%#t(0+fh8Xp z7+7j_9j*Tq7iNX0ZsY3Dnu$)$oOR`SBX4P5KlDi~R)!Lf2(KW&uBPjkgmFKU08L;9 z$E*E}>5>G*)y8B9{|4b_-dBGz{u9+spybjbSLjs$GhNx*c{d{q(^Lr=^t0=P zFM>Td*Z-Jsdh3y3NGB`ut;1}(HjxVwfmww81;-5<0U^FKrb>5`gLTR^g1=GpQosm%ZVV$OviQQ|va!yAqDo47G*H_1bNsTq0AE;7QnbF!5=cNAt4cQjzSa z7lJ9^7MT`S(boRF29Bs>kQ`)z0d4$16l0T@1-|B>2F^dCmN_I-p<#c$7qyQja<0PUmE+Kr-5-Wx?A4bgclZoA>&ef3y& z-MLT}>jf^vfOi{?X#@0_x24_pe)%Ev5@A+^>3);umM0G zIL~+P?EMQM6X3F;>V*jiXEio;iA>RdWc_Z{bn7!B4@Ky{qS=N-O1nQ3Zli7eU2R*ntH644RC z)R=WCEqn~OLFT@3Q=!K#hVC06(uIrhWf_$!>(@!{^-aNwv1wvcR#5skh>BIV^tA zstCL|VlnBc*im`C+$zbZGYz*0*t@RaumDYgXi$_RDY!~+mXkhcrU6F}C~@H~1VbcR zFKl<6*i2wX(SOlnP?(9N4vTcar%#A!V*U5XXiZgNkX(4jw4Js_h~;*-IPc@(<3oT; ziSFQgasV|m%Z}t9v~P9T5*Um>udB#?77Sg2^V;d54L8<@qLyI9VMIVy0&_)u%X_-h z$fcOk)mlhuYsF&63Y1+D{RcQmA(bz0|2lrenhyHxKMZ>}>Ob6?dor?i8*ajrkcq~^ z!p7yrN-)nP}SCNGC3-M)TX8>r->y~GB?YkAGcwxU=`I+-=+k%$JWr3RF7e~_xmN-+w zGn3t?qKUGxJtFpbhUm0AoWHYyF<-}a-rZ!iBB_?cDKsFqq`Ui_gU4}xI(K3=TK*&5_D$P$;f{VGQs18%7QeLAAX${+MbOdyD$+#oy8_1(C& z%s?Fm1ff-L2&5&l_T*VTqp)h7VOYW0FBUCT_v<9HhU@O`<2g##y&NJr9x0)T;rG~} zAUO84Ili++^eCx>_0yT<0CpxzE)j;nlb?!H;yU|jh|fQ}W2#feEp(8`&8&YxxpGO_ zJ*=~jbfZ+2!c-lQyt4XkugDX|r{=ZHeM_TL80-&p>Bur1`Qf3Fxhi|R!@@(RSBzuw zzmvr3?<`7*N3h|Uh@ggs1rf$Skhr(Y2~Nn-0)T&2GJBP}K;0+o_Wf(kX;wkQz^Dga za8$-{HdL~KKzlXi|XOm>VMT&O5^IE4qL z$$GA#)URqcDiGQG9S1I0D~xVDeBb`_BH(weP1Cozpc8Yx(A1u!`+8Fkwpe!E&(IxY zus~;g`;Jq-pB9=jpY|>^&vaYzm@z@B!EN00+O0Yu;+HIDdBmcvJt9FtJmUmHpJ-rg zi4*Aq%s;_*LB@~1I6!CU<=sm4B=75qgI~r+pM#W#AcJQ(ND)N4T>U;@_*wj2q9!m0 zw&l7b)38A4@cjPT?niD4S9ZXMYmRxO7TDCRBoF~14U8)CNC%u)mlR&PFsVLvV0SHX zyKWpMo5x8%7UgHUUi!e_ZCwaf2WZkpW6%$bGyvzbn38%4=J0h_2Fjrj-)EP%nb61P zTc=1AWLap%X-(-UKV>~tK4Fs12HmI)A&glSc^i6HxnD`hwY~<8GAg#A7<&Nsw(?7o z!|Ibq#Cpy$^Ua`XX&1H>}zKG@--po{Ohmi5J=H9xK3NIKwl{e(Xo6% zk3Z-g6WlWYm$we}W_yNqtYo{o{Y?`4&V6dxHD(kJ6Oc7Z1~PH0GNRR%=S1?3k~?pV zu~sx~`*|ytQC_uPN?IB|K@_|w9vd4+S7Z9@%-Q;SJTzCVA^7pv>tFiVW#;^0WgLiBGS>E&U&vP}n--i3O1VMo#T#v0uADw$LSsM+^CMCE18%mT zM9g`6#zG`lH43E7(>>ivv(RLI{jshcl#)!m2%DyTDKB#@Z=YzD4m$c9oMT}nGj)WS zGP(*Jd31qf;miiE_f8J@D-#q^$P|_D&FVoIG%@)f*IFSKFsh&8%l8Y`=WjvEC5+z> z2E?(E;eh&S$rdI(EX=XoP1}Sy2q!5;^Tn;R1fk|l4c6KM>vqyAA&SD1(tqdU6h!2R zt@>}|6Ae;f~LQ;13q5rblseJ0PKG^z@t7qi?w*#aGa!F>!uqY=W{ zu`KZREXx-7Y5yUKrgEFao(rz7&SqaeFdO>N0kjP=oVjnfL&bx(?Kiqs(A~b5#P&JT zw^ZDisUU$+B};4rrYzSKpBv@tGk*1Z>{RN}Ht@9!H=`#V!RU2ZSTiKb>aBWTjRUzi zSeZP$BQ>9+$zg%0TXCM~*|?eoV>`L}Sj-xp7|S^fN7%+N0-|^1c+)xtaQq##?kxhB zm@=AWl%mI}*?-oVj_Z`^V~3X|L<2zzE>8}Llt_Syi?$D>kT)frj_z2FzwRZt>tqe9 zr>iR=6|U)%t*V67g+C>%syKgp+3|DWM)lBvX8U*2K>ZlHsJ6qp0kV-GKdLT4d}U`u zRqtO<=7&7FDdZncG?f&oU>hLjz~Ny`VO*tRjx{jIh)3IvWU#{>D=(4SmxJ=WS0Moj z>bl6eIvK&zImFboIunKi1t(A8SCEg{)i@erDp{yo!ac`X*@I}mluTgEE^+$FEj&AC+LlWb4nWdRi zw!HvZ=#>1b{KJp+R`VPijYK_UXZGM=zKE|}8D^fB*Z~2AjNl?rr9}cIa*JAnJp#Y> z`%yQ`d2an7r#eLcP-r%>#hcwXTZ?F(BZ>=wKE1o%Q^EZ(g_Om{x)~UzO*;oKueR4H zQ%lR#-VleaX#O*KVO)QCYH>W!#e%kRqH3`*eoFx@oFU#puBg-iGg?|INfyj1)8y_9 zI5$3aJ@=G}(;JEIfaJjVxxvv`xI%^mj(o{D`ZxZ}e2O@o0=13=UB9hlk>m%$D7QGZ zfL|Ri*llvf668@gNIf&^9oIiPN$ zvBS2^*j9Ro-#Y}<^3`_2TNJ36<>+d%5*@`oIppZn`hPcC7*DSIc;5^=TvQ3&uQL(9 zV(vlqSQQW)6%Z4$QIh%&D0{A*v>N(_!}8Izm^ui6l*yLoJ;XR8ygBQ69A1=-7iLB+ zCFUgW+xE*C2Br3w^K_p|DQe16aq6QbqTSoN6-&_2XYSK9)-iRKcIAI(v|a~h@pS}I z7?+W7wk1)TR?m$KSzH!Ev&8dhpmNos&TO;62|MvY{Q75sGMT z1_lOO_Se1m?Iu!Kr~(7Ch2}EWVS>Lt{R0z}D-n+MRMvNA;_D4>bTg@#i_P1q zm7VNrMbdO`t||uFlnLYU66CTdwu98yv)_lT8>F~$fR|Xp@NTF$X$2L83Mrr-UbbwS zEMa`6SaaC@+m;(wN`o;|a##Cso-%&@wEP9QlLoAUP@w<0y5sNdYz)C4Csb z-3%0CwpJ!yokW{VnSP+2XzM_puot8fW<7|9QZLIYpFxSv#+1PmJ`*J|Lv1FOrx9ti z)Ta_^R!E);vHG2;Sj0j;Ym>(1=naW7O3mVVNSvbrq)$xg6PuvVt5R0;Ey5+(-Zf3LF3PCdQc)hG&-z;DPs`WbPy z7H_>R;w1!qs+{wC`v;(HII74!A9_2$9_}cRVqPIiy+2cmpdFng%YYn3jJ3Lbf&l+0Hms^&DejCg6gT+sn% zD^4(8@-OUo+Hglf0InUTHKbZKH@w3h=o^Z0_>3L&NpYax0fH29V@=GGL4GbC2unw4 zgt6u6Q=hKTo++KbOg3x(g$mIMH|$o__2-+Ne{#$*&J0%zMTIBUN<&x= z9-SxwwQs&8wa$P8FfJquI%cw^S^J4X$BLRF)$p~XNThE4_hLfPHydMq^shuk8>22I zEL^mAdjM^DM{dcDu&u&3pH)5rT&P%6Cei`US5|y-)FVuylu!|&K33JyE?876;Oi1; zjQwKCS@W+xhbP*RgSjCHE_@A+zD{jNPV#vHCe1c@DU7!^h%wqmt&CCmA2XXUhhmLx zkAuc68x4|5aW!$oqj7>a-Qe>Wc7G-N_#;eo2KiUaL{$LY(*ex)4zY0yiq@3LSEvpS zyW8y&RNG>8?QQSY0q=P=+LU6Zh3_3iU%`9?y&%MwpFly(-X>G2{ad9BLTULe1IRb* zK)vawUlJ3d>RKXlB%)ZpaoeKpsby;So;16XUu^u-nGwRun8Rur0 zSyGj+|7L!03Jfo*9Bm@Ngah*+ZR9{%n>x3N+(>Iaw z%49O`YQUPZue1%sVE8*JrHzak53*JVFhq=MKFA^dGD=ndY<-P(=fIO-KouUB`~JT+ zKhOsZ!GKv&Wb%_sUXsfH^Ctj0ZQFRhfIPHHIiM7oFl;}D+?IuL&s1P!Y!?tny{37# ze99_sqZYLB&U&8jZqG0H(M`H!m7V{5uZ z{&8V&(y8x{{(DWACeWU3Mqh<7whn<(WwYD5X4srFxc%KnYb^ul$cN7uP7UA#=+b^U zK1?Gxqd{y$=E^V-JIiZ3(pCS*-b0~@Rqk|0mV`=$3yr>xO;%$V*6jwc#lrbXQjXC{ zwb@>I!dp)FK1dh^S~Uuyn5UD;^6z{>7DHcmi=Fz&W|zPdK1(?xQ7ADiv$DEL0#t@2 z#nO02%haWM@~Vwbj_ll1)*wgSknWFamxMGjbQr*+OR;JzYr7T+l$6y(2|Ti0MTzmW z$it?BM-i^=y1|;ggKp)C&y6d6DiXJtyH6GHic*OTpvk2J;cK%%i zE_oNLsG=Ay;WO|5E!Cw6zb3r>2@#%=#H8tSl)!-WbG~vq)mM&<+Ax( zNHxx;ZDHgKI#?%6y^vo0uQWs%f?AigB+n|<30WFk+E7F(0iy7E}HinGyo zlfazX9N3Rh^(*s;UEc<4i5Z`cnzUtlo9p|7nX&3si%p$xa6LWSJhsXV_Vc?g9h7B( z0U#vtgx#2WExnTWUHYL|nK|<6>F)zZOHqfkMLSFeH+JI zfB08^9=2)@G&9Wb9+d<9X?Qpd_k%;{3wwPNqhl4p2S33hUrG-kR) zKFnZ>PE_FaULG4TgO16=7Vbq+CjY@>Q*7t9c^O*58i8Xa%Cc=z;~^XWo;97FoyR68 zuXYj)^5?BDUO%?ye36bmzu%4lhY>u$DWwd?!5c8n7#9?f_f&C>*Bx!irot6n3GY*1aHM}0#|H` zW3hL!EMY}|=>pts){!3w3jHFP-+F=8r5Y}dP_=(BZNl)m*6fWt5@bHVx>d!=!4`0$ z+cw4>_N6|&2`=tkXg=Z-m=>HunXxV~HqLSm+$dQ&5^${|SB&UJ|7y@Pe6;Q1s1X<& zX29l?yqpP2X!#lDi^m3)+ExIX!jd-qSguCYekMu9n_aK19> z>Zq*h|5IwQXq1#`v0H$c_^_VXx0igP6GUxH!G2`Qk>cMN7VvWFL`}`G0ivgs z>XsyA!}dKG7jPH740mc{c2z}XM710M#IUTilrMr7e99V>3N69>3)wk0WFWs`50Zg? zImR(rNylWf#6_bNJ+sl~ilkKG89}SU4!aV`Iy3#~3iE&O!d^`(_jQ;#~p6 z|2D0qh^!NXCCp;?K;VpGfd3rW4|mP?w*V}j8=F5}{K0B1bFMmWS4;TT@BBlIKu^wF ze@<@0*1>dsyVEmI=SEMXt+%i?4Or>-{(kJ+^^Z{N-N#B(WG z95GWqxqk_MFs5^0r-Tk>L)xy!V%J-{JkZq11K^=1o3Zh8C^(!oq}(m>uZE~jBd1*x z>-y^6u9<*Idvf`@8bPbzePY2!AD~zjrRV~sg-!~_qwrzj)ArL@L>(mHK4=06MZ|CgzTO>=Gq~Qm4(oCa;)HA zW;x_o$!62VPZ_27b^oo((N81fJdqDV^oNo|7)DDN_Za35`NSw&dujT$ElA#uh6*a-Su#>#ZJf4z~QJoG4<>V-xuOhLf{38Gsyadkh z;DDzl(@e0HIn91062m>%lCyNN@`n{8CIICbH%GlmM&g-ltp})W3 zYl}9?nfG~j>q}PEBPT?(4BsW5DS(VD=SqevO{DX`rJ?@`zk;hB9bz=`yWzcMyiWA* zyMNo6i^FxBe7FrqX}mIsqCjBcT*<7!<3WD=w%yss8yfcic>w@vf#&T@iDJb_MN9^) z;P>KPW=@gQJg(?*Pufn2nu&|+&Gh^% zLIF|{3JMB{z#_iIfX6KoI6H)J8Ri>WmoOlMMUEUR24Z$hz~wG+pfQrO9k;PMIqQ#u z-2{iq&_0jnHJt7b-f6vkt*`|pW&SFQ9?yfmaxWH4{M$tzZZQ}d7@0TsrG4T4~>Hb_=s0T3Cylq;%_CN9E zrUr>+^PobHaP^MF4E(-a44rbw8eiZBA|0yF+ql1BU`&^5h2=L4)+AMDp*EgO&9At= z4rGYLTPkLzZqJoazleJs9-W@5_hx5inpz$#U&+3sbOh7L*nL`B{j>L7a!7*yL+V0i zv+`US8a1_f%j@IuEYBO62%RL+U>4d$SON_zlW1-|=g09yn|vrJ%~JjI42A1T^z+B)C$nJrc7Dor#aCkn+W+ximnR{m*&ntla2DYxO@E8qMc_Pyu8DwYhM^O zZRF(@&mSiJvWo!jKmv^-kg5q}5lO_ATRme~6<+9^iL|Df@nY>yJP@KMe6|uy%k2g2W>`g5h=A%&p(P4)yb-jt~djjOgbRc&< z%iH(K>q;xYh+s@%!Y+c~8Re;J?0;Tw zGDJ(R<3w4Ha;DI?Dy?J6utlz~!-PQ#;oS~#EH}3NKIVlKwiX$3ym3eMRY`Bo>&}Iu z*aH%F6vV;gUu)yBD=D!uuH>&d;C?nTh4;^K7^PEZ?>kj}yv_JP{ z9NLY&uPd^acH{*jV~StQX>#=gdX^`f7p#1Wc%oSqA~s%6lrEQTXdW(sTr7Z$$~q}< zh5AwO8Uw)SJ#Xr)&wOhVoHX&ZX9~M_S&z?oBYHfyqYQCS_~>8+Qdj>uM^Df$@Z#NYZMS92t_i~*h<(MyVR zuS3$lK`Hv4VKIKs+d$7#7h1Sv%L)R?H#3%hwF#ors%k}t(JS-c{tZUsa~{wP&zjSZ$mHX-_vabi}?bMVfM&#q7a!sz*$!vt&UT--(~VyS&51m(M7zxPdlN*Xq8K51O}u9vbs7;{zD^;q`2 z=kRJ_ZVq{f+PJ?X@_BtwY}3T6`1U@-7X5D%Yk}k5V_9IMy_tIa$>P6GU+y~rZU$8xm+^U+BN3Z;N=mIuKAaWq2v5Pyonbh7jX&p=F90imtPm*9>{ckh_5hP= zc%)uIok9tJ|5BtyHk>3sL;(jRULe#Kd)Vy{PSQD>e1v(2B#~t5!t%!@gV){d=WC@m zm%;EFY{E`TFZlDNN$+4%FX&36scu41(U5Mhei*Bz(K444AsvtFZ_eZsASgAut)nbn zCt0#?y+C>WzGIJvi>2clx$9caV(6;%ug~Y>v}&fK(E>xW4%yq5vmQg?eVBM< zIbOTTi{YAUN&v~uYql^XwZ=ZE>qsEmt5JAh#XDf%u zJ5QaUK%M^6Alr>+mQ#y-JSA{%R4p5yT}jB*C0SHf**rn*I!qWgp9W`Xu^J+zpli8s zTczVR1OaK=x+(JQ=RKqCf6>llu$q#;Y3o4`F(O%>Z$97qy&Z5jnd$;3-%v^;bK`}o zSm>MvW8trvBY%0$n||aL;|KQ0Q%n)Wo~bTsv8lW%8iQ3`f4@xxqLvrj=&nclrZwNE zQafgl#a3O;csaNlJ=udA6>Ap6k77lO1{Qv{5C4Yt4Z-7zyl?Ye-fB`X?T%odi15N> z=SSjTvj3y$EQ8`|!YqshcL)$5xCWQt?(PZh?!g^`ySoPuA-Dy13o^h29o*evaQ1$? zwSTFCp=xgT?S9WW&%pqGID7r02g?vB-oi3MtoNfaytmr>p(O!4M#mphvOj#|oCe3E z!iB}m$cNN9+?!C9~;z1k#!C@$a zgoW@=ZE-nv%cJbSd$ZaDAwN(Oz%nGDftMcbhjH#@-Ycu5r~(LZ>MsC zfQ2lZpW&l}&mV{#f{pMA_7BB(11SI~O#_MY)b#|v3L&l93XE-wGKvdn|iV@byFV=Lr-8|B!xB)G>%$hhvZ zoWWkPGYl{$4d6X9UkEmwP?_KmZT>zF2N^Rn_|fD*bnlL}Gy0ylzELWE)d>pvFwR+Pt2(%J(Lh!$6Dr~37b)!QWuOag!p_PV zf1VJ^J~?`yWgPgxw_xZcNgqZnpOO#~=LkWj^xh07{BvFakuQ!dboiD2$;62y;&?Y! zM+LDO_xWq=v@;+D;nsHhXer=?!``)2=NAE|AwE-W;$=evBLMwu*dX7|oTs%RTey#W=Tycgkvf05)`vn_{lmD<@kqS*y{*aDi3 zR1FF8j}!4FV zy4@zP?OvFc=U0hcXvcNVKYWP1UQzAzB!$bM1 zaDA(G*qnUj+eiB0AGIWgRpOSgU#j|6goaBJDYlSrpRW%pZJS^YBZ<7o!~@Rx|9KTe z)Uf`GR-cG8l6|fyl;qW?c;~vneznP)46J~nhVMoOQfq!#!=YG7&!?ir*4C6UNv-P< ze|CBP&Fs&BL?Rj9<4|`bL06QYpR2yz@JnfHKXy5Fe7N0$&bXnO=puu~fM54@ClwY= zbb5?hbK1dJC{ax;4u$#kW$Ws4q?q-5UASQW0(u4#X?dAp{?JqX{p>sLjjoJHT zkYp9?kVcLL2~!gBN0}&xr*rzaG?+G{r*7NSG(JRdv8098%H1n7n&vU~kKG-s=nIE1 z7#5ry`=}KgqLo#}l4YqV0g1;08r6_tzE|887f^e8c=-24DCmZs}bG(xd^n|9?^PB{zq-2G^E3B+U442>?=s*M>K$-;kttjS4Lw#f$q^>0qilUCIdHEQi}C96~iT2pFz5ap>m0|b^rB_|Wj{dqeKGVcvC z0HG}3X5d8VVz7)|b}uZ_dnz=*c3t^pAg{o0YHRh}C|3^ur$%u;n42@~9O)xy@cCJ2 zC}rTU^4#oOCP6^+iFbnxN!M?~*)`;rkxwxFcgGqe>E%*Cf-N@*3oxXZ9dD$ZY=e#4 zRlXmv!G2op#0{p#re=gq!Czje!(MViP}IBN&_OhF79Cy-_RQs8GFS_Qj~Z|s5A>bz z-oZE>A2wM$tS1kmzpr)&Ghrl|bY44F?o$*-^1*>6L>|8htkJSL4oj}NFbzxA%7Q@D z?HzqQ!1*KpfI(*AS5zOR)VyTpp>k9(2!J zoH%SfG5%o5pV|o}uZQDm%qiT&I^-|dmw4;n2@{L)!ViuI?)zlb*8K=xmQjFLm6Vd=g&^px3fzY>PHe z!riVBoRN~y0PZ^zehPPDvq-zh)}`?T7U&&K{u7!b9BMU7 zlpZofyb6I*8Cl!9Jv)QZK=4Y~haTyCHhWI-b? z$OFw?WeOoV`4Y>R>eDqtz#g1BpGkiUYErr?6IznUFsPUDC{n1Nr9q}rqQ)Q*5k&Ze zPJDxzF>3t7plg2GP9`q?3;P7=6LcNOGwD^!6sh&HD;LXz&dh-MoF>+~_=P}go-uLy zC}2I@x5d8nK}&i(^#eRa*a+Ab`?~XKC)C}!)u6`4YXFbJVFYcL75JsBq0q3zhtgCEWqGYLwdw`)iQy3fhpqb>pYNNOh>6$Sk}k_F8oj{G{%G4OusJ@Q)jablU0m zJCmup&kGT{wF`eWe40P-AQ406ehe|3&}QRqvB!HPH2UMhfAzp@{ItybkWB8wmL!5i z{%n#yLe6%5TU+?xC^8td`L$rT&&F!#AvHC{tEXdPWo3E(H*GC~SYt(|#Os7x&hWNT z{QT1GaOsp?iS~m-GsZYBj$kY@%J-l7BVGT>R}*2GMiV-kHkw5Vadz^X;gWu zuhWUOZ{G$J`MRCDU)FdAp~wVbKGrH$md;b)4w|5FxEnup-V_SCA}5eW@F8%~3SON- zlDt-P^a3FxakAtJyyF?UXaCTnT}G}DS4`rvpM@43=cWOfs z=7Mh%S|r$e@hYlakNl;T1P>o20lWSBq&5V{5I<@OE^JPcJb}c2GiXYSGQc#{mBPPD znk)|==RODz=jOKerHfCWvYLtg{O?dbD_0gB^M|$7w0fBDk>J5$CAU9o?mNb)x0}X| zc8Yhy1I~zL>OpTIDu>h^v>?e@JIV%K;9pjGdo+GR^mQQR=ML*UCp$Q! zdgx#)?s>yKI_pS&f>QdmN59>j<1C^7dT+YoPHpC$wX?LZ;jGXY?Xr&}6@+yOO`v*# zseV6v+6s#*%$u3Qd-&avBAo7FHWNEhNa<=qJ+3$sXmq`ufU-OFeDt`&w-DahfO#C0 zAM6g8wpoZD-JMLKhW!jX;=_UmPzmXAFId+1HlQS;(+D8*lyTNH(@HIldO_qJ04 zozt_I{0064+-kvF0Ao|u=Kuq12C^`IfA2lgm`#IHa}0EJN4V5j8ruYOI}VO*+alL0 zd{yr4#!b@DU?5~ni~UDnKal`ZtK!C<9ronR?~0yBW>x@!I(-TEUh${`-RuIi-;A zljk;{lfEY}-L?+kG{3o_3A9h{?nWO%JAmdy&JU{l>k4TJ>X2vp%a%9G(4x5fqf+rl zErWaMcpM{e{Zr6LSCY`5B>EisHkM3{_3gY1T66F4z|Y0S#mqe6^7evd@Q?3HF_E8R zTwJTL`*oQqRcYVh3Tmx67;Fi9;!_XiG zCYq-XDkz6X-ziW-JPdb^i)L(G*8{vbgoTxZf`VjwUhoQkUX4;)6324|Z5QspZR&6O z=`_UCqI5p38Un-YzawwL=eCy>LB4yuhAMO^o8n5;w}`gY@+kJrb!Vso2|m4B0EY5iZOz47sVU@78&_;=ozUenOTD_F~ZR{UJ{0T9t+bD{9=i*5% z6|d5|SV!Uy>s|>~1zDT~?94h=dGJaP@9q2|=5hm$0%d#qX7Bbd_ zeakq>24VZ1f6&vZB@h2(E#EnAPNkt&DK&RD94rt%s1-`y8@FgYFu-(KFg&n(KTMxw z3NK9fBVPSxytZGNx2XFK7df7_3+Lt5nd&{euyljY2%kUl%b@l~a-_O>>VXE~{DsrM z@!Db|Z?Z3m>=NX{7XlOQVb_f}%6MW4IdcYIJn@fMApZ28S-F8b&=PzpE+8{#;xw$>1%ANE~sZs{h#844@ibW7l z*O)2o>A45-lpc~I1O8|nd;RlwH5dlCoJGxa(bRyElX$~Q$rrJM(Ib z-V_H0jB)0!x`}nVhAv;b^orEZj7mU`aIh};8@`Yp&Nka@n|l7#nC(R&=n2Q#<9wk_ zk5^Q2R4CGCfJ8U^JORqPoDC=>x$nJy8?uI+15sku0&g?g=!Xp?5>gS;T1mPHj^#aa zN(3~t_Yo28i+!TJzooz5=)Og|35$=v^&rB+QRqp>bHggaj0;uo%|?sw3ne?_QH;wy zB{!j{MIB64?03K!psCk^@|@A?SS(!FtX*kv2fJYhyIX!`%DFM`bji+wJZ448+1H-M z{?5kVbR967oPCh%No^3L`yPH7@uUe#-Yw0w7$5e&KIZ5oms%i+(%{Fi^gS-w*j3xs zMAka`xYUe>NiLCC5aEF7_J%wbtvzEJwelG~8{O9v=kbxFMo^5KC*j-28x!)h4vi2n zB$hkwAIXkhlt%KJcg7zt>`E5*mT=EJZsy;($@mJDP#fU`1aQ;We{nhnzb~2rybM4O zVrX6UBmsitFLeLcyRzNRs%Ot>lwlDsASfX>xOS|j{@qj$JG_d{#6IAmKW|?06O&;7 z*|BU^ewO9)4j*ttKXzUXZHxG8l)^wK%f!rs`}i0!wtp>U8a0m!X>l>kTw3}7sHtTQ zKYBzHZJpjO)~draP}vGCP0QyhJsLupLRskX6lni_aqW3pM8RvQl;Or_6&!_0iuUHHfdFr4H| zW_H?2M(S8%4F@C#)$58Wax_rnNllj^9U`GdDG?Yir*DR76qr2Lj*7TLHHMN>rtQfM z%&{7bli@x6;k{~)A07FY+imM5`Kx3+xPmt5b)PBq9BAg!2Pj#w&&##dE8NWV zc#YXYkukQc>iE*`UI4P`K8H1;DfBezwo}l$XB`GsPuw#@VlJaq`*fP8xdG$50hJgE zpCVaa*##eY%m=ZuErk2Zc`^R<_Zd%!;%MmasW1&AzY?!qvxa4upiUG%Epf|kwG2$# zNU$b~_+uLoUdygW+x<%_qw2g>9~2|Evm)EnNvg;8i)4@RlM5S+dEak``;Kg;tD`>b zUC=e5iC`4uOzgOMpK;u?Qj3IXe#)#q>ilUX=q=!6wIh*6p6}a+n5>Yc{MM?D+v~Iq z_tdsAMIgAumTZO&&ELq0dF(IH1n?sM%bixxxeyxp(LG*X6jT_D zYD<2?@xu7Gd*>>Ds8`R>_Or?UV$YM;e#C|FjoPTSXa`K5zP%ZLHp8mB=Kcq6^iaKK zAX0vZ{b>G0s86u|p7pEp=embA9q= zF67U9vkpXodAaK^?%qt%>%D0yrAfy13BMy4Vn%lXaYR5JNkZ=I&oyh{tvR{*xBuMQ zSpT^#fvX|x+HH+jv%S=ZV_*EZk)H2aM3VeYIc)VRKj-F>6JJ&|eV!72__>+gsPVf(Rl2+_`DK>da3$yO+7h_vbMSDwgQc8~=44 zoh_t6c{{Fs4esv7aq51sg8AQ!29*@?vU$^X3n2l4_ep)vmZNh}l*8SYR$jQ>sOBFjVR4lF-m8IhbmdtE1y-I;m~VI0tYVjqUK%Bsyjxx}jZv^hk3PY`qUy1LgZiGJbV-11obBK1}#q zi<1YK;s5Er_K8$FAuc7LM{i198(>FBHpvpiy9Z(mwz9_45I0q1!zX{aN1zlR7iWz@iT zC95aGpFoe)Gac#&@uN@cjn=$C)>toJ4ILvnUQF6&;maWbo(JAF*)(PL5qc-UKT`{?XBb=5u?mF zZWSC-*(-LVN}?(c5x2K7Uia$RI0SeiOo;$rim-v#fZQf2;{SUAC{t)mJv}q*JTeR= z`4tQyJw(U5VWvdP6U@_dy#8g8S0J+EGlVn^8u`webbtP)dBA;&{ST}#B<}s1x(rCP zTUf6fp!>^0Z!DlNNQP0maY=$P92*XFEpX)qkcLhGD9UE9nBC*LU6b_o5f!J+D;%`JvfW_*{=!p0|(! z6S@m(R7hWNk7Cgvty{OcI=}AnY3%LOoRMs*>sQfl?E*CS^;?F}*!&COkuYH@wQFZ= zrtO*qT*l&617bS-dZwH&f(qPTtwkDpCwW_|L*8yYyx)4P(hQlFnUkZvZN5v?PaiJ0 zkRILcVI~7RQ4Oq(=2k1W>9{O?rC6jGRnP6`!B`MmRdBt)YtY@AkWkHa_xVewwP>R` zB1~UCzI60I*5n3D-3$x;W|k4fyv0im*{*g^&8M~n`9@DgNbcR3@^ZN?*viK>wW;#t zX>mctoW23P=;$z(U^&*ppg3=qj7ykI;W-g_cijz5ghz+P{UL`;7~$ml^ty1pXr2hRX}N!e_J9Cb`@<#|2pd6HKhaUw`z_FMjQ#jc#@*ok{4wd}HYfjllfpA+4+US-+?KnMy;V~jKwi86I>v+_z; zxV@t1uH|k&WgSvz^Kv|Ld*Cyttx2OwkVv8FXU8u(H}BZBwB$=qE9Im`^~Yv>NRh16 zC=)OkXqs~5YXl!&Wnu;8Lpz}X=$M#r8$M*FSu6kt`0T@$(9;Q)&)Gx8!-4F2YcX#p zcD6!JBa8dMUMJlk8(fZ4(kCE3za4R0Q}V&Lw7-{?kElF&-7!=HUqMNPs!w(g$H%E+9;I?aQf;+iKNTl z#VBTXen?``O!&z1?av*19ZchNUp&;-9UqbSJVDNp8iHBZLEOE{;9d_d z>a5H9RR71Kx8X>UXV03hyCbx~Yju1MVUgH?4^_AlQEL)C$38$$`Z<6jqyoJhP|O{{ zgu-VlB<3@5azRXfeBDi0hG~pP1OnJ2h4-xGwsmhUxhS1O*=M&}>EBPTQ#gmXYfpSo z%J5rqsZpuF&emCW@FWI7<<}l+uwZrDyo_>OUi)dl23(h2b+U1-p~6cR}r@hCabUr2seUdJQh%@un>WC#O_orgv;44Y3M2 zImFVs=1jw~=G5*X8)cl+rkPNi2tTIqsV!*qY5gq_2oI^_tFxv9wIAaRfB}~oA6b%o zze(H@pCLWOlq!Kd^eg=8;b& zQU;?uW7^`HcJPF|CL}vT*d6fUF%!}?L*QN zG)Kk=PdB<)MCD`iT?0F@JQ6_!Wi9ZGN4H+V(`q?7%S3?*H1Z%h3cDN`Tza9G39h*K z{GFXK^}l7Xp2m&2g6Ey7eSPA~`K-JBv+25&+*+-v@3@x@w#?$Eln}%x7MU>2n0cI5 zqH7L;{it!rATlxF#2j6#>fdqW{VJxQ=hvTFt}hg3=~2Z*t9A1cOQZIr=HM@q_=-c8 zhQw~+q!C3kj=b#5;*Q%CZ4wEtWldW?;p}k$8;)#yv*($v@OiLeG3bf05Sj9z?V-IU z)>2oF5g@hnC=fLRTkTq7@xD+#UtHG5T64inucU>hj|JX0&OQr*>*7^&dsDofu;3;> zpDP;YHYk~#1l78v4Wh!qeYYwg+)XHjXr%oLRa($LX}1%cJgk%s4qJCj9XD=6JEO%3 zVL)F9o~Z7xL;u%6R%cD0=>`y_uz+ZPHz5p=7Q{!5jVl=*8UEwAJ_-D}&9~Q)&WG^C zzD$CX9aS!p4#ae>kZ2_DpU{q#hHQ87*uIk!<_<3?(!2lrGJ2aFX1T>GLa;d`cGOM@ zP=mist;JN@FNxjuyCv2f`){HdZyX0*^BQzmWBJvr#*!l-h>MkJh%-uy6w=4Q<%P3o zxK&7&(TsiRn6aWuPIujN?{>&dHL-nH6|0C(`|ns}l@%X}2Y`A2a|OPHwil0DNk-`s zb?ci!bwos^76VOj@DtkF++YJs3SWqaiJ4!Sxx?bkQ37aT#UCU8D=!+elKGH&vqsDS z8~HYq@dIM{m(9$;2l9IJkpyXoO^%94p)BKEZmRdgw0QUZ5Ziw(k+J{msv4uvpOf~K zVkIoUeYtDJMF($;CYPYk{c;!h*!}cEj}rPlGm&(+>pYOKJ?TC;)3M542{fU`Kw#Ul ztkV*zq^a?at^1z(*Dlpj6Ku0eqY6+Iw(D(Ah(Sx6af%%-qH^{ZBQ5Q(k_Xt^vh0Z= z=FegI@lViH1JM4mwoXWvo7?KJ>HNB33RC5 z{xd7pvRU48n|_wqyD3zhCBHoYS41wL@?V|s=|eF!Nq@o%iYYYJs}Cj?(E6-LZZJnn zQgRnF@NFmgZe5;Vr~)Gj^QSM6Od$ez(O!=X{z&9tE8U;^#)&l_N6E9kea}0M4n(CIFtadlXKh zB^iIBh{OonsaeiAxAV=dO;nouFlKpg6 zro{L@)*tGp%BfRjMuZ6My8cKi>>HPTXls|Q@%8LW3QfWXGE$(o?Ych}sV!h#gg9Ox zvcNAGV_@J1jjOoop?|o9u{FW91Q9%up61Z;%L^IfQ<^LMlmygdQCAqqd0*7iPFI)}b7e z*H}Ag8cKOtKR8w?qVdoN#B7Lx!PyRKlhrXg`WIVX{T(!)Ek1EDH#(T&2L1|oBWEM- z_QAI2pBcz#Qh@QnEy(R;;R?~7UCNa?^q6>Iqh#dalt~{IA2i5%jyLz*2G!9~^YWB8 z-tENtv{$n_ameCJ0TndU6qsD0eNG*U-CDipzCaR=m>yYKlGlBUy`Nu*pBp`bCI!1ESq*~XT}i728j1J3X@ z$G}P9ba7BU&Ne$6(gl+yp%89L45-1TIi%@ z`~XV#`HgB&&M=Fvlz3LYw&EAD5V~F{Cz6BD-S42Ba{Q|{<^#eI&yM(Qz7@aouIC5i zXMXaB(MTNRU+|yH%jp-Je9#mo17uU*(HBS;1fbI54Zb~%L_q_HzEoPwMUTtnC>(ht z4!eKX{8{I+O;K}f#Z^!wl}IJDZtZJFI*#kGd|eY;!KA0M|{=s*VNoKO^hVg=>avGeI8PoF62FFUNkDYN+F$7XZYg!uJ(R)?|t9 zF66tvk&MslRd+9@n~&!2!wX*077qB{tNq_qx~#tFojRU#y8=s z@F2Tlla;^wKsh81CkK`yQ)?!qcYBrS%FF)okr{`dfU5duc zseyi?X)ogPF(VjojY?28Ut$Had{TS$II=k9jyRF#i#3V|epxMSFOc$xbtdMEdN z`(oBlxBl?RGjk0{j}JlxcF<_sPYE70P--DVo(>i{@@9Gop$msy0c0kM=7~z zTcit=%D8E8kotWQH{dh22@I%22LZF2R;h-W9-Rx3HRwG8AAcs_#2OOAtd`Z&CH(I; z7#91&(LIFyM3w<=-#+~mi@rJ~&9L&Kf0bg+rWc;R=}Pj^I>qgt{Gl8lm|D(PBlLl; zSrlwr0wqk$fdiD%?K}?{2s;K{#gW5uXS!A6SZ2?&B`{L}O=LHJ+`le-6MBN4ZtJf< z>XY3cCSGieyo$iX!;fk;54yaq6-}^h zJAptEMV>cv7u!9UlH@ZU1HT`)3u_;T1N~NoKmvno_~+yP`p81OVTDQI(f&~Y9NVVEJb=_xcSKY?c6M|&?f2n+Abp?jlJ z`GVdKOHt|Ic}wNL2(|_N4sYamhM2MUY;P!1$jKNC1w$Y2n6ZY>JsC5;5>J0pD8p^M zRqFmMk1LRmsiEN7Mw+nw?fKrNrsqtcpTdB7^?n0sGhFiG{PjC9(iFVN*YtWBtbup% zdq~#=H3XokXWb=;u0t#5V&p3M)+IFltJB#6OM^|!a--O()|4Gn=(jQo=<&~V6uND6`W`Z8Rbr;ZQc8&;Y69Z zaG1nKaM@w#Fe0HKw}lLu-1KPprBSg|s>QhJ;m^Dv!w|KNJu(TlZDGJnYY?l}pu3Pz zQXFAdh6B-SkAiKR8NU8)BAI0Fjlo4g9d|(%Dg-Rut#jo%th0_@E?4{(DHQ30E~M>_ zg%V}ofe&NaL3zO*pHf=wr!e~_89)2U9WIY4qFSA-g&eV>m#*PDYHUT1-VUS-QHyf$TZCE!0@&SQnpu zf!Zj;et=KRmR}yantOi*9H(nYnGT|X$hZ7dUz28LKD0QjO+|`cQ9!&-4j3mG%A$&q zLDzCA6WFzC40(T77^J(5_Iq9zM2pnPw*l#QM4KfE2Dx42R0hfI!+M;ea?W7WF&G`+ z;LLwjB!xzN;d6)+@O^Qdl6n@&rIas5h;R4-u*-EvY8X&vtn#~kxHSLES;IJ1mQNim zhB7WL$_p+l{w;MVlI_*L^Pf`6_bo57#t9ESg+5g%QWwBSm;yE7@}4J)m==xb*ZuFV zN9N|M^?e>L>dOod-cD<05AB3*Mk>D0(goVjoX&Tw4{dCyvANmh(A`$@P*d-(SA0T{ z68AQmov}}Ev`pSV7kt@IfldYxpzUHbw>|B_|9k z8qa>R1&Mn11;$B>etwxy3~}-O-XitGYD(|}n~PC?&v--T+ti{HY}(P6SXF1SFAAG~ z!rKam)`TWk#$X_fMWv-0OvR<8+)3w_zq$AiPeiiI(a{N#ILp*nZ|=;Om$t{7h2(KH zYn-T*8|)%9P#ODNK5p^R8WT~Wnz@EkZZSxJnblGlM&X*AnEJTK-E%10bq9~7Y-}jF zm&L=TnU6FLmBx!Wb^(lXAg?0g7`F_&pL}REUs_x@w_@9#+ES897OX})1Lbrgnarv? ziM2g@gJbMiw$-^{oAbH|46sM5HU_qxzVib_M51#0r%Kn5y&`m=dzGJ3~!TqAMyX1!*Oaq{2F*g z?_8mm@4T)i#~8hx1#s`T|Fj-7?5X0rJ^A0v$of2AI=h0EJN`VKK{X6aRUcgM4GW#d zskMJs9|f|d@u5cz{K)Le8)0|PnIw4Iu6n~;oo?H{dok!b{sc6{UI>hOyY&3fh;ix= zcO1w77n%k9Xpo-we_Gh>9m}-w5*E3BU;{?Dyl#+cUc7rUg>tDtLLbZz+>{8x>qCL> z%hGlM1!YzH9KgIwI;{M$RZr}wu?}bl8lmIj&{;_~gxp_h@mP|)SNZ>Kb!ip~H}|Q< z*LSQY!f+pX{B2I}vMSpn?6cS0ss~wGg~Jk8AX#<6oc^P`USBsFQq0AgCP46Y zgMI*hHsM2K?j%|P_nT`Uh_5$3gr!^N`*co-8hH^SIja->$Q`D2^qa*HCzVeT`;jJ| zLx2OhV z8fu+~;%nZd&(m+#_9Ac|P)KPcf|D;&!A|CXk?9TUc*BIBqiU~l8~NDEAs`@Llw@va zhsgN8U>|Jjh0+gGOM>k!a+(lHj-aHv!0+#!=C$^QDe?#w9hk}&bXgr*Vgy}Zy!=?u zMqMg4GkSdAAbt!AylW&CxbFkkW&6*)SPYo+1Af%W!Z+v)J9^;#$u%(2LV^KA zyDrn-2lG#bAW-@it>UDu=*{%j_D%3Cq3O}T(~Xz&BApr&NQKDp^l-P#wp|c%6hn1swuGPT~Xfc$TW;K?Mu`7U0J&8A`I#$`@Eti{)tEFrC zm2s8EcPq)ClU|;TLBsJR{4URY|7+>1eS55hUwU9fZvQimfZu;TQ}9S;XMtz-^o2r` zn+7gi@5jgYBPPZhyJCzst#EWQ`ipIx3#VN;;0B;Qh*5Kvn-*P?j&4|PJ4spJ6+h#0 z^uWzFDg=3C@^sEwvoPK-|Kpol~kOdy5wXujz%7TE` zcLIjaGaRL*r4XkiHsd7)S!=)~Z!0LJ{!KS;+>v)ASyC1|XLw_SA`%#YFrV)0 zkFoRxItIjn8@oZx2X}+|Zelbck>6^bWO^~R*KFd@X7hLm#@(Bin=T$&de#n2jhdkc}-8&ljUs4FR zIPY2q-D!3?0$Wp$fhC+6T@*E2$uG$zgPdt>hF=q$1C>)DzJ?`gI!i*~8mP4-ocdTv zv!>qHD$L`9SQ1L(!}X3~-=i;6-Ma)NCEMP8Bn)7smx$sAFbgjVk1#|710?qcvZAQp z_dR?r`g&ALW=?#Bv&xr9GV~5nrr0^10sBQgbJc=A;BHeDy5w7bou>w5|LCW)Cz#!< zp%3NB8ncdma+QWScgGUE3>i#9(0*}lN`_2DAbZKltyMCYW%{&-fvnNbcO*=wtl8gd zZep{;*?ko|-pTD?YjQ9v+KS!vHNQkQ0ei|4o7ai7D9H^aL`m((l4JK#_g)!}cDqsC z$6WgEHyY8m@~6zz@?(#sHgghj>;m-|(XLOI1@;BIzd|GZT6gnX@r;7d=KFsQE)wPP zR10BiD{SpJ=yA=YR}aorfTSh3(A%qdBn$+CC>Y$oaK%r`ib*87&*;? zls-HzvNr8LOJnfcsO)fOg|zT~ke=WB0$ab;kvf68rpr^+Iai`yEWiqNLHE(1h8d~M zR@Y-Er|YNQd!rE8BWnaa{nmmY_Dvs-)NSR`1|s6M5X+^ka`_y(L6?y8rzT>IkUH@; zhXxmO$HRw4k<52x_(kMq#;{|X3veexEul$}Te7hPrk_>P?a}Xm&`3;ZxV6K~`WZRhS zJ+AOfTHj+!k2APJAt$-7tEoGl+^ z)bMoB7IM){o|CywK65%h5*S)_2a#WbLX{_9lWGLhwQ%bYpk&}SUGT$Ffh2w4@w1;iwZ^9jaxrxVhrB$ zmS8x;q!%ML!W92KDLy^Ay?)Bu;(D z6NQJ(69aM$SVx`$pMi{K54qujZ7W2p3chQzF?<3Eh=91>9H<9g{L>VA-eq$cS6;Ya z>bY`J*p2P^bI>G!V5C%2$D@@u6;b|Sv1Xha03%@V8h|kTytqDpp4==M@xI)k1iFq! z&kO~lBt^mQNESI`ee*Ir#=wNfWyW1Nm%7s6QKQjGXJTspLvB`S63A_Jt!u>(BrNpS zk47rW@z=3+C2HNN>oLJZrISMM5(*6a5=aBXU!F3d#@RVJTP)6PiP_n7l9Cl7we=kN zPSAg2t$DHcV`HL1w_@WvgThdkYlDuwv=l%>i*x9#LkBvVcKbN1mrTa4r3yuAJpy$7FjS1g4gGD-few*>Dl&r1)p!Vvp)C-f9;TOZfJrnH`R+ec9LSmZjb(D**6Gt zD-D@D-k%4kX~mGs>@4(|CemD94(JuT1vG zfjN5uhzIfu6TNun8VAL=z!VnIQcFBA@jv%l-#x4--28P4v1t;-zw%km$IL0W_}y0rJth9c_{tWI8?t_TsrRbeyuW}e z!OQL#2~h2WA<$KY*46SPw?(h(c)8wd{}cv+&%dkj)rm~9tW?V^x~RYi<1R_IzR~Md z6bTY`&9EU1dxHn^#FGRg2_MbBeM|CNb0;iXDDUVEe|BIft6P~+Z_^Nb`#?y^Epj=Q zm<(cL)2a)2@?5)Xd78N$8d+qjWqw_0$u^I5LK1x-vlH~Zb5dli1gW^KVi4}>7atM> zRIh;pZMw%B-5BnKQ4GV!mUx;78Z8|sbc;aR9n>E*?)tql8C6O|<>IYI=a!LJqx77QvOwwVs$v>&M82JT~XkkRSa3ZW| zxpmSfm7}m+on*x&L&!tI<3OD`ju%0>suJm1CV_qb&)O>Kulds*TzE(qE6wi(u2Ww> z`OnQFnMl-ypyKui&x(hZ2;QCtmj6UTV23izVW73;CMFg1jPpBdixfQjQ?id$bS#il z&T!?8$MmkC~-<~7HCMMj0EJ}Qoo77U-37PWzpne7d~s4m_T zyU>-9w=F#*gXiT;6uLBx`@o4Ei%c4h4@-3)zzxU)?ALVlj$3?t>DmcJrLvCGWl3x$ zhc6k~Ot6f!%kQFsZ*&dg9^myA+8A)z(x*tnSTmUbbK{GiGv=0inns?GPYPi{P{Dc7 zn+s682wmwaB!8+;WLIOU{q?ZYmQv1`--2YLEoGb!l$0r20*B`X?~M|2LqQb za8h18yNxhpG6@fr`Rpa`E0pzLnzJ>UO2Uro31lr!)oUhpoDrw+u7V-Pq$9v{yV!Kw z5AULkH%cROgAoC&CERdO-Ptih z53@hqoG$SL5B+K9lkoZ8#b)N8&0&)N*uMFW3fV_S0bg|GFJ206^P9qH)df$l4r>aUVu?k&FIX^&?L6Fa*Y3Y&VL62)#c zy;j$wwQPBuVhzweGbwh|6+adg`Ph`#B;Z9Iv@NSH!H zifkV(+;51&L&lIqE?7NJm)E$a+YOqISwfuL|Gs#{mypn@{{nh8*ApCdhWMr2XldMyuBb3YKiUA-N#z@*aj3B>-&t#cgRRZstsP$X$?|YHROe}W#eXF!nJxi2HwiL5Mg(h!wq3#c3}&= zuNc)(*P(5%?ZRn_(*B|wg6l6L`6`6UU^&YeTfuvmevAb}*{ZoxAOUhes$LLq=HqD` z@E*PlPW&H#?Y_1K0Hs#PH|1v<|7YJmEXD$ug}8TJEo*)QtQXh_(+S&e$LN?C9KKuF zb2+it%eqW>=FUEXylD*ur+f*AO%U{W18)jgT^P$80n?-(jdzJ7A_1(QbDXg6`)GrV zAnz&>Tn>_DsJ~0u3M}*XMEI{7*6l~^lG|rb%pYe#2ntg*887u%X1RwNeotin%FEaP z4+NRryuX)uho+%WWCWFASC+~t{`KWG1$sgD>N?|zC3QT}8}*7lKP1jNv^)$M`zL*^nye7H6>DJ- zP`ul6opx$DYzk#6|5Rj)*ly~&bAhww4_YM^^o^sIO>_aRdU1S){IFY+GVS&MA_1^= z-s!Z&ddH*3mf41!{-L@2Tcr$m&Po{}t&WziW+|!W+y1xqZ?XDLZQ0fOJesu&jG2nS zEWOSlvhq-On7(4MEr1EWOlU5cvw(cop_Kz258{bTFj1F>CIOD})d*u6aY0Wzx*Nn( z0{p^ov)q)?Kw4!4;BT)|BI6n?=<#H!@n;t4J0HKSUJG?P#VY4&%R1>qDY?#YKDBQI zJTgn?NbR6zcK=<;y5sY)$Q!iJTp(B z?%t28xrTQ#m1&kN3wji=?1F~$D71I)HHQCTozp(Taj9x zVo)SD9bcOT)1z9b7;P%xu5XCQYow>C0-goHsCCChxw>DC@&8WS1>3r`;HBFxOP%f& zH%s{De3!PeXyw~X2kqLnTDfG}9;e776d;XYQai0BlKy7-pkzbru+%~VX^~F_*z15I zsSG9}At_NWwAcqc_1$i_?Uc$ITMR=}xBCY3sEXx{`>Lqgt~X?|97f}kVDzt!pWTz? zQ==Snc`xT%SH}NMpa&9t+c{A0hVH=1$ng9?lg`Q0c$6!~&MvR54A;$}<9m2625oj? z!<8Mz#m95$7Z$A^vh(mnsKw+9dbt9tpx*7N#i)!@+1y~nti?zcjL>ds`M3`Ul)(1H zl>ZM+R}~dk(=ET?4grEY1P?m61%kU<(4fNrVS>9ufZz^ca1ZY8Zo%C>xI5hQKisv> z%REk>KHYm))vf|N&gNW6`A^AiC#KGQ$}HXf*HU+LjD7E#t{gHK{##ynfVxQK2VgmJ&&gRRYG}I zoJH-dFBY<*j}78rB&f+NNLzl}*`W(H@_09Y(R9%tnV@qaJhy)d*vBWCWlf=X_}uD| z&)I!f^tMR?A$g(eXg*3wzP6i0iHg8coj7^0x+MYN4^^qKv&x3OrLOR zd{_OWDVMh~ShWp&O|gHE$`5z|^Ii;qqHdDKCp5bMfOIdPm>>7& zTb&-8=XLE6!WfGW0|QYSWlKc;|15ms__Kxi|2|>e9Zp+uhFIVsZhoBb-3=$0jfHE5 z<(Olt>J6_$zQq03;u-i0O2LDq%FH_(%=dwmSVw4*M>3$w%wqy7?0vt)Mk>6Yj4wiZ z-U3Mb-+06x=HEz-1@Ac~Ncmt@b}boNqE3bk=iX7|KB%cPi**pcP0WwiTEd|>dZZ}@ z;w_WneC5AyRz0j%3s6X>l@g{ZWbyb?3!KtwfX9}c*!-^C6&LX}Cm0eZDVeQO#pRYH zQYJP9>Z&DANcfqEfbU3{VN*A37A*$Y&VAdDIyr8#$@2BthNWcyb%O`G%2!RtLIf`LxXvdFD?|-{{X3-1mQnTS`OuD#i(;DRWDyQ1bCER&VN5zOYzXyIU})~d0z;!iodoyskDvWA ztqvos?nB2!zJ(zYUSul08YAbg#1Z@Q4{#L<4*IuW<>knN7hFzxT&Ym0_qdi>eAi>w zclStdxm4LMcBWOX>fRpsY{?co7kUu@aOP(8S9A{e(Eu!(J)M%jvGdURv=(7WG&(xU zp<6ly=8YLKpEG*#wni{Y{swkVh(lr~*xrt;LBdNM{*S$*bwR|%)FOafC?z#jycmm? zwzMNlZVQ3$j79@h$0TOGaH3Bd#oylGF~r}i@7vagV0BJ;EGk*?=~(fgO4bBL6XGfq zrVml+U%9OROLC5LF(mAm7QR7#hy6S|@GzAfn(Unswi=?chTwY+Qd~jk+%V}LJ!TYY zAgm;Z82*eMZ3y}Zo#NI!A+62m=7=2qI%4!B-COZt&VqxJn-l)vsGd(KN+PE-7vumA zy`F=E`|RKNAKxBb)B)%S1ADgdXq=BKA#3`?VQjYLU=&lMC77lPUlUEB)djs{nLY|G zL9t3P;&BGSCfFar{GDmJZtsx?FjD#9%!*=}_kB*_*;C``)Js>r9Vc)7eS2_XnDsQh zrPV;wzmj1oXwf{NmDT#G#YG0N1Z~;i0LI2^JHIrx1)o)pkm77jbR0&61o@(3IS#uR zg$}l9kad(wjoJSAmB%<^xT*jCs4>~&r5=2kl&~A$v!(Wj*M&e#z*(jfG_Mly&C)Av zn>`~-m1!Dg$HnnGBR(-ey-pE7q)~tn@B#1n3H%`IBMRXxY|WpmLp7$)T){4%!#%RE zBS)h48IYMyo+~%Prc;~KfTTcF#E-twT7+Aon5P-3BC&_j#_`iw385(EZfK*t*zY}; zfT^6KD1^HCI&SQM9wPGP$^K*HmuHsgI{|m{F?MIbh2>^D4s^|A0 zfEBc8j}yXT3@n_-cLf%zjQfZ6!bl-V)xGKJ36KwP zVx40x2O&|4>Z}9O1&1F9-4I~WV8e$DhNCcNLPf=BC2Eez8|S+@za}XM+${p5bp02g zphcW4!33y1MouQCuxBitvz2ieq+)Z#_eSe=1n@50+@v=0ee$uXGZl;^-a%xPlVyVL zYZfa)oYxepb~w1X6^ac`5phlcOAaNb{0x?GI4OKIviZ-}6mUZZBxL$Gw&Kl-)N>%Ee)=QZ zRhK;;9r-YvZ$mByN+?rwLZKeuPB+)BXQOL7-%*Cs_Dmb+-49!JKmUR(8IDpc%jXTN z95!vonM@Y#UCOlqraON$aL8GeD_<-6uXA!3UX9;p6#k1#{sOc2kMHWuOqO_k8Wfz1 zO-wYFD677xy7ppG8q46dpx5k8AsO({iPnxfdP!0x_Cm7Y*OU@+Zsz>;P?UU z(2ziBjgo0UU&6&anBF%C%Z-tM_5eLdcK(inpakPoFA^vruE+{ID>B2+a~)}XYSP#g{75}eTY^^ka$J=DOM%g?F&Q2^H41BxkbWwg}b_>PR0r zF3|AR;);qy{zilzIQW=Th{Qz0Ecr{*P7Di%T&;@)Vq}>vDv;Z^?xMjV0ryzV;_ma^L{hcd%yluOLrI@-8dfF9& z0OccIdC%=QxE9e4c`9j-%IEkLzh|5A&0_a-*Zc906)^WQZumHyp-%NN$mmx*GV#8+ zhAP=-%$Y2;P%l{i=+PEGb+V(%a;E-HKv@D!c#c$8P{ENwjTL*dz4`u?E%U~T@%4yr zXjN66PHKt@$YMA!6>a)iST0F+GOUMx%E z-`1Z;_gc@g)X_?{2Ls>~{tH*8mEis{s#vSWg$~zml-liL(EV3tzH?~bdY)7>w6qsG zcl(uu5!dZqpZxnCknC2%)Mp^lU{BxTgZ$9iRr$Pf0!x@Pp5i@uCcnYJ?LYbVh=!ms zHzg})=N>w==Lq%GNz6dY(y{v)jD~d=mS+0<$p~ck!`+^HpUzpGvmAZ4Kgt}`2w>c; z9c@>aPG?NeSmE*sFdbFNioSjqs}2B-?H%_m+{URU19Mv5&F#Gw~A*2}?sfinr8f)OMWUoKvq>`pqlR3)MwE{Qw z8t;OEqQ4%Xvw^#cY(P@27rEk%D%11SasM@k@=2;cpw79CQpg2&9bI-BpIE_3W8my@ z=h9uUjMtu8rezJ7)SR-fXVeOJTBfKsi!0E(^S4jY)iEJ;JoD|yYR($d5&2OFN4q>` zqIyvp@>$PYIsDLz zNIc;;_lU+7N@hTlU|l}-#mh6z;JWgW7yql^J9M(J(4G4Rc&PhW9NMOI^;McN_vd85YZ1`Rqme5$gZzI1gkR zA7;Pm9yNzpCsNSpothodwMDa#MM5jGDMK2@-wp4}gM&X_}j>=L&0K)gI_HaU?eQ$8%1mK%T$B zX}|=7&qJE=7W#y*|FyxAPWzkO!LOMA;^RqrdXjxnzA{P0<$(%X08peLHLtiE6cOa# zJ)|X<6ZFj@2qed-BLmz*s^bK+1%3~ZC69^PyR}T5Hi2}FFMIScFZOzcaQ`tRW2Wva zu-S`>7u$+KceZyTB>giVa#8RqW;-ht1;^MVM%^8Q5ij#Eo8N5N3H!4tmCS^YdT6DP zkjh8>379@|Z`bUM)Xf?hmlFei7V`xL%3oD;8LMGHC5W%%ajj-uHLt0bR%y1|KS^Zai6fi z`JCO}H@4FUp!(5;SCQXgEKa#cEBB0w_B_;Q8wJ;Qbc!(Sg^m)sSRF`PKHIRx3{QNJ zXUu0z;L=;^glu~n1~t~!$X0x;6`5ZjoI7bDCOtWSu9^Ooaf~CQGiNd~b3j*Mms>Us z&!uE$j%&tlCViVGF}*=^ExTk78#>fuPDB&CxpO3o)|NIPFE}lDvQ0A2^A8U(}Q8;Ye!z{^Lhn zReY{)h>2UJJay)FbC<|3pG%81-?8XSXcXloLgov%+p5*uVopazBDF2x{=Ybv(-a_@ z934Cx4U`c-AXZ2gBHwi9-X_-4`(%@L@7&h~Ts!#Yeyu>(n>{@|JP5|8dNyNnntld- z46kMy%0fg(G8ZF0$9qT0`@BOq;zvlt@p**Ge1QYwZyf6osGk=lc8}&q8h6{7;Zxib z?#Swy$N)AUcL`0yzdds)OYH$d?16JKKqz z*^8oCl@5yM%Qg!#-+xV!r&l29o}H2ZigG@u(aW>!a27Neie;H0I|28-(onZkddCCg zO%QB!e!;-EczRoPePPj&XZm-Y!h|w@pf?_cIt5l-Ro^}yj7}I5@o%l9*TD#`Up*B^ zT{AFr?r`CmL6P5XM=wMyq|=98ADnb*PxaB@B|I9`%s4Aam?&OYD}trKNf1mT-{V7Z zf!D)2p@@Qc935kRh~QuG4Q|&95^=Mr+1;40nYL9`6lzI@xxX5d#a;c> zk<+(?v8~I7rVzlovhIQeWAVKlN|zv!xruI$PrSSh_XmM@;>qUjVWcx*J?{in+;EtZR_qvw3`lWH6&UY71AHOR48n9>S{9{Z7!ZXU4y$|n-_Pj(Hox-=~{ zMSVv+NR{8Uf$hdV{Z1MVIuX3)Z5a$}>@AjnM0Tbe3r!IHFRmLzeyc5p#SCXK!4O3o z-f98{V=nU+&yx$EU2C#Xthxtn&%%~XXcPcBx8?I<$+WEAj+?k$p4c5j--XxdT5|-L z=)Qdb+xQJI0j)7;b%23JWT%5b|0qWsPiXS!$mzbUp0yRJ$6Dy+cPAwCw|^lhyub0Q zq}+OBlS-lnBC=01oTuE{<;WOnVbBKhiAQ1WLj{fQQ)Uf0NdeyO9#5DK|ia7pl3PdU6TEV@XGqD8gQ_H1ok_BcU+JxhU zu|sBBA&=3}*BEdL^@N7Bw5zhQX@@{{eHtr)PUcwIw46uY;t5!E~ah~!P zvJRn;+)UUigG{>#QOkIuwqyEHyNCjwV)wN-coc(7vt~$2R#H<{sow71QZFmskXTvC z?sZ415AN=C=r4sClr$350UL^=D38ynA#}d-bvn6f9hZ<83l5Fq&J%2UWf==NP(O9J z4xVyUHRJiSAI(JN?;(MIdZu%MeohQAjNt(}jDuHX6Htd2W>R}Sf->!R%NlY1qRFG1 zLuZBIR$!{L5f*9@{pOHWXXyeBk#VKicyw;f^06+sV^!ZFwvOCZ;%aKykGR2<0*38d`Mf2M@{gq zW~i4jO6^>&;4J-jA)W+gD7+E~MJ52XOdK2uj!Ig_E>o06eXW@Y@$etWTFzZeHJHGo zKbArfPorBHzpq)A=)k_}IU1zPv2hd}tYu?3f63-tW@|IT z&Yw9KRhKuoyD()NLHF7}Jc_!%I8xo|;Vo?I>b<-?lvR}Np^8$sb;VWvO&^4B4wi2d zNi}m%N+~}x`+&F@rC|@-$CnbfBwFy)mkYv~`R8nNBPbX5_hiZTPC|bSfx7dC)nK0F z>qx9Ai9stgHiD0>`q3c~STnU9l8Fky*3TMOi)855O4p%-k*GipRya_IlE(vGV8D7Z zXshgGVejbuw}kY);|fbI?s9tFJF>{PRSWe$YC15knE>+lAfGYn5p~;!*Iu*U^D5P$ z5&A%20o(T{(MIB)_BgT16n`%8`hM!W=CAu08;?9eAlaPPsJO)-tMIvnC?2O< z@-q#H4Q8e+UC|Hp#QOh&4@SS>XGg0tmi*%6lNm>IhhcyHZ6dQTHUTBGYK(F(2kbl3 z1w$*uJY?kLZ#{(^NedgeCRdNQ9_q{#oRs(}YD)|T89c{p`dCMBdq5Y8cmvRo2tQLI znRUJeeC&PyT@w;%T=5>0hU8?xGDJeQo)2$t?|JiOxH@k=ltJk%G%;++ zEdX_(ZYUmbmLq*uFMLfm7RSj>oFkr>m`909#AC-2eL{{ zP#C20f8xd~2R0e%t$F)}X6!z3frUz(?gUX&_4Cij8_YO5DfzH%{>F08BCaobNxjfk zTH3F2U3JTL<;ET3O^*8qH)N+PVX`^D7)Kc|FW7$htnT;g7;Ut4JWr1rrhNPRHM^ls z-=by$M-HDlPh{&q0sksD`~)dwUr6BCE^<&?nbjqkx;#=FMY*p7;#eg{p0L~18u0Dl zN-c~RQAxlELCZXsE*f_mfY5XOZKrar1BvBu7{pR|I1y=}s778bOC7b7r-Q6?a4HHn^@IbUkI z{^ItYZq~**2S^t4G>&IBy@0chgjHDbl3W*Y60I?WBP=g7WI7z(A;~&kk_*_SBzYgB z#o*nV3EC^--^fjiCXsJEiNf~D)e}{NHvK?lwS{)e{m|dpOk?F}ntDmV-l}YF4p$E+ zoln=*wn%5&xi3LLCnVHuZ2a7@Y;|~w`xO#>{`?qa+;dp2O$YtC?eV2>6!n8TNl`V~ z*SbT!I@bgXxwct4g=%>6@A)`DWpYIRDq1%O44SI_YVJ!bF!%KA-1_Fss3xDCAeb`- z7VZiH(G@s1cevs)57RK5+Bu#KTfAOR_zac_H9V|A*1PJ-FOO|MT8`raDw9yoQzFZh z+qi)=8sv&o(?#r|DfFKXeqJxpOzehV+An9}cX{gOvSwsC-f7)+m&4zR4-Ii(T&(0S z#|DG`vU{O=zeqKDy1G3Hk9ZB=Y<46k(Ur{&)o-D8rqR7Alglk+x;aI@TRfcM_idLe zEC0Fup`Mqrs;XVOW1Z5HH?vWw{K!;q)<81J;`+(kqm4ohKh}a+p9RPU2lRG2M()81 z$!r(a#T%=4yrl%pJgb&NM4>rc!lizKGsBa1qu+<&#d8<0!tM^TfS!INeR zCmX3!$*Z{M=TwZZTpy^##v-_C?Yt1aeqV=5-K$*hd+i6aKwG~GO@9ImOo*a~kbC zIA9$gB~=}NHZ3by($zByc;jUE{AC}K>`u^$@)8npH>nM=+Rx&T#~jE$!wP=#`N#^~ z=8l(k`PG*4NA}{sL|E^VR{8Kp?)$vPLe+;!k;bb#t?X8ot-l^8Uc9CHeg3 z%C3~<#Kh$KadmsGoNr6SHqyfB;SeL88s)MJL)t8|Ng9FLchX70hw57uiQVK)wIoFK zQ*08u0eURth4D>fzA~OEoI#NqIfkwJmLtwdjF2?rj!dIxm`erxHiEQ189-oIYo=`iug7(%3;~58VEo z25Y9a1xP>^(ng~vN#lW_m!fLPaG=bpu{747xndQbkQlSB=lhmKX}9&jLsCWn+c!(I zyeYKYf+)qA1Ms*yqI{|8+0NQ=uHEu)F<;o#{zOexRhQ@4C%ll&g+Meg5r2rk$b9ys zJ>Bz0}OqY6bT=gLI<&iGX^FJxr=CS$e#N|FMW<38W7I}GvKDmvG zcc!{NzTP{P(PvasoM7StaFnp9oOC8+#ZI~24Da@_wtxYCp^$i>6neJ?-wup&UR<&m zn>xFvJ~ZjE8MptmTOv~DBJLIS3Bu{!{Ex5Ei)Nw%Ek-?l|2@?^e*(Cd)w5jE6K^}k z7W`l!smiBl?pm+PF5O3u;!_?qs2dw+)h^rvlSe49^=)HjsAq3cIVVrEb7#XNO*Z#k z+2KRH5AlS^Ug&qP!RJ0i{fxaq>^ywMv3uabcqArexzn9Mh%5%{pJ0W6fx&**{)Ri2 zdy-nh$9g-_o0$1SrvoQJARZ(`Na4>P)@+{E+ofHrdu^Hb>fc(h>W?-&C^W7#FzS(= z_&n&K{wMb-GJ~5UEL-B(Bext3fd?FL`OY1TR;b`G8hqj9|kwBx&SMA~BVBUhZ5FE6; z;4~2#@WGc-wIqw`s*4yFopQ2!Pi%#sMeuv9w_-#^e1F;70-EZ=V5$D_0b%hKiYVc% zJt@b_g=l5?^+$2}?_rB>kMQ)*`LQLnO;?-nYtQiwy3H-MD(Mti+6_%k-XSCGifScn zls@;o*c2<&7|7O!a3m0!vMvs+f6+7MdeRm13?tQ>W#vad9xgw$Uu9(O{hNifzTBb# zV=u0-#dHyjfjV$~`lxZrc6a0zaD(>$K$y&uN$NG5)m6!Pm$a=y7JyAX!EL*LtZ)Vf zO~oYacFoUaQHs{xlnZ(xNCsN(xQNAEd#LgJDW7qmov5CK*yyGb#e;0i)M!aC=>2<{ z`YZSzA}HIsZXi0qC>o$$et(OM50+1&@7*++TD$&*BN6uzwZNGR(xHx(9$jCximMr- zjhipuoB2vTm-&jiv*;g<2PdeZk#~5|>Nl6h7!C+n8N)-6TvWb^IcH86JxI;)bws43 z%BbjER$j42uN>uB(bobFz#ch82w_NiqqAx(z94q?JHIfuOwr|BtX4Y z%meW}W!2NQt*%@!_Y~Ud3RF=YHUVjaNJ;_XHPwWeZk4G zBOC0T2rN6ibBwJa#}tMqzUVs zwz6P&MzAi!{$NgooFR~&<@3JmqeL@GDs50S(RB!!)fyk5a=;cU@2m2(?g!3cr zH#s~#N9%q5b)_vZ{oeSpX@~)DNnn)%%UonQT(Wtn)fd&%uB@%?9ZRR==4%-2?rwsg zAuZ`TSuN?c?*~x!?AO}1T+`F1ck|_|8%uShz*kIBlK zfzz>C1+~w(>DC!$Enls@;j`tfT~*7CEolF|bSbMP%-GarpW$ofV1v`JDtO9xz-dtk zc$S|ew4gF?y_4Qe{l z-Lxz{mBpge+uDdaO>}vaZ>y_9H|2Z70hu+-01C9cMkj<*f zO4*hde&9@{fbGZ9p{n6yE*Dp`(oS4?C!+Z^H6iZp5fEY2H#tLsPfk9yUqnVsTwX1P zo(L*VO#DqvFX&h;>{!ihAdk(bhJ){^=7`F!)k{LOPyqEr$*;IZF7}h5z^YGSTJfe2&w1$21e~;Kz2*C<%Sax+veK zeY^6}2|1MF(Ic*|Thfc*m-Org0LP%%yp*KAXQzn8#j_Z~k0@#nsfzl)VZ;(B!!$kU z%JfU)TM18;!dojhOa>j1APIy|*NI1}_$c$CKYUB$O;aT0xT;+hm}1qVYI##bIC1#_ zF=GD`*U8-bwqyOkeI4J5ir-7ay>tHvqFis6zi0C0nZ`)M>t`&+`!G$Ar$eF{BX9?< zWV;HJpKqN{mPI?{`Kvb@VWu{gtMGd>M$X?H`(mfaDHQ(T|MO2$3#< z(k)$@L^VzAQof#_Qww*%0pOEbhL?}nji%p8`HEDAp(^6?5j4@`PE_wy2@uDMdEJxD z7N5TE=Ybfj$pUBTAP#KY4ekogZc=Q>`-9Z}!z@Yx#T6GS;dEf-xPNhA#3;^z#ik&($VYkfN_)&+bd?3NQO@=vXa zkm|Yh$D(sk=5Iv57|G@uVsrXpiD+oi7w8Sp)8^{mH5)&Rnd)JUx!{%YM9zU!UYzn1Qj&r#T4Xn4`U3J>j=b*oWLQ_f(nQ{+*Sf*_ z5?RRGZ_3aYTza3*I)(-)eHAO_N!I|q<-Z$2z`Y$rg6Z{ERMh@s!i6jp*y;8wZmAFG zI*nIy$=GXpPYT{dVyH$N(9ubX`I#v} zDrC3O>Q&V&g+9=T^2)FNogbZCmBIet9a9k9x)od@stvDNYe$#&*=XW2|9q4^q({ZXw5J+}wNivVpwf+4!rCA;Lz8t+W)f(hfLfKIn+;yiPGI zw~b9*q6K#Ov4$~>&rhV-Aldlo2&G~)oTM7KJqXu-5?7&(6jhh~o%OwXW8aMl9hU_L~KxvrR{3luCml~G z=jPU-AbjvGtMM{F7r84Mj~X#!5es-s#mpTo0)1RR>*3=sEyPZEKgy7W!W(q({#jGx zC+qnk+nhc_Vzo?G#OnB*7RrqN3qIuWrIR+2*5J%RC4_nU`*D*!&>nL-IzF-BF^KqO zp%8aI5CfHrM? z|Bt6X!1rhQABXB7nK!Exv=V=pkG~1w^<_;<>+Rq*tyz7B6$)7`53DbDXx4O?Y9bSr zv4#s5wxr_TCIe@D_w_R<(#6d9DCF#`L7Toi{GW0xx3`xMUL9R4D`eshx|W)_A&Geg zNeX~`+lAG3xxc!k1Hb~DMW!s%`Ts%Rd@^%nn|@e$i6eei#YXw}&O)uas(SqKQqUqc zS00Z^DG%ECCcUs;u$r1~ZYu`wp0x3}y>1;%`Xy}#>~xSVNFwRx^KuZW4M9NqAGC8j zu0%2oibZ~2`?CDIpAPfLgH4VI_&?LlP@GV2jOhZ(TU85jl0?P2ug{5@PonNgrYDVg z=+rLydVJ@K5rh>+bnN&n5YpOZyMjXf_>x|t7|srCHIl+- zHGj@>1`2&GmSXhn&ce zm+LF-(8bPw<^qlm7w4w3di{QTTYVSAzljUFj++E5C&nh1|5dfuN-to?4ol0TGey4F z@~4@=@vBmK2k911DUc$=IzJjKTz|mNt?lLjI@rK-h^U;`*g7F9kY4dCw(O}{&s1iN>m z=I|7N;|oz?Vrq+m%FI_AYqDI|3zB6@)7_v?3CyTZOfM%XYnDF=7iQ9&Nlpa&IUv*= zpCY6IiM(y~9{@oLj21J>)rR~%bPB=!QEynsn`qIrtr4q^-*+C3^KF6Nf(WV3BSXJU znQR~^@Fy#_`+XL6&dy5Hi=FO7+^YYH@Q9wVzL_^TLn1XL>1z`udRJCMB;oHD#ivHb z5xAqDQxB=)feW08@%^t#9LJ#xfu>yR0>m@$H574C-%L43bQ)tgP(BuYX@hljmu>#ZA> zfqp=7y7zyw;SxHw=>*mh#^KAqru&9WOTrKiqHAIdBw;Ti(=^2Y938i7v>R+Af)yfI z4fM?+b`golr9grSSTI3Kg2S+|qb&sN$zLvZ$RGwsjWE$ODJ?69D;0`m;^{8~^%I|o zmt{J%cfJT9?OCq=lQj(n6gfcAX+dnEr=Ii#92ADBC@pFqP?VYR3PWfVni}~h9*o~e zpC>8bP~Qf`-bC7;GQMAE7{8I!S!Ptu=MOS`Qr`Xyi8LL?gSdV|j|90|6!T3s8;$YV zImf>3_~t(gy^Z^SiVdMYyg@c-5)|YHlG#V9O?OStZ1d(wZuH=^venj~1WFiXa;>be zQ0bK|*I9weu8!#vZrTkC*Kh(=ACi|XE{x3(G9Ao8r=LvwbkAM4Tx&}@QmHJd{8dg4Tw4wMV z4T-e)T3c9PUAK(!2>c zj?RI?c#ZAR7Ah-kx3uG}ad>{r=r)m$%4eIemu|TEvhLUO8pUy0lYqfsYu3`Bl16p= z+U`n|4X&EJ!0%kf5w%d{$p3o&`z}163f4&+k)whN0)^}L!;X6hSYV-kZ2hUFLoR9m zdE@QH+voI2?8~$(eOGVeUni$sgV6dq7eCv|8XlnS&cgpV;8LESZy0oR%f>~ z9l>z3v&=YP(Q;na4YEQ1?p*swts&qLf^NIX{~f-uVEB59J%?6%?u^0 zZ@BZqtl|pV!P5Vv;ZHuGC0RxxHmfq87 zilr-Z=gyPg3Iq=t1Y^t{1|6!vB-hA+v71LZj3E^2sulpn(O-YE*=$LI1cr$@XH2_? z7#NDX@-cm1;qOL#GH1pMT=Ubf;Z!RYvXBMG^u8YpGhMBU?*+P*rr70vTt(rqllz4z z6}=tX^6LeI<$}p_jqkI-HBx>i65ChlKo+52Mu)-O?GRB`7PD3#Xk4mMO3qqXQb!ZD zZS#({k4uScpsSV@qo?TC)!zQ3N7UGu(%f8q<)1j=XegO@nG4s4cRhehJN$ALxHjFu zcNdA}F4^7b?tKYwv~Cg z<4P+@A~%6zvG*P8$Tu6CS}rw2yzO-3!K<9K^t4)m41Ng|GWO5!(n-@>-@0UG0{mv{ zc$UhLF0#ZDA~QHBYSm{*oG(Fd1|_ls!7+)K5SX87J;yHuEi|XLsK?X0E)ez~v}6mp zN|~`kj?^m#_)yTux$xcLRAmyPDJ3ULY+5$@EwD4WKE;ESt4OT8G(5%!Yw+inDm***o*dbG8waB3k~J6f@VW);#w_HF@OPyA6L1Hh4rItZMVg7g#6yO1XqQRn z-X8sOI(&|_T&YE5BU*Iw0Q%8Nu=^g{DE9%TZu8a8vAWQEU_md$QF_NS+0pdUOnjAR zW2S$C^#Q8t3pOS+?%UFMEb@11I`_0d3OmE$tLiv=pKsgq`qPJGnyEy_9Gm>SQb_?~ z?e6)g$lFNHYd-si1cZc*4)*>s(G*opv%A|W_TSRzjbEqGQ8=Nk6bw@w2X?_dNqx}V z4|&<$mk9EGj9TQ^&Nx&`4wNhZuLWQ;3c1BMe;VV+2gy#UT`5u{lpjUa3b?NwJeADa zu!=NKXg*n6h-xJrI1*<6xjpY;#)ClOgb8)$+$t7@$5e$_si zAFJ|2u>EYac}=-AA=GZ!Tu*ywm;lj24|jkQP!3nj%RCA}>i!oKS3m@l7!F5`&}6iuzB^o8>4WLrYb+nVt`MNOg$;8Y(s^^E}m;nv{aJ> zjK;)3Ec;KQdXJUriv0MIF>utBVxn?C(#AaUaX;=>j-hU#b};-mml|U9#^BA8nMzj< z>d0K871>PPo+o*Jz4njUtEsGK zzqPu&erP}?Hk$t6HvrSPahaQ-X0UtSMX-cNJmSNK2*312w%Sy&z4*0!5ZRja@{ z!!L3&IH9yTE6h4Tk)#4FtVgqS zVea7#Zu9ELsouV-uWs$p+e?6uV&A>7Tmh!@ir*sMXUeP^V#>kCHvse=%gf8c`ubAE zL5qui#l`WijrbBAzEJ;%2=t(rn8;n{ZXd~Fv}#Q=BKiV5v4*yEpu-nIR?eNO9E^L- zCIy2~puaZ;G36nV2|py0*Qzk*=5PrJcFy-5B-5vF?>)9&(o~X!JE06G|1pGF2(7ex zVt*lNy*l+ARaDVH7yjozpja3=74G&|MhPyg>KhUL%V~c$+V=^PGLZXkTx{G<_*nn{ zK4COECZB&5iNi;m6Dl%dn~9yahIBvJtTre9bWz$n@NVm71Wizafl5Hn{r zlPIDz;OkIp8zHPzl`+)plBUW$P%YZy_ZBn}THdO43sX?m;;4$i!JV%Fkd-CG&# zO7g(*75p+~ypehiS1c8YpQh-Vxcjz$%4+J0i}}(Jgl3VaL811GQfhKN6m!!LJHhid zb=GzIJMQCCQ@9QGBHvtiO?=uz>@vMRn9MtWWf`06Cr}fk3**WWPv)9mIK3)Fu^^&% zhiyRXS@23&St??`_)yGvS398&2zA#g%TDokUr=D%-aazjcsRO|e@)U7Fkimyf?o*4 zsV3_;iQ_p4UYHQ4a+@pWTYjEA`hNcXd90)B@{)_v=lXs7J|{PK&+{=T>LY`HFKX5> zoY?uKe2<(hy99@$MVdQa&;p#H7N!GhrQ&bT2FCX1f9=CTF#({+D!`>o8lM5-hD08+ zqZTScjYHWQalc{cb}`b!%kW>QT7K0vLeN0{yoc_sxuK993Rn$)@_)bsAS96sH~kfY zUC0IO%Mq7KTjYFsZA!bVjX7^YM{)o}E@?uWCaZUEg!MH=5Xggh=V>WczxG|hrD;qf z)B(C#GJ%DH1R637#>DQcR#WZ1YF0L**1^6A!o`J!jqPYkQzC(@E6k;nc)pVN>Kr`W zeKVu@;5c=20RWM1svcj;MRpU1AHWPrwSng0&K*h@H31kr*l6o-ve4;(h382(!^)R~^EEIR zOd5Y%pdm{VsshG?ohMUA(za&t+UBqA&LHEp$bvT>oP|4-K|k;B%TzAlLR0(nmbjJj zOsVp#9F4oK|4aZ+R&r&vM|8f0cp1;7v%$N3OJy>o6%>>Iwa=U9rDKn_D{GhJ45dlh z#1|?zmx};F-}6x4&bm^a*a9iBU*{um^StgS%j*T$gDh2lIZ9(CACmlMPy zeN8@-#Tfl>397XN*^Gj5IayJ@Wa-O^;!BrbY2AdY!^jm`PmD@tDh`|?x=6!+dPv;S z^Cj_E068@4cQ1ZojHisx^iiI&EmZmbd7)l`?Dj6BXMCr4)Wz#xnO+`-o114a-`mb7 zij`IsT&V;hfC`--6wu~@L0G5aqFgCN@C9~J7!fK&VgTemkm)tN)h(=`Fw*+e6^d{} z|1p3gJPb+X()OFWD~)v|coDfAb-TOPPQDXW7{e2<2#GC{@|nB$rNyE1k7+S}q;y7? zi7$>mexIrqlpPpb@e1jUnIqwBkbS6lK^q;|47?D-;$m=^5BoH7#s==$@J{2-;lM99Nz`->#I?4(qtE#<@ zN#{G`6k9j1d}OIsr%>_WeP;irb0M zx-`nr*Y6!8kw^2^NNiA;$V;*kze^D4=OgtkDx<*36zs~ORZp{cvRVI&BEmN_a*9=% z6}R_>QS^=&Oow;K295m9R(W7~qL2iOFq{DWGTxjl6xHMBW5yty7|F`^@Jibtvs|l! z_keOplsmSNSUgu6Mxa}067@qO7$-nDvbaG|rQ<4SLds|lxt<#~G~6rBZ~wWp#;A<)0EwS)5=F8=oHn?2a; z{UAdE0s?SdLCLxmQM3qS_?9YrXj=~>5caI7q=Y90KR2h{+V#OfKe+nGJp5O z>8j`FhWYKsItT(xL6|60^E^l`&va^isasH7CAWyM`n7Um%bBpJWbVTu^3PO(>xT%F zw8{o9Q&}Xn(Jj0!dii4byC#NxT407D9M2M_-$s~)-#jU4`-fVP{CeE0Uk(`$9Ouu0 zqwi1zS`VtC%@-$;nQ~r^lly)?J$q+=u07-O9Td9he=Ml_w9SHHf4Vu+H*OY$zel&}fguY8Ug7BhwdH_kS^(=ySq~w20^-{yGua2;k~~W zYj-3Tf?SS-T)zywp?BKuaj`q9B8l10yT@8d?_BEG6P8$u>dXix{&SJYJ7V-XQ-^KtZi-^?tXTBw)cD5)2Dq` z9-H6e&dO$d>U8fC*3=Y-CF+H|e50$QBj8r6`8lnO2?LxESHu)*x^XYsY)E_p$sT-q z609%#;lyDADU15-Tl|qC`sPs71eFO}2ncWC)|4)9vbb462dgC%5y$M;0#%F?wwWGV zXEcRw`nH#-Zn~KsU(9ymfBMu9aM3T{-h^S}LjrsTR%`N(V#hs(U)s-}b5=kH7U?14 z|HQh8)$v*VRvPY>(NMKJabaO62LIYe2)ci!{`0Zrdp+%tSNrRwg(A^S>3XRC9{rR# z;k^v!N^MCoPm80NA33R;iL0=^N|S8Q5iEMY&+Q+CYC`=2BqJ9gPSz@+L_}E(#>1FX z`BK>9sM8t{!b6jAz$}T6VoL3QwNHh(YrDRFOGHhp+h)u==nlX&gpeIva{>&p5m&lq zExpSjJGRq$Qk?-0yWOETK?+UhaVBOfNvO+p5lA>yhYj5fBC1wZaiK#IH(;?a6zWL@ z>YbObgM>7xaGzx&b{W&7KRR|@vbl0|SF*929tECMQRua!aF)w*a^rDu<6+APR#ag9 z^nK)Wb#)ybACLK}jy_YU%4PV>=s;@qNWGJxC(##y7^x~Fh7t9?HNK2x zeMH_Uiy5K!7G60as|dBGBwiNo0-4>da9)zcCi4x z?o>B^wO~Py)QLTlUYecB*QlPzdW#QOF{;lreG3?_Nw}g--+ehW7d(rzTo0lN%g-gd zVoLhhqb^Z^)f$Kn>$!cFN|XV%y59EPM$dlbfACtwLZVXCs`!?K$$R_f9te!8_?&e` z!6?@1Uk@kQO#04&IrhXf0^M3SN3XOlLF&?GQq8xJmNmbWmUZ9QlT*HDzuy(c_grVM zzeroVOg5)!0QE=6z%47Ap-r5nU`EC=fc7ToS~meqQ>E$V%Y4Pw`A`~VfKFV*_%1S^ zYNF!scGZK4iLUxs%bzTTHYOtB&BzE&vZi`X`yU(2+sP&&WRrHjW_?Yrr5SsIn#=;w zJ9HTB2v_5DYO=gzMHp!-Ah`Rg8ww`2tM)i2WwXx2zHPs|{-|$jTdFQHJ9<)SqBr-O z-mR1A{!{nPKcVh}f5tE81h1>e31MYJ{twPQXKaE`K7_b_7Udh)_KB~%c`!#qiqDQM zLo;N9+_j*fs;W1HY^^Xs)CJ!93ckNuwmjI&xd{3#0~daV>oV`Rt;^CmHY)-AKIlq* z02ig~^DtEuPjbt5?6-Pt*n>oR1&xv?f;_euG4|xli@pog%a_6rra5VcC1X9-j4nIK zXSvge=UHdHF>x^Y3PHhYjfosD=q=Zrb!Mr<&E%by7F<1|is#W*E0J%Qtw6I>K3-eoNxr*8O5m4q-44V}cc~92qz8 z&H6+=R<`&oCKNF5nh%wcaI{5O$X%_(yJ==wwX3SLBOLLVQaJy2!_2?lKD2T#NWjLr zby~V3#}waOXq|=_Ad`uYjzs$HVu<A7nxoNA zk}cQ@n)U^kuZ~`K+9=Gf5-`3XjFPkTeFwnJ7=>+u!yOfU0<#WV2}HZy+4x zA>hTYx-W~E->SoK;p6E|(yfkb0l5fPEbtoFtK5!m6UNv7=2R`yp3|jQ&d(a|f8jks zBUBQWcMdOZi^J`n>#J!(dE`8Mx%Uz1`qft?Q@l?}x}w`00nYF;l5fz(4W+JNK?tt3 zYA&|oA$bJ+YxPY{nrZzfjS{-aGT8s+vHic)9csFaDzUKvnJeRhkrGPEAuS^)UH--T zrvS@u@A_3lN{IC{i0JUP5s^xk-^Dr=DAkFCblVt`G)#DMu_bexiswn6hgBOem$y;q zc|uv4qMn1&@#vM{tck8#_&KW*my>67)b=)z=)>Pg7FzA*JNibp-lIPC)%?Z#T^3A< zWYFQ}zJ8{mpq9KFK(7tfJ(c4XG1St`o9ceDC1MoE0z@4ENUO@(H%y`>>epgTvY6@) zhdQ$eEF9@dhTt<=V>)cP#IaGbk{Iv9Eld_nzW zMe&y~1V%Ba^TDi=w%}e3s1XaP^JgRs+R%Np=wmkI1!yHv+K$PU9^FQu>yB1c zoXVacci#uRSO!$;x6t;9Jf)xrDIjF5rs%(f??7lI8R!(NiHns2@*-+VfBj@7FQ-Cx!7YDPa#pxyjMXuLD=@^=D2+|`5bqu1{+0JZuLpy{Lr z&NoohZVBWsAJ%pV_g%VtGu{$FDlR*Hd=W3B4N{>5XTJQ>C#El$I_1WL+hi2}d@siw zM9VC$-D0{-u#A3^USV!M^EusinVXjI8XzrTwUmCEJk~RGPM+- zCrY%qRwkjAA<87=+G0xL%Mq&`eeZMUd=POWb4XbR#@%GmI>N4g7Y+3wRG3p3f(O99 zNNy^K<{i6~YH~}0gx(*GggYQ7k7uG-FVL`Kt83C%cYhS@#EZoa6d;>U*B3r*cUi~z z^nq-?Vu{>w*-?cdOcb$sdn#2|y8OE*V0IFFT}A77o%0bY6fm6s3e1Qd#;H->U3?1~ z8_QT}J%0n+tW8iQulP7?!}}lF{9jXzFGlI;H^AHJ^?1@kj2R{r+Cn}Ec0NSM61~Gt zo;8CAT7m_O*Q4YU?ItA79s}w@=cK)uu7xuS@s_PV7$BQy%Db<~0vw0+;^q1|hkopZ zMit8N$b-%RT?&9K1!GIA^_tXPmU~Vx<4JNH#g_6eQ@;KzRuT-shlCo}s1Xddhq8+- z&{%2CB3CIR!mnnRJdG0OcDUlHC8zh?$~7mwErbeHhs`=~6BOCMdfJC=VaI9{6PWP? z8WDn!?J4{@-jFceXjP=U2m^DDIz@)x(AXGoJ3iQNkOXdKxc`$R6GFFW&;%oRO3uf_f9B)&{NEcZkRLQ*w4ylnDku`3 z1*#RkdlcDj!vR*&b8RjPIWC2?YT*FK6fp}4?^E!}olf&7wXX&~*CNAQ;PXD3D8giV z@CsEeDtrd*(BMUlNIpl8N8s@2xbxi}e>bp}22>+m53@CZvuF6W`_=d5Aoe9(>@G-b z1I_pj-bwMTf`a^iPfAjqvA+KHEXzov9v>Q-XpF0WXTKiWX;@%7o1&YpAl6yv`oF`< zn}AOJwnFHShY#ot-lBl)N55mp_<7d&VsXMR292*=N3IKL26S%>^pS+8RIw>&MiE{mmy4rrGL|zkbO8 z>)69Uf((jLlAo2+l*9N-(HtYdRA)>UyfdZf`Zzu2K;4uZHFu)tq4mF2w9Z+}aG6xUUh;GSv{MzNeuMx}zX}IO5iTwIxbtTP{?8>TZZMcFe zjzTRSF5g5G!Cl>T!KPqMFh0iZ>ETdWix8cxSg?y5LJV9aw>hpr*+g$wf*Bsq#x^^q zYdb?bpa(&h>f-Eww{ep=UpE_?0?%kZDaKPEqao^3I>1p3K!KqeAp+;OESdV9~V6jLKi@1W^^>dxWp zGjRoF(r~D2DyB>sMEr6*9i*xqnin|FSnok6f6{i~jo|7V^7Ir!?uRECUdOz8x_I9? z*UEuz&3l9o>^Sjo&-ZM@=Zz)U*aGT&IGlS@7vs4OFgYr%ZypOx_4u-lOWNxcCOc*f z?1#goP-`jQFp2Z^5sN{$UvzJ-YWBWoYTVE4Fl(Y&8nk}rQ9v({rD8cq1z=nNxk-R!j&CxR z&dwNrd&k2Oz)_3?grmt`0sey~>(+(8xdXkwuYEB2-SE`&_iOw4eeO-1qw{unGj%3GmV?5}Fj;Dd z{^<-^rTu4V9PY9^)1?oQ;o3g%B5b$$D9q(d<6j?|+x9}IVT}fTrUSsb!*nU(XOW;q z%jmyC6Vtr$KFO?JDhu$g{q&bf2X+oIWBDxm>w>mw#pL3CXTYS1UqnCQDqDb~P)3fh z49CrFZ(*@SD?fU1fl+Pbn-UU2qNo_Hv8hd6^mUThM5v_u%qWeZGg{P=J!|#)Rz{c1 zD^GpcWMN&JI5MB{+}AVT?frj#mjsK&{*nCURhc2wQ+bZOrh!Xg+0K_T$IlsDyW8T# z^v`1yfZkr=Qb#Xq7xJ>ORcaXWf_jpc;x7VJ$8=?72r0_`H8F!H_jN|->HImEn&nocrU*>T@WpHJ9 zEQ*sN3M82|HF2U>VWE%Qm7={U)N$%&=>)~^KNIlruj}s@QFixVx2!W@ZV%NprNgAK z#x4&E8on;l1Np<|Ymj~Wt-CqSVz62Tzg4q^lOZA9E+*^QYOQ@(6d~o#qGfmZ@wn^m z@W-0YW~Ca!lY4%K02=nvi9gKXSPhkII-aF#a>Ct{g&0?px5bPu2Hjj$c;eaG5>n~K z!KS|}00sNDzz^BkOkfWYGC8=oV)QZBDomzb`lgJq5TD33D0u}}tIVDgao-s4Ogzs?`r zka>6H)h(n!x>9=k2gZ~~A3+J&k|u&|tG(arzpCzLC#s}}F6jHAXv75PGm0Od+s$Vw zvEU7cV9OQ70j&g5QR6}NC%5?;vv&HEB0;^AVN4^Yp~VK}@of9)!(fBX2QIw~5Nj6L zqq*G5uIwWYqE8#MR1yY2)VTZ*Ju-ZbR<*t+}@#g|hS;DLP&rK7g6UXxmvFQaJ!H ziyX>=A1^??jVB^+X@KL0_Z^B0Yvf=hEc%up_pf)ErQ>2oyY+red3s0drfBxU>tcvo z_~8H@w#fyYIQX;9+wmB`*-rQfT6rQ&BsV^OVoap3%LIt?*R5`c)Y;!IhzsqUc85tE zyF167yx2q9Z%cloWu|vqPOMqy|K>LEyo~~Ohuua(!PZ$w<)*K~ET!`m;urCsC?pi* zi9&$_e>__x3ft^9Ey9O~ojTa$52cw33m)**lGjaMh>^)AUzcT+r;6hJ{E3(pZs(b; zZ4M6BDkUXhtGw|Tyg5EBO%w`j<+As8AS(DWLdh4Igw=5%clMcAO8e z$4^^WAA+jpPSYOiK}>_8K#p!=A(PGDK6|00>{jda(J@voA)yJANlP#|+H-x?#JWqR z;)Jqdxde)vwT}XM;4f4s_9^E@r6vNlOUR5NRy@OBpfVBG#BS||<2fzXd>P-KkB#@k z#Ga_v@5epqDPP9MvT6*0mav;Y=8vAO!FmCyY^gQaY#3@-hQH*kGybAE6pJUN$*L{G zCw**#nV*>!azi%C3M}QPL}-Fd@MRnK9jmmxzhy0|WbY^SAM5;-N0G?vm;2fNaTGK7 zJ7ZvO4AIpTgNX%A1g_HMOMFO@`WC-lrGp#OFfPwixBtbf^X3!ef@V8Dj7__~rzF>% zFcGARpjw zrE0vt;_br8XjUkMSmE`(k3dOhY zVQgY@Y4ksk3?mb(i%WTjd4>{Nm!4Dvae30!Q+%|10BtSmC%FhFdkz++NuDvC$6TQ@ zEuLj=#AtmBFG6;{pI&uC4-etaUH-Vsvt+?I&odS}o1HwU(wNvl8i zr``8wkjEunBcBtDYU9`M03~s!7x@MsT~O^mQcmmI;cdZ3c@$QhzpVNq81yPQi3Fwf zREpdmZK;DCg00c?PKeW8tA^;?S8uFad_!TuO-;9uSKri(jDl5%0%-b^>p;20tV#1v zPqEDZIGzB)^Wlv=87B$G!pdK4MEdK{sB33SE5u;aU{_;w6H;2!j{Uu*S|tVYvxjz8 zDA%E5HL(0MB{FB^b�EW16cnDFP{e%*v{n0FiR=yMB$e77NBkp<^1s%brc=+9hJT z_@P&!VgwzepBMS7eW~N;`-ZwkONPss){KxupU$gLIY$)!m+gHsIYKaR9#(SGa|a{ zwxBbAVQ!2z&^h3MNu>}_b($W!glcvE-2YVy8b)AOhh(eeSZns0ByW2+4V~Bzu{jJO zc0bq@QFs5M8JXq3wSpt1qWHz={>qr6l;-k>5ga%0VTaTHb5khK(Ts6a9lIjWHXqJN zC`c-qZuewy$R0Inb-|Xr0TeYhHonP%r;Ai$+)IJMIBtv-!=Cy%G=EgFR%LMSfrD1< z_aZkMPlh|6kRehKwb+h!1Jr zUpsdDv8%d>2WzY~q%1P1|5ESQF!<=`+jCuUHnaR!^Mo$6uby?uK2{M6@sBOAIh%(Z zSG54B17tRAXR?_?H=<}+^e}*3R`unRU6@vdOnawzRrB{b_qNppQhx8NM;wS>qe`_p z(?f^VT8n-4-mpSdHljJoMIq%J2It)E08rkd5slUMNiD<6DJC z;IYdt`lHvIjn=rkgn$2{w+4>i^k$Ppd4Pp$9VatKVw+uHZ48R7L9!<DV5OU0baLp=(IyaiuNoft>@U1s;hLW1p0SbbbB zYxu~KV*wd%?w8Ry-*H1D@n5KtO@%SRkZlg05uTHb>~bRW*=F=~miUyg`((Qt#D zPGku4tp7Tov=p^%AK^hH(F0#iNPC>g3ZVcr0%*EqBseJ+0QSMWJA-Z+6$(n=cOGS6 zh;j8OwI$Hoj7K)u?>>fQ|NCny((@Rbk<*!;t0)^fnCmZ=E`B@Kzvu_#b{R$MI7@24 zGOka*C`#Ow^YnH9?W5~c;ltj~iM3Vo*Epz*e5a=6r1EE*@>)*tumj2)-Ejm1CQ#b%INq9Y3|G+NtogxG~G@M%z-~ZBB?e)f= z>UEHk8b0l?PO ztJ>w!JE)kM%^wi)bz_9-{D?~4R4GDD*F@Qx5I&H(!-br9-O4=vhUzoID%arj@Ip|7 zjF3HDg9+VGjzlFILap@yMh{q-n}jZSGrX57Z~hn;kvEX4hvz>ZM?L65I0x~)Zn7qB zgPtlgP{E!1a1?-3Gv5Lt#It7@f#Mz)VV)rvw|qBhJTfz()C)R&PEY0y?EO9rC|9L+m5CWwes-wgd*TJdA~XMDBLkJzxI1J|Sj9-dSMgo%QY zfO2Bc0&9jS8g?gx7IiD`TViW`dUV;z6OAsHx7qjT55w;xJxH~*B;+H3*?rdo-&Vw6 z1)Mogzt@E`qrxzM4YdLC>hT97AGFTqP`+%*Zoj0)dGq^~lCth+=Ha(4Xw&%T4=fw4 zzn52Hn~)~1i7>;w*2X7podgOQ-vwhYG>fEd!VkFArmG)IHOX03_426MvK$Ol1y4Hz zUOK5wBtFyDh!cU}XCkI(8wZSN@h?bDgWsW%xtuUtN5kE^PZYg?O%d3<6K~eGNG)kH zhZx&l3|D9i_*g{jcU`^pJIOHKAGWQz9MGS?JJRk_T6GOC*sK#y#*)(2x+ogFep-(O zN=R7T-rv6LL84f{3+m8kYEl+*q*aRKZBwBcw3p}p8ylHyOS|f@tB*KMrzqX0TeIIf zdJ42$OJ~XQ8O;TLpuoa8{+g$=NnitI zs9;LRK$!WGWHUrvZm#|=vQm6_W}R6>F#7Z*H3S>oCkR15u#t^ZNppzZLh$nCG_7}e zpDugT5)u7OR}+3tz zSbhV(;m&WgeN*2cF4nkM;lNWjDwK`Bw>w2>2RxyA823Gbk)-^bAhhQ{c)zcyn?0Cv zypismGPW#~bStP~IA*)_MfOs-4&5x$&V7GZs-i>Z(rM*A8b#mB1X!mhnn)fq$8ns} zRInTQzds*VJec@qdeN{P6v6X+C&WrNv3outtfHF?%!{!(j-qvbb_ISxf|p3&NllJE z@!Ia6=#>9%ZJ6+$P8-;U1J3{b)r^Xcho$#W=(oeDoI!PBYuwn_*(8@#^`~d7mw1bY zp$Y@7oT3>0g##ZzBP!q~2x2Qb8|w%I>}GHccV*|AW$8(55X&2cowbIv%L`hgc1OCF^ep@#?2rl1^f#n*$k=Hx~oR(cWSx$DbK_&*^Q?3g@f&uYZ?h3KIDH0lPIuifj-#=|7{Z=67#Qwv1W? zBzU>w>4?pksrbRe**g#gTZd-7{hLI^G43mNKNaU)_x=x9)NF>*S;p`aGQv*9F4-DL zM}KJ+2zH1Wqw1A7Uia4#5QV+E(zUd3A)B7msyM|V{O^7i+6!|RH6{=3iM~;wUiS%e zDOM)NlwfLJ$^Nr2cuUuD#}x`vGv1Za0KCY>vFx8O}qNRZ3bq^g)s@=U_73V(KCA7B+=pdC`t+8%{yQM(|IH}5z_)X_Lm!MCJQeQkT4EV(N+e`Z=U8KeR)$g#extPgPc_au&laP< zxjAForFRW&xv6fIxlF@$uJzx)x3bSTVBNTVI$O$0uD>;#UKH|Qw!D0dFGbO1k^%J0 z?~9{%HJyI%*KaF+`l*eHg{r;ZNlT8_cdT!2?mgD_S4rMq>G-Kspf-4EU}3pjczCGh zyhIZLD@&NcNi1PfI1xi~9*hL*5fp zBY|rJ;bTddO5r3wU@dA-r^Zjpp!O-2f64X#|qNO$Xovsx& zNfCOaFp%L<59;M9p9sgsl?MMUQi`I9;#A5I9vLW35R{Y)2IfV88~E#gxv=<MQb0&8!hwgWfTW`xO}(oL#n`bLL3)ed4MnWq4NY@P z3>$mEWO#*R&-Lv_gE8XF0%zRuBH(P9Tp%C>oMmeGh1MTA<#?Ol%In#}i&2em**$K| zX;$$9mV)loyYhO)UO-r`{?2#%+On_v^$sw4HtgcNAf%`c}ywfPdJ&@ng+ht1P&F42I!eYPmQK`-Vc_EmsjV3;ZB* zORh6a9Izwrrr7YtOg87{r{v&A&Ke6($~ZGkXN$J5RWDl@7Kda5+#G>O#*qYd+i9LG z1A}ktIgPuFMLK$VX4cjbMm2*?w(~=m;oO!-qvKk1CxBdoy?HRBd4`oBZlBo5-gBmn z6`@pEb<#NiIv|~FZyQvBp7@_`Ag8Qc+;q6_4zj)kQec7{7G;gkH`x87t?6-nJzW#g zDSz`f#1#$Li%Y(fNG=vwGY<~JUTz96Kpd>%dzM6j=7qyh2L0olu(!N1C2fkJaR zIOsorcBxno+P6NnaP@Zpb|H0Z*5D!Qz0DXBYz@h8j3I^w9ZUr^`$LMugV2^?`$vE5 zsO~{jKAj4iQHl$Ah@wBPUb9IQ^ww%0R;I|r%xQk-BZ&ciu>wEJ8ZCwh+0)V$NdIctS{$KwLup?}`nk2oC!c8b$2k z(m)0^-|-gsMqx!x;0CGUs8a_^9>arE0RpOND!xpp`kq&Ki#i8O6gtf9_a!2%mNC*! zeYJee7D*;sYyY--+2s%g%Q3$i-<}QzJ!zF%TjCA5}@(?VMfvf^AJH%kje{@jR`d&irXJt+Pg9> zn-hr8#wr)R`mpk3!()w016V-5UEm4d{+hUaxjq)Y-q{YXry|A>x4i(FJ9mvW5g@@bNm0q{;(tutsl7uYs*fH-%$V$5?-JU<}Za2riw3$O|QI3jjjk zY;eD`Qo1JT&#E7@C+{)71016QHSkhOirB_U%etvw*Z8!0mPASHda78l=M|ZO^UtaW^*FjTMxx!mG+L<(XcZKQ0Ve72ySC1#5`ECv2z6wp< z-rPD*q*~sV*?i81$2WT1o)$07lqV}x4)*T=HcOdNiu#AbR6Btvvkqrg1?<0fi^-OX z$rh=}f@+5G3d(e8HLOpW5YWF2;kx2il$*Tc;^8>f%4jeJ9 z8WBP}sU1x6MwojpZ3w2U|*b4W11aAUNCO82ss^s6=mviSm#Yovj>ApIs| zKNkGM^BbcoSu(BnJkiC!T|k4>m{MdD44A+JC&cNWpdMF5octfy9rz>tAu!al*4i*T zzw6@t)iqXJ&NmyfxWBIqVKU6UPrn8hdK@su=z@_>kT*VZ9GsS-!+B+oFrufm+q15# zrWSw{k0iv&N_?6}PNji(;_Lm_hzpi=xEbN5Uc@g_D^pbc>8pmbX9em6Z((cnur-UK z-#iB@e2bED0H&B!I#Y~$0+zyF*U>icI4_pFe0=`5L@b1_UY?`w{pXx3X23dS#Z%bn z_RvnKg1cE7dwgOnA@qfV^WY|;z|KbCnkD=TQj9i4`#k z>>S@}EsG+>@MBH}R>4)h%SS(+lV!E~LYm@T!TI7nqG}OUmFrk>=5y@P+~6*xKkPWL z^gk_tamx&ezx_C$=aat>uxkY<^|vU+O>>!$jZs>nWt+vNm&_FK&@bnVg|7_=Lgk3F zRF^@(=ktrrv=Mz$$NOA5reynQ7UKb0aSeb41LVKaW11VR(~*QSHk3Ew15IKYt#cqh zW*^xE9i}-{jkhdCCcreUzW}9XPdgy~OcS9^{mX1!Vfk5L59TS~(Hl9FO zj{l707udS(h}DRs^i)Jfng9s4hP~{5(}qaKr0Zf!WF#MyD+sfw`Lr<~9*VFv6_;*) zd03J|%g!s4{rLw=j6W;cwgkiwCfKgq1DXla4Xs|G zKkMvrvCZ<2+_0C~m8#}I(XvqhP-6H3xQNPjQf6rbWuRo@Pxlh{Z_Demmbir- zxU0oIQ3;;M$MSo#NQOf!i*dDam9~SE<*qHuT?Oy4&`Wn#)w`w9r_sBcW=FU3;3(tn zDDFDm_A z?c}n=Kx`YXcD`MdDKk)DJwGzv5pZ6-pehx(8uW~?ezbJ27xd>b0FHgmch+?-O3Fei zT~JFxQzmf7SP_rb0Fj5B4YIxt?QXmv|-C8R8j zqnClW5Y)Hlfn1;;(?u7j81q)UG=D9qe?IisOw#r!Q(8$Z56&Id6o^w~zOI^ajt7SB z{U0Q5k)So*0gOBc1;;=6?L({`nIyBMeq&Q3=FiKBzN(f^p*URju@0N9sC(WW$u+4F z=y=whv#@4d99mAMP$1coA!g5+^fl?Wa(q%lclMRn{Slte7FS#6l0{3xbx_So;wHBp zHA&*C3qY?r%<=QQR|pD;nKM~0D!4hP*~slWkjjVB zq9+dJmZ(R9M(*w>JjaQIdn+1sUsHonC6Wp_D*Qg8)EPmPQmL=ndD1XU?ADh{Z}9b1X$ql(Lgcs+xMT?w%X*-zupfeE}*qu<~_J?LEm z5A_K1d#-tRPqJ+ROnyGCvNP_9#_cZDp4*De<2sZE)Y^p>#9dmB#}xttrSM~ZhuXTjp%sG+o)}fAn_af0`D}NmGJII4 z@&$-a5f5sb50ywRYL!4RER+MAwF81BGrb#~`yd=jTdg!-h;t+HCHn?yIb=_hnZqWHaBW}Ofu zLL%7xPvyqj@pPYA-g<+{z zV8BO`-Cr?m9It<;dE@K0#V9HHk(p5en95RtCG*IyYGa$p8^Npbzh>L|-8<_>kE>{9 ziDde>F-oxEsr$+0X_xD<)~5@2x30CZNsmoV-YaG1cMkLIvXt(*{kbEVv(t7}UbajQ z?ZknQT$-v4Q>oyIzW%hFf(#_83J)9mzIMC3JVB}reNswtUivX>a%kT{P8D+)&_5l} z?4J)(?0%YfO?@%>Z5}JEq?-w%d{=~?AW#U@h9Cm*WcpUWXbT_HN*yf-`7bpcCWd6X z&g=I|BZcdWJ)dp3mUrGZ)w#9wq1hx|wOZ#X+0v~0b`M#wz^LAR`lEm18@tS(O62y~ zzv=eRdw3H^a-;Q43@LDi9J_BQikYm~n}B;nhwj?Qhn1PefsP=C;$)D*qb%S2_Ps(` zgsO~M@}EGGWN<@Un?m}aj(JdaqLLa^U@hxNnliM5(P>pbsIeNzIK=dSo^NLq9Bbat zP^B1xyqQG8hwrQlD4n08T*&9~HgE#(-~ zeZ;Byh%j-gg*~%C^+;M}&oAW7xZ?U5W31;GgU8N%mx z1$Nadxmu1Fw(EBvU++}K%$%Jm2J3$h^hVCn75EX3xJMu%1Va(sN#~tQXKmzo0JJ9I zbSHg;l<=#HS_G?`u9@DrKy8xHO>^(f87b>r(uv=f?%P5`P zZ&$tcm4{?2bs$0+n;=`Z=uW8#cg z*Q8Lf2hO%-ndf6i*b3Rv^15WE5CV;iaBZ;7EaM|We~D;__YrDj_v4#~0p28fv@T?<^b-SuIaEZQXBw8g(bT=;#rU*3^}Y;9-@nK~tG^arWVeFTVAg zVvkH9JzEn`u~83zY!f=F=UC(3AbYuE6)7b!n!T(D4}S(_8+TN=u3T{6J4qCnF40=| zUW$2Vzn-_hhUU%|&m7|ZAr*ceD)}cuIKmT-1he-qk}s%zs0Izqq*`X*yUnU+3_yQP zb)Llp*ZB_^p)f`Cz43cq3E-z2bR`Vbr@=CE8cCX};bj(dQhPfG1PwTj#mk!V#s*N4 zxdE9SY69hayVZ*LF;1OuV7(pdAKUZvYih|SYCEXKyMI4}g;j>@#TlJ9jBF-M%>Gc~ zMAz#x6KNEGlM99dKr~oc{MV$|em?-Lub)~RaEvrM+W1e{AJ@Qc;s_lXA+!LeDouY4 z4p8BZj&dt0%323oYO<{`L<_5)+xn!KorOxU7tgLi^np>LP%I>d(mCF9)AMB>3zBRj z)ypBfZh$Z%ZP0;IEbYT~)G$FcKB~wufO!XAUWAFKJkOO@k=OX2h5q9_G; z?0)Ze$(=uU2W(<*-@Y* z=1a_3jt{2qChn2{Yj;2*C$OCm1S5^zkcF4O)36-}`mQRE=={;CqJe7zhmHmX^8xdh zzfXo3?21f_I*UD6H;(*^7y&)?1~0oQ?3ZP#qJ~4EuUD3K4j%syau{;FGCeAWO4k=} zJ@TD`v8j`{6N)Hb@v7YAllzH6m5sj0LbunI_#TB~Ed3o5g(n7Z2R^yJ(z|S+C{?sM z#`r5HjiK4hX1^6jxd0W-rGHRlF;|#r4BuAU6~rsP;?u4(jHT^}*!^-T14-U~>psjS zrC`ogV53LyxvB8v#(?a-g4Wt6-`1TdzI~ZjCTjsE(e${ zO_@mBI`F@LffWELc*+U1Ma}l1=j<%u#%u|dfAg>QF-&S=<;C2yr7 z&t5UM4olPs*{KK!IlC@1wzE$HS9v)H5a#_f*OH9CAt@-|k3W{Oi-mpLfd7^A#B@>j ziP5-A^1OiX^ZJWBBkx78;J64M z6P?YUbxXL%HHKK=}zQZHjN{qGeMP zyhTi08({0t8U%mrwXku*^QHN>Ta-`xJ^yO>0nMNB| zK8(o9Tv6_p51Uy7IK85hTZa<%8?TiY@9FbA_(CJ1&}0l{R#cla#El~g4_vFZI1Z~_qujHqY4@6CB; z-DfwJW@;em$mZHbnY1d@{m;Iza2;)wOh@_6DT~{Z#49`GI9ot zK3C0g!(qa0)xu8Gk>{U5hF{G{?))!N3CDeq{J%hA(Q@;6>_83$>#-HR&yFkKDW6P$ zZ}_HIf&b$?cGYu*WQ$(vKoEnoB+&9;abR3MFsK0&xue@x*8E+B!@C#CIbUsrUtU`J zG?Z;{gcFjfxqipX;g|c2FEIb$UbvsFazF~C&+sQoSziE}u@J6hzbyFQZ!Pn|B0Y8e zo^_aiO%AN^Y9Y_y!92M1||8Q+!oY(!Qj>zBPwNXJI~t?lgH0D z9)KVO5(5p>9>$qp56kHk&~T206`rXpT_SC z!cLK7)F28dhC_Iy#q#OFsm%??RE_HNy6JwEX-`-qtd5ySdR>Ns)@D5=d22Qr_;0T* zGH7ZHh7rKnVX(S)+CvxZ+Jdf!n;(7}hnmLs7a*+H2#NM)*ph-Wjq@4b0Y*fx|D)-w zgQEKXE-s~X3%Hb|fJ-l3($W%2gGesj9n#(D(hUMjhom%uu)xwO-5}la-0yGZnYqIs z46`%9y`TGzb6$s3!)ENyU3juxCXYF1Q3_Bvg@#Q}e@shDJH})Ipp63XF2uHvA7E8n z``yob(;0iRh#Q;&8M*zluM%`61ndt^JYC3TC5^PA8=w@JtlW0#--KSUt9(j#Scm<| z800*)(Bp^t)vr&diZ^&tOupf?}>JU{iestI>whT3jL9aTVii(Q5ug_aE4b{+5b?1L% z{T3a$_dlu63)l@NR2t6CoFaraDGAv$BB!*nizDLuh9Or zWdA|>7y71WLB>wm3tDzQk{5Yoo-uNCBZFoR-Z}C~0~y=CSLbX>M9X7+qtM9gZvm_G zUQaFr?(oJPRfDmlkXRhbLI3!Ig#SW)s9f0cN#hRAm*N9@-d1-G4@&&w9$S4vF$2{i zSBfXfG|$D(4#&=?Mw6^G0`|SVmS^xtRFDeD5KjnDdP^d4Au5F7bWI05yImjQQ{+N0 zxTz40ELpPoE5Mc45vR1F0xvU2jb?r~&a$_nAll==&&=@=N}R}q<=@dQQZ7&j>E?>d z0gY*W)J-}K9HjlT(65q&>B?XV*dTIAGMvkC}!f?j7p z-$PV_>E#t=)6A`4pWu3!-2ff%(mPwdS%r*%HI4{=VU$OaySegs@V@dVkXB1In9qX! z@3AXAMTmeYXIuB#RJyo`8`~>dAH}?N)XN$3zArd+G3!5Q3nXsQ&4j+>N9x=V`alZx z*<;`(FHsXBVwt7be}2ZOZ3xlP52k%W|ACbISN%kJcjAX~ghu`@Ict|y)zLu;%~0Ow z3@hY-UbV`l;^<(81ERnXIj#{R9^^{|ro61keXiI#9FDNLNRKs{vR2g%~h#^>?HE$Mi%-{Imnn1H!} z=V|-tX7%=GFu~c|T;C`_8!&f}VCJzxAFHwdGsG?*nkDQbA)AxGcem-iqN9^PG*TG> ziTpYV7sn5$D2W6!mRK%l$M$6rN-?OBggqMK_Li{l0O^S1i~a7RL2@>eUw^w~ZF?zK zIW?$SPAXrBh&90t2J2KNiy9D85kK0F3JD=(b4S-!fc-X@V2MC6X@FaoSe?{^rt}fL z8DE2S9hC}Ex_WXxUG1MLinzTQlo(rIr*E=DT0tTTBl;I~`Zk~IqycCC_B3rrl*vAX zJX0qu2)uo!UtJGSoz~A5Rs!>}T$f)XT#7V?3f`fF!5JWUBXwM4+Pl|axWSJY8*9Nd zCw&96P{Q+Qe1br@jje;5u5rM#ud1bgs{dKLzg&anFx~wwb<$HA-ZiMI?8U=tTrRnZ ze)<|ka`8qY=xS|{`)NxeTq@1BbW!pxG4VcsK@*A)MeY-ov&)Oy2ZFpI$tdT0H?@8g z^M65e{}&H&Y7jnpbX*%RFzW`y|KlD##erTV|!7iOQ0_8ZCB%s4#$HS&G6eL31U6%2EsZvyMT}B?Kv zdkU`F1jU9BH!KonJI(+2;5Br=SUa!9WC-)bPP@;Z)EGyQb-~iz*7#_Qy;kS zCqG${f12R%#i~QSMUp43KE7xu6%V}X3s*oUR2_+%=n%>#>5WPvNrSs1wu(W8CSe=a zI!%&kiXfFt(YIAB>`DxrjBuO89gJ4EN>ZP!EUpApPSsIfQrgaep3_jO!;MJ%u8$qB z3XS3zckV~4l1p*uxO-r2#C0k;(fdB>`24FaYBR6E17Sdq%biMAnL@8Xd?q>wIAYxn zH<47lq}p>F^g|=0w)R=dOK}$Kcf~3XcUcb{C`Meg#WtYqBaRsr77Kx36TK;YC4*LP zJVb4cG6~(gS%@uCMo}SWhl(ZW2O2=dzMMH_78L01s4HU(3EN0r$gYEvk?5rywampu zYeYHDnL_6Jxxn6SA{3uqwP_@MmpV0;BcP(D$OZSuReeJx0efu3QiCHo22f-1~lsBAfWbxYvFEc z%wjIQ=uZ`{?AH9`E#8+PiH9|U+dnTPbe>wy>7ODDGd%@gM=|{Npm=_vnqY|)_jD|M zfGf=qQ}C<*9`WSszM!t26%_AJc-y07wKGO<96)lk7XEIwo5YGByRe8;<=$l#N}lFa zmd#3NsaCim9{tem62reJL+eY7FgEp?AB2q71!`d%&c3?1pQ7Y9p-9>hN-M7aF+bSI z-owJILb8t+e{?hg=HQRmpfDsy4;*!*(5yb0z_t!lNP7S9lLmQ?o>rW^L)`26gp)zC zRFM#&d0=(D9DdaX;P&i8$Eu1Rr_)5ivohs$WnX{Y{%lg8tbn!>R7j1y*X|d|t(Byx?1o7FjfB9q5{k2hf(5uJYvEfLS^hx1w)+HmEB9H8)1MUv^UmRPW-;pW6R6Wn%-1G+%f{gx{ z>XMZ}{|6ZG-Fj=hroVberUn$-CKU7`dCM#2+;bu(q+W741D=h&$?AB9g=@Nfg*4h6 zOkj3)lOHGmR1?Nr0!=d46)IT0HbB;KRhhTzC0C8w;NBZjX%2d(tAwUt0D8f_=TOnU z%Y8;5a2b`A2{p8YG9>uFo7Vg7nQ}p-Gf0#4?@oYt+mYHic)vbZGGMEe<@UAjF8A;1 zhuH+?l+oU0_d`}<#Fv|?H{2^N5zS439{Y#CWqtMJkyHY;$bVN#BO|;QrJ@KSzdLcj ztj&d62VqjsRL!p2b8X%5W7#@VqLch{cC~0{9T=-2{AiNf-!I%T79lqxC!au`q}R(l z;%vLvH;xgih2E(G+tNwnKHcDyE>kVj0saG!O?~pj>UPD`qpral&VR4K7|pIcCVBv7 z?lmOgF7qeI3S@1LXG@t_QsyT|rlGXMhz-weCk0~DMIhKuUL9k8bkBC@ zF2WHLDl~6c6ssz!e#WzR2}zRqym+D(XiM?D@E@T=+{24}s7xWsXmO#zrA2;&bAlLlv#Bh`OBR{!BwRJ;Yu9x%7uL%%vNF^-V&p-Iv~5$* zQex26*)N~_!1b#pAbRBh-Gewq!)$jd%h`CiF2=iKtW^Ax_1{hWQ-)f=9dfsI>}rM# z&ev9u!_18>WE$^IL8bX3bz;6VZciS}UacCXC_PIQ9>TdF_G^6@)Ke4jTr9>z_cMX; zA{fp=8221p35k#+swmAg@IJCr&DJj*dKqS3)8PK_H~%p~aormTCi{C?eGsy?(tiU< zza?F@xCnj1IRCaPCDAy{h&dM2R+acZDNEH-raE2o90ZZL`t?c}s6~O)n|xMaP@A(; zOlUm&28lhl^C;#Y`+W@%nOi^K_Nqs6u`(STSOR`YDqwE`3azaAadH2s-~ymzP9H%> z*>oB&GfMtk&hkUqr*^MB9H~eKYk_fzTrZP~i|t^alWS5--n_E{GRfV1QCOF`7VOt! zF4oE@ zE9L2b!fl^*%;!>S>@pd%C8l-Fxxv-k)Rpyp__Om!y2C>&TibSt=fD_3ee(+(BTy7! z1#TSfXST^Ph$WW7bZ=hJxjMZd{?K}Qv7nDh=lPI-?{&sN3(R2w#6+*r&X`gyjkH2! zN`E3Uhos%34E^t&6D-ms;60Uvd=xkijSjulB&m-mt>k9O;fXBwDI0Otqvj7_4EJeW z)*gh+(w1vQ&aqagi&8eFdatjs>i~Uet{G(Fk{L)J;=d9!>Kcl8DR8Zt3;?XkvV9n|<>6t+(3&q^Fm9+W z$)jY}il?g~YGh?-ddB%TaeKlL{pC(d_dLan+MKEK(2 z(zxCO4eQ1V=$iQ%(w%$x>qt5$5HU8;uapkuI{4dY{L$$eTNIQVohJ zdyRGs$#;MT(ka5`x3hVD1F6yC@oA_w>R)OSdBt_f@Wgx~h@OBUA8dOThpvX2+!Pus zRgd{XtZ3LmW=-DV>uZFwZE2CMiVb81=i(m70A)|n@ZF%SKRJaUdeS=qj)<54POBSL z=+#(+RZ)GXe-1znzU4^O*uYU$pya_db#9~Bi7jL0aLn1^C5?dsal4L!S)!%Z&q|{+ zfgk0?Dt}#^_3$PnW0(Is6!Y-t#YYl|O569QQfol}oTX=+8zRD1{2rN7zeAI^dXlbH z31*0*_gyVmJTlP*fb~v$M>L~p2%BodQlsm4tVxjK3CBG*c?gUnEMI-|gM&_=df*0# zA}nv{CEPM?-BmMpyiAQk$K&;#*c8G@_BqO(A9>yu?PHed&(ndl6)!3E7;;I{@dJAQ zzlMED+=x;Z}t~ClCm1Hi!!6m*QuO;MdgVNYANYs(tiq$** z>dFUPMNO^qrnv74_rlb=5~$Q8iCs5l9>zR+QQ`1|KK1u5&?9$;VKJO#uHn_sr@N~^ zpS>>#vC3G{s&pd!U29$mu#}YumW1$n|GYqm4fZ#4ZnWTE8ww(xt{W|Hhvda$c7z4f zC_FEw!hvxb|a3 z$J7-92<7RF9_0?h&WjB~V+oq3y_kvo8b%N~ON(Ga9HBrS>@d z2FhCO6-If1g$i z26HM$^<0BYGByNPR9IDS$-CY&&=AXFgb&Fbzb}Gz+lyHGZTt>gEiQrbYCdDpuK&LH z5yij$`4?ahJYmbPt_X}%Tj2nK{x%uwx1?nAzEC`{FrO29@YtaoiQNSBXc z+6Rm7ujt8#??%%%TADHY=c=Uz+SLMLM7p}Vl8V2|FJpf}b`C@DU&YGVX1N1j0bgJT z9C>nGYZuKDwd<}aI=g<<>|q7*O=2lz`C{#s>n~9>?+oNY8j?@#^RKa#erkRe`R-3E zGxXCR!EG}buj!yqkn{)U>5=BulAD7r$vONxv}gK;Mir{IYpImtrk2T@ke`6f!} z;ob2|T$CMBZJ$}Pft?E)ed!4p2nwPy zr$fPDY4Ob-(-F)gddDW;{PSzNbnOqVfgc1~alCRytVrt`T-%Aqul?2`{SDhXr{j29 zX?Z1Z>SkUHpE=6W(LJ^Ggv;~6*|8s;BY7fujlRApSIgMCq?n_kYq~3PL-d2=JNlsz zV0opUF^Y-p@SMBz4=7Egtz+cG|Cslo)ZtOgEAhOL+`q@+VV_gY8O3&Xhx2Je;I?Nc zAYI)dSqB24rlxsF%lrQp~^jm|fp z99x;k*@Hz@<`&wcj;4V$m=?H5e!=F3K~z+s(Q-T?KtTa&!sRgz^#Jmy;5XJ@WJn!B zn21ls=Zv5ee}WZXmlN^u7F%ZjrzapALs?%wfR-0xkHKMdSl8YK|y3Azv1PCal z^-7k_u^X7{g8k>z1uV?5FE7IoSE}*F#bi!d`3J(1f07wrHR?S}dAkARC<(@$`UTXj z8=L1-&AdJ)4?(o?*yxhQ%9&1jKI4tk`l&*hxEHxF`oCD|nwFZKZxYVN@XI=RanMD)?oI*PHNZq(p*(@C}ps{#JS$1SB5p zPrJ<0Rjpb&GOQR}l$+-R%CSr;5ehWsj}9we`@sxlJ{64?9hq?T%Ni*@USXDjmK`Uo z4|2Y1i~aWl@tPwG?c8cKANtL;$)lX_6QR7X|Kh0?yU0ZocEK89m##Esqy`B0xz*|u z|5>@Q^t`|fuB=hs!9XoD$<_w?b`}noqQd4I|3)z6sr2bpO9$&*;R*nIj-UAs1?@Ry zRSeL5S)6ruG>^x_`ijtb# zlW8#u?(d%z7C^WZIB~5)$lGA3hsVdjb4!RWY>Bv?YZ9LkV}Yb%C^x@t-dzfm&sw+NZYOvz%PUgE5~q>rx!z0fUxK7kLR~umv^NiU z1g0zn0N$1amY*$GVwPFyeq0l;nipgX?)lHI{0%Dgy`;rkwNdRvK8X?V|445Hbwoy# zKn3G?H~RP=I|iLZy=Z}s18=rr+&$o&uY>wyFy!$rIdVvcydY(LsvIw>;LpXL#yv2z z+8Go3`I+mpQ*DvqmRH;frE9Agc!Zvs(SYU>3i0#5s<#0*Sj#w}E2=wq;@;6!g?<%9 z5L!WC_)aMsx6B%8t~9fJLv^UgCHeVpyx40q($bChLjm4Iwf@+AR0WghCS%RqUTH`J z>%@UqVeX!5Z$kh=$e4sTwhH-cHoKr8E}8Z#wxy@n>xV*9oiQx4ZY@pIYZrTznX`%x(p`=T99>yzjNbw-OP>2P$s z;Hj86YR=B2Efoi8oByM5m==jiJuqHM`?7HCL&5|;EuUtnc9|GxezRDi(o*k(0cH&zKpY>q0k!SMZ7Bv{6q>Y{hItd z(4P#tgx?8(Y;99wLo}k+9N(vz1G!@6y2-1>i$~5|ld>@OXqO$|N8 zpjvTDJzBkr_@@t1coRiKOq8W)lMT;EVcR6JJY?xW1YgE*kc&rY_z|dKkth#nHQL&w z)6(=VycrB;0Z{2WOYyvQiY{?l=+3>2x=i6jMnvCRwwVTMyT&5{X(2-_=2fICiN-{+ zeG~SH;FuYz_8u8q)qB3v7G07Q^H+rvyJ2!>3s@s=%V_1g)8{}`BSq;n8VNav;jF{W z;q-~vH`2N{GPyaJe3@0>p2JzN`T043(D#t2mxJ7+C8M9YesZA$&CizNd-lISntnvv zy~51rrZ}!?&@%OCR_oXXYaCSHT%v#ha-Y;6h>Xs?wsZih;I*QK#wGc0YeC#*4144@c*0YTaB!txnPm zC<$9aIR{IQ|8RQ~SfZHkHLE^leggQA=Mh4O{Fp1<@$S$3pEgdkl!m z--q+RlS=iAdi*2-nD0ns!JM-!*j|I0*+6jPveDQ^d^MU6Nu;#~kdRh1u8d5n(B^bL zmZDy5c2EhE`q&rVh>-(n(x;c6`d<+l-Y!I?f&1UCjh^J zs5nu-_`#{rcIUr6A7D7!@3!pJdTdL=qhhiUZ%vF+k8B%`Yi>QslPe<5Qag|Vdap?z ztwp!-Q{##5?|br>OW(07`j(KZ-LAdr%PS}RjKyYdM^nlqWU@pD2gTG5x4NGJb)q1D z@V^9A_0O+_0US^7nRBpz06B81)-Ky5pl@9x)|E70gbZ$()R!cOEE!^gG1u4ygE>QY z`{$Ip3ceiqxucZJ{6oeQ$p&5}#;4rkmtbu_(`PzGyLKlpKwFoP5ht1R-KR3~^C2@}HZ`8M-Q zRc-$LW>4QK{;Xm{bMxOTb$c`Q*XELGA*5bWCUX>Nq2|;p8B5qYVRFQHUPn9CHGt^0 zq7kxj(?F}JNQkO33x$AyBvT`w%ov3%smzYiWP((*m8w$ui74GENSzY~9ifXq?+Pe)N~Y);gI&sDjp7%y6r>Mao} z$I%5=Qn6erE*j6`!lZ?>sb|!t%cku)OPho}(onaZCES+lbZ|<7D8#zJSpyvK_vLeQ zWr;h)D(8tBi6ug%2r%*_hA>PuaVJJ@)=@0_Y7D+t$i+pdQTh_6*f{yEzc&#@sH!~&4Y^SCYkcF9}Q z&WgoYWz*C>Ty%f!P*-ISLjI0+$$~lZ{Pwj8Eoas;#*i?0qPdV1)ngyv@HW!>GYmxE zE=sWw#`J!rqP#4YcqeEt)H6q(l5Qy!xRb=Vx9L&Vx$&4`53^kq&r1}hP*l*eAv(jI zwtWp~aqVVmU~m-!wD_R^xZT8%?M!7rEg#S<-{E$$1x~pSi~~Ezb=2qnNt09*5~x6C zygAiVR2XgiFOPJ+7}#FAeha7dj}TNGzdS1{hYCB}zD&1dEg^icR0{}P;o1x(H~Q&9 z?SGH#iYvz|01imQO`$j&Vu;NYIS5b>$n+-oH>(LoM96XL>Ya^j6V*Kx6eJLj);cIU zlqJM@x6IhCyQTF_!J+{TIwUe8%x@CH$V=^t?5R7{hmCd8HkF%Z3d;)Sl`^VUx&7H; zIm>Ei84r0EL+#_;!I8Hy4bv$Zdt2S$G|&{Po-%HA)37L(mIiYbk>1Bk7gQY&`RQiY z+95t_k*!*)R`H69V!$&;MV<6L>#1nCe}GK=tML=&DbTh~-&w<8hH zN5&B!CJh=Dxi_m!S)bhE*g=Se9C)!5M-*7~tTuyfdP=nwPq#B2YMd5;`ByzSSV_GwA&irn`Gj}(XlRB_0di>f zkJTI98h+h3ZU@%4v}_wZ8>TnONYetUKvfM;tgx*5wv#8IJ7T=)l$iK(So)+wzLL7V zk@xN=6j%iM(XL)wmXH9Pr@3_+tt=Hag;kHE+tt zGsokPiwWY{XWGs;E>g-Mt-FqP{7lPF3Hs3q;!| zCKi$PTNyvlFHlx9;G(Ui^S2F3zS_6qK@`t&;TB9J5Io(Xu`nuTyrxgVeTQ6&o&8Wz zI-C{xh~UF}9^8%F0UuTX2HI!Kv}V`|%SDk(1a!l{Vjh-|y8)Ni&menaq9v;V0TgH& zitf#=4WDM>eJhiQXFYcCD{;cLR*;0>|doo9LhKmA=w;TPAPg>8~-c_ zg8%BWO}=wAI}EI3#qNb3D|Vbg>Ddw}pGbZo;wQXlm&C#pNemf%Cot;6hH8XTvPDRh zpGtv$mqOmtk!+d+#MmiUeS}}>HbtAaz1JngyAOH9|7M;ZxnFXb4O0o%Hd45qh_{GtF7+Ziy?^r7xDbRZ z87=n1Juo;@olY%o~49Ak*m!@Io_T|)1MCnRc}S^ zHGi<%*r3R&Tfd7cDB{f)A?Kp#tE|4q4QJJebEJ~24#1eL-3=Gg2WFW&rvsGcg_(Uq zUMQm$vE8o$Ie~i28}m-ugc8=y6SXLNfUz~$^A8;PoeRd1u>A`a7-)T}a0`}{V(P1& zOeL^>{{0#bOW2buv6d=e5gr#(`VW(uT&~o3^wH(xJi%%u)_0>q>!1=ox{oCM>@oxc z{O#RyoqG2AxB>ro>*U3iHy-E*xG5v8eI#Q`0d^CDXDLq=P~7+QRTK{uxQZ68O19t8 z>*Z*I8|Dz42^y1DQ*U-!uv6vaNs7OX{99dws6Ze^TDy1Z$ygZhcs*TNj_N#=U!Bu7 zgI)m{1PY{@#%1|tDDtEaimYeKNyQlFmC<`8s#F6vmp&&3={v9BioRpFAemC5Z(a(_G*AQw>tG|ysIhH0SfrB)D zfTHg;)z!(qa-=hcA`!&50ZnkHH6N*GKcQ#Oy^Ftld`OJ{&Uj>te7ne zDSqJ>Kc=&(J@KOR@n}B!x5Jr0r89NsgE>W)JC%Gf<-}xm=GP8noQ|$x_Cq$~FUATw z%pe6#x1$9A8~$t9#CGTNDxj}WoqeA~rSerPp+qP; znxl6Gb9VauWYBUp2i)Q8s(&OSEOb1776-`9oUl(HjVReGg347)Ge#vjwKnnPf00#( z5Y1|1+)2KzLt=P_dX;gv{+E{XX4Gr?LJQTCbt|7FG0OWRADyhaG7JVD0rEDAi;K}# zeITGj^Z8AekGX|+F~BZhK^Zzyib?)4nBh)VY zjcHWZLg~cj50_-P-erPPsqIDccGD2KwTLahSw$5jzU%Xf*CBZ<@(wP(Ae3J5h32Q{ zQ-bNCy4H&-ODPUQwu2^fl#_bm!rxkPu>d~GZQlYkMK#BxT5{HP64JTD%;P}}(6MOn zp%4P`>Z8Hh?*>dvy++|C)zZt2k#f>ziHNMj|CXN~-(-n+q!Eby6CB0J zbsT4iJ?R91`y@fF(Z(Wo=ted(WqdYfP&rGV^cB@~u#&=nsNpi#wjy!+V%}E+sgn6{ zVP}AZ2MR@R>_~_g@CO~Ti|ajO|)+@b3Z_) z&vC#U>?)wBZpWd?$@NXtZ;ZcUaN?jaiZCZ+vWfYKE|x;Yx-P3*p4&Qv4F&LW>?_}E z0rQ$N%bY+xJLeNC(n;Hu`M3J|`e-?x>ubMOQ*Yc`hxRYMT}5WSHYZZA*$Mv|$zO`8 z>0@g*AElNn4JztZ!r^Ja92a|nF%BrA^cbU@^PUy+QrMHAlLbq9P`$HszCD_?V&~tz zW^f(tabmxFB*Lj8b4p5s2p||#h=aWSCe5@K2>v^T5bFHxTopK{0}ZW(*iEl7-zS+B z9F>)@f20|8{WR#W#UWQCfPunXoo@bW)Z)D4;(L^8V@u2L)VHh-?R6sqp?9^FITg&{ zSRTPIk4y*>P&A+IV(E`fhCX~*fB*IgqNOLUVJD&pN@fy8*8N6M?;7T+gwan}$-$;< zpgonF@7t6ENgv9APj&ZiNSYr1DKps&o`M|It;gPvd|*Zjqugxy^7fi3?P<0E-==XK1@O;e5929G~wI;JEry^`V`ciSLWtYI&f*_+8% z=zq3+#ox)R&$#3DLs77LMrIZ-XaH5xG*A#kgm<6!)7emYL{cC|pC4=CJT3jgqj~qb z4a`}+{sIMvz^j;MKISW&unH4KF-LJG3>S?vl`EVmdOh#Z%gUnNZhz(H-e%a;gdT7% zP``e_dCJ#=_(u@I0^1b}`Uz-FC#{ygtw{t+0s+30Mdhf>Kk#140Xy|$x3L_X90;)o z%T-d}HHT=NJ`J*QVdYe(LYpMf`AJKowi6h}0iy}ux=Py=M3!#RY%H|NbzP87K~5)a zY`f9U0Ku$+)1xlcp>AqZ(L1RT4Q79b8T9&f6i_$)XS231oOq4f`-&~iT$fks0zeEY z>6_>Y`q#?_v&9!VL%xr3T3N9DzZQV}qqG)Ow&eN=8e$TW;!F(p+Mi-I3J}{oiZ%p} zu~I90d4|X@u8+G18Bo2L=L|E5968>1zd&IVbO`cprvx>BDua`s?Ra$P(6lwraLb}Y z`K{l49>20IYudxUr|t|b%DPPA;&GQM<-jv>h1*bx zP!{_aDO#`b-M2(An~U}*@sjU)use*%4Kbrc2MI)J{B9)2vV~%gS~j7=43nLd36`vI zhmF~l+hKdtT1ns{W@@ND8K2)v+Ie0uJ^?Y!`t9wJ3ob%ku8Ai#wlJYxToOqnlU0R< zcy@~@#kd>L4qgIA6UVvIuC~xE&pEgRl+AwH;{XPNrj6Se%ada-HUV2RaBS(z|2iZL zN!HhG^FG=Sr%?RMi>Ftbukod1({G}?GVJhk)@cPfIqJ@TAWT%5=ueK_b#z)>Oaqb_ z`<)KLw>haV=lf?Zd**b3AfZCiSkLcz5r0qqsiiFu;va45bZPo__AU=p4*jHTCim zU$ekKLV(%GNKT<-o$V$=e4#@+==b8Zavo`ai-IV&SK0?-K^XqW{5B-}8~4%F!hkI7s+ck>$;C9uxBf%UtDr0xaIV!$O7)01)fj8?7H^3DODXM z<$yiU@v*daAEsB3j>r@+(oiHN9_e(8T^s#Cih-(bU3e^M-Mt*N_n3#xPUe#=Cz*PV42Wa8IaKMFq;Rry~#U1@!K==S}BCcH^ zqA+r!CB#Gus0$Q^nS0#~lNj?StdtLJ-m-mSlF2RkLft53sJlGiBwG9aN|d0Nt8Dh5 z2s(@-@nh)rT!oAbzjO^dpL;iE{Ic-PPZ&JeQb^&;*AluudYHJ(aFTyn#|7%Jle#5> z_U1u!x90ciAxR1!b!+DDXt^@;Q9e21La(<7Vk5Z+69C8FNc()bWhhxw# z-RJf!Gc)t%?jlq+X@IE2&qjNcn)Bx=Y8`}*>Vm?3QP3Z67H1sqd_1ySv`n<$umh+z ze>mUT%?OMsC)MxtUu;yc_O&D8O@pfg{H{8IL;B+BAt37;{-w8=a{asSA|3%C+(~JS z;^MczecnoGDLNgkfAl`0f!PDoBbQokcMYr>>S%}pl${fZjtnzbg-MJwC4`EOXRV=o zkg?I-xeB`xrl<_La<5pWj7ckvZ24&@s^*rH3<6m?_+A{p>VvkJ($~t=I^ZN>3=1N5 zqN|&+v(9|)?zt5Ng~MoBW`X- ze#W96X3E4aIRm1^-9}Etr4Ai#63e%H17@85e^l{47+Wa;D}=oy?d0Qb$%3#a&vvF! z8Q4qTYmwEp>#hsgoQLrZUtndoZV5D|0lvrKzWdtZk$&WQMI{O{9WUEUp#$&}=k37y ztj;G~kxY?8gJotF($=+<&}u>94}aaISXssi2iBm|(4+(=ZoL|hFwUqT7OF`-y^g)} z6+GpU67H)q{1;-aM+duMp$D@y)YparFT>y)^z-e`->RzY#37;#bK5TP=-Eh=N z*IMy))6_m~uu+aqScUBTC{hT5&XZIq4LU^(ln<&?d=VLw*~R*68NmFtBj}Gb0C`lqgZ?Ft)wNhFs(8mN4}lJ0>_W-+X;Dc$^vdq=%L&)y zm1BMlvW&D}`qf4~=YErna=fnK#V-(wnuaE+{}^VG#sq*IXsjl?ElMX*UQY4?WN>TA;lHnxTK}*qMgpPgVt+?!|lz8=z9AI#AqbDL>{z)!Iia*ZlU#- zlmexntb-i6U?Y#JRv^sxJ*b1T>ekdMw6D)WR>G5R6XayWXgAL&wON@uPY}E6-w!je zp)ei_T;|sL;bpdL4<0%kOzRrWu<2zEn5IXmh{r#5;@FnILoc@dkFG3U%ytQ6AEao! zNvmmor35B~@ocQIlescOmaHytL6jx07wCGAF#e_A+VdpepQX`7{ z5>j$n8sHtbXR!{=VW*6|%ei92l~%6*S$ATP-90w;b$YtvLjgc^K)PC(^HbqDWncT# zMuyR)Az|&++$)@;tO0h5<@rT@4QMGTq;+{SfW}pc5GF}#0jv;rOS)%LXStQBfsj_I z{VL{O|9J2Ez`Q9OKC;X{^$_wK0BW0NR@}*^s+g&zDNjZ`()2-Nr4cgZgY}WySVb~~ znOWt1N3Dkm92P$ur_I{G$BTE?PFi5x#t;0e;i;*7u7-o>qD3hHs|{GtJVygwWnaL8 ztILg;@_WhyLy#1WDG*;1+;yA9A450GGy`wj3T!D31A!AwAOu};}L zQ^cU9M%#!g#kw>1xbQ$2>c4S7-4ZG#U9`7(+Z?@3iqGKc7w1x`kxchQC;Km_J5F$r@Q^!aa;bI zzCnqBc_d{>ulR)H&t?AaBlRJ9Ya2HwU5*^o8HKR!y$-#=dmM8CXP8?>wF$>E`dyHe21U}j? zUNpwz>-zww+N>2YJGJPthGK0i+3R8{q_t^hja0;$kC0!hI6l=mt8?V|@Sn1-e+To? z6X`dghkpSQE~}RZvrzuu&MzFn%BmBFt(o!F4^Or@U$VuEx8CH~%jawX z~?1&v(xJ(lCR+4@bl|6phmw!mKscTMFuLPZ?OoKf1JC6vOw{|IMA z45DwMFBMj57#c(jJD=har;XJC!B5A=k4klnbcm!vUGa% z1cp2kGBXCRb$5?lvCkcC762HdI`$v1JMDY4{Um^>fXji=?2Hr*SNFv}Xq?T_k+nuS zPl=z?Rtdrn2rT+pEpU3Ek|g+L>Lj5U>Sg>PTqqNp6$e+7YVQ4E$L!i7ijO;NE4N-P z13fO*YbD?|oy@7-10~?=>`lhi18%>9qC(f|+V8z$k;>a8Y1p=Br`V;3qB<$bsc?$; zL#HLxOYlA11jfAVo-TJVqj}8Sbt*$!@8MKg;vA;yPoT(3)f}cljAT~14SPm1t1X9yMC-@v9R-le8i-CL+yt*SR@Z&#?}&(F`-*zP86nk zWMR+`n?h-(v=qc1L5pa;<2uIG^N)en1}v6*V6QHYnugtGn~m7R!G2)6dy zG0esChyE%Y4rgzkV;B?ikEpC1{{9}R5-EZCw5kwP8Im=a1r^??4}NFMTi zcyHe9OPr=CQwZJM>Pm5=yA6E9TzA|kw|Y{46GKY$Nikjxl@2h-!lGz1dwV8sTtl5nu-XxCj5CBJ9jSE`OE;-T3{+(TY+`d=pq!}_ zEM0+rRDhE;0L*x&Ao82k=RyV^5^0!7o*yoy($$nmvAN#sN5wqT;l?IAN~AMu)Smy# zXV4_X$5+}Kz{aeBA9cookC1+#!JQ?Vvhc|x_PA1#DhRoDu_-CbTumZNR5j!D7qAB9 z?8LUkl{%UI1Ef%8jX{Fl4^^BWSC3-QuFf{%z@wOQZ2mJs*Ih}(T{ML9SeM(kKDkN% zy*KqtE8kN&>y9hN`O3p*Q)H!VLhUjegxUG+?SI;Myv@y2qaf9lgcS+Gd)ErldL#v5 z35hQ8^I}d7CVFJLMt^rF7;s5X{GaY2Fg*Lp>f{nEC{=RlgiP_N*SnknSAI%F!&`2g zG;^ox#Uk`$xsf+lU7Bg4=@N6fETq7}E;fbpW< zSL5@c`lM~WWcs%?wm2iTABy` z@hG7I>~vK#AfLAI_KUNN2|@|Sy`%n}&Rp|_i)(`UxmJ}ME>k;Rndpr%^jLSkt{?7b zQ@U}%fIfd@n+Hu4uNbm>enLQpj(fiW+14ejVIN^s(+nE8^{F<2g>;B_XYrhum?wsC zk2ap)zSPE3WW_~RYW2gTNpXU~OpS7UQUM`_mQ$C8ONp5e*|W#=O226Rw+J}37`+S3 zq=1rR14vwcLUHK2WQM}drmOw3bDz#7q9y9!@C^u6GY)9xjJDZQ~xRWzOZXG&ci-$Goqut{%Bh7ktPAj*xN$Nm1B zk`nUBu}JIte>9y1TU2kf#RW;}5D-R??(PtzyAha??nXd5r5k~vQ&K>>8>Cwp89IlO z4(Yn*fA4d@!OVGQ-m~}GYyVbS{&d0ger!m+nDTswo42`)lI>kcc7jB1$By&)+nKp% z8u_x5&qDb|g50G)e*Pq+JjPy_|A9?My0A$7|(gQ zb^=Ud<^NI+J$|qc_Q9g3pHQpNmDKh5%5m|rVN#8)LTZM@Hz%~G-umftO!-^{x;n1cg7)aA5` z>+&ak%zIuKZBdKiMU}1udRmOWjn+*NqsyNZHp?itc&czX`MzrZ4-6N9jP!)zM?NMj z#l*2zmOabF`lf{p(GSN||4xI)Sn;a}LruSx{%y>J1)HX$*%EH}>{3tzCLTnrobL#V zLnU$5u6ZWO^S<(PxG(3*z(u)BsKm`qv%Y=v@Jx%HthhYWITY?gG-qsxnhmQljPP~t z`qe3DykTOUcZAohct0>)<0xF$RAP$%CxjQJE%}=k59r_L$`OK6p+h1Ap0hhe({zT3 zMx0E03LsKyV-@$sf7Fr$Zv-rDE`=#N$+Uax@tU#v_EQIz#OcV{)Y8(@a%(*~twn+~ z->~=Xb~z$>_g3hgF!@(5?2wQ?!{g-~qbNfa&KU}&eBee}?xAHLkT zsr=E5{Gkw9u-YQYH;f-HotugcoXe6STSd}GwPdJOsp9+z%to*7d)-fHbse4gbuaFL z;GBzC+J9fnH}J;)$}=EA;tnPe4-{9s`CAW_x4Wp469vnZ@%~ID-*qc$A3r2o(+7O^ za3l#&AB&i7aJako?YIr`d;^jpmK{CYCbk(0zo&W!cUH*}!!PhDd0cc5U*WT9i>>=*GBwtF{a5$8J?c)y6|5(R9 zeMoV*@>waj^hZ`=2H<{=v5|A?FS~Vzs%H}|fgR3B-2t!3zy)(5h%_iI)TJi`opCvE z#JkVyzsOHy9oIrz5#R%gUW#oGA8djtfLdP8*U|r{oLe2Mi_GHTr4L`$YVjex(Yp4Q za8>i2;`~J@=JC*8Zhb-l?N~SgUcc~n%j3E7Dl2yAa50~nGrHF0zjEx{S_HW2B8fo{ks6N z@SY2n5$m<P^Uw1XIlU&scXxyRCkb-o39$zZ-GyH*)1k#%+{j<$t)+xG z3JlBM=4`7J?FLMhh5;(YFS2d{bWMGGwhHpHZ1giOZ_@$%P*V+y1$UZS6JoHGy?NJW zHbOY%;ol;vNR0Yj?~A0*9|&>hZO|UV@*Y9nW!|UjNDytscjEFIb^SP?hu1Vl63k+2 zh*|Zn!HPV;xXvTPCW+;eVd8*F?~V)!>Q`ko*ysn`PpC?YxYyT{_|?e(;aWU!$>Fsr zM0cPfGGh68b%<|{oDbr@U%5TeL?Ww5%#4f6Ah;uVi@Sf+%q@>}Qz$R$;HcW&HO;lT zWbB_7_vv7{!xu=v$^)-ME$K0wb>ga!TWN`^X#e@V7l5Z(lX(+9_N}6nu9HuZz}l$< z9zy`&NIw_5${78Rtk6!5Pn?}bXDvlV3th7F>f9f_iJY67l%GN#KNimPeSRY5Sb8Zl`#`9{EgWj{5L63B9lxE zzGB2=wm1+fG1SCR1xs`>B$h>3cL7Q;{-ElZ)CBWl0SsmJnev5jsfE>BB7F|bdy`%K zxoYl&1~VY!ba^rTzANe%#sR8fvIQ7OFTe_izZ&vP)D}{MaqZ!raR@Ecef!=(Gqp!` zNFBO93CBq?eQu?28J$U=5Y6Gn+%8`qJW_R9UZuk{2hI(61m+Krmz*|6Uc5Sx!q6}T zYW;I19DtRNEWn+`4(n_AJMEstfQTl$INUlmuhUiB912ytiMyHL7^cw?p5Dj%JivC&p_)#B&JGYk7P2y+rs2-!g z1f=j-e&CS_sqf4D+8dKhfj%cZX8Os<`;EDSLfpun>bGtZb%}RCnptbE;9}fax>_fg zR-*UO1Zl7^-rhVD;C%pVc={b5m}LPxPAWhZ2htfe6&!qBAKd{3VXefFw?q^a|nifql zonjK^agHr`*sLo^UX%wJnl{=iZrVTW!MG%{eK$B1ojf3PnaxBaruYk8UL zd2<;wCvk~Z9k`D}>EF?Jg}%hZd>TBsyz;7yugMqp48lB9qrR@ju>~-&_2DU*mQ^Y! zrWcbtGlWqE-z+jpR_rd0+mow1M?AU2FW$TW){~E#M6Z4dVbaq__!?&BusdvQpyG_u z?E0>G;T6Af>U7Oox^^;#6gT>&e>T7Px%fx3<|8qxQn@l88=*~Z_2y8_t8REtHNS?| z%*iqA&|v)cX~W5o%(Xe)E0?7Ejo22dChd>;DO!KBvSdPtsX+w>JbTCHK-pSi85}Ma zXVb70`iRtM)iYR$rTK~!LW>H)+gtbNxBrN8v?caRc(dK6Xz5^D)d zHvC9sQX{9I3x~G!wR0DOkW=-(eY50lp4HB!cj)YJdHSkzy|>|nH)ix+cBEL^o^2^d z^m_-JO)*mph&iU5*A6mV*K@{V?L%E&JNa>Y5D^cv4UohSB)<4(;I!Xd{K= z^4RA#Fw$~I`+#-ed4%_UeO}KQ@k%E;-Smq|>Mn4}2&A36DpFNibL)@_l>5dL8~y$M zM1`f4ws#W71HDM`kc(PwR>R_3z{4^!x4LO~qa%w9pt*V~Kf&a)J*W;heUfvC#yoyB z3)nO@&#xU{h<4vnd0pF|5MJ#r59i@S>^pi&(g}4yy)K|DysOiWG0lrTs(-mY4=3bl zSbcnd9hN(YKMGM}1DU3#v1?NvVr)yjE|1eUz)YhxoT}l}o*i<~jFh&s2+){{*hWiJ z6-f)u359*)Rbevmt&89ZkCjK?{~%h4J!XoLt0sps1-Ip^NBZ!3||n-3{JGa4Q^8ehoiX1JZ(rv)6l5; zVEeWcd#lW^F)B*|CMH#yKTHIgbs$edP72x78kd8?<&(F#zlc`lE;b;(Si>`sX{#-Z z=fN-yd-!d?^{PxDq#kJEnYAyj-jqZru;fN`DzW_4 zY|YoNk-Opj)%?uoP>F|qPj2ji9H7s-Jm2j607P!uDt3zBgJTLJCnj($nQM3G*uN^`_A?)Y-_(o7w>}2)l+GaLh9It-nuU}{k@bj^7(rRp@_h2 zI>@U|Dr9Be7h_(XdX)KpFTj}{uB?-3dW6lR&!rFe-P8K@ceZKHZe;B%)nX-)BL>B! zSb0_zSkZz5;m}!nkbh>VLCjH!)!ETrr|X8fzvcUh}*08MS~C=dA-u+dlh@AD@y^>X0=!w$`0gfBL3 z+i>0an9%b3o@&%0MFoNXQf43f#B+`1M+v3L^sCf$by&(2Q#T+Cx#sLD>)U&3nY#uM zpd0F0KRqo{x@q;=@Kgtrpt$3mM7z*)AXB3>AFu4dJD0HAUN)_*?VL`F2XsamSFmV< z%a~%InWk>n$I6H-zd+{%u`wG@5rjp-w)(2Bi%|ZmUsu!|?Axvj|0eKie_|RZgxVA+VkWHk<7m61o)ciaYhPiY$ zs5LJYnK2cI@8fjBM~%|?c-)V%C+4-09K{ybda=)N<;H^EZo?<4nwi6(#0;F3)qRK~ z_L8(0yFjy(%k}X})FHfyt?Odt#4Ho7$#!$ex^cYk3HbQkej{rZtv@jCvy@X#C~&p& zCGk=GuG>Gm^4P?@g^T-VX))vCUEhpbJE^`O0^Wf)y#oqxDU4vBnEX{5Wx}r8ZD)iK z8t^l*x|oEa%GN>ovS!&X+47Qr%}V<;-mlEcQMx+@BXItzGdlbqVXrGthH%fcMr(Tu z;VBLk2qEkU%;uA9|8Bb2iueoRY|~1`!s;C)T&3fJ%ZkF6d_ImZ+wOrhM&=^5 zV!j-Y7@>IEMh+7{OE6-(((OCH*&kIg)gCo%(mkXx>hn=8En;%dcnl?G*~*1?C?JT3-2NVU4y_D?NaOWR((wtaly+4|heVSDUy z0I%c)VzK;<0&Xp@u00fEh_9i+3W>$~O(CWRm9pG%=pC2R5-lAUrKnmEzO0WlpMCoO zvaiZM_u&0Lcsuh~C5<=LQt`y(gEhhrH4*$7Fz8eg+crteBRZY^^RhghT@O|rJJvU2 zDr_@AAnX>m(pMkiiH#hVC>cq$l>DZ;h^J_ZiJQ#xQ$Xkpb1j1f`Tr$|ojY)cYV{Fs zdAnB?DlzK3ex_ygmZ)J?_O^PcgO_V>Q6W$hPHx_W_vVZCH#m$+y+oB-?&soxx=sfL zJQ5K*cSZfZ)3DHoPn8HTPqZH%C^@F)J9N*OP0c@ zv7NP*6zz4kP;IKI7>lYqE&(5nIfOx07f|t=4t_74Y_#BllcrB_Td(0`Zt5B~m9=a! zKRfh2_rl`yFZj$Jt zOhc~pwC>qG0*FEfhbM=|dt$bbnZFI+>Oha#NpzTf8=paB3r(__uhTZc7MTni?|!wY z(N)!=U{FW)Q6I$(#7=K}e?6gU@1Hwx-@m*QA`nzf=3_6>eVxqJn@igwQC>7;s+5~b zobiFIoyjtxo2afopa!RJWBip>CnW$P;`sN7U6>T7>n8J;T;m{xWf?pfij%#PK!R$D z(bgV8G-_P0QTBDgZEP~452Noh2TO??y-7NWH+i)h4H6f*_NOHS2T)-ngF1iJt~$Gw z9?ul}CR5;{H)yVxPZgN8yJDKC z*ImXGoIEEFIU^J2@;3?ndCy|0BN+>Ov|bl`t= zpf$db10c>&VXSgeUD!}rBj$t3-#$MZe^uO?CqQMtv(X!U9uE|9jgVl^6B}ap;NYNn z`ZmbiXk~72nnlX#z@tf$Qr*u}F{X#q2jqHsq4XYx0&P|Inlvea(%ZG$>3nrWv^)I^ zUlg2#Zo$47r)=R-f|ReAmp7yGCyaBJJk!AZ4~Fp0== z1LGM(NxkSa`O=(|m{m46J|F8Bo^$C}`CgYxjS|B6bjz7(L%*_(hOuHTHVyP{-~*!1 z@oA@#^G^@7l>Fd>jI_n#bL0e}SPrqwr(X<2V8S|YUn2X#y-EIeQ_9dfjNpan*GkNr zOj{}KZ=E_j)WFyn_r8EsBebVwZ@~V#ln-~IquwBDsW%|{M6VD_ODW*?L`}CLAj){) zhE+m25!<%0RPU)tqC@EH&UW1gsj`tBo8WZXlk#*s@WNNj>%<(Ijcpg*Q8fJ{p(4o# z>PH^Vt;SWy)|acD{Af#Xg{BApaZWx(31L>zW|Q+Ukgf+9&eP-4z??2Re17s@(qc5Gpc9A-u9b04$8F;UJcb z&xUE<@98dWp2d}W1SC0~aWL1FHqHWCVdMNN09>tF1& z__6PEI!)-k{?LKg)EiuMhh;lA#1(_{V`8({Bdpp?m~gDFBK79A6d}83KQm}YzbRq& z*f#caxKyPG9ZoEAKZ#RP)K4pk&0 z)&u!ahIsmTBC#gdEXy~LZGfz9N;V%aZC|PC+o{?)3&}+9s}Ews+OISz+X=tF$CRuH zIrtcW*L}{KoHdGf#vicR-65ZeW9wdm{u)ohuZ3&#GFb}a>&$uVrgnE4@TOrg>o$!| zv4x6z++2$J^5ME;=E1m1(0GAYJPjb|xR7nKDfo1Nn-!D3>>M;Xx_JrpUr%)zgP~sh z&&$YD(>AFGqW`WVzIe8g$zk=MxfM+BarMVqc`6p^c;yOmzjRusF@^_lqRGfqDz;achkdc8gPGe8i9>WZ<+)bZcN7?>lH!Ne@?bKKZ<{ zJKN?X7oRlVb8XuU`9lGi)T-L3tK7^wPF+nFNWe)(Hk-Pvt-`cW;-RAAhhU`ZK>NMjV7Gg9Cu+ zcdJ*dJo*|*z-X251#IH?ESmoOv^FW0hnNQn{ix^;Q?i?`1WPcm)OB)it*{6L>oSn* zOdbEVpczBKulsrXt@Fs=AW+;iv2GZ=WRQ2i+-DSP+v#PXHZd$}IRL#pr;%kQS!Itd z%x+Y(UQQ$p|LV@NFj)`!x6MEl()UC(fTzbelSO2iIK66P$SRcc5*F0^uGe=w+az~a zX5*W#?|HfxK0(AnSn+`F8;Cu0+{T$LL8Gf(G=JJ5J|v9OU-4|>n&DGd_YLE5a#x39 z#ryX!j*s7(fv29@u&BwdeE)n(j?vOAKQpr>8!A+l&yHdnvuQrKAmGX)gxG@SB#kv1 zH_7MHNu|i3-d$W&v`YemG^D_AfzFhROy})pqPSl(g=$I=dmX4-S5%ORQ0iR_q3J89 zt{F4O3M3T|^OP5kk#;KFS*y&6T3XepTer2NS@_6P7kghsfS`%scS71oIKe>t6l@>b0QAk2Qcr$*;i3KLFy*!6&tszdiN){ZBb?dEF_vUiA>ghujOCZaB_>fjP2NYG;=Lj{T0>gc z_<@WuY6h*K6UikqeR`pu4M@zpx}Uh~)B=q7yUF&HuiGaHYfz=I!O@)6_*-C+=0(-i z{-4g1yS!!#B#$9|*1tS`;os`|FZ?ZPA?9jL2rZI}xCTR%kbrZ2%O>D-`R$67xyF1! z1*Q)&XJ=TiHT6cxGa-dnW|MSAFD}ECGi7)iQ~J2*$glK2<@u4#2+@P+^!0wKX34#5 zGHPpVxbSS}p4hn)`f+?s-~D8tOtC?l`3&8g3XC6&Rg%r!?l+BYMRqhZ1&jpTy~qZ;M6aZ4+2fe18V+*bjQ zb8laH`{i{F`aYC(um0jX&j@z{yb*)GgZ&4zHkDlLFJYN{utf;F1qft9;2Iu3vmr@JIS;eEmeOdcP6aBflPZb(_mCjne{S`&#tx6kafgOAPIvy^JT zu>0#1fWOun_$+=c;gfgCpXK4}`dwFx;EMM5V9NeO(b>19>s0xU$vVPf&;wCuSGVWr z*&SAg^ojK|me^E(`uF40y(f;UX7W0pI<_DD2SjcIS}c%>LGuul|Fk`{^t5lMOYw#- zDu)%bvh9QW@04lmCI+IY>1^Xq^pNKCjou7SfiFeh^S_AdBjY@s!kMYCYm+CW|0608 z02|~|8ufGa)9Sc3?Dy;nJEl}IJZXgUk-LX)e2Ie7g6Cn1iI(6kSz$d#qrCNhImc=; zrWEOp`L{(i4lyA)on;+Rm=`qbOL8py&Toa8`L#F1pzP7j$fmNK&V3-02TYEbBVnDP z#_l~<^DL45kxgb7y>tZYh<^AQ>uK_FTA^vkZz z*u3>O#C%~;DrWpLQ<_ZI^{3XTi|M$C<|Ajct6lH-r9rfqgeTt5$QtHGxj3G=d`Ts| zrT1i1h5SImS^%CYL_2Se7B|9Cy(?hrYU#-14K5lH$`LK#x68w7u>55cC!C|Q6=wA& zCyGvq>yUg63zdp4Ip?;}IYaU0D0kxd>igK*@*_(3l~b>n-5ijCi)EKq_f$z9YD$x0 z&}vrArQZ@|r>OvU{+S@G9*uu<9c~B}2KiR__p(N*n-cV!ieQ8+KwTeA!#`*S{Q=7?ih*=^j%ZsV$@Y z4NY1Glkyu|f1h0orT(#>74f4h#U9GREGGU+r9tv)_Ya00I5l1O^?cs7Uu)MCkS|`p zK`6iOL(V+M5I-Fd* z=Nh<1Vol*5Hl}FQK|bCGHjhUE_GII~&gWB}@2`}TKUHlycV(XDdAz!E4KWVTcn#|k zsks>w)D9S2*w*X1B=5d~-`1bR?l0M zJWq@6IaX&Qz<7OPDpXYO(K?41J{aMu5+>6A4(&fv=`e9;Y1YGWAxrMRO`)x4I19@1 zOe@`NXeM<<3~t@7-L@yEv~jjP2mRxG21#-~E?OxnWp1$+PqD{p@}KvUr(2@h=fGPC z!Kw6sg!1bT%hXI1%K?ujF}>_}T`NS};4A>GsEfoTkEw{C+sB=b{QVP3F2TwelGOV- z5|Q0miqqG_#dl#L=$)zM3@1Rg!{K5lg)NG@gogXPe5?<|H1c*Y`BXKt-kMw<1SuQI zlP}j{tT>az*BCF{FHDfnnT!=4;K&>}xy9p&dA=xoF^2zOQ@<|yeMA(`&?n3Urupy( z(tGlc?MYvBHwT^L*|=?xs#|oe3n(9I4=WlYCb3|3%ohtg(sFa-f+7 ze3b2Tx4DAn_iY^q-y0cTAsD0SjUp{*FwvKNyjy3tN#91aqZhfj6z@!p(G=EC=e{H0 zB*&w|ZE-)iS@qj}JJEZ3L+(^FHTAfS+$6t+G;ynPL($RFl|SlaNn4%)!-$F=9zvTW7%TPNQjMEbWtE%?ZQ{@zVgI5%rx zWk~+;chKG2s^D@{nCSUHPubP+RHBRWqIos?=1ct+#mi)=k1LUZo;GL6IZ1-Z6KetO zW5#XCXKVf*UF$#DMln%4NHJw|t3gPgMw705BG_`Kt}To#z>U-5g>J+AQ+&O6hFnj z36V4is7YJ1e&=6Ylth6x3P2Jl@?pC?4!8{atud%3R5a)APTMsyWN+c&MR;j%(KVu- zaIZ=-CR$@QIVQ`Y0$T!HnPfXN zOmTBPh?BqC#BOMxd4ZbrENB3&RH<+6R=3ws{jBgP>1esg(oP(lCZqIOf}g439T(s8 zNv^cXFUDoEp-j#{b&mH@$gLGGz$EjNcJxHy0HOQrmoQP+2^X0RVzQqvUL|!KrE%;? z>y|(7heY<0^fq0UA5S7Zx8RAB_(6h8@$|}p7RjAb#vj{C{P3b_NbaBgNwvTN*0alM z`iGtFJe`2s3g;(|EA{8;GDG01N}v>jw8}{RXDZq%HFOB0Ode6=$h}f<)x(giUMik$ z%f=~gUm6HNo{hFQFsB>__BqN;*=l-{cK2(Qtp97)(QI9tD9qB)&VWsuh(TAD>Ij;# zg~z>bKe`j(stj^PC?;SsQ9LU&Du6798(}>t9Q-bS+UB=Y^O^rM_Fr9QRLFSoVd3Ln zb2absuN$|FEiVEtSCSe+DdIPMYe)3Z8M-BEZoU+5y*56x7H~bjjjqOFH>yy4x{3&1 zoS10EoV^!~n7^_^{gZ}N$sca1NfMJ{;tyd0Z{Bk31S@W=ghXDd#S~Kb34vyg03hoA zy)rY9569MN;PUM_fRxjVr)x4rogvAl=ZIc6ts3bugiXC1`PuxaA%8A ze)%|%UGLh4L00lL0O@kM+Qpj-+wHr^8QNy88$8vL02jggB%x7B+GrKxipwDd-U3K- z2vL+uv;cD=*fN3+Q;7nIJS6()Twwi$paFjK1TIuEF>CnC2RuNgnA>qy>lTxts03Zy znii$NzHoI96yvx04-1@vx1UZ>|FBJ1XVHG7e949+(P?x_bQHV>`oe_X*D7*lsi|fE z$4J4wweWr4B`ITJ2L=;8tKKo{bDqt2f^bwRV51Y9s+me}n^^$;#ix3Ohx-F)wZ=#I z;xZmeFFqG1V=^muWY+%{xZr0XxQf`yXmjm9;CoZ&eZ4a?+1*U)cCk}i=#fO{cc#Zk zwaFRTEq@!6mq$*P&pOl2c1hGomxfu%-vlHyDK3WfWvi82Nnd_ijb3gyV z0_BSNR5bH}Zh!=d8l{en#4d>i8zA=Y99V+2DtxsqKe8{;L>07Jo#XULrP2qi>oMlN86?@@NcWr_R_DbM ztGjb+0X@6UJO7k>3&+=;{R(@ZA3B53%X+B}i2eTd?Bt2L-a5kp8^KP+Kk{(N%zjqJ zIG;BfT4qa=*~f=z=zR?e$%;`IrQucB(+OAIw3EMY-s6POOo8pu(*oW@XD$?Z)O%C9 z>|tKRD|#nl|Mv$KEn;icqE(a4tqX8-EQ`6Docxw0SYaWnG$L_tjYf6!)>(w(P2RJc z;bOIeis5h(+k$UR%x<-=o*6dI9W*=FxIQWg8=r{$_6jrjo{QXQH2VjB@RKCz(5Fg* zT6=@HKx~J7XT8Q$PzTeH$Um3~n8X&sRas~YWgUi$P+<3ob8)SRL zMZmK+8X`r1HlA;64+?YWydj%k6dC!d!-J{+lsJ*YePKa{D7HOnVLllVrBhAoiGL(RH$|7=rF z5ke^JV=f=@f1i{#h|cQ#B5?j;R1LGyxoMunCql;69F!9{r1*?r>}Ef zG{oMLd7k!NH zuxp)m1=6%=|6Sk{fe)Ike&l{@E`MgR+DJd8q*By@klWvTfSh6R27}f#(KJ3O8d50E z0L5CzYUT~N7`l5Hw2tuGxH|LM#0WzOg|6HZma&bT+Vx@y?}P>wu+{1+tb)q9WlNZd z#BqS_H9PTzDBQw>Hem9>0b(g0J||x4>L`2ppHWIHRlSMPXaShq&^mFrsBDveZt;y| z8%Rm2gDIIVXxOt2@hK>c92b6@m@wB2!jl-kEq!*a>pRsudHQ6R_nfRPPgev5iHY=h z|9bVSj(RK`4#}z$QhOEuN>pAl4Bt%ZD_XhT)`lt7+^45U3kb=^yACa_!8v_)sHK{Q zvBNH_DwZ8BM-n`<*W?3PxcO!YoLo8`s(qL`R#4Ommm0lDcBdX!0`i{hRH=rl%^~+H zvBI{7k7qB(AN@%$vrl)k6rlPEob423kXVHcW4nUHONirpB)+2^v*$2uro8Cf&$ zg%~2{*`zM`S=uj79a!JXnf&Jx&cg|;)(lRq?2yZn-e8A1>mAo zMB)%$9ReVK!L@5<&fghAsy&lD_ys5=df7}dNnYvZlWsW0Mbl22#22W;A;=0bf|Y90{jxm2L`sm2;f@HdKpP_N$mn z_cglozG`5tL7ZEDuF;4I&`{dpF zk#7+DI0bC?1SA&g`HJ6s@h;Fk;;<75RtHhQG+@iZvKzi#a^!Cm1_Ve(YqA z3HE8{?tSZf*ot>Av}*Utj*TLmOV^1VuC#%A{7XVlXuQQ6fd;53NH}CGC$qk9!rv)# zq($b*U^dG6S50p78MIo^sM0nWE&9Nz5K89H8{&|Rm|3HMK@A}Jh{UKSdq8YVsX(E= zsY&3;knEResZRFO;$V0F)7~Sy=z#igmFzPT z4{e45FVbSsrV1OwyMM@d>{$Jv`oj`iZlOKX2^YK{1l?8~3#+V=bhu~1vphdxIs!5= ztF)lGqHpviwr2k=wV8rRst~a`P4|yT_7wH>`DsW??!!qpQSFy{oEeef4xN4n4==0F zWPU?nODCpe@X^Ub3CudWEqLelil9q&A(X$?w(A0SYx|7fFYfxLc8UVfQb-foMue7+ zHd-ojROXwMb92jM?cxqZ5-QKJ(WLDz$GFpD!_QI>_Xg%+`TQlQJHg4A^l#j7Lh%v1 zigAEe0p+7`KYws=uiXc-PY7xphiJ*M6N_n-M-$5paQcKU4VDD>KH-N)zL`pP{Pe}Q zlhRAn=w?@>D zdX5e#e-ZCUmj`?y7)an$HUk-I)h!_pLaFup0D8F@o7gyVd;SEz*5!jldS;A+sN~WL zA{;HnGyb`Kw~xqGXBKP?VM+}0blIU}z? zEu#ylyy|zVtAB^hee979)e~o~2ZeE$@IOkr`jZwU8N07ca_J#m*I&PsN0{31K>u^Rp1YL0QK zP2!n$&FoR)wzq6|coVuB;JhuL{UY?Y(5gj*snGad!zVh_geSV(G+ki+0M zaPD!NO`+n~EgXm9ncf^@JW&NVwOZ*gja2%oU79Hb{VZbH397n~0{tQgTU4ED7YNf5pIZt&@v{>)R}qnCoczTsQ>9njNzE zCaOec9&sgAyJIYB{O)He?tqhK>Rh!i@V0#w&}-b1PH~*vT>?4g!PcB8 zFz!5ZrD}r!80xaJdd1PiyEdf)4Z(VCWWD{5bqAP}K}v=4O|=SQh-U+j(qbtyMX6JTXn5Oxagb02A`r39Y*R zNi1NJR*Hy=yV`rC148Krx+Pkv9~nb_Wq7fYQ6Qt;#t7?OOT-!|R+ zXZQa#DEvc1pg2L>fBLP(u(ITB`m3a+c8G09rgA_FBx{bp3OAH1jpyZY8`}LnK~~lf z($$Dk0X}kAE(D4%rIVstk(B+<4u@^3P{FLOg`9ClM_e`B6o9otq&yhv3~-qW`@`|@O&8G@c+)=bVPVn*s3!1OHx6jx)9o?#ZYt6Q|B-vRMHr50S<&> z+7!Ehd<_mE!@`Y&bvd;~0pL`?vC{Rd3hQrjY>O~7^0_^3-Mu>%rNYM{e1PPzsk*$( z;~C>pr6{9=V5z{~O-K|ORV2$$SDlzaNW3#=R&9uI%`%Tfl$6fdfKyO;bv;T)q$p-_ zP%N1Dp9-j<1e~Dh(nLz$LLMo^{+w@THET>!sxh2vy!HqH^~otIrds-)#c)JSyYSTZ ziU;m+0vV?;RwG3+ULnxtoUZY)zM`UArE21C3uB~xolZ-k>ho|VDH&r)i7h~RSy*ff zJz;vMUdKxR?sMF1uogXf`+FnfQ}1Mb?P@_QG$AEsgCY7UIv|Iq)4tNyWAQLxxp)?t@@-QB*yaI^>uZqSOg#vmh8p+I{nkYJq52P&z%a%>Kt9BFbFF+C&?(TD6 zK6+k$`M8#w`$WUQ&{oRA%F1|={e0!0*Ph_4vGvB3OzqonG1R=-0mi2|gF=m`cbhSh z@nbL>$`gbk)S6s-ltJ8AD4!ULZ(%Fd$)6{cX!*%PG1f7UUA7SRA$71tvgUU_5IC%* zL3}GUrDz|=Cqqw!Dx=BQOAnL?T%Z{vVUgPLBy5-~u+~{*8sAw8+FgIYg_@G>(z%`R zV1i5I!I;-vz{E(HAU1_ZNAs2H8cWCjPZD@OAvdz%JPco6TCOL(#Na+#S&e7>iD-AamyO`xAeu{ z)m?h3a_)`-HMo7D#GU@b0e&$G+pi3Ec8pu`HUvf75G2;u*go)G~^lja~)g zs4PIMS!cmfm^*|Dv5#ik7@fHN(vtunCpC(rMD2PLS_!*_z_WLB#+!u_7X-1)nLi-* zzXB9ex2)s;8Ew7U$XCuSrknmoGc{Zf<%>ECHu*)S%p7;pitqp$aw3LLFQkB^pA8k{ zI~r36!%F25mhC(i8_wfVT&vY~0@hrPj)5jXQ1OilfhIY5D&T{DMq*J9BK*4!PKg4~ zwaK*3SMN{UF83`9n2Hu`@Z|^~te`1b=7GtONKfPT1bo$^Z0ylS_!eQT@e}>H=n0kU z4!JZr(MT{t2r+sXa8dO*boCI#_MWCE<8P3mVWAek2}>5js|FNPvz8S@$6iE7j=MwY zR%e*SHbNP5d{K~S$sA8QUg_t~f*(wy%zZR)Ob~BALlsIiYSnc@gyJg}21KP)_hpvvd}$;P7rf^&}(CUYFon z3k1jC8`9^6t&*$cE6(+&O9{bCGT<6N471j9|1qp>hm!>a5R7U&7A0<=0`Oi9;)VX< z@6cc_B}U|kh+WADz;*3`g zQ+~%?|xba)3Ypf2I=ro)Dj7+y3? zsPmoaoDzmi%BuEVHze*dV^(LZ4zo~^pApCvXkG%sG694W?hmbx_Es(yL6x0<0l~C# zm2vp@-If`ase}|pjCXJ|jk>L|)6|jX@0ESC_85M7Ujq{|5^s{cRvD$jQ@fZPjK~7e zlnVp#=#>O7#2z$69hY!C%v{M_H}F{m%2EqLcSknPuK#%Khe9_U#41Q4k>&ICm8Is) z!XW|QPI8McD1VgjV~K(H{-9QTbqWJ$=jTuO70Zd#DMk16`eS8h^mpmeyt^n$Be%O? zzz$kq8c&+tS@nq!pjC`sZ?>eAJf>vn{Z=ZRMo$8^G%PuWX32nW*9ftxtdUzmnsZ<9 z`({Qq_FPqBD_-k!Oe*vqx;;{{f!Fs<8G`%Z?h@Q3 zxI=J<;O_2jgS*=Vw|oA3>sIl|!_3qM~_sa7lqzuMgu-IAkyZg_7(6Ll8w$?WD z8D#l4QinN;DKzfRpJW0><4r%C;QvPUpqNGl7< zOMX`^y%x)*h;hcs5(|jjvxUzti1N)5b{I0+#YwQ1rGz;K>u4bUAKQ zm$VWNoJg%m8iPe%cHqv^&aMH2K8sd1N-v4Lqp5hI7F$4d$#8AmC!4xLwJ-IinPkjM z%b{+UHt^$gEI~_AqWQFBpUgh?C7N~$XgH+nQ%1f z+fAkg$pY}f0SWcFZcsqZXQh4Uc(E){xC0%dqIN+F?Q5m?q>6Yh zVaL&~0|1kGC=RPxpE+0Nw%$W`mYwozv(E+oqBQOD`Z{UxIF}YBjxmW<3XU`u@fsXI z?6=98ASv0*k2UOD=X_OwaUER}*P(iJ;PL6ses$#mv87I;%-@6lM;i6;fN6G)H(0dd z{pJGWP(=HQTPli%uCDj}**j#<@3{sJRIM2A%&Q4KZEEVy@OIrf_haO~cM9dSJMdmN zwkr^i^5!kx!o&!KlK~bNCKFge>2LmB#PCE$)DPa7;VR%7ug5H#G#nFq?k_xaa2v-+ ztEPZj9$e|p|J1(7B1cS$_OVS=E$t?smI9s!d;Y=ipr!8$YeGB=kgyHTFTVhhNIt%H zyF~dqckj%|CjZa~TYgYakvl0Rgr8qp^y=0~64UNr%~r`Vzz0URm~aj;^x0`5EO6Aw6c27S?lLPs2x*(koZH zSX=W9GGiP3z<|BE8t9OX^n#8LFLn$OgeD8I-*CSuWK%Hh$B{gfkmQquky)8_c#_M? z=Chl91Z-4Z8|3ne;Fr&e42xGVMZZS!r+r6-Fsmo@jU=a@>=V4U_c2@@ zop~iJ;MB+*|N0!ETokm^eRcy!2bY18Anpf7^ru88e-Dr>$}4q=Tq(D?ss2liJ{aes z-qR5pOTXNP!bkt6qP0)S0HX!+%Yv&aa%4C(_o&7{J!@I}Q>0NKR-PE*NfhX_5<1+B z9C;m#kROqyH+4CX6p+Zq7a#-#8i=&(@{v@uS;CY6l9CVGVprA5P=(xws!q(yn^w+0 zocCKA6B}Mk`*5AR8pfBh1e{vE7q=*{2e@Pw?gLdF8=E|fg$!Lca4_is783r~4`}37 zYfA(`fX&ZEz?&Di6{}@!`yxN4dmWUzLW>p!Wn-O$KqL6sHf&uYVBJ?prN7=9N> zYDYk1{iS&>!GE@5VOM(C=uJ-ZeO-b-WLx-!V&MAAziGA6bniK1kh2sCg2A6dwnPUb zf$iRUaf@T?U1I{q;IgdJEW3DKjM^~cwSSIs6@M`fOLtD4ASA2{AiPe~fD zZXB;}{Z5EFRJ%JSMT6S%^;yeE%{{Ey0s5);HTGnZNpc-3J@|5Wv6CU<8z32^LMfUc zOQ~B`bq4}9vl9s|Wd^9p0B&+QS*nkjf*@_fWwYc+>H-n`B1hY#4qHs|VeTcw-dOJF zvLHwH1D*d+BfJD)07za~bpc0YYYdV*QSqdO^_^tz641&O6<%ldwU>HvRW-x+ry= zpB=h-834Tq83G9^DRW`N3vAvyPra$)`T-B~RW(}YuBOU)tGKUwV|=|$mD^oN2@by` z(OLr0t%Q~aY7UBFk%pit3l@%*M(Ih?7z1W;#En*1?!kN9hj6a%6vFutZ|S(f z;OhA=3V3q@krdMAjRE9*2f+pzDLd7~;#r15+TPq$1Flu*fSq3d=2+g}Bc5OO(6u2n zSfGaep-VC+*C3lA3=v)coibn@=p!rnf1_>IOfR33pd5^)4rRcaD3cfukE}R6e|vlh z^k|O~D8=Zr=cgisG>reWmG5{JU;mY?n{uB?hn+c&Dig*wkL`tL0wRpiZmH+UnJ%V_ z5Dm4DtN$s_IEt|Wr8OOMXT~s5-d_ALhbiUK)^*gyVm0H&1N+8KZzs9Vq|_|cs8wO_ ztV%0hHlMShh}w2X>|2&Yiu4*%&-a{|j%fY!Z#?2QhM?yppg9rLpnpgupcT5i{?+-Q zot)0$cb0 zkY^Z#Y7B)&n`{>0T2=lY6M01T#+tz;9ZmEztIHVh5p8YSh5M|L{=XIgyHv-iv9&40 z%_+kyB}qDo%1mL`BpJYI7=yyhhy}%sAe;d<4*6Rqzj2FIm<#jrI8?N#lTtH1>KO(L znjKOTN4a8Wa$4Q9eas>#KGB9he;6jK61*Wyu3V=G`{=~k;C>P1>b75Spzy+<1-t5d zL6qft8#zOSt$x#*GhN9%9>4qg!lYTHOYEyF_$h^Pw1)+G-OIYB_YPPw`b~)0w#sJF zMzW10E(Osc9ZN=jJq_9UvEyCCFnUF19bFn%2(GDb=V68D;tL4gw4{tSW$f>sf0}*x(D2J zPRoY#3Km^*$DF7fmJpE8{iRaJzwsqC#^R8SIIzbhB`~3YPTZ*>NY0p^_*xtT>jpB>G6q=|Q zQ?9|&%FwGVZ<8SY{DpN`Pai5`YuaUv|IwaMUjCQ%Vn6%%hk1QcvH2|lx+#|;y^A$h z#NPovPJeOK={{y|X^U;CV6(48H9H2l;SrZQxn_}4nAMQS_mSSfrLTMmbhwOC%F8|=bE~3<)y)-XLfT8xLK^KHVQYE z$>a^yKul}zWGv-D#^pMlf$08aiaI}!4+Kh@?$+B&_dKG3o9JTwmH(bpOl8$wvx{|1 zYdi&_MSi&<2*YQ$n>!EtRB42^Amy^ z#1~ok`#OwnPqsZUylwl9V@qC*(70C@?C)s}V@qxkq+K9WGyp5LFIq_Jo;Tj%L~ybxTA@-Xi%u0!>IgGB zh=a!NR?N}ID=?fZb2wx&+jFBe!nN9Uog;8UyGabrR6N<2$)zL*s}hzZ?!r|B_ml-I*;d%?l^oc&|1z)*nb`NYxcnQAl``TLIOx>#JtYbFnpCb~Nzy9gp+p?i|EUqXtA)g}uFfanh!p?Nv0lHR z5^am;&ydczRh-ac&oI|v40`vrb_Z&EOZM{FQA~U8_5ilm9SimMFM5{OwHI!?GM6Em zY_E+Fb*0zTbe=1_UuR1x4Vxp5$utg8Gn&GLavuRAQDwPOu4z`ffz%9zfD3j9jf31Q zH-Ez=Dl?Y!mp{YqbAdfb+PU5Om6d|i(r|B{;m>ZM6k00gd_tJaga==8`^C|_-GFNsGqRRvQp9*%C1PW?51B7=f%z@KJLjM|6Y@ zSK*rOSD`tXk}H?`bh)<2W8_~1* z)wuU41IfOaClQ^>(~3!s7Hr;qtmfgNqen4$LtRb}-zS3Ek*BD8oO zh?9#+h|8rh=Y**_J)F=X?04i@o&;2lcKq4fH2rnt)v>j#$ng?S7>ijx?;-X_Ru#1` zn?&~9KZXh`5^{&)n!i#qUz#_$u7@tlkOt=do%xZb)%WrwP^q`!Xvigxxp4>POgHKb z3yBX4;lt!3fM9F(@IK8ukmk@}Jg<1wbi35;JxEUN`up~9bXAFHwXn+%VrHKEgs$~2#;Sanprp@( z_639wO5aoxD6RNI8UoshgTG<66zzG9P0C7*y}khI`Hr5Y)F3y$SCQ>&e4#T-T6i$>eh}N5`1>d#?R? zldFW}pJq&EDE42U8i7_VMu57RxRl|yM04H36`afXOpPPQt1=c(A*H#VRy3hiRx(yl z(8;;8V}1f)<>f3;mbtoZq~_WPF)?T)K7D64*<^;VR#M!!g4sQ45DOD-81u^-gaddW z%H{`NqIFsFF;~e01FccY{1{UJD3k z?>%TY*`Ky@p)|jFh78rH&cB$L6or7aaazvZ2l<0FTAr_h9SR47CJfaHQmH z4Y)#g|B;PZKLv;Yab5DUi($`F^mGSyg>@sq+1`@R*8Z;R#dT6s6Gk|ZC(D+26myIF zhaR!R*~*sayNkBk{$yX*>-CpQdelga3=vo1-zS4qUDzt$4sQ>VI_8Aqc6Wg2SY-am z-nGVupGnfnI7KszL$k=>3~SvHI3m3S6F)sD&GjC7wfBbp)CFllc}DyloMG!ufHEQG z{p=zpDLrLMo~R}%?^oX0x!n0AM-%vyUn^*H^U0!xw5B><^x>ZnbO)H~RJa`{AV^ocINWL= z#ORFtsW#+Y_mSho#GvS7B+{i7z!`gsn9Q%nPd^GXd6#lv#Fs8G1{XB|1{4>Mm^e^{ zep-rRu4adwFZgHbz>VPPqH{c_l}(efh5;!-2GrW&^2rPsUhk|^HF)|ER*jMkvizxU z;NQNvbr~y=4H+HxId_cL3Ddm)$o#x~@#U?}*%y;^j7>8$HK=CDymH|H^*Np!aL5w1 zuoN9RAa|e&2b?X@I2-(M_1o)Wp&OPM)m7+8qxd3H!Kpy#l3k|rmNb(5M*>T+N=plP zjs_&@8qF)Nfc?ZMy2|D0Ad|A*6}rQ(1-71GotNh?!LeGJvA}PKqBn1>vI|Wg& zf^_-H(%H;2bqcgmCvH2Q0`jWBliS;^?^TsvDBUU4SA!Y@mjL9`|7GdqBBe0V&2Ynd zRoL5T}onppAyr}|F9E2{*=Bn@gPm{?wWzz z+>L!Df?C(IV0rx$NJoIb`|R$?>p_zmcSI3dwMp%RT&&Fy(vCnnJ~&ie{OS9C#mZ8& zbQNxNVtOHIxFPc`PrVD6&%Duf<-Aj$nwg z3y2>b^U){T7s>0NFUrbW&^F*ctnqom>Gg5VomY__#{rs2V0npox6vK~l!c7aF&!n_ z`6QJqz&|}+kwULo`K}ce@+kby{_T~w^D#Z1Tp{~4YjMykY}_*)0W8F+6Q*;DW*FUL zm-5#^O0=lHP{T1Se$N%DZUOM?(=qX4;{L!0B$$44_mU$6Ych?MQ$_E>cv7hR_% zwb_av8$cOED`A=34KoK87XqjwHC-%|S#zCWP`)Eo0F*46ZG~R`T3NE&e${@v&2ti0 zJenn@1Gk1fZ{1?TS!g1Ff4urE-qmnI4vRc6XTi$xrsM$eSpIR%+J*Cc{6$H3bK35$ z9Xg*VY^er9pKC7|W5gAgE{d18qs&#t_;dR^baC+ldZU+JZsQfMM-;>D+}J{6lJO(j zdYXliV6bXu9`Yl4u$LS$82pXYOXS0!_4BtN9YBSB_ zN3mepun_ZT;KyAfo+aS8hkJ_V)tQh)g|KVl@DZIYeQej|Rv<*~?Xo9q^Ui;z2?y6l zci1vOau<)77=T~`WFv{IEpBeM;XWVk%E9Bk6YY*GGC-~F5sKrsQ1#A2vh`1jvDnmLnV+=MTeFD@_x|?5P2im&eaNvMgue`lfJ1~3YNn|TV>oW|b2GCKVuG)Wd zq@al^BETM%9C!IJ&K_ToftpF4Co-#0REgPxWo|CV(0#FLcB2De- z&18Ge^>h-if9()B1_gv_?o^F#vA+z!9C&Wba*Czv_CPVGsngJ2s7d^gS#py)%)P;Fp^;_H3p3B-gun>v;j?+qkEyYQN$9 z*-koAeRa%;zPY%cAT{T~PmU7l{MS{IJqJG~G#+_Y+egJ@nKN@dldXuz!4Dch5r%+2 zTGpVIB!VZgLl$_Vv4e45+|z9Nkw^CH(2dSE4S!20DXe&sQ7fmG`VRMagBZex-a|$2 z2nEC4#g4%H^Ty9?g(UK`B=VTi^wU~caFu5hL{%BxsVNyG>M>ZqnzQ7SBpfRiXIMgm z1DfRo>KEKN?!p*sfJ(Dn?SL)x9bHrjXKzcVT2dI45Ym!?M0)7b>h?PA8PAR~6)x@; z5By^;`Xrw_p<7{m*h{rlvc%K3%GRDWSI+z6&ZkcoUUv(tVns-VeJ_stZWSXK5KeQ3 z68hgJaQ5XOP)VGBE)7k%Mcwc+S8Z#DPfXSG%C4zO6!**3@rJEXS9J#4Vqz@d`3k&m z=q7&Y^+m7CZ3R+wt9+90Y&Jv^DRq^|<)f*>x%B>{ z*K8r6Mu6j(i#O-;^ef0KZ3r(AT$GOc47)C7q9?<1l`6{OXvHG?jemph8|t){Q8UvO zi-gpr1x7Ch!tX!xkvT&wB=RKTsPpBG^6}54sp=IR?pXj`|9v*%FRcoRBEX=sGQnN} zas65fRp73)*I|!TmLa4qLP`wZ+#^UnIByf{HQ(|(+4;3LvGN51^IpF4+w-GgtN0B2 zP^|!5VNJPVhz?CbY_LA+2yBZQmV0xovqT97#F-`{-j!-%q3f0qU1fVw>%JZ^`uv9& z$6jn~dL47ts3NL-@bwc242aF;&airFBAryhXEdV?^seAANHKyWM*dN;IOU}e!b`7K zCot^md`*sr)@S>?{=5{x)-!~zf2TsI>>xSNqr&Y?0sU0OohgocOhwN2rnLLFn88uD8F+LTiHT{{`nc*?_8IY1Q#Kc=n`aX*Ka)7t z34s&J;q4XM#`??}oe44fF+#oOZ+k}&I8&f9@T^JyN897t;{C(qi=z)z_ARSkHn|w? zeR~BwY_tdt+Lgt7altnz<=u-W!dw$sJ%L@2ft2N*6E~l@a;zEda35UK2T~w1g{iHy znb=-!#){KaqXT$lvm`MTv)dQ)^q+?UB`vj?NlwwwVQTXAp*B(=R3(ex-g<*vp=XSK zYTvg%lPT5^Rh_E4(N!wxZw96ZPl7MHzErqkt+T_^hS^*}8k~obJNS#u9kN;DX62wH zxCS$g=pIQxa<-Zy@cnJh|Blf@9DsI4a4dCGWOv4&-S$G)yr? zr;h&FW#$cL5KdM!Q6a4i0xT!3gM?q++ETqF#f{*qHRGw_`vuL;aaZ4`R;NZ@;(sNX z(liB2x*I%B!58-5f1BNNq~|nez=FBult%{c%DznMQ~?>VgV2$8KYtQX_68{}PFub}iFN(m+M=HY7VyZ=mU|1?+;l8BS*Mp8Cn(=$$4vwkXoJM^{*D{{i zw9-ZN-ml*dZvu+}T@*d|a~9XmMu9Lse0DD_JTQ;7$h)blO!J1?}4LRrkO<2jVc=fzFMhi+5S1_s%(};kO2cidp!vs{46I7xlF|8qh#0x73 z&>0O!tqOZ9r zD08;yaKo;6!di};2xLL8>I}c3fBQ6jHo;#B{uyY{bm6`I3$|@X&PNgmSPtA8tE|mZ zmtG$7Yo3c zEW-dn8bCTa1ps~uAb8D^ok|+9wf5%Bb?-hY8>HZX2$?DV2)GWzM(!RUV=|ko*y{eN z{c=6-`)0jgm*MDh8CA580ar`0 z=>A(QJd2VjBlF`}G)6s;-sB#HZh+?B} z_+vC`rO{#M{+Gwv=RBu1Ytb;kU;iPcJ9Uch=c#ybT8)+cDqx(wZceh;RHh1%Fw2uRjPR4}|J)wq$8~3gpKHCg&G**>EW&SuljenSMX0(3ov;P|3>`{1=uF5eR- z@LV3vLSct4LRb<^drR=)U17(^Qe!gTp(X{u)B^z~%qK*<3DTg{wei#Ni9@*|8?%kS zu%dy4n&V(gZ=~7ODu{8){%YpW0xVEmX7jH{_8hfnp5w!8N-TF7&wA%#{AGKCv^aP) z4@`d;H1bI#{}A5j+NtGZeI6vbE-la@O3QBo;n;HM%Whk|K8w^ZfquAO3Pru`o_7Nnf8Dcc zo0}*0Mx6zpCaG{E6+17j@9(qCb|wN;@BS%?ce`%5N8tj@Q=!XjFN_L~w~H#TEO>(S z=OHv7AuypIdY^J1o8kruf*0=^k?Z*?CGz*{XHb^+BW-XyY74_qZQ$+R?KCmJzl70g zI*3yqb2g(5@XRL9C+RC^0;_;}>)L#PF)6#rtTEyN^ zEtVHTfSa~%5o<z$nxO;to0 zksGB@xCsTjtIkGf*S9-90Vh{Tmnd247m6 zVXSE6$CQ0mq_H8fOWCN(Bh4)7DK2u$g+W@ii+9v~S@OgxN(W7X`0#{j@;p6M+EWlv zg#>D`{gBaw$=Q&#Z|BHRHldqz?6?eK2EqfpEuI105D}X76kUhEJ>)(q%%ND;W)hSi+sZ6r|ByNvb#GfoOIqs}ryR>-A zFow=r%|#Qd6U9uAv;BumGi!((?34ZLB^V#Ypd$SLS^#wa2~&6ok5Je@Kz?`4us3tF z;1KYgR;m`ZJHL3}Cy{-_m3H3gjS_elp1wb?Oj|17tZHO$-%~}&I)_^!42(p&hRP5% z%u9%UUYd=7^_R{XS*Ar<6CRSWH!~L!*yh{w_LQp!OBk0w)9mW6{Zn_p8*~~hX+4M z9nC_bn{P5*-A{x%q|F>#kk@xYJ;`A%-9?m*VL5DRKPkLx*Nr?_07QqmGyrn)z*6rC zzpCweUHw@-aGbMO+Y|0N*G|uwp*)4x9qKc-9t^QnnAif7hQyg7cGVO<%yD z(A|tapK;5cQYgI?6AMjI3lrFD$Yoe=BZ!mmuFKMqPL}>ui3XXKUTHn}G`k0`UjU>< zTc~Y-1oN+zrHj50B@6D`RXV0$GCF_&b9cv_iIsY=BR1zn?ge6}_E9D3HIN8c-B)u) zuE%J3fWeDgykYmu#1=~tE50L!N?dZQ&No&KMAbbJ@n(_rY;5M z(|>U(Rt%8uGRYJetDdd_iyc=w=bgUU?5Te!uJCdiXTN`X(vGs*1BQ z_`A}{)s<{5wnJ3b-RWV?-v_YHwv{^lh1R}Oiro5v+ig_{Sr#dBDU?ncxvQII1M{w zD9L1vOCaLQbJvZ%cCPh;jnqzg4-H@{>v=Hp6G$&L5T3eBcCfX!?&tP#EdQ`(HP`HT zfZAxgu}}Qm>pN8Ovr%e0h5hSP+wRq}FE0rDX$(ovKgKsOs_zB3-bwZ1!DEPLO)qN~VRJus5I?;4IfNJTGr=pb0_4Rr0}YX^ zlA?g6C1enTjz%_$?K*x+OBD-lx#L}TgLOj#ANTEb$xjoI2L25$>?sn%2Q45|YIPSP z8FZ3jW$Q}sJ~ZtH%km0B5Xs2DfBmNqtQF(T1&IS|80_0*35d*!A*T&Bq1 zy-4~HzMMj9$G=HRPrkBJ7hoCSsbKZHRp6n9U=E9A9o%;)^2jn;;v@3Oe;!zWkjWE^ z_~p)r*`7%%lIJWu;(}kt^m!)D(o0rm_%@)z(S(qXSq-$^MC9($5MC>jIG2u61BV;s z`C?_YN*CC5=WTJr3m_H63AE^=n!_!6&)-#XX47u-$My&_nk#C11lj_LkS+ufu$>D( zLapz>JuGrogZ*_n;XS#X@pg9$ytY0k&Yb6hKT07-xk|fmFPYs&u4iaKwhOyP(rn_p zLsv|Ht*^7}wBh~~()NTQMOhxI>V^(*$gF9Mdi$i6?Bzt@^U?sZ?&^?0%=l6lD}N8xXmMC;TYR$kz5w@kuQB$ zIXhYKAA|39%!`4p+bww8uF2J^;;#;YkwO7JFq<`r{wgq9lfQAnh8(gJZcI2hXJI40 zqWw*7w!Fm=8tJON2{RakPGKO{F7Sr8nU|xMrcujNX$8zxZd;ctLKk6T+*sP#0OXtf zS+f@v@~q+17us`#Vh(HMGCy?6T3$?1sS&MTNf@TE^Dr#(MurLCWc_yH)=%oK08+`R z^<~)~bscM>?}i{@AnPD#0kv2lu{2M~5>70D36vBWm(iwDG2@{aX;|kY4UVP!yiYh_ z2ZH`Xl9*G81sLKoddfnsb@z=&ypj;v%`dln5EYY*)x3D zfVx2|8i8xTCqO=;0`@t3dm?LGZ2ZysiY$^hvk?7J09eKR?%zsrYmcz#&8`Y34b*qE z6mIWWOa$z3NfteAgR$FcR52gh-`7hR8JG$IayuUY4}a1-3(6*E>*}tgV2TzP7s{5x&o9!@_MjpBn zO|5BDhryp(t&-#40^$weuj%n$Vsq)hOl+UB!@k>xBEOokK{|16jK~Uf7LSH!1Sase<&`F5U{q|fk(om1j(dMl+DwIoUm)^?JrzB zW7<4VDPrDoN;m47-M?y@`<@C>D-dl&uCg#9&jM;b{_*9OMYE|eJN|f&R*}5<6iAcl zGRpE;Ds$|FY*qNo0lGQz0<_tpI! zumdj$zkH#}e%a2SJ2!jn6WF}7dt38#>pqH30%k$Yw)UYt@0mOANh@{QBkAbYTmcD@ z^%cC&zxe+(&2~OHzWus*x*vS#CccNwGGaS*1!B$AB;0(gJLn`pbSq~c-LrPMQA-)n zbG5WxxiETJLgVpzf7o!~cHIyH(Y-Dc3mNBd6YzisS-S0?vyeOz!>Aa2RIGac+7fOo zKpR*DVkZQ%xcXxZc7s?HVQiN<1I}YdxhiAL{8bPcTFID^ek&5YV!&)81bd5RDJF)@ zt4WXdibP&KCGzN`0gw*AU$gdvF1$KgY!Zw`_EfvJ-q`ME*kTo&`08=ynJVBRqOY%W zX~1_>LA2z56PSz_LrgOI-4Cj7a7RtQYbfUM>M;UYTxkRSm6pdini-^pc=eI^l3jBxD2fpKa0*mi&IxU-?2Ss`!*)cwCE>h}U8d4)sJ zps-LW+Tj_z*$f*|cWnmB|F}}?o_bsDlW&Zt0~|A3INgcK=GspP7ca*fBGD_+X5%lH zO|dh=(KrG8qX_Vy19U|PFVNY&($1*P;|A>Z{T9;JUC?HoCb6&B<;j>fnp&{-64)7I zXTG$m;*6B;qM1t+zF z$7%q;KWV3Cr5qE5PFfPoV+;yM_dm$;#u=@-6v) zqna{clW3=TvxkXsfGHxp#&bLK$@2)O+{?cQnMgZtV*oegJ|nFV1=9i zH2g>x#1i@2Z;Ny=_G7^MglP5_KQp3*Pl1>zsLx(5jRI(TmCB+dvGce^@Ix>=Z$gvR zQ>7KW#rt_w!pSB}|K2LYP1ac@(6PD z9C_+|h+$dd953=gGp!CcSe)Lv{U-SMAppFbk|YnpL4Nwus~aLhO;*eUJC0wk;cc*d z-Uhto@UFz0Sq{!#sY<1QN!#L8C830f|FE{j!+BMg3)x8f1wtuz^W5-zrs~_@2Dtydu317YqtQ+FBS{z zMKYZXP*YFG+NbCWrnMrgj99l7%<*i=fTDXcFhoDfWleXzSGT}y_x_j4%iC$Ydo0DW z_r{&OyV=6B>sAN@(bVu2mF+og|I7)dm7|k; zBbBKMK!vLaLIlCc_fSy$>hnflgz?m$TwYtw^lT|=JsBC{+kg^-)Ymv>IcD2u*Jjy% zW`_#2l=0G+wLtftbT({*HLr(iy^2+;*Q5~Xh%35s6LQt)jPMC82a)8-qp#)bWquUO zZ{qf@d}FQz_o^WP#?j9*HaS@ounrCwSAH>~Ro39V{6B?Yilc?#d1sv>$l11hwE6NH z3BqT;m_rv~^C_-Ma*+~rpbX|tI#{(>XRpjbCaamEMP>FZlv9@qJ)6cH341rAFsV~g zQgXEEIFB(Etaln&4;b1;UBIy7@K2MDfAkn5| zRBBJ3svw9IO_Ry0ZqszJSYNLrD-r_9fPsZyXi|-qnfx{+N(g)F5WI=2R7k_fkpZ5$ zd>jn}EGR(~61>qHn(1daI|C*lfg+oD?$Q|?-)0+MFLZw2*2{4|1{a>+Pfh6`LGsb59xr8B*u42h4=4cR;MDy4I7XXEi1 zg3kDZ_8=W=yVMi+q=cnT1pA4--K(9@luR+E%h_b0aH7Q9B-jiyYSZ?MdHb`R+R*U4SUK?( zadY2mVTPAT+KQ`NerM!x=R~yP-&s0yl8z7TLZeNT{ShslW}HxFGQ-|q!w^U%;q#ha z(7f8WPIa(#f+9bQ=x@VX)QE!cXG_B(VFdfU`H89H?xm>dVMrd2LrwXm?lGDPpfOx(ZzERCUjE=HHz7aUR6R2Cu$OCs zTum6G(i}Yno2G%cnP?d=FkhGPIL9wds8Xr$y8scCq*N(S3Uz|SttP`_ezS??(i4Xp z{nf?)PZh!25-A_t3Tu{?>v{Zif1szoUx}v5caPwB=L^UvrG9cne_oXe?5eYp8>O23 zmR3euF^{@eD%-3vQ0C^AI1~LKxa&R<#3sv?K*)dv#keW?@IAmC(tlkuIX1ScWU7qd zS8p@a3OR#8%rd*$y~qf1=Bm1D-Po;syVa@F&_Xac=TSuKWd}RA$ju#(O-@`NmsR}% z<5MeS{W*g_&CdR+K?@3r<4M}F;+@pT;~m#X{vHwmge!xvER_0TQhW!iqZL5`r;7n_Zos`Cpel800b_T3%QbiB zb+-ELu;!nNpLR|TMcI!D6t2(~ep^Y7y;}`wdf=Sijn} zwMg7?0DB9+4lhb_jXZBzhT-u}du6{Mf$R{r?P>;b)gh?g_zPT0p~&I|3#)(#&~eG) zD3n~TmdMW!*W@09N)p3*nl7(md5Xy{M{C! z4mvI=QBOApuSY(~(B7V)TH1hs3I8ePbZ6Q2Ep(-?Kzj7mS=~t;tIBA(|3#4t+3L~n^mYw1 z#MRhc^p5^b0Q5vbclFs6@#f4o-0`2#VDl3qyX)h%yV%PI;U5_Qwx@?)Q!){?JUH!Ln;isFXIT9b=EwW7rHs)QBH7hGrx8p!90T zju4MkOX)PRxk9=h>9IfcN)n=klyaRw-DmTDt z=7bjj4&8bKS~F-HnSy3GKe0dzHxFO`GFS3+70VE9E$l3tvW!6r?@jZ!M2|0hvO~{9 z148*&r78jQNTGIh-310I#vs?;P5MdbHV2m!UgD^U22(~+9pI+Moe*I8cN1dE7yS4; ztne4#IT3|OjT6r5BGZFADeU+j)!s2|u!#|0!TL{?C7VS4NxM;0nSCcnzt!5z(Z@7X z5|fZxTLuFj&OtqXzcbz(him>km9iNd_SB3_Q7-2i3Q2SHAn~$r(?gmPKxjq_H4GLF zEwe^nt_AYPRaXQ_k!M|K6*V4?(7b;w#t_55FN^vJ{DwkEP-vY-a#$~Yne{$M)Y`!_ z$bvyNZ~5PHW7Yl71*exd&~K9P)NIIO)_|=u>v;Q)>Nlr)(h0z`It(vhQA1IYe`!r8lm?1j1#5{H64%H&D`k=&7I!fS58Rt}@ zhWz^S<`fJ)$_p4gW_RC4vn6u#kefKK2#-aFVGnRTzzvHJd{_pnS{E@O(`28uY z=NI=<6CA6&=6fJyjq9}rfW;!8n6OwP>=xCF%B88slm@lIF@U0WqpD$ZD6w+M{C=in}tCo~E;Tw3zUYU}c^ zqG}sazMd4tv_<-?emDNIo%QsG>sQ%{bwUlgp<5$Uf!GM4^R(TqmU{hNss%o8|G~lk z&~%nTZME$dt^&oaxVE?lg0xui60CS}m*DPF+@-jCkW$>exD%vkaCa&0XTRUfnc)}1 z4+uMX?q}U=T?Z4VE{y~Gi z3{2PLd$+w{HA`nLnN#>e#X{}Ce-^xz*JCUo1HD`jD0b+|ri&;g}cTX_w#b(?w&B#%HVa6KPzp5g~n*Y@Kk6ACz zVfE#&5MT6MV(pvtlbXAQ*(&C9W2Khk_Zjs-X-%J`v~(#>b@f~hr(z+GMlWkqBW;7- zp*NZ_bZBy(*2>k^+PnfOb!V;PQpoAaD?KQvJK0-4f8x(MSOC5`=*#8B<+Gk- zOBF3J(ljf-mUOMF+I2QW=DPu~4_%m{Y5&Z!ADKSw?Fe{fvOUojOYu;Cb3pG1Lw|q!L4F@+j z#n*Pr4~%cq7>#}B<~cE52^VO$gBt-o;+N{F7PERrD)uYma*uR^D72#V-L%1nQNq|; z6V686cg`zfH0S4*#8(mH+yMg2{y9FCfcHE+&yTJnA&vtbBo-G$r2tG_r6)a z;?*PbVLw^DCv(d|tx+y^G^0Yv;WhhdhWDpLM&Xw_MibNgqjQam_g%JQ$LO0s4vV=j zHwECua$~VQIC(p!6jCn%XCfU)q$p^s5m4R$?T1$NBy0EmI&OVHIpL5*y%rM_Sz2&; z`q$Ll%U_+d&6jFap`zJgsYj{wDi9FApj^_H*ItCLT+Q@$=7|?QmcS|1c}>mNR9gsL zz4`NjQaR;Z()oVA@qC@!$IfWM&WJ@5wQm~)di;I}6Wm?}c__9>Q#{IM|) zx(+O~6t^E4x#&A6!1lK(Z7CUg13_P~O;p(o`!Lvo0ty*_m9TiDsRYS2-QkD}T)dQY zlVf)Bo?FvobPhvv5&pXW(L|`&p>iY0`vYbCfvfA-+Wmxz)%h554; zn$!Tt)Np-l6Ahfxs-G71HCaU+7sJOT0M;^}mv!Dh99& zS6P$FO?{ohpRM7sMrz5DuL;;XBODHvPLf?_-;S()fiM#0bf?c(RcN~rt-k3;>gT*yd0|55FwyYET`t$ z19F0vbU!?3qA84DO2-)%m#eYk(*pxb7IP&_CcWUVI~qPk|=-8um3l7UCVpvHRh?%kqzHnIRFK zd)E7xVFwdOcWyAwv>)0`WDT*O*^E!*{t5KEEb68wenB~6RpD2G^PTMrWA-!0ON+$O z{UuAM!IYj#2%&7mg5gKV5Ei>%6$+^4e1pUza5jH;>m6~nefy0DO#>?a#yt}0;ml8_ z(^}v`M;W##G@Z(;zQw?oIse|2IoM%~J9Rv^%t`rXEl3GRLA=4X1iABev+VKQF?hny z^b++V2cPCiOxNmDiwfNRb$@-RNx4P#i9TK*-W_{$#)huB%wV1teV}UBhHAjO8I>$= z;7OqDh^KP!UKT;}sWOw6adeAkYhf&T(KUhwGbJN4tnR??|GfZz7OCfZ9d{NMUG*kx zfdWwbicGV%^}&BZXd|P<-;+9v+BpRZ9(#}#;!Kn?+>K7$WPbOvs^3gtWo?~y1`L3= zwS4cbDLgN51cpDz<2GmVXmEObSAqZsUXP+SI)RP93v;0mi2L6e;G-vxSi%N}`J+^5 zOXk)Ko`X$g4d`Go1AlDUqm6JSo^oI%9q;yRyPS3UPh3({=Nr>l1F0?odkWh3V}!IlSw;*ha6SP!uf6`t3HuVOxcnkK|M;)T+SAP?&M0qzui)H zJ|#M&vJ4|Rq_ekKt@c}5UQ)~dJC&mQiXGaAx)0mIiFv&FQzRdXuJZot_X<;^c>)po z9PJh#TCG`{(aR@ZqN`b`v3XghY= zShTcCj4b^U+l+;KIq7r|2n*tfxDUFksTj1Y&i}?AEX`3C_3Sc(JfPlHOGW_CTzhCT zVL=#rSoo*zLGudi=quDLjn@)YGs4fAa9?@X6&!tG4ANr$d3Cpa7gwn?)TLd1ed`M7 z1Ay_pNWP|~$bWfVRz<%4LhPa9Q4L4j>j5qe_X(NNd-`y^)Zy7!V@DWA z1loTlB~;D+r?f=%_K~OltUp-~_VOKPv|vrPv-9TTwN(`fWnsq4X% zN?!Pz*7O3`BO754v`n|!$)AN#uof#M5g{pLCJ14)LJ$#6TL&5t0ftVp&#h^ z+S9JNsGQqJA-j(?KMVf3#M6GNH$dl!dW=%f+6jm>E7PP#Csko0wVfk_=i29DX!}h4 zCPnfo75wg+E`yOKL){>>ng6%*r!YMjV-j8VwV?cf6b;p;MB+P!UwDZ_yH{VQzc+P6djk6u8#1R2g1z-oArp3Tos}2bX&5W%@VE*!G-}+ z+xEdF*JbI!I;cx}`W*{!&*D*K$2CQ4zE&ezlw@JKFg0a~;EVpLgo$p~&0%a>D48UU zZgf5!_TeYhl?q|t%T?b?%3OsdjW;+u?NU3#&y^{; zz?~X>m?jEOjevA+YqO#DZfkAfUW?scdV2;|(|#X=HfKP{F1nNjUys z#)r2qBun@?Aah4eWs*se_hlsQE4gZv-g1LpZfg4Y?n#QjlF-y`#pq?;BpK!H)$B^* zrP{VGGtx?*cw*OROQ@7`7l@H`C;jV z371jvg$MO$7RD77DsAbP5f94_7CBy(a1!P5m4}K7ri%dVerC=)2;Vb$N1yQ(s#j`ot>zEV9tAEI#-QP_75wFITg4$wyZC zTE54brd(bLdedhLdckz^oZMsUl{J?9Or56D*YbRVNBK-PI9P$xaXVWq01Uf$ZM8o@ zj+AM3g0+L%G*pafyUacuI}~{#EVwE}X?`#*9UJ!Z8W- zsq?%6P%Y!I9+z^;l165n5Fuon)c!@kU*cKJ{$CW?2nij8V}I2B3IuYCHJx2vnY}w{ z55n}zf=-eB&&+-!w9FBuo|97_;avVM0sJ;?VZd0MJ*z7`7NhItr(C3O!Z{R(7&cXHW4OkP*tL{D7E+oMsoS-V#izs_!~%r{ zZ0`HW@Y9EL_ES9JCmRZn)tCQRsO1b_h<1n#vYxHJzMit;aerzu+e3N@JQ<{pT*^*r z-qp-BgER3k5NzQJlWWI4S{*0|v!eRcu`G)T7$Y(!XLi1D%jH+qhHEYJ9~}m)GOJpkB_zbYqOiswRB0#*DqEowI#P{Q|ikC`EKs|iQOjDLt@z|cFYBdxzn0@OUqE?A@hD$3`0=!pE$Mx+^R0%IUc+iChg@6> z^)yjQR`%~ZQOcI0!<}qWd9@_0ixadha`Z?#@F?}wXwc4*68 z+-PL@60k1jU?6-OfaqwU>R$e_4J3z)$MYl+O}in1jtdD9kC7_YKC z_V2$3_lfuB7YkTN=W)-{VH#${aiREB(A^pX5_2%TGaw%i9SUrMwXo=_!7v`xH`ksL zxu_ogn!0}OBnHMNh&?Jc2) zH7sIRHkFUR-u$^e-)TA@`=IanZ@4>PHpX|A#@&OIa7_14yZqmpI0l+9)YlDR;UO!{ z4hqmDIu&}00qwj!bs%NGB}KS>pBu8 zm1UA(xupZ$;+D&l%pdFwuq2I*FdGERb&pFTqbdE8D=P^$Sm#YfE{hVyKPaSu#i}k5 zQU8FQGsw|fHsCm-k;?d?`XMC`wCZ94&aMpoa?1v*kZ$Q{NXfG%D)kr7y-#*Sb~{T4 z0_;i&oWXI#Nk&xXrJz(I$GRSaKjaN7eOOsONxi)iz|KR&rsdLTDMV=%39B$ z^26@1o>88znY&3)cL-*ctxwkdaZ|cxo#>{mjaptz;a-N2Puh6Q8Nc-}JXJC{ZPNcS6_|lIY?6#Y(EXl?8P%^&OF2vCYaa1hPxG1U z)y(1J5wa0#nt$3ajlPHYI+%B&FUVz-AW~aa^luZ{9gkal{Y5!l;ZnsE?z~5m0W=Hl zM@JxDI{P^TkCj{u_MTD^#-Nj;zX!^Msc7#l@E`R*puA!!-Q9a0686m6S;xX8-w6}u zlO+liH-Kz?KEL>;gd37>Dg4(t-ll&=h3X}?1TkKGd_e9v4dc+LcM!pgDX=;3l#T^I z3EVPj{!;=|FvK-~gg}BZK7Kk+vr^>CIM!IeSI{q`5_x3Md2Yp=_0K&XTD>80^A^O7{!K9cKAHI5bhU zU@zaM!|2qTaTvv(U`BeePcd@t<=z=6U22<{Q^sw#^ZvF*_*us1%1kJ@kW;iHYGl$+ zcxc}uzPFbalGQII^g#V95mlOOwINM>=_;ug8!$e3Jbn8~R6G_Z4pQX(GUY7a?mAaFGolh3fuV1L%wEi{Q?-6+;`Z0R?3lX(6ZWl+7^HS#vmzsG~ zAD;t_Rj@SLlo5}LZabY76q#mZjpro{zw6Yz{Z??B@~*dwnpbzNYuHzetkxd0)ly5r zWdso-AXEI8`TIv2yNY1&AQY@jKroXKc*hxd5JCda79M`^QnbJMONpgd?R!1YklO4{ zNv|hp-|g<9Et?i7JF3pBBf%jT1s+E7(|k5V@BT7KmP-mwXZ>}#WPyR_Y1T{b*i8)< zA+wSP7U_VRGo6S=#%E`|;fUkUGF+lArM@1=H=n?nHSW}W)YmL@v;H|QRdk9inFc@S zVBoryl8$Zy>@Bvz0mHx3dKhu){xT#wQAmze@iFnA=D#oVnBq8^MN#Ein}Q#8sW}U3 zgGa(1O_7I58boz1^Kv58xo>x+gaTn`T{eM-?tz;ckX2W=)#Vnq%{64VjnR0oHQV;k z@;!m8UH+8c>StP|wzqZn@A(}wUAyo694oY?wm(fb%VZV3X&0Yj8OzjWGwu&szhS0l zP-g-lwwF!aZRcYs%{tXtA&?2lGCQ((j@`TnQJ*&UZZFzEBqdW%$lUI)sS*ub19j8E ze1fryO!Eb~Mw$MU#y!yI&TY?`zDNy)xg)#Hu>gKUCBi^rh=$ma?4K_UWZ{#Z`Bhz` zyp#p!T^dBy+;QKPt{uR?XZ^UU`hh7*rz!@@zH+@i$- z(!Lyr`RlZCaMZR%e2-q&U+Pou!tKI$UX&HuU93$7_M+CmX0)`x`%}HxEjC06OcZ5_ zCV&30s$!>2ltyc(?=Pt8aYGn^Q^xJ_yhFz1`So8+L4V&T2~&zY+JA>#E*Tps4a5-X z1PJ3S6T-()9xxB_nmPOf{O*KoEY+3Yz^GpPl-X2UKRb;Y=8A6je4S!@l_OHNF?for zU#6MHisvs?vD1ZfTGS2Ys5`a2Q}ms}mZ09695Zt`XDQMyTWy#WG&$wk?i1lh)xtI+Iauy&*!!Ct z%~I2uRYbBL*5$-v1fP^`aiu`aGNp62uPP+r8w7sHY0pR_n*n76CIC)jplv>?%INL*m~${w*LK>~#0Xlxflr9_Qx zAyC^>IN;aytK>0@f%#d|0(;0BnRhAynvN7$o%&R2EDmrdxMSLr0of%6psRTL7=0$u z#X->|uldRYBHdUSdUeSz=4s8K4j~jtf1+~7eP2F83Ym+Z$1@KeWbW5xeTZX0o^ruX z^Mmq#eQVGlh)swS+#93o6||+6JntRCsCp2JBY(&rWS#mKLLn0oK_l&NjZk5FFFQqp z@=88~Ph`GMG1Skf2|91y49F&PHt(h!7}V+QTTu)5utV(O^o7Opfd7R@V`KNR!4Yoc zs+`S)wVC9a-te$TQYf)3FxGS;D7~(?I$H5)$=3St-lCx`n{Nu)D8 zVmTmVC$2nOu}qCU9pn5FGpi`~fMn%auf4xvBP4{v_u(1~_vWQWUcFAWOT~Y7UO`dc z^Z85{`a)f1EY3o2y?4X)IBCHNxNxB8tgQ6ARU*siHzo9i(!R)fn*v$;wx!f(kdsJ~ zSx_9hM3PXXVHXFP3ijtrwqp}xi*ETJCN1iVb`1DQ8y5@dIoj+X&tl0YU6CnGZ5wPx zxN=Hb5KDlUxT^9vz#+BX_y{Y|EQ_U)*ly0mpm$=ryzC70pH{6+_6huc{aL~!Pf~AH z?NUmkzed#)7jenwz0IPmjOUg$eC>OKUa!^XK(;PxI5+mK4&bfIXMOH1nKHX^&A#Q* zb-U%x7^1l>Y4V#`mXA06R98ZbKDBwVH8_hz-YA03B?6{ z;;lLYf+|ZkqGV!iK*=K$48{Kk3u*g&rm$~tP*C35&ET`q4bk)bni-#+%-Fut>*2Pu zQe06KV6J!I>3DI_9IRqknbTB0+|$#ePbV=2X4C!-Q(3r`5d1H@PdVQpXgV^TlK{NN zac-_O5-{BHmiig^$1+>zUn)#J$xs=mVG5{+i7zrW*gsmh@rs+gwK`%111u*MI#H3k zhqPaqu81WV%)wLs1@#LGw=qF8G4M2^Z}{9}boLl4l51#?(D){BGJ4T@ z?36;C5KmNM0;a%w(1akFjf0zeFs5w-XN;ZAVSSTvTsFGxj-XT= z+yv37w}oxDNd*Fk@0H~pY&6oMW!pbZ`1Ml9oipY019&KYk=4BZ&rW4cXG-U?_x^pM zN$k!i(a>DavVD`~mL;}e&>cmFIH*|{-SX;@^6n_)@fo5~Jm$8AtN6|8YKm{8&P*Qn zjxjAshbJYLQ%X)YkB+XBgmqb8YbFVik)V{oY~r6&oV1Ug9n#8h{u})@cgu^*LFY^j zTt@mm()3&FY^6F*8^?u!-DW>%>Y^iD@GrA!;1Ac1bC9l(OXPWk%B%8Di3=REnZ{1BzP3kmAwO zrj;|OHt4z2qbnDHi>JfGfif08wqQDE9m)%2cD5|7Qpm$hI#?sUEQL$`wrM4;V9DHQ zp4Uh9Rk)nr5#Q$CHt&-UZ=o6~%t6oi>|H8JYb1MTav&(ABM=@{|pvL`?G+QkeUA2=r)t^xqZ4V$=cadhWDp1!u~XX6oTTZ*>X zmp!TA0_ll{qKcwXt?)r}5&|vA?H`C1pE*>RNiEh}qU9_D+*x3#?-?1lVvSv&t32u? z$&kMnhLs1`w9HG`Tq|u8!G%N8GJ?ImZK;Ds=>6Ef71m8k^12iy`;2Vkh~}j8n87p6 zEF5sB9QYis-khaML@(R(H``SDt_WmK!=kXpJA@KG$Vee~Afo8rM3)#`_&*8g#eX^W z)PPBg4$h~cNK;$95-DmFn*A84f4lhBYG>h4uHK86S2lfh1nUeg5W;0o)FLq2R3sFo zkw%AZ^v?>-BpqZlgX7E(Oxtb$@EQOwOF@YwOlk3E5=?%vM-mKbWNbjNT5zMu;kDi% z>up60Dxj0^0J}$@<|DS8lV;AIx(_l&g*!!qyz_B1fjJZCY-gw670CKkO4;1o&!_$6 zYq-=LNNOAzg0N8mLury!KS)CdiZMzlVvsQl{|YIo9GU2hDztP<#I>1+X)^=sBpAeC zZZ9z+yj1;a9D{sV7oneCKeqT2wK-R3f?0;@n}+`{g)WnYl!7>-U=R%@Mo{Y!U}pa> z@R~23^!tc85WB!#Qg~=$>$DZ(V{h^*$n8<}!p!#v(eJmf#3Pk@XElA?rjxgWR&-!rPqoRxf>1@$O#wQMQ#0tu>8s zSUXO&_4NL^TBwdQA&!!Ky>dM(t?rVN!g2)Rk)FDw-a&wj>hW}VcU?Y<5kF-1)H|n@ z>6(c8<&v7G1)FHRZkl5VD^_z^^%6g;uwh2}`61BpmfA`#2XiTqLOgQv_aLmtIm19g zkoG6xC3H(es8$#MeN5~QK8b^A`Dy#fF33zt--hmqlC2s(y%>w%YKxslJ~tV;1t{F zQAWwF`ZwvD*J_8{;Io;H&Dt?E{Ja(qY_0;U>G}d@jh1nhwo{UX7^-aPGvxzK2#@0{ zlNe9#DS<;bt*};0j?OHi^Fa7MQ~gu-QzvN1V*vhKDC1cd`;7rp%U% zoSvXmBHq99^khfgwzVX`KzDsNU~O5AmM{dH2tl+MBZtU2$S>vDkCg-)CEZ#V7j_xi-CJ1Ok@; zku9}(#%3M-nPMmF@tI?&=FoSi!toj}yDQB*)=t1paGMqPZ6Mzw~6War7N_=DS1+t=HU>jS(yR?MMFax;eu9?WRbd8OBmlvuLEl zM`eXmcCoVGugFNHuG=s}7+DaaQM~VrTu|gts-1}kGJ*b}JPwWY#9iCkS)Ff7HeUu2 zPcuT)U$%cW5W*ELgqxR%Z@q{^21{bz-+gDX0Ch* zSgy(%`Mt!hwo2*%yQVgNu_@k!1yw>0J1ebtxKdDpcTz#R%@$b=KaD*gbP1idU)v#A z8!B5DS4$`bM$dTVIrzCG+SYO2J|$u~VQ^rO?{GTo2jv-r*1cOpTH=siuZ(p(HuywQ zzhR)s(`=*t0neLt?qV9RFMK}4CoG@xzQ|nkbiGKp^Q`06J8zp2`;MFRj>z#b{(o|O z{bQqIY@Re}zXsY1C!Hb{Cg7$BiWIF7MD>Q$eK4|H_k9$|mJ{Z5%Fw%`+}W*vjh$|L z-J}?r&z5*+o;n**#geJU&#=Ijkk`@AiEi|538g#K!ej?oEeKoOz^l6@A*RXYYwC$6 z)yvp|Ple96&c)hncuoy^ztl`6zWk)kDTu~?siaHSWT;6+E50@`1R(Tjnl7|~h=~$o z?X5L};y3xDckqt8(`Rz=j2s=B08i-gmt2XL>%)3Kxag7Ai6NiA;K68?VFE-VA|9Zw z9i;0IX8q3Wa%9bO+fiLfPKL%O%jlZO2N5pO1KP8bJ@J5*a zutA+vIq5~3N|{NW5YC}lyrGK zPFMK6XJE>z(~J^8=P8!8vSVtF4*i(0QAT|EQq-+LTE0Yyf?4sHnyjKHy=d%TVuf#n zDQ_N+V1!Z}OO(A}42S%+lU5t0c*<2;#vQG7muNn5V7ewZQZ?LD;Aazzfok8yT>CqX zG}l7r5AkftiX~ApBz|WfBO5!}DY~$=JzIh9y;+6$9z?wLfTQ%dT$PTkaZX;s2b9-f z*6wPjn`JHm_jPYExckE_=YwPj!$|N@q%B&4Xf8&EGp|^d47d!1Bta?QQeie?ABOEe zEr|wSx@FN%GIiUU{7wW2KnC+X(ixnPGV>Ni^MaCAEAAd=ojA809?hgF^+LrjVL$y6 z#uXjWHl(_YwpzP;|o!gG5O@&w`hr>D0I^TBs$^)GN5zxkv86A^l zqHg7=1QGFm<$SJKTi!u;Q08PzVbDS{x;0%zvPJRXf*(*h?Jw%JJ~{7$pV#0|{yVyE zLCJc8^7vA+e=RqYp_wg745}()ccSb{Lw;o5!ta2KqjZ9m1<)l;`sR;kYAF*VK*-Ct zgF_#pn|uJjMuSQxqujXmJNL5^b+;p_ib>6;X5x%3lWe6jp>LK8p$y>z)ju@b0J_qX ztKKG&6mkq2zVNdi+AHC%))9M~?}1d&ulA?Xc{?YZqiCdO(Q8#Ygf-B4Fbhj;A-(Gs zAlCS4v{ItJMoy5aS!nl*hFZ_}!ve{TS>E$Qz{#@PH};122uVC((STS^&rpR5rV>44 zW%xAs4A8`W_B&gpe4pU;|USYc1)9nsO4v&!*4-c=v=Q>V* zeKN4_OB2OE!IO}Hkl7=38Vw;4OIVmzdE_<7Gn7ScTy<>mg2r{l-ZOVyr7X|Vzn{V# zrDLgaric%h`URtXMjqz`uU=r?y#c<&TvAm@M-#)LVTKSPjFA)=nQ%p&@|ifby?dO&z4aSfkO^c z__swAZrS0!O31E9>ejinuFu{3Ww%?5&t(%s)CbUpk3(CZT`J5#(MHWn$KQC^rE#lS z3MQwF^q%rNHWkkGh(3?8Ke{B^(2F0G(6%lCYH|6Ak!|PFtiAI(4Y8MQ^oD-g_8%NA z6p@zc0`2A7msU&T$ejOak-WdIV-`h8SEq6N8I_f}C$s8((h8jd*hDI4EPg{RYaoa) z>~USFxSvKx9P~QJM77T4;3ZIuW8ZL;;B6_CBylo{(jdTz=v-3!Z8^Ec~&Wwp(&mS*?4td5I3(9oF1 zY;EPab55kl3v^N1vtOi;i)<55dnB^V3nDM`4W|B9m!2|YlfGI={U<<){s~bpF~0QV zh?|!Zrqp%J&rKB=GA^m3hpJ8Jyo>U8KXT}yC0dLZC741D@^3wY-Qh4X*YiL{5R94!KR}ckJyX%^FUhmL< z&crNC-EapqPSTENGU3hK+>M9B3YfS^IP}Pie@s_m$~lffbS1D#o)Q6KFRjK2rcS&& zHr8P2rwik;ZR9l_QNvD?FWNGiZ)uSHo)is~wzkbaK9^tHhvgH&5vgy!jz{x7U04<< z+V-(Fk!KMaPctQ_=GH?459?eK>+A|Rq= z+G>?A&%6d&d-K*@NkfJH2G>bT7ObH7M?y z8;n`VmYoBWu1}lrE8|a%o<+ZT;1SR{;sk-X8WnpK!E-3r0b$SCZMRaM#wCgPNuftuu?ac-Ok;j6ZEC9_6Lb$|^aY~oz zQp;87#K}z(b4wk!YO5!%Wh-UzmR2OLyRdx; zWe;9JoMUqKjWGXSz6mXR?eboVgZs7nn3@m164R>{a!uYqY+%b0P6*H5L9E?HXrgRBv11ur}R}99tRH@Xeid)1)GncBc@Q&z(k5Y?#(5wK( zL-N`gARCufSO5(_R%ek-G|)n{@IqlWVJGY6FFbo#MeIdPWJhGJ+(#a~Lh$I1Daf)5 z8Pg2a4C|Pxs;fmyj92e_d!LfC$3kbM%gM`mZ}%E>4bQ6k>Q4^!MYkD6-0vyy>a8b_ zol=+7t&A_4NzeCpR*qasrXS^C9;emvopQUQm^*h-9d z^?%=pd})~eF_=k-e*G%Mn|}ZM)qdT9VH(CNL;9#V3S4T%nZ5B??R*vp%HsEuKDk<0 zq;=dxbQCPvaDhOb`7uHe0KKGh;z9WB_dys(JvD}my-n8-CE|(iqJJ$Px%0+`MEwaj zowOoQ4DgRKrNb!`?6sc@T`4H+9dkjU@qrF7e@#M^-)Z#_#=Ty~q~$*KQg&ij=Gy(} zNtcf{9~nxaBw1n3C5;=#G#JgL9@h_G^DFCU?;V=_ZBX^SrXCRIoR=# z3@S?`&?H5S4Xl(8Xs_8$>AeCPhtZAXBzdKA0T}I)jca9&N0!uIgm(}v^_!zawJKsF zkRjo~WXgiLw?a+utEeM+1x07+b!Ou4J0;u;-RV2|xBWoP?g515IY z0CdIODm8<8ed~7JjLNHQzG&Wu70QQB%5O}G-!(MWj41DkR_?@4x_2v3uHMWCEZ!%1@;&~MmKV13_oNg8Vo;KPJ)xv@^2!kJ z>8j}i$F_a|7sY^KL3$vG?<{34|55S~9|B2$q%QK-ZGn>68|E5pt*<)m$$(P1bAiRD zAI3%|L6BZ;Wn7PKGPt9~uCu&g!cQ~(dDonc%g?nl-=oDyZ1p5WArej6Bv$2satR4b zxLvKXX%H)^zJDB4g7`zi0G>H4lRr_5+OnRMs8AZW*Yob2v{0mIs(W8u3{dVg%aqC! zki!UOod+G8nCsuUCvDvED6$g^&_!;Nz+as8VBxIXpngVZr--14#F=P&cLDXTz(p^% zkTLu5(CjvI<(6FNVVH8e$q_z*=J`EZ!YVYXvxlJf>(OnoYX_y^r?$fD3W3`FZ@-ZE z%Ed}FyV!3xp*#@r$VLOOKL1$ktAZVOzG$vpr%LN|`G%0DC^fy|>cQ$Lk*m=Gh7=3M(Py*AmbkRI9gIm-bxh%rK@QUg( zY>%JqMY2Y?-U0%{EDe~ca5XymS2!Xug1^J)Smg&O}C4_E% zcw+E*-lfjgZsdwwa|H(VS1RpwBL~w?o{aH$m$}Q|a@a=^$(3N&{>*EOe^0S6?0i}q zUVFi8M|j5{BVji(S!4u)|8>JGDU1e2YW{lhodDbvS`y}nQS#LQMcd5Pe|Oq@E%Db0J9}0SuDpg}Y)-egN%(PV=&9xpK*={Ij-{E&WB08c@?o*NmPo9oXFgM$| zWUL%bUpb|9CA#;-P;`G6#InwFMn_lIuc7I7ki7Q8;gx5PtSET})uM~8YV*v|`&D@| zAgv8As&Wg0-9|WR4YTO_1j(0*6xGQV)kThQtyfAV(VD}M{Q7lC9;5#I#IYzC0ijEH z8y<+P-rlkm$uD`2&Neyx_wO0Y5qz+LyEoG)YFI)^KQ0aVgQ)O zVSn{^7wj`S|6D@yd&BUymOk&j1acfe8D$XBmaI#ZK(cIPj6KvQ8W`L*)wcOy%?9^{+b)*)FtRg+dA{ubNQ?`egtN7l9*oye3l=weT|+0Us}RiN#i z9rx2tJV0PU@{oZC^E>nUR1DnH@?v7WJ_YUy=4m z=J8Pv(v0y;XS`_5i6l(;$w{w(2T2627e~zWT7r`+^ye|%>BTIAOc3I26fg(|BUd2D zSpdM@F`OSOuQiQ6uKs8PJcH(}#OWl6f5Vg##KCL2Q_i2@j@4iqhEJBSokw}#dK5Nm zpS-}Lze%auYbL&?ZXhFUH+C&z}{-7&g&VIH{eql>oUa zN7vV?pEIt}eI*t!M~2NnK}xwglzJU_1N z{CB=RpJF}#>5U+a;O=v&Kl)KtCrU2(E;{0LM%6{!e`Zj%Uo@$(Ffv>RC0G0jtNQDzK!)+?q5D^!0^tzjn zPl^A*trI`S!YE7!u@dPYhQrIsnT#UF32JeVmV*o?GV5F&A$TutroGG0&(CG$?q74i zeUar8oo(l^+t?kl!SADH_&!yJ>5@sq;p6MMxSR?@#RtsrmG1o=8zQ7kdBR!5BfJrD zsPs$4X28z2=L#en0sJ=b$0Neq1>W{S;ip+Cfb|p|c4klUcm)JjY?R6s7VE7|fgVH% zbTnH(W`I+oPLpCGLpy56{i4fC9d}>!$5FVm>bnz^O!f0jhMVTYv4_ZAj*@mU@ z4rC$nE&Q7#RtO&7^9JAUGo${S4dEwz%7<0tCcCv)_tz(sZk})a;L|>ioQQ`sLeW2a zEwQ$~v)^K=&g}!|ZrnZmc+*me?8VG6+II*7%%Kjo%#zRo9O}F+73<_ykq8kpD z*^7uklakNrRGe@P)LLp5-r;a)VtD%lA7Y>#T+SU-E!mQY#Vm11ZaH5_N< zNlLs~EsP_QLK924zgBLYV?in0t0#1n14E>)!o0ElRb}%ap(uX&4DYy5t8xJ}vL%Ac zIv;!(nvR>ggCb@PRicOGO#qf(ZPJnBOOH)=YO&@8nomDb3>vj z+PP`wuKdAKB{8%0)@<~^&KM;%GxII#yez`yht;=#iAw9uGxZmBddvpAJsgt52pg(E zKf;7l?U?(M_Vh&1QZG7)nYPumV74Z128JbZmo zvi?BD(9|>l_#TL@GV~HHLPl2p*sC;EElvJokAsy(yu5EsncurWV!!4)LGFZ73H(Xx z0I1F9zxwk821GVrw*gQ>0FX6bw zv(#U?Spk%d%V>k4Q(|Nz<4^Z!>;I$aEQ6|g-!80zh;nEok92o;NOyO492)7CmR7n! z;E>WK-Q66z8|m(P_wSwg&oF#ucxLbY-0NQJT1X|P1Yuh_%u+TSY?PD{Mxrv(S$l|` zKf(W=p1_Ycc2jdL5OWhOIgk_FVdiXFhx_1z&V>k~3>4$q%XebUE{$?j;)7*!f(4Lg zp_%2t;*e<!7-`!UnC-fI17Zn2dx*jhx08LXTQHutW%V@@N#^tIyZ2zxM&3Kk^WKxTkv^r$VcA?EJ zwQAQZGqY?Kh|+{GV_gqc$-f%f$m7cJw+EVQQ$znyZ}38YoNN4axn+&Z51FnMkzc^dA+(J8GU#1Q9&9 zH`GPy;CE+?M%jgS7odn6LeI#Uo8M$-NuhxrD%`NJT>ah|XDyXqyAX>kLVoaJ)o<>8mOy96HM+8V&nxbB{@>2B{R|y67-OBXxIN z&Sq%i;NWok+^zTFcKAY?%`~;vQCB77%9Xi3X^{NTBjLQ3x!Kg&L#@hZ!t~2C z)Eud=pjoh3 z;0@q14vWLs!cPrdN~8~WdfK-ma#*5_1pW-e33Di?7{+{U$+Ui2)!F%NZW zkU6rMF%q=$tmozzM)LqoBCNG00gmAiPG6nRhkI+VDVt z9_%s>wi?LA;j7u$#LSmke>`a_=>a|(H8r|_EgV!*xm{`dtL;z-g?dsyC~iEYDLB7{ zlBEqh2WKKU&HtV=Adw{l)&yx{1N>C7k)3uFJ6}It&dyTJeeY>~VDv@Kr8c#;wv~E) zIT-J#hF8uwu~5$a`n3Yn_$0UB<~R_-r)It7^CIitAIa3(g{deIxs`k_^SNY86@F)f zvy(oW$L;QogU6X)f{L6%)aBH0h2sg;9y-u*kOB{Ysp{GqLS2>MkB4QSwUI}4wA#kV zRp4UmPKVyq&ocY|9h`s5qpD%J+jnp}$5Lv98BDQe5e{zpu*aKr1Sq=z5Zs&R>0^UkVAmL+AR@Mc$2_W-1yKYzi@G|obwcU z|25!Z>~VriKnUnMm)V9ym@kQ^$IhlCweI=O&57CoOhEe4GufqdKD2jTj-!QS@~VLD zp0$S#|5gMsZ4|}ydL`R*;4(v{mnvEn)ZP4od153tY~ch6@vW)hzv_5?`WH^+d9tkd z_cp8M>C(M@ywyFs_nYqp`N4-z2rF)wn1A<1J`(;twP!RiSbw^|%;5D5l-kMn&T#b> za0JIvN8LR6*2uANu2#tXWenBERi}X>l%)bnXR?8g1;jHe=)>W(HJ>{&;#=VvgzmNy zU1hQ!`p~-X31OjGd3B*OAy0Q7LET_nFMWBMGi`hJFoZwZJ{Qt24;8OzK_5_Ac?6~7 zD1plg+sNoBatxo_Y@kC$>sTZbM^4@TJwZWqk=pMi@f1q&f6(u=f1IZ{8ETlATD_Z| z$n2T&r|z;Ee%B2$M|FZjzM@HdtTS@J)EDm$YcAE7m_wmVc$dk-(@fNUq?!#T8)w}$ zNZYy?#&K%F@Kb6utyU&;OXgRs`cegrP;E%hNf^Dm)9LMGj`~gL3&qkb*E3mbvq>n- z_RMn5AoTh-T|CP56)JmaMGk#n^G0 zz>VJD^iLbUBEof+^c+06O6Pd%k2t(yZr(w-zq!DY6>30pmp@fd#;$jg4g2ctfOIa+ z>SdPu)(1hN=YNtsem-`brZ=m+6kb=D}~%Zax`$YMgK6LkDXy_bHttNPFHM;E4}jpG3JhZ!lFDqC;Oe(dsl zRT_$_FPQBuN%FO}>D`4fj(5}O8rVsx-jJB0#PtvA8Tu}B1Ww+nwsD_LRb59ImPwjd z;Jb^qnsgi1q-Y=w1Yn-(kb?W2_gY${CfuTeEawN_QJUj(*DIavtuJeqsHX(rhSPyI z6Dt_Ik_sub$8Br^;&%3wJ5^OOHKnE3=>!L)i($5C39_{sEN6Gc-o9JS0(Mm5NsTmkN3J} z`0Rbsyk~#X`bb|-uzoLS_}C|O(eZqX&TTQtEJ0d9$T-b*a zB^1;B_3?~>?jStgYSJVcm`bQ&eKwnOpOERESQh(kZ1BdS!YfX~L(l~BmL0cWk#wgo z2X?E6%{bz0reAsf8`bwmJe6Wx0ga_XrZ8fskk2*IUjQ;rrHJk9u)D9Cu}#H41{bu~ z>an`ao`NRwwIS$w$n$F9G3PX^OdU_^`_TH|$sv|aiAp)RIcHAz27Tjo1wDPd0?+q9PH`Kb?C|U|>GfPj_$^JIZT%o1k;T*-&*!c8 zB>IM1Ky9vC;lMyg3pMlf+*ll|kfnQ*uX%mL>#gR>{$O7c3PE|mp?l6QZd0i7vn?qa z`(yv(lD@y1A=f~S8nHjCHYRDx;otS z%#uu+ZH`e3c5)Jq8e|Z24fqqx8wtxTC$0K|zIJJ8Zt6edP0{zRQQVGRrxXN?IMaLA ze)&ttDr?0!iqpFpaw3pGbe4ZsAUm>ZkDPCgELkGVIV-g3=A0EbBLt`!$gTlR$sxt$4 zeCJ=PDOkWc3OXD)((04SK6Vy(Aa&^5Q$J9X@L=}dA(CFVRQ(Q9Z@8a$+*v~-iQD%9 ze{o%zg}#*~V9!|Ki2+_KX$MLAch*+OaJZo=$jAk*KGv*L2 zjKv9e!-KJG2fM&LH{axb2&3*C|G1C8U}rtKl>mR%x?D_+F63RZF>d~|8_o<@+wdiL z{PM>Z*gF{q#-D5kiNOJcHM`%}MicDgYxt%nJ1Py80ewVLAVC09b6;s%qyy-BNT8sF?Pf48<)-OD{5K|H}O4}#^W(0~MS zu*)5HWMUT&X$-{#m6_#Tl1)w-xk={}ma!}(QH>jRU2CD4`9G){e{#zU((n;dI5XX9rhN5cGE1^j!zqQB&Y_0o|`zjMUpA z#Tkcr7Kd+ZSn-bqKe~T3CNtJJ?!Plo>Sa>5_tu<7uRsBM;M>H_kz5n#gW|v)j}!#46%+{gS08$)@r9~`FJ{u#l(u$L@8^;F*f^d< zuV`|adIqJ+c=&*5^DzGBt9UT4Pn1p>=as;m45kE$bes`Br7#UHA_*V^MFG@}vFAIC znUcXP+xK&=RW|xN_^?3sF{kJ2aSj$_xNbz{gOVi6vPmihQLKOj=J`I}jhEMYq}t0K{XR-tiqGQxro=VD zh&cG|Cn$U=FRln;!gR`R<}nw$$)lNyvi_VtF;vV(AjM(mvSohy)QMU7D7j;K$Nsmx zCVFZiH=*3I|Mf|%!MgL)$riZ%ksB!)JH>k+!xI5ehmWJMG$j7~g3=_iSPsh>HhRNW|^<-TS05>_5wy&(jvshxP42)r{6d`Zwi=j(102__ zwrstN(6dmprZ7-Ub|8Tl9u$rLw!bOPII6$9-YGh5E&je*jn)_!=zRwud`@68XKAHR zj^GddPAQoy<5QcYfOn9U4Mt&ctJyI3K;CiFQ!t}P@}{aPMEbC6OSp&S4?PJAA->1O zAE6=@8rZ%I9+9CgP@LnlO-8h_=XbJq=9~SWL=P|A!PRz;3?x4ceAf2<;bFG5->3lb z$T!`q=+9gRLN3;fDQ){KawNkYCJ)HF<-k5GSpiNDPt{$Oy>rwU6t*W4tvxq*px4W0U5j zeXqPNZa$N(s3cK>VAB;u0r(EU3fZZoAXSZ|3N&$aAn>V`#8D*nUrR)RnWseaO5bIR za3zZXTle%8`*0)@JwqKX(QWzCO@1PA%=^%f@sVGy6kiig1#fU8Wo5y9Zc$8r=aElG<1h3;JKQH!fh)9j|5x;(*EZSY zTmfqy+DY5c=|h4w$$s?RE`Gg6vHH_DZ)ENfC*Pn{3-Jh!=`AmNaKa8z*p!@g3DH>atMdR!7t@Gw; zH?D?^={|i6@T87XohNVKb ziG_6_rey3{hwm+@B*+~j#3XeYZ!Po-DI%DX65Qn&fK<^Uh86l1eLh(R+Id}EM;UHf ztHWl6DWXJ_{q+Z}(91bS^4{XyQzmUOWQ0p8o%bH!s@2o`H>0MKg9p+gYCY&~m?B%j z-GfM}Vs789x#iXObT88IPSIx*Gkg7)B;m$?%YaD3CsN>8^)7rAF5-Xh*)1Gwd;O%u zjYg=i!snK*wtY8i9=*j(3+}6vu&KLAT{d33MW2(jiDsoY6Z(!O0;2t1+8Hb{aS-C| zXAcZ}IKxj3{mP8|D(8=V}XOaEG%1{xOQ-OLM#BAC0^j`}4NjwlMM- zW}sFQ8EiBj$hZu36E({snh-MRE)SxV#Zo>K-b35kNKYY6)GtDO_Os^#ldYd2O`x zilW;25M}QDBcn2U!Dt+L4F7;BS{qROBFrqvCJZ)r!H?uFN3z;v?qo`q-ohPr`$VHe zQKe5r@wp2P*LNe3K)IX1=`asnx87QG^1$Z!4DHHomY4#F_}s*txgeUA~aTl!DQhyvGzCZu!DVV<*272M2U;)1{&=&rA!dDIwvY6Huj>L zwQ5kbb&@$Xlv&Prb{L3)MgW#){p2(MW zSQ~mYWFp6rli7n|)qsH3cB#0wY1)2Y@z>>?RLJMa39vG>cL`XYZU#J_QlKx5LbbT8eOuW&QgiNncEm%#cWwy|*-=o13$h5heg+xh3De-7)t_lx2E%;Sls z*e7n6QTr85v{6#&9~7#uh?7=?5pm#w77aj61LTn(-5!oHnHC=^wqcOk!5YwTy>?r5 zpy4N}+@D41o5`~5$?12((Cjyu+~ty4P_6o<v-LIyC!2z6t^}BZew3+(wLKWZ!)?I4NW4smg#Zb>&~jD1H!kBicI&!w zK?Yh!t8GQq-{mYFzuCX3SI52xHx^<nrur-fc zI8_bTjPon_+NPzZrV1Z!048{52IrhRm-`Fwc(!+l?_)otLBwYb-WbglbEpk?^wkdE zMoT1nwaQ^xXlVp%uoy4rg5d#ggUukS1qkaZG#78 zocWZ06FQ=WA?H_H12wn8YfA%_Is`F>>W%mpw;v;Vq@eXl@Js$K{v^*3Tq`I*o9h<< zvJuhd>1Ggx3Rw5GO>MF+b)sFyH|}p&hUMQn6+Y zecZLOCU5YMCx(}cnn4)5D*c0+V4k&Uuk_X16|0LQttuR23-$pxO?nvo+f0oQ?P|Ya z2S(Z`t!^r6Xmhpi-QJgS@<`Zyiz{{6R$~7!7EvHpXHNl0MXzZ9hG&eG@V@7Bd#wZja<}f!Q z9~SX($lU7~rF`$!UnY9%PAb(@r`IySuB$df_}Z%H1f2qJ>)DNThAT>cP28Az0hQ9g z8$$vy$e?+&6?F~Rr6yS04Az7%e5{=v0n?Xw%U%xa`561n?IC`E__eEawM#U29fp|e zYSo7v@=a46_85;`>`-VVVOQD_&7r!r`mmYo{qhtk=B;F>O^uV_2rF_63s}C?*iV231O!!1GrPw(NOMwPQk zGQAvt9cB@!@=s)un(@-j*O+?iit+b-T83PDzJ84@t{mr2kxb`} zuXj8zqwV)xaG%@Br4bUbVbvZmrlj*WJWSP=ImI+p{?{kgLIq^h2pe`26O2tn9b_Qd zts@H}ldvHoadSG>TABFBGGJ7p!TaYxXRg;e&MtTD7@EI1u-|P4nN42%EVhEkbY{iK z@u>buxOuYkTqZb^5E8ffK~VM*r+E563=*t?P`~%9kEQ&u#+uNI4-mM4C;ZmD+RXCHKGH8KlzkIzdK!9~!lv`lW?U~*G`MspyfLDme28jE3UFbnq%;x2^~o+r@ugKXTI_)R6H#oeL4=E zO-qyzV*wjpJ>7T-Y;yNG+YYG{kbr7K4JzateH_QfM%m>T>FoLn3|>DSmi=G`J*m78 zS^v)frN3);an91i<7gwqJh1EeKyU`ElbWfhatEsFcnB;*~vwY@CJw zW1}drl%Y4+ce=k2Ke*0KEJhQpDpI2rQx;1y7jqJeqx8tqq~62Bmhi{SuigA7K!q@s zEJK?gmqURM2L~t4@EGO>0uD zm!{S;|18y-hP*-HjUqB(`l67470};H<~%s~sDR-nBDX{yts2MO>GUN{b~NCvhjX#C z5(CWck5LL`lHH`v3C4f=DC+PH&|Q;i$z5(JB}{;jWKQNB4p~_U2*U`0w_zd5|KMLP z(}N!>T)NV^LIQCi0huM){Z-)1TRJj2?p(b~`basu<$)5jx1J2wS8yQK`XjNI^0@C) z($2b9X9u!N&uI5W7udKk#E{ncYUCF~W)f3N^+?+@RmHuI2qI7}w9xJ^G-^@f=$(ki z)IOE3cN3oXgZm>M0UgY`u6Rb~F4W{nNU)3SiAc2K`clZ>vficzKVOZW@n(QE7Vbkt z`bmiy)Awo6gGX`_c1l|o**yxTo9Iy8!xvvuZwB0gki+*+_l8dtM31AdN&K>tGLwh3 zxPWBYc-xxH9xi>!#{}e_NK{Ia2I7uF_3|7j`zU>`WCnVXnAijb2ano(5lI|ZOql;J z9mnnQ$k60clY&HTmkM+M(mp}~WD@~}Rh7EU6g=sILXYvb{=18vI-^Yj zLz%nN*Xuq{UKY-Pm-UKV8xFCoTee3YnOT-HtiP__hMKxP8cV&u&+gti3M9+4GqRt# zO#vGeJoOL~jn5TeREp1`+C|}IlsFC_Y`dw+2aVA(Do|#TltGrd1p#C37LLM@_ko8) zs{e97`Z03#)rJKjX!f`(d@Y&FuOgPX@@Ka9g&78Ws+wwx@2kJ^4eSH^i1P*=ye)jW4AmiJpuLX&G}HMpzi;?08>y|{=4;6i+jB_itw&q>_?@- zi1htCQ_x5-j}Kz)Zq=z@cAjJmvj9hcN*w<<;*z|9;_cqtXOd6m33g`i4jS~sMqW)L z+h*bS_t@jvy2jQIZ)U7NFVz>%9RN`D1ag3BfjFdDiX=nJ$bb7OW{=g^EL87v0Mwu% zRi}&`ngZNOjO4PL?UHA8A|@>Z=qekaj0H8bGN)F*#GpzpUkMgxe-QWVQy~j zh)O-Cd{*w>bJke5=esqCXO!okIE8UJ1g=eE=F{ab0Heuv{L*}0SdF{7tuGA-+bTOw zrL;gYAOBWYbY)$ZD!|Q#h*dXBt{jMyky|&_$sUOUbIS|adUVmXn_})MOVG+lFXYr9 zI|$is>^SG|GC&og&Z`x(ss!WEINJ^*z~c)H+^vmhg&KWpvAQ3<%rK~kJoHL=#`{#p zku*{C1z&HVCTh?Z_+9}G;-!;4_3lE&?y?^+51o8*=G1eC`(XwYLP7pJcP#Os(Srlxct~1MPFI!P z$jeq~``Yze$wnq>W*(l8hL8A$n>b;sr^$ZO%z}c^kTf8)-n`O%smD0V@ryN2?VGm2 ze@BE2!;+#Yo)gHQN(q&Q9>f*!#5gbM$)xAj6;w^-O-^R;I(wi=0X#x*|JSwqrnTUJ0Q#?EgVS`&exEz9QtvicPI z;bb10D(BxvbX!QZC!H~F;KIVEG7YJk#_vPUeN>d_p&i%0a!Y+^2p6s9P)9oO)Xj46AUbJ@3}iP$1Ga!VHG8=tPvofeN7bu8|nv?>+Hz%qe zg?}7_;$jbVW84U$b5`uhT+uQ?~43DkN<8$|4q=_f|)4wG?X>8V6>jl9Gy}JofDW2K;*8PcWM5?HuzAIVy_~aUHr0fd`ZA^4x*79Zg-5XTawgm1ik~;yU0_*^Z!kXaI=DRleBx>M3 z(a-r)Mzz=j$OEuP3+S)AeS)$hA$_@6-nttU4YD=D68CjK+-#z|roe_K=rywTxA}Ve zizcaH!}XBar*!RTUH~p9)HUFWakut*rV8loKggv$ZW@W4kN%<8jwpX)+uP!Uqj3h_ zokY2f5gzF7!BJ-=x`Vv?*`EO`ub+otT?3+!TipM(S(1@=i)O~KEbM4 z7#z!C8d&1!hR;Kq_hoAj3;{Y7pI_;E zJ25}}Qprv1s|9#wsQu27Zl!>)M1N0m%`0%fTQ$Em#lBQnscb^4C2H>jHI4LURE`>{ z^k!Q_Somzonth^aiiUr^A}TFn#ZB9Cw94WjX`w>)Z=EvIV58TUXKI>8$8%C==j6!} z+{3kSK7af$x#RS<6DJiJ`hJm9VT${DBuWi*5i~WQzz9Y2KXPTN1xqKBHX&Dw`nCYk zq($HTfl!&7S*Kp!)G6!0BavM?6us#YpiLwF98p)t#X&23Q! zf{e>kU;c>N2>iQ!e+J~WQ})Q$w&X?oeb0gj68SW65;iFp#+yLzP>M8cg5qA3Nj^b( z7V>~sL>zg-5ap-^5|q4vhWqx2PEKxaQYLOV3MVck4dva(ekY(%Ea+8N+n|qGMF!f6N(oea59&%n_AK&XwnjXRr+)oQ z_Z^RG|7j0{uaC+8z%aG!J}w}Y>eye;t!(S(eLQQ2F7>D1RX&C=lQ=^`TU(nl!izg5 z?64`wjiTQv;+o;?qc?g1UV^}nPCe;nCRjMrYSPMZ(0!24^nvd^5Q4`#lOR|Ko~ z>k~DX{CnF1{o!7dY2IFiVTX;i1Z6KRp@YCwkh6_`)3jaOb1i@$$q*dC;o%tfLf^WSKJj~m1-IB3@=o>aR$Shw_Sjgjk!jo&Ce10*e#-14WclA1~1egzD zR;t;{zQS=!oGDtdTf9KJ%&tYE0u#f{+eMdT#e#rD&bEK47Q|;_$t)MYAlkoQpTx{C z3S0Az%fV7AN0xm%Hr}w{KeO(t{E6vdP4m%F(=|iW!RU|zWiBrPU+-!xxvf^XcfZh| z*VIR^G8JT`j6Mi>!_E0{5v&+0?Yx=et9BQ4G7RgQ>OBbwm}-Zh31FUYfd&S2c zFvfN%cjmxpUnR1tij}E_SrWRrF%R(Z*aT04CUCpVY?rB|zu7KG;>0>IQw4rRlx6z))@(Y4fdu)WSrqwBUe7p<(Lk&5`F_=sMnk)lHR9qip^hXy0|hs>m0VX=u1Z~_M^(30 zt4IR@VEWNcdWS#Ey6?t%;2MkLH)Z4l)?q*$zeOsRgBEF&!Yld^>F#6*d14Qr{|g~0 z-^!r@9|^2=vjgr$er_oY2)od00P0!s>!m6^1H+_!!?|zv+RO2OdE?mltMWtNwRX!2 z-+kXyj`&2mu1a!};IHsx64)d~$<(F&kp|}j>cMcgSZalV2G1lX{-$i7;LKT}SU%#s= z?!8Qp8!>xlbQ*zsrRlQdnuz3v^Xv7xE9HFVx@{V@>g8P<7u)7OCGFx+Cm>DJ_A|?U zke~bLOJtsphnIRZW=|Nq#T^BTWuDU!YQ8j6k}=lNcx>|a!LLKuw|$9n5zWx#vyz7m ze6HU9r2WY}Rst$fvzWi&2$|hFvF!!^0B{&LB;5|jVQ0wZcD>%~b3(4vl+{4FW$>P7 zk8*IljH?5+%_BSC>nione;_!%7*U^X#96NP!M)gF#nvk*N$8}%Qp196Ii&O(I;k>E z9P6Y87bwVuw{;^lw`SqQ=O#vh?T^0mfE}knyqNq$rL`}GGdY0X=Gu3#w>EJZ`-!fWg7j@P2 z1TQLWrKAMfs~?W;4L{C!6&~Z>QfNN@4>N%bfu^1$2HmF9QV4$X>FVgA;j0(0iD8r6 z_2?Zo9NV6rP8-KIJ>V5(S{cm}YEJfEfcYNPFEJQgT375jC=36XZ@{rrO#N&6NU18t z5lK0wz-rc!DttQ7Yg77qq9#yn6XhaFDcN*8m6;rH`hYu&@{|;2D|_~G_rg8+%ELp$PY#pELi=EHQCD=6B;et)z^q#K0x@t4l zZfWKARPRZKf}ofg)cpCEUu##^-bO>T3D5|b6!JA-!Yg!u&jtIp8t+P-_rbCh&;??* zFqQd?*o_7xfp_FeW@w`&ewYHCt?Y`7$-;9vleWzK31lELIarR8%h~e}wIMM~>3Erb zZ&4cYbxA2`(VS13JSqvjj=fwXf6u>vXQ6Ki$knN!Sl3>eLl^wbZi!l2>`MT z(Su;JvP^ESf|9S_2aKOSL>W|+#m{l*nGr<=9}~1zF8}yie|t8sItmL9JpR)P4k`Hk zhT#moX;L3`PD5Z4nUyAt7_n(pL?i941~@Rq)7Fw9`lH%>IjyGX?}RyLhrb8Mn>mD-(mL z$pfg#js#`-I?4_k_5A#XCR&`KECb&JKPRXRa1*DG=i22&@(Zo457A+o<^pGkr(`o~ z;cH(rN>pF=(POG{!F!uy;d=-yNQ6L0y3X(3-D&F=_sjS}d52&1o zRgIC2oj<@%dp^clWCj_EB`X{0VGvTb6rpva4ffOc)UacWOTf2}f_tWh81#K}f_v}L z0%iw6G@+NA@W+csl$fl=Rw<{nONi^?WBRUvY3??{;2oqUKX<-pbD|TB=5v)tw8IBL z9Jp3J$eh4H2IcM|xvi(-WwC+;ny*BS7K+Z)^esTB(fhh??Lh$naW;bvk}1+BHGI&P ztb!m@$DRGUgu=~&kDNUuGt$#jLSrMjpj6!RCo)%B>FGr#}1ObU94*l>wYJY zUct%P;9Mv2hMJ=zyp6X0!ndPTI(;7WGr?Rb)zHYpWIH&{!oFL;RQ=&nFhxtYza|$; zV#Qj#3>)J?J=o$m0k%j6k#@1F^m;RvWCXzwjYcV9h)8jB;|b{I-Ac4`=}cEWR-S2N zxxn*3D+HR)Dt)#~Nl@im5~d%yKdfC5`s=lxHUw;&pWWIzmb_Lk9}Y{WZI18Z^r_NE zG2lDXI@{G1Bjc56_o>qnu~cY$g#Kwz^K$*6j%ezRu-Pw?=IfsXb_5RxMsf628SR6OTHD3XI8l8l|d?7M>e)Q@HMuV#f?)or$EV{C`K-7&sF)9sb0?kh zqvD5xr=;G+I@=8RbrhRBty1XX9@oEd-#*Nv?qb$xWl2iHW*I?S+BePmTj1K9=aR_e z&daERwfIU%sCcsH1a|I(@_h`dJVdHSm!Zk1?Ym`F$DZ<({hx^ zBK?(bKSn6cBfw4*)Ur}Y=&(^)avlITxvCS6cB~MAw9>xYx7CT!gFzfo$20X zDcmnR(T+Sx)Jk9P`#-=d*!GIHKWQMjZ~R6Q&oKtWgRyaHe&GezGLsr~u1gYtV|s;5 z`IRN2yaH{oDl0FTWHI^Wz3YN~t*krQej+}$NX{Xz@%*7VDb%b#<_i$gqp;AMp`{)) zeZ2WKX!cWum7QN?_?kw)DIVt%xvgv5)zE**PJ=7uO#r+6-;KQvcCQjLnU77ZB5(*- z#-7FD5OeA}-AWRO{>g~)K~qctgr14vw+*9ccWOV+QaG&fHEkBt{S6|CmSFvIo|G#u z9z3Sv*R}*I!y!x$K|0yU=_Jh`BFP=jlP*XrmGPZbZ+*jaf656)#~-`~p#=Wm=4_hu z#iHC5r=H0JXmA?yjhEZo55Z_>iiX=rEq~H~zx%r#_v5e}7VxdXq|#UN;~X*`5z~~_ z-QCNlg{aQWP1YXX(6Vz__AKrf8qD6opBobsXvVm%OG!R!0ExB1LGC%MC$>TYtXL@d z7t;q=Se765I4!IHTqwFOTCm-GeBoWO?VeaN*F@^ycUZ*@CAs$c5qsBIoM#aUA(aU_Q8nz^%cI!zi)ChPBQVYgoHIJgLgeuWfLC-g;Mt3&ffV3Y_`f z0-&G!`m=-aJ4Iu=^lvXb{TlYph7H?F4oDUiQhyeuyutcZO3^98a_^4SYrB$GI0Kq+ z5yp}}s58~7mng%oW+wVMY7TI#gc*~&>S2HFzZR>($K6Ujcw!>E%EKOpWDlBF^PUn$ zEt>I^Ui`_TLdaQwV z4p|gp4t#8=n?K$b!o8o!vgBO@p6UY@R62@5Y%ZCf`4hF`ISndBDtHsFJp8>mUK~SUL~q#>I3@YyJ93kjGHRi1kVe&P zN5Ho*=R79*=)EQyLbCZQtbjYM&$DdBxQ%)m}*;wzC#3N*c+1^=+P#KQEtnarkfk92UkEPM4tyz12B=pMp_C%61 zogz^N9bVYof($WEMzOHEQdy%eUU|~>3vf9b*H7O##eGYdDKJo979#&y>Z=OFr=S!y z3$$re?rWe&!8h6Vg{_=~}QyC+?Qiyz~2<&2FAO?cCh4DSib^EgUq zIl4G{s$A$?+f7}|gL=CZZ~V^9lEWS#6$1B*90)FK<#iwiAY=8Ft+8gvc zVZDSUv)i>7byUC$^r2_`yOEj_GV~^* zPT>iii*TAED8W^`vlB@n_B;tv4;OQFu$B(_KqNz3Z_BXxi2fiJK^+BYWVqnTgzlJ5YZ51N z@VMNud~2l7nY4bNAWP9j4Wx^Pc38_aN>`F;eyWs}s{CtOWvfk5s7QMj_HUHbx{m%Q zi3SgFtDx0Uag3Ppc-4)glZ&<34GW}+c(pvp+yVpKq=t-W2ydI5{0PWC$+NJlca?e% zNd3lpuHb^wqd9pOHAWZYF}AT!cB_YnNy7(Ia}6_8!+B1^r)d{l~{L`4(y{ zQ8o3d2!2C=;;`@k9o$m=c@P?!?GlMsV7O=vXJsEZeT*`h>7XUzyGpsQ=ZPZwFzw#5k=qSRf~@W zS2J+Ws_5xWd%)&=?3YWNFByX@5X+=k;tpOP&rCe_+(rGEi7xwOkqz1f$m7Q;Ba|(T zgm@7t6@X-6C{<{sDt7F0yE~dx?RhK0&SY_037j!*mEK3MsPG3CF0SG2?f3z-m50I! zt8a9tCp=GPB^ZV8CTA^A%`TBeyCDtgP_|NMjIAxaKw=S@kOH1RYWQYs>z?vA$LSR5 zgUrrF0rt50Yy|12taqJlz z@4&$0<&m{HL9I|QGNo5$T0YwKE38Tt#jiBP{uBFX{!9@IKaWhS3Yq4}FBv|M^6`Of zMB|?x;KcqRb{mH3dytBBf?7(_LYt)RSlykTC{2;Z|Iu`g(Q$Qc18&nawrwX3CuU<~ zlE!G9G`4NqYTPtxjK)S|+jb`Acb<2x@8|rRHD~rdH?K?YRIQPJ6n~IyDidd0kxZqG z$ykRxWc%rNUu5;eX-E1At;_l?QPRXk+~aH^I@mQZz@OM7=0NF3n~C;;Qm&l}GM0fL z7Q{_B=3%P9M1b;PVuI6S7>Af8^nRU~Jv;CjmpYZ%{T%`lx(nY;F(x1L4D#OkM5qkbzl;BvlYFy(SeJIES6Hcl3?ldCUoLxbp6w1N9U%` zi;&lmON93zKLM><6^FEWl5Hja46DB0iSF;!Bwz4&SnV09!^Z#Jkt@4BxEC(vihgHH7aT`>4>vgDFtX zrF5%j)@-W3!UZI&DCv}-1=1mTTp@GYzar{)eQ8?lIS{(%6}rhsy$Zx_`%s)XQo#(` z)+BGTGv|kG?S}5k7xVlts8p{eM`*9?u&#`YpVBq{`pgy$=4ns(*q<;h$v6rLE^~dNS`_@uD4s4|l zs#Cq+L%u{dZn||4vtG#N@>Vzy?m*spRcuIh*!)c7v+Qn|+*@|7RXIcKy9j zTF@_<2k6C>_%Hy$a4FmdA`lxpN?MQRp}5-yMcC-DK1rvC7>ZYtaDdwQ(ihl%=wwOc z@hDw{u^wPH*!8Gd^WWBr1tz;Q{)>^jg_%L$GhJ74P+PgunQSJTQ(BXHxz65D$! z%NAt8u%`z3L&YZ;U9@u`DWs&YYMs{IPRLf9~rcq5wS5L45x5d}AZB zA=a+9xqR&GJ)d#UjZB=e$f3D6yg69BmPUcn^qN;#38A=3_-aQC@#%rSdd?qI;^~(C zWAPt4^byvatai@~$7vh>KbpdRWJV>jZsyng|11Fhr0C|ZJWo!&7!mclz^mqpEki4N zo{Z?&H2?X^cmDFFUEPl+L`maV;X81GDQz9Cv!dKYI0rvOq9^6e?#2>FiZ0tfD9~lg zhkBZZB$T0NHsF-iD_B~GKgq_3w)oo~4$+keaEX^s^~mrKN3UhhmqUpEo113NkS{9@ z(S!>~lAU=}NAKf>#^V`qPP zDWRr1j@N_CX7JIrfm<;qOoJYvG246*Xi%VPlYxEfsvk1`EDoYwYcxvo>@QpqJ zUhTtfKGc~pe2q!6$=S=*8ChAz6S>1lUJ%lCSie^p+r9Z*tq9St*XM3_>%aTTOl-&| z=^bJl=jxNe(XpoC#u?Ij$1PQ~5}gaedWV@%wr_hzT{BquN5LKZa8%21#3d}bvisCr z^1eV)?y+sr!1ps*G*vcS54W)K%zgEKvhSEEAUSbQHl)0&HS@n^A&VNV!PKE4WwSEiN^;1%(Jf|mF#+ZL32fOn4OO7~gSG+Og>d=srTNu@Q@d1R zu4ZQ7cQyXC%k=Qw*y%3>dI`QPDf);c#kZh7m7&Q+kp7GW_cU~eiP?pU^Nfk*Iawx( zD4u}(eGrz^2F#tE;^--80YA~5>-=5r8HBAAT)clEEH4c#Rm*;<<+MBP1l*E{hWQ+xu1cs~hLnh6+V}$+!pKHPV zCf{%|>%I22@`KC2>vKPq@k}cDH>#_wPGSXfWY}H4$y-hCgEnu_o=AF=`n%(;2^BDt z2bhwf@WtLu+C&+`Tp|@yW0sw;HE~4gpRj1`iK2| z;j7`Bj*OPMWYl+%-X&YV#c@XDHx5)b4EVG_>}XTG4P@zSL)d|YfnXS2icJO2c!?M1 zK>Zhy4sgW0OWq$M|~j;K_zCD2u{ zs9mqEoU;!0WB<6E$mnAjv>*#T+pUhgpYpaDOa0^D@bFcm9@p6Bp~)Eq8^BL;UvA;C zZkGMbqUksRUaXvSWpJ-WvQvI&{4u8IlsAp{Bsg7qZWJTEm(goJ6P57DVhiwrA4Y54 zZ_5qF098Xd(3A#t`FeVwdV70|!1O32i&BMCWO)-wqkEbHTuL54qHQvaCv^o6^4r_t zsZ+*(>Oa(lPoqIaB(ljKQI)t5%B5QmMITA5mI$0W3x`^x8b}YL)GL5zizqsyxcKXs^t#8em zA@lb4GlsrfS@)3{%S2}Lnanr-FTjxKC2@fHA zPb$GY1VgmiHcetA{U&(tv}+6e_BbG9LYRnRQ-JMd4d21ruw%4cf|Wr?rXFuQnOyc=vLC0@Hp&p$Wz5s)`BVfIoq;9w{3wmqYb54 zHFkHn<-zp4nt;rOlvEtTpu@82*(f}MU%CYM3ozi8VthDBm8JRdmNnT6L)nMrb=dikp4G z=I0AD-c~gGpYB7vef=DB+D^Paj&^L{-=*sc6UUFE#&A|5`P3H8#_OX9vmFtks7d+-!*$*8*Hs??5GQ^IXx^*pghKGSO~TV zn{~|qiI}o15|$iHHkS!e!U#&Dq!rtl$yjV*k(|Y=ptjVEcaZ?IarsHO>t_`Y<{OpQ zPXU$$&0lcq{_rtQT7VwT-8y>}xL*Zu^_pY-2fDrNWPu7WLcphH+MAcsPaOwrd@jB)lPMCo{NHGD zj_QMCki=*sjpW5HY^URhb$V*It4gux+EOP@19*Ypp(LeShR|6ZWv13)TFZo};Q*W1 z?4AW}5dAh;tni7oI05R>h=ks__K}HO9=F9-Z5uJ`euMDp%}ea9nlyNoi}LYq3}wST zrB_$AAQLB3IAq15hLt}kiTP(yUw!uZ&-bJ4WN1v(x6Q26=2Kolb_?1##dfgi#_NWW z?Yo#R1X4}O4U#Qy{1=<|iXChrbVWbTD$AgKi^Gm1=o5Ls2p&jpRAfjyW|UI5laMxz zwN<{URb8VM$;Ul-u3F zvpH+5%@xq(VSYc3qw+Hz0~%^dgPbeKkQqIsT(J#6Qko0mLK5;Q*tNpv-H72nwx%|J zukN>Lkyli_IyDy#<3DdslBW?XpWA+WzMxGSCNq^6O6!Mwio}g(8&`=Xz6@pWZEG!!M zMHgJAk3gaphyRtC0XweqTB)vnj!YTz7s%o3b4@l#(Q~KhS4p)#(~&iJE*=af8O8_^ z8Z;}nXdUSJ$8LDZT0CV4Qn=#h4}DUf_keNnkvyBAE2BQbIJMua`@3~G5rb=*VL4=BkYF07&L zv1y%6J<+@))A_u~c@k}he|D#TC$Jv|-BF||&#YK%6iC(*fY;i^YLg6RVy;wXD9-%@ zT4?E}qu-hkf)Rc@;-g>8d)3OzvRlvY%=uV~vo@)v_4|%#@)Jz9?5cW__oH<*m#uA) z8eG1879q5Dk7U{HLU96PLF1XYbjafOPgRx#9S66+>an9Fhz7R+uz{eQoLt-Sx9aUi zJD;e9_H&oBg~MQ#Y&sDexn08rM~j$(B=Ap~60&Htqi-Lv$+5uLy!d67?W)Epd%d<6$o5jP=>tkIogM3akHO{2TEXhyazT6T+isR92{E7#-o3nSidYy`# zB(iUYtFd!NS`BID5Jwf0hSTU#l+fM(v?-qm-5)d^3D^~MdRiO^Jc4ttEqIq`bIfub zf$5JS)zAtid}-kwK|ozy8sl zkYucNg>u1F2ow5C=s?)Bx+MWJX@CS*)=fPkv@E@|UavK*G0=A8=NjyLz`SoK_1q=9 z_kJe16a16*Aoz}&x1IJ#BRm7i-gw;DPvnhBmBNy=5i4*-n^qDs>6%G3tNdD}%tINq z?+-zxr&b&xzkyAO*oi1i5A$<}Yg!j}pbU;RWF~e~L;uXYywE9KUmLzGGQ*oCGxdYh zEAbU9;|uxHIb14qOJCLb=DGg7uJah=_VSU%dkgXJ#P9)Py*BfY74=4^p9k4iLGZzW zKwNFxTyv01wuAJGSJ5mA3x>SKG2bhWH|gIKfq?=0)m~X;%U<)keeSeFm+*F)CO8{|HG`|)9cTB> zG`Ju46X}z}BTrc@=yadr66%;SW@bI?&YApDJ6bWu2=BzppjaNJnwYNqf54q7Vy zSW2P*w@ue~NXg{Tv11~S(EB+Wnd906bcScO2Tp-bTjH@&bBK3BEu|2S?S$a@)70yCtwygi+?JZwh+rE2=GiVC$k{GQ`WJDm9+W<&(8 z$+opLTu>3wDd*@2Xl-@PGie%%5km4KFg@QQ$gqhJozE){1vp5ZzIwW_fOah9SJ<9) zgEo9wM_Hnuysy&x`CXgk7nKCd0ASH@i36bvI0Iswr&|5k{3ShIez~HM)na0bu7cC6 z-K_9yVQb%_bU?2cYMrxlf^%bVdjQjE8O4ntcqs`IZ=pt*K7WKu;~~qqv-*~oIGncR zdsIh{6tl&3BH%sI^tfO8mc8&YP6~Ntd8eFc-NIfxA~K%Ay*%@Kqf=)Xb7ArGnef<_ z{sZ#zpE{Cju~!OO?STDLfwi!DLj!VhGK*gem9i-g$RYSO_@TLy09S9xV7q$i5^Ztq zH#8L?q~Xla0Sl~?Y3|;(c!4EI_gQ^J(x8m}nmcdP?>g%xoY5;6veMZSy=PLR+R`To z%90$$+ek@Q57>Kz5w)PhuCp%!%zi}cUeGIS3E6h?UlA>Rt zUBI9WPG~kPALso2Q(3%T`&VP9a;H&^jn2Pu;uA|J3{hn}ko)_yut>YU6kPW=4eEfd zyULZ7>N@xyG+w^eDt0!GnG??L{GiK2rKy2ZG}Re8YLyY_Z?Gjw4_+3t1cy&$Yx2H6 z!@CnGB|O_!58%t~{CGFLNu$}sQ#Y4&H?k1&P5h@f=cEGN(*8wbjoXyr`ukd!jgAb0Zh`uca(6z%p8KT zPA*S*;R!**9s{oLsp{tA$#0D6*S*ioEx#ma5$9DRFj}WL)oWGDUu$x#{<%)Cf!!EX z$znxoA62{;q{?e#w&Zd!cJFLa$!xaYUM4LK^doy0(a*ldjEJ zGQz3eOJdnm0T=kI(MaG0FUGD_CQ@NbEEWh>e>>q*#Fdn_f+5)S{4Q}e<*LcWFi>R{3fC1W!(`7(75Ju{o{vYU~e=MSYrA!YnlGG z{JARtD@-q^>CC>xT;kx)Gzm8a+1G*T`)ndlW)GS&GUs}eaQ|oeVbdkmnc;ju#?Cpt z9(uHt3S8@Y3SQ4TKqW4}ulOHy#cmAaE%^X$^dDo!LZs{xgI zK-ydXB{>rQQ(VHZ3ezYwwAhZ=8cJkJvFUWi%tgRmav(f8G^Hy4$HlAYgFid?6XXb= zz(+&|?}Kry0u9KtDdef>DIt`)^#`rr=5m?&;QG%GI+I7MeemPf-T2>cwl;Q_4cs}r z^l!ji#;jA;pt5Sv-}biye%tc##;B)qmWIravddVqgc?L9L^Hn^hSC(79IL8l>6ta? zUe|;#2VY2u%;fIb6oQ)CJnnYi{5dQ1u=wg&t^De80xE2itJT1-@oX91;MYrSwvrTM zkNkj=qrRHKmjqL$(XGq%CEF9V&A%pypN~_pWeZI~3X}+xk-ZX7!eluz#>Gsc!asR* zd#pUtQzL8-`&6P03FykuXiqSFQH->4RIt8t*yoelA5VdD21eLZeY!D)9|gn#vDmX;_2c?g0^#lEd!*h`dSL#;W2KOmUM`p%;E|`=>@)~u z-?X$ZXz5#nwIb3p*QbyP03Tus7}zhFT1V`2_!saRw}pqWGMtBvt+d8EiEPaIScVm= z`m=RWbc80e%ITp7AH0NBVvPR4R#wkqmi`UUSE#IhN1kFJvV|OG(|ul3p)==2XNYz)i&`Qn>ho4n8Rf#Q4B&jIasbzP zq{lHZ_IGpq>gw*E9uXnqYT)phd(9a$PVf%zKg`imjWMj9*UHKyCvkD&*v78=ET;TF z62Yq4W~}P0>%7*2aRQJ+p;mPsBtV=Dn*Cqm7(@cL}C>nlFQZ!=&+!e0V()gGyRY3v z@0c`hx~=EDnSXwxDXCsP%TFyA7$I#x`qTi->LiR5}d z)Gj$w%+ON*!c)L>h8|7m0a%2x(WWf0ykKZ+dx3s+P@m zUB-P~mKb7P&=BSmd(9cEIaU+iPFJG|N=)pEs!=s%KvW2xjQ`!gt&2Tcdv!gyi6S`sQwwC3H4$aj)e?Z_x$^x7n)Hnr{o-A;N)ZO3 zg<5ps38MH`W>Hd!m?`?c8TY?SgoJ;;i8tQxCD1cVu0pxn0{(0D15QNa6|N;~Ktcd$ z`G(El1O01c5TAue^Gx*gervmTbk!sYh9)B5#1_o`IK(|Y9%+}hY}$bIbp*)^iEWaS z=lC2WS~22yJCK(}dY^{(HuT3o|A6tjMo%*}9$*?~iGzK4S@U=sq*geuNEeu7UCa@5 zfnS_-!^bBT9l$svx;+Or)_yaxsp`0G-emacc~w^}{7}Qeb+C3)rQPexgf2D9Yf1gb zagEplfsh`AR6n7f#7gCFZatriXj)eJ%=wv^JQts~T|eqRUvn2|WpSii%x8gqS31e| zAC(OiwN?^ft~@pIeA5tM;-9IMedri;ES9aDmxn^^f(ZPGf!W)_oM7N5eUKyBqFA4} zxFzx%t)57fwdrVVE|qn2n7nNy$c#1A2Hef6_)N4RNh674X@9aokJEIGNz^IBszjMo zvHwi&dNF5HGn-@Pc`>C$u3w?`Sy^L=?3b0#GD<$a9>J}hb^3*Noi*hnufP}0-D;KL z0lYRkdmX}D{v?^2w)$Dft4^v!F?g#a%XT|Mh&9j zp185$!l6>re#c%~5JzBoc8WWG!KW6^aJr%?ad(3^eC0Yrc)36TBvYd)N-u%;5d78e zXf7iIAAA%}1_vV(B9x6joRRlDw{ccyIA^IA>u}Q*)EvWL@Y+{-+Hq$pa6h0!hZOUX zkcHViiYL-SJ8<=kg{8M$!}BHlM7)EPc27cdK!+rwQLhag|98&f=hG zY85;~-uao|#f2TyeTq4YKX?5<(#jFR?vB3d@WN7w8$!$W+J!70?KI)wgM3K;*xbfX zDu+PnI@1d%5?W7V+G0wm#L2G9>0e_AT>?uSF#xmBsHV?HxHS&Y%&gy5xv}x_$>uA6 z-@p7QIWUmE4fnjb?uRV=EEbZwhn~RxPU1TEwdBEz3;UKvtm~sfu4+7F#idOb*fP=SmK$FB z5awba`-c$|!z@}c3#n9(QZElNwAghnWYnroF3_(w%p`ZfORR+zC4J>Feo8sv-r(bi zdr6NVp4i+r7tAB{J0o7bn;_jX5W0rdb$^7kJmKm`?O8L=MN1Yd7ETM45;3PFimP-@ zYKCeOfHX4u5_;;1kswzr1Wn(}4~li3gyw&J=1~l__A*52^=FmE;h&krOar!M?=yEH zvQ#1oA6CQUH;tG=}sO`R0(Qmso2LXz5H>-gd!UDW|wg5uQx zcSnM^kP=OjHA=A>PihbmzLrKtdd|#|tN=VR*fO~4-a0!3&VQU~1rtbdWpkf4hR${S zo>^iZF491c59ncW#5FC(OS{5n&Mo;wj$*u2LdY>hDu=3cadyY4xwJtCp-e2#SaOBQ zVd|LBD(PxeCKcg5KMCd4QqwGFaWZn5ue(ssX*Gxh8S}jAoN)Rtu`>7ol{>I(_|L0XXqW9c{aX~6D>TY z%CBf`h!$Y6-_fJoSJSDbW@3e5@Ou`kEd(rsZfxVXTbaL3nmC_A#|*rkbJ#!Mx1>zm z68Y|9BkR9L_9wlqOmHWIi`enoQl%K$g~-&|6QFL^(!DJM&BkD%Wo3X;CR+s-ghTGI zRb&RqciBB%v_-mni7H3NP@5+AM1_QY%Y(#qgj{C`vzfWYh@u<-)Ti2@OQEM4=Oq%R z7!s(Zr4HjLj{h_7^2h9V({l{Ds(WSQ5)_5o*8G_t>$EmES#Q=v{2QXnfL(vFF8Q!( z^}TQ;F3@_p8=}jev8zuG>TWEvdFkd~|2iU5qpMZ2WX;aO(Yw_f*0P%@H)K{P@N`HS z-N1-xm64^lvQM=Y7l*|zWHpFks|Pe?`yN31KWRB&D3 ztOoC9J??hq&jL46)SfY?B+Udd>?vLHKO$X26YEUxnpLL@nc`__U=E+p%qtE9hU6Lb zbT3g(QpF+IvUH-X>sZYZ$E}}j2KRKoo76W(>Fw}-$@9nwfDlxsAf%o7k~mC4MOx!n zE~>Z7lyBYQRpuZDcgR_q6s-IadRRkI0q0tyZlOhkGor+d3qVBa9OGRkvguJ&hmSNv z7Hi~KOca3oz0_Ly>}`MNH>v(;FM#gFPWkxBQyF1x67Ap+?YOK+3wBh|Odjdv;i5cz zl7LJjWzU`n81NieWty6VtBpf!EU^-I(5Y%rsD0C1g|z>DyeSp#Jw0Ut%Z7%AHb3rX z{r8j;-wl}2ljY#+O3`~{qi_Mk|RSxVAOw0=hq9_1NxeRJ?9I`7|Ea?rm@5`pV{%V_8zH0 zdK)6&zjtZD(})^4-b@OSbUdG&w!Cph+x$&VF%HAeSRXdN_m26e9I!gcY7av#l;^)M z8)MdcL6Dh^7@V)vk=!qH3nMKG2P6e$){(mOa%D%;6)m$G#~>?Y`IT;~dAyC<@(T~f zL4sX5vGOS&JhXlcy#+QV*x;Wk)tLPXp<#-DOi#aD?E3SM+g)l1h8ei8AqYbXMuy+7 z4#;I?!T45U1_WJpl*R-0^Wn>S>j zN+~X95x;4zaIqzgSur?51&G!w&S!RnscQ*wtbCKUE#|RCo6IrErVtsp0E|EY4O{-- zjP$u%JK@?SJ^{gTN0VhHh~SItjt>K-Q+o;wHTCv7DOpJqx&8x2a`cBvVtHt)<#ocs zqd+?A@9Bhumx4LUvibOYznqL0h$Pq$fnYY(*wL{;p^W=u!|%q!R%VVcR5s4D_%RyC zbB7|h7q}H6?v5nYF)cV6XS4ga;GnowDL&!8_NG@qH5_w~dE{!tryf1)&TWPYwMdfD zkve&-V2~AarfrTYx#ea9URI{G{47^jy#l~~(fFr=H?qYg@PpAM+Zn(2^c_-G?QY#} zPsfHFNl|cD5p1fpHfCP8Br-!mbO6oe|NczclOw#z{Xh_P!^hjPw*dPs0+X7}Y%am! zy+R#J(!|j+aC3H?#2M$Lq0-UQOWC24Tf7v*XsO(>v&=bwCw3S|6`0e!#12g;uALNF z`0^tKdz+^Z^jyDheia^r%P>tz&m;O`nt4^?1t^)RzxMqQhfT_}6N@o__+^XXNcNA*b~4{|FAb`;hHJ$keQ#LQky~X6$?xk_bJg? zNDi#NDlq-$f2(>Mb;BO5g++a=&_~wC!P;WMG|~stMNXEEd#je#gQjwu4Mh<%u|0qAm5_DW8Ovho+5Frxs|D%dVJ1k$Es7_0cB@mnIiYHmb zeq{2t{g3WEPd~Wpo?tgDcRdGBmO))T6C~FBeMOCX(pfLJ^8FXxAv{YeBkMHqWyvty+zzqUERe+{hPY0 z_xRQ%_Gk<(1!eBRTjPZrK0p-oOrlcJT#?s1UIGRwgDA02>%!}84rT@OX-f!B`RyM^ zV3cKLgz}`|S{!xC=fp8phVllko&uyczg+BBKUlsYzE>SoX}nBAb>8epNp%CaiQ!+1 zlmu$r5+4=?445$31sNu0%=%Al-XDu^V&`x!W)3naiog1l)ofF2m}5fs`Sz@;a?-Gr zZsa(HXfC_?(O?wNx0dFflRvAF5FaT_?oZFX*{BObFfsi;gWP zRn^ziX&u0fT(!@c6+Yn!mAGRI(Tr-;DWRNKV8l_zIwWr%!DkodW=_g8(aMq?$r}@I zC@`4x1x_}A`!gi}ej<=P{wBw_>`%HZ7)+_FT%HE$K3e z@v<)0$(6F^VrW!wGrg{!EUohd5lc*?;XD4i<9x57x4^Id{Fd+HgyH4d@K|{-P-8mi zQ-wZFX26sm98iQglo9$B3+9*g36Y#qm|=Q-W(@Kt_zytcdmDP@IFIT1MvG8H;41|5Gl$*2NMI!b`4Qbo^0yrhO@g)Hw9BxJl0b3Mf#WeXF zJ&f-Ea?(pQ%h1BeWnF?566w0eu+_QBQ+E=J;ng*e(Ve;Rc!jgH=&1pipZ?bN+Wo(Y z$JrD7H2p?%>IC?lt}h2IK)!>Xq9V)YvdxoQhDW6Po(qsS=_Q2Y7lR=f@)ng^=|bbv z|5Q*6+z8*FC)Rt1s>BvsK2~`g#iV6bHTIcI8!Q_i4W9U#Ae;qBirbx6O&7HR6X&GC&VOy3{h-bOi`2lBbF1s>u3W`D~Z-NfT+b-h-D) zCkT?KrNwN2+%1}8uW+`!?ECz3*@s2AA)B^HEGCw5phrUb3_5|kR|^oQ4aycTCqV&- zsA(NH#XuZg=zRywjJs5O5zif?XC~#vyK-#qJ z`I$Y1qBy`14*-c)nw#@wme8mC@R+fBbd|7D04BuCOHbF_zW3gL*S?Ds_sJ{)oI7Nu zSyO^12L*ujxlt~)kqZzEPgl;K<$74P3FF59+zng zLA`ddJ#IO1TfYZ!Z@51NG}{EBEyj)pp$h(MSkOfVc+bLJJv|hU-Xwz#&HKL@Ettl0 zA!2L_S+0cx#`i)2hRgMtsLEw1X!SmAZBZl68n7J(BWE+_`1I6T1cvFj8w1CpWYn|A zKa=1_ujcb&{``LLcynyU#eXpv(t{Z zPLWOZ=1@|Bpd6m^`_ge!g@8`wxFcsf^W%Ga+Bvlx2a2wPKV7ssS6@R2!Cp5z;tT}n z2b{D3Cl6RjLjO!2(+|_%jZinJ6wi`6R100)b?ew?=zq44CR(5tn#CAjtRkgZLf9u` z>AVj{^Cy$5i`wz3=KmT%TEz6_^G_QZ+WU%Me$+sUwM3}DP@+gA70!j3w1@ncIv8yh z7ntto*D2;D1s=ic2Wif}ZVyM!8>EF6w}Z=KJiQfz){ zm9um{@Gc+&)^n79$+P+y<+^g@gKyJ)Ju|08B3zwNQY>{R^5-nJnkBZWXwo?KdbXdqgAD| zISq}n{rMMhX6QwsEbnD**F%DCSAFfM@r=m!_qaj>Zf|>jSE(Csc$;}~z3!40 z#THC+Q_G7giAgGl9PC{b6>Kin5!ajj#^x+VRKpm|g3kVANM$G}j&ms*AM9@yRR#uVCbhF6B1UTtl@H?1 zZ#bcr`7b#7=i5Y$Co>1ShUqvec(=oz&2a zT5Nhx{wP77S2*>9ou@w29|+#wA9C+6oBW=e+TLF;4jzGR#IvT2@fhy)=IL!pocVIFiUSm_8h3b;Vff$mNKVyn z8q6+=pQV$aXKLYI(JDcy#x*>Dr90Af5-!$b>5476#Eu*MT^T72h`zrE1f`o@_$pXQ zWCEOS_&~S`C$06n@v*VQ5@gpi{H|IhVh}uicu%vcBVdRepJ}4bS7x@~rLNu`lG7iZ zg6-&~ykG5iX?kNsa(Zsy{s>A<<@*M2e4s}Cp%w(l9&*6Tx7HR-#=1@RBi;J`R5H>@ zAF8c$p9)?^-6r3r+gHcAJ#D#=njzx^qW*?(+kXPi^r15^LS^!GX(CmbJC9|B-a}ZN zHULwT1pI=5*Oxjc2$7I`JkuHpL{wBZ5yJX+s&t}XJX0Jn2%cs6cqYK;y6))DkCx%E zR?BWNSt@xSTYS@vr-E@Y1PXx(A3p6aWKr3V-|FgFaiQz2RuVf zeskM9UHe==e0;Q;i|d1{+B|PY?vB&JMMdTXtFkec_+lu_)9hAtqR(nlFb>(3IUkRZ z^s7_#8X{#B6NUBC^Jov~PgNUuTn?yg55!g{um#=LJj`RPs?UaCP-Bq_Z~7fXai{xS zb>H?74SF1`tJXIA0lgEladNQ3vZL)ze{pH9c&>59V4X{je zx8wPIPtdI`3;@&UL!K7w0W_K$2_4x9%J=HMzTp&j(Dvfake&DE-g_+}`%3Hj*q_z= zE?+0LF=60mR25>0t);wIxx=gD)bvLZpNfb&y&$OO01kP>qU25kKwK`z5o`Kc&0X+i|zX$E7?y zo1nk%I;h+3xXldY$hs_H8bg@%+QGhAE?^eXZBLSW;Y&2Yy#3Xbeh{!gZN3Snhen8O z!IEDQgd`#=5Iy34L)6L>Iv}XzEZIYsTH!cq$jK1aFBQ5-Vu>^29bF*$WEpJHpnbKV zonP%CgoIq}EMyam_B|8EfoP|dxzPsFao--t;&UX|C)4A0{)X~jJM-Z&@7*I9P2gry z3}|!DCCgIpU-#eIDAKlkXG}>rTZ+5Atrqct-->Yw>sF|hr-;F8)(pL6_T8qVgfk+D zNe6NMQVYc+V6Hy#pVUT&7V0218d8LEuOxcamMGV@i7+$H9oD11E>%rFHCn=ns*_U- zeF}BSa&RbepWtYC{5%c4i$c&gJ`Fv{F+Ngc%dx+&9UW8oHni+3lKC~$j8Vm}ZmCH5 z&mSd6#(9ySst^4JJF0I{9^4lfE${O>lt8z`bHZjXAHmYoa15Dv0gx7MJnXv-VIxS> z4`Yw=tY@AUtM5WcHr~bsAI|)DXiL)bvZRXfWe#V4f5~rDA@CxK=D(i_G9#-yJqa#=!vv%?X|g+rxhf`t}bQBVSZn?cOWDe*KS)rj-IP zFnhQY$Ii76X3A}0@;!u2hKZz`tCqJOxXby|B4UzZrddyTy9;k znm^XO3pvx96$J{}QKlJvhT*`1MV+#_`>)7o(PS_g^cUgH`LvGUV$Yyzza9SBADkuT zw1Cd{!`D$N3r?29XU(Yi#7R32%{FN&x91yPRA4awU%nXOT&ob7 zLXl7EYAVQo@E2(EW6(D9rZJs7G-g+>zxT^KOb##}D_%B~d0G?H7-LgqfS9flb%V5GI{1P^UBp>OkZHABDx?5 zr|TSnJ5{z%{Gm|fH1;gQ{=+l7o*fJt+Vj+Z}*GDfTV1k_! zCEz?{_Yxs7U}8asVl3QzB^BT{fd<}B(`4H8)8bp$p%!yuMWFDP^rs%A5=(Z-tiUuY zU_kw;;9(y>Fb&oaETvr1!vBr-_)(ucEXgUNH$5O9K?Mys*rAqylD83ZiZs}WC<;YT z3mx6Sk8JooLt)!FhRK_VlEeq@ahsH{cqbWcQ=3L+dRSDh_dlGsaNg^wc}8yTex;qy z$%wJt-!rbrentL@`Anm-*@Q4bhioa{`s-#)TBi))E zn_9jEK3t;oW80!4?KtGfVWJMfvc-X>IUt=f&aZzJ@fgW~U6>t@@-OD0hAK=|LbRjo z0M7K{u)=#vB_c#at0(py8^I=S%)ls#m4eCJ%n&1&2ejXKBS$)c31HF zGj-=IF9V>3jt)r$UbWrKb#1JYVtzt{ofkhB$R0wd>6Ar1uj3h~_g0j_uG0C79L=B< zJ~1)%#WJJfeE-OYjOji@k!jm4US`T?w}c6gWQHI-28wmb4CYFHFul*!sF2S*Wl`Uu zKIW-uQWmGrQtFJ2!z=-d0r@EVNYIYevLm$9AZ|kF*z^mLHog4H_F>TA5cYMjufHkb zVyxKTB_j*(aF7hZQv}W*mbh9dL(Xqn;-EU#@JmN#U>FY|&#eq2ik)zNl=#i|Z*OOW za!+71B|Fwo_oE(zm<@br7_TX|2*Ngxwntv>!PRe#_TMLn`S87HgAVFY@Q2XBmcNw? z3*{ZbtZb$?(3lo60#~5brVsB6N(rt$U+TG(wcssJ$s|ePSQZW z*9qV*AeFBGa)hMf@9F#}Cg_b>L>*@LC9l6Gl9^N=d?oWIc`d`Xeh8P@tdQ{`Aj(BK zCEsDO`E5&0O2rkPxFkv0 z32hkWAOikhpk1rFL@UReIw5+YFtC6bBFnBdfzY-&!nJ&O=<)-k4nkKvoC2#^!JUzr zVQ&9Z)a54>1Hi`?Lly3URCnfrBDkGB+m+$SWp?mpmbD5#`8;K7v=Tn7;x#x+E(~^4FbR>FNx?LSa!v_-z=k9NO^dGW9IA}0081Da6nRW8 z7eJ3w!D8cZ3hc5|#=pcPbQ<2P;6SK2soB43-T&)^U%hU}ep)GXkdSHgujX+VKInbt zU~z|@#G3G>=R7{J#;0myCBT=pCN!k%b1-X@^NdeEkoj(l*y_b?)tS0BE>Xe~hUVbV zl0%0Yehk#MNiga@{3nZt;P4%(TYuW%$&Kh)GHT^fc_P!;%gFaNXwY9#pMjk6W68Iy z&)7!u6sMwBFXkKdGr&|HyjeEs_b&8ZE4K?jNdB0xsCxJ%;9ZjJk5NMV;3} zH9?{#r>uG4h)SB`7YC?JgU&r!)BllF1F2q2zXy&vPRr?#>A~x3MSp$TTBt@4qJ4ZQ zD#d3Ta$f?c{XfW?9$)z7NAs{1gc?K#_0G!G9>jxj#2jfMw`lig4(GPtpN^e z5lL7%!5`Ropr6RaTcC!oJ+uqeJ_q4Ua^HE=)MuebL2R})ziX1rC0yl>Olbq4qgYI` zZU-cJCzrQwkix&7V@NF%FvnY>C=fGEE;a{cZ2XOA&|UI5XyehWCvPopyEN0_#rt1p z`|`FR_p&C8_gh(VXNz!OENrtS-JVB(^oBRjApe~$=~eQXsNcdQP?*VV;0iseykBYw zhhI@Z(Ql~!+r7b8QktdfG*&F)COrijuEhf`j#@|Hl@*PWm9BnoMFYKM;D>h~1#bk?SnRB6r=pjPI0b7VZ zbUsfvOTpjnpKNc9W4NOYUB@9{0t;g6GTx)5|D)-ggZt{fF5aL)!^UdR*tTt_v2EM7 zZL_g$+g4-Se(&>}d1sPL{>n`5_ndS0UT5vkiXTc>rp{+LuWD_A|7{4kFqp8ij7EH3 zP+mu(=s4WR8mZ!jQO;YT~mdT zK5p3ghY2$RJ)Y_3I5)J43Nf!k>tx8K^z(56Ij>jR=%QeJ02oA?o?Q*j%_w_@hekMS zv?y0ZRoO2|-qhndx=!EN!!c-g(%eRovKCJ87AGbwf&&GkK`m`4zq12dO@#S#Hq8*d zPy%F2lPJy8fSBF)-F7!ppB{8q@#%CMpRf6i>wu`q?P*VJ#q6)@3X#|%@?~wW@A5ba z!UQUs?y=o(A+mH_ToWtDE8$F88RKzg{PBeYjaUjj2O&=eYw!*ZFt8{NM6-_x7?B0J zPd1AsvN;jSfEJaG!AIFyl#e})QpBVfLxU9bv*?s?iMTSJFWuTzkSK}JEglHWr#w- z8lJ3d*nuVh7;6Lap%-kF&@)p!Bn7jjiq*7vPC^7WH72qk<19IUQu=&8tOfr5^P;VJ z$=ih3&K!MyM#hBdZ8l-}1OPj%fAoKdk7cO{6RF>?XUOpX@3W{6MVxBF)L#FQpF8-x zRe5!jnQcwS-Wrp@$ZKK7bei~sCArhR-Fv+K*=OBmAHhv@+Cb-_n0V`cyc6pmc0R}* zC|kTmkd97Y1C_#efufZ)gXMkjVxxrV)eY<<#oZ{GW0?CIh^D9Blakx)d4+6e&9NV{QF=Yj>!6%@pDRy31WX~Tv66(gS{3V zY=a)3ORneM1Ce~krx$9QH?IV_rA4P>X(AFghw~Z>>CCY*7(Hjy)In^20of+BLLF5M z$%=RsjE28LI+;Xj&Yf8!0|l7iIeP>4aMLoeNzzzofiK&M<%sn7N!kg$G)%oml!`--r}S8-SRN_CEWh5Uklt`Gm!#uEL~0dG{Bzh^Z2#3X{I&EiAQ~ z+D)qMCoOJA4X(<1nl~K?6IzBLdFs;Cn)G+?gxbv%%ae4ozfho2dnjy+m^v0fZnL4G zTvaxi_W}Inr+%Ha%pCIW~xmn}^ie%ztO|;jCKb z_J989ONgO(-g{g}YcY2z)7lBs8;q<)kM_XG@}_<>&dwHuvJh=#D-s{*k#ifDJ~cMM z0*n;ae-Ye>= zWTf@PX5)+t%dIvoZ{pFrLo=+~{JP)Xe0K9faEmo*?!xgt`7;H=N*4_|)A5A$uvvYw z|J1$SpEy_}f}SNF+8m`Y&2oMGgKbsFj_Vw}G~VFHl7w=0nFC{$+1Zzt&mbIM$dp0va7S%P zDe7eFD^V1B^w2aSA}@v#tlBic2MM4@mBx^Vv&^T}!p<>g1&J?+MJwcb7|d1HU|Iq;;4 z?It?+58pT^3kc3w+mA9sHhXR^c?Ni;;BDL!X_qgO9iB9>ao=Nf9Bgh(g*?MAKX6^f zc%RO5`RtO(YP9p^6nmC3_ce-TkZVv$IXRocsYx_TqmMV$b_j^ZY|*v8W!v1<;dzoL zAn#GpQ0M&=^DBO)R6#NL?_u5mSJUa12yu}8;0=a$Z9^m30xC=5zl$Pb zq19JSE9ql+qg=1GTP{#brCDNHGlBF}AcS+;(wTps%W&49fxRC#i@>Jn-$0_Fz9;iK z6)dt>Kg^8TT4i>{hG4on zQ1#bUWV4u(Q)@P_S5+|UtrX9e&YCXK!%aS`W@}cpFz7f`jbzvkOS8Ca7~V~bGJ1bq z22OKl*$uNIeGWe-tRZ$!nOaup1|ex3`qi5n5D)^?N)Pw9hu9>8F$A zT=FJf&*i)cDPj{gY_z2p!-*xLfE?x|GDMIJXDwWo?(gqQ4Ur2LbevItse60AWe{s? zP7_4$nGm^YkEMwJ4Ul4qsRl>>Hm@iG44^dnoc(C!v~z|j5#U*V=Hl3a8KYsl$9Nn!^?X(QRqZOdCkDPv9=XB8C*H^__} zNjqOr=yM)^HzV|T;0aKh^Kz!`n!pJF_T6>0sdPN4Q|6r#`xe;SM>0L>@k} z-Pn!B>VW@1+k0#BzIHdO8tpj-f$djKix7)X^n^dJ0x}|$`|Wz}sGgHJpZm~%ZS~?k zRyaJsXuQAr!*s5h|v?HH?mV`wT{6~=1ZpQg(!u)l<@DtejHTVXhrsg2AzDr9pvI)C)J?< z!mcRBuWxb1Gyl1E>XU#OxXlUaR*>yL^@xlhCc>DO!V{#!B^uSK;p?T5_+8b{!d8tj zB+dcLTB@MLzbeo_?k7nM?p0ZQPHH?ivqL5G#3cS@J7ld1Z@wI#OAP5agdarBow`81 z)U5UJ^F`?3V5nx-z{)d-=JEyox4KHn6qul-z=}j9+9N$;lH|@)^DHCG z|G>r6wKa6IWu^>Fnf(r(Rt6|syU?F^FjoJ4=U3eE{Gt^_5&r0Xo4?M4CrLg`M(kUW z{{!tiW5dAF+Gs4SmL5j}T9N@Rk&wzXIl}Ngf4-|AkpxN|7G7-s>mBkG?-{E3ZZg}c zqhoiO*A+IZN4-LC5&PLAL`H{MhB446LD(#&>h-%QmTS;&osZLHOgy}!nNP}=_c=iv zk6W{7Zl_GT>oR!FaJ|*S^@&nz%%mcWV0`I#C$(Z8uUAb?K=u59y3>3JFn2wj-BWFf zI9SPK;|O6Q3MRPGkRB5ZU_!INY4OAp-21hSmDD?de1`&IpBU14X{U^+uO=s$d-r`| zvRRixEJ*VPX9a57$*d7<>|pV!w6S>A9BCLjSnnSjJUeZ3{(Iu|k=kF&edgL;5ocYf zI#_znpwv{p@`^VsH1(Ve+)o%k<#c>8RrMcXzk~ER62l2K?af*_%WG~(cqI*X3-8j1 z#QR3^Le17Fmrsbqq55M72i=mKshI z6UW%Lm}Grj_ZpmcGJ$JK=zPH|W7ResCC}se8s#2lq=KzmGznt>NV{kouQ%(hdt^vc z=8V+f-Y)KTHdkFdt8G$AB&9a)*A!L(EVPKI)Xsw}0B%2j)at*4H6PD*Wctm+&N)uA zHgb=K)8QyZ2VH<*PizUc|T0NfJg-ejn7}dtUwSLj5m9^|vz~wTa-^(K!WGZw! zXA~q3*$g*)q&hPSN@Um@1@6RwCL2{MC309z{IrYz$7U^?KT0>T01V@KCqWnzO(K^d49kCo9FB+P}DO;`-BAJ@aN(8cv%m8Icwii$eaXGam z`pC2FA-H}bN#q}-ljj$$`4Tu45YPg!x~VY<1DnYk$}lg3vi*LNGa)qmRtjk~RuS%2 zWuoM!s}0tG*+D#6SGD|tbv76%(^&h~9%h<1f=76h931<33 zBrZ~bJ7X%uCWA}MI|>Y?D1Ly*_+O* zO-T&l4cm{O!NGqE6|5Bt+Tax=8pfI?ph^LO109}RdM&ER0ZHr|_(iOznQxGLMD6TP zDQLZQ(kMcPq`bOB&0a!yLe1*tZ2t;Ug4PCX+RyD&sDfjE^A=<6M zI;z0)PBgYAL5!+bL~-)vKeU;h9%=g?+|5?|%zjHXY%!j@KNor>b%ph{0;Y~Jakht^ zD?^Pb37`}_c@10*6F(p!;uP>zC|Fj5mltJ-^Bw*yg~AoNO3w>fNTUcdVLO>O5>qM4 zQ)wtgxKUZWX;!oT9{U&5m2y35fXQezxL)1((n={+=-cf@WHc&khBN(qr6~B`OzCxL zf$3RpeH)(lEP(e4+=^pMO~_Kqks)Xu_pc~`cDu>oRHr2WrT{ZYEe-+<4dU|Z2J4R! z%D{kG{vW=}n6FHo0|fVMUZ(8pGd!*}2aVqfYbm(+Yt0B3hkj@oLC73abP1LkNut6} zcP#*8fDBENie`dQmHaL|dv4n=MR^L#yJnC_sdO~z&@>xmd>Qv$(^ zdOsx7b=oP77vee&WA~ZgU_Y<3BWarGA(mmWEPa%t?=42}$-YP1=rlO;0LXrU8;i*INo(M3kP$zi;rbh#k- z+}w!c7P>sY@xG7J2a~#c5fMR%r29|Bs)f_BR7+u0g7??9*EO%}&QrqKzu@S6yt1Zd zVu+R}mdH-nKmWr8EStQX=aapJC(9v#jO8tcI2=Baxq)OeCHBofAAZ?}06N7GDw) zF*ynsGen?_(J-$bE(WB>&hqfk;%rK-*i65Ijjnol&D2=mJ%EL@viD);g^OyU_ZfU# zrIf5pzg;@FAaaa8U z=3R31V&nNnMeAwgwb`aX7MW%S(e+HdX5)o?%CuY4W?B&cZO1BRvWia1o;}9n%FCB< zSsUnIU}d=+Mlyj9m;#H%gLsQx??lN#F6(E}r=>XeASa zyW4n&5-`D<4n3R(r)3@~kuvP$za#4**0O2zPomajO~vTz6_4JKb_utt>w8{-7x_&# z-Uc}Hp%AfMPOY&8c_##@Xm=f)v7FHxAPZ97wk8|Vv8kSr892%kT{y!Wy**vC;$iQ< zaaI5K0S!+CpOL5=82)1C^U(XL#w?$)Kr;8ja@kbVb*T%LnxUcV+A_wy{lO#4^MWE8 zttpsp?D@6z)_U1SxZb7Xm_}y0=jPSl#^dD-YL+fn0qf|Tp|N2dUrcU2MGz)XN{tVf zKqnnLhi}SUb_i2SMG^{Rd3-$f*$l9;M@&ul3DNl*;gLqee*=x?iS|6^xv%8yFqYBd z4o)mo^G73XjLmN7=54jtlalg9lsetxmIxp%hLtGN{$5rgC)9PmNXNDkmw&1(QD+Ec zFALf}b*;G0F~>v*tB*CA=uTZMM^iSiMH=*MNc0vTL84CuPA zk59sQdl%CD^|~kf6k{ArYhA2%A(r-0b_8YWH6ef!d)YM?pPWRsa}b^*I-I@Yjb0*8 zfOKYTvoP!@^Eh3B-q@I8$dsq(cZThFU!qWC&iH9f6Jk`YrQ&>`%lY-AAF)V)!sm0@ z)0fjd`)jY8X?W!_3NncZE6{J&JPuAteu0G>t&CGpcRh$o{5l-I+UJ52h_Dz|OU>CU zBh3Mnq-bDQT45EAKHev>VFvM)e)0kC6HbuvI_MAEaWLrP203E+NJQ;r@>WH+KNNyx z6@*i911J*2N=;o>bI#JnF^hJ0K)3cC5i=H&Nu9F6h#;C5I!eR@xm(V}x(!&TvmUW3XS~mZO zZx}f?hG8ta`>vT_1PEiLi=ewufsW)!!EB!5ttCYk1uTn3c5vT{2!JMsM_K_(%q%x4 zf7Sda1a-1`1e>!+*3xU3y#G7tg|i>rolyrR@o8%l1Lwn4W9yZjW7flNWcYvJ6Hy*dMjmStiPv4`%q zAJEqkzugOw-ulu?=&#y+DjE|hbMo2r;qV` zvMYo(XcwJT*K1!Nzqh0eCCu5Wnm<;KBf_LeXsL1;!(EsP8!34`@)?A5b(!|!y*+eu z{>9~Fyv3L66y7@1^9wUyFY7k%n_&b`awm64M}80K4^OH2{Wgm#P<+c~nrrzic7g9G zKR6{K57`yxf0|ageingO`YIO$Wl+wmnmZefN+%y0lP5+bmiL<$A(9%6 zH3oyJ$RdS|2RniCgAn{~a7IjM*Ry9Gvt!p{ikm)C{mY8+OXH6tgLJ}wn6Sv0nCobl zj;!Hq*GLVYYvro8Qwm&*u06GB}9e)x71>NIpvu zNX%(Xh|z(w6!v_Y?W*s7Kr_4NHA@J>X3FiG3#sRESK@!a4s=i5Oj%fIXY2es*@JsL zY*M!ODXF~(2=nN&XZ=sbVJ~zfQ<;88Fi&R@*&-TOD2|?#*T^(*wBK&!T!G=kd4-j= zw896Gs}5R`$s0yFHuT5u@jfT`eChYMu{D_X%J@V44JCa;krAc)g}T8+7Y7%gGs(Gm zF4ZljA?~ro)|$1BsYq+PL(8H)uW^XZD!)d!%GUYR^uJ3zkxW5yb2ALr7aVP#;eV#6 zmCV49_h!l;oR-~h;wT1dOTi#fh*{2yBhxjRDC>+r8HCPchW+ZOT3*nEY8TQJSEOh( zEnvw<+Whgyhih!Md2n6-fx!O)l4`Qq#y+05rxj(n2YdKPF^zx(2pE!L)>0`$3Sqo1 z@Oc~lbbq~SoESv<>+>U;#w8&=2@E2sX{OmV;~I{E5!Yx>p6&UjL=tj&oE^5QHV}_- z2Jv{5aYQi#FJqc<2Bl=V^2O3cv|6eftKRESQJ(IHw~&aq^=hWp4~YbiLsXwH)v+#x zqc@M$UV;s(0h?ge$0uR+qaP1#9Z zWcYNs+40nQb#U2!bqKgY_v&*#fKsp*hRyaL-_fF|XzIS{^c{;ifbPN%8J1(+27TcI z?i$L~ltHs0rmP985{>opq}zWX5C3EP?tIm1*w2@D=PKMOFKV%Q6G(>U0UBlBDu6SL z5jJea}&u^&xX3`jJ6pXhBQSR;+P>;OCI;efaE7_D7 zIebH>p z!RXsi23z6$Uc|su_qFE)X3f?O~n6EOe z*s{c_o?a#3K&P){n~%^3)S)I)0g1JU3#ToZb?E-U4;AUyVlx-(KE4q&Igsf9CJ`DM zT`U$e=hHmklqAKh>vhtrZ5oOBT!{g_Zffp~GH)EC)OnH6zV=7Y6%k#=Ud~z}TP2(E z#*XF*w*Phi?{p%22?A@dSn!v60TbZ%dr;@g6oc(AQotn5(SgHH7N1Aiegb|>-`Q^d z*@i4Q6Ui!uj<%|Xfr=+0kk&^_K}$d$3dIiw3Cs&QMKREtEu?z3)70<4HgkXDh8f!U|9-CzJjP zrB`rhX9V}q5lN8Gk>Vayb^pElu0416&R8b#&5+D7FElet^Z;kTIL%Hn|BUDF`A<>m zKqg>3j!AK)DPRl<@z>G3_u)a>yym_jF*Hx)E2DUSR~2Fm*BA!&$k1f9^TzY?emX=Wj^zE;?32;_IY-OD%^0DFalYA} z661YefWzaNnl}n(Okzx=wsbSDAuQOH;Ku@_sg_5_I!TK)vdE_m(CN!;i4ceVj#f;M z@)aTM8;6slxazy(I+yNa^_UJ;m-a`EgPGSNnpZjL4$ac|G3J z?Pt?>h>c=;CPx^K;84ID8qDinoMA-r91!XZ*&7*v8Jb%{AB}4Y%Y+eW8M){>+(b1R zZ)pkq0VNw9`{|Bxc9YK*oAEX6KPTLa<0bDxWD*Y)SCbhp4Ab1*2X7xi*u6sOxsCkd zVQ22Xx$|awUt3pMib<|lqRK6wj}b~3EIatK`Qz8yUO@*QHi9_qHHrxe;k#PHx@Dt& zw?t9qoY)PA2W7N>Zv1_jqD+~Q`#htSD}#X}M})AV_d#%uXmqSctj8EFm_rS{{9+Nm za8Z??0#X!Of%@7DuhJmUQGSfzw26G*D{@I?frm}E$9FS;?|0zFhecYARCmqDh~Ezb zMfjSw(PSi#b2g?^vOGFXuH0*_6t>gKz%wOAW@h2e*?otcHyi|>Xa391BOadjX`aZd zx0NtxqF}EHy86*ACu0$M=EXNp5^1?%8N-7_qE(b!wMZI}Ulnk*Lv!ZC6;v)_io)?f zL_~(zye*+lEZ=z|>50Vs8UKY2Zn|tyQv2s%PjM1?JUy1+b(@J8HnmY`I%% zOq*2}ZHixSAW4u*rROgHMT%C>iN)-+4mSMybFqZG=hwz11{taW)U*gtfj0Q_M zt-82|GeyUam2_zmPCyFDrx+K6;Xzr}14#`Kuq((bivvB@)5$+X5TcL|K{OK;iSM3~ zLt8Nikhh06-mHa=bDE>fKBy$(3yV#3Gxj(lqoQu!y1(8gCMK@qVmt#6l8kWOj|tGw z(8w;wK|{eZPoPPPP4?M)!K)%#Kdg^Mptb`HD=#Es%_A;Il**lqP0|y`P{Rl9ZeKiO zf(;n$aOO>!ma3f`_;%cB1O){P&BD*DTlCB-!}e0uD zaQ1N~I*s`s(@of2BB(9h~sa9Tubl6rC(t`Re=6sxFo+6Asd3CK!VfaDZ`LZWb|_) zDVRTgbGc8m4O*gtl$7*LMW;}`Jh6_eLo?UKn(psYN3*4MG8f8>R#v=C=Kw-d1nW09 z>`5T2bM(Mo)k16z#e%x3Kv^S`&n2DfHAm;r!L#OQWgK`Pkr5R$2<<(tALDZP=6SC! zTd0&{<~h=i%ivB>+y`^qK;wf1O$kB9GPPjuzOzooFn2Fs}VtTS_f~% zc_^Yl^J|<@HAC75!&-!}L)r<6KX_4-=tn(W6bAn>{3O=)s{>y)o~XP(P_uzW?ZF_U z5l@1gBMNQmbbqPwuF{CQ2!*Uj&fL}ji%yp|S2IPXeI7kSI;(<2l}HRVfKJt57CC{e zvUZVJsHnpn-VOx(KMIcUnVR>oU21Bo?rY~ zL|}3@o(L+gG1Ho7N?kI&u%e=3#&k(+KCq`5heuPWYy(>Xu380KH&>M$QIy{M*dPjI zAUiAg!yW1lgmudajF#6ST%=JDvCB<(wVfr^^ba=R0Nu*30(PfH%Ce$k`h92$!AMIIN`5HpN(RYl5 z-$svrwx9$UcyB#V`UD|C05ip6P3K`B7zAt!R-wF*ULEh@jcUfGiPR5;B->0>eJwt$ zh|W(E49vZJYjNKK9ANq0RzzMiPILA5=e%)7<8}x0KFj*_RKJf^*VNVZneg0UR&_r9 zH$!~{j%+fWKEpB3N;DMT{Rn{)9uN{;LFzXZLLcnhE{!u>el)}FK&ZJ~q)>KG6ai#; z03;3*lVj%$B?=HiLYhH+=m&_V@;~S*t~(wjwm30t<_frFa@8zkD&Z}DvI{2+Z8nK5 z*n6+I0OY*%mpm>_+-b$1)rSt&qR-2J%!(ba?-mOw8G$eFuZ~aNq~*m$5zuD`%ct*0S@Ge31QE4cX*;p>$4N~z{ zRczfwEsa=>vdh&O5W zcHD8}6aAL1L3eVhQyL@2ih>~g1h(<>wH_cq)-2tg*H7PGeQtgYoy=F?>?g*H)pd^c?2Boknrp$G^19w{aVvG#h1g8TnT@iS%g?0k5FppCI0R0j& z`n+J(HO<%xlXfC*=x5d0&g;%=a7WH@16BjppTxa*A*~M0Y^KxQ7Z7DJx^(=Bym{~w z*LKF#8Fj+MZy9rD%-8SV7EQWCvwlanpL05T0%b=<(Y*LgCxe95rx+BM4`F>470tCy zmzx8yD>s)?!udm}$E#d&9it-x8`Iagtiv=)6o|hFJ$AAg8>}~y<+3$8{jo7^x9#=x z6P%z`Gy19f>tofOjeQg(`-1(jk&%wEJ(Qo0gF~cDsqbmJauv%8NLBC(PLBGX@@Fzi}bx0A-hO)!zbLDTg7BAaQF1rVkUDUu4e|_C>F(mWPcd>+r=@d*;vL%Jm@w-(WdE%iLCRiIuc#f^#JHl$dtT#$E`S4y zWc30Gq~;oyVom6@RI*(*a}~ESs!5e;Y%Z-2dkj9tKO=~)Q72y!$fA@&Iknz<#w)h5sYRZm^co<_FmS1n zojAZ>a0J96Wp4WM>l?a%R2c^;WDAhb%S2w{?Tv&9a=qQds21eK_(PL_kKR~Osc@pR z+%kF2VEWz8koxV~0mPd|*R*e@V#y46)un6YmqsJfjNKsGFKd4`8B`LVHnBN>*_Q#FJoSXD!ic>$U4+;?Jf$mZFP!LRq-BF4b#M}fhNC0{ex z=isu7q_Q4&dkH73V7B+G8P8*F3~*Qgj$)`QpRc!<$?bRPp{EN@6Wh%`f6=a%8%>M( zQto9!sDNxC8H`}Zb}dleo(GTeHna39^`0d)ZEX@*s-n7-Nq;Ek5{L!$h`o_tsA@Lg zM*7?{*Bx*c8;veJk{Bk-OkCPT(m->ETM4wyDC7cz*ottzMFTpbG>vrQL51Iq!9a8gB?%qW2W!rHk2V-Ds&9dVV#Vzg+=1L#gi#HU@jUqQY z=_Khu!eZFc2tc)6z;B^tTx|v(QBv#)5`__#hXt$HvqdSK{xIyP z1oY@y+0Ulo+AvvQzcuy{zBxR6!C*hV(di7ROByjXTQ_G=imgRKkvlA;v@4~wvq{k3 zopNO#8AwauG>)c3G@MC?6AG^CE)(gwdKx+%CdyW&5?+d+gh&*Mha-XxJJGFW&a1l+ zoC4m1R)(dOF8cxdj&GH;oksS{kjNR(FmCWD(eWhEjYY(NBgPBGQ;1HhWbPk++Pgf? zcj8vi6WOJNmE8c#yg31h7=AC|;Jmeh+k`Ab#=!jRz~khqY!pjVfoG6Lb z3rxe&%=;R*W)wAx6w%|#$WKvoyxk_IF9?{GJaC7E)D?NM5_`Ey<>+TQuY_CH#oZ((OoNS*@ zw<=ECZ{jR1mugiSyo+g!YIGp0#!KoEEUz8dqLs`;7yyX7o{=$-ogYI&Bp6IWlvMjG z<4)u^ie&wtA71XXs?FTni6|Q7?v~cg_MN($_*7I%Kry^4=f@N+P6eeY)6En^sMVlN zGMnzXRkZ2~oE$MS3W13zWB=g=`;iIL%)*1mRMUvUZM_hN?`Fh-x3`_9Fl+R+!-o+z zwy2iS^}G$+O$rBE-ADrQwn#jT^`$#? zixX$&Y;@y#xX9v7>o{{k0v*1}Hl;$ll<5yO8zHaFeJa+C)wbOuG^kJx)9t~LZ`gy_ zPE+GiX*KS;&j{s@4@ia>ZUcxg-hl+HTv~OQ3ZyEM9BAHBBNsNN_<|)alN1Qyl>Eb zezx*ju(RvX+1*X1amu!;lE~~jY}CdRPxRr7n5PfRU27?` z76GKEoU<9D`V-~mM|BUO!>zS16D$x5I6=aqi8%5RoNo0f@B=ip)GC9>LHYP)naQ~E zAjdUo99C?@b+abmPRlXl4;}g3O$~?EVl-KW^mRX%y2&Pp1<3g#+Mb4m_#Tve$9=f^ zwoUJk1BM{`G@|G-8k(EFC+%DY4yQ(1i?=JhD4|B_b7{x_sULMMP^2-8C;? z*pS9a#0veC*Pv%;jGPrkR26EEQq}I`zQY>L>qocgu1(gYDO@zKgb58A!AbMJCFPZ< zRo(AJ;2G&h;GL-ceA78tTDK0`nIOKh+#I+kX;vL}uW|-a_2HK9N+YB5GneJepKPdTQ4L@@q*J*ZUDu~KPYeT2?OVBq zFm~CdNVLo0{1WMd(`4VdbB>zbqdUKJbUI=l6zG;_Jm0j~DrJ^r$p&7P&c@kAy;COA zS}>N>(M*y}tC&h@S#5FrW`l_qQEq7-%oFCsp#AzV`ey*IaGsPI+e$6ZI1$6Kkj?|u zh%X43Hm}*7k*TNQ_>Mw5v;{TL961+6q3p3u{Z^ON^+&`M{r6qt@dk!KP9fLHX1%g8 zSrpd|T$KGkz~>B*8O6=^O;_I^%%QV)AdRtec-SuU1bmLAkHkh}% zN3=DfZfg&+CI!u_i}nLinJ|v~RKMP-ROY}L)^ZX0p%P^oNk6h<7tbal*Q+Xx24)MQ-bb2e@>)Itc4m3YCO5;fwMl0h-1~d(F7+VUk(j`0>pt zWaKQFXoW_U6}nk|n1N)OlC~FaJx}AjJm~O4&C*;c%^k4Cyku=SA1Op-oOPa<$q49M zztvMnwISW4MC2PG{jhh5fDb~Xnyf-R6m@64639)|XTl+tL83w2He` zY+gTuzz779N4W_S?dlQyx+TD>gqT$b5vdS?XWTl=Wx)agV^$>r17mo)wtcL-z5 zK9VV{J}+!(&WzPeNri3=m^fMb$zK(^1g$`Uvn*HweOavgZm(Xt+Y)gUltRq3t=K!T zVd0P%@;2^$rmt!MG_j+C>*Yz`Lfh3M=2u+Nq=1HD35!@oSi%sr9*ET%)0x~@cR2q* z==}T(?kjHKk1n$}OfR;}d|!xzFmo$NIcs!kZy&y_Aj*^}NUXxo5dFpa?9- z2wG>i&zF>+pnWq2`j)1hDOq`X=d%`k84ppIzOzREh;w-d$78LG+bf}_X>~3nF>TQ- zKtlGcJ)7@>7^?8}og~sp$c78#H3V95Nu{N_x2C-n+X}mfDz_yK- zWfCpradyq?MvscJH%{L9N6#+23tQP|wm2PWZbAjY1%s&Hk)ywFLW1fqyPPy|KJ&9@ zM5a^ja>N%UQB3nZA<1tX$bQ~WyKQ@19_@$iIj%KYEstbQjtL~;v;I$hhB3{OBm47O zHK&?o!}w*M^p1#;wRsk}6l&6)19#MMQ>l?HsJl!`WaE9YY5l(&AvOiO{wN!uS}06Z zQu!Nsu|5pawe66dX4WgmE{piw>2GZTP-8#*@Px^}i%+Nr8dUTgBOa)}I^|y8dZKdTwF5o1G?Y>>T@j-_x1zgkQGBvgSUOK(MR)A%CQ1^ z#D#W|M=vRj(dTKp`mYO2de$!RfvrdkAhKgCpLyfq@U%fhGG;EYga&EX?$oJ>pqk6V zP+^VfgM;i{*J3vK4%^bS3{5^BuY!%@p~E52<$oqnyM(A$9{j-hnvn|{`6xm>iv;Qy zA$D&1?r5)@+HFW-L3yrw+Fx!}y7^h@pZQazCpN?@gge5DLl7`(Qskp$n}0q00X)C7 zkW$$zG3ZU91#S&Aar$;gCWsI%m(;m5pXq=GHLu1aO3T2`9=4R8VbkTNmH8p+b1%B@ zkHgCj^xj=F4%si?Q|P$5W7W@49wvAR5>SALy8=L_ANVT1z4?7QI^252u!&zkDf2u^ z4%vj5IZV&gEpX)ka!3PJZ+3v4zN*2=U zlPuY1x>5q=+64`#b&ZM`l=RNBRDiV9aT3NsO;NzvZhQ{TzoloY^jj#LS#^j0v#kuI}_%kOM<6Hz03u;^U#5Yq0y0 z{gWH7(&p?z4o76>+lg+gr+hPA@&Z<-l>^gA1MC@yzcfGFiZk|3NI52hACD6RVyZhb zvo=3UMCx)eeVIrb&1pJVE{nB76{Q)gIcyB-i4gSiwk_CyP$##?)}!Ys$z-uu@1-J9S!@u5AW3HeAnfj z&(t$;f1HTiABl4)??VgN^!dil8=-@C>J?sJKre;1&P<9Ammwv%d(IaPn8lV56za^Ts=l4+|&?g>+-=PjGaQ0fNsfk+guD-U0p=5g7N1=(5~ zeY{EIgn1JgMJhBsd!!L#X-jyLVp*)lN}D8%sl(?&&Wf zCwRBv3w+IcmF{4+hu_AIun_?pykXSJxtjh4!-$Xw1Y^XRA>LT^nxZn%1UNzQpblT_ zwRkOfVIXmjnsMl4u(9f;$|^0FYsgg971w}(tI%>}-NV4bF*dLQ1v6h__bUJ|`>N3j zVN9OMf*Gge%i0_0f7nupqREoqss*mx|Fz%?@uhPi;7ok#Ib+>q4cEAIg2~fZnfx>jB#O1N*eEYrHQoz+X9i_kzItbqAgaNGd*Mzuo`e3lO<0;6OMr z;QjnB<~KJ&9LZT*6C3s3dTUqYNn-qh%3m=m|P3OR!N85Jc*iIVT zR@2x?W2dp5G`4NqYMeB-ZQE93+uuCjTJKu-FPNEo=Dhaa=dnkg^m311P=t4Q2z595 zmhG1U(j7r3U6K^$2jN5>2bHzg)X?*NWcg52HGEs>8w_7-4etGt=-!tlZ#CTQUY~0`fz6ch$c? zhNvi)d?^ce&~u+5h+bzx0fj!=)+3}ZOYlxB9HqTeN+$v* z&C4(L_G)Qhj!+7U2O6lYlcb|f4i+vt2pfavCkGoPa@!|8qKTJ+h1$I3Pk$)+dC!Cr z&3$kembjc};{$&#;D>axO8qBqDv+2^;?KEaVP%avqSlP2T-I?+x)QkK)o(d0#yerlq^7Z0JmbNX5TsO3 ziW!3v4ez}9z+v8*j7W$$mGWNy;bIG+BwRuvK}P-SU(F*7agCA?W2{DoxJ;C-MmjV1 zpkf4@>~gjhirw&q>-9=A(f-R(&XGSfp}wJ^o@uZyy%6KD|Kna-V; z`#pr|LzjUQs8yiPM!XgYijuBsOh3*2&uyw1(-G%i`5*z*DjK4 z78H?SFj{9Sr4aVPu|Zw2et(go$!LVKFzj72{{i8HqVIn=`17*u&V~B|Gh6k0yJ()G zgITsvMl_~D?H82xf2Ps9@%CZ4_qWtol!RMzP=PD3ub@U{kQL$quj^qHDUzt(waDu5 zA#AwdIO+(GzgNv04)A)fbE#>Wnf>Q6+CWCS>~DQG!Z*xmb& ze91hCtTJi&O(3tZVEbm@-Ol-fsy}6M&4+gjRAe>e>0xTkv=7k_mH=ELQa-o1sc^Ce zTTl3KnQ$bzyjeEib3&($!4|l1eRYciiJ0i9#no>ij@ywdrnsTS;ffM#>=fTZumgK% z>R^e(tRoh{q6g98@+gqN#Es{fLyY~Fpvo``Scz+)K%a#TYDRKau~IB;_{E&NgqjHe zvu-?+t|f-_gi%2&tAI`0@ZaKh2m@6A-nx44X*m|+(}wHL-lTlM90IdQ$TF&!MV5d} zzTur?>48xCQP+yNMA~(CVb$+*Mxd1=4#|XDka} zzzd;!Wlu}vcMf4*_SNu%H;5La6|r!8-tbMr6b|RK$9LZ${+AisJ9<{zi0fhxs_Xr& z_6y{60Cix1+RTzJO0sMTjgs>F8;>P}ViMvL>X?q6mzkN_N^|wVoYK`iPvP)$++N-Y{GcXrJl~XIZG&?F8N~&g z5Vg>vm>cyeI~ascCMig?5Ha&oPIFk5nlIY=`A5`>n}UkjRc--A^(k)E$S(r^hz`3j z7K~u=pU+N`uza~UWpM+z+9W{83asDA! zUpr_zG{VsDwaW{a zMRk0NMJ@UXjzV0oZhS5vH=Hu?HrqA_fLDRV?8oPrEN`Ud{&6Xg&6shG{5Lqm-RGRg z>ktnjIW!W`=ef;O=MFQS8z2l@%N*!^uT@y0E4JaxaXNw_+*&R&&o%^;FM$HF3buY> zqh3?R&^CnqyAkLi$~5%pawTz+a4lrbn{|R`q;uW$b5YLs5*%-uep{&@G~mL=bPlbO z=!N4ZCwFP=(??t~W{?y%`xXc9ys;+RJCYn%r7DoW=vN>uZ2e$N=fo8}_zkTU*IXj= z}~Hmz_x9cFlisd>e1$VNm^461k9AU<$aTRE$w@dv%#x_g(9>D9#^_6DJjMauf4mCP6z+yul!2jP05p+Toaa?1mLJheJkh^?qE9nkr|C}4 zclYW2)Km(4`s=Ac2<5FvVW!KrOoEOg4a<6e$bw zuWVSsNMy!5&g=0CHF3W*)8^0RKOCG*6kS(t0%G)%R-58xb@eneLsC!q`7Kmf4HHA? z09a6R_MceNoQqHn@XaxkzrxMau%mTceYuIW-smszJ$}rDaX{jNV5^h95pb$HtohMl zfcXdJlk2cS5rrC@6sXZr0|uzcK<5HLT?P_=&#%kfQ#!7j zl4hkcu;ZL}6Si<*n3#~zkGWs1g$^i1a9JLxm);yJ74U*EfwS&O=-?lU4~bhl5bRmf4)gfP)se%oT&tVHa2LLTajlD1pny7H79mg32a^y zKFqVL6qFc&4JARHVS|M{*@OKV(A!B)hb81)8*_$yj|QYxAS)o5j$;wexnQUfzF}|a zi7ND`;cBMF3mZ~B8C`iI@1a>X#uS)0d6cg&sq??@6YXw)tyTXw3iHUw%ChkDPcePn zGAVnV(tuE=ogq^GqxkQ-@f%kTW^sm(94c-y4n2WHvJftboj368xB#{GZ8bsvsb*IG zC}1Zo^cBApSu?Xf&*7O^o%IEb-jMJ0m|4Eoc!gS0|Dx$T1rfPnj8!iKa9_X3UHqv~ zADA_kN-RAxd|Zv`xe65u;_(#_woF+Eu3$}u(U`ru6$wk*!w;cTj{<~2u_h1^3 z4(wP8l?v_K9>85`#7ZhAEZ`0?mrNNrhH#UT|Ko8xK6!@;`;2R#OG!ojz&27Sx6T?W z#OHO2+kUOwHgxbxC_1D-BI1wQ=L~z1@$!y=dCPBu1xHU@ae#Dqu|jK_%usgL9I{^* z^dO4KryL>yR8 zHvFzqeux^8N~8?qM4uo_4+=w@Yz7`Z$u&!l$@w?I!a0WoHkE)xzV9KTwtove1U1p> zmHp5T&I`B!T?QLy&&M=k3C4 zKXZF0Qtutipvn&-$LqDdW52514f?1|hF;q$)&RAL_4W{pMKXZXi>y>_zhs(y_PY?`M)Kj0W%G+8mu#T@%ijz}ot&?s1r*KN{(I!P+F2N9y4!G^ zz8f%#y*W)^{e+_|md_@cc(Q#ww5n({&yJ&0br~S?a%t*4I2ck8sQmF?$1|W72*f6> z-c3$Vvv94xn0c6Ehw`W+DC7@E(uzTWCi60%ArN6&k*!hf`}lhy=WCtJY9 z@OZ6Z4FdGBSWC#P9=}OAOa^}CcOwl3``-^TGO~B%?rZq>xvzKWXCa9MatI;8O4Z;| z$)O{r5>`-ZXvcT%(rRKrLsiRuWhTENdDn+r`AF7dx-V1F`V|6QW(IOpkOSl@E}+LZ3@YdbIaEOspyKc*`SpU-*6B zuFc%H-?oO;x?fdtydO0_caT5PPmYhdtmU*+D5Dlv0z+p)W2^Wl*Z7pHROMgEP?t*C zZ=mJmY^A&o?OrEvVhDJK;>pBY->TYM4~sK3w6pd{fv%cq>vL)AEVK~N#5ZKc>PovS z@2A~A?pN*GgVUdpxqpy1xhB*q;y}78!FF>?21UHiGcQfkXPZoknxX zcSH1SwF~swX@x#_h%J%hNxC@{Q~^SQ_QC3ZNT(*baja`B+Df|Q0nbB2a*t7DpA6gE zBJ*N1YEWbZ$}-;X2d?MN%x|J!PkYeS+5NcM%R*r03LV*`{kQ@9B_j46S$~uSVl`13 zWD*G5))&=cBsrGv%{^57FH{rLQ+5Z}Bo(9QG5y+vXCY3APWfp(S1rM#AIcL|Eb)o#`gP>16JPH0#hrjQ{PYSeGZ<^kZ~`nHmX7 z;nAwTQzokJj+xI1ARixF2E~bPx`|&>*piRKr>qI1Q+Fe|6g;C`(^7KNrO1GFLiq6Ks0i2;V1mswdnct0RS!p{vy@Br=(;xU(UPtYq zX}P&3R#pYpR)eDC<%?yzUr&IFqI`*`2KGZ8x9R7@0QqJatW>Obtdxo}+E1@tq`w%c z{*eQYQ`RPM@SuuGmo$-wpx|2->IF9)pK>jQ@dh^wY?Yc>vhli|hw2EA$3Ip)FNdL0 zSAJVEv@-v3Ovyf9-+E;C*Z(B{x`GQdywz%Km6Gt#(qs{6sRLvPQ;aVb?`}3cmqV_jwhWgPJ6_sjt|DY(tgY8 zj)0^HxpGLqvzHF1*B`*dI3n_OS|ZtwNa%fU|6hj>NJ`>xwNSN>kB2I8fuqy<@JUne z-I3kL6`2W)42W%qZZG!ayCpn?=Lixeu`Fo>^ze=2dM>KE=5H46wp|>6R9>VM@B30O z0DOBlA%O2ok85zSw6Z`GPfveDp zq!236+ReHkIdSU$T{HOhBK^UR(Rk2Ya zrIX1Z1xzDIp)Nt7wFIE2DV0f}JbT?~#n#(?fkL2>Q1mJCKHSeoMI+SLv- zZ#*uoGgAU!&isOk2)AA*F??ARadhg%0eDlpjnvVA2o}b{d}|(NN|Vb*cPSBo6ls?m zN6BK)OQpAgL)Wyr%Dt?c35hs_oj|^;^VFTGuT0};;FA+R8r?0fI^Tp!_VwV1|NOP; zc}Lt{_11OgIJLRGR^6^wZO%3W0s{si0k(mqNKRpyx_pyzE5l{a>u}zploS40a}-FMyL%ND2i;I zP=4O0YTk9*cKgw0*Ldquvsd@__8T(q@K>G9#8x)6U!t0cFB5chp3044pr?I1?4X&h zDC1NjPfPB)A~)xMV#m#BAFA+#H>9 z(8HZw361M+p43Lz^vE@4rdWC}XSVtcd&je66S;i-h;NT^L3}-bR04$Tr?Xva8|wPV zeDA0g|6=3f>l=1RRWIjtX=_nj>D99T{pGJ~Mx<}o$)$aTEsQw|7FkY(^}8XjYi6MC zgF!%2H;f#P203~3kmGA5*dQQ@U#^>?V)?AH3kxEBLM@{hCLRsKa$9d+XTwa_^dHgZ z_fOkT!tP<)YCP9^E_7S|J6ZsMV|-;3)X|ZzASz>QnAJn_F~Enhokih#{u8b$l-G&O zeVHVIrdCp6PM^8d^3RVeO@D@ipHDHpalawg>uT0lhMfI5&lT}YeP-Hka%$a*`{!D} zA#GfcF{)=!XOo782o>RQ?81$Mf?`(+Rafgv&^!bBB|QII`t&V)_qC&X%4FGm$xHP1 zv-9Vh_ZznNso~Z@a@S}BUL57fAqBR^8O#iAXkK_rh*tI-CoqELGi#^~t`0rGl920G zMWxJ~xTIm@9Ul4qD+$|+Gn(!mSh(~)&)5>G*By83R6=XiN^>eCI4!B;oE1TU~YR zcpQQye7z1`a=z^hG|4B984543r*98Gn>6GhVHQ@cT+uH5rI@MJ)`ef)I8+DuqQpO* zWX1YlN;Lxc!43zp3A5_-^cnk&f3-o)av(e=W`pwzb z`+4!@5pvfvwm84H-z*+GyFUdv8(8F}zv3+qt$HuW7T$0f?<<=m%OB5YF4v`- zS^KlQ+ACRy$CZ_rO``1A9|dZ=^?0qY{F%th?_ z4PhsWrJ^F}d@Z@vMoh86BVk&N0_60;#O2~vZM2!LO+0|)D|+}D=aUch%=6@{(X=c~0!R+c>xUzi;?LRJF9ZM)gWsc* z@V^}bpfgPTV%0I8_dJ;n{ZB)P{3paxAFq<7l|`PcDkMuA*u5X=a{j$f^?d&wyjF%~ zeROocepq4}fih1S$0_~9lw#R0Y<$8(b$V6>#&}9pVF~)-{pV3-ARdQ=-{Q{}E}1}G zjz${h2}dwoZYkrI+By6KFDQEHv0ob@3N?ymiP&Qmfy086c7e zlAuEDIw#eNHMP$bDr2fXD^xH+U`QkiWvQg>^BG^Vv@4|q#X3|c*?k{JE_g>T&W7HJ zzMALp-Sr(OU30#s9DkXGT;DQM>A7XAeO;RP+%|t@BHHHWn`a_*f=2%H<}jp!<6+^v z1bN}`SaG~-ar}`L{1f+SGkozv2p6rLy>pbdOd*I;yHZsW0``QBEx~;AD#W97ACI8MX$+so{b&n9?nvsSVa3fJhXi`WrA?!N8ep2Pxj@M}l z8VZX!kur?w>BK_VmX$lOt@|2C|DVuNeiU+;i=E%(*YPi6BD zhwoDzH}C*1CTUT$wN@caj_(b{R1V+x%r#0sICv==xf-pJ7JKwzk+VNU$FTmMaN#J3 z1*;zlO%+Gv86Toy7=4YK*%*sOLR~|Ra2}i2A+jxMp`=V+5}8_y$G{mlw5h7^<2#7; z4$l#;*U8B|Z)=h-!f1HYw)=-4%nypz4R&`UROzmb>IrklVG;M1Sm(sw*qZlU+N z#2z|IpSK>dKW@69OCMpzU9s|1Dcnba;n8b>jkDQc4{U!Wx=G6d!>2Sw#5Aw`W!aHL zc|Uo(OP#|qLsF8+DGVvvT#pcr$V9UAkrpf_*b~~YDqXP2YMOQUrnQyPxQOM?JZ;h# zLn|}O@&1sDB(ciL5hqw7vkSyZRJw76%s^9c_8tz54@mor;+Cp$;QadxG(QiQDVLP0 zmUG64pg@>cx}Vn$bK(tSsZp};1XxG)axx4P2o)%42qP~2jEmSC~4{xT?-O^zf69$w{2oCPga|v5RU_C33s2ftKV5RRQT96ZdQ^v zOt~x@d>G0EE-w@OlV9)Nk-qllZ}0G*n{6z<{~Q}9SGi0i_E9L#_7WU$Y6hF)KC1^DioWsy(&Y>xvceYX@|tMi_MZvCNLm*86PI#&^K`Y1EXbdGq~>#|w$f;c)%_gV4K#j> zhvkO}_&#b}dPLf9_Pzh?*M%@b7;CCMGGh_H5+mSD`i2{q7D_l&*-*R2p05sS9p}0k zt_T$$bi6{0mC7vt&M@RM8!Hg=Q6}FrLwqXmfm6&2v5C19dL<47?YDVjuEAyg#__lk z(?U*2;jt+AF+&K9EELFq&0P|8-~Cp?a{OJGgb-`ywH!}SfNiasizsFBxY-fwQVfx@rut*kQf8B1OuSnEN!y{deExUAtSIF?e+(E9 zjdip`katt3H8`mPcWbl{sF!v#I|`$s#Q7L=4L25cyM}60-Vf^Pfsr-DV7Wv58hIA`vSd#k>bQ+bUS?!UOMv%CqzNP-BsPs6bOB=o^5&ozLyd;)=Gp zM_HsbkM_CXTu>vH-RUP1V}mcH$_-JbLPg(KCwfIO?1=FBry|oHiA^B3Rl`x9CV@Bq zo0J!sw|QIF1pM!|A;ouFM^mFeMnA)A6{A>WVq)ju zJtw9Z^qq=f8lo*xZCjh(?m|ttFr?f~U9R%A5lWe=YCJu#V)@v#_pb8-MK@6j znEuVKz2?P|WI7v{2cJ7DKA6nmA>D6p;WOYD=;Uv)Dca%=>-61h_0*B4qb>A6`o`uh zBZl_{37@=@gim=sDVtav4IS0YA>4NOc7z9$H{c|iJYcX`JRCRQgfwI^X2G(qOY zxSMF$9c`5JDz=+!x-@(LMt{f4Ky{3?t$-?STvodtXFR+CGuR->@=jE8PwUMaEtmS7 z`-qYemNHZd!nmg#V`lN|_QhSN+Y@E6Zw&g;EqG%~G`!jj?Y?|*pz8%2l?OzvH#?+d zHmcQ+Ep-D_VQUzL#?ILQM9HAct94`|d*f1rmb2A(-;G0|B;ZMve^0UIp-whj*Vr@6 zG;fJMLq@ZQg*~o>Sw}q>XSc5oJshyKg<(#Hdp*t`5k{SRz75RU7KH)ZrixhhWxwXL z+33#oyle{v6p^mS#%jg#MWB@Rec{vJxp$!Nwg^23tM`cofQQ#H6dwLrSaYRS={11G zhL-7;4fko7|H@Jb+vNoVC5KrTo`~wbw5P9FWT$%jP87;1_NajA3r8m0UXxx1Il+#$*Tv3Z z7kunnAQ)sCWYXy!@bvxz`x#W44zakz#qOhGugX_~rj{TyHKsF6Sb3wHXx)DF5Zs2> zE{@6PCerIsnFs)tdyNJJX5;fl{i0bRbTGg?3pQHWex^N5DFBYFLoJNlvMcn$3TOa2 zKtuv(&!e7m%l&(Y;;-N8IeG(4n`fuJ)xU)EI=T=o>J`cxaR@qB7Hlcz-Un}x=6`1D zwhv0jAB=MK&nosZsF<&z3fLRocMZx{u0O`ac5%!(<3FfhW@)+hX8Zh(xpf1z zsLY->H9{S)qe&ItYDNg@MM;!B4rgMn(0{?4L?#%Jw&~N+4%&sSPz~)vpEjhTIV{O3 z@wpP!3N!+xyE@x^SkM9$aTw0jDYN_2jz zIeU(Zibg#EM~cSZJB}~txILuD1cWye1ULRr?T(kuvQ-8P62o91E{B65M$6zM|a>)Zf_3sAX5Qzu$oIQuPTlQ?_jB{f|VD?0EJ`7SamQP)z8 zwq93kMd7509I-oCI+~Lv4lkhEPp9~~&HXQfU+%1~(@>TbVTFM|^ie+pbNj0q5_$N< zJB%PonnWMIUZ)2VjRqD;)|v@OaR8k-SWeh*T^k*(0Sdb%h@M_>1-`aAFc?}8ZTNhH zXKZJL_^1e1jPfsb_9~W?1$ronC-O9~h*+ZopN!2tNeL9bTR2M?1s|@^FP}oZ__Zuk zL?HO=%vrF*!kOgPgc_|&tpB6{GRPJfQ1HX{3Kjv**%X4n=@Cfiixhw_4>lgTVM-b^ zYm!`CgT=%6OQN~msZ8t;o4OfE#rq%4oHVJ$N@o-oT8vG9o=>BNvQS~kE9sRv{@cK5 z+hlwKc5JBcvWz{Pqt^Ds0$@=pF&{a)ggvgn(?-h{pBicvXs7>Gmp!a~2|pD%p`j3i zK}*E*g!*I0r>-=gPqtw6K^ZUUKG1zJ6gR>ci+-db|9m!xCzA! zjlnh51O0{TO=TSGGP*QAYePRE0jnNm0f?FGBIg$2Q6eBA+fR48-d))G5YXhU{?=uO zQb**7X2C9C?(Z+%rIn%!n#Cru*Y!d=TGtcV{$k#n@>G=gwej=*yX#e>-uLiwa{F%< z&Nw+~M#jUWk@c9;j_kCxvvWct^rb7m(M|DPaB_3{o;Y&dHcvzk90pa&mO0_V_kiBP zR$tOTkLBOJKHL(&9&X$TPvBMF$A^DJlOGHt)0sM;n&slCbNriZrvI+s{nP~jCzR@Q z+O!4c4ey5xC~eE?yy|*a&9Ks1U7_PlQu}q!z+ovFAs1~8q(r5tNe@b+d7AL>!uOxk z^j%@GUc!O8{+lb~MFrE3v~-4E8)fJi1i zY9Tc9TMZYjBjR|CUj<{7BehlK>Zk=f8F=#ttB&luRZ*9C<1#p)X=UDi;ENE+xU|fy}Lq89|eqX@)^Y| zsww2Nnj}SyC-A*C<)eG=IAeh-Qpvjv9A-8~`*Cym%O~1cM=R!WXh9Uc&l0G4vbho) zM+%yb^)*jo3lttrOaVy}76nPbX|(IUi0S5jUj9EHo(1Rwe1GTle7YQLvcBxNlS>H+ z#W66@VXmzqZe@*K@w4{7(9h+JNnZ=Td^5l%@GI+X2fxj+|4g4p=7i{h9G0aX7zyqe z#He+|wtOe4h~*8NMMG%u4`s&d?n+WczzFQ({eaRMY`XF9tHXacgdBGM&)6(wVyg9g zVx$}vlTZn0(EjxorEkbCeQZF>Hy#oSiUL9y=KeEqWDI3V3Gt*ojOdeKVv@x5LMTbP z^cH39=}l z%l2pbai!i}OdL6?L0gU^OPw!D^+J9##`lKmiGkf8-%2WiJT6j%odu{t;<^gCb`7Fs z_qTnB6ZI+|%!x93({=J+C*bMd=j6$>tZ#>Pi#lDQJIfReF{FwM#o{}VRp87$;+p+z3?>?qW z_pL;5>$;Y?Zta6cMnxg25y@-#bd6jN!Dz|5iuhM+Fe}Zq?h=Ve+(ta zB8jmIqB$mFH#;*^(dzb*t*%@QSu*#WO+(MJ5`u$M<)j* zQk1)GWHC7|MYve)1v}5vq`?HMbUlmo9lOPEvcmc`Fy~5Blf9bp5o5^dZD2MAx(rpv z?wwFk$n7Q8)Z+icudJ`yaFnS+1ZNEjw2$xQZWuhr+Pc_fCEa%WMA_a#pAB{H?>;T< z9klV=ckrhH+bIXuN{CAojIGqCO4Pb<$OCuAHWVbq!Gb%gcWmNFJM3g$>EOe|z7Hnv ztKVB}@x?<(8oR%qBpAZIZDQQ4l1g__Gf<*?^;L&AJ3iPDw1qJ-|I{vY&=!XiK_svh z*(G~vF~(X|p$bmUsFg)MGAEolQ&+UwOBp3Y~1~n`v)#zxhO#EDR^~x9S|; z7y$$BC!m1>upz*{cLbnOAaYr5iPPSfju1jUSY6kUgzg8ZVq#+0jj2l%SC+O7tLiSB zalH2|S*;p&=Q8%NApR!HsD^aeWYHR$Lkqu;)wTx&I=bagR?;-GS)kVKYY!S*8P|sf z0aOwOp7OXABgR{N$4tkn8Bd-Ks<8e_PkFS+aNOBecPGjhEH!lt==o=K~w2` zYcC3FpnoZ~#Y{hCo}(Mb_*)6=6a#T#a1%xH)u-RiLt>gzjIn;)VXQYc1*C;*aLai- zoQUC^tVQUU0lH=IQ%XcE3xG?zn>kIpXt?eEN{ND}2 zxa2B%=5VYW5%#k}@vDi~yeeij&6L9R3;j+LLSDyz2)>VIdVBveksaTk?Ew^AK|#TP zUcZsCc>??eC8nNjJ*qD~^GXi#5HSxy(oyB59&YSTOG%tVdD=DZfZI0~{urMVlYzVs z@9LUpAsC?@O(#zhTuJ`xYIwQn2RIVQ7@`>)b`*;-a3T*7f!rgYL18aa@72-gd^fa| ziNRoD9SepXLk5NfB_)s=WA;fPs_NHF%HT_h4C{};_i#PIu4{z+#U6?9hraJ4jwJ?9 z{Kho$+{{t6TkyleDB}AAv)HYDXr9Onf9BZl%+P)x_0;L$FL#^%{bs*Vz{+c<@)r%{ z;RR~`&6TW3v^ow%FNd>!tPyQvyW2 zNrX|ai#n|(>u;dRDn#$n6E7zbL}6irEF6+kF&zwfjN$-MXXehe?17#S;w_{o?)Ue~ zE3&;X;~HUGue9qPUBj|4r!dTaI?^+=BzBCb>hL5m{g*sS|5{W@f(qA96e_GfERP&e zgoy`CT8IR@TDoYBqVim9Vsy>CO$?`dJAZ|QUV90Z5X@Rz!X1)IJ38}fB@_d^9Uxe^ zkeYH62vUSVD{J?GCW*VZf&>FE6LEATkpMBCke=D53S(i->DU@QDY9_J%-nDmxD_qy z&%(^9OCpOQ{2Tv?UXpj!cUr%X@HW^i9@zOxz|#`Jh=kOd>_)^gL!#=GB71tisw;vCs^Y&&n7k*gG$vV z;tdksvgi3XAbBof@SsJ{(N=YfAG+H5Gr+6oeS;T$-)P~?87M+}F$^~?=v^6MK2G`t z4@GCvrz;T$4-z;B<*5aG>g}IBp4T8-GOus!l*D;HYqP-Rbc|Bn{fL`$HFK$}vFjMv z8zjn}SxANs2!FJfX4Q3gYo*xP$SAJ9Fczz;6>$UVW^z5-K6u*5H)Xj~tj5t4_XCVk z%o=RN5b$T52 zr>(8m5hvlH|D=6y7iRno8AiCoi8>UQ!M@y9KxCjG*=0-mMrH|&E>Fw?Zl@!3pgbYj zq`Rncq9|9SU5_{@VEy79Ykd<`R3DKpOpIn(P-|10q`&?MTB3PTiYK313u%gnBx)9L zqcY&weOBw9#K}HMzS!W1zA(P)IW6M|$(xq@xyQGKD&)5Y8IKx)c_ZX8dsV8NUs;7v*GMKs8``-7^d{6)i z4V7HBX@}lDZ~FBMGHo z_H^=fO%+4P?LguYx!NK9Ujb;V-*&w&aJu@twK*=cuN2W9dGUvhoV-GY-nno)zcH%B zG+C#{zeC8`pD|fg2i>7H;H2}AlMe{bWnb6+^}M;_j|xnNCDaF=H=!3>!V>2v#kJ<` z2-i~x3x0Vs@nnT31yXd$7L4?Dkiqepa`Yl<)!P9bXX{3YE_fIc$$ew3;diuag51t= z=f}&mLhoUQa{mGDtXy=a9iQhHtKB4~%1NzO;h_)g<8ph`jaZ%1u4aF!Z}%9gy(XM=JJ*=cV8Ll8YyF_Sk`LTx<%bORme7eI)*`mubhlNsjugw|{LHM_RVF3oay4)&`U=#Ckr2 zG!Uonj?)rz3xh6Ih(!5_B8A7RkQ4LMyK-`guU8e>_kCtEWdgAXs!I!Gk%N7wXPfiN z=9TFiEOOP${Y~^qEWi?h%TDckA|vMUqi{ZFo)ROgo)*vxoWvHR z2qji7!ltQ#vge6pfbm^{u|O%f;owyBPMkm8fH+#1l1hvk!vRR^E7~@5eI6v<_r>vC zwh(+f>0(`8-;d}GLIEphN3QM;;PiOVJ1kX1*?Vz7U)%@bpF0Ae8zvp%}L6EO9&))`3F%>w|Jymq$JMk27&$ zpy1B#toO0%`x=}seZ7n}#`o(L7Ex@a3#YQL6>ulpjZh1w1P?~V9h7wQMgl3~Fh(*T z{dLUfHP*q~rD`Y~@IJKiztZcR$o{7TX=B8Xmo&7CpjBx~9#jQStwgHbZTdWDuNu91 zvv=vn0(T^kVy_!OG}F_Dbl<0?9fpS`#acr7cek`AI3bdP+X38D!vZUE;= z&mEX)@%Hz=PvzJ&s2=+{YDzE-OXZPTMhIO;cUoTu&CkQ#H?dsqx8yL-r)piol21$4 znWxcIItWmX^9;w??Qf`8Yp*}c;52gu$H4IjuL48GqEuKM>k-=d&0H_mYZ8{)dtdI* zAv9+8Kzx2E*QB-eG#EB;cX;q8&rv7WcrMGOsGS~!&^q;}C5r_r)sAckM~jMVxw_pX zFR!w&4=HuZ?YseJQPc8Cb>}c@g!q)nkrCzx(@X~vX<@p`8*SIk2ggpJT_Iy!nlq-q zDm&4f`1~H55RYwz0O5aGfV}0iIbGeY8BR4M%BUeWytEUXUnkj5RMlJ8Vg*hSIa|Ri zomd74q~Ro3`kgnpyr13^@jSCnykRPO1IHMAya_7198RFpQAi5hg5_zyhLS=(5MnTo z8$BnoZEBUY2BuSC0{T>>ZB6_E=#I9aF658EA;U~16O{2O!kv_495YFp8*d^Kh-fkJ zmO`0C*!}=Cy}=02!XfZMXqLbPXkU3Uu+$RaK;chKt_Hxue7T|l@GUsg%Xi~ zf%51F1v~?YA*#<8c}2Gma=ChOC4#;jK5-z5I{YBzL>ZFS?j2$(U|~!$GA_+jQy_;d zpw`03$|^Q|0M9R(Re_e?460u<273F+gK9)(ha-FagpQ?adDKeOYWR43qrUGW6VInt zciPWskpSf1Bop%IF_yQbJC}MMAUEZLVlZ50j(l1I79>85zkSj^^^Yfq z@1qPStjHmaV`_a8&PW;X5Yoyr>3FXNP$M6iFSkEK#&Tv*$-X+6W1|pve}0?TB`b}O z9?`>fp2pJylq% zV_3N4#LGdsy`K>4%VMRn?6&X6EQh7pc?=s59^ZBb64J)9Z1kQR;LvSo`@J6=V>BuakwPMD ziN5(ZPoB9|7h{_9_7L4B!&K5{2&d?!Y$OyhO~ZBWLz80Dh1k4imkH(+{y zftiCb^QT+Poj!*Y9)7O0VOPhEB93|tjSXG31zN{>)&Eq*v!hr`+@UQ*{brDV`p-kKxHIb9OPFEs~PuW)qmsQ483kbklWMeerSZW zY1P~0i&d5vR+v4t$iPsQtqy5fbebK!;QC3~bzR~(#&xr2kd%_+Cyw*z-#yCj{_gLxZ)P9D5)2Lv@|{op{<>}7NiYFmdR@e` zPoZzv4;OTCXyu|+11Ya%uZc@Q8pOdve3 zx70vr&5@f9kf@lIW}99w#3aSdYn9UnsT|s znRD}ujSSQ6L|BewtUAp6;u6Dy6@1SnjADj|2I+(mo^9hec4lO1+t-YMg)xRSedkH2 zw+$www6RaUN-7-~9D(G$Wv{zQhelMVle9=pif{Q0`c;bM0aRtEuiY+5fBa{$pM4s6 z@(t+qkn`sdFC9be+y%oUm|PBo$b2x~ZbC6O#*{F+gjPLL*=1@ZlJ#J&oo&`vAF&lPdr5&&HoNW^iB<$x2c?{A#bYvk&aull^2 z?p^&^qWSRX(}di%>HEBm%|T3(NzjrYrKB+#&>X*yT;9wDI~R8jr;GvpIy6l5%>YNXVdL=FKTPD#5?0T7|#RW$9nAh=$$hcB!(m^&12aO zgt*3~(2WIJf-qntBJN=pYIyp2#`hm$3TeQ>@o5=58HAX8q}1EIUfDNQ;Ni2Q3Rq{jQv`k+memU}XSf3={piL~G6T z)D*2&n_!1eFN)~(dhDDWXKrDUG;v5ZJn_S485jJ|C(rQL3WNXg~avQ<5k(lcvih|wMEqfU(^c=PmjFtG)oG3Y+=x+67s7Uj7n zLx1^g;+>N$-+zc)`O>#_8bx@y+;y=4*9dIugO`B579mWEDHNgAf%5f3&fN@j+6jK( zU!6tB`wVH>ByoKG1QI~6onW*kiBsI5fDkFh^wqzlh1#>3rHy{&by%!n;uz~=A3-lHV(QDVdvDghvpAo%F}?I0 z)_o75Yjc#I_*>|2nR`@;FSd@y0z$k$$kS6)ONy$`M4eednr_9+&+v!s`? z;_f6(&b3aGvvat1wg@&_W&MUiVu~fyM?ZyCTR;i{1H;H;Pa$4BhBY*V8J|QQxCImB z(K>y5j)ieBri{@gV%0;)F4c*E@ttLw^)BDq>u-I360H)P-1WhgIFF#kG7c4P$23-jo7y=m=V+{pZ=n zAdNxmx6FmE!@~RmsY;odnc*W3eS~tQ%<=!>k@ee(cRt5R%O?5AC!jn8=~_33RxVOr z3x=T*j15r_-3&1&PJvR${d>^QJ&!*20%D+qIB*D2$Yb4hGtq$qG}{S_Z@vMy+)L}+ z8OCmZfa>TlN(;Q7{v{g6en@$A98oNxY!^8^f?k+IIu543f;Bu&`ux+lufGC=Lzu8b z{^(t(Z~rBwP7@R45$$EF_ddkb{NF%M!o)PnbMW@x#hCLf?hSiLoB+obxC6s343%?KN5*;l>E|fs0zfc1GR#1w#L3fV@qHi95jd_#;0N@= z2;cJ%WGzRsuOzqGLCE<^nSX&2+t^rE^~kCp+3S(&Fj||8f4c|5Fl2IKf|W)S&vPi3 zHMQC@LxTmD>uqM|=NT-QdFiz`s18*!<3Mc~9;`4|TVi~)iX|bA6=S1STHPML>k{}L zQ550(@7`eWGBc4tAW3)cMV2b)cUbDX5cOz<+4kvGdCbe95!X4>I>mH(&w9s7qtQl# zl$f#cESn?*=9W9KhN|$=^T@NOVc$(y&;Jms)k58L7-8AyTrMkzaw(%c0Vao0IZ_>? z(jJA9P5D+Iqh01sH92?k46d8Q&-eAM-v-8LEL)N<6|PFQw7witD3w7Dm(ct~km^twF;2G)XWV+`{P^ZefL{T_Sv>{nT-0o7b^;zviv;ic%7^#B|%xNifUH$Qy4! z9Y2Tu#y7#T5&0bAuA^8Vz8`t?W`yTtDs3VL+aSDzlh3?Fq6D+^3l#DJ3(q~x4SRMm zUt8hnV=uCM_b!sNv)pmpQC4Q>dGob57@IkSD-Am;Bc!!On!ENh`H|1idi@oKZ#;^ZbH z6!JM1YKx4IkFip3Qp^Vo50+S5Zc!Z`#E}+Z5>pu{(G4SVeZimeRgX)qkfmi~)#f0` zqYmzP*HsCn70bQa6$1(AFM6Xz#?&M^dFhHkrj*pr6bMjLJCVEgAcO^4BRvORJ%xPk zNzC*N=AlnwCov}KqAEj|mz*^&#<(O=5u@waZiC60B0KgBu~O?Wdvcj}BgM~^@cc`Y zSHo_L>iFn`D z^BBT*(VzVBRW~3Z3|b8$MHeBjrU-_BRA9OZCQJ}H7jxzu`pG9TXU;&ej2JE=$420j zpF|E75v5|5d=k1Z+5lYOV`PlR_iPGofuX@lX3*Ea?1n2PKJoB_u8x8a_^l#UUfIX6(B(p zpz*~YRp@%})qP97cfY^o`$eBVM(z{;1IahO%*45Kkk2Djo1Q!Fr|1Nq13~V9(x+g5@>BGW_>0`$9UxNr^x4g zv~=js1q=`Nv#_*;6gHk~;rkvzkfGLSlkuI-MBHH8))g&7TE8E7UV0vV-^1@Xz>f?K zZY(!Akji!s_V=Sy8gAY)H9@6PWnyHA)k=kWvrT_*5AzF4_@0B(nir0pV0dVNg@q-G z#XOEBsW;m%PbP!``K_;F28J>3eTYl)dw3a0Az5iHUi3F(4E08xIEg9b3)mM#{9_$a zPby@bOD`|dDh6VNw1~FdgzOtcES!gYSDL2!`j=DI+Ec=8*^U~U#t1Mfc}b6jF_Jjy zA&z>m>?XETrdYD*?i(hK1oNj?I6pg!>*olv1>^-8ly<95@8FgdOSWlpXPzGS`YxOSjW zv`ibzxR}5G8`Q0Pk$2t*7ev-9+o9cV5r#2dkR?eHEGe)Zuj2vYZOA6RY0Yg{2vNI< zm%VR^nxYOm?bMbvIkEWNX`bJBu#)4~lRgy_ezDkzmk z3=9U-JAhnUd5Mq1tHBshMqM;va~y{~dv4{ofBSb>US4KqW`+kIcmOxPc$@ZRXC~6Q zh2F9Q>)EG}wHi8~>jW|_w9;?|R533`N*>UFV`Hjy^rMfX&z^&775is?2DxPtmKHI$ z-+}DOBYJxQjny5Hu4s5Q;^a6E2(!`iE-r|cuLn>I7nt-0nG8WDvmwn2Fw);cq7+-l zhfrFfR6- zVS%+qh%E)`Zlc#=B>qI+FMlW?uL$aP~iew zi0R1*k|btwY?MZ`iEUYEV_r%ogtU-H4q=Q&Z`poHO-`?bwrXKXn^YR8S6 zI?!+txll<4m1Gb?VY_8)r^?v2E+%&LvwXhB{Fzn4rpC_}5JJ$?--YeHIrXd6Y6~yu z!FJPnwm6Q_+Thq0vU5YN*XtNUa=BM7V{wGFk@+0keKC=G!R)|4F-v>P*vqec9alXP zV)9+xBopJ9{m-Dcjv{+EuZMhBo^3Z~v0TaW!Wx-;fmW?WtKK44a9CYfAYUxdYBh;N zMJ5-}Xhis4N-~77a2$&`(YUUMkQQ2}&cz!Ne{Vs_g)s)pv60q0Cn9^LU}|*)2GQ3K zCV9shwY^cSE>>~9cY;}_NoA2QQ6BYLfe_$l6grVW1*I=gbHYI2WA@yE2t!0?lKxuo zJ%{Dh@=N|cIXTIp=MK?owa6FpSkmIp|Nc+m_~tU!>*$#<0z`K=L?Jo|E*hg&MG(ut z>wV64vds#R4n!g9#4P6I3CzMG^48ms<3s318#y_F*s=|}a$rm3eRp(%OPbf?KjQ`& z;%0)d1yWkCOVZWulmM*iA;ivjMxdPhS+w>M7><;QQ{U)@b6`y$G#Q zameUE4-4ndl5uSo=Vqx^Ypj;bJbv&XJ-vP0;5xL=o?w2d!nwKgY~MD`gn{tHan!^O zRO}i0_P&dO-Xca?xbOWCs|TN|4a7jP_z??^O~ z?ye&3FiZ(x=K+vP++Mlt$GW0aHnW*wdl@oeBaa?NlzP#VTQJG%Zy0i3MxIg#L9tN4 z7=!yFM{0qDvrIlm#}|xTu|qOC#-ds$OzoT|4kM&3P_d@f2=Rh|%IX@HEzwF- zD>ornHq~oBX5I>VcsRSu)EK8!a!F4_jp$iTJrsVH^ix%mwoaA7f4<#3+}>^gHCiSb&9DSi~%?V$RPar>7Bv z{g_97h_M{x*eG&z5K-#J`Pc`*Xs{$3u?#*%b_$;|hk+4~(-Hyp*d>XX| zUXUkAG*YG|sO!ES>*jT7z)4+H&GA~eFoU@MjL2W0&gADNIsusdUAp| zPC&=Fwo7-`V`TRZ>Wvn)wPjji#LT(#WPOMEXP;tnY=|&1>^pFf@zF7sj-BG(JNKfG zzQFzi&oMT>6%n@>85+Z1T4bfzOaG^TgW8E>l(y|4$P{RdPm|rUjpW=cPX8dN1nQMk z3G2uq+^yRYVlVmmSYzHy54beBmN8WWm?K3Ax5=Hjr zTWKrB=-3v{9X~=ljOm}=0!c(HJ?78OvRZGlWpWJ1^*Ot+%Gq;sNGTW@8D^+dq+Bku zw6cohdW;VA<9Z%(5>snNxRxN73pS3q)@ktYavseuA`=3k4eZ$J(fKuU|e zTcn*dH@`s$f>-D}@a+utE4cT*9&APg3_6L@vZq{*_`we%W=|qpElf`za^@uRvF{`E zMNFxL+I1TyUrb%NRl@pYOeHx~l0(QC+o@nXH70g+Gj+qdX;K>qFeXO443T<0s8m|G zUUtJ`K8|A&rI1n}Z5xE3)ofx+L@xL0=0y^LEiHtB?*4?5UuC78rnKthSbM69c<71@ z`#RnhNbmLE54I^?0tu+Y- zS6Vb{bsT?!R;`T?1|y)lQo*vbgzbn%rA4NYp|ZS8kjWE9ZQ?M&&t_@WYPdl*EwMu5 zxEbOk!gD=@6c}wfq&X!fLI~opPOk7yh%jGC2n+)G(T^hY>pc_K6|dGIgrK}q!?E8P za=B61rqEq@?FFwf#9>0CoKWmNrg_9Wl?W7E^Z$)hV$po z^Mx;b0mpIJx^*i*`_n(mH-G8-FtfRwG%*(%=UqAs_ToII9g^(0af3`~?V@!tRf!TW zSIMycJrbHRdZmn6T0vx7Z5O{k2s34q$E*_sMW>`0@jww*q%)i#Z=ZB6nnB%*QzO>v2DuBOJwp{+RYYHy11@S z7^nAm)$vJjTo{19kt$EPV=+8}qEkQH(~Z#gBaS_fc>XYAd<&vlL7baGPi{e%N}X(lN}0BHh{Imu zuoug&VY?MD4nodgSs`)Ui{s28!~jCjN!Jaab%YQSA#$W?#@BwR)v6JNVhP7_P%0rw z(sN?l)`lNOyWK`5;VY7~3t?-pg(N|YnSC(vdJgM#TouT59!{##KtF#R z`<9)E?3E8suh+{;DL1a*Oh-||>Di3@6}m2#CRIvd?VKQLN7#-{94CbB5Ia9f?R*)> zHbk+aRcqpB^OTn=o#>j!+R`GqVu5O-g=5=v_4X3AV_g60H1K(QV895(+6rQzhu2fe z@J@zS3Sk6BT`@P@8aU9|}#u=M}r#9F0mlsG>Kkj9ghZq$j zmRI1+ahRM+m5~5roKD}wMSGoc{zzdeb?{t7Ay533ufoD2L?Pn#JCQrKV!iu5uv*JN zw*UYj07*naRBU9y2hRsfL3aImervK+j+^d_Yg@RT;8XwTCh6-RN#{HxQzK|?FiK-N zHuXvk*Y{~Pny5I&vK`9H6)anl#0jel%j8SlR9BbqIufN}D;g>5MJ2gZ9$X04=tLz$^ zB&TA|dRc~kL&ehJm z>T(%7OOM}=e2bdn)>WO>>+<69am2_dxIRK_>@&v@CypSW+lTQ3)I%RdWU|nzp|Uwl zhcT-pk4o|#x5xny3Q$C?aU6F6rSb^T#&J&*$9>p#8QVFH(Y;9P9MFqWK2kQ2vLDbG zlORNadaZ%&1Q%o_BH~VolVjUhmQ55zL}7z`;nMU;M%*HK?Gp%_U0drsaeDK!bH}pW zA+uC$KQp)V+$xsIy|*7})=G(7Ts)IcBhmVU05v$b9Z=yqyjJNiJ#{Mu6)E?AWn`{rmUR)6+vXo8`C@T(oYmG>1{U;BsRY zLZX5It6ITox6$j8?gF&xM<;beI|o7{GCu0rLzsO}W2!Yov4H(czliP_0MH+nva>aB)?s}UNe8tk{`^lY?#8HA}PZ5V927v(Tl`3A~ zQ!Cer+6lIsWo@NGCgam=wrEzH1cf|ni)&_&7u~rm zu8=sl+|C*n-Q$zUc027e%;X5&06UX~^XIU3-;O$Z2!K&pi7y!o2j_v(G&7r}S-mFWIh9?ETMRhDSTv$X8|p zVo8hP+&IDrR@#e%s(n$Nr!5@{ZWqJ(aSHC+qw}~?&nN{XVM;D0w<8C}kY`V(Ka3!Q z{O;EfwJP?=2uc44dSVLWco>~*Hgb1r8v){IU1=kON_qf;iU$Z=rb9kPvFsJJc90^E z?Ji?<9z+e>Sz&F-$IFdx7>Q_2r~c5|aKUc1T7+SP{(&m#1Jc2m2q9ivZk48L1yGbJ z@wjP^1OKpj98S#jFliMK7PNFiAZ;2ZNq>Y=QZ^C3uxRO+1_>S(O%tPm#Ap&gu>P7V z46T3brN{$c$LohgbpF|#IkKOkpP|dMxLSzBq&GD3Z-7psV>^xW&vbV^!dhXvW2w_uRsnFARsS)j~7b=M< z_7pqMu4|hZy%@IZQ0UQEb_SU&LEN+Pnec@HgE5+9Y8vbL16WZD zWtSk15VnV$TS1?kfw@JDuyB6*BalRhiAiK{2{Aqj7Kp(jVxa2+zo2)1rqOZJ$+;J7 zmTY@L8faQ4BLE{)L#RXn0wEx3hq(S0DytQwlqjXCuGaB$KDD(PNfP4+Hp}yKL4whOft~`BL%me$EuvMq)JG=CcJ~s^&EoZx5U$JV zg9n*8dYHo0HWH;N^ptRfMHIF+>>9*#fB9L{CPRMwZu*a(BiMci$&Q=eaKFUMp&FH0 zX)U6(BGw7EWzpmJ((U!WWf_UfMOv1WDnrq3VIO?~jvPXCmr(b=4|)7~44`k=jgc}f z%K*>{q}XWYUT;LYR4AobTdUGLFigIaVpA%j)ofuq9-il6jA3cCVcRJ+_UkW@ADq!TkWl+5s%kS8EOm?L1a`q zkrmKTF?q|StV7UgNle8=xI)l2387I~LekP{^dK~9!<~D*GF4rVrd~EAlAU%BmDwtP z@CSd&Z%q&K?@llB{`cR{op;PLvm$ zET65>Hx{$FT4QkF=8exRB-ZgGh&V>wbPI{PG*iZEt$`5^!^6W!Dfy#6`Xd0gY}rDo zr$ldGFS%Tf`S~n2-+b}!dH&PCLH76m^=0pev|Ze03win|`rIs9gMQ!x$e9yZ&prVI zBZ%=)tnFLV`ePD6cB&h$<4WK{0rbxA%)=V+&nXLiwyLZ=ZE&6M?iGy2tMz)Ai;k`)H%V ztULQ%MUlN%g-B17N-$DlNe7g|e)M~Yb2Csbqxas8+Iu(FlaGMofiRd-KWcmm$}8Y{ zh&V)e0XoQHRE)G7v`RX?6=s8YRI4?Fbm|xnugc!t_1%&7UvOpCf`Z1;scnFcl=ye00j!YEdf-$@lsW6?vLeS7L5`hwimP*K4 z4rLu8w82b!Dk&=>)va8O`;vaD&)_FH(*d+w&YKX~m8T?YX3)$<%%K1uv4lNC!^Om>Yh(KC6KWGF05XfX8#qL4#4 z>-zE60icqIryt%=S83?&9?BbrQVCi$*mcLQw|gj89F0oC^N$^8|LkEFmzMaEH3UW1r()`~Q#2Qnmq*!ooXr0Q2M{;0Ne!J25+NM*ALqa2DzHgYYg%AmcjTTCA5s z#ZipbVB3;LtwAR6SX-^4;s|Nklvk=ao<|gh)T?ds#SE)U%LG9d4X8N5^L>&y#&$fU zu+c{2dLAlHkhax%c9^%t|3-IuK9bI>5Q18*MmC#atz4y8%!8Zd+^JJMaL+wNj>qcS z3MWpU`Q#@)N@ZmUFxa-^QR+`!CZn*4Se<3%{2V7vJ&bXS3~YT51KS?BqB|gk zymmOm20HH9orspwF~YJ*-t~Uu`E!V~r(kddv_>ceb0=V74sp-Bk;QI!><5UMQ{eir z^9GXJ?m?V*0qe+NbWa~*+YP9JVRW;Oy|#?2ErQ8OkZ}K>+|LhZet6MnPOhEgOV59a z>EaX*|KdO3<8`thbY2A*7Z9kVxRDu&RN8PIwWk=Xd>;#i>SQ6#Mg!C;5k@;$mO+Rz zNqiG-u!6KSIw@j1XE3H8Si-i?pi~jdK7=s?VCqQAK_wZaRY8aWl0;zJ5n7iJqK1@t zEF2&tD?QfBuX3Gc@{DC)loT8oHVKxH zBqk*~Y4?ZO$b`I;dOsXt;TL?CR+stY?wk07Z+sVka;3u8zx^=fMuks*`lE02D6b7f zD&qL^saGWukoHo{R?gFv>82~_devp$5*Q1!wuWkkI6XzK=9=oa1NBN1$Gu9jNN*5v z)TVc!>xyc}UoG%54(BS%Jn`f~a@hN-)|J!xhA(I~A05DGv(b+ewcBjJd4hVig(W3% zqG(jA1o=GW&HUoWDs z4~#)r7V$mrLNptY%_E{V#>*h?_%Yjb35`2*z*A^|X3s32v4v?NL;Ao`G&A&Ca*q)tfU66qAYj}Q<-W6Ttm)kLWb(yAk+ zLa9L<_dHtVQE`mp9U*KF;W$STGKW?Q%dVqU327}NL?6bq5W+@?0gO2h^a37+5LXm1 zrj5X(Tl!!WdEss(Kza!_h=Ktkqi}_!ZekoP5;PSZ;TSt&4p`9(?f5w`pY89+ny_F9~+6XVkPYI2YW= zBNegSSf$_>-u6;W6SvX(_Ja*(tQ+B6a}k?26*5vd&UzowwS8LP)S|;s@W4aQ*Z-c8PEt zhgz+MV{IM-Aq19{ny<~w%nEal}jFgC&#tSzsQ>nf(#vh5&khd7GxgG{G)L0-`F;dXke z#6~drax&=BvXHh%b!m<*W5c+P#lqq;Kl;&QU1D9X>!M}V}BC(F9 zYV*;*`Y7Ms_OGy>egdS0ykQr~t#@NR^B7{^Q!p?H`2za>_oW$MBCSEqi!2ZV9=Qu1Bo}5sLZk46MQ9W;8W%~`LWIf(m;*pa!wq@~?A9^>B{-?iSd~_J!_nDbJN1>QyVq*9$8_Tth zYP&|1T-@xq+Ne9v*mq8vMCL7!1XHj#{HevA8Mp zvU~S#?zrO)KKK?W{OhhDr%u`vK$Iax?Dkcdd{A`vmOw9z-D6Gcy0@|$>uIpmib|({( zeqQJ*@z~>!GJk%F-tGd+Yc;yMdwB1I4-j}R7--jP8>6+)EYvx4y3F)&o~gkc6a6{H z`?J`c2V*whOE%w2sjp4{z!a@|o%t93hQr_fw+!F-AtrA9Bth}|MCGN}G|V%d|85Wt zoos%pqLg?5n1s;vs5WB!T#+yC`{E^k+au>5DiV#^|Y( zL}&+u!f}>~!tFTjd891UZf0@Z6R4yYX{}<}Euyds*INPxft9q^!vqLX2l}yff|1~f z9vodq$~+}(gn+E@=@l-BR4YjtgC)}JN5e$qgiFPQXp{at>%=69Mp%-XiExdeEeygK zl1^*6!H|$9P32J_I>Ui8sOf0Cs`iq2L;;5-R4XL)8U&Z#115zajG~LmIUp^6`tXN8%tH@7M3N*NKX#P6@41&R{-14*&2E;& z{ph=z`(DR>>0&qWPyRGU7=+OnweEy%gUOIKUBCG<)9WtYNusfBNf;)$u1&St!t-ou z)i!?Mpc0K`TX?P{jt$wIOOj|T>-9yquj7qjJ@Y6nxe)-(=F@qb7i<#IV&BE2G>#IS zo2O_sS{ufH^-7IQ;8R|!5``_K9WZz5EW&bW)hlTQzp#kIHhw0Lo6U0Uh39$ydmp4) zS)s4Dho!YTM~)m}@2$78wlITjyJ@d4VE@#8*Pb}bP)~-bp&UC#^9+}= z6tn3K%XWNFsy0vUG}rfAuREubc6`zsS(e%ac#Lj+dfZYmmuicxvgH z%U<_O=f1_S?D^%+4?Y7bL=TT5Mn+i=;s_z(rah3v%v6uO;{1i3 zVzzEYb(N4uo`+%&I1a}5F}VV|UO{H_5VkRn4VD8*8-tG!pjD=09;k_;wCpa9hFPCH zCGk4D9|TfHABS7gvMN1>lvSi4h^VA)A9B%jJ5gWHSMkN`-7kf^%hM zh55O8#wW%RLh#g6Pw|B>e1WH*{spF{zRj`Oog3@^u(6kSJ@O;eefM70cN(p*PM<<7 zFQWGB?ett4jCN5fL0XqjB+|Y}Hfr^gL}6KyC`_(<2_nLfHhITt42+{zY*5JC<27$Sbw;t;fyTJt#w0^@BWqkSCWfF*0^D%|?Y2hyGul z{pxJeg~37@6%U;-8~4EOyC9ChaS<*g?|lf7?@AS`dioJz6YjYm zV|$2d8J#OYvw;>M+if^=3Z}PUuPq=Re)(Oo_0oAz|pX<@IfK)wsz)!mWfm6%pD&GvLsLPi>lHfUW0qfx2{t>`qQPj&XX zK(wI%I);!DM!N_RBV>QU z!I*v=Qv(y=8Xu3e_oEMmlrG?*b%M6#Mz%s3llFAzn2fNglh7~`1>v%)+v{hRmPrss zQd)0jR|)2kA0i)oH}5q4`L_yvxn36QOBYGP+CpL@Usf@>H(PoONB0Ua64MSbLLglW zqauWT{ocC{As~sWSg&L9cC|qW2-{VTxY zKXQcLt`fJ!F*_#*(n-0#JThTfvZI)oJ`j%{J<3txRps^U$6E>8v1!$t z6nj!~A&^*3I%jbGEajDXrY9$OdjBCF-*>TT2tUt?8cR8$+F$4HtrjGsYtl(EFme+IEQN7C1a^fDk)uMTT|4pGQ-4E-X^ z!V==lDXgw;q~oH-CUO72KZ8VJTo-xA?U<1X#NU1ex_Zz$M(nx`GdzYk@dC!~_(Knj zV7g1NFbBN@nCcp2vfy}_xSdM+swmBZNRirx=yakUcN)=k?32W)v$Se%*5AhAG)5;x zauUm`f$%Uo#&TMyWEk6Cz_QyUv5)N@#;6{YtRSU}N_=c*5vBVPVi{L<6Gu7n&MHC- zQ8b#OPzaGDCqsl-H}Fxkv>^}{Akl|jKrbvIYYjxU$aM$g%SX{K(4Fbxe0A|P`(8ZT zWwV>Q!vVrdDg=I38=OH4241OUq??OFfh;H3ob8XtY}ti(N!z}{)71GHjK+q{Ca~y|ECMB8KTw!Cm!C^Y&WP&6~ zFvc)u+f=Jnx_ic`*XwAl$>l80pI^myJ)$t8IlD?%KH%`ec@}T7=l}p907*naRC@c; zQtU7a>F&|g&ce>;`MqXhXu!ulevp98Il8jFk_XmW=C__EvCwR?`4{XZbAF4HK_(lxvbAzWU^NwJt)sPeCW?@8{yeSn7^7~3EgD#&3}oO+FD zQm4=1k&eT+0uq?sirKOqqhf^RqA-a29)S0M1gdM8TmhNH=!ZUxv0PZ3M{mCoD{jN~ z8!+uQva*KuJgBU}nG;xRYp}M8dFVqZA+dh=9avg|LIHKpyP&5Rd;in0x{Mg?Lr>m- z?&*c{8gh9N)!UCQm5|cKm;_m^Kv$_VX44^DI-SHBgEmFb24h@wn5NYuHIep$193Fe zQNkKWhy-IS!qzypvqln6U^^=SB;hcQw?Mnqi|bXeos&eZ0o>py&Fs6!>d5lgQ$A!qEwL;44l7z1WAq1nv5$a)sT3CO@<#KL@vF@?AUBw9i z%Rzttdx(`~*tQ*R+5UEq=&FKJifkcEqt?QhkjiR{Y#~c|WrZMkahvbz@Y8u+g*8N?0oO@V*D$!v}i1 zIP&a1dizSKV#hZl2lq z75cNEVX?8nv%K1( zP$MlNGv(S zSge(6^!9fV)gz=2g}h6vrO6jIf3Jb>5GRTtNGH6T8JM^0w|f=AsFxMB3vxN0*|!g6 z45Phy`kEm_x9q0a(~FP}?M8z*eyNeGNDlwmYZhLvR70Mht#D+f!eY6_YAs~Pco%!N z^e|Ei=+1fg?ki7DP96ObCti3MD?h@>O&_OwY%h+N!_E9-Q!+4Ul@PWntj#_}bMX}C zPkfWC@8j4G`O-8ayFWp(yN?8y?f>Zk&eYGp_GSU!vN^c>SIOo3Xx5g<7lx@f7RY2v zv|ANCKey2Y?Ri<8|LgA<_%DA?lb5EmAN$L%vu*qct4n8a-GK7aiL`mz7#8LZ(>rt{ z=V$g4bWb95OnGgNkzF66xqOUV|4zC_ZzTu{bdTK1{uioz>)|=tq2>b*j&bkpgS1-> zv`)ujjJiCn?T$q4rrg=ZPLo0ij7pHUx8bQRlNeJiW4d~fQ3yc}F?$NJx`fQRsGc!Q zzJPe-yU6o%se0A;Bzj^B`&)mHD6fJLsO>v3d+)>g%6|jT!!#SP_g<3iJFp)60aoCn zqXaWLi5VJ!Cf@>cfNw{xST!y93TGWe|bg5d8t@gDYLw^#^~4}*=ztD zp;;S6sm-jfRc~Pb;5(R7FVXFHZTLN14wOQ>ptyUWhG@C6Hf+&ozYzxP6 zu^pRYCXelVWU^UQlHj;b#}F-*D1N&od9MYm6M*%MqDm69jn!rbnl#mRgvxOO1HUc#^i`^7!LVQpo4fgdmm6l1!)R%A~PdjTO55 z#kj0u;^GCIn5c1Ntj6q8o5fm(e9B>hCqrO0^vB=1EAE6v}Q|lNcGDYGs$-c)cWb_#}^jE3P9>sH76o&WUc4{QD z16avkJf}%^U7Ljnp-i+3AQLwNyg6ZU;fC2lde(KxrPD4g6bfM-=-|9^Z#DdKThw!tJ|}TdzYo zvLDWzLiF|$j%*+tS&K4u1}bIz{ysEAC+zBnP8*svWOrYbkRDkrAUua~*)LweCB=rK zXeg}~(y|CuK^R=bixwfsNcm~5MS`HUtN}?NrHi6i%Om$UQqujU2xUmMQ={W`2xas|l#OS} zTA7!B^6Ln{Y9qh?9b_1yY}DU;SNvGvRR@J6OWxj%G zDYRNPzU`sMG?wNf-gw~Y)SGqU$s~|5>Rr9mk0}tg5O$&*|wMH`KWAsSCg7-x&A= zTOa&QI*leqJb~x=WU?6oKOmFMpeQP)X`+aTD)Pf`GW_`B{O99*s=20VwA(EdMG%J2 zX}5`48kJfT-w!YijY_3PHWjDRXrKs5Dixz#u2CqYv26#_(n%*Z?6yxb6C((h19y`; zo*Q78+H#Zhe53P6d-`$kp+h8+`Q^RE1!#srBArFln`9N3H%(5RI7zG3V%M%+gr1Az zw4ZmpS5!<~jM;LBBcl~gP1UG09GV@UoojOJSevJqvB)P44E;sAm{Kxv_DROhJcgbf zAw75_sh+JQvi-!;FDwdvqapCyc%H}XGvAIpvf=pVo2V}5VP$M}s+?|((>JNUt`u=mtgpLhSAH_mhKU*G$Rj`dtftBc82FOMH> zF<855sDkFS%Ril@x2_XUP4tQzHg!%i-chs zA?j#)6W`0D>9d4kH-ZX^nncP1P(p|z5YZHb=tj!YvfsKw!~=`{*iAuR9R#x6!T-S{ z(5jLKcGO3qqK!^}3)k>2@(xg^y5;#7p38k4u z@?Bjt8#RzBR?MK)@~~niz85udG)>_9V3;O$yUMQHuDfb$ckMRc{run?aU_Ef(S}g(*oeai2sUmd$mL$JGy1ZJmXgw9m10ldO3Lp`;b%Y8;R|

    |l|cDYL3ND(`fPED!urt>&ZI=KF0rKhXJbP74Om={Iq;v1JP zqzo`!)O1=AJ@N>kE-R*rjE)an5?%z;pWlVHE`!tCN2)~CDwv%vN8(jSq30-}i%_~! z(QY^*#B@&NsAPHVfrQg-35{yQNm}~D0_CtdYP!O6F350QzyseS za=N1Qp`@2PW=xnc!A~*?@ea2ZpiZAC5QhmyVo*3QPb}+PM;@bALW*E4lChBas~|V0 zLg_8GBMP!CiEgglL`YU>m7Bum!s>EvGja>)Y6BHr<6b%_y|Q*^eC4_1@B+>B0*PaK zDL6qT>q$@7fq`9X*2k^c702cE;U{>JrKiO5f{oZ|$LLYf|%LE&y7c2^U z+;`fuqocQh4?^K6=qT0b%Yx~WtkPwysiwzJ8|HTwN)uKwY4;1>Y^T$iqQrNP>Fph=cW{g7L$;U8{L8>eK5J1Lev^UgSyN{ zcO%7c=JK?~m1c{(-th;w3+qSzS22C$51^+1=fC#SVc(;s58bV3@@-}Ozs2XaJB|2@ zYPv`QKzdG;n~pD-*jPdtX`Yvnv!&34$3^sXc{!5^K_G)ssC`nfm(C7lT|j+yMnM*0 zx*Q}qT}8dzZbJ&DEB#!vyl56T4by`rdq&j9I7{`FK4WXW82JAb)9<*$F2hh=0Drr< zXlgojJ4^Bk3dvyPsY9#t_ylP+$C!*KtHZP8W+J0&haoXt)O6z3CkOgX4&q&AOiC}x zDF~xalAm9e!t||CZhw1kI`P?|vqNXkrkpaen!_eF3Kb;Y;gt0^~mj)Nig^_`(Z4JqaHpu;XTb>+|2Qy1sYs zsz-Zb-0No6742Qcbp^M=tv4~JpRum=*2Hw7as>4ule&oMlD~L37OVE*)uG!DU)+A| zaQDVz*Pa2&`);-$j?!PS*94->*`PTF)TM=Gcjxxi-4!t=i`8n$-GRp(150jQ zXlH0AkWMU)B?$uqU2BNGvvWXW)!RE$0a{$eX2OXM;3^%MY;?(lK}+wAb&gy)Z;pe0 zb!Ypz{qKK)mQD)e#fvj9N_IMhq+FUekH$e%XL?7sw>S1WJK-+j&MW6-;t**sZrWSh z|N6jO5?&sD{q_Ej5BEkE(KZxLFX`mriNAMuuc+W{|Ke+0^}jxLuW)*H6EDRrCdRw* z$_MAJ*3I5GY2T!fBGT7MAqg43FFn2c7?^(b(}XjFr#^cIOuu~YohuhEe2G2%OPY|9 z>(XekG)|vCisV3lAAiJjFr6}EI32Cut?ApbjJKIxSzZ=~q==CNH#_zdJSf~r{2)v@ zAaj3z9;hhS+1-iqQXks&q8vO8n=vx3BJ@n=a z>CA(^HDt@d>B{P&lyqCvi#XItkI7APpd=S3ez8n&rn`GDTNdo&<1?N5QG#0{=XK&w zmp@G})bvPwY_y))gqJZRG@#lL=@1?2XwOTR40ci5>8P4w`&7TD^@p)1de+(!}^rG8Y2=}Jz=mj00P(8wvm z`DQV`pr%9PPdp-abmVk}=@gqjwE2yPgwv-!^aRfIBWqqGksLqE5m^1m^ShoFDP7UJ z0(CLPX!L#rT;D9_bcAuF@u}Ej6sU`>Mi?E1o(Ta~bfR65(8Zhn#AaDR&igr=pn)W~&8dO9#`zRAE(h^{cOjy&4Fob5o&Lp;q*0 zSz=jyFI>a0nMPh+tDG-nzr>@aS7Ml;y%9WKQ1CI7UXT}l(r>}Qo?S=4ba`p0>C7n7 zPM>OfnHKL<`_-nk^+D;p(95Tqlgm9PSW90)%#`gmnE4UY^NLg~v*^;>d)v3kr7 zm8oG_ae!f3Wty6o0R3Qp*l-D~y!-B!1tW%2NE(<7rtk5cwux6v0qKkxoAA86@=82i zS!Kt9W&n~cp(ZT6xupuycgmX_m?3=5x*4vna@U>1X9SutyujnzP}4bJc@a!+NMv36 zHrngdSlTUJr(b#IDEk+9aPa{B1Jv}fDTPu#iFj_b5Yp0yvn82MKW0)88-f~$UaUo) zE^q5!9M*wnysf;(e@Zs2n_ND~@2x+6+|ED}CL8(-kmBP~eFLRy`~5DD4;M-Y)A0&R z+tIs*jcid>qvYw#2n)(fD_tCs#cdzoGkVjWO(UM2@a%97E)yn<8NO-6rpE(UtO!g^ zL%1(biw{g)k=l`1N$v~i)OVF-001BWNklB zpg1?1odCHtUDTCg$-z2PehOQA88W&hDJ7{k*-(RJhVH7MKAst(Yf#gR?Jclja^Rx0 zWP<}?wm)6-l^@F(X#K;zT|N zphY&Hgb_!Cb$-UC2Ro_=Mcg9kMUu!Uk&L%pFXO;;=|g%aZAb;vhaerJ$+&TT93#TZ zgTnl>wq!`YT2VztEwa7#Eb8fQpNyU4g|r_Yi0K7PALFOg^q@S{bUTTenVr)LrWZtU zoBI07tjQFRicJn{I+mAd^hd+>a-XUpbs0X+(>JS?t_~Tq(}QE{<9vBpep!`dPuADc zgye6orcc5bvYM>&)vK4UUM`&8-OX-xqTY)6#)r}Uv0n(JBY`@Lf((jE-yH<@PC5x7 zV>W74q?cCHBi2;x4>_otAnduj`S>{Kn#L27{?F*;$F@h3(-&jv?mqS&l>YR`39TyY z<;$D>p9_?W@!}9@bp86-vx?C{@iW)Y@U!YrOfgaF(Xlc2_AD<9&p}P+#x?UIZOx4| z*NftGiFuKN(d`MxcvqpFhgWx^s&7A>u(A8td9kMVS&I)JZlX0PQuj?fFaLUz14}m# z4!%tFjmgbnCg$*f(DCTsb@rL02d>*;tr0c--GjxLz-j*jqr=4hLY)ZYZjPZ|^o@yj z)-ykmL2yQU@$`ApL9@!3ZjKDg4kZy#zp?(_`3E_U^X zSVHPA3a0ySPjM477 zdWlcRjegsl&eB4uAC(c34X6uy`$Os8_TGZ&!s+S(zsIR*UqI=iftI>n?UHlj`2%dQn78-Z{KG9Y~%2=2jJ;$EEV zmgz)hV?cUnFI|(X4ZUm>Hi$z~@pr07fpplr)TFDWjg_(219f@nd>_0P1zRs`pAEA z2=LK9*d{&j>$aE{fR&P-g-Dl?$YjYht>}E#x}s zLP{XG=;#vFh?b7)1bn%~)z4FK-k3A*|Iw%e8V^E)^VLDjII@+1t6(r+(pR$MLn4wRa{nK%2R2Nv*>kk0)?Dqo+o-0a>MjDQjL|!V z(1|e=PG5`otR6!$)8*mB_`>5(n*pX*wzlqy*zz$X9v*&TD~{Fh{w-VAj2=C8*RH}7 zv|uVIASbfF0Ly&aXQxj!ch$p=rwH!AJ}*_BSd%Fs&GQ@m zX`!AE12ZRJIw9#o?IT?x3ajf2A_9>>J;yyhZquH}J@@R{GkU^^5hI@Ue0;>Sn*-XVN52ho<29kJMSES}unseF5EyC>&I3{@@ zEaQOwuMENTANE!J>9ZSu|>*IxD5vDA;+T-;-W?Z9*ylg82ulsxmvU^=xXNaenM<0gz@CMfoFFkLgIL+D(k z`O`gxkK^dP9B$MJrt3{P^+n2Dqdlbdbn3w;*%1U89yofq3&H7QJgK|SlFEC!mh#M# z@Y^ucFQ_Ifa!VnYP5~)i7cr%`0O*=Cot<>_A?5C)Noy}JtT(0ydzqs0CXXIB+Aj-r zof=YFno3>l-*g0TKMcoW;y%nm#dx|4g?3h~7BwBCE7nof(uY)ZrKcxgLdT)reebcWhoe@5=}{P1wy!>kSN+(DXJGA{77OTJ zWxa6d5TdR1(9H`sS=a&YT4TD$(>c;Dz$Z9#d}w!XZ)D`0Xm@>6Rc^6OO}F-nZY|T0 z;-pMsJD9i>JL?@&yzFrgNJkTvm+gHvjwpe%c9V+RJ?#1Yx3zyOkbHl%oP4iPFr!QQ$&bn>o{E&qq%Vy$w zDR1Amk3Y_R6(^VLx+_+1Urk2Lv17k@@9PggJoaJv%a`AO@wZa&N(kbC9T)nb^aIqr z`q(3P3#TKdqXLh64UtlA5vFU%%ma1;fZ(_!bC1cxh3 zx0fWwXj1rd2|{Ud%XOklX$nV0>DfEh^;vh&1lG9z+MCC}USDl!WVeL0II?8g&Gtdl zPEWsh;~JQL`FFqD{|?sm66#8;u+VRl#!MQfd+RWZyCe70+ejWcge?MeN7fAn;ac0%3reK|W0O6IQr+dS_0e1BIr1%2d2GtSMfnoA~q}P%7 z!sv8F*{1mSp>-fV0NaZLe<$s<$*W>=;_e*ayxLH|#W1rj$`H!Dg*{U=OLdTGilDhR zY)dI2M7;p#m}|yE=qfs$-lsJ3NXjg!>8p`YArdQVEdHaGjhzzUk0psc9ntm@h8`Ww z?kqbWFJyklbZqHnCI(T4YNNA{y^dx`PWpUDJ>EWd6H^UG+eeJ@r9b)LkMO?WxS;P2 zn9g{ZSVlqe2Om@tx(4IGxuCjs5G`Hk8xq%iFLE31@nhB9NFGB5j&s#~REkICASo|4 zMO~s2XU+QYtT#4;?8Lkv%>P(?=_0gq6BKA=f(LXrb3v&6>0KDoIlT5X`nf3TPpgYc zRu|I?)uiHCkx&<5a!F8UE`gG+{55bogX+?!Uwa);m)1$5rzT(csy5@V)GUb<-MDk&XIpVlJI z;c25IDsx2CB#h&62x`-W$0e!b@o}R^ZyGTH=gSCwM$Z_%$z{Zh32S+{wEncxjzl;e zXFQmmJcy-5de0K-jxtV&ds?!kif*ZB=9Id!7oZ&3tc+6A+S;~L@kbjVcFJK<3b~De za2W10i1yCaVui8r0cSCkr{%@xC7VqqH@#FSerJr0qT_p5tLYo7?aCv3CzpnQ%XIEl z;3t=(N_{=HXlgL#3DwrqKsL3?Jh3bABi;*o+`_zmG!{ANT!KfHHC@DXvR(w!U0o&w z7Er9e#V{$j$Pk5;pu9IUR~0oKXV2{|{{qh0KDQmK^*M39{2{!WfH!LlevnKjy&EnE;KR+{ zAv7ei=Y>_0oc{COpJH0s*M09Vo`TY!JKWvddJ9T_@tNPed-klt^dUO`?)lB@R(I6& zm7TpA%d4*(UcL&?%jch?rc0uWGQ7x{;`M}MpHe@1@5b%NPM*9fru4(hS8v$9F=4~T z9;K$gTWgN)y*M+QCZLC`xmKe|`9{!h*DWOaZoJx?&^?>EN_RJo??@V~lXg>Nc^SZe z_n-v{`(iIaf^fP!j82M@l897Abs6Ah$W=z?ZRs`JK+PA8L>jtV@<0O)7y!0*}?tYqdUEw9Of%0c9VYfvG<5%{PnNjyLaQ> zg;wjfdHzlMp85IPK0J5MKnqy@U4oY{C#6yXaJmVtJoesuzxeut8yImeORQl@Qw-Ae zfdlKZ=daw>o}_p4FQ$gnUnt#)GHgFC)6s?`dOG7DcTVC@#499ZR0#7TP&$PrC^f~Ok7shzcig-lwVt^8TQ{y?dZ7_1 zqr@lu4p{k)&h1xET#LK)#s2qS22W{?6q8%RO%UDD)8|cJiMgiEJCdD2G*dzZ7wYxN z%ysj@^^)S|9;4Td5AKe%*Xeo^mILKb`k#z5c-9Z8wP)nCA|#~9R40_aEMI32pd+D6 z=_m{OXoB+{NoAC5bBLYL!)S*9duMxbd^HDhUfk?S&aBQQ%yeh~>59{{seF|O))6-gt4kIm^8tr!2QtVkCC#+p+i_r9Uo%Ee z|4auk-PzfP{b0Rw>gv2fb^hY?b}6An#v;8>POUM=9Al`hkBa6QIg-6j0g4k+gqmq+ zpDmNbmHyy^k0G9uqu7EmUBmRp=rF3xE~w~WC21M6TT`h1z)}k0*WGK%Ikd8ZD zKz=}RJeO2!BLs4d(=}F?s29b~VESfCJ*UpX{(_vYG5Th8S0QJ{TrRDdx>*JsE-v(; zK}ji9q;fbyN$Dffg_QejeuTir*W>~NcRAjgCs6Q#b>VUugvM|)lGlaVMOK%gP+Xpn zC9YLRve6$?-Ho1L*6@%Po34~|nK)=_ddu83*wq!Bzb0DxnkU5g!cdC3?NnQ%PI-8F zPhxkUEAfjsUBvF9Eojac*PltDz&+pfrn^q?9qs9Xn!XD=I#zTsfwOo5(+el9r9rGN z?KlNFinuE-4^?>srNi5b(SM^jeJ2d62vsPR>*Q*=tZC|;i<;iTkF4i@oC>5Psw1MK zrz>Iy(?yz|Say!o?1&@%1kB|17xb_14;S&A@>U95iJsX)p;={rW%*#`sZ*b!IG;WR zgBfcEPoL%@VEatRD-D$s7nhgu+H(q93lY-|WoUFU%VU;j6yi-MM!l@8ywY!z-yZqG zMt?i*cie9e67J{`d)D|3xDFps8xTxiRGt{-=NaZY?$y9oJw!)Wn?Yo5x{k^aR>z>O zn4L3bD!gw+>9P%k)<-H%XZsNN(qCRi161=BvA)!xrZXCwE6*i@>6Vhd{g*pV_0_yA zkIv)ELsM4!xB0gIi;s$$PElxXZjz;pkQZDplw6h(S{~F9L<6H5^I&;HT0?m?wixk@ z@E&S7sUb0?Ho3f^jg0-QM5Sf7#ia$|6p!$jAqIeHOI=5d7_(F;T{xW}Z>nS zqw`S~%BRZAdwleWXZJk*IL)T^JiceoIL}Q;>TtTM`P($ZWx|Ycfk(6AwUF-gO#UKJ7}3oprkR^lwss8 zScpL=rwr9ft_{I2=3mow`=vel0vvtP*OyDbG6dMkgODzzwlPHR zw!7NS{x05hgOrRKWBD!#)@7K;O<~$lRFtu`GF*CgDjJuU!=C(Qm|v7bWD>~E6%zcS zs}K5y=|#fRJtqjJkEFv9ZAgdIbcO0%k`-YE^{pP98nLDesT;S-M*1E_du*_tRP`{y z?BOF^CS*xhIAUw-V?^bj6l@T0dcoG}!h%+s8~F|8ytIhvMN`woe4~=nU0fy?&=_EA z%%lLSQq!26diq9G7Szw+gi0mBg8lS#Xaw3UR!i)5tky#5|8b?gGey7LxK~fWhFErF)v8}hnoDQa+KHINcFSq#|Q;QmC=_I71rkhsI zth?A78*8q<)O(m>Q?9*!Ad=Yh4I-uwsD*~%EogPlwQK>V(#nfTq$I59 zUNalT^%4oB@0&E9Jtx?JE*@hyL&B&3a!us)8y}uSpML-S3zFZMyJJW8sM$>=B}ut4 z#DIY51g2Askc979BEVsE1~ajwBxl_8JtC-UlDY=!dr5o|HJ#E;!Sv!{Zv=E_pq0NI zCue*?_6{(5NK;4%8IRds*&!hPLP>?mmc;Wu_Hc-rE>SOCW-K^rVCx_tCI8~p8`t7? zu}^>hJKL;#*HI$sHV5NJ<2Kn1AbL8FlJj6>>IbOFlsqLLY%v{-c_ z8>LGrEr+H9>e$nTnVkgE<^AJ;>aB~eu8)f9b+!-iw|621$BBOxnv%-U0A0?rQ*gMz z=ny*9plIm`>U3go^mnLAVlvnK^2^OvwjF%=<(E%2@2DvrwG4NT*yCj;WDlp)myE=8 z$07ssXLC+16Bz6qz#HzzofJ7-Zo_ye+9(?R!4bul;?E&x{GJlwc zM+(z5*9XWhs=DwcM{&Jy5a;*QxeI0c!a!k5?RpDCF(^;o$DUqRy@9hr3*E0mikRjP|2~bY?f9=aw0>heKWeaoFJit z>D+`X>4C&x{S#Av%(EiS^QfAdE(*F}I`9s)t1hJCO&3nrPB@pv&2mYbfZ$E%um?=X zA}>0**k1NL_%p=xdmfysEH9cfeGPq=xKb0;xt(puUHtf&O4z!hbcN|mic~p(M5QZK z7rTob@VpSY(?W7OUs{xrYQLvDT4wmopjUNXgz7&dm85YjhjS*Hx>(kOmc)0^5feTY z0U1dDjZmr5j-@cRwmADbkFT zYw2l#!{ftxn{lev95btQFUr|{H z{Ut>02Xc?bC-)i5IE>Adpc%|vc#dXZ^2uv^ZDs^QB!35wF4b9~_#X7ERDT3;#>B{}W`x9Pgd$4ZE zv@d{e8#6qJ^4_1^)n42PqeJNgy;!=)wYg&0*4|iis^juAr)ma|{t8ORsV`&gKg65v zK%XKrq>Ijsj~mZ9U5&~LIue(3w3XxQ$Cggiq0tJR8*9zE#kDjAB~o2Vd6UzytJ8RB zunb+jfvlH!k5rGf&k~hRuNMqf)0F9j@I}V(O)f3>Z^~K{7r{;pU$BYZjZ`#`m@s-Y ztWGosp?aPZMj)v}>6^w8voT`ErU?^B&GGfGNOhKT8&VR?lG5p)-d5|4r| zvcizV&V=t#v?tv$TW2y9dW>+9xE3&d33-fy>9MorWz074u^HD|yEVKuu3$+Z)^wXO zU99PVI)e=%$?3RWT*3;-g0Ifd@oa@l#!aAxR4`q<=>h!O{>Ed{@&w4VJK=D5I`x*_ zk+HG8k)8HB?*RMg;&$ap7vBq_t}`$p9aW@q64;=)aYwP$y&^KQUCT~CcV(NmeuEWr zw^)OrIVX4edqz9ybsOq;_oJ4hr~m%n?@f5`%}1Vk{kea+7oW|ETPivIH^2Gpv;NaB zX<#m=SYP0$GjP()RV<%DO}7-UjE*raFS=s5)VsbwDE;gp*^N>|s>$f9w55cEdpAmN zBbpm=BJGdlXJgO3_x2p?SF!14b8l#RXJoFMgFcp5AK3}4M_R3J0H2!+wmT58(>DVQdez3-WdVYSL$(TXUQ9KO}K2zo+O8R8zf&-#s*)GH}n%Ldo?G2_A z3d2K3R^U8nq7^4{y0e>(wm?PBblQ{#r7v3uU(dB#uOG4=a$iZ<3*n5HF0Le%_h55# zGhH;=GcA^?D*vh&A!pD0^#h4ziwlvIFyt)F@tf(`79aVc%Di5BPkL&ov9o12dQ8*xx0bs8mHU5FQEEf zx{(Tay5c%m001BWNklz&7q7P7D!q38d_g@z^1_8oQJmQABNe*@ z(yW|!fcb;e0SNy3`yXI(!Al>tY`%AT5 zzM*HlS3r8c$mzlQNIWlgVt64#g=$d_^h*Mt(bK_S%3?J~Sdq+7{b!Q$!YlD{)Zr9& za&TgvD_u+@y+fA;cN%(0#x!^b(D%qc(LmUp^?54yJD_Gp39kn?eL6%}%3x*}W323y6-13@{n>G1XD}>cVO=W~HQr z|6nIas!e^Q4U?Gal~S*L$V`ILAAF1mBSYD=jg60~j3!uO82weW!)0=^BLHDT;xdbwbeMScE^fwXBHw$qqZ@hSDL}ZtN zV+NY$t}Iebs?_w&YCfQmx?*dAba{4?Uf3)wX=?grQXw^=eDi>)>GwR~%EdLW3928_ zsz}uxS*euu?;yM2J`s&jI^)5Ax*HPz$vyY{?8*Co_A@1#nLqks22{Q(Ej@ty43wVO)04V?}rWZI{ zz*`$Y_-|yXg;h|vx^k_inrk;?dUnqr|?5i zh6*rNhL?v|Cf8QiE;q(dLTaMD5rK?SLt0)iZuo=&T8<9zMx_tw@CAGWV;K6Gt6=(* zEf2tz6PDB`M@(Kbxy8>{f+HbyFkD!j7cYAhY=bF`ydl{_Lqokud9xy@4-MC&!m?f1 zT*_h2xkRBgVK$v|Sjz)qOp8f-Cr3;B?%&*wTsSc-+r- z919p6v8nKBT)h99GmQc+wluz4+a-I0sC9=nyyOUlYB6S3_ymsOi{vOA2hy2iuYx`1Ubxf?g( z=EG`#QYgyypCtSLH{Nq}+ zG_>ADyYsNW>`l+epk_3q$Scy#E7F8Foks2WUI=6?G)kV!5X4SO9}3B&n$*z|PUoKl z(@Ty7r?YQNqFxlIQ}HRLm!C**I_47WB{CGHi?%+_FEFo=M8?3pYGg9Rd!k;bRsCLn zc)Bz$iWuR-RFf*wh$W?qiA_gMCxM3NHWmn`7ZzgGEA^0^7ukEHg}s32Voq0TI*jk) zI(%|mIXy>nXx>!6B?3%GO%In6(t4x%v$(zO|0WBwDIo3c-ggmL-+prS_|D$wNHjNl zirbv=IEYKZ9v3<%{1C<{hI6TpqnG`*M)w}QplG9#(_cJy#SpDuem$BS>huI-6HJHr zZXe*KziuTtog&h&e);dmc0d2dQ*S(XY-2Y7eIiWE=`;cQ>@z;Sl|(L(z6#HQ^-%61 zHCR4$Xs?Cv!yH(^gXMS5&|2-cIP zTx+I(Q%K5m8j+rBzsL+WefIX{tBI>bOwl z+{{c8x4YYP|M}C&-&HjUs!tD)K8K9ROz-K~Ubsb**X=$>x7Bp(UgF0UbxxU|lr-I* z`UVOe+{KCFQ0(4>dfr5n(iCPe4AI@KxM#4|0P12*?>l+z&4+H?D5Saw&kJ(;d_ob^ zFJ7d2H1F2=6I)L1-78&5*I7+f7_)jy>ZW6)M@^qTuS7E4L1$jG>Y3_~o<7AP6KhR+ zikEXtB$VF0FSM@PYx@S}dikdBg}=O^kj8JK`i78wc6Ku{+$>A?vX2b#fzqh}??4d0 z{8T=4s@k1}bpt3Q#rP6nPlP@dtkKNkK<4Qba?YVIDathgjUuJ}PstCCjx^+C zIQax5C3*X2^6!P9?w~f9!1@6a8ndZaB}AWxh0h^%F3GZ&qd$=@eO;oa?|=CnIoW@3 zTUpJhQDf6n>{5b#*bO#406ks$P#I{E7Hq0E8R`pbs|`g=BlyRS<`uC&K&85Co|>W0 znFq!3@)$HKNsKKpsr*Q^i&ir#Kq-8#-?qmO?6nMNda*+7+ z#~uUW;bhg?2uj~9u5`_vu1ZKjb^4Fag1QM~L`|0)E8~mYaH^>3;x5^Y=|%B6m=4-2 z-;0DPlAkW>`DRw4p9`i7?~6!36@LugbkJN(IVx&~M|?!Q>aaQ9bnb-bMQ$^c^dfq> z42WE#bpdsGzpA;BETX29$0+!%wDExj5;Xt70#CqQR=x(OYosoxGC0Km!%+pms5|*- zPa_-kv447iEEhPPanC(~`WV**Kck3rC>)be#-9+$_{T1!uC6;r`*{wG6D4`{z=Yug zqbGQRu6tJlfms|0FyZi;U%Z>5QM*onA^^Q9cZ6|EP9Bk;2n-d{?uCG7I2 zU+H*8sp+4kVa+hto)Ttf#i>(mT?Fiv(_9|zl4BWKJ4r9G%VU?XF2tKIoL*KQ?mI%> zFC_%Xo{9UOshM zb}+2H{ERAxJ-YU9&;;{8`~F|%Q(H!p&dNdjB(>(sGzoVpZwTs0#P!m#=(MQiMt>_A z<3@H$7;~+dM#Kpo4%FA6N%PjoV{9l-&Lh^mpd&2M?{OEA)2B_tvAeY8{+7Fj!Rbp! zOz;g1E6ob@3tZwcZpLt;I7XwCYt|Rxba4Y9rjL;01OT48zY)V{3?DvY9JR>f){@TN z){saKBRYyo5;`TIWrO8y$+v!$wu#@ueX7L$97 zv%5uJIsLG@j3n74R~9ss*BJTJDQGBz`{}frRvGYZOeYYCB)n{Y=VtvC!wO>6{S`So5yN5(6e~oXuY~1GP}})xrF9ls@>unr@_8=ODfMF z`xFfuZk8@Xl7TpMB9Vl)qnv%;Rg*Mp&ah#BQB9u|n-LRBL;*?1_+4U(sOpS~jme10 zDXf#cML0e;SCF^vN#vBuy17-djn?M#ttB*B;>GG){YI;y<=@L=Xi+I2EfLcznEAfn5 z@*=W4CV!*1(HJQtRVAdNrc2ffRT>1~7E}^x!yb(AtkL|z+tl=W!?$*1eCH+nKo=)f zECpMK<#r=PpJ-OfFs2TVsz z|HJ#gIsNWuFMoEb;jFT{z)E{pS*>W+));HTq3fh^H$^8!dpqlUSi8-Tap`K=^;6i{ z%PL;5sp&%N_oAZ1?8j(CN{gd=w@WE02rnx)3dRHNyHV5MJyY9d!MPGibRre73@2xH zAFS?-bhL9L!!O#@TM=y{$q(yZ(t(m4Njq{&x+9G{L{0x}u%@ps$gJ6!@gth{o=iUp@|c=nD^g*@pr$aRS-dz(ZvU{{i`f7Zb;k| zjQVG)wwl72s#Jk$1=XjB5So~nNc=4%r4Ln-@(a_Nk%lb9aZU**QhW*Gdx=Dpu!V5v zWTz~oH&O_0prl->LIv7;*5y|DADDh1dj}KprS z1p(?GC%izM%psYBMvUlUp6x*o;p-{f)e!2IdBzUt9^cDlO!JC@PgEs~@bJ1CvqDI%QfN#fKAKkFp$ z1;>fAd$eBiUZikTsymXRqcPk_1`N|2ZwHBhVYua|1VmL=XZVNuOqcmi<{Z5|q)kqj z)b#A^`6)iMFo4o&LMr8>j&_*T#riTc)W>^zO;=y@euQ)|{W9j4nl8(zQR$;*r-!28 zOA}K2I=nynnEGlr$0A@oBL?X{M#t-8hnUIUUjk@w<1p2fU8Cc5+K0&`FrCm5QO!k7 zS4z5=%++Ou<2En4f>=3`I?|!sbh>o@=tpq5fI5vzAGqf+xu+cDQJ;MBM-O6&VHH|5 zNH1-S$aj$w5!Mw_&w6OqEby6!q<~cOr;9;-vv}Dz!^T9aO!Wl2r}}})KgNav{=(xJ zSYCVj`8OVULku)eJOrg9k8=f2Bu9a982%w{uWDE&v7I)gtYh#1Y62k2x~&VTP_@YI z@|2MJ(2#kEHbHq}&t?J`A68NB2-v);xj)k|9S9dL7e*iAbg2Ec*C;g=c()l~gzXtT zHYKFk_u1MHDnb`ZXDC&D42ZtqL4tRFB<^$`{+@g8yXU^2*go}JhNG6R38UaF&@U@2 z&?7Kx*P1oE)*RWjhA$ktsz-QaWrb0esUrJ|_ArHa!*?~zMe zl-)(HgHaW)at5^u+d{RHH>e&*)&S`8kTce9iYL~uHP2&B0iK)l5$EFy&eLy{DYY;= zYIS9+H z7G_+nuO^VOtei}d34BYA-ZU9CeZqu+3CvMOj~f{0r#cpnBenb4O=-2|i^DwD?p&jG zAt?N2NnY(zUh`5Ub>0pacvrk3ZTi7ml6S?Mk)M{4Tu-ATPF;7VnycHE?B~VcmnT8p zu#L`3$+r^A@mV+T-+!4TMiJ~)F1yI-vWflyYWlJ%85ma5XjdfWm*mP?tA&J=_=f)Y z_>LtFl?`c?R{tghXgn^Jee^d$affVyb2<&-Q6DTHZ0qo#6)8cEl?_3!j`MxoW$Dr} zE;Jui!RhGfElXWDkrrLBILvdxxWJ%5P<+Jb(KATVVB5pvnw$=%<9L}cVz>)Nm*HFk zq$6d5>ojAZ;TuSDdVB+njz>M2eG;hRv@Ehp@hhlqE^AATH;>A8CkMIMV*dXz_b*^k zp6A*(E}@VD(MeD1j0@hp_NZi4^iNV z->L_zxGF19lqIOK^%L@M`Vx|ux@k5&5{zw$qBd__O=A52uKO8`Nt3LscJ=ML8D{g$ z%rnnCZ02{L&v~5}!h6LSNM6*@v6fD7>5i2&tRqvz$Po?Z6+pg_eMM6R3cAegii&E} zYwHp=ZAiBH@=w6w-g_)GWrA@Z=I7wK%eDc zdZ>E9-Dd%Jye>RT4TtcrGORpa+ecsCQ*w)MIn7mqKhOVmHJy4Sk$G2 zG&ME6t}#DLWNS;h3vYpSDr-tg0FH8rWR#a#l^VkTuZ6f?s3H|LeW8Zw58lJ!!bXgL& zky6vY#uq=e3I8pZDIQ__K$k;^=~dxTI^ws*fQ+#PQPAFuG-zk9w|3;Z^1GnRz6aj=H{|qR|N7@I z|L~Qcp4sP--f#FBm`)$kKYw`b&GSdl(~p$C^^-sS~T`sSPM9mkq|0$p7( z-#c2ZT4{-$))+8Bh+o-rjSt2dU(c0mR{Abl>1Z41xoFlRTOO?o+LDBqe00Kmr>F-bO8yrk)Aqj>c^=7l)YyjHJBr?4qp7`ElLr~kzo4eS^3PR)xL%Im z>?mBmcK`a3eq1ltTWGCA^@eMCsz=qnpjE5Z27>9I-8wU|^H6SC%h^wq@1>=T0)>M1 zqie8=?_cY==IHVaJQ@5Ngh_lLrI6xyAvY3*+{oKRDcNkKq^{BK3*6YLg?XrTzmkXu?=~s^&J8}-w%aPhH z)bteUb?5+`-nhXz zHZ!=`x%vYz-T6SM^FVN7u`{@y2oEbP-m~XzQPYJ!AyL2+B8SZtlX8WjAf2n+MKjLG zPH!P^;Z|-6u4?D<1WHFCQ6;OZRmp<{b1}V06H@=o;5@u8B&Qck8>829LUw;ZtT`4K z;7=Scd#=%^lkGZjbx-WTE}u8M;n;qZ(YVIMu^<=aJ4x z7gFpEQe?*P^Gftq##L{yP<-kOS>z{Uo0lJI`bNKCZwZgQa})tIS8s!6nrh1xtFuI- zauzW*^S;HCPlgS6t`?1R9$PfjlpI$QT}$F*957hY-x6Ph>7|62rJ?gD!~!IHMH(nk z2k;{L{69oZU*K4S@kp%NlbrR{nQJe^CMG9uNc2ZzCrhPntxt0u)|ZNel4iR~WN4ZW zB_?BxNuU@L>$?BI#>C*$vB{XzFNC^9w$1?19bQ0EhtoIT|FD~%H;|sw7_xEUJcm{n zFU-7BBMOfroOe>(=Oz~Q8Lbrg%@zj?bdK8~ayAYaRQE`5eYTr}Lu9L8Y+|BJaE69R zWyGMaGG~ltO!dvQJ0fAd&$zOZ=|rtcahat0wYDR>(g`&k-@4J!5onJds*CP0k`RNf zhYyL0KHhg1m8AIcOF351v~k-eYr)N_F&8o2W$H$jmy2lCl!`8#S~N|BZS4UI1dTP( zdfGG`DpOCp8`I_b6efS;ioVX9&g+HqT+1wAT8fxjVq_y^?qHNFG8Qc5mXg!ug)D0N zG^PxckgAbCbw9VhK~3ioUm6Z-eU|5c*NZ!9`iw8$?bkdPG>6Qi9K#f)V;7GS8%#}B zerbNRl_>Q*2Vq+V^ue_NSG=NDDbuJZrQu>~MJDESUw-BP z?ppyKQb~DeRakjdRCu{9$X6H-qSGRVj^t(&`k$VNIZ0Tyr>m&1eSw5BiZeUyXuE#r zzQMBgg0d@DREs0pR{FS_Qb%!2w-ksQf;FVkd(#j&Jp8l&^VVDcj~HKm^{apV(F4Q! zmNv(oD_%bDvU5rgno8DZju*gA}!v$-u}5#)8BlPkn&nE-9T!h*)d>| zfu_Wci(KoXu_&9JY!@wB8_zvXHo3Fnojh0WUum1|v(nSv92FH6w5nlrkQ&&+?2eJJ zsBAH(pF7f$G?A1vST^dO!P`r^@;+@zuasRM8|%7!w0*3vuTP}$^XCWtATf+U`pZ8( zvjR$wU`NoTl#GGqZbP?YVHwUBFkSXdTia#q${la~=3nrpzjABq+U@JRyKfSfvS$Ct zesc+~mx(RX0y8DhP~(_dH5jyL)}cdZZvFFT|Gx8Q`$*Dh{{%Vx+&kANhIi`eD0GzE zZZV?J-IJg}J--Od*M!rB)UzG!Na|dU-P}NYiU#VM9@km zJv@F!?`eIC`;`s$F?qn3v-icya=>oopQU&t1uEAJ2;n z9gd_O#;xK{e@oE(E0F#bkNSv*E@Ci9Fg?guVY-b;++TKfVbazJPREWSxrT5$$C@l@ zNF)K_<)_aO*+{mobT5ryo&&`@ImK6|JJC$p6p`xWgKwT$4~Jiny7lSo5QXVXknE(5 z(lF^mR^+B5r|aaOA^(#E({q!ChT5R>BS${rn=#f^yK+{_tOYbV^5tIibf?h>GF(y{ z^J@&Yq*A3ik{Ze%Z9J6|cK!A~o=N0u!s!G`(kIwM`>%qU{@h|Tbgb#h?V`*r5}dBN z&lQ$yg0hm<6}Ue6=%X|{62l8MmJdBdMvTCv2U;Hw`I|%64*4Eb0jA zYG?`S%Ag{gj@7g7mn$^%UIWN#X+`L59ev0cwl<B#38 zT9lgpiy!hDyof+L&5o2YUDlRB1>2s?gbb)lfL_=4Aj=GK$hI5vv zoOM~Hpt?Z1us?A+&(R!7bG&G@j&lAS{iW2-lU?|z$mxgglMgQK2Q>|qcidYry*M*? zQ)uF*Oy}YQ)dzyX^bbOVHzj5kJ45M8y4D;ofFmpovdXt$`d#B~7Q*equ)^aKaKgO; z=Yrq@>I|L&iNpE`#fZh+KQ-iPJ=LVJc3fQY#>~(>Np}eeiBTahyLUILq?g_K#OGZ& ze^FVtF{kf2bs7;J1^qmpaa8}w$;sY50~e2U9h0&g8P~~HslnASR3s911#&6240QI= zjT<&@+9-n$S7+WQDQnKmNrB^8-|&ZqpGd2f+#%NvquioB7{ zeBYz`HL>CH&ei*nH-XcK$FvHj^Crofl!tRK-vdQOP4pb?uSuSt7grh=7Z;5=Jt1Le zC>qqf3Z9=9IsF80NiyUa_5TQO`j%Pdno==o(}Fawq;vpHd|Q2R>_ti{v4dCCiLHdR z#eoWpJI0P?u3p>(G3O-UH7db*GO#UkAhX^jlXgP%1dYU!e*Zm7TU#*-Gd9n03+2}= zrnD|Ul;AqJX&!(+V>VGQ9NFNcAib4aq%qEuMx+Amp!y6fF*sl%k=^H!q2B5c`4ls$ zL^992`i8pbE?QK{zr5z!{j-{lm9$KSy6fm|aTfBB!f)Kn_=?tcTNNYqial*@Hz*7apI& zbS545W?9zprMEG)-mg*9DWCl>kMF3aOOgVd4mH8)oYTMFxHUXHt1%>`##J&d75cySs@q$#PribM5iyiDW zZzi^M%b2Pll@d}ZBE?8IBiLV>ABR-%6|)dbck?dB0@FxQu`BQ5u3xVI@^1bPPgo_s zY~)2!8KbLwgODQTdhv6tjvDL4uiQr-Y%o% zy$_{R(RCqM=ORs_GgzR z9a?c~+s9z~pF#9<@W$1yG2_;5GGZ9Zmlx8tl3Gmn)TmJ`*kxsf>De6x?U?BH_FTG7 zm&|il8z1=Dvx?Do2%kT&W9v!Uj{@i_YjA}sA>Anm$tjp2qUQ>sz7fFuxpUsKHiTg*o56l+^OA=QpXV?*e}HT@eaRb9UYNBa`4)S6rxklq)g)wHs9v z6I8aQF_r3XLC+~@wsUl{M_i`|Qeir3dRu$jkt5ef&iq7S`fpb3T-o4*c-f{Mvl#yOZ8Xh)uv{Ti& zpWyo>U(6eL?)me}<|u-6x+=u-0<9DKVn>4>5MKP{s*tq%aXc@a)PTMTPY+z1T~O&$ zNDH5}Y=>y>ApBa^vu5QYibmJ(-`)+jqo!xKlV8GUZyy^g-u1{USIXKrB0DCY7v?e1 zw?c2zw&hk$xd-C?`ferx0j_!j5r|6O&q$(Ll(9%Coyt@}^tC9=vjQ=lSUWjUQo4wZ zNNW&C4{8XD;K<32n;n)qQibY*>t8>1j0A?6eCZxa){Jk2dxNL1J6VkE5o@Nf_Kucf zOb)03>V!d3zR4d7zI4i4?b0dGu(9&=4Wkzpy@$}!N!UzJC&`?!xo9U(PamK7f^=Vu zQZ!@DW|Nhc&cjf@eWh5{Ly{OheEA2+RGHSIo=Md7g6U^5y+{e^RZ2*~^!4XfevQpe?s?Z@}-k z-Vw=(dV##5bdk}OqeYA_Lg<3%Vj-7Em}MfUYnVIIj& z8o;=GX)mKdUQ2r6%?rUFq`Q&CrZaJn>4R25df#(P*gT=}mtSI=Ugn!iA@rxYwB)E; z7+qe3HL-u$KTKYzKozsg)akxw?mMhyVX|?6`lD1v;&}N2)5r1oy1W$XTwUz!SDfiQ zUt#(OFF7B0sW>#)-`Tksem#As=cXb@K>dp`1?q=|RpD2pbs=#9Q>CVhge>SPXNpzj z8Z2JlNg1XhTJB?!tW$lT!ks-Z5KD9TO=wQ^Ann-{mse52Nj}#gckIJ`2~axHIqfnx6C9~#q;^}RPr}Y)P7T0|YA37R z{eRz^K6i_4X-P#MLV88qfPY`b#*K-7^zqp3@vpX*i52J1`@pz zV=qv#OHPV$j2=iEW8;#8XGA7e)P)QzY@NAz^F80Y$6@vih3OAIJTI7v#GKN-dCnxa z%=7Y|N9!Z#d$wCAL{7-dY#c5U_9AdTgKrVqTe)bJTdlJZ+*@Zm@H{$`*3)!q8*N3K zu)V0y?ocwuH+uF7Hy zNG}k2p2GBRUeVWk)4zo2a$}~vfVfM(0L@Zv&6CA+d+Q|=aV#nj0C3^4ucyy-mR zOJn+9qoz;e{j2e<-t=iv*wW!1qF(eOrJJKtiD)dUsSC-g$kGwPg0V#j=^#0cNDvBrcJ30(zQu-|J^gmxJ z-TQ#Y#6-(rgVjiPc19UOYijdoi`g(T?7Cycvv2(rHT~tEJTM%zW_{&yW(Kz<>E+Mw zoRb6hIBbuBr`ZM|9g7Q9t9axG)6#HY3#F$y?bmk{WY;z~_Qah%`_4P>oI7`G#mKWe z{)kk*W5-Tfk3ImV%NQO$`NxSBC;0-{q4gC?SVvwz^ESR8Tj^3wBovu_2`LGRFhjEjgMEB^WwzOg zeo0_@%OI3K+MI1yK0LB-;tH9J?_Fsu%I+YA>hmMVE}uPneW>_pr1aIxl$JgyJxg0g z3nS7>P0h8oIN)v$G{hA66$oondE9{ARYvbW?3(0^tJq#C3sOD@hsng z`_pM|x@e8KYA~*Jvq|83Wk(zF=hTdDukCr|)mLwnH5WCO)U{F5+EUhkEBFAGm)9D1 zc(|@7TZS0`ZAr!O&94dwT9`r8)J2P+b1HV}m;|LWcL-d-g^j0mx(%+FHOraYG&BSS ziRCHEiJVHqvmF*8{r|l6^?+_!I^q$iw+oW6mqkgVOuCZrl!$J?(FNdFLKkfbe<34X zf*S3^R8o2bdr0P*xLoYuZHb0)LP~dvh<7ST_en)gr^~gOxFAobep+J5BMEzFF0-~W zEk42wXZw0u`3_5g!?4cPmBJi#L`!v>T6=x0P1(}VDoy>^SV>W(C+&{|QmNZX4G279n;yJ^K7Z%Jd?xmnWV;O_vf<9=uN0ilB~%;}M~BSsiSy z23LgAIm55=ByovcLrxbRU52RX)R4mIzo>?SU)qJFzGRo+Iz&yv%fJ5k$51+%>9DvI zkCMe`31rj~8J9@t3lI3!4{2?>WZ5HV;v~uZP?jouM`kBVeTjMu%M_#wLnGNM*UMcC zRBAe$zU$zUM;1T#v@}LlS~^WgACf%A=fs*0qjQe}b0wq8EJD-OMO;Tnr;JpS)8&Pq zCJBcE+i|?<8l+pS>4%?NEbb#BIo%1DleQ>1UIi9G4uI6Bj4o&e7!yeaQp8 z1fs<58Mw*@u|9P9iziski4%z`GjUJvwTlB-W6t*_G-073!K0UeZOiDplz?3WUyYEt zKRBKPttZDMv+|zg92Rj4PUqzBzcD$}rPXD&S1>aWnT2RWY3CZHZ)Wp33Q&LgbZls1 zB7_b&#)ig*4ur-I5IVzstuH7+UG@ZOdUR7<(@=k{zkg|7V^eZoZGT~HLMfVmQ{UBC z%0^F+m;PIJwko_8E&lYEAn|YfjQ);KpR13d*5({rV{4PQ|4~(4Q=2!2XxWTLSsi)X9 zVttwhHi%ChX?(3y^I97xtS3BqyZ1R8vx+Ek_ z%EPd_h&_G4%P)?Epi;8psYC8d_W!as9e0T`mwd4+MG?OX(-(3xMBRJ0nhvHaT;`6u zFkPwXh!SpH93z$BorVFNLS$@O* zo@)96nLWt(c5k{NOy_7SHVnG5u9 zN~Lh8)APtG6`wi%jl84{sdTh;@sf6+BBy`<{-u)0C^|Yhjmr4qg(t?_D>I}qC(|!D zBo#5;(JH_cUZfMZ`B(qwfM-Oi@MJged#1yjnSQA06oT%qp&OE5eX2y*5}8hO(qI?m zc>&Y0r3=-|AtcS4t~wln>Ha`{4u1it>0UFax$ue!K}#3Yi+FnezGD@RBI@df>H0#@ zH(BV-PVP487#vW|O{w@m5K__b2p$x}I!Zc4rIKP{ZI8m;vBF>gMR09g{}5UH&+lbz z9Ug2M9X07ky5s4eX*L)}%QDgoBMrKphP^-eDa}TIedf?`Qp5J_ql5caeDtws@L>88 z0reweZS4}d4yU`Lc80l!fq`LWC$JrEuhi=ebU1A;>AiIJopbLXrze~oIo^#>{(z|I zWV>vY2u9$X1e23zPOczzaPZ{GD!H~|1zky3oRRSJ-@QQ=A^!{_hEGNZg+-4BMMcYD z1VYk>DZ1kY35&NTmn2=)cD6V3)mBwyZvR{`eb15TeO4<219gV-@;8iODPddjI4#ia zjS5__z{9u|i;@R@M^nRn=cY!NuhIqSQuX|nL>r^lZ1IeMsT~bYX<{pPvTMfX^X4b* zqr<}!QO$*g{0#QxPQ3s6hwmdGHIH>Aj14JFKN9B!{H%WR(3UM`v;eFq z>!bHpMQ4>C3VZ-D{a=1_W`+Lok&&NygcV-?1Wf<%QW?SGCZ}w|{{%3Zn>jjK<0Cid zv-KdlsObvQ)9}C$QetnQSu2$ORZJI3$J(+IL49RqHdb^*eFgEz=Qa|@ezdv0Qo`N4 zyM?>=S5{_YFwY?DrR~-)UwQT2(Rd>*>e^Z|j<#ICwZZu|YWk11dK?-VSuf)Ke*0`g zytS_{IBaJZ?^Fo(6O%q`(HhUSo}#9&-0w&h``lR+@gk-BEN52G(qHJ_5HvhI8ZpWN z0{#9ShMSu0<=Y|s*%jR*hg@}@xx(q5X%WklBx+GCD0Yq%jhd{9AosPQ5iJ5Z%&QY5 zH#<2|%t`*D^d>dw*p1j>A_!V>ipSI+Z)2bzL{@2*wVlnDMd|TQ5WULi=Qq!XvRF(j zG$=q$2mXCMq`i?&FTOLhaN9MDAoaGPwz09Zcm(8-3q7-kYO`%t21V3l;p2_=U4=C# zNNQeF=IZMj$$AY6(gFVV5jdAv2ODf7hsxk|wirXrR1<9Q94Q^31`)L(kj=LY#pohN zBcg-pix(?6$C3f2FXPcHUxw*L8>%)Wg zxzi=^1x{Brq>pi~nO@*@09_K%5xBjVNERZEj6|)b`=|n8Zb9yR$=NTo!cmDxS5|cr z8GpsrA=9e@R=D3HvC9P(8Z7a6UVimsA!s$&JRxQPS=8A%t`_q=9OxRXlZb+=gKw-J;3+m3E$@({ zI_IJE1KUQ@4 z`SWl0_Vo7l#x*tdB*ew_#>F)qiR+8&-Q?%x#Uvy%bA$h;jiHF0(Wy3?5#k#})tsEG$>yd5aK-rLU^G7sGtOC+50h5>(h<=E3g>6<(2pK_bY zzL2jNF}=W&(M`!jlJ_L{MLQJ?RiNIM^wIbJ+UXNlWuNTXBZeR$b;?Qq0c!eO`yc4)k)v^Lu~W*n+Zp!HE*QC(k!bU300E87v)#VZ5w zmJU3HnjTV-7zv@MzN0i`1lR9>aI?e0V*j4f-5b4T%$(uv=Z#p7&My2dvN^GgNa$G5 zSt@dRq_8`AL-QhAT?kbtHl0$^NVj>dev}dTCHg%T>CjrA*w>f1EjF%;Sek^cS{iuo zN2OysYe{Bojwk7*2uO#z@w3#?1eRj~MlvKTp!B}du96}$U@C}N=%@wK6H5AWVq>W` zCFiB6PpVQI>%JVwh_QQ0inja-gDB3oa*<>m9MDjQ<$E`{aJE9<2$P9f0Z|V?srqu`4l09QM5Yy za#Ivhj3`5U>*zk5my=gxCBAJ%v8YI-rGx2PtX#v4;n5~5F_gQS!b3Jn4e3HZtqm!S z%iLyYn63q<1Lk~9sp;xgW<_Hj5_}%5`}Bl=&>KYm4gT;HeQJ1)%X9}-C*c*kX%qi3 zN+o7p>P;c()XpE-x$7-09bg_L{9DQVl!04F)GfaDyR=^uPjx-q+Tns`0g-3#R|RYNDS% zuKuchXDn*E2I)r#I4J_FupPYN=Lqy-+ z(vA)xbJTQkwTPH5)*VjtRXu~CKDh5j6>Ugaf})PE<9B$|Cs%O4O?J^q?g$Es-Wmp? zpA0`a7#`(I(xiP_d~-kXhUn^*9hjt>+v5u(kk#$ie*XVSB4b}w(3ZdenmCm^hKGkO z&>5?&tO9gdQ7HiduBlP0Qp$~0=BViKu#{AzX;qL_d9-O!fMXPyqBe`{o!mXsWC(1cA458F4lr@8CGh6g9E<4(VRh0w3FU8)xJNbkVH$WO^ir+oCMzh5yi z2&FGiqoE}Yf>=|!HFW~)ew(yWTrjoKZGfA2(~WQZh~V^p`lr{<2owK|Lk=FRf`XDp zuiUzH3v>E{S+fEc1dQIOI(dfiBXVATbLPxGdeW~4Uyrt37TXI|27`lP*6zflH28)^ zm<$vzlI^13ZrBf|qo!x4Yf`aT)vX;(1qPEN%Dtt}(Uj*!h#XFr;Kf-hakX&0yIb;L zy1Na;RIZ$5lWopsY4=DsC86uPJGSqyHWS(6|O}~*pRHFJTFkXxYJiITH{k$P{`dG zEg20BM2KPu!KaS>05l$e3RHMkhqC3PijMzIE~FE zf@?PLIR5nrX?F#sQ?Ti7XW}=C8c-&>b`o2T{*SH9HY&OLPj}q?!rDIKJo~*a_l<7^z*x9k`ZMDZpdO1r;0(tpG*`7LMV@RVN zg1XttHkbHF#;R46(1ck@h$PYNtdMQ6m&$NGdw})^Cc^wFeYL3R3zU}r=yT*RLWqEL zClm>$!{v(AA>Bt8OMVMWo?omqbh!(2x-1h+CxuZxgJ(%IQ%Oz7jlNEbNM$@i*2`nK zUX*06sp-2!EC;7|2~i8HV?lWgy?fas%br{b@3rAr(koDO^nt|~lN41SnfB9+7AoN+ExDklY}EYxnOa~=wtbIy>} zs1>Rk0;M4K>C+dR`g-RJPUrPB60F31-X=JBTd;HJ#>`;n zjj*}+U104^8#je+$lSg~)CEzsN#|@->VzVvqLTcQ9KWaB{F43sr0pp2i<|GEdi0)qzIXrT zIjxyMdPuUjMANx=yJ-r!c+!Q^k<({KqO4EnhG07CI;LHd*QBkd~TkU(AE z#%+lMdE_|Kq?E%fLu`JwF@a+Tv9SaEXu3FRFcjC5 z4-q@~Zgo>+^DxUDUytcu_NIU1ioRY=SEd(*t@0XpZDz_P(}+7ZnrYLlxHU%>e}kG{ z#Qoo{rZ2qz`}chB```OM57dT3_*Z`;7XZyx0YUgsR6Q7GFuUWiZ+f1{2(6iGxWj@c_xvsOjQ`d32cYzLl$)PsVmr2qgR07*naRIDr` ztseuh8x(~gEGRV{J)JaJiQNa&DI)#;{SQ(@ih4dJrz>5Z1L8R&cmSYor#=|nqC(bFl_;E(ws-Jdrls09WocrTPoIcVRQ*& zT&l$}is$A2haZ%?W_X3hh&dfn&!IYlQVXwS&Gcdnn49v|o%@#?^0zHn<>;u7iVCx$ zlr)OS^!Wb%cMJND!%XLvv4WlO~Xu@;u+&Q82b1(Kz9_vsojBu#$ z+<9i}PQq&F(8Outuw>03z*-%?qV8dg>1fubH29u^RF zvMQ=3LTB%b%Nc<>KFwVi)rrKHY-H}i!NICwAE_a|w&%#iL{P3(>QO@lu3OD1 z9KgvkVSO1kmM;j44kzP3HQFPEtlxlu08=!!ex^!Ch_Fk6b#^d$qoEwdP9~L;t>sh=vTrTk`1R zVLEdG!S)eihxT2{>Av`fp7G)86UKvEZ)_ZU%Fk@C{q$i!(3~-bjSGk!ZjIuuUu=RS<@kOW+Wgx?r%FjixB0@GS(!y<8qQV zourBz^xeb>byzt4+Z6S!q`jor`qE^HZlqXVl6-Ne6A_CSNbe-I)t)*`BqY3u0miC< z2B5;@L?-z#HRFf}qQ8WdOK!PSnvJ;W?XAp>;noo~6{V>hYq3X5C#{DZQ!{;Ri9wb3 zguhG=-s3wWL~VZu1g?=E|`&3aWFaEN|>PYHJR~L^u13XuejI2pL3rH8io;`M$ee>u;cZ}&kx~SM zS^{1o0aL{F)2AX&_x29-_Qa8$9=g!ax!5ZvCo?#+7}<+@)=hc4D{?Y3V~OHB-*=ww zsC&eju2yy;xHES5WF2Oh6Jqi{!E*fT13-D#rI0R?UZPX^s^}>pq;ZIBlH_eDYoxmP zd2hq6WxWE7vqbEsUd67}NZCP^?}PtA_xv8^cWtx{Kt0*O%uzYKXV4h~QG zB_<~Fb8hOYEgBmts>ByrTO=-)G1z;pO=UqH?j4NhnC+>GrBJjlA&#F|@IZ20AFlKv zh3VO~W60`FO&b!ED@g0C>*^~dXuYVYCTrysYpOq)r9_ci0vY9Yij^YZyU2YLG#jlR z`W4fQ#hbq1F4N1Gyy@S(qVJ%lPh-1O2`QI%Lfkb>_m++Mikd!kK;S=B(-)AlqQ3HH zTQGfkk$Q7qoXrjQW-cX$r4Y-G2`E)dNE*zyJnT-=%eQ;esj?y?GYZv5>@MM1S&jL- zRR~H?sDD0*=3qLNqZkh`z0lN%6vmV&V_kk$svM9uMH%yxowX*U%A5|T3#JpAe*Zn+ zzh7axGNmh67v~F@9-Ol`qniN!-1V}fmEAXu9fszDmW<^#Iuiw;X*RZi%|w3*-tvOfN6K_~&=7!|9U!++JA_kNLg4JSxhBZ+HahR?l?55`RZpT3E#B z;6(Jq^>bIxT|0;A<=nZeFJ7A*LPB5Bp)mc8t%vZUbNl2zda819a;(+{nf z#G76LrI&j)hXd~WhO16Sm2WNg*t)emD$C?(Z-Zi7DVR&yEV3kKWC8J?R1BY!qvZ4Z3rFekk<>46ChmBjUR;3!FQV=r3 z4MD2{76sV$8`C}MDO!j(x~zq+Nu!mQ&mpIewd=wP+S}U-+m2q9?Z<_VY~=OvjQ(LYS!O%~`i-Z}iG5 zzgdxjL5I1EK>B;{z5D*Hci(&W#%OLXe<_D1&fGvohtmJ$BgAy#?+4Qg`bVo$oop_@ ziJtz>J6Cciaskpcwm5YtByL#F5sh@hd&Ki1sp-t%l#i(7ty2;r~qNmGX(qJRj7i(X-G1+tP6s9j$j+aLth0P&I zvAalPBcbg_pGO*}59g!LPkCJyV@?-fU$Tr07cSK^cqBB*Gc20=BeKAvrlYQtoc@Hw zzbHrtkd=@waygvNIg}1sQw55gPPM5xU$Dq1Jza&n0Q8XUuBTm=V1Hom>rz8WT;_MUyvySg}}`XC*ca`w_4)$3qp ze#|@596%xC%;0YZ6Lv(#YsQbIX}@^@kSm(}!dT+!F7>B^gaM@`4{5+kqW$BTa9oY8SB zM;3nt)2B=?|EV`!o~wpQRxIN$O)vSP;4{8gZ29*e5Mx<#Pmg8$zEIOs?`-kZn(w;Y zTVtfR0g^hUqx9%RM$eZ-@xA$Z#r`2#`e}1v^i?SVq`U;!QbUUECBP7#zq`?>M;_Lh zjFf|__C_-O77Qn0e~wCe!EW{N4DuJ{ui8TC7EDiWEZyW6oENSqPFUw^iYB||>kZ-y zklI5Q%CG3`=?-FgA&@boF4Y!~%v@2^H_`5>C&u5|&4F~6JH8h!HeESh?w6<+?wjtF zDT$0yWRv4O4>jE@G*3d*DIv9zD%rp9*ka=-eiEIB72aCVtAG)2SKwsBN4pJJPV$_X zU+74RlBbd)zyX}I5q4!6;1T8)9ssgi-05epU&gY26Tfv!A)VVJQd9d!)7)*AQ)XIr zCFD=P{`CKOYp@|HgM(V-JI~yH^~FEG_~%P)XDB^v@q+ionaH#U)NkO3E&qc zKz^NC6yrbr^d~1L5cLNmoDA9B`ffbg67jBgq(41yjG7+dR1i%N?XfYEUe2bS{LM%I z`<4Iw*{ze3_ox{CeIWhaOQ8CDmu^fX<*qt3yyBlf`^{(n{Lx3h`Oz8r&knPCf*qr4 zZfw=Jvx}w6(Upl@p1;y_KR;qS_rV5A2Bdb>nvO>FAk|ycbf#@4G-cm4wzm7x(=E0a z#pv4EaWLJ`p%inxEwK5>T4Z#rE*N6u=6cD6k%!_q4;<0&+u;$2Rb@@ajoZI{_2ZsP zm*{A8`(uIh`Tjj2;pOP)>qiJ-TsdoPy2$Cw78pz$DoLM@kGEO72$##+{hI5AE1pQ# z@f>|Xzy{Sb(lVA~or-Wz<6Y2XHCu1!xCy7frKK|7f$}e1`9Iw1es*iOtE(x(7fwe{ zU*5n^RXCk#g0+o3fGvHEtbK97a1N2{B+{iIqR<{EOT3-bmufLEsObc$%T&iM$|)eV zF52GLDLU0=rKfwpncq8@-!4Aej`$p@i{+pdG!LYUl&(hwC#{{fS?*ZV3CTPPs$VBp z|16U_x?5%2IGKEz6#8P0@g?*MPS2&RfV4;~GxGYJN#7;;Bj(qJ$+?rs&RzPY>IhJ` z{EvYRQPU5r2BIM1VTk%U@SH)POr%}Gc0_b#PPbTHL=R?2e@>CdC74_-5L8#slrt$I zmG9@NBBc?jSk|S15TP#M`9UCExl@RG5mM(%%;`_CPS!wnx&*^$LuLgG64ZAA;tXMR zib$u(SQPdj3ngPIrz1wwPX^dCrBO#gAe+ z(~RldTFv(G`dr(!WZa^rD|P>Aw`Hj5&w%MtKPp(RCJfL zIEO1J7R9=6p>%=tAE2hQl-Qgnp5#R>YP#(7)yphDC}=uzyxKXY_(DhwB2P?mXmJi7 zKjf3Y))N!j6qEN_XiQAg#l(xSuSV9J6=DmfT2NK^Q@B-waBjh}a#ENsh%PrpW9MNk zu`e^KbXuYRq{xxZ3%p&AD%frFEXdLD6T1?rhh0_ z)bu9Qbf*HzO^?Q5F>vwxHJ)}FwC7Mjy@=^@`H%3X2atVUI#hR_`q7-YfeWQ|wEe;P zO?jxzqDnJ)hU77db-fn3nRG@9M@u<6(N~9q2TMs^Mb1V)w^j$ZXa;<=`F^}Eu)0`Z z?wJ{xm{Z}O=;znkijY1XaU4Xp$DJ5*?G=*Hv1PWAi0)5-0i`4a4~p3V1km z+O&sR)M)v8nl=rNw=^;m9uKoD|9aEQm(}!dT+uhH=~HU;G*@0LTwY6feEOY@5tLVz zqq6uLN=R!gkN#S3`kghIq%>B>Ut)Tr1A8n2X3DW#;d!rB9nS%f``~{;s6j&{5IeEOT1W%1LbJbfYF3C~B*O31tIwnDfCUJNxpe6;NnmN_p%9nzQXtUj#HR|8Bk`pYl> z7+1<5jgT_ZB%P$2LktEES2(&l5~oeQqOGrwyE{Re&CTqfBS(gYPyXgJz8v)dDD;v~<31VM{-BXn2sHNm*e_^o_lH4ejkJ z?FCLpeNLn9b9;vqKfNR{9k+`kjGmEhmkp*XHC>Lb*xAt2(#O}=RXE)uqD!C)@ZH_r z0h@PsfbZPGfWCe`sV~%&Lg|d|^=RqZ7#X37(0<2Z533Y13D;!QzI*%Q+aJH%d;8;$ z;q=?LdvEvTM;rC71iXxN81}E_K}@2E91>@iyIm!EdVGAg=c1Kxx~+|H`by8Wwmv|5 zJV7{V=@Rs^CMhGW!QC_(<<2C7)OU8|euJ1^zKzl~WWV|BijhE_lYQwKC&{(rLU({tKYY1wkt`)snWO@)uN8W539@sIU=M07RqfT&C0k>$Xy>U$&vPMD%b>Hs;MJ{I%h)Z3~71FdW71wCZzN<70-*t>58P~OsVPeKD8G;NNhSx zF4;3uL%L+0^1LkbCg(+)FmSGB3$jsadw!w1ld>8Cd&U&0vya*1IAVN(3V4t6VP%%7t0^2EjRXp5Qv>6Oqm3CWCuqz~_q4Wj?@(Gr1GO6||R|(621! zws5dq*_IGDKe@N7^hQtSOU~7qAA|_3SLfwdFR4CwFgU;1!Oi=$-$fc6o&F`5E^ZvL zh@3j*9m}Tg#<$)VtEDs&K8~)vZ9{44rBX262&jkeZVX2&C6=*bQ|mmph0Y``JBJoK zFI@QQLaJq7b(wweAd2ll`8Xc`!Qt;e_~6X(>C?wEWAb=Me94LNwmRoU(f)z*6BpS- zY=vw`J%-MxF8xQxsOzrY{#``oZTFdXv#cYoX}A; z2BPC7!NSe^A^WhD(DAwie^Oi=9A-Mq!1MC(VF+DxbamE=h&|wkL#SR{F5tOT&^;v* zr5GpNI;RZjBBqo7B2E{660MP_?GQbzj`L*(q3H_R(bjoXq{AHQNVjc>C4Rn3j-5=_ z6?LGe4-IvY-P>H(mvez>+CUR&jF5U4t#vmr#fYUsIJSPE7ty>4us0Gb$wP4A#|^|) z^bO?nB_|Ic(U+9w*nSDq&4QoB7W$l)IfH9L?%q>N#C>9MZwsd1rKZoeJVX{-YIwe^ zrhns#zFtiiZ+hv}%kG7rRX$085V8VxxeGdXQJXKA4(6(X@IIxczro@x%VM4w`lYvO zS*~4tp{5soX*oCk0@DL>rquMjud3KbI z(o+I#Q?R6Sba%nr6f1prVOlPZ4&BDg=wUYLN0DWqHrgX?9?cWPb7d3rvs+DSvnkw^% zm^{qsUJ}O$p{qbfF{Vp%BXo4E=}Jt;_2L#Bx`|_!44~e@Ei^}UB<09KRw{D(SNHCJ z^X)CPQZz+zP~L;G%?NAc{atJvoTaQFrCP)hx-9-e|_T zjDsM}CtkC?(5~px+3UpWm9-Sc)5snaNK4Bgoun+O?5&^w>C<1oMbHasdiRK6x^Vs3 zw(In=7$X@q-p)EHD98h*@$^kEpzRR;icuW%<>iI~EZl9EuYUrYzxm0rvI#g{*9Q)vLYNkG3S`2GI$$!8a&~);T&m0tfA`~euUDH9gp$Lm|6LIMit?wwf9bvJ6I%{FpbRg! z-uw3}6Nl(8-!Lc)ezd))v2m|4y7uxha3#E@3eAcRDMwUbH60(k* z{xeSNM+i7vwJLWJ-t?C1XL}*^+gAZ}ZS?kBkB+<^YTW<;AOJ~3K~y((h*xGm`I6Yq z*X++WWwQy`g$~9}-L#lR00j z*HJ-w-+k-Ieo^|ls&17USKwSbNdf80lANya-0~Woi0Mn#Nu&#=nJG10oG%)s!|Ch* z$kv_5yhX#W5F~Bkoso10}&c;dh&+k zTcug~G&W+&@O$ZRl=u6+As6yqyAblD-7y!6FAQAlI}g+&)Hv=o zd;I=~zklBk9-i(nb9U&33*LvBMes)6KKwTL%^Q+Qg)q5{L`Bq!-Q~c5+Bb*ndFNod5z|Wo-t>Xwgb-2FF)m7bqZ%>2bk9jZ9bH8rP9gii{BNt2U$|1Ey>q5Fv4vLWut;z{(!uzsYaCf_$Z}ke!V7=R%YSuq{_5L{P}Fe$djwg* zFA>0kle-TIA0WGv86BN+PHXEZg4`rO9h*8I>sVSj;O|5YV?j#+^>cbVpXGLrjw5Yn z|3j#o@ga&j9tz?vIHayO5%$8G%QA-F`t;L3{rs)4vIcju{S>B4ccaTK6j2f}2+?50 z4I9}UnMn`EE36=usm(OaHemRY7_Ot4SGQH4#bj1TB5A6Koz7=#gQiB$x z`)Fm$AK?p3|NPC17v8}15*1An;$ToNt`2-1NevD3IKqM7Y(`2SYD$Q<$6S(~ zef;>?=f^(R0@JT)YWmf)V0r_fo)nbJM%t2u5`71kvHLbSIu{0A}HIljDAo(?u-x^bzc{FO0ypl5nZyq@r{< z9TlAcsUxXV`#Q0O7kKy5^(zy@XE3GXd3o>3#H!paxrK!Gu=c{joB8>5Swpogmybvp z>4&{Xx{5j^wnZ;(QspruAA;$q>0){T)49#$#s)XIm_Wpx?z&%bI!G?#S?yxKa=Sd< zz5ns`Bip;dbkbeAk3;DUKwSow7rN}&VuxQt&db?LmwG?`xEBdsg!J3DlW)(zRnuSA zUMn4!C?H+GR@#h`RKUbe)O3<(ve^gm@jh#9($_9pxcBPWjr)d0JE?11W2HLJnQB|abxHOQSV%?mM29ARTFAyG= zcoSMRE^urwaww`G-X0&0lVCbz3?*}JZ66PVi*3jk{oS{qu88n*Yg;=y;TFWx(ly=M zktq;srNt>TWB6PwFZKXC)^{7vHO$96q4eBb`Gr`%+-JGGYvM5x^z9sVwpNDlqO94OsZYimtgRJMh`aEev=!!{Ra|2`I|wC>f&-l*w< zg;>-joDnXTI2XAhju!EbC|VXc*8m-U*RDX*cjR=9({aH_e7b1p40-0bB71NbBl=^H z9TbIIOJo#Af9y$RP=Ad2QOQ{sR2SFFF6Db+jcn35=#84rT2>={3u~jD1IPmAVxg47kci|IwSkJrPnZgIl=P`F!GVqtkp(hCN16>u)vx`Jy7TTuoXmK>DW z^bZizk<+=8)N?R>vGgDnOviYm<>dUFbXj zr31Wgt3XDPdj(7dS>aST8}*lKc(Ao`ST4X>!EfLknpHQH;f0&(DLg>C8+c_U3fp;> zswlk1mAlek~-1c$eL~L-OC)y*vL$yLa#1yE~sM!1LFT)0OK5wiV5~ zKGH2QzbHS`&rcjWnCD}OOF88|aJoJghj9tTX~^luts%74^nd=f{c^_KXgAdP~{@m=)oIGcFuks~BjN|gwFr;g-HFw}# zBy{=aA#x4pOK0m-e7KL#oO$^0j0?D1;u4CQ>j2$^p`N&e+LnIFO-D^nIFFT{w-PBk z^tAB0YK+wR%>w6N{Zaj&J#mW-*7Tx|jMJ6av2L=cqt58qQDok4u1k(9X{<}w;Fp>B)EpE{%J&%e-t#>U{V#>nBkMQhG&y(T zCXZC+bS0I$k+i6y7a<@SI9ps?B3ULnIsuK?(4q6$DC(5&af7%Xa^zOtaBxz?$+t0^||v~yEw1qWFME+}8ihS&izKAYkY(g$LD z6B7F362?ea7knS+tDB6&>BEtOF=I*ZhCY^;ez}Bnnn~p9d#C5^t&3TzRc%gdWPw9~ zwpSP4d%wxDe`8oYg~szNK`h)Qk4BCUci<;0n0^-)f5VCv@TfcFedmWKhL$-NqQlm{ z(DIA2Y6iLznC8sMfU7Rn@yBjMq zy)yGngrE_zUi0AOQW=QHg%B4J+zQOVxgH{e*{MF`pt-HJNy|jfaC9X4!`-fY zlRLb@z2QVEp72>5ovU%G7xVv7!g&FR*vcA(@+1sJZX^nJyFvSpr*h0=d(x4 zjusYj!pUoGW#s{0B>61I+g?~k3#HMCePLjFM;qOKp!7ZGKDm6{V|b!~+vw?^j16LU zQB6oWTXAN^PU%C+6LnrDMK^)6t3h$yrre z4Sf;jZKQxTBC1q9ajrT8Idau9gmQ;_P5qJmF*HB0R^ie*0vu?7n z?ncdMS=*6wS3i95+SMbIpWi%AS|VBY6TH6gxpf*74pdp?O^5OLHKBe~qECE1ZP3%{ zJoJU}1)*G6oSM)5h~VTfBCCrUPT0%wXPE#fIbEala#vdf@7!D>A5JA76#&2%6sGws zPs4VS%WrH1RSzB>LBr&*aEwQ2+0KqsM#EOo(3OaO{F^ELCY_KR$$|_}oStMYsf@nv z9D1T&XM>S)O33iVx;M)jiWfq`Q5ViB^chvElQTh{ix zIQA#kz|^8Bs&n>QtqKCfZ8^|GVcTLuOcFyEdM+fV@^l2 zWhf?>M8&BZQUPX2+%lkTh*wx$>FGkuVtUceFuf@0nRcIIRu@VK(xGdRoRoCcuSiVd z2-{@50P33Y1$c(iA9?agx{oai^(&Fi4s zczvwcFz}Xe0zY9>Md`rm+oF$mvQRkvl(Lp{TMYs9!;$w3%C1uay2k9<;!bsOSQK=@ zc6E{)YTz2d7CgVVG^Fl=^B+heE)EIBloOn{mky~Hs$crig=*&u7Y9yU6t@fVJ{?Cv z@ok-n7+mNp85?}+#K3v(KXGwD1a;aBH6aC;P(G?SJtU!#It;2xE0PcT6)zl@e((PSg12}l7qs8p9=fsP$ zBh|EJ)?fK~{5L#pt|xn}v;;9)LR)aL^j%0ULT}18V{xGa5c;{XvXU00cwIzgZ!Rfv zG8WaDc27{O|pqg@&h1LqWGhGfs0A7l=H7 zA!VKS&T#u)BiBWuolx)^NhicB<^2pSs z_xeG7GQ3$uo_19f^qH1Fe}Aq|Ie3b>e!us_^S<(SwI@xx<4ymIq?ZMMVS2HeGQE6% zN=?6$^fCkI$~O;W@kZ6?hp=?WwG?+cL97*d6tahI3JItG5P5jg_Q;%SHt9%VB=ALN ztlLdiYY3>mn{pbQYpMyUl$c0W!}O)#F_8WP!Sp+7x_Hwyr+RQmV@Rf#bBIA?dRrYS z*gA=l`N}qOdoC&2do$^{<=`NgE~b~BkVc~|-t-hOopwhYlZ;t7Lo=p}oGxiEDvpt) z7tQygIGv_mbXg$lHncd?Yr2Cso)?LlRhf)Yb5l~#^2P4{_Zf4y*cU`ZMMYo;4{C@i zkoHD4YxpFWPjDOQXapZ%6OSPC1tky;K|p5sVs9c0Gld+0zOm>|HUY zTUmKZ!6l^M5>ZBn(BbkO9qnz$K9Q)vbCNbrlnarCBCUTSC8TsWl2)V-{P7IHzEk)d zUY85$ee}SNeIvu`yNfQAzVZ7D7cXA85E61DI=U)sumMm{N}4FU(stw0?fLU#Ii{8v zn@9oxzC{{Z6U6f6fhcwD+S#@i$jHZcISqxdL2Fqm3CS`}W`IGLY+Bfsb4k3W9*{Y&p(zjPMMIG*u$MK^w(@$v2I z&L#NLKkfW<^^%uAx^ZS=V$iO#FzqNLjYY%2;SJH#O?uJN13g@2DrFbnUn@Pf>2}i_ zdf+448~yLk(9p%4j@gB#qK6IO|O+0lr$ShUB}J6 zjW=p=1hrhg#=fRPw{LRtt!GC@_LK91oSw#9%??TzKZa7%k<+ny(4iI$8BnL7Rg5qD z*Td#YDi_xaG`^k~{q;b#nRcU(!|~kNeH{Fku^w`N+;zQc;7TApDWm1`B?)f-@WYSK z^(M!>w(<6+k8Z#A+AXy7!j`u7_S$x&`0d+4eWKH6t+dIex>X?EPQ-N7@xpZKE9pf_ zDS%@obr#Jn($#3qB6Q{QsIXxV+IUG9uPBo~LJkYL%k`mPB zdPh$(HnF`lcybiQGoHCYd^*RU;%Ua~j!Mnp72$L|B{azbynWKMId=q#Z9#Z}^>p-f zCKGn)_U_ECqOHwYb$i28ebz{HBd&C|2!&fTa`>C)+2Bp*$dbPUpt6BdYFMTzK;qEv?htEkFK6BqUTZV6pub^&&wO1|YJkgg3O zbU9%Sr|Tx@ta-!*qWR(^4UW*#pLpUCyy6h}lek@$Js}y6@_Iagr)!W7t}Ad}^0fHM zcLC)rK*tuAehgIS&L0ZR^EB2huZ7En2dx(WjHvo7L2?(T3_&pRRV|l9Ouq}&mA+1dOtseMNQ^H^o!8{_ zB@~d#bMITc_)gHveb0=G6Gp^zh3OLXBF$l0a^Lswv;3gu&8(k|>Ei(2&jYV6bPlFg z^I)}$3&vqNa~qe~YJp)v$31UrJg(f+a`mtRQ$os5b#4||WeCE`g$Ck+>B6=s&vy+) z5a-aC;_AG*>V?k5-og1X6PSESa~4Gq;6)cK>Pmk`L<9N$ud z=>^sI$oV~2*~#onsUSU}g;fITf1i)*Z(Zx$l{G{wl3-kEB(Sh<%$N{&oq*d|oR{(a_anVf08TI^_&t7m%Ng z9M5CtILur+Gx90#(}~G_9GDm?NhqQ5AU&gqr(yd`k`o6?FPwHx^!DR8KmuJ=>2XW; zVnPD$7dn^nzJ^LC6A;&%>Tt3rpD(E`sHLj3jtH29IDfmZa%;`Q0Idw~J7}Db#C}g^ zPmII8Gc5YKKHpg$a!=k~-)S|wMd7}8Mu=uW>5&^ivngLQl6aLy-Fb<>T+y`f5V-r^ zd);<_C9quJ-R<6)Aw}Ui58mr-`^8UGC%&9{F+IWG|9+0*J$<9}T)OxBIgKgPYAU2p z>Ahb0(bM#eqW9l>@1{oeK6Fdv#&pYM;)~U3*G$-I)cBebQj2zer-U@%P6_FMQBBXG zF(+iM)MaUr0HI48An+F`uBeOBS*@hYW3t(K5*d}R zMZR9*5b6|S%bM{qUF7hHBSGJOF(wIBYqk4iViTnY&6PHz5~+>-t>LG zVVKj8?|9%$jHu}!o-L>(h2v-jsP05O3Y~Oxj@g9;ZEOn3D5HZ7I%3#sj|r7S>F3(^ z<33-}e0l7WV0!Jo2mUBrE@>|h{BZ?e`}iXD<&S{+ik&;bcN)D18Y)hoI`FUKZ=X1| z1i|S*XkKG0HhIX-^< z<9FZ1j1I1A=N}8Czy2R^dhn}mr>g&OpnAzmuiZE~F+4bG*q$vQ>P{U2HMzpcCMSjI zaPdAuG3~6=o5j38cJ}Jk69+!{h(N~wJt1-FK>+%p;b9#A1R0JT8o6?b@Dw%9T$wm| z#b(Qv0Fx1-EwFPP-q+DlTa;Q=H5is%dyGJx7q4D>^Zf6A_tvxBkGuMa$pRH!kDQ(% zzG+l-glr5N0_u)pe67cVCAVISK_~p^wOhZxadI@{Xj}W`TGaII+a+~F@{DMmjdl*D6IQ57EPV={vg2u0)z1Q?bsxzOVlR+sGaNST>cM{t{3#6HN0{F5 ztkTn`c>M0m<9FX!v125VgBVuI_9EHoNxA8Tq@DBI5YJBq>IKH}m@vpVwDCnY?jKO!TFl=%fZWw!}H+GF7(m1pdOi#xj!xnMaiuE~BYKjVPD}YZJqcwBm zHE=p_&o^mNQrhTp*R*bkRHiR=xji|J)G zb*F;Jg6T315PC*A=S-aE)PJ%C5~c!7KeAfl(J`e{aLPo0!3;nocaiPoCJq{c*k!4B z;Bm?DU?F|6#Rx&mx-CPys-gQXEzpKnf7*p6q>tXW3^AP`chS>bmLYTB2e^ajFa2C4 zxeKWC&D23o0_oy#htyRTqs2|bi;aswj?Lvh^cu-aXFT%^M;}CEmm?ee45Ysi7yL-% zReoUkAnJ4wMxt(#F@3riv@w2o6R6@694rAV)z#QKl#Z_IM}@*cNRihCLJ#xLO*}A4 zQ)Y>9w=Cuopas$ogSHy9Phq)QrW_-R($!EcbNM`l+^X@05yyjO!?ojqgr_-r>nXZC`kbk3&F1JV_z zOUuDI&&-?WFdiC`ACluOoGt|F954U?AOJ~3K~!(L6ZNCo&o5I##bf=5sJTl_=S~gd z#rYyFie89>Hl@AhIJq+U&BkW>$Mp}zp{AG6kQ6n&CZPwmJaXjx)jinJDIPtAEnRjd zy8}%BN2uwuibPJv;0>)p-9s0Up%W?wl82}f1z!=L`^aMiehGg;QLiiV*>5ECrLL~D zvDU`eSXUB~x6y4WX7ul)A`|gK_eFrrbo_h)l_xxzEkpH=Cx9*iaH<3Q6UY&(T-Z1Tc+rx%r-oq~oouwB`AHV+^_u5w zoHjRnYH?21oi+XCil$XeJ?txPlp?6PG2Dxnz29%|ofW7nS?@wsfOu4P>GBhqI0KUyoTvLS*69n!9A(A*a-rH90^W`(k;gz zzO+|Y=?q!L-t(BlPoFtEQ^WLpBQu=2#4RBA7n9#&v8K-y=ZlExSktk4;dIe_FQTSD zxODn#7ph!oTU;FK?J&nBr&Qi9Qxix%S{IL`9UVKI%BVmzVT%#di&E1EQPaD3OksM5$tE3>c1u|X{VuzAU~w^!7S)Vl zAuVjQEW^=2JDg+KFo;Y4S`WoR19 z+ZR8VA*#AaQhVM!Ha0QXkWR@SKnMf2@ZXvZg%2?n3#P}X3$UjXk?w@Kz98Ml2g}Ro zC_zPy`M1QqaUj@BQUwm)e)TqNj&d%LuJHWh*FSt+#Pt98^M8n-z9Ese+nK?)sU9VW zF`IrsU^;wmZ4L9IWMekL_2Q~?MNKcKe9^8jyS?M`k*jN{98HTT7f5Hm z!q_+LL9Z;692mgUt=EN>cdxkFvEtdAUt;pR`CK9yW!z-Sr#IP1CgYYQce@7AnV&Mf zrs5;w)0g{V9QUb*f#uXh=o)Fo928(>8z5E2YUW@iYP#OqcO~Vlsvg|l#+~UnH726rYyVLe zNE{=Ot~mYhqldY9c-i<8QUew63X2PMYXfcwwVEPk36c-DW{s>`=GFzan(DN!*M&<_E3kq3F%nOtb zf^%JZiE{SjlBb`1gxkAtzkt>RKaGC8zHa=L@GL z%h1x5+hywF2hXfq{VLs{#0jIU>FiJ<(-o$x$6EgN&x4J}-R6xS^nTUl)rDS=xwAS2 zS08Xj@~L+A^YYrJOzCeUsSAfod7}ir2&aSTLhbyMJ57rsAylwiByr*Jd+yPYoF^$P zR}0lYPOb^Ht0B~Dxyn+WxjC{vc77~LD5Y5!aJz__o_Ro-UaGyF{j0(BdDVINUM|G? zk&Gg0`uX#d2?_qETRX>3(f>0M7tV?E7fPxpGTWtdVX&JxUYMe|aDkvcK94$5FOk#%_Sy5i{i$Q?`9tU7)gq?zb_tI3 z3l7~#9oRr3lrHaiYG_9j)Gf)FWVE)9M`FP4jC64>X^w7#(hF-#N^6GjruU%n3?)dC zU@w$@;>6Vx7}S~f@XfAeXKemQsOei)M$?lMJ-GwjoIV;&=*&cqSCrNoyT~5LMnWeJ zsy366*K3U(6p*eYIz7Lnq_MQL$hNtzBxin3vY&(0j4DjOA845YnrzIg2(6FA^fIrt zQ(CiPYC#QGVmi!(=@&wW&atMufavog$&_}hcX5O3xdU%HvO4-YkKjImc^0sWNU_jR zNBTnKQ}r7X|c54otv`Wzj(~o ztw=rNt6LGyzHMY-05AKM`{t4`?)n#NR%`jn(y!dSvuRUT0y3Ed$=4iZ$p^LXsOe_! znc7hDyg>N?O3&{Pl;!b9NU+>7&BQ zHK5MKm>NYyu$9h~8ZI@YIbgc93(_#%OS&J3Ue4rC1*Z$C-$Np!0&|hmC9hF1oel{k zGWt6Q=R^ZRlmY6(>&$pwzHYY=oL;lZMSNG&m(FvhMKSG>^P@copRu(v#)LBbHwDkO z>;a{wtM*2uy$Gj6=pyP%qa$1|Bt|X_&ddyUn+c|K+(6l0K=p8g$q=PWSp}wl-6l-^ zRQ`s`1r1>hbWgXa>AuuCrt|r2<7;P*axz;}yA}mCfah3kX=#Kzohmu802M*%zP;F( zI(A50dcT?K(3Xgi5rcKZzMX$O`95;GfcmBD{bqA&zsWE%VpoQoUd0tr(K?^ zcRU;OF%Nw4ax-c!2A7tj8SZ+@MR#;lz}ehhP`G@#`=E78OSAFj&0~|-gwp@NPc9FQ zPQdBL%c7=#h?+j}M`d$Srk4lK;CT^JKZB|ct?$I~veRS4^-y-jX}8WtpU^&6e!!1G z=0;Eb@~NkOd+>#&FDza9+ta7%_pIO>=)iOUr1XWO>8`>ny?x4XZ=v5|={)dm+SC5S>*4pdZN0eD&2|zRK8k z+Hc!|+aNh~{_eZ4<9&Jk!}nqIKffpG0^SR#n_cl8L|#}2io&1UW8v18YWdAxQp=7U%M>6L#TK6Eqx*_}Vzc_s>H zi!idlZBom7m*{eI>%EDIeWMxe+t;TA?$ZUj+O7;3u3AA043A+#Emv-bh&g=mB75U^ zzx&DW-g@h1cXnD~nmtOdMNQXo(#wl>@Lj3F1HTek-v!f8_7gvN z`RHZL={!ptbQwiXcM@wlC8YRW;BrVEpUcsV!gw3x>E&y1aVKTO+gpp-g|QP-$5u6L zNHyu0af(?4s@`#P1-6&38^^VUZz)jke%3gWqBH1e@yVnjqTk+k`5M${Y%l#z7@$a{ zw6W3CpDRMwAg&i%tStqY$Z)-6L+CbGgM3i1eXND+Wq4AIZDWc~HDuLA+br_&NiUH6 z7s2!b^mnnB@f=s4D8(RB{$TA6r~9~*F%v``b8drV6b*;bqnQ??4Zgm#+FGz6AjQ?} zY6zF)EBxuw{DHu9>2Bo9o285(z|)sMW$7}^{F@^Y)HUN9vit)Zakha(?0QF^& zurZVk-CFn@#+9x^mLZG|Z;FLol3qwy7rs=oHDHT{1t2G{h4>gXSo=Db5z{C(7BPy8 zkglCDz5MWp1Tk_h=5#n+FkQBWXQ{k(R?ExsBJ?DclL~i%tGN`nx+aE$-4v%%l!~1G zh;%bjkdB&;<3(&QM6t`tmAPJK9iaUeLxH+l5AW)W#Vp~49}%Q?dHUe$hro0?pjJN( zs8=tUDaI8lNR@&vaIQL{YLu=Nb!HG)a(+Pp>C0kzvDA+e^s)>*|2|e0&6v(wP}7$j zB);;wXGBcrr$7Ozw0e>s3$Jp=^a3suR95ZnT^;N#R35xA)Y&^2dr5U>D7QMRtG!Mo zN(re_)Oj>Odg^UKbBpVROHqx{3@oUsRB?^Mh0htFJ^wJdq5a!b1j|xcD0g*6-ow4> zfdZxkzMS5+?U$&{Ss~77=Aj>igce_jc`0P?s|R0-5llZ=o##A2J)qdn#U^r^OvHh{ z6C{>*x}0+BJbhj)Itc9-k)>(GR6l^}1vNcY#PrmV5F*nP5=s(!w!JW2vKKMnd-*v( zHP1~BD0uJU!~GyO3^zAE#@)vGNXCT`=@paTSeg^+%|@?gv)`uX$9th)W@c#Y#(`qR z>AWe~c6o2|4_{+-tmZ6G-j33qFO4ZoUywTUOUu9R z#+{^>@90eze>X)kqWBX*PL>J-KraqOsuqh$bgDVJCaWl1`jin@qI1Y?IOp zP8G8$)R})_Q|5F`FACG8c#}gq(^WS!h3e$0OPeDwokYgHG0qG9!*!Hi5hfnqNTur6 zMZHK3X}G_e{N_!6c!slVQ%)XH=Y-F=S{W&E%|snvIOA?iM^In7bm`$aN>0c1BGwzh zbc)uQCoJ>}c9}O5(@UPH=@?%S)Wan;ULTP1_rvsAK7dw4RD*9)kToCNVS1-1Yw8kp zx^ky-eUJ`S9j61GbgVqe*~fgg+f%C+M0{hIxgb8GMe?F)!YF>2biIDX#ESPs5SDS) z7*$nncC0MiKeD50qO7Ik_|4yw$M~nW%G0e!cXZ8~hYwPh^F)^PzVtn9%eMB*eY%Vf7%uce4 zswIWfNA~TDaBs*+N;1y(YK=Vn{4>9O;f2k7#ymIYVL7zBc=7YkKfm~)haOsdxRY)} zZ=UDu$gyLSM&Bf(WdXd#ZM@+X$QA zCv98HhpnuAj>eCj6PNh8rnmm|r$7DfEr7MVkm(i&P$)>)(Vbq2!H4oBvd2{;Ip&mUgB z`pJ>YM{`LR5OcrXojLT9(%8CMIeY4inz{p(5FCa4&JJj=xHESqx zKtC^RX+FA!N>bK57%>_)XrXk?_QDOx_~h3*-i|Dx3>!N`$BGWT>2Cq$^8GC%FgMBF zcgq$^*R8Ba-Ggj{tPN(4Ylu6AI#FF1ap??ePa-O{3J!V>#GCjF0hJlDi+uG4wET2; z8ZU{FtSH(hy2fla+3IceW@f{z&rHCJt*ejhQO}j0J~lS));dT46e8)GYG%fuz1{$@n@^(}k@$6Cs)t>M|XOB%Dzwef2WM=Ax}@n2zHG zcgeEnSu771yE-W{jE5dww@iZ9rEpYOoNsZRa}qgSbG>k(Fq)Tp0;pG%F6I|VT`Vv# zKjaOWi%<=!t80{jLh6dEe}x%lmuweu`s!V)A467`lgt(#VTyq3<_Wf+6EDqp4D{Ac zJX;ibS&LeefVu_Ncgf>K$yX0ujS>9=)O3Pgu)Q2qJxCX0O_$tsL3EMQaliarnbp}! z3Q5KAf|;E!fpkqwe|iZKF~Z)Ux}}1YSjX`tg6Y!SNIWmAai$Y-$v%)*`N0n?MBzYP zBglz@?p*Cms!O%^0j|L7-17PZ`t`zvezXdrf>gSY3Z;wGD=c~H6o4)DjwgrT4OS!lsnZGqgwLcm>}A`jOm&X1+_W&Yj@OfMgV7KeNg^P2xl zd0@J8akcZ0VrB**4NNOJMSMX`^Zpey{gIHjg5 z(~Ef1Yf5Tp=T))Io5Y38%*+iNV(0t&p>JXFVTp6F_d*rc#=(Sz-b4n%j9&i44C1np zck(tH-|3B)(9aLsqcfL zr{8nW!}rf&AIxu}M-(dh3vQi+D|XIkl{Q9nHDXpYo6z)Daj1joF!+qw$mXCq*M!Km z21u>*=5Z4+2hCZ`qgyHHQ&%`(5y=yus`n%5rKF2aOys>JG@Y-bRZs z@3nmaDu42B1a~O1yw-QX^gC+$ckDu144H%I5W0U3)iOkp6QEKo1Pm0%^yFt{Q74+8 z6)iR#;dD{cQzh!9C#E>lne-KC8PkjEZX{|toK7LQa;D#Z&w~!A>5AY*Yriu>^K0l` zTAbxbnwf2oK0M!O^>v3&rcGOgaXp8FKOFU$Gb31SQQqzvL%>`sy;Zco`d1)gx*SnJ zOXvIHrH7ZI0i60*gO9#MB<>eC-spjnN-~SwM`oBd{P->>M@Y$O^ z9}~#<;wO{_wv*r3lHnWVik4nZj0gpbqoc#1SA3ge$L|{_kI)V1+$Zg26aAz8{RK2G z>bN{~iB6=SbO7kxRF4X#V{`fAK7n;ErId8V13SvY8X5>}FWE*#(BVfP`|WRk`9f#p z5~_<1AHJ7Q8}bxn-1q3)lb;jqGB)=4SjXpMpHrzwZ_pu<2u`0rHl{@~zWw$dF#Y(} zDspR}aRT%Zaj^^-3!GB>BMRxuz#)M6LPsCEFl8+7Fm`OMDZS*6%lwzG{#GgH8k~!S zu9?y=QQnEHed)%fTbJ^0UAlF>1fTr%>+eb43jqJ_$Gumto*Qdxrz5KUV47I<3kyfZ z-a=>8=4^ZVf-Wa8-5N|EHenNT#ZUg`RVe-1n@4(XfA-2pHSPOPp27Aq9A1?oEmy0` z_nj<1lsgf9MPBjN75cEA*+E<-_t6q+t6W)8Me@90y00$Hy^tPKQpCn7!``GA6;IX&Qwx=tp zuV<1RTtKj=Jb@w)v7syLIs&&N$EI{Zx*gsYI~#MfuT844F3Zfc0YFy`M=4&H;VJ%c zAG(}!I6yq=zBU+Ocrj1(bb>@>DI7P7*XolCtwj#K`3&C7A=8?x>`YBB3 zMbXlkHavkWZW&MVo=9=LL+6Um<>u6o1xq;b?v>$2)bwTdJ%_`^;!S^g{JDpL?dO)D zrvF#~9hqI7l;=gM>9TErx>S*(r>nUDYbD9?xy9ednvOXgNnM@Gdd3x{s~^Op^fe-$ zUK7))Aiaa>pz(O8ceR&Gb+AjYb9HdAH)^_bwHKIvz#B|;u66@;5vPUH1yC`BOW=#r z(t*}abajvvu;f00RDo?cU5!W@`dF4sEfdfMK0Afsh0S@6+~B5SdKMhs+?kk&nl9e- zP)$uQF3$VFIpjyX4j%X*_`r{1#ur{lym+zi;(7AX_rywKIqEYVhNu?37<=jzkS?M$ zTgFCK^mW!JQ`jg;FN)JcN@_|-8SJ{$w2fARBG)DR&yUO7h}kq0DULwn;!Kg`gl!Nhmyyq_u>h(ym%i8%upG zo1B;!)6~>eSIU8bu0Gm}CN%XnmG;i>>ykhlIy99Gb&v>OM=~a^c4E|VSC$PPv)m<3Ksu zAV=8+4wN=%P0pK!>2}$Kr(AgtIbG@L*RS{Y+aSKS#J3QBIBGDI-~8#XfBoy7PF-g5tV&jF5ePXar;Wux_x72o~u-lvWsDTa+I%IVAO?*DfDT%7}=F zZ#GZtGk0{Hy>#xKb4Rjw{&9st8PieIrGQjnI>n=Z-1+PSI|b7R%W_A%wt2PAT>QjA zOyAp1S9ex>dGW!;Cyx3sBKmCEiO)ap=;%1!zMY<<>Yt##bdVBLE+$&aS|+Yvy7Atv+wb0fxA)xnbH|RgA5Et}d?6nY zbVnkX4~Itw@p}!HW*uq(03ZNKL_t(RzCMt0eAM8u&XHD3VYpP3l>X+i+FP$+O`kmO zy5eN{)~J2-VTIDe;Pmi)DO)D0%C6iJOrIFs`o;r0kUhANB~dj-YpE z;TXOb^z*meuf&vo>Go(Y3%~&YifwGZi#dwW@T1?PDx+A=dbS0&W znl6-nhucX`7qbhcqsr|%&Xx_0fNH8v5}7`PRsdswXLK)Ozj zED$K_sK*~ph>g3WVXFa5f9qRhbjw`^j+R-u2hHU(AeRVJU%f9g+LchXtBsu?wmr5W zyKFowN=~QP+J?Um8-8rK$BCDhzby6-!^VaKF;4ac*68KtqPnaaqqU{qD7Cn(PI`Pv zwYH5qV#6b)d#DY)93)&ZH;EK@juIv1uF3WA_0V}pY%2rLiyY1<2X4Z{_l8>qSs0yz z96Sx#!IgOgxj-b|7ex4i=os86d5E`Qx~S=Di158mWdO<_$6?4CMtww#EsSL_xuhhD zzvX#)9_@m7S3mkZ%M^G6@6V~aPvPO`l>z24p1%xZ`g4zpJN*$d)bXZ6(PDbRo5IuN znb=a$(J^8_DV`T9Jq6OAhtQuFqYTQjN@l!|T7;1rU>;4zG*g zj(+~g>PH31<#EdXqD>E$Jwne@U|wQgpkN*Vh$|WwHC$Eib?9A^2V~x@hX! z*P||~f>fpLh?6)4z?7XnrS)yK?UvdeqJ{Y_(*cp0fk&CG5 znwBmk-U$=G4VBBkJx-7?i@4B~Wcf!p1?rn&Z#nTu(3Woo&*025xGj(F)E*`GagqhG z^EZ+SQc46v@rBS2l$x%YUYuj9U)mkx=64~s=>qwM7cVk_pgrnoWOE2vtmvE(rY@U% zO4Rhu3l}?SQbVwdV)WFl(RkAvORm#Yz9Q5+SY}8hPj1*07n>%4x6D&atGT7uA(ewj@h*NTc5FNa8&T;ueoDF4(3q)r1; z;d2b>XzTN6Op5CTD35f&0@I2s$s2<@_lv$REsg+v=$yyavoeNA?3C)xoJm~+wsXot z32DKiPXAPb&%2UOZ;Q>O3bsPpsrJ=L;$lfxLL8d=`Gm3NN}qPLG2TR1A42-195Nuv z5s@9s4^Eys&ws#AK>i2+XG4{c{_PC+?Jx6nm~Po0e+M-k9M}E~1<}QrE>gO)3>+n! za;UKsnr*D31yZ>5^`P%4UL|@TWg?+_1q1WUtECUAV7P|qZVpPx#`JRkoY^={6sC(k z-P@w6J6B|d6#HfFHgmYx7GFzak?w1|kWO1*TW-wrl8k>*(`D-5-xE@o>Kfo{(1#PK zPPMb!46*Uke^-W3I$1AZxt5LEzF{1^=oOO@HWNrssp+lo}!8 zAR`R*by6ZEekZeOXycL0Lo6V1c3h%uhc3 z^{4+%V|w&x{m70LuYD|0FPCZo-VrgE@AC+QSm``O$?3$PWYgBR4H49JI+vsGYv)o>7vt|AJdx3MEC z9r4KSw|v7YGbO&=T%zsEa{e z8zWd?j)T~ALE8Da$01zv4Q(0(zBbJE7#6ivvv(j3Y**Geb!*;vZG&?9B=^4l{=kU z*J0mb>>xzxBd6QZ7nTTo8@=J?iti++8+QZ}0gLTr8XHL;BYFo}k>WzSIWn~=f;GyZ zc_;<7$mh7rnd^om3_>BE1vlLT@HJ8+-Slf|}?E$JFR3eUKxO_)19kWheUB z@(1RQlx~+s7X!0|vfI%0R?1L4A#^esWu%F#B|wg}$-y=&SF$?wI=yjkI5DgEVc>Kr zvf;0l$QNul2Zs{*6>*)s7vV)Z9BG^` z{q0efML2){c_mguu9!3suAyU9Ln=^@aIHNBpeH$9r3^m$%tJ7@NZOhu-9qZ(J`wke za=kpsC6vBy-80WW^9-bpppI2#nW*rzGJS;Svv!_{4$d{aC_Gt|bq0hkR1B}Hc>oId zV@w_d()q%$LmyH}n8Ap{0va1FdHOL*G|7q)1zsUKmv@F@ckMPW!9Gx!?)~)my2X!5 zstd44Zu%~XYgv5XIthCDxgvCNy;wLMQkTt9mjYL3) zPXW|Uh?v23a9g$FIdKB(%VyzgAX`qt-G}cvyqRwqonJ6|XQ$lme49n;@p88UbM+XW zCr{oSxh>Ie8>Sag({nz+n~s_u<1F6v10TE^yt}wFv=8GshL=4j22P#6h=wj!c|ylw z^wXyYPGER}+V||C7wL%;MB{EOskwogE{Tk(TfuZXz{AW5G1VVjcUC zRU9oZ6ddqR-nePg#?X!EcS_Nl&xix=>B}SUnRml<#f_>&KLrrZp(4RU^N8g+@Of_& zXL(JV{7b`);cw){Wa+9*Svb4lb6%J>m^i&LJs07j?vF1l7>%yzNvLhB9Xd}z?CBHi z7YT7>FC(RQZe|bu10Zp3V2O%y>7&pR8#;017f3{@E9%Qcl=fClJad}*Kw#2fjHJF) zbQy~pCre1YE~$%#Y%7|Q6CLio=i$wwrr(P-LgAEa~cbi0{sTxeG=T*qO&lA5vs;Z^h|u)9Fwq zGWHMdUpfyn`kniPnnMcv-ry17qS}f=sC)3kB0>%$dQz3$_)z ze5&gzU6d)DKy~%2ORX)KE=9LO=@2@Cx(vyBv825$b(lv(H4fdm@v!N${rt%w5kr1n zUPXR*Q9gZ+_C`Af@Ci&;ORIpOza7)r^e+-7XL;&L4~Y`fi?6kml{qQR9QlqsaAGXX zBvqK593cx6YI+)wPD>Q&q#{NK39z6&lAR9sOPIbAU+~1lm3OgsXq-OQZhUq}d4wT5 zy)2_8yTfqvC%^vm=f5vID!!01_kAm3J`;2LJH~8%`N#;_iIlP;wTF$S7SIy3zhRiZVnoM`1)ojrKPmJ2tla!cTwv5#!yf z6oh{ACUjb97g6A3C;ntd=_h1|-Fn!=%5gvQ3bcLu!KxdtSh%l7^I(X@Yd=+L6v3@IE{Qu;e6>1)@{Iy!3>vE&N^0xR3c z$aMkR%ld2RRVGEH>j_xcToO8s6J^eVhuvm#vh*Tgry&dcXINyGh46J z8Ec$S+~WO9X*{gU8=Y7yWoad>FXJkL}w$KY)OBk2t8uLq6Ks3ZdtHp zRRC%^&KaF9I@)9v;H$R^L|j)zHl)4S+6LwNq;cedc3bZ5l!fEV_g#~lk#H;TA*m1myk6qQM68ZDJxUvceY1fhAjl^<-vmP%Pfl|QbrTf zL3HvQS_zPyb4^^y;TqYj*P=2&G%J^zYyI+_(yQ5u=ebH{xv}rb|69NdJX5 zJ@T*%+HkeEn-`XBq4R~Am|lSNU_Kzl{eky7R`h8Ba|Sp(74xDragEpowT0n1Q>-rd zea~S6v$+M-%1r@Wxh5wDXYwTO=35ppxR0gWKM=cN8(@se6>}j5Z+grJAu$K?vZ@ar zkP^}yzYEfTlqRGXPyd0)MSvYZhs;^zd;&2Y>pYu<)();;9H@_+Ps_Oy4wECO8&BpD zN5ajnTRp`ueel{(KKKBmk8|S2Oe!3wh#)i+DsaveJ4^AVjhmqK1kZOI8Ky@zZ#K!cHG+GA>o$b zIz_DbDe9u}UH11Q>((M9DNi~F07$wyb%OoO{$Lj#j{KV_>#uwA+?AyXdCC0TV+V4Q zV>1WH5{GgpOZ&LUOw4Hlc%|#nB;8a?Cvmt8Tqr3j*-bbjt`{ghpF;`34yfpxC5%z5 z=}+Z^Xk~I|!emda~KrF_avOUA?Z39}pQYC0&z4Lv_gU|6?(IH<;e@*ZqLM`?LNM z)2B*Er~P$my7Ajyn?J=& zmFyiXf5Lt|3H+W?(}{Xf87ow8(*DzrS-IRNg`}FC9-NbvkFz{4mCs760N1FR8q?Qd zI!BnTbjFZi4b!Jn!@{QKRDkILdb6n}6ZaLZw$Rb1(r%PPU1M|>f$U2UKm4%rraO?# z%KwaD>PM&3vqFMw}cRHe^RmQiQLT21A82~q!>r-^ve@2q2st({{SMT(-P z>xfpiCnVi2o>o2a5m+3YND#@+27nxCr~^IIu_XfWm?}~$v^g-u)0PHEsDfa+U3w)< zC2~5L{;ufhXWKfSU9lr+fG5YOZ@DzKkMBo2BlpphX5w7 zP@PF5QFeh=F#4e|`jz)euiyAl_}-JF6QdIuqoeMoDpMFfiwF}QEs-iA*Fd3@FyTdPAUi`Hh>lIsGeXSCGte_1eHK>c!u7WEPsNGH-j9?$7$cI6^c z*(*tX+`pe$mR!mW=9ngHk73wcN$Hqfe20BG6y(7q$FVmhhkc8>1MU9B6W*^#(j>_K9jQR;}5 z4Ugxb170EfbVqm|7nvO`QX|6aj3z;8p>t&(;xEgWgI5%2r<2D5>eIS_zc+byQj#a0 z^d#+z+?SMDQ2N}tvjSAdQks@JI`UU!mbPy?D=R=9bB-%z-#l@7T0{nUn%3?*y9iUk zs6FZHo}TUvHkNXGi;Y|`U6a!V=rOE_RIdtDsp6Dwq>!|-yFlu9u8AjI{4VIn4?U!mbk5|2 zRR$#;*EYcV#5w|6$U`BIX34IDbW1{LR|>uO#}$>MofDKUQaf}m=Q6mI8(e_tWTr2{ zc0%>5IMbJa&6vlgN(4DlT7cZ(NLs8Ks(idGB7svt5V(IvK0*n?)7tf0}SRg~(<(v*{q%PDg zLoV;JeDfr^-Km|l=Ws(HT@AIGPGNMuSkd85V$&0QAf(2S-TAviV))MAo%f^go}9dp zo}NZb=^Pk^$p`lMu{|Vb?Gd>jHsAAyfs2Wxzew!3RFN{F7#KJ_b3PG_T_>dnDHg7f z8`9ngQqDVY;DevM_Q3})iEm~8MsII%n)CkoluzWiIfHYs!Fj`mjksPyN_)To*={!T z1iTtcQDX6cRJh6B+LXC*lYbl_nAb;^TtY}sGWU=@(eopYV&~`gZ1SgUv9t$cd}&D| z8Z8rrE^$6bH%BM*#^F}4Jwi1sJC_~GF#$?Q@w}*gc;^H5+xX_c_r5Kj6%{#{UA*gQ z|I?S8lW;!SKQ^x7LKBqBSzlkBvDQdZV@dR6T&c+EITaL}*5w20g6bs|IkA2(Y~H+? z>e2f*)8pu2Kh{?f;_v3*LdYV`it62-^74~*?vVPF;|14?0KAgaXX7@({UQS;+or-7*Sz_|?0csNwYr)eA51lPK zx|q{pb&K;wV4V{tbP0WtcBBt4m82K`vG`4&=|D`WvpDd@;FByf5b5uP>m@5yA66cn zmEUNT0f zx4D2M3Mq#pBpQKGAVguhb!BDy(TpTe zr@#I^v@L4-;P9E(J`;2LJGDrk_^#6he>-k=+=QOr`uy|X{q9Xd7(cu!dFhOI&bAzl zZ|;DSo8##@n_YXUS7ExqIE1d$^D}>ZK*V%%U*sn2zHdd?@T#DsRkk6SkxQR>8aW6@zR}M+JQRSA?_28NLl4*%fyxI?_oH9L=;N|6x*4P-z+Kx@uU3lr|zZOgnA-7xtZt$lQ zrDL)uk{ow(#9-JUlL!xwKv(kR+bPi<9qjKSMH0))`6BaCb0 zjMu3t=f`w6u%3QPH)*yJ~`G#?;<=$N7pV2)H$XE&RW}!=>`3q zc?ccqhT7ot%SZV|8f%we$-qN_BiWM1F1DBU0swy{C(Jh6J36qwlia>?EwGwxazvkI zXKA(<58tq`h_Eo7M5E}aBDL3%Vh*LJTl4dzsQEjMk-&ho!6ZB{3s$-6f&zkg=S;RR z|FAnqMY7Xl8AJV!Al=1BjA8tR&~~7}EHxkOC;a=!=_V&~@S$}2h=K3%sYR)&;n7Yw zTEr0J>nb&=zT!K>>f&yV??s4R{OvluwLA5r^fqFM=_PmNN@4W5vsSH?&2Vzmo0$YS zrq&cin+rlQNen3{9I(PX+&7fu$FF*aUM)9Wy<>vY}SVw68Q5J}nE)gS=^YR=G zNWpB>^kqouAh@XL&&j3ax~NOs7$7q!yi36(y14*1SSdbkakf}AXyNoJ*UJ-+g4GJ9 zk-JGvw5aI{qvUyWCmX_S zz+zxuLdJ`1G>?;4=N$Y8(`9aeq^?wSvAqz^D3m@0=vtxsH^ON)OVzl3qGzbasw+F096iE=Vd>SY!{w<}sOa7U~=m zLxH4*=|YeUx{=}omt1ebbK!FVZN=#d&xN!Vgx^bY`aO{N5~ZgLgtHvXAWp?TWDO*{GRC1{+iN!*#u}-In_%OdT%EubPbIiAzG69Q#ooO zpA*{7W%vD!pV5EK(`VWG)3zyg;FRCS*kpVnB_-(7&}&80q_Ha*y9DxXQc`G352G%&cX6>ucW*nr_b@rOTcWj(GAeXYpyIV_+3QP#Dp%rB0+LR zx-aSg03ZNKL_t)Gn2uWM2CqZ&t#aWYTDnH-Dx#4b78#0|-P%%TS3N@|;r7BLyZ;l!~44s?{#>}V2idTDKKNy!+;HpIhT+gw}3p$;7E z1i_=ai#>)o$GE;B;%kPQLbLxTVtUL><)Og%?ElyNgunB1QgXy5!tkC-N57NwVhYvt z=!G+wFMR#Dll1Z(bJNAFBL9e-gQXxdn5GS4ToLITOlQc1SpGv12a~570&&bLG#E=b ztwF(ILO&Iz6ZOIuPxaO?-J+&HI9`FQmzx^%V}ku+YIHR3TM)p}Xwy`R z!rglbCuo3URB14?Ne73A9S}6o_x(v^G~o^@&k81;$ZekF%Zup+NEcmQ6V@$?x;S5` zCS@7F+b%fiy``V2n^z|92HT6gBZg$C%b|jBv#W7;%%+^Z-(Zx#d(-~Y>lC7rt*?z) zuA-)whj~b11Uw<87aItjaOZ-4l2!_uD{=h_y_-{;Y3Y;N45vp#h>$LgQs`!G52f=p z=x&$Y(Vkt1oc`JCpS^!c;QAk~DbhHE7&Rw<2HzZgv9hIND*1GVrj3l3I!r70vAOHN=`Od?Kt3!+i9N#Tz z4H={T5%Ih|a=?d!eEYk4ub%$pFZuMKA*qa7qdvPVEhBBYyA$!~@KXlQAT;y(E#k;Y zQlv!@Wui#vuS?$IdzjEyOq@J92<{G2St|9HbSLfSsdVH?&**O{loH#rw9$xB;_(d{i|{bNUX z)Sj#7Ye%E@4gc}8&t5qYGx_=P?H)VfS&x7~J+iT@Ysv!r*+D^rL03w#;7lat4z3v4 zF|slsclpWyE3(TyQo_h7EGI@YD8<9tH`nKAOW9~xRGZ@TbC=%G{ONjH&f-t+W}C74 z=v2xdjcf@El#)l$d>PW}-XL9wG)xD~pZyt>KB7D?!1_qaf-OlIEoa|RSu*E7IXl+Y z(yYwr9Uc2;p_2y&uHD`~rm5**`cO&NSex>uw_}CDGeh-hV7ZdbXGy?1rt~#yR|amU zIVqSfC8}%r+P~k%6Bh^$7gyAC9lzpMVMxqX5r8|s7iyvnK(ItIrqTOz#GNtsC4MaJ@uCSpFFZrPGO2G7!MY2A9@r{7bsVT z7wKH8^3#_=<3i-XE8Y;fpKwL4JoM0`53O5$a2Hjld`Zd+FCYb^67Vh?rfq{L>59|U zCTn^+4}{i5M&Bhux==X;%{kxP5Ir6Bn-_tVQPW*O_VLAwcO7^MmAo1?eb*A{4tn1@ z?=P$AaJr>}RLt_4L0#phvocLhSEZ-oW1;=1=1o`Tm-{&8AhRM6U2!^~E?33$B9FEF zpy*&fGjd^Ov9t3gcr%m(%On*COY=YH;v9(m0IcpTDJt-}NY^qniwRc*&J}rcRkN@F z+%hx_k0h)X&b%X=A3n?zxG9g(9;Y5IjL&UZBEWw5aQ(oB4fE&s#w8~w#~?9zVJGQn zl2ZcTw2?dyq+@N7ex1Vn%p0zqzliCO_Ri9gl-5S1(a_S98O5nnnWtk($S&y$*J?`u7|coc|G)L=}FGS;=UmhqdOqK$=Sao zx+XmO2Jvf+L_~I#=2cM2C@JoYzFzulC`<>@BR8{esUXGQ{}1t|+c_utogT=E>&qEP zuApU+bQr~oj&-NBZ{Py%ZqOVmZ(h5$Xi{u1lXzV!C?pkP&udD~Ol*Ca9;A}R_`UDl zyE)Qp6Dz5!3vH#%`ixeWr?e_kZ*R(QsSTAdMzIXIxI6{0ODQQgr$=%@9Vtiy!fUt1 zk1i@ZX^jw0q%s&lI@71)BA|E=#|wV`rIeA<&k9Z_&ZV!bU^8sHxPjPM!fcXD+MDb8V!h4(6EWTL=lk~! zP3J`x=uLF+Gnk@^ye%X?eM-PzRc^*+%U8(PGdfG}B)#0pP5<^Tq=2<%aske%{a|vy zF9dNdV7kcQ%$enHk^_DIDqfv-M*g9Mk53m3n=##+2PxAF^9pgjh@3v#L0L`cZ}gyp zv=tI_y4)pdx}dsuXvpql4kG63`9S4^-5hR~*zzwArD#)2)`$lk5qznGi@Xy5EkkOe zT*FeM8^LsKI{AXEvZ|X45+j$etbX7$PpfgBM$Mu4$ z5Y_1KU(sl?B@gs(^QU8*37}c3Hdfi_t;0~$hbe~(Gf}7ps;7$;HZ6@dnlvz{ony8W zoe&Hhw+E4FXA}W}aQK~k7eK@pCZQ9hwS9wo_I9LFLzTt$qNTkgVFhVEPId}DmY=;P zNiT2hpsA=i-Q9ZUnb%$sHT^@vR654SP|<()mN2>uiRwm9e-lpskU*DrE?;iLRzf#a zk@VvUII-ym)8Dyzb_b=RJ4OW3VRMU`&NY;DU|qcF!-GM&t9&mkocGK#&wPxUKGa`R z(^9s4Z3hK}VN{ELt}wmM*i0!E{n7vXQz-q~5lTq;6u3rsOM7L!QPnGHa zb`bG`oIWDikOT5?o9#Zx>U_g7%^fa7Odc^I!P51rJ>yH%PuS!-%~ zgq@9!xXaum>ok5-P|`Di>{YYoZo!y7Yo)DSyxz__+linVdnX&m=;qX##zwuBtD{wb zm9Mo`E~O_e%q|FrX`sRc#h=O5DBr%mu)6lYU;*|Pv85<2_c@jCvW)s_TrL8RVqpPQ zF@`IGgnyNmt%!Tql7r$Z;fo73ER9H2*11}MEoL!I3PdHwuP(-MA#=iB5Y*LG1?^&Y zdHy+>D2UO8%2Oe9)#FHrT{cWkY=Z*lhr|IRye@^N>%`KIoBfF=#$}sCJ{K;R$$)00 zQLHXHyh!WH9P=2mI^B)LldkM88l(%N3$oue6e~ZsdR*Y0pqItFP}5(czY==7RFK|x zpENhJSYEW87p13La$c0@1tA^Vi+sJTKz+%$rjLu9E<;0g&S@&e?v`Ou)YWzMDpN@> zb0soyo_Aii3ISBo`F=Po6*qo()9ZkQi;DWNY87fEu3UvfnrLayk!65?_G zJTZ*?n_>gdo&oVaCoZyxCE)q#0ZD*4eT_^+nOHDRU+j};Y=!BxIKrEL19LcBT!G{L z_dnWQjOk^Y^QKUj*>3CR@HKtT;h8hXDMxcgyyG(;{mpM1@}Bbn!2J)-e$~9s(=S7m75vi^K z>N6bXwTe@H9$_yil@#XT_T9Xha68D|VS40rE@yIM^X8?S>jz3plVb;ZC2X;~Qvyky62gdrG+gS9Z*h>@FXic#nSf?`u`0S0>8ZZhn6JxENWU zee2h>H~P07$2&R<`|b2QpMCANB)$Ck$mhqgxR52HiRjW!M>sQ|NW92k78rktIYC0h=X9Ue~(kScHb;9$@e`xuwVXC8Xy z_5XPP`W3~##`aPjV9R=q8{ub;jX!XjTPSLEbO=bHrIKAXbS-d6g z<@}`4zO1Yv!(GZ;)6Hbk=3MyT51lV}N~{ZV`nw;KzxeUHmw1^gsa1qZPSCb=Fl;oe zfYwls`tEFfWqJk`w3N}}R-sAKawxqp!rfPA>Sz{f@8A2A*M9!%|NSq&xj?%mX|^Po zPJGMd%1X*L;XoVP;h>-fsWNokSH6!4Kub&8S)}wm*NzmW4h{|n96Iw6nErb(ef^=w zw?n*vwvPMPyYAl~xZqI0@bH45;ghK8rB{-2N4LK5hB0u<^8NyQ)OLROW+O3vd&8rK z1OET){d-*0=eh3>2MHKJ9Rs5XC_dPJ@!*_;Z=6!$e&-J-Rtm&MSlyoxNTsD-{atUY3AKtz+j-LL`JKatdRL&a5 ztcPT>K+GROgwVNjK3UXejU0%KQ z_Jfv_r6e%w8%e|j(n*{L)Dgo^*Nk`6w71YMs&xN2bwf3*xwN;Cu|Ix#T_Cd$&p=z- zgbdP!Dq!@52?+^pfzoI7xo$~l-}@Y5dP0Kq@gzINjZU4k>O?+|isB7xCMIXZ;O40- z!)=7JoRLmpCAAlg_d7Hx{hj|nQ6HtjXVQk?v5T9+*Vm@$yma*SL{2BC#SS&y&RQCr zVr`Ot5F%e#bb`?J){=KBEeYH(w7BWw?47e!O@|m?tgWNXro*h4*y@&wDMrP?sDf@J z_w)>+UYPvkX;w4a4Zi7P%qSu5x}+Vva`R@*o3%8-)<*BlW1!GG*~R7A*_x{P5_YDv zX1$(DSKWqGN@=M&6{`%Xrc{0V+8EL!>LU2{s0+4yrHOeQKnA2mFvkr}ohExdkg*8h z69A(i_k_4w7!Wx;tc?S5Kub?`Ci1n`;7AY~!JRgw+(h%Hqkzj(v>y+OVi6^&rF*}HwRvDhI)d`YGm{* zn>P2Ext5RZW+ccNuABM7^Y4{TdayZWYhiUvFaFyA)exUOl5;3_3}s9wk5S3g3WK3; zA#Fi)hA8E5x*QYcKHn+5-?##Ha}FmVo#X1N>MV6@&S7+NH|mb|^essIT?3gYNay9T z{X3JvY60u6hWIOkSFYT?B1UvUbkWn#o#zwl8XsGn)rlj0kbp+qBci3#f%FWi>HXJ| z=}H+*)CdFcAFlJ(&w>({Rj?Ul5dqVo7*sg|j~OTl6vZo^yH>v@?Y_nc>)fW#Xt9NQoL zFMz~ZdYO8}*EVH$m3(pCtrPOXpEA3_|yr-Hg15gzApf zMLg&Z@^*6dMxZ3<1<%V7U>tu7g`j;i_kb_((+3&iQ$IosW_XGSvu`-~&a{PAXl zNX00w6;><=WsHw4udb%)D0Xz3G<7A%j^lC}?_$Q$#j3zCeT>Fg1ZWs+C@+dn-oi6a zq{HeU@4qh7c=?r_MB}VU#Q8t@u*`1~(^^D@B`rWc*QIt*va9ETuBcf2!xnA6Ma!=udMh4p@T zUZ(TjQ!2XPx|mzonT?{YyDte_iPt`K6QQl5qt^?l zWA3Xx9G-T#w>Pw2r=b!u^$!jmwo1<7Dp=F_!uYuN|#F*sSAO#Wx zffXI+OH)P$;U;K-dCmj*>Gp`uc5xAQzBUjU3;W3K!s?{OWLoFpX#mr)xqKj1q>9t; zW_G{xIsAQDI$6H++kgGnpTE;_x|@t~JALb_w=STjzxpviuFzbgbj$ubT>bX_Q>T6m z%~3wuk=+gb!LD=Ipi%aERp9jE*Gw)xPMAqxfj$$)I4i3J&yf?f6n z6*V*@?JF9nvst(IhH|~!HkBn&1Ug1vBcr*neB1dKR=>+P)x^XXxLpv`zvz9h_g-~% z{cu`@VJvDWiKQASlx2y_#CZR;L&I-YVIu|0UG@_OuN*ISZO^Df>$Tw=RpMf3pA*3B1aHJa&) zv%bVYguWh1Ut7^ZN2!~cEvF7y@FR+msGq9f7zDOlWTYE@Wtz&*Ubd3WBfh= z_IvkYNE)xHQR@xFyCA36sN{4OUQF5Ru<>}ZN?>c7N2S8Tgry7hwt+CYWHhQ~r;@6U zwBF{FA!d;>RDbcK8z|!>^FMFQOeF^WTRjbis60Cl8_ENStszd+B=+?Gh|xj##!>!R z#wZmjw%0}Da?|u+*5%}oo zEJ)es*@cJK)(0ferOhhU&5ra$R!gk;kCQnM&w=X^9z%~Lal?4kVW(dKaIf9415pGq zed$swG<$gn8w@XYc1ZhP)`it+_V)F))ltC#(t;EdI)uJfGo-_%{Ph*MFedj^8-Taa)h6!iC5qC6fPF{Ta54GHHXn(mSjgkb>+noPM7Tv zie)R=nCGPt(o;`9Emz(}l%o>A#T~C6MWsJtLPxqk##IQ7;o+GBXwTsFAHJrP^hqbW za=O6h=;p%h!qn`6{RGs!P{p~ciA@L7C8xdWb@CV`=w&yU{=?sBa=PrxuaLSH^P=r* zzVx5S9WoiH!Yl)k<6{vuogWE&;XsN?rxCcrl7R|h)Sh<_#RAi&&3&k*XPx(Jp1)@+ zT|~BuBpgOD)7C5u>D#jSGDNA`$QrGKXx2E=r7lyHUX*NrTF&DWPwC+b%QZabEC^j# zog)(UGC9;0wX0k9xr8%S$f1Sf<#^=w^Zk9d7Q}a5?{B~dogD9%EG;Ez8cE9aAehdI z-#LCHvt7uX&B5;ikuy5a`5mI`vzkG4%4Fh9XX2T`#K99?@r9D}LJ4W^rs3j)*W*ug z^~Q$QA3T_gH0O6dWUD{2+{8rHhZse-Rn49dvwoEy@sw5aO%E{8pR}s#D5`oDt%t~b zJaOvArSVHAy82@ks3V!jQf3L{sCxeyX^ zVadMQ;bMp&=z8ZM%O6fcj=Ka}U?{2np?pNs5ybn^T4?|3*bVN>nx{;u0i zwEZZg&XQ)M3E723wb>PI$k4TS zynW^rr1b4Qd-hOjODcVFuHSTQEYj1cS)_AU6h)EIA@li^l#L=Y4RX%R?Tf*G#~G19bGH*h?dKBG>==nNhATwQag3Z3>4NnL&r4SW z%N>1vu_UDT78g2Wb}8&%5Ytc-hfL1G3~4YZ?WXZUV4lHzqdXa_3_?80dhu=4X+ILtsg_q@ZKlc=FS(MyiG4vk z@LNJ_EaYpgI8%bjCH`=}a>{6Oy1J#v^3;$@){D&Pri<$ZJ)O%e+%Na;l9LnS>YZaE z=fySvXG>IY>X*qVmY0V!NP3B?-sZ~0z#(YPY?%vSP7kdwG^d4|4lj`cQe|&Zo)`8g znZS%AK6Q42>DnMOT@7W^0^xDJ;NT%6H?ToZ3GG-$ozyIFvF=ziu-062ehr8c>_qXqgLjJFecZ{by(u^4yPNSE+cw ze2j8#5z+`D4Ak%+iH{O0~l?m|D( zYKUs;=6Tpb$<-Oj|Hr-1zR91(Z$mY|F**sI!^YnD?*gl&AL)HQc z23n+*X&g2p=WJ`>T~8ooSqEOAj{6^d|K~sd6imN|ihtt7?cwO+_!GAdy^WmSUSMya zagePIQn06$?K&s^YD0#Cb_=E7xoyPZQ%57DA~5~aj}X#d+_(3%IJBkWvb)VV>LzMB zt$xO&4e2L!JI1On9u9X~ltg8#6V4E6uj8hVK780z=4Qw<(2%~ajoRMQn@O4CPx%9V zj&AdpdgrAV`Mi&-O9~dJwGEV>XJ;=(lOQ@PEJ{t!z|uo&DzkH&8!qzaUIfzx)L(3K zqXYuJJbCxQ@4)n1Z{v5#v&KNO!xvk8Aa;9R1Er~VV0j_MzTjliNkshuwQd3Z001BW zNkl62-VLh&7qNb%4_6 zV7i@6M83{Gy4IvK*KaDs%@m>a0Sgm18IL|S-lb(&#E0Cl3lHukm~Qiamju1M#9n~r8;Ppb3UKzKS^ zX8AM_N4Rp8U{FEPMgHDMe!7V2;&LVJYNDO16Cgdu*eNX?Ycb?|s}G|J0y=wd$Wf(>iY4#RmCLu~0PS569TH~- zLDY-PAJ{Z{8c8AM8Nu96E<<3Cxz@lP6e6dmQC^LXy`Dl;+S?R=R{U9VZ-~oICL~*O zeCGRvkknjt;lc%1M@O8o-XTkrr0z-;fzJhYRZCo63wzBa>|Ds8c+>GUx6}@^eW2ii z%`pq`w)n5yoU>p7jg4}0#qxrfp8HvOFEyp1cGec=w>fvz52B0D=%KfftObyPzd6QlkKg9OoXyQM zL>^aGbOCgUUlcDo?sSw$akt=aXcomC;C6KEiJZR&l)=mbu}dYX@H-cSK0%MpT)Y^! z023^N9le)q_8;_fM{HL&o)hE{G| zkLeH9^oLzYXFPOYJiPr^j_}u=&SZ|+o0wh1^a86(p|Rq0IfSm+@jjv?L1T1ubhLC4 z)EDDLQF6PuUIfHNjR(`koGzS>IbGf^N={dotGn{X^^)V_>a#VRUYl+yI9rUi-;l0C zrlFPISiKc%%Nz%p5OCv=EPtZT&1oj{;ShJKBgBUO5XcE95*xaD_lma85J6ph={zlV zOgK4f2Az&_aMiKYc9vfh53Ol3LO3 zQOxO$t*!rSm6%>y*_BxAFLWUtvaZ|URk&@>#I#+ze({G7-j6N|zc;YoV{f(*@wp5` z^lkTD&wrZcVV@pRN@#l~;e0FO2-D;Pb*5lbNeDyy`fjP{pPiE z%lXDx&90~C-HF#w(}{KYL6`6 z&(3~ez=QPIQ>gC9>9yw3R!?7#btl`e9R1nPe)tiz8c40c-o4qmqJ1E6$;@ zd%f4=@0RY+kscrJv|~g13NJ4*Mhw(|+B%sohNl@kX`_Q`@3~^_!ps8uvLVS$6g~aK zZ5BC@)1B-xf|G*j-=lNVlLCZqgF;6Z2k6*?@M~QlZf}0g&U#(o=!;6^MpVau<3>sE zjtwX8zWwp5K>FL4TK1dL45`$v8mx|cwz{=OA)|NPABWUyI%-VW3%xL5!{+NuCNtf9 zGWTaLTw8&=GSC!`K5mtoqSGzi5nyW@l}3#yF^6T{7EI^C_GWiD)7P7reX~)I@!pV! z@5mZpMwd=ASXmL$i0uVQTioAvq=`Ej@!g=O3yA-zrhZz^lkxwk{l-z2KlE-oa~dZ8 zVA_z{>f@xnr!kxQ%{&TfeXZ?igQe;|t#PMQMyjSTHj<2ps|8SBNG-86IAV$msav}_ zMWq$4udX#)x!DFw(mBbEptNARH6chs=`gr8ousVfb@!!;6fJ!op96GR;ta1~FIpkV z4eZ$xJFXFI9UUHxJa1=ZyEND;VysSjB5hbJQR_TsSe|N<2D?OvYDirmU4&`{x!S%^It@XUmVN+Q7o43O*wWQe1aZr4xQFEvO4BCH zQD~XnghJ;D5M5#PlN)zGv5XyageR6s)C(#(YPuNK`PCG4ajDZg^vQn^ll$}B0UEmS zIXEtAx@hpLG0%|ME}83cAGAl}JcewZ&^p4s9H(i~KP>;wcb5NDj4ue~7EsrYs?%Wg zPdJ=Ze{ zZuSIA%^|D^6S+_o1CmSNp(wqua3t^xQ*%t?>`o%C9wIlmtp*=v2x^NERleJA?q>ggZbd*XcGmA+U}M(QFm!y328{XTY+vkxEx>uMf9wMPWa>>NSq&fkXT9;b(sO&`i{-(})sBVi-Yr{0i{s0$$M#}< z;l_Og$He!s$-Kfc>FMl&(Q&;v^4l}{{rY!2OqtcxREQ(JX&gKEZEP;LYqFch$t*NA zMb}o-83?u|CPkuMD9Nmi$H0!5Uf99PaADEPPGJ=>q(JFGM-mhLy!W{KZOO@UCGyf+ z^iui}Mb2&}+64o^Y)P9&B^NlC=As&=M^Yd#+Z8LjsFJE$H1Y_PP7SFDs6j-sBbbwq zkweGWEiNuGD|0r3Pm!cE&T!Zcx6Oy2=s4QXi@Tt!W?(qhzsM9#0webN{+gzOit+e{ z*uLRmtTDv7)HLyAfcN1d65t2@Ia7kyCDBpb?BgB(7t`gfm$&3G&GqsyH~rxovfgsZ z*DdOQshTcKJAH=2^w|;UG^8xnJv9VRW^-W6-yLd!ozR@-g8mUMM&55^yw1)!X8hIGh`YfD@js8Dwxjs)8~7K(1%p2 zNX7J`wDiz}Fnc|&VN>)))OxE_dXoMPvvn#+>s=@RT8nJmsHdaG&WgU4Iy6m56v3t( z6%m1F*&2g7jF6vaW3V@j<)>$WJxzj``9cIzEyx~-Lk%feBn+px3<)o}`@z5cg4h$} z^jF_~7rqsl96cRx`j1{3D}cSQWIJ`__JQetc%Z~|V!40x1B@;oz4OlfQ3_Vs5`!VH zpx^;vAaCE@f3h3X@@V%eW1dG{T}694rWc{~mb}OR*XXF*E3eQTskL?0|EgpU_lv^x zRiJyB0YmOm`+Dg__k>c@hdj@Q-yExJ%g#3#S`BEo{hd!e`Kg(wAlc`2b#*ub%z0R@ z4f+UklbBvkoT?!`(mejTaQdNZSC5jF-1!2K4x<07h(quG>$|_n{p@`({R4dHt*xU3 zp%^PjZfwtP$4gxx;WTlqLPVs~@R8vgVWu8HZ@|t!mS4&OMZP&L&oFB2=qS8Ok?lWy z`suw-?%us|_s016_{EE>D!T;4AKX|6pS!i$w)u*ju5-ddKM;{Wep}*j?wqJzwQnCj zm=$YJp1QN`XFvPdy~nYbkc4@fu2PE9yI*{96xR#3m*Am$@AY24SGvRZ;`)n)`qUj5 zD3EZeO|`K>QZ}2*++bcNZ6hOq-9n;M@-j1TXq?`Uo{pT}=49)YB&KU7Gue5tIcX$J z;PT_F2?+vwSutQTlAiCZcWU#*_rln#$~qOL-)y&gBHf&3bkmjTqtc=C{uBTQVM*I4o&^*Bkcj}?gV z9{AoP?7Y0v2PlhR*(}}iX<%V=3Q1Koqter#qJFeTFkOmAC-=xb(Kvl#^|9rmv#-YV zg6##@IzWp}2C*9TT(VXqOi|-?&IQzk%U2&0N|$0zm1Zt(7X|4cH0}&EABPI# z2{FCE=*pQ6ct8K-cfjhON^>Ig_tg_f=|c11H>$egbRlj@F%#T38sN%8DR zX1f}ME^^2{z3@}PbU8(qi{f(&vs+v*vOqu+Qi*0fMjqn}ACmMUkdB(Z3xHm>5lk0O ze~9Rl=5!JnwaoONye2^}N=`o@_r1Jl+B3^`?NXWP77g9P=;C}?_WbkeZvmq(>*2Iz z%$;WWL(OLqmi9)j?h_DG(M3(la5ZB% zHeOQ8d-2o=r626YgF^aZ)>a?BW2d{*$M9&#h50=}^MQ0+FGMo?R4wNv!KqG~o6Bo1 zuSps@<%xY)PSp_WNBf++!z7<4FGyZM8cckze=^}Ol#J4eGdUJ3MJP>2doil_^MqGNZ0aavf4r$9zoU?hl=5LyQwRP0OvAP1iC9*GWXq>c-M-zi*>6uX zy9EvYeuQKA(JN9o9cM0YJW)hNBZt04C_f^ou5r4QL>2{NBjaZUhwE}X^iB<7ootL{x7D>XT?L)%h%NO zNB)eOo@)_-zh!Q^P`U(=vzn)sjtZv>)ymL#9ie@`%+;WCA#;g14C;ZAvO!S5IRS z(}Nrr&mn@{+h+-BSmpI42mtk2-l*)8TDtgMWQfg0A(k;TWbTy$)ij6SV62{X6C@X z_ocbw2cMiVu=Bibz zDq&dC!PBBDD+SRWP(%8wOD9*@W#d8V=x~N^iFa%_H=(Bg>QcL5)#Lk)KljSf+=3_U#)*kJlx6t(}$M@8{l$-u6q>^vZy-=&`!vq@>#sAsN@S_u#RY zpZ=6O*|-5_52Z;$m-%MBPDfx}LHqcrQztNp1KN|Aer^vUy4YM~$9G+4mCKo{G@m{D z$!EX#_=8U{o-~d&b`ZSCd?qfty`!l^?KwA@nw<4i3(_XiiOxEsx={*m3#iH^i+fM+CD8^U8`rm(wF6Uvk>ZDj%W=JwrrMZl zFNWuBNcHgWS}Xo(9dYMoIxZ1csB7^1fal>s=1(@5o>^LlC(5a9)X6tt9b2+@U4~%@F}<|q0VSy)({!|@ zI{d7`Dm9?BwYB6df$b$xm4(i29fiy-OdaMD(+C|>&1uo;Ugq%VO5Io*4PTd9n@lF7 zRmb5dV@Zj@KtXkIREeQ%)ktevTBWJP?KrClGP@dC5O{ud6$(kTn~VWgc_y>3 zlbx5Cbexz3;i6%of?5#%-K?!`Nk5hPQ|=;x%F!M3Qs*s72(a}EmWNPxO{|TyoZ>;T zqm#f`A01(iPUB%WSosq5;^pOKpPz5fb!l#7Z@pnHW||diJtE@lv`+(3(_f|sDMGs1 z+lc1{MO_)dN%L0p%^uEh%0Y$G;dTr$_`?Be@R#e5<2Zp7|MK&K=?pw4%80H+csb3W z=u@01a60gdwoTfLN@QVQY%6fOxpxY%u25Zk>9P|<7bm&= zvZc%^IP<^@tC#J5L4scJykLA;y$enJi3t)KH4**cKBrOA5!9u9dQnEjb)Bw#W`P3I4xUHHs1cwQ#eboWU2$O+JC0!DXLtIOD6wuK?2 zFL6Opb|*-@%7GmUg1|_`qjh%1oBzI$TV$7i{w+0W9gd$leXP|JA)6bpb^NN`RM?}@< zq17HoQPdBeJJPv_?Xy7d`96q@_-w{-7Z&#-5FJ+T-Bf=tyw@d*oHsb#HHa#+Acu{F zi8##J-s8^qD03CDrn9avaqJkJu%ya`Rz@p7%*ol3jMZgW)uTs8Hw|#FeX$M6Tm82b z$HtcXZ}mqTE6+_P?}hO9ULLDFz8w8Nlm}%`+vQ3XYb?GSRU8XZVtip~fafDGBSN%{ zp6#9IEZ?tx&x3ih+Q>p_YN{E>aE=FkFP?MUExdMw;#19h`G-c)tdeY=>Bkhu^UexrfMWKW4 z1Tuo@^Th!%r+EwQL~D!s6ZdR}yAwC>46AM;A6)`@NnoS{DKCCJ{flTcO4N&Kyn1{f z4xdl*=ER-nclw>*GME^XOku=u2icAPXJa~@any)f^60;-rhi>V*Uou#<|L+nOK-ZO zbf$4)O_w-*h3A$%{uB9OCZ^&Sak?O-V{{QjS3~1)8rb@HV|o$%rcPPz!+rJ~)!#_N zbTn{TDC2Sgb!DmXTba8uWXZN#LZPh|Euz)nH)NG-YI;<3j?WAUa0$ZY&I9>nQA0{x zMp}KC4@NEVwuophvrna*1L~Y73qq3cBJ)#PrQ&L5CgJDJ4Iq2U)qS!gUNV%t7u+r? z@I_R0RYqEvW(>_K4>##j{{}TZHPsw8fAaHV5laSyg!@_nf5F%Q$nKyOiq1edMuc>- z$GMJ6n~vqyaryX-^9Kr~>XEWiM0Rn$VEx7A>Y+nVmuS1p%oTNYLu29hzWbS!RD$7B zB>LbK?TYZG|K?x+^|$Z5l;0vng6-K&*FT2i|8N42OX$Ixv9Zd=)>Q;3TGMvLLr+3F zp6G@*J7>Kanbm8SEKdm8qyQPWggG@5g z;W=h=s?U|(|AN|V@e*WpF zpMLjV_3)+PyU~DpOOyS`P!pk$cOKl>yOw+xg43<=RgYwMkWrssQ$!&x3_sq4>HN5- zb;Y`qC%f*PzW}Cpzq0RmAQE;(2I=M9^p@gi#fu54N==8-uixBJXF6OMo|h6}9YF+0 zCa#LK=)&+cJ@u?kG#6!f5~c5EYm-qx)7bqj*9lL&b>}j2diUtUwRLr#Rt9P$r3jV| zuKH}}_Wb>1N@mvKU?KD?GjnKYsC0~?*$UKpQqXBAO4xU5il>TrAql^IZ^y+q-@HjT z(h)=J+3=B(v-DOvTjp6(;^|ppZ1pshc($IcG?ax$1xAINDo2L6+z=cUZtrFr7A@b32%C) zuCme~6BgEwoS79m38hP4Reht$^zXy@S1;im7qFo;x;i>7+Du{B4Lp)jxbLVIi50JxohY-ZL`W+HiLs>Dpf%WL7nh0M_CyleS15Jblp%@5Ixmhlv!&219kpJ3F5HO{#nHs6DHYEPqB@qB0|zjJi*}6&&RsvxHqrG6 z2_LTK7V>b?vGfTt)|HyhL_&FK*kcYLV## zF4pviyQ!+4bQ!OeywX}%Bh3|qqW(}#kDQLfMU*O15th)sugb^8#b;%h4;d#SrDJ;W z@#$RR3h)XLYv3y%Td-sgP!4YkU#kPo7FpbKrkpqROHvo0=VpTEGVslChEmhD8))YW zr3XbGfzcCh38N=wB__UcW>CB?^eaL~kVE7eHb#6dY|>XSov8zxfF#?d9^a3b=7iLB;w0a6Z_~ZrmAPRdi3Bn)kvxc?W6=2oU+RuNk_(55 zzTAC+;qHD+m;pKcH{0HND<@|gm=5~K57$)J+$|h{{uFe_E?^g*?4OJsBey(OLf*@J z8&KAJ;dIO|G$&Qfk7(S)kVz}&5gFtS(CWu$mT73y#052yJ9{kicyK7q@6oDA}_jo?}T<-srqa_azs+q=ZjQI zk!X)&&&Iy=zI%|f6esr4c>GIslZ_8 za@g{&{g!IF_(J%jik1#ui(^HGLUvjep|MLuI{LI4Lh0gr0n(`v)rv%eL~9T~i&lTC z-Iju8rKV4r83e_1A)qdhZsBwvZ~xGoEWa>9hiwB8tgH;S->h8+=#A02t}|4$jDu?3 zykyC?&`r_N>rM4xcvxU^p>&4Q(lNM*$wf|TXK|WmM@@xz=R>?_$PAQcGQ&M&rKssl z?O}9jjwaT0I9*6RJTE#oG(6gf@#SHB`ZsUgzyJ9#Z_#?c8Iu<;venz^3|77)b*PIY zO8awz(~;Pb*30r}2P0N>%;^|i3Ni{XHmm^5Z1gm+k)|yek_osofay5Z#nZ8(ZUvZr z_TFcoUB{q~rv*@#aP+rN+_`e%%7=*RQ2FPd-@o5+x?}il!Sn~XolR-!Lv-Rari~4y z=RxTC`87=~H8*ZtLU@&=mrFG@(p{-#|JcY#>B-WQr)!2KsPS%vmu}Sal~or7(?>*7 zXY3on0RyE69&a_2>AlvjJ2@V+W{>;CuIGRGhu^>V$<3ssfY##y z<6HPFxc7mU{RO3x$5^H}=+GVWTWT&THN9oLrsU$CcMn~@d`5kxNca})fA{Rz{+brbS@ZMT+beAAhVoCLM`2F)!kg~o1os7xl+i-9 zqrHX|S0Mewc!wbvH;bnYHtzi=l$w6O`?-C`UnEt$&8rP@`6cA^Y^Sz$fvKp-L(vD} z^!+=mOzWeoi7_%bm#$69%s1-O3hASTi9@HycnuTMh8K_YLNFbJeS3|F;J5Bv{q?W! zcPFe}2ngCsC#X14(=or~Q8v1Ne?dCssAX{(M4b@a$qbMFJatK4q@cIAmrBuN(*6f; z-+C1f&yDtVC1>BfxvDjI1R4G8MQML}+;Dcpv!wF)sHwzr(MUL+l(G>+cpl4EXTyht z(6|OA zUxm|o6KCk6@ZSfIFw^jr5?DHWdN8r_u(50GSan*A>F-P;`DEqj(yq%&ekTI+#0lWJz&lZSTG$L<`qK@myjNj)1B6lE#u5Y*BakRori~& zmA&ckdQ&06t6sK{xavddWJmo1uQ7S+Qm!j8oKE^Sw}eIWQf8&jW2J9{71YmF`9qOm zZ|kPFFN-S6!`tqw!}gL^ZM|WvI+{tq254UA+8Pki1=>pgs zO6ZFiT6O`?_{cd&v%Ns)lDIC$7r}PoWmFxjcs@k27hY8wIs!BIL?@$-AT|&1Eg11!$l&;QA0-~@u4dzng?R@ck!URlrF6{4o%(St0C!-ThoSA#V`t*Pny$( z(Y4cZ9>--fmQQeA)$(VTNze-}7bv~z!bW*5cKbZErhnD>B1tcj$oLb~boTMQ;Cc~8 zuXXAYS+S=K52R(H{D?ZotOeiyu(OM1cv*p+_uCI z%O--6`w|~&{K&Una-I(?sQ2A766p<$E3W>^o=~@Zq;Zx7+`;s(T&^93)wLrQn3vNU zr*9Y9-_CDjQ1kio;(ECivv~`Rfno-)T_LOxI2T$MRALQ{8~JNFsKV|;zi z51KpIkuP)d7)fN*qF$KC(AnP4<-E&a&Re}Jx5UN|c6Igjk*1hNz)3Xr3Czq`Td=10 zVp7LzD!J(mG$oZOK|?Ghr8%naQ8JM*Oc8p?X-rPuOlKtNjzoK;t=KJOqh;_c2-0EB z6X`gAPv_+K>)-KkUIJ=49?KejD-g^H7r!k5>d-i9d17oa3cIPOh+vndLYg0u!dN@p z5ofCHs=ZyF)1Tw+h?+iSCasOON3Kb9-LrXTb7Hc~8gD5Vm9Q7E+rgC>7e9bFd1Xw< z9zVZk_y#Q_bq-is;wh1hZi*fsE*xm8 zNne{G;V%nfyhVMd6H;vQU|(`yY^@k#*8Pn+8-K??-2eWE3UI+w0tg2!#>Aw?ALXX2 z2mHD>-QP&x4=4P%0TvPXOEul}=eAMVo`lgYTDo>bBXybIDIwhg>1-29x|q@}h>rJs zie$M!=t?c;P~8&Oc#x_geP#-U$8w6#ww z;klxwGeJ<8jv*(kcT@Dm_2Knl?wZHN0_7H9htow+*C<^?c9whGX?HB$7(`81Pld1- zQ8z+$ z8z_LhE(0%&Cl+y*(FMrS{-_EhLeN9%1Yud{CWYw{kh*kp!TMqirYCuLa8F~=1c%?e z`+<_ng~g$DSpC)^Adf`!cRs)W`Tg;6O-+Ab>S)wU10b_Ai&ZTx?M*EV>?RKwqNOt) zoH$ijT^(K1GIq1|=Kh=e_eXb01?h?WwQjAR`%GZEXDjaJk$uORYoL`M_Z(@3(*r#{ zmo8nma5#|q(?TrCdFIN4Pe1?kTPziJv^2#@$)TjYltG7O z5&2C8v^S!J6oYwO)WzFS`n$yM?s?;lS6}@d+jafYrJ9!Zg%#NqPWB$9H}AgpyAST( zyqQ$GB15V2rTgiGR7Y8AU0o^535~^y&A{ zR?^X(R!4QE1?18AQW9`Vj4h|y*U?VXX_U4`BW3)}npE}ZEmd8b?W;0ee7%+~+}{=B z^0R;Y$5q|W9Ulo4PG6^@#Ki^Trt>_$BUoo;h`x8d_xdM~Y$&M?uZ{{>`LX z*~u7QU(b3?9>yFnT?y(=ZcYm`Xmwhe+1`Fbg3j+;Lr%Zn)>g6bWC2Z7(~0|G@E122 zd~KYFu8Bjh&aCs$8@r7Z(b`+r)dl<7w$W#Hf98foJJ!;A^kXQUfXThch$tS~t9osaz+Dx(y3Zi1ZwV;eAz!Cx#O| zMaLDf2%~cmvikDx$YZP)&pA6ul3`YW@kMG^CD?KI?p;sq+K4rM7l(?| znM3TF#zvy*%hMEP9^GGnT*>O1q^?+9KpnRWKY%(LCYZi_xev!TPJ8x4iA~4yf|`yZ zzHHgX7hc2kGC4S=>@K)oIFzIpl4Cd!Ot)k|R;{KiR1D`>S*AYpyganONC_!JZL(ZT z#CC{&?y|*}Ka`Y<&YxZ7=jsiWhj@zvTT|01qU2i$OqZo&AD?qsiBxAw6gf!T)2T>& z${%sK7{f^rwD7w+c&z8KFF{@WF^K7M!Q_>|YKx$*q5bxr9&F9q_v~5o#;pZ0iEq5& z?MhFR^XC!L?+nsu^co520_iB~g6Y@Jyem+vY3QJBPbVkQ*P-1rG$BP&mrH4R)JMT! zUu<7;Y;s?645oK1CdEa$epxW`(cFV!Xz5`3oGEotd>c`X~ih5sP@`7If^3d3ATefW8Ous}- z8MIE^oF&ILXYKUcDW?)S20(geW$je$SePHJX>L|pI@=4M%PWcLWePKw$?w;{FHMLxOlOnOKxF!gS+Ix%$_}i z)5z&tx=c0wF?-%%Ru+?7+~gF$bI;KUxS1_}D?!(xw}r=TVp<9&2f23mS?@`6Oa zHEVVzC&$F}5u=WtK8P=-=KpLpJ;2*S=MN9Qrlx=0n?5t=PiHpYQcah-g@;PIlF}8j z%O1-t8l-D%D;m0G2&K=RGKE}pIGhSi$%C=T=}7RR#ZRB3N=UUnq#CCyN>`dYvFu@? zq1!@SLJ3Y6Oi!hd^c(-#tn_Koq2AM}j}BVwC|k#`OU|b7>cfSbTxL*3p@tIB#m<7? zMbp)V*#UN`ykI$CzBfhdDC$a0htq?UJ6#~%GFXaZo{yleB=y5)zTd3^g5?!eo2ANI zzj*_{ajUVW=lRc{W4UbJ4%<8$GfLH{Jt=(ZQ18TdKFyA#$2w`#WMs%NM?vNGG#9eA z^GK)5k#ihD8sw(qttB!WHQgZoULbue3dx(>j*Q&gfA{*wi0LAy<9(5F>uvPkx2em# zbp35b>979bQimyO3`~z|qIJ!KQx9lBapTe@2%XwUnvmj6$Jc>FoTS>jMfdK#3IE@u z3h@?EAzdw*UOLafk`i5T-r2LQtq}UiXk+7u=ka|dXQM_(jxP%K<$t*-(beZdl_b3= zHNA8oI;zYm@I|Z|MsrE%v0YEUWx_SP19Jkl#r71 zd+Syoc>$L$-M!JWzon%B?@32@cD6@m(%tKr({I*g+GSI9nVn%{Gn$sD5Rj-f0nFMYpYy0kU=^uK@l{Wqf|9tJn~P`X`vMYi3T!gNv7 z+jw51y0$iyYjc!c)A$3F^jmjM+-S;n^5oSXar0WbG%3G0>t{dv=l}6iHwz5e?R(d~ zxR=(SGDh*RjCk${FnA87y&wPH^??m3#%jW~Z5R3GrzesBVbnW^*Ve8tjK-Nyg#yDM zyiT{A{DOkgli4k$!s)jT38#0o?cGa;4F)0R-#EU9#tda6&%H7_+U>lbRfM4-Yf@7X z@a;V6FjLvKEnJJ4XhX`Zr9{Tudi55KM^COu+EE!ka=h{^LU>73c*zJc@Tlo!0cqil zdgH37w34)ukut^SDTEg5xxIZhayrw940{_p-lV}yMd`PiXC^#d{8}FAdj06C z4n^bde3i++@pxmPm2FZ0IrH_^W-C;6y=}0KlQ_o}r|WU2bKF+!C&2-vu&fY+xUL=Ti1OfgFuhBiYytyP zQf5&(Ix8SSrT{qB=#?b*rlS^|eMyK9@Fls?KFZp9AUZlt7aU=>$Ej|slT3H2zUdgO zLNvj2-wivK;#v3gwR{>ZBl}SJ5D)pYyERT%K6C#J8woXfM+ ze?F^R>9TRyShQsH=a(-B(|HJSyz{F(FT&{JhZoBTI1a5t>B#B3m+ji!vun4^Dwgd= z(g)(XFQx#PWi*#MI1ZXy#+S!lsN%SY^VGk>@)uS=v25aplE(;lR~$jrVJh!Mxl90ch2e_3m1r(9HfV`w zUCw(rzC!7f=XF|+ptLKnS9kUB-g*$#gOD$F_T9P##yT$cIX1%q(~9&jI&+A=M(E9A z3^@e4%Q-S>u)sb>nls8BgDIU3L_j*Iiv@=87rH;k=EmlJMtXVdf&~&A6JK3jjudt@ zq$)QDjCRS|x@87p+%q#DoAS(KGoN{8g0E6FIK-Y0rHAZsX}G%bkju4eSNpHh3H3_X zc;bTL;oRckVN4UzcZ=eo|LaKQ$-S7=w`TdF>TyF7!8^6;Hv~LC5+0EAb}sSRi8nQI zCw+jJ1raVI9Tr(sRZown!{p)&ntIQpQy}(l{_g!xJ$KeD%ph1ohR189bhJPD8jcq- z4JjvuUkBq05iSaAJ2J9uY)s_AP&iuSTtPNWKUXR)j&+|S=5!_*sOdX*GX3z|8SB4> zz;vEH&_ouCJDp*2Ns!6Kt)IANj~_xLw5iEfTcmbkQh%F8{Wo zqw}9TMUv5pi4ja!rgK>W6J4GLN2-K$rWW-gQ7}qVSN?SVO~XQq{X<-G)6k~^<}FIG zb^AI6bIu|PzQRM7$TSiapV@?9ddSLR8kKN1n)#Qixwu>ypt=}cc+aZJSe^ze0$@6> z7rMqxmtYuqIu1l_i97w_Aj1gji>f2tRDW2PVwFm!Vk-XBhe45F-@re4!M}QPQFO@k zNlbrahnEuu1rAV3mQ02Q^Z=<_5%~cENJ*(4{T6=)K3ZRD1g#^+B4~j`8=!o1 zoE?}>;ETay$ll;#h=_=izCqwp}0> zG>01v0fz94;U$fW7Fn62Sr+qiJ$B*f#$CVs#RtE*dvn9hyU}OO)Bx&Hm`h6DI`-7W zTc&KRd=+u|6*kD2ZNli-@*}L{#=EE??c(ujDx+@;rXRXJd>2W4Kd!j+3|xTi9eYn_ zpUxgl&%C++`tRQRpyg&}dbXs}l(mt=o$XYSk9nu&?kU*(?Gqor_c3wdf4Khf^}9C^ z-0Ox6HcS-EaRme(p7`)bbRYfae|ht)&B^xt?WJ`|b#?Y^6}BAIbXJZpx36Q^U24ho2!a73B6{nA46B#-F zNUFipcdQ=M%O@LBqr$_hO>T>9t?S75^T118h@0(jwHYZL|1*F1GNX}mS)mj zNI3n~TZdQ=x!(<@(|f2iQzGB>5vAz{-RLW?yfWID#{{GFrbij+_%yv+m}Er+rMB&j3%B6X5i;O6k_*>6um;P!?WN=433nm{!Jr znBLa5$;rmdbOI^;?Afup4P(*K(e`B}ESNNw1vW~P!V=H2vR2O$@&}D>BBzTtos4#4 zHchlJXu;_W>vW`aPAWm&-q$9=Y^d`jK0R2Pdf5x64+*C0$xc5lV)=hK2xativ)Z(Y zWT$#xJ-m<69Y>2;&!yEU;>BO={Cy51a|0L~NbPMnQ%1pn-kOlfcJ8@x0XPEXjd)bjBFxB|quq6HC&Vw{lB z^a-L~IP%nLTG;mhj-r?2^AM>WrCJ7u0>u)p4i<|YMu=PVbLshsoc=Ptap7;+8N&$~ zF39QNG*=S83q!%WcKq4ZvJtBDreHcfen4q-bxCbuU^iz*pgl059^dgupa{7UZr)18u8fQ9$ZW#jU+D_#$ik>cIq_jhN;dM}5D1G?^W)?;1 zVocY5G-TJRNtK$;Ypq#c9-{}6TpPvM@`oaN(S5e7I9`@e+yp~{>F(RI$T3*rLL(8E zux&0xHD(b#7WNzP7=Ap2?*)Ve)RC{nnZcg0GDFV)lDOgV#~%A*P`9{XxXz1Y9}M%^jnzHcP7$$q-yr`Juy->ij02cic-=A&Lc6v42o7xK9*?mY)>a= zaV05j<#c4^x$`QNanGSX3@Hl`&0Mp{MqEHDc2{q2@uptyCELQXBpW>>ENpX5@`dKv z)1iS0e%uksK7`UibP5zhFzQ3{-dGcn>9OEkxpHmrPT%cQgMGC`gw#f3dm$S@IK5~X z<4bw(R*J;%5BVXLS4qK|2K*r*JLSB@omq)HHz)d?KOb`j`PO@lRK~fwuGy0)>jcbn z)C(%Fb)>u&=jQz>6@B#^_&?|PtXae_!suY__%N>d{IBM0@mqtHmm<;`&D=g{ zri1_bP(OUg?#-?ZM$F)5d@_TvtiRB@mT>hhyy-jshF3YIe$(G@ z>;LGc^TNyX{-f*sZI^!?)4!JV@^x?e*VXigx#{!&d~Ui$O}9Y0vcE|Ef#~Q;MVCFv zNmu=hlqVf~6`wK?I+RW+!*tMDsp;Z<5lp9o6xWLg?$U@<`jBd_7Y@XpP7R8;cUb7A zl`by1Cf24Uq#TR-H@#@7x+qh4F_;degX!X(cg0p7ioRCM(#~{Ya%?T)Z4tAJz`3~6 zXNXyc3un0VaI{UOKZ8=!T_qVtds4HHg%BT=)643T;Cc>&0}>j=`BERPOPLoCkUAOm z@)r@hdLG0vIzGhoS++D_R03NB%nhSs>XifZa~9aif595yDZ*-5p4MyKKwyPO#F$52 z1-=UsP~wPpMrOD6Fjx;+M;Iam(h<{XQV*%qrRLNr_!jfZSNMGLs4}h7hq47s9~p^g zZ$I@wpd30!L&uX2q|4re2RBY}FG%n>P)?kC%iNDPVd@lrD9VjvCkT96z56M~^=FB$)o*^_v??2kxfn+t@yRo3W!LcjAeO zx9F>hk{*{IXVV5hjbhs=iy|k!prxz-O5Z8ze>pUu)bvB+SaSB`D;F0R6{602JF>}i z*V|>5QbYRj^-q+X&TGgkk=7JVb^37E_3Nx0u=|*ZO4)pNEQYSX{jQ0GN`~j(& z`2k}3&p-X2tIF1qH`y{UHa1j7noE;&)Y!nd@c3oabg2_{V{)N0q~~8kNf*aU%Mec+ zN~gAvQVP$pd&DvR^Z#r--QA|o?{Knu5uY~RbkZ3cN4fpHREToy?q}EIKS@f}hZnAo z)};ooAgOPy4UKuK>+6f^*DFkCdgiH=ay|8i1+-2*$*Ulam5-S*{QC3z6s1DxrT9e3 z$oes6x4j6~(=doG_NAHj=2act-PxJ6CJNs7$}8Oq2|eGiV^KnZ=>o1TH#$JP=nC9w1#FlNXLMuOOK{kS8pz7xE|fb_42|v}lPcLkOKbqHKMJeVm;Q zshcA72M2rl+8gEVo0%?{UWQdiQTjXoA*YWr(=*hj<%L(%VZmA#V1@sLAFMATaZ~b1 zStqb99B?%@5OH^-B#16{K9{xc~ql07*naRNGwUWtHGo9lAc+T$o0P zC`K8qD@>F5-}98XMRB~?+9m{~isNO`(m-yH#T}IQ!pd%f9^JPnQ~6 z&E_wj7j;cR^+|8~JWMa06BJe*JGMkRxZ~{fb6JuVM(Y^*al@~&w=FEJN{+Z_*~(K#F+9X&iybC*s>#K^>N+3e?cfr?zTUa38u z&Hn5OCPTBE*Q{wivd6D^4fU;&4g}I9VxZrng@w;|Xhu%QSHxxm=i7M_JclV$BhUZ+ zDgBXIOHJbl&chf(Xfqm*N#q*PT3m#`#Z;J_T$3%P^ui|Rrb3BQm#9WuFg2#4hUEU- zLHA~1ZH(!{=|M;QlH>cgZb|lTmL8+7pgP@VwmbMG*Bc9q8*&IKPwezdj43ZF-x=9V zE~5itI+#9p?zEY_OBYXb@Xm_a+ECuG%@2(p%ZmdRhM9|}IEK}h`_TsnebQm(qca`- ziVH)%=Sw0ZYW>_fbEa(HTpK-{jE;`mscSfXFt)s5LGp0ZI5wsJz6L5uhx@yl$g$uz zE~9Xm9CdT3JzBQf(<&Ye0Lh4)S5_qU!GI(6z} z=D+n${_O1oye$DQf6nysr@85WMopjo=hbu;Lp0lq0(BB!@VbcEMRarx)FE`0@giEf zDjS_5D!Lq_j1<3bN3 zJjC==8$JG4T&sCz7R4nlka9qp#GnVX!mooP@S zht<{InnprM>1CK7V8#*O6~5dHs`BakpMQS)*94|q0=Yj{lDb7#S6Vvdp%2RiOR>I&^O(MbU*0jTLqt)nXmaHR~GPNAm1d#HV{Q$-vOj!dj9L}YZBJH*_g*ViT8 zeE)avA=W3A5`kWVJbbqL-u3wF*WbI2%Kq^Oe~{hpKmI+8&hEYUu7}?o8d`DkWIJB` z>P@*He)xl*|M2IZe)r9h5gRbQJwL+GI!2Ou2d?k@@e`=&58Bt+!r8RsF&YiJ0?vE; z(4ETMhTeTpWWS-Ac}e2&=AIv(Iz&$(PkkUeUc}X-n}p>>E@2q)U^_rEJBQTIv8y(XN1HwAbF4*2G1>6tN^L`^iWog2~ii%lO#x5KnaIuv3JSW#OXR7de z5kjYd6JwE^UW4?&z!YJ0qSG}@=MQWo@5RoBQemNVdUfGxs?ghI>s3rql)W#$7fNak zyz!-o)I${u(Bz2c_ATV}mq>fDTAyaFt~MD`qS68&bwqGDSs)!)){%ZL#2#FyOSg~X zU&Mx>d6C$;lDJcZ!P#TUN@uXw*-$3xR(p{e()u)egUI~Bz9Yal1D==2bSL^bNxI9T zd9xDSY+!cnQ6O_g=L*)XtUQt2#iJ%(e0%4l>iV?&wCD&gU%k$jYFXOFQu%F1e7vt$ z0`mZlQRJFB`S}J6O!yze> z%5bk?`lOl;lMAWKfseAL%W16X_;@(O^@Rf)rGoUsD$&wW(M zJVsQIUk|&&dBpu zrHoX1b>5N3l?RlGf^a)p`cmkwdC;rP1=B+C%>bgBl zEZJ@8)_Oa>Ke?e;dKsaf$2Sx^>z(7wH6~|MQE`2Zm|cp73k#!b$ZWh_9P6Lx9Z7w` z6!k-J`kDpt@e2|ctnqn+i3_tp`rDG@l2vaq7smkfd%V4m?D5_+SX;ZGnHEMz9E0Xg z;T=488glwfsstQ;w&f&~evvci7by)%9h%)8W^SM97*ZQbvs|C%88aMbZeQH9C$zBG zC$bq#r*kfWj8lTPAdn|+2GRQlV>wnnTpZg!KF(S|EG&TUbAOs;sUA|`ef0ip@;>AqIjFXcA~Ui`MTZz^4I@c-$K$?dcXCx|C%d)3pM?l zyy<@`M}K>7x&n0-^#TTyGma#!Bxiiyn)WPUs~8>dMo6FX3@Z9!(o_Y~7tclIX87Q0 zk?<;|rt_~iL-ir$nqrDka=Iw#isluj=hl~R3t3t17JzEK=#kWb$*-}mykhfGQ}i@9 z*%Sh%^Kf%0vS2G+{kG-S)*jrH+pU6t?d#!SqGuZLCC1 zK9yN%W+&=HF~Hi{QvgU91~M`HN?j>GbR;cQ;+nE?sGEs& zmeMq96!x((f;W`pd)$}w@jPQ$8J%iAm#Wd*ux<;^k4wM0^eg--V*U8lb#h$ZzV+ZT z@rneVuWFKxqhfXW73hBX!KoiV5GnoRU){KIl5o40t_5`CymJ{k6~j95FR1A?`)kae zi;k~~c1jH{i5>|~v8t4?N=86h8h{h9DAjAB&G2Tw3kSY<>%y*Gzx>^M?{C;KG!Sjm z#vB9-w%$;(a{8``9B2ChGu`bAR(RP6nxbtctzB3^y2Bz6;lGK1=xXZ`h%r~#QW423 zA>It){+P0mf@8mM-3|UIAHRL)*T4Pzezz0Ob6snhF)wb#LNTA?cF9~@VLW}mW4xxl zBOAjzV}yP~Z6q;nNKM_apBukQ*!{`&j?otbl7^CY>u?WM<2c0tApcIo(Ekkh$e?DiEI#J@yE4FSVebySg>tx0=NxAx$|w(eClBmHXH z%hz;utre+Mky<&2N99GO5$|pe2GX&cC?5-?jsrzP64AkZ4dw{@^f<{hwZXe0z7)XQ z4U-b{L8?9pKZUCGHVFZGGmu_iTS?h1L$*y4QduX#M?;oOz*71d(bZ@cu5=kz66m6Y zbpAnMdZBup?__>D=kY{sY$EbJ2GXoIcm?Yta1TjHyuGy(@s3z%Xx{3J1BOmavV{-5 z>APRnvJfG3VPo7bqNF2TPoVDZ7Uu`BE#7j89+v=hNO>coxTw-%965#{E*5SX!s(dA z=~%>gQj^yOow*}u`*~Uyak=uPa|fD`F3heKk!q%wmvOy_-{e^-^`zcYob%+wpxqNN zLt!YCPV*v&|LFrbN>I|j^V9Er?|VP|-s_mjiGE>A8w;ju z`Z*m*h0(?AqDIy70}9ihouHDG>pZ*cS)g1zFYJ!7o-l2iG&jPQuGDn)6{&ykwI3p- zi#uI{(=opML~JjJ>0(V^F8MGrgwZX#XVjr~LOd^QD9&_sJpp*d@sn!$BO&;%S#yP9 z`Q`vhp>Y5mn~T4Hmdg^jbz4Z*O1vS|SXRw;J?A1?wm`8O;(-zU7X`Ryq7&YRxxb3t zVtV;w*Na?kxsn2O0a43<&sn&hi|ZxwjXh#|NsI||>|p{i@!CYBAJYTE#3Rp%lntO0 zjUIXCoPu-(<=hXgjD*+O7R%OgDJLV(#hmxs61uI*<+YA3?60e;(cgW(CKO^}w zx3H)W*TlyU)C?3#uHV4jc>gW2e#d-#j`4lW_w&SziRoy>owIq#n%Tk_Hj+dax$U(( zl*C?(861p}+({QobYo=3b8dU*x$R_1@>C+XcQV(Q{C@pA9?r_3U=%T(g!!)c2FZ)W zCNgd!!>q8jyg0gzR?f~Q=j_7rhVmj)4anOe@r*=_SH}tG2Em34 z5;r%m!C)Z%9@KP93of;$YX4@($RosWI?mZcjAdi)a$E3lLG%96qxfowKSQ4_b zJ~S+3TfGhn=9@7!Wip`VD=#f)(knc?-bFB-#}UyVR9_O-d-yP)C9?(3k^HsE1n*M? z=U?Kw@~9K@!pDNDAq`nFpO{g3Qu3^5ag^l`oC}`=>6T+y)Rmwfx~WiSW#xn`1&vLQ zJ5^MFid`81DyDS_b?5jZ(fl7-l*)l@xH^+(lUmKx;vuH*Fq=K-okBB2mEMwv)R^a_ zccOp2R4U?rk@#nW2?!yxrVT zKiYl&9Z5|8^*HNPMk7(^pOk*ma+fBXpX`U*A7I?Ld;{(E@qPOI7KQ0=|Cq48Q#U$p z5CDj5P8*z-lVwqrV|Tkw^qn|0d{<2ABC>OE=TZ$z3&)R}P5KmD6Ge#7p4mhRBriy1 ziS$(sCV$>-a1C=;@)gGasyjX(4Ha6 zN6vos>CZ0oo*HjIxo+>?eXpQ7tI>V>rPH(+TAC8*8C(|)rr#Ub5e)m1qmoJ*A+r)Y zW4<{et-8M2#NUkqM@-i6p_;bgd&xIv$L;sXU@G-1(lsd~z2DKD$DbR|OJ2Ij<^)}4 z3PX<*VaeaGsU6tduwlrv?YS47RuILQnzG`qApV0JsNvZ!z8I)m!I?0uolcrQS<@Ye zhEE&-?2tMGA2nGwH7$bX1ufOX)f%SXIN4IuzE^uzFH%X6ZFIuwLaWm@IyiNA&~6n@ zm&+Bc<9l(g5JHF3(=+IhN_eEcBAec$5m96I!NJt=8l3XX5jLb0NjF`+uB^M{e)peu zr)!RwRimRR0eKN-dVQKwQz;D~>_y~s4C7c{AZRK^h0`O(q;eCZiM6QM;#C38F}9DO zrxSjurzKHDK2_M{DTW_jPjmDr5WSA}Q9|kbKaq?o;yIIXX*`;mKm-issMuZbuJcgJ z=pqvXF}#SK#*h~!FDL)eb`c&x`Gx@7Xp^tr&dL`#oeS)2gA=G~rLnN|O9l09be0b` z5piK~k-IUYOO>do>Ca+LM^@+j-PBQvON8=I!E%a9$v#9(r$rHnzFYwP;SmkMxz^Ki zU9@iYxh0Ml8S*fasjjK%Dw@$^d)bJ$9Nk>toS<}dBaXccri1oiIu)TZIgmR6))`Ok zg3@9018C^aKlu;;0I9$J^pnr4B>_QoOfnW&7hk;=UxTVH=W@Pm2#mgb^`y&1BGe~~ zNrlxVgHg+4B_O_~DN%j1II*Zo2HtAm~LC z(_eT^lG9&%VPYfT%>d0Y^IFt&C8lF|nKqR~OK}&m05DDBV1&>u<6#M@W90OWvoUpG zZIQjLd|mlt0ttc8*~0{a{lx`C46b5F9~Wgcc~>wU27Xt`*9wfGZA}%I*41chS2(?l&&2YIi0-inKP$4?)l~U^S9ne9NgT~%TcG>}U=kANp4ATR8_WmdH0xN%(r!v=8Q>rW4_Q4Fw$2%e6xUMDl$@ z@XVDfx5sPxi$Qb>NvjdnYvOy0{Kd{M_L;D(ZCkevZi@+n#mV{OmRIEG;Sf|G9OTC( z(Sg~YEQ#$S4L*1AGsUihxM-F3Ua?`nU4dGYN+B2i3* z(j>|`AkToiQz85b|9E%tMm9trXLH|tbgtOf z9Ysx7C8mnh#rVRN{Wop$cgdPeWTc6RaIRwA$yW~A4Iq8lRO>uW<-hRjz)t~OIPQMOpXojrV9a+Fe1ex!=j-8+O&)g=V{%N6;h(HH2x4Hf;XLoquB zb-EQFtWUEF&=F~#X673i4>_J#Nu?2SJ;2I}V-irqKJ1RSUV5RZ?G}GbYKq%IS6;ly zCz6_PwnpX?OsAO&a=IN|8SV7W`FT#n6`JwXVhAzXQ&UQ9n)q3LbqMNoTQ}sJrTq%Y zZnPpDFk^=CFyJDPMS4;kqZ%bYBi+N$efphW!|9)o7o_JkHdaV|;Sd#|67iQw_aHv| zE}y#bc}GWg2gE9BI#`avTth#cQ!3}>!KHR%Yb)U{HwRiw=F*#=;Cd0)x~S>H(beIN z$4Pq8FA5~x&(oj_4k$~DHs!g|2B*w3AjM#cZp!XTTyw$Yv+wpIryu*}7x&&gdp269 zi;9p|t5!o%pP`7Yti;Symp)doV&PhG53le|T7jD0Qa~f6{q*G_*1V}niRp(r>{qOC zD(h|}QAF>7fQ*ZHXlU%FP&(o{9FBr6gKAab^N$74-+y2Ia_M{T-}~g|C!G8RHu-z> zVr{=0AN$1*e<+y#FZU{k>c$L1tz~+8Kf&u|&e?nE1RCrsy+-+d!Tdu8OaWGtA?b(|g6sL$xSy-sVJm)i!~1 z20o#^a;S_inx5W)psqNbJun@6x;`T=+fHXaW{w&fiHIWMQSWTFC%fDOm_}v6VN%;{2`jrPr4 zIKm!IcV@HP5(13TQEp@5)l|x+BBj@H75RUXmPS@fQ|Hlobl%cn8xI>WU4wL?boC3M z%TZ6NSas5g)X7@r-Zl}w9%*!7N~^Dp(g!5?S~DLJNME|cOI~SWBPlb5)2+2ngGG2= zkkb)z!B{!y5!VRHI?N~Z(>$p)fIt;!PKG z`bIIQ!|51b)ZpqI6J1?gFQhG^z=P>xmLW3{DP7`TL`#2OOfRB@JMIorm`*pNr@!;U zPk;K;7hd?zcm9FFzFc2)a_&JwWrWm)?BR6oLk>~ZrT-C64Cf0Qjq!XE&R-YDi|lEl zI!WgT#PqU}YaD~+pIWwBs~`o_4@`*XrDwuoOjmNcB6TIG3#1d9t}+=RbwPFP>6l*V zZKTp$)SgD^k7;tb=1eEil9&8tOJuqz=?{M_AKMc>)8|jPSD_iB8i#ESLp8?y5#|!I zb=#J#3t1dFh8Q*5VPeMgi3y)7j3TpbE-zDCPSr9gXntpC#o2zRlj7!6xb9b)YqIr=x)uD5F*iK}2 z1?4?G+IDny%Ka-^7vP1|v(8^7aE(;-T~(ij<|J;8iQivTZCc+;KH`?Fpd~vmgl$`} zc>yWr)QN^({O)&I!ITlo@1}#H^zjZ2?PaAQEGy=UVEW*d!9#;umnCw;P}9e8RtyhR z4|f$I%_7c*`Xk1#yn2=ITpaMpD+iMY2a~T2Ub}XOjvw-As|Fd9;&4B7?HZS9Bj(Vp zGo5>QT8vICJ7Rw6?ELE?aq^q_FFu^L7Dvb_k`}0k>c2+)C@fCWu*rmG-qDodwQwE% z%o3W4vBEU;7k43~<5VXwr7#|=x!;=R8N%sQ0`EDpoy2soH#Xkiueo`RxCGp1AZ>1U zZ!pzn9XZlWQ==o>A9e8CoKsyJ66r|8^_h=KDd5bxOe%@Td}gL&Rw#9JwYLwJ4-#P~ zFci5M*Nc03uAc+AzJ0N1>xr8R%a>542ixIa7s=JNw_4)t`{OBry%LYlJaMqAaJV79 z7IV7nlUY+#Lr0?`Ix-QYSzKEbTizAFbwR9(0_t0kNPWb4h3O4{1ExRX_#a?;{kFgO zkMqbQ4px7~jsD7;d_&Z6ssI2W07*naR0F0L{^?zrR4Z7u7{wm3NnwZo)HU)g)pU*0 zm835HuS9NU$etjrv@?=0M9J$!L{~~WzVtZ`Tp*W9oXcFg1&N$420n(Srn`QL>0hZK zh2mwPtuF~H-jt(iNI_oEHYGu}|EmUYXg4LmmO#eCSyIkAXXavQ!^F>$u$;s7IaxmQ zr_T{6XUL{}1=D#Rb7BO)KCfsUva0+pSaZ`)MZ*<{$8`2x2S<2mq74VT^VDo#D@ z@<^1RM`Dz@GGffWPE4|%p20f3(OGOU@K|PM1Zp}->9;%L(#J@U5og4ZVXuICX=drk zVI+Lr6?nW6H9au={z!`0TmszmB_@MaRP@NAMV^)6=5_0e61|Uo@!4Ve814GyFQ2^d z;aj~2!;Mh}d<96UV+X%Ms27~Xv5vf*T|)^epU~|Q znRV%ef_IOO8m(p00i}cKQ2P7I&+>r+brH`+L>KA&gHIUmfAYbncw+9o`N^AdT`>I@ z*j`Ha-|hE5DwO_D|MVG&@GJJ`Q-Ir=myMb}RB6bo*y}_Wp5U=lP&!`}C&Z

6OZHZp(FuGtJ?uCvS2GDg!Oa4T+fHPYN ztnV1Q!;igkqZ!e+0dI3(^Uel#wcW~wpt~{M2TXt4QNAGUi*+%1`gW2`?JHo>Y36Bq| z+ab!Hp+J&uMJqe%Q_l@vIR~XHJH77;uuirAIfV7mzVo$0bpjd>kG{wKbn1)x4i4}& zt${Z2w#&PM^<^!2?LkzF1`)cb3IN>lhlzBjOKM+gW+tI5y%d@j9vxT}M4}`4?Igym zTxozieH4kG`clC>JJ3Q9Q&Yo*>5S7HWpD$Z4>pq&k9&v1l+42M zP3|tFxW-i>ikuGiBAWAtSB1mQ3QkAwmQkGwQLHN*V8!ny^o6QXZ3Abcs|P*`aEAxN z^8$15Tc#HvAD_(H6-yv;kR2c=HYZwM8Z0n8h-IX|&;TeXp2eiXtOVIn*;hdMnBh5Y zz)geSeM2!y{|0IOx(lr%+J_VMxB_urt(SCY!3!}4_ds4M2!AhKicsW5{5WW2jj=S1 zVcm-3)~+r>7m!2c($6&!k4slKv)tj4=JEi`EQ{a1(VS&+Descsoh{7nSY!$QU#H7o z&=$q~^>b@U|L$FWW@k^XSo?E#y!x)dpY`0Ue}QiKf9*}}%SBAbn;uKaX0RXn8!C4N zWu!W@E`x+bQy4iftF>afyfSfn&C$z#4T*V^aS1dm-K@?4x{6CQJ>L$%O#`}?LwdS{IIgDjrnQ$M0jt^S{Jf0EX>;YJ^!P7SH@)SV&Ei%`3?B$-%rrMP@&;+dSZ3WXAG z4I%K|1icjac@CEg)1Ut9m%sJwq2tFJ=nmyiO<=-w3hv*kEOP)+mNW6uE1$mK($h`z zQu36p$!Huus6j4Ok#>E;&sS(;r*gkF34C6j_O zdWp~#YC8{~#0ywkv(d+&{;UZJ-YGRlTU;qoUOst4>sS5jTbolw~Yh6h#N4GNQG& z7DdKTfceflZ@+tEwk)IT!@&#Z70C#uuZt|L2=J!4kw;{E+TnDXKo57HJc(?7=|p2= zfOo48=APk8L^F230M~cFe*O~bHO3Yi*9#oChI!F|3AYQ57afBov_?f%ls3jJIy(PH zn0&52E!)S7e?I>)QHrm9`r7R5U9;0euDSPa4ZMe1COT)FA4ES(?|ZNIMn%47*REY# zY&8M#iAQeMz461g57E=_7*kzS!Lb?Jy1FlRcOPl&ZtrQ_w(AIB&$xK8)LPSXyTtjQ z8@qOi(vwM8^rG#RXEKJDG@!e}yQF4gn5VCg%jL1Iq}kI|;~h}q^7bro`PJkt3aBY5 zZ!XD5ZmIM_POtRIugnvqSGKE$)adC1z9hFN;{ifV&np=U^Q@`ae>rh-@~ZK-T%F2^ zQ|m4aNsm7D{;S`dIDYMvQQ2R8>zsOg+bk)9qLwJ6xj*Gp}VV00RV zr39d*b23MIx{r4V@r)r+VOd!lr(FkJ%}FHT+ztw3?Oc8=?l+h z?z#hED07t{UME`%?iCCYm|E&+djq2@(?!M=V}6mFMJAXwj2IeimchAe>@6@k0VC`O zSl4a@>FE~M?E>lX_-9f%I1r}uf{m;$R|d^9Sz4VLjR(EsA>v*rBkfoLl^Gt#Rn9P} z=yIeB%Z)GHLOOSDL%KlS8Pd@KbHrh!^!iMN&S~$vb&3m0m%;^UZbH zYxZQ$7YDAPyJ$T9nBoif_SUtmsSk>#Q1W2p zqxaI3lz_(GnamjxHCUcbkBmWbXa+OKtNTpi`TE^;yMva=4?}w-MSAOGcDOQe_gT(wvIS9TrYirq7tm{KV6>OG< z^@QG~U^-bD*axzPx2{{abZJ~}&eC16bZS2(OrPj9-iQ8YjGFG|Z*DOiY&+iQ*i?+RYB*dt9i&10|P;oQHw&F zT&@%q?M@#UYI}42`te#NvW{fI zFzPP(jo|w&^-+DXXF+>=W!R#;kG}S`KY!`zQ!nHD_?(>Xc=#mvDd4Cyz|+vV2%TZ)-AgipJ-rAjEw4G6m@xM0Q}5rJqc;5N zvsy;>-(Cn=w^F-0ABo>Z=LXXMM6+%qiV)pWwJbEZX?uaXwcadeOT+W#5jNA&t{`vS zJkGJL=#Ip9w!`)=&kM~(_2haP987TBpfdoDoUYd_JzZt3z&smiU(E4_bds}-+KE{=QaZP{ zklF_h+KN(z#;|;F;bg%klc_$4n$FJ-{4aYpDVC*!xR?8uJVYO($1$h`La-9Rh3D?8 zNS$GIbI0Lgu-u@zkS)_D;oyDT{FG)=&hdgsUweQ>@3>@K_!!o{mcm4Rl zgV_1q${S5&?7W zeA{_&`8>s4iy=YZbifc{xcX+W@czb)O)%< zzA$`zr4hczYum89fY9UPh1sn}o!)voUcnBRz<%P!!6P-PnTH8k})A7R0zQKr1=j!e-y*yg1vQQO| zg6d#8a~RKYgkxU8T_WxV*O`U~B9a5+`oX_0sHXN4px5IKF-NbWGBg@a<^d$DZ@`(3 zCnj($Ww%R~t=)ijt{tPO<3^{#)Oy)5vzVusK)*`jJ&L{PoEUb_KY-)RQLOstqeRYZ zSa#pyRU6RT1LKPy#gc@?U;OBf9g^RR!-4W3p4)874IUdVx?Q_!iGZEM0G^m&be#LB z`FB&0OFHD@`?$j3bV@SBEdd_tHdB_8ge0UV7Rj!#%grW^jxJEQV*%X_yZ@5e^!Dy| z^2adcUj^#h+yC6T|HGY`&A(`e%XWX!(qGatYy~;}F|qv$Wh6Q-j>eZ&c)Zk`RNKzG9fCr%5Ds96k zD&i_i&pNPmtE|>!sOPTE*tK-^>dmK~pd;z6&GINe^URiAz@6c4N$GdE(Pct+0qp0cI=UVVXmsV7ISJu?FjE;)bWd=MsRKZ~r86`B6T(qb)DKAg4 zJLUeqNv>+5)8}s-*r?PTGp2{SH*TD67@56}>E+!M2evNlN~fP3-kEOH^bF6mG%V3+ z1w)u>IG;)J=y~$l&%JPIw7tNyl{(>qs?jTb-Q6#=Nm5TA#SBxG)?U%xn8Bw_4Q~i! zsMbKVwD(qBv3Er&HIV)$lJTRfrik=EUl@FwF*rZ?-s|TFKhU3e{>WcJBkQ}-e0b;t zMwhN#2;>ExU0o)a$B;T;-nFZzr|(MYmD(Oib(_xbOo_f_e%aO74&IvXwOdJi-xw*3 zzj(1y-Hoo7#fi&5JB;JSziSbvTQa=p7(_A)o);)REv$kzoURh3GB(%bdDOVdk`n{G zN@~h|TACAGuJX#3qcw>&KIJ7f&Fx8)lA2T(%;^|i5Y(;lg*(YO(@O$k{b~~P6332j zmgVKS_n(Z7^&}d7>(+f))6H`O^K=hAwfUKARFZ!0d(WMD>(KGoZQb1`6!(%)5a8p9 zGo30?6<;h2htc`8b24bO2SKPw7;U&kr$~+{F;>el6PNOK}~5`SlQOCoW`0i+FI6Lo0s><_LL`&9! zEE#^GrYlG{bZNzOhtmy-8ncTtaeN={jz{R=;OeLKzMSk960AzAirR9F&i_v^Ffx) zVR8%b7SwgmfVysUv7|1;%fe7(Iu~in>Pos>t&2vRn=!7WKQihXtus-Im|wE1v(uYf z>Zm6j=o_7@OP$9I(_Fig@=`Kh2ocfkXx~BTx|ZJb2eTtm)0;IlP{B(wF&Du0EtIEbw^vOx`kd?vpZT2 z400LK)jJT)%mL`P8D0EseCV4p*(pD2ro;_GIzOAR+6dCMknO%4 zHGOq;G0u5hC4=DVpo@>0vmWuq#Nn_auzIGqaL*c4;KCqm7349-2hPK$GlAipVc2sN zK8;_iqQ=vdH+Do*~YM^nSm-Isvuy)!d7 z%j>bL4D#i3LI9%-Bo3parH_ZV5eid?R4z&Xb649 z%4Mv@js9qH@tSOFb}^W~hq(WEH1$0XKU%zU{oT88(vFT~E9!URIoFs$wZk)u9OI0Q5Gn_^3Qp)u}6OEF=sr@mx1}U%+#+OZhQ( zS)!qp43p_%XBVc@(*^ziak=S2330dNZ(JG2reS?B_k$= z|K2^y$vaOEf1XquFlRF+kgGz6t@fAY!X;D*GegaoPSO_*Mq#+t}bls8@H;RWfQ z^fB^4uZ%Ko7d0H!Pnh7`BdjdLIDRWo)HNXWr2K*qZxA#GQ~K(CG3b3!cwzwbAu)MA zaK3S4BtIB3ibC=YsRKeqU^?wua_?HYYxU~8Zlb0?@#zmXEAZo)z(0W6%=eEd3zh|Dg=h;(W`WZOA2(kfG@hDdk?T5L!J2|Cu zvh&o--+KA^&Hnya*H2&^IWfdIA*1)p8-KQ+ zeQMS2bIUW}cj*ew$z2x{ zqXtL9?11*l3eHq`aLk3D#lxdwh;C0Ic>(Ln+kG?g^8E6eDF&_dOGZ(ztn|bb zM{gmg%k|=`ASDk!{Y&%lQJzawq{&S;o|jPATvwV1MKEgR3A@M6Ou&| zWz!s`H0M=r-=3J5m-0C^{bxd=gYg2(1v&k;pl&qv1@+iU$%fiNS#uS%{}z@P zI9UWk`WJl-ZcG?+3Qf+O9y zT}*b1vAvv=y@iMu$NgemFnv}~C%=(oMhWk_PeG~iyTFC)`4$Th=H+o$l%qWE3urVMfV4#Vr&*}FF>`aB$9#HEgQT!^S1pXo+*iR6U1+y-1!@TV=C`!1Jmmtbk$|gN37XhJ@DW_HtFuW*B0J4Ln6-Zc;sQx z+fy5gpNbEBN=BEJ)dzPLJLRA9R4?hcfc2nsxTJD8pj%`l zJnGnBbcTb&D!ze%)OqM}Epj?z$x7Ts%jiqm+Z(naYQP?xH z;s3(6^m-^A&ObM}CN;a-`L}{Hy}MYzYE^QB>QFkOHw%>M!jLn30|AXPtB?hQUXB|E zC0iST)!5VVgHtf7-GIcfcF?kT8B;j4iN=l&i<9JnX1;2LK%BBtIb0N>&H@?9SBliZ zbTVOdNWg)^qdWHCe4)#!js*a3`EQD~OV0Gfvq*{Tf#AAG9P7MszSCqWkQZRcoueu> zZXzv`Lj`J7d2;2s7l+3aO=Ar>&a!e zFb=2NAX5Rnxms|S)#dhZKH*>f&4c{U^9xhc{||TeGd7R8?>9F5^53}o8TNtcB)x@_ zqO76V7Y0se{4Pl;q`%N!KB+P!t8!>M$<@-bz2(W2(1yg$m{3Yc!E_$HKQA=SH;Ft6 ze*nUlrlnEneBPeqFRsJ9f{?y^DV>Zm=*gbs;S~qxQS@fKF(UPR?<8y?6vCA!#O2;~ z7c>t{WRl|LQdj5h%SDS^z519@(?1fX zU!t=*dr;e7o;ZX$d!p*($%<}6=`{8vImPAYU()jJkG}rW`w!l{ zi0kD5a=MSdUqZsj^>;sh4cALe?e+vBY9yyClyN$Keed{#?VPGeOdMmtcq;E)KXhJTHBoD6X5I7R5{IelGpqs>4D|+d-w3Fs3p+x&B5!~fhsWE(2MBA z(BbX_Nev@K2GeiMZj4!4Gxz}!?0qM6g^z6p{V>`47%tc^%2V zv5G>3f~v!PS3vX^t`MhA@esM`1qGBel033*E0=YV-h`7hmbM>hFQuJlN=18RX+}=$ z-28v~^Ov4_^$jTfx%aQ6D#qo#^FaDP4bsZ=23@8v(nDw4qD8(5zFp|%QDO)7 zmS>ooik;f!M|dLYdex=$D^w~Su4?q^3J!+nHK;P}YHU0)9D+ID*DI3FOp#l==wQ`# z9ZU=vC2;@%AOJ~3K~#TdcG}J8c59|W{nM7V5@hHVg>{RR_#_{F?~ESoFUIhKyPrr#MoEdc*OrnN z*Y(8BN_lzix%VH;Tk2QY(^H8<2=~!!Ym)@^k6u0X&8t_hszvE1XHMOuUei0xC#2P% z_C=KesOHNvx;O~nAqztW^=%orSAxA3`Nw%twJ^7R`?u#GzLl7e;NeN;kOziydKi^+ z+yHZ2XzGO)3V9r!Fxw}MrM_54VgZ1U}M%sQj?MbLMpbq zC&S17vOq11LZ!jZ05XD@nz&MR|2hkzdGT?M6gmX6-9JBphBy#*;JGKD#3?Lw9%gWyr3^w~l&!5t z4(=JWi0%e;gY|A%-FfKeZgxiu^w9w)6`P98z*=CZd~uX!JZ zpfERyj0UxhIfnaeE;kF{2<@x6(Ltcl7M{+r#`G{+I0R3%fIMWf!ho(o068{17t0*j#iaE!wn2d01@bq7a=cz%Nb**12%~z$}rX zZZvhHsI%Rdqoywptlm@~QTJYY>UeK;x+{Inruj9+)%c6nY^X1;UfH`oe$5^Ux$&|| z1kOJ?|5W@_#iy4oS^Ut>I+ajTS$R4L)wTDb=xmO2P|^`i(xsytLf07>btYv=-;F*} z(6euJf=%T;S(XOp2RJhO|8e&>a8=%Sx-TrHkO4+%1Vx|e%*)CTe}`@?*M?2jpG>ExK0 zz0FR>)YdUp>d~1eu{_`Ff8Pr*NvECtOp|lYy>P92-EZp^{Qj@|`dz>5XSNi>yq5uA zx{q?yC8r?7%Z1C9h|;^46fT9n3m1;;*-{@Q&kIwbqFwqUMk3BiaA!Jo3aOk{q{oic z97sRAkpvhKJ)q9Cbm#oN&6f?NYs302dunLx6mb~Eo#Su$EiW3Qcc4t@ zkU23d=+2l?$ zysp@=cr;2jpw4S0tr1Z>J`mO1_**1tQ)dd^tJ)M*o3--8&;S-BmvM%FOgs zUxW|MGiu^P=jn0&fJ#<9U9R~^(AqgL`!B=iJ{O1kT%-Tn9Iq4^OK`W)+=g^1?dG2g zB7f(%d-?PCZ>FaID-ZVhn=g-k;)_+&2SY;}6UGw8giSQFTot;C&O(4X8hNFEN?xiz zc8jR|yu9T6Jk<0}%|}KX>u5^ffs(#qctdJxUY@U8R5EN1oui@a*4-m2Zr5_G=)&|} z6&Pv4;=%w5bu!0C;P36_Cq0l2ah+GSRV7zdy8F6;>AP}0q4cN{d@mSYq^9$)sJfxL zATd&a<)2dSUr+##W+k@fLh0{>m%8SRRb&MIdg#`~^!)*M0u! z=I0wO?sIiN+VG^}8@0)iF@HY~zs$uRNyjHno}`ZSuP>$^C0`~z#KX(q&yTJ%0p-;x zm|mVdiFf^?v#o7BnIg*S>iqHX@#O0L`|~}@@?w{dp{8HD^u714bU7K`jOQzrF(IM# z-UmM>0L6iB-V~SH+i~aqC*PuqwDCswv!}8L0tT9z#uHjSBRdhQ#~Bd~9RMrahM;tk z(n-^as&Z_ii6`-ahc@9Uc9f;~dJl}ps6W!~qt$5n4V2av5qy5WC?O%LXk1w@?;mZ= zS)8760Zx~iuJ{n|01_6f+k4u7(hs1&rY5J{487J~R1gwb&<3Te!k-AobEI*R$OxKe zt~3Z)QW9BE5{99g_V!&T%7N9qyxQ7YM`tD#v#9C+=|j>7Uwsud{YL+dn-6Ys{A=fi z+VcJOcM_tAejXd^N$5&xXXnArF@>6UZVeWqj|Goy_1zj9ytOkHQ^*xgs9qxj2G@&Z zcY8YXdfSO=T4tWvdeD#3gzCuH(5gKRfyGg)!es{9NUHn;79NUXbajNAUOSjI}u(MrZQqB*2B-7Pm}i z^QO9l;pdh0(!@EdbP6Q+@iuKn!)Rwj8&W(j2GpgY<9Q)JT{FINzcAiz^bbf?`&mv> zan7ZhQzkm~LghzTUh{ZdXx^sb<@Vp%&l2P3FA-nPlG8=%#({0F&6Ta93(O^?+iLnB zu$Uhayg1!f(2eEAMdEUkAgP1M{J_Insp?Gw^Upr}CnitD3RQvD@uhr5NS}q_;I#UL zs@&6(yKOet9c!}ZFs*PT;Ww?2TpVs3G=R6b+p^pkJzYAx1#?GMWM%nfhbNh{ON6N|5B^YScvi)Pv2f`ALm z7Iv8>pWR7ol+?%#SK@f<(X^idbZf?-zjb9TaLMYfTP)5nc28PNKkk+mddzdTWvHhw zA|j1HY%vx)d);%P90i#>walW@7!yQwQJ zL{pbZePb~mB17uMHN_;NlZ-AsUL-DG%SQ&)nFY~VB5XGry1-p`q^EyLYWk9$$Lb>( zS+8*}DdYBe@%% zR*!oMNDoUhKaB6(cou0G%GW?yiqssKB?O-v%lhFA0=sq-7+lMnPscj`dPD0|yEpai z2)w)kRs__ke4K{`BR;+!Q045!LR>Bj=bkD&7T6a7eKQ?1jiLA~vm*{4#IAE4o2-+AbF0h(42YhPaG^wnP)0 zu42=QO!lh7^zx%m-Ws;l^cS{1{kkQa%ZhI4>Q>Urlg0}Jk3VTVF9LJjA>)NBsp+GX z9gt#`0afgPE;o+B&3tCN11I? zGI`ihnRF_mAa}!CVEW#NUF88)JpFw7PBtbaG`vp&%KLX(YBvqvp5y7)bnz2Z1)RVJ)i0!yVe;l{kJI)63+Y^qd8eSJqQPN)0JxpesG;Q&fQJ z-}BQeXzAzvzx)H#34Ls@u1=2(sk-u7#$A?W&~#3H=XM{6#FH+*Ur=&h+1rtk0d%*( z*>SKm0R8_^%kGxWSho(c)9UCnTPd4yUq>g6S<5xa^1=ra;N{2T zs?Cw6($cM^r9e88zOQd)n5UbwF{avclaxE_WP7J<9&O z^!ZT!nWeI5%&H=V(!VYeHAwEdvD9>{l2U3qV!ErWQn$v2{zs;=6kwOMu7w78#lJSB zL+dQkT9ZaD*oKgeLN5JVKrXTtS7T0>ncS??HU_#y&PGn3QM&m*5uOCMe1gxV{%?T z{q}w1Ikb(-YO493cMtEEl|g_9*i?*(|BV@VzeebAL!YBT6!P@>y(zV1r30Z)$vp? zErHdIN4>Zh-X>&`n~i}rYnj*nwyVVexo})27tkD)-Mab6i0T`^BsG0b^rHENX%yU& z^isduv1gka3GL~l2Wj?H&E>hP7m=B`_GLm%EILF>hYv4ffQVVMnI1kEn9;tE&Fg-u z@B(jR|KXeX(82C(xExN`nF&5libc`Xv(NSk+_SO5q$&DES?U;Hn2m_wL!eTiuWub) zgP_%A3zyk>B$ufzJ+)*BfsOM{b6L-qJCuLY+8Nc+-?}1Ntj+( zxbbYu+4TzP85ya`Rx_lLW2feR<=CM;B7B)(=8e=B`jGBelTi=K*N+VKq+Qs1q2B&o z!AYW^6hc!#Y(ieZbdVManLKnHBf?}5R?tjIs43Z0zB+dEg=o&G=WFqSE4_s!vYJOD zNwY6>j=2SST1gM0IU+Sf62f8>%qZWBoH5+YolBP^RC;|3m{OG4z70^u z7SDX~j^gmSix$G)@}i@J3&wc{($<+6QfjOLT&v|NV!O$R;c<8X4ym9Sg+}7p;d}rN z8y#Jt$s-8hk!_hja!3V?Cz^ z$bTe;N4=^Tb9gpV?SmkZ;F|g&vCkDunJUk^%}*ZyRxE!Vo;*MJ)t5gfQktL=egsjKo|@m z`PGSGi8y62y--405t2pABP4VqrW?lyr@>G85n|Hc`sSP81>sNd`n|o=(~~Px(QH%Nyh9r&hL802%F*(l z);vrpudH$}iSzgM^G|4KJ%0yx`i=LSuQX3Kg~ldy+>?*XACD`zX}Y z!y_`CVqK~non8UF<%b9uZb?dA73ZGU46;M$*kg!=dFBw>x?{kBJALQ%J{s**bCQ7s zoW#<^tVr6W<_ptr-f4z# z=hFXsYV+GaqY>#F|0O!@!H;h|xN+{>-P$v+0OBu@y~Cs`(awWgOJgOJ$HoG_j0~CC zY9O6!{4fWfe!WY5j;_6(akuLrj&-c-x?t))(bWZ{pE*-ry8lG`{><25H!J9+)ek@q zrnA*Sxnq#&gHh&btLul|BUv4dDj{vm>9|EgLede_(?c+2F-p`|(SwLdU%umjdZn9R zrH8M-r=Qc?-^1TM%H1oQJTJa+Zk~RQ%Fw#W$-b*EuNhXjj+c7=Qm8;MI(kZ#N9Vsu@s%2HN+ zNoxACWAh6+xo{IqAKBBKkv3IRKSfymR7Awa`csQ`F5QA38Z5Q+TSWECObQg-yLUTs zE)30`V@rJ$ntnK9J*kLi`?2`=T-WEl@oLcC!b9G;{6!h+S)@CxdZ#3C+u>fUF#N;(!wl3a@J5fupR!_UIOHo2 z%(9?p`PvzNM1#WN;o@`J90AE>GlJnpHJ9U^HAY#F4kC6%R`8{2?h5wK<-`J$x}M@* zA-O$!%Q~t3JQv8DZ1(w!mZ(5f%)Nt{c7})hEJPJbRisSmnB}bKv;tl~jwqxOmR09Zx**H3i$u_0<|{ z^FI6Uv>6$=aW;YbU(;CyS6$ciL4GGQ%i~5v8&iCdG=t^nm88CE!KzF*Pg))sVqb;z zHLM~kGK;=2Ekx-BRF=Dkc?LK`f=63J-CCnsLt0z)PaqJUp@_6$2cvY&?nW_>~-=@joq$3+HK2MPNqq;_4f2UVwPHClze zS`vC+>3CrS)|gA5d~*LA&vs88sIK-`tX=|+eJ_kaB$Ru3Bda&#O>TCKyG3~$H5~)Y zz<3h4PB6@I<{KvKX+=7cG1M?XGENa`fLU2Zq$qYqnXH#P17oqf@()wW`O&!(=S#9e z{G0*q1=We|JqJ+JWllf$3;vPx(tcup6ls(DPcV^r7#UegW_oD_A4!&b0BtkRpRYb2 zsqXch-R!BYUb(U&kq^8H7Bj|l#nx^(IK)V1t&-+SX*Z~VKzyl~^@KYj3j-0Zn> zWuFWwOw!K{q|3;HHNCU6B(fUQJCKg|1wO~&LM5qu=&!&2u;uRCfco7lU1#i&#aFfl zcY3F%q#R*f=siYR4E4T8 z6C0$cQ)zno-40(*MjiOkOH21x5zLrhu)lzIr(V9XQq)WLD`U}9T6mOiRIWGUproeZ zM^~pF;d)8-_Gj3EEgegGr1D(+_{~r%6D>w@v&;NKpCi{5xQ@o|8HI;EDl06pYM?rc z#K?xKqWr3cqm_PsgseL&9nEF-pBDR1(Qm#nly0a~D zbG9H5U5Atq{_l-oZc)DO;&+iXMswDcMgaQZqGP$_bv7`N&b1jwfa#WdU3rswCiv!Y zrP~3H9959cj~HD|TlH4yVpot_hL?XOr`sQtjmH?TXSn$@$UJ+Mh1!;oE=aeq99*^F zzF$^%Gr4ZfP_CXv)&y3~Uco|Toy>YRdR~U;M6+fexmtQqzlm;@r^`svw|4Mn*O~UKvjxrfg~Y4`!If(J;=En0zVBe z4kdXve6D9qczbrlMxl8PM?j0GqEv2jJyjKgvRcCd!8%Fq%3I%t^*mbsmwCp65iccu zEpWbm+l94|Ix|)WBT4A4i>0OOHNyY$!0U?R@BN+pU;Ud7x_JI-pAlRyY5g0!3ws>A zc~kXi&AgXWHSqxN&QpEa>xAhq<9m5I{<5@maPCxh@s^lvP+$;Xd`!;tWfu-#!|cL% z=O+GhC>>0X0Ma8O9&D_yc~G;F_pYA~r}`H0!uunvQc|%x?iWZMVO-y%zCGDBF)i_h z;#G8dyw3~ieG~+%L+RbemewQtV^bN~mMsC^1TgL#IU7SRjM36%O+STa{czjRg^kZ) zS||6hdCycm%T9H#{%XA=8zp@j(sy=uuirbu$478FqqW0(FW7GvF)4H*l|P#nL|`=) zpcq>)eJG6)G?vxd2-674@b`*%K`%g0Pa_$*rA-Gdj3z5a{X{`!7RcBxq!u6x+TnU^ zBOtZJbcAdfXE+M~mW2}l!>gU=vlL!uz=D#_Lu)8t1bQ~z&KP3dI+^431j853pUc<) z-JdiX#C1vi#*$7^DUYHINH(OxRU{v8CDI76Wj+r?&&Q;`LN781w~Er*R|Ia8pdJW_ zQ>}`G&IXJHNLpVy7q>j^n|PJca=_CcjYA{o#}Eb?h@S^C=gfc(Ns_+e9*rqR?UwX` zirRnE7xLe1{p_?A-}z50F~wB=^O3hLPG9V{i2t<8tjAl+?6iRX%o9Q4_1V+(!Q7Sx z{vq2=V>&3lm(<6_bK>p)0d;Vrrl-XG-ip0zq^Ez~rL%wK3-zWi4-NJ8ZA3@M8obrd za5`ZxD|5J_pwumMRZed1s@z?f6>;tuFq$1H!QLszj7}%y?Ca~1KqRxbdp<4|570YO zRA)~MDx$CgM`neEWwo{j0O>|Ym)39$%Wl+NVuPYX=%{DOk2u$At9s}|(s&dH@K(t^@`r@txF zOVd^{;p;$O@K^`kL6N;X#tfuyKt-R1^$ky=rrSM^jNcrZPApv@yEr)lW5A?GVU zeD#~({@CF?g8%Zv<_|WxpF{>>90{jikME) zOWXd)C>%&_We3`D$3(Wb9Y9d8O03wG8&$=!vJ=(kDM2mibRwqH6SZVz#dz~0yw_7x z(qu04BKrH^dHX};^pF4Y?{54fO8!qyoalN;KTy#(WbT@t9y`Mc56{RVDna3M@S5Qv zA~;I8fF8a4;6Wp(zjN&_yE7rC1NNPrT{y6aG9)?ud}&EVT&p}U@88ai+q$(PPA7uw zsk76s)6d@oDF&1i)IuX73L-e$Sm$`NJ!k+|nr@yDS zSDCkmyQeeH!#5zAU>9QV)2pPW%a_g#8I)}j(=+{(?j>z{_at7HS5IHPKh@Wq>|g2U zU(QcDL(d`tX|f`z$!?n5a&_v%t1nJYT>ODJ{f(<9>&7$=LQO9%Z^LSoPgO$!LkNG5 zPBKwTOT)zJQBm-Aly6*=v-$X@(NP+au6sT&0VO@962l9Xqnx1%_VcSusic~e@Kl`a z=KCW`*REWvVVNHmb&kb3uDB5Wu4R=ZR#hh!krSH2YxVW>^mMf3*?-0CzfLnZ|AMA& zv|w2`08fk4C8r~(OF}l2!SiWEw^o?7Gp2OQovv<3ihqI9Mc)vw6l=}N6=MOgwM4Qx zh^|F!sf`UgL(hhwXC!r_ZJTvAunWNd+;F@>b;IMjYm>Qza3^;&QzNT$cy>_nr~!PP0icZZS*htRTe^$UEpxh&(`Vl5-)_$SpoB~k z(rrqgA!%y`*VDLdfjCAMbGHV#{FV~9I0_M6L_v$wmi$@Nxc`Tn!LCP=2P6p8n#V}D7fQk9R=zmsjz(p@HW7pFt0{K)p=Qqzs5E@J<3Fnx~CQ_5n~{DT~Um(xbVYS2f2q3==JuJgITY4nSnuC8Wwe|FITnAka~ zF%S`r(;H;PFhT9-JXG|{;f1G;EnQleHWX7IJyH|H&M^eFU|T^E-@C1_n@tO?3(#Fd z6V$`xOmf`*sl)x->Mx7VSMMy`eGjkFb&&p99PI3h>19NeerzO-is8L`?BA8*81)g_ z!Am455!Ks>%}_2-jzle52h&lV0eMa-tRO1|g&Z{*4wr1c0?8UG#x8?kj+Sj2nS$xE zm&?>6pF4}uq49|rp*);+NAw{LkER?K#FdDyq!^lpLc18-VP$3)itzaiki(I$`8c3) zZlf12nuixhD34qps8Z4BKuj)pY(&SFh>y=5v0cLf6@co50F;d&Fa4iq!?OxnIM-($ z0}Y-raqR2XlJ?HCg}N6qURa?5ScVSjpc)?!Z>x8cRCmS+8WaHZ@qsv%@Vra^msLkE zfmehlpV5lJcGUEx_B;H$znKxh=PY0H#8+&iiIe}H=I2iRlF`9ZpX?PiCQeYSb!1 zVRmH#?I`IXih&shV)8t6T7fVg&_DExJNOF3~g5J88p)1wB z7g5vy^Uu$_lOvDup^aD@)POFWJWe1{*#Y~ccGvpmC(vf z&ktYx>ZpFJ4((=YeS0nxRKNEH8&qhI?|E!{KeZBAARy4E?vIfI3;`-gx^FR+Fh7#be^|#;D=g1gE324>UB~>0eDF(~-2H zyrWq~)R8hBJ-o%^Je|-PWnc&<7)%_p+0@q7>`+$=g0`EM>fm)iJUb#YOx`A{g zkf9R=1^HD24%{zo=NFV#AE>3{(Sf$AtcqPxG~}!ux^iGYN^c}FHk%F|a*(y@-VCD~ zME}M&u7ARdnCicFmt?{>-uV81npslRRBRA8TbjLCA?l0f? z_>I$7r|z$ND=8JJA4pfT(X5i9_Ue*I1o~CI6o9UK`Q>$2U%WVc@zz_f{--y7cKY3r z68X>IPGBK{MG38TIf3EPt7PuPUMSyWrEaUbagz!AwvRKoSHb^ZDwiww` zt?hee84%4{Hgl=v_J%A`f;#ui1({s8MnbnJ+$MEVx^-b&{b;gp1m`BNMYzq6*;_|3 z7wg%<=oY7&aRf+i?xChD4u(`1d$Oc-VY;RnFTYdf=tp>MOZSzIbWxXXF6{0 z=)Id`WRp;1`j?e3QXd{pI{C3}8QI0OI+EvQ$vir=KDR#Y8tq0&bTJcY>B?f%cSPnF zx>h}?*XfA!}Q4hLUW=agm?q?gl_69vn_taz`D`Lmo9>D2K2tM2cb2TlFG$2 z*M5h8_cyb==}_}D989c)f6M{r>}8hVhu zRnV*>X!9l3;VPNkVQ=!qs_DRZr*CI4aymU{I%9hq8-wE@^;K>ldd~73a$g|zIm>ew z&+)C>lvJ0Rnvf9c7S)*G>xOR~ecR7ZI2jV+5my1q&w=l`8AUKD+y=sUo1BT1CyNFgnjT4Ti;FDC%o$B;`NPuc5VJXykf#_v%v_AbU~!(e~RaCEZ`tAWR3A>wH)3I!_zYUy#~z zz>(+W@19pX)Iw80K>am!H=h(N}H{A%^D8fv+Mn7*KBfUx$qytd@9+zKzUX((wu zKvK*~ztqOO=8^FQlL(W^7V-kjou27QEzYpKTCYrR zx)fnach)-mf}LfR6mC{l)$VqBx`&lHyb#vCkj|^x(($H1=P4Mwhb{1ktQdCb$-J)v^k+uJvcLhjIx$>*&ei@{-Q|}@9oSNqZ4+3oL}0PE2CRX%F`IpX&}z;G|mi%vEO(wU6m z#k_65HZJ{N`~>U|O3W*Zv~Fi8+`9MpwPgWuEwkWUu5D`O^wq%bm9IQU8EA4B2pS#(AvnQhmmgf!5-d@auECaHa$)<8_DWT{-$JXP4$B}NrUVMDIgN}6uPXycVnj;?b&mMI#5x1CgRxi75q<8^xTh z25>@xoI{kGk5s1xdL%;Hi!pNJJThKDW~XiAtjk~2Q~1E zAijfcqY}JHKZm&k*KLj|4pI|R^_oJVk2iJ~R-1fAh6wR%k`8TNu_S!$I?Kw!)6!4^ z3(U57iQ)_rd=|0^^VwmUqpj2A&S%J?#Hosk3z`4R>Xif??RnBM}=gdic$>~UK1k;!20>qGKVydxPqT>GWchmh4F_oO`8{g&`pYi3O3K9&QU_70jL!+xzspZ+?@|6r-lU zf*HEgf2{7-^L4!)brZ+y#zv1c(l+#ku_wnY-wR^8mHuMdkWSOO)btL|sKl_9nH>{{ zhOR{R{+u30-~K^$N~%yVz#Fefz<5=9a$A@0lRtd(o8NwE-&nq4X!O%S=cR&z@`A{c zxWV!Kfx*#>(D&5jU_yR~m$zGQ&M0d7?K4Lb?%Xu)^vS&A4;!DyZG7=|$Hl2B)by#L zqR8^bl*Y#7d<^+T`Fg)3sC#4AKsaTJi}EG!J4$CFyb~(Rl8(0!%sAef)!?9H3V(VU zn123fdpo&|?d|7_j^4g=?}LB-;7(a%+{%)nYqT0Vcke)Zp1VJZF<58#1IqN8t`zB_ z^hdOG2j0R1q>`7M=T4iWY`_b%H0|mS9il3MYSLWa#?jH?q{+$2`%{-Le?wlEsZVZ9 zzW@G>PcC16fSO)=_2X}S{QZvuQPbaVKl;<3o@hUTf^OvSGh5Gq>9VlE>05(IaWBcF z;*$#me@5)CNnZAY6pU`&`ug3wXRl=+zI*(kYx(O>pE-DjfRq#aOH0!OT5p>kq<7le zyV3^-ySh@+%W)-n<3~4*s3_)Cvrzo$&~>?#bbSLoq5>%Ttnzf$Hao){weDezK?2-8 zJ@XtXVXJU|P?VYJ>u7NgbC1e%_zBYs0-SAC>73sn--S3vC&4UjWsZTwU13g6Zfv?m z(Bj7*ZrOeBQOt*rCOQ%t8yUHhcuAoEO}G}6ga!Kt2j?s|iHcKK9})R->*QM))W3J@ zNbmCHo&iGHk6=uo<6R7qG^iF;K@SiU>vu>e26lmLHzAN@S+ zKRx_GGSlbjxUO|Gx0WPq%jp)1qNn3~u_SfZtp)4Gn{H9MRC5XEmXeOqMedM4rSB0l zHhznHVRakIY5XZbW+CXy9RD=W7F;af3v(>AS>52Y?B-%;i_L}Z7MM#lw*_)*fkpK) zy{mFm^{NKXvAYP>WqonsxtY-&9!gJ-f26*!x#rA;$0QR*UUmNQ!bRp{bjnBnSZ5t{ zc>+|o8XEm3Ieq4>o}RNmDB$;TFZgU|22^KH7I_O^(ayO8gJ)mBuq=SLgTo81#7b`n_PfnwDN*@y6)r=SISxL+O30PzD%!9$6k2K{{+|WOYO8TBmV{ zoaqAgz4qty1>dY)9i3K_F?5bv%D>pr`obg8Aq#rR%C>Cxf! z+c=l7H?6q72A2iA3p{r}$BQS4k-?0>yg%abIb?Ob=$5puf!D@*^mF-NOuts%i4i_u z-hdHcoy{_Cp6fYx;3qvl;lGx984>tmu*mntOd+XXUU4}b)jm9k0L=MM?R;va9yht6 zbod%{59-@nT!@yAtAz!}x<|sdVY&HeBUdB#cB?OsNMtYExpQ^KQ1?jTWi%>s8Z9;5 zCi$JmA}(CWw%`1CSa@^Hj_m}#a7{l?Y#pGwxESj;&KEh(QKyMqp@k>nv=(9l!NEPguAY28W@O4Ze-gI<&IZ)tsV{9olCjtcD@qJ~!{z;ny<6}54 zvLl$etE@Bs&+oma3(u>*OXGU=UV%7BJ zy?GPPu_F^Hg7mGSs}hD2fb`tuuy{^r&hpTvj!;zfIk|B;#JY^84j+NvN1^zHri54} z!Q|u+upTEi&tb3JQTl@B_7Yh_q+DIKnvclijf>ASBXbNvHHlmskFH&N z?Fx-ZF{l6R#s@b(xIsCyo*q+Rqs8*prU%98 z2OrYwDEpna?>>A;fR8R@xuB_|s^e~xHn;DdQetAqDB8A%dwz9w!}*mZMC+7> zWqN|?%U2CgUR{Tg|Iy^dpZ}1~StK)3p0J89RC+nh0L~YjFCZilC?`LiLfrz-NFbdC zz|H`#l$5fhx}=UtA{k$-3k{{RlrVI*FO$|H}#iFcKp@V=gvyk~yiUSam%F#b5rOuw1c4X2YXXyv_tqXaX``GO(a zme6e>U8F8Cox8e$%Kt#u)*PuX)+!~vK)VvBEkHNoxW(SCMTUPNVo|)s>;K-Aox;xM zVis%8x@#q{{4a31i_uwb)46VN$e0CYYa8-imKSw2g3)QG#3R`kGY_PjAHh1?$e9kP zll-E@7lFFr^gsWjKMPZRp|jO&g6m)~~#g90$2BPqw4EZDZ@XI&fY zw$@oHx`pa;p@XQFa&E7%k07Gg5=(-gby&^Lx;yJZX82eOh3K;}-QLi8p4(WZZAdSd zheZ>}jRD%+J8Rr8n%yGDIn&ubye*mq*Y}zP7{m6^w!Hy+U?)$@FzM(7${6nE_~5g7 zU_I@1nm5^<6;71AW=3kC8caD_Y06Nvpf^_mkaC;ngi-e?S3x&x$x*> z#lC3TX0EL(mOLh=Z~U^<^uk4j5gRkeb^+641~Ljs7SJFkVq1N;&+6!Bwij=!0qcs_ z)~wwaU;kYFMyhamPx`W_u&b{)MO#)pFUQDUq~)keZqwQo<8qEq08Cc@QB{rhKaiS^ zJAGqKJwKp&#KsXV!3y($G?)kCdBW8D&zjU11NRc!(=sBq*9R>dSx6>h_$g_!V0d>S zioOV&dvlK++gY<`d$hR=s2851;Zd537Y_H=XdzP}gg$clG8A9f{nedmLzrB6sn^M1 z*V_7_2-D6K&Fb%JE}XT0SE5NXVNxL}6PPX!2_fZ#g+tsZ>*TT&Z{MsoK*hL5jQ2b~ zFdj!bgo|1Y}*j03ZNKL_t&n;dI&4 z&4e|b)iLXeqhmIqS^DSgi9vpc&>2Sn?}2nWHHglWmQ{tE7{(AwNJ6Kol~pR3RTL#I zo#JJ%IJOl)Tk$On9`M2AQm5Gy&t1v(Mos4>sgyuCj%1FbUc(EqI!w=CM6vsCp0yUj*d1pHPtB@eYmNqL*0y; zhUsTiH__BP+EmvxnlOyC9*Vf$7@Clp*XRbecaZwcUL6o=hi-C5>zoPrI6Qo%WRhcH z$Q%(Jz`zNEk3`H4-y$SdhlGr~uadDn)2k|7DzYpez8<*Wal(7ZU#k=RzBs+TNqjEI zZ%Z!;@miYEulQ@6y3RhMt;HD@sxr&!+CK4`j zyb#pE#CeHy8e=9``udk0-&C8IiuOJ@FmNv$Odr|Z(2&)B2Sy(lXxpEdRdMIe2RA>s zIe9xIDzo(3g$rPMdwY{tWo4Oc?YmoQ+u9CXX}POL-n(lDvZ6?cX((zv+BSe$1ILC# zor~HC^DZs*r$G=WHLyYDjt)P6|Nhi>zVRIp{gZE8zx0j!!>zlppV(^pm9BTyZS(sd z-+nQ4w6ITd_-egOYwW0IjD8^dabgjgT(bJYWl??}j%J3EEb{b7cGTuMo#1+2vzLcgR9P9}haULM1FEP?Fg2u3IGu-R zYs<^8s7Qs<-~Hj~H(veQx8J_owSS1Xo9Bl|I}#H7Jqq#@;q?8~+?JGP(k_dF?Bx~o zI$AgN;ne*XFW!1d4*plKzT4588|TH-D=)|Qg8rVEp6|iwi`df6f=CZ}44o693cCK>c#7gpbYH|W0>7lrEoCKcg7YYN5C8xVkoh)_DdUBqMUck#a zRY37~^E0(pUc49i>zr(;3UH6I|Mc(&=`+*6jE%-)Ee@6WT8g?g8A;vtsn0@niRKov zi_s0Ui_KMODQ}Ds*p>DI9fP`mAc0yo7~mZwp4QKW*IEalD`8y(tu2hJUDVAyJ8G$^ zEM>ifagz}PcUuy<6nXo?9CU5n7q(kj?Uw6hT1wY5(IH)gZq2Y%h;F!_`Dg$9Pc@7n z;zh5CNpA*1y51iP)e+K#>7QZqPrd7(`<|PH_6Mb!MvHw7kD9A#jGkU$`V&p#we4sT zgjrk!DtU&{#2aCq#E74Q3pN)JW2(I{HKs+eAZ?}U$ z7l3{DkYh->AbogK=uK3ErKNdDoV-U1($L=JcixkRiJ3e{>Ps=s^r*2BAuvE3VzHQ< z14y*DC#aeGtYFY!95=GXONNIy_q1U7Q$;DjPROI#1F&De{sLk+CJz9erv9x^f!z+GeJjjkc_3e_CJE&En|p@aT~Ya?|UNb!Ru% zk3=v}G-AZ|cqG%bHQC$OZr`?TZB4NXW$P)k*sUk+ux=oRC7nS$0wc>Nlm_~707qQ2O(1n~L%shoLO*;{<9yNiX>rd+i0330mdknerMF|)BfH|t<5!9(Mc z(3$O6_Q@8*W5fPi?A82yGe`pmPo4Hx0A-Xih?2suHQa z_<_;kbh%y#d~sGuEC;|@kq_W1?4>ozJt`NL*cFzJeyA;>cs8l5^rOv-C(d+V-S|-o z7@`=*foi(Ctc)c%eSt9jJ)@>yY$WN0a>dS0&yQavc zZ+&vuXeq$ttPKZTbZA{R}fmy9+tYS1bZ4b+m; zBV}GrPxner^=_n+^LSEO-uU>@f$@R9)vH&J?4f>CO8US6MhcMqD6W?qH|`9y?#kSM z_d@@*{+fSz2+&m|l+lw7os~_TU+#qr=efc>wV)n&C(Hbepa(n}0e9E^TE2EzM;Z zdIADCSrF-6TkGu=6;SK&^>8|f#KSSBL2oMz(o=LA87@k&)H=OIDWBgJ{(P3O5Fa zpSim3!w)|^{nly4%TsuIa^DNFvB=@x>GGy0Ru6EJXqTb%axXkcoCd&MXEPAvGS|GgoW;5^h%V6AYLMP|)2BII2Vo@#H&4I}0L*jIV8H1Ac;}JR&5s-}OzOO< zH-HICx)qlGggx`yaQd(P6zmU5o(mgEf$LBC#%FLnKjF`#Pit#x|!E*LSogA%0gmqZH{KoV=ZwlW=UMlc4_*KZS7+M7^iiX=h( zs`PYCDC>y!Y5f<>sD~?dh1W0iU$A9$DeE|3R8~r`dVPJgdeaeWNY z=r!xpV$xc&LB05RI*>xm)M4^fIZLsw)N@$-@L8%!Gq~b?G@Sl`&sj0^oI-%hC8$$A zT3-{hab)DddM;GaMvT;dWc)Jc=wq5O#BL0yNQLRojv*+0$uWhkAgG5k^jS(!y@Fo= zSsw~W&k~w0U7X0p@Q6JJs;?Y9m$shzQbXUTE~{QtF)x}aT>aJ6Lp385%TiP-zk2uT zjYHXm-Kg`c7ZqYYa;fP+==K<*(*boPb#e*m%DDrxNb!zsXy(|rWyfAC`+5w8o9N0* zd3G3Is1=3UiGI?5OX1)>u%}e+ zea)WtM8`1Ty#4olF~fWM%*pDwU1=*DAhpp*D%MD>IOL|tOg5zW=!2rvxG@{OuM z8ei$jhNPxQPgjtPYTQ)i2BJ$*_pJoesUa;&&nE*sE_V6yT`Ob3^wW6LKe>Nr@ZiCx zd$(>a^>lY8)zxj<v1T0JNvPxG5OAO|fBPPtNPqnP@MK;J zW1HtEbq1nu9^UkuM=ee#-IDf0`N;v!Dnc1)G)Xsmibf+_BeA6B$u&8>GrO42jO zX>gR}7#OeS{3e*5Jg3{Wv*Jwm~uf2f6!Mvo} zO`BS34>2`a1H67q)8(O>?~ zcfN5M9Ua^K)T2j_ZcJV3{>J^u+ZA^{xbexU>k-oHyOdA({WsR$c>l)xcN*aI1Fu_# z^J!E+gP4x4UYgQXe$Y_*V}x$!tjpiRMy4q#Pn~SWyLWr8-F^ES9ZKKMzLqi6wZFtt z({H1ud!wcse~a)O@-$?QFWrUe%rW*W;H&88O_XA7ZJX24<}9mqdUyuZwxKasCAEcx zIh$*%7!tYVIjY?KJ;L%F9$|hc@Z|*s>5|h;dm}O-31b{ctcc4a(dXj-dHQE>{Oyjn zTVAK8_1+_4I+;Eplw1@r5gbVR&&J(Je|> zIJh+_@<} z&dp-BFbi0%`}U0?bnC7K|7IKOXy$tQXtS1?S>sH%aDDbF*JDjXIxEdQ?2Pw?q!*0l zSY6P`Wq!dpP7x=j7QE=((qIQI7cp067`8?JRTomYc^k|Je@{ob>zFdTNI$n8-*CG< zt9L|ddm8Q+rKsDOuA82ovuB}k(!qu3^eBSUA$6An#?+O{sea*t%rQulOojX`6RQ`S zyhh3CmcWeiZsxxnHGR$n8R*k``f3oD>-!=Y?DQa}Gtda~SslLz5jkz|c9isJ8a$=- zA-YFD7hc%6Cq|Th`P3;0?%4ce^nOA^$K!(OKTR<)d``&WJ*2(pTth!Gi~TrUc$aJH zw>@A?gqkk5dOaOPA$HRR32hxrCs`f$3z07wJvYxz$(poX$&1lQ;L#)Dg-hzA>3NDQ zzOYbrr3=x)H*VQRE+dT2k+$y{sy#4tAmi*tz+1+crG-34$>`muu5&Hd%h|qT%3UY= zMJWoHUeb8s$Bu#N7dBr=vwv6ASThC&$DvN%3z3uv)4)2GlO2RGuH6B;t3fHEHkghp ze1)PC@qcjIM8Yy?&OASImIOwtF%fSU<(-T*aFbvSUn21vsyE8EEa39W!1rLe5ufEJ z(dh$>CiEaxp=bOGAe+rioZ@zR74hit%c9ZC*M;L+S1Tiv_^1>~o`(sE42s{9SBWv$ z1bX;7)(}X8$9!H81*PO9E~MOZA)^K!eIcg^WYk%RK}CW-E_2dsn4f>aI<6JL_QFn^Dsj`%W8RmM@xBr#c<8 z&eo4(`WLCDk8T+5812}gc0l-Az;tXFN0Nw03GF?y$!#>LDKrjD-ym8a?noFOog+I8 zY}pittED5i7fMHH#|opR;|S@Pmxnph;AmcI6y09D{0o%5=&cSc1mjhDd(ht87n$7O z*SKEXabo8u(uOn&Z+h;^Fj{)13)5+wNLie>uN!bKPB+1F?g8E&AqAvAS0`44MTW&L z-!*5!g5_ZPxA3OlzY}%-;MP}Yo#S2Ame-iFsW~NeA}@8Kaja~jtZolYVjPWm6A7V5 zQX3mPHs}=#(>FZ%f?;+1Fh>#+s**iQGb@uOj~}2_=9Bwgdh^YY(HAy;n(T!g^wk%Avr~m9_1;U zi^5*AqL=|T)APMZqYv?}Oz@L;<+!>XRW*zcO?B_|8RM>Zi?odjK@#R3v-HdDf{nyL{ zuoD(WU|7#kyX8%%Xtq2gYw%2YKoxI1+PR^0Bc#tzItG|>7`=e6VVkp{%n^`Y))wGs zc6t;z9ZtTTRb|eo5L!t&oL*j0ZF$~)$x3>Oq79NLoh%m2>1_ezyriU*leC^+v3xv< zx`&59IQ_=oe)#s;u7jlu;+p!V)-mczAXLUsI{THUBd0GQw*~JIjkuQgjy`bk4y z2z63{FT7JH-+eN)Vz414y`aD&zbe0E<$_G!nSg+T{OYRlqxp39<##B!GU@o5O_NtY zeEHFa(NJH$ZTeF1>){Wl^Q%D{CexMlF-q4RaveRfyewG0c=_U-Rlx!NZkw7bqf(AH zI};csbJ8K*t3bb-`t!x4zk&ZVlabVop00XHk-DX%&mwgL<(8l>;oRnRd0!|e<-SCA zS5c`PEe6zGTx`^H+o=v+gT}hHyf9|YEVII4Tu5%)TEyIl^X!a~#x4sra=n(Y4Qq^# z-AMAxi|O^)>|-F^me6%n!}>5e4`v?Ej2Fz1!P3&ulp3N&uNZiYbKk4U2JVF5UM^lp$1P+n!Vrxb8Gpu8OF7dGV)}9VKqPEa*NHa z&0Smly4#rtXD{vIlF?l&EUnw3`kMZ;_*eGI(9+Ya=0ya&AhFY!N46Mg?XtQEru$%Q z3E;-20wPL~cO6j=Vm}@0mTP-~%f4@(hZf7Kt{g~&bSCNP)`X~j;R1z+LUnjttxB^u zoA4I{>Vn-1m|w_bgmZz$dB>iMHxV$=@sicSW0#^1r+-;$dOh5|aW8Kps?D)%igNq< z`eUXd(xwW1j%D}J^K;9Z>}}iDXJ<12>dUSP!XFa7r;kd+%a_BK6fVJg#kkX{9<9fqj+q>PI_DlDkktDlfc5_V zbN$MG$&mL&xiQ=Ox1qmJVInFlo(d;QabY(ENcAe|FX6@8iq&njc;gh$oQ_B9*CWK6 za7?zFcj~el9vP{f?DfL#uk5VPka!NX7oyQ)Q{UY;!U+MNMXP;k4rja6bo%+gp=&{N z1M5I}bRZ)Z3QMw6VgdJX4k#upCmJyHL^ULUiPBrK_N9FGINwB2z}`j(Et`ZwdVz@qBGe z(0p>!@!8;n$LRuZ>p@Y;gQC~fHu|q3M{oIJDhEAN53N(!j2;O8yDC`cOJ1j3btwY@ zo|(jPm4Rxku#hK<+#kIoo@XU(AFLOI-G;^nA&YV7^@?3};6Zwv>&Jex* zmy?^>^7t%FpED;3Bg-0X7xTmuo2R#*ExtdF>0hLp-iwz7(ry~XwX#8&-jUNw!CK10 z&|YU!oUbEwRj5|7wrMz_5r~fyqmMT=h31S759Y+7nRh1a6>9Z0RmEbQH6BSl!pjz_%lvZWh;m+zBm}#MWG>j+hM!>|v-gE3FP?t$ zuU;xkY4oqGN**{mAWkRmFSQ}==ihzv&6h4VQbL-Zp0c6q$XGJPq>q7I+sVc&AqSHkKW4*`yAo14SVN86&G# zclSAt;+HvkKE%&6bLE1SCA(VRS0(4|271zS>M^bVN;|-bsO(QdkG5DziQ~!zVSezx zha~jG#FCY}7VKJJwDeryF2`-Ov1zhz>ScrI|1VO~KeMAFdpiU#Evv}0`zvbFB3SNJrMkW2%dW`9X$2hv5q!+((e?_u@>5|S>IVvytA@m%@=i(5#hRd@(+Csp*!WZhY!Ob1kyy-4?;Q zW4PIdX92WD>ej6Ua|%c$i*pfr>z|D3u(suju{YPA);^NMiB`1bbXR9oLLcpsfgZ}V zNi`3x(orM%v)T~4Uia4p>557>Z;Qq0z`BZVKl}duE0)+Flm(?WU{6coP_YHnHnS2e zXwSK}fBY5~0=rB@{-^e3TMM*j}OXRn~SwS@{Kn?HTA`HjSVv=7> zw)t75vS?0=l*)*;Tr;M+(|QWC)p?V8W1fKE-@3S-&&;U>@Eh*4o{o}Z(9}65*A}w# zfQ?0&+M6u#&Q#Gj9oOOt)IkxEXo~i8O`0Tw~ICsJ8#9LnL`4P#B>TsH(t=Ng#Rpn^s^cChuyerUg5_2@^9OF001BWNklh&zby}s=Ma=W4RbBFuMe(AZ_6LC|`OLe+~p!NE~n(g(c z1m2+c+-^}JCn-k4M*>y9dh@WI)7YN|h~r(?R!V>|aypfy1g7u&YWJRz!s~!N0z4OV zs>9)k>Br{p+_`bjU5L$0a($?MC%NPzb&|@lxF{$^j`hu(`}#IhIx6)XI7N3S&qcrt zOQWpg9pAPB>{Z?ixraft7{!wgb<5l$zy`0Cylzhh%>~bpFmP|>7h+Ap-(yp{T;W1x z#W+fXS5G8O#IhKN%i3_C)l1RhvCR|Q!eBwqe1%*q>kg&*$1Mia7X#}2$L!qH7jIgg zs^t*@FKFI#=Pd)b;cprk88D9;c9{XU4gRvGS1_aj)H5t4Ex(bJ1p0N+bB zqEU%#Ag2VhcIkYq>~Olz{3Vc=Vi{KU~2AK>G=2?$=$mbJr%iopmto&8X?zsa*KPSHstAS@Oi97^4c+=}9C=VTO#I2HA*Vr3+Wa3QSk*%>Q&A!QbO`)xMsd1@E!^25U2?=!x zxt!Jq*vE$xMh8OmOmg7} zSWNJ*gw(ONgs6rTst&>Qf;l}bil&TkI(>|cj_jG~CUZJbFH+!BiFYJv9ZXNGSeX^s zOQQRN#l5fWd)319^CwDi_LdU*eE>Iz1MS`!>OUdbGbL#v!9S@kZ=x&-^9xpA!TOQ9 zx(-?&z0mQ(h9eyY)8o{2rj!Ver2Uz_PyYN}`WyWqH3fF|uCA`Ct_J@qyEataj=PA= z{?Z0q$gS?>DNs6T=Xk=~+PYE_MiZz*WCUQ;bb>!Ts`rKO~QA)A+!;GvG>1$TOs0*Ig{880g>QeTjh8S9Dd>BajmPsxpbiVFehj~?9_ zzJ0qlm(H&xxpR7ZpMUuqm+!y-{*P}y+A%`i&`|q{eXruW{`h~}{)m{FJGalbcU`fH zKc`DY_q}fDn}c++71o#D}oYXtdkeEhdp zFK(bim%r0l5XrWsod@@KwegtM`A1RH3)0K|Ji^M7lIw<_f3*4KtCJnRlo?~EH^W%^ z7D!Gf0Vv8XjB{7=h+$ASUKsIvSXNYia)@F}moHwGNh9HAXI>H&v`I+;36#QCm3tI; zrPEp0{)@yPBzyW4pnvMFwb5+g{5`~CWxiPM^gos>`;WeEbGlgFHHpXVN!D~y7)9x3 z63L6gfq1Tww7G@2nFot)TsI^w?q-?6b<43X(1yAVWizXL>|$%>tkA{cbVyw-i)82IQ=h75Vh6pb_SAxRb5I>hJ6J>ypPSvp@4A@b2Cv#Mx=TtowS^S% zy|~_LV{e&$gQsU^R?nWZKPVT3np+#4bu-&GZr0h5%sOi;dt2B3LiGL%2Gl>b21GYY z9$Wm`C9VUBjV%m!Es-zBu=EV4gUq_aQb9Ts8_1%9y#h#<-34}528%o|Oy=fnpUFrx zb`?E7|5UkZ!?=BL-P1B1ng^y*RZQ;M%3f;_UDg-#ywcKe((KuNcQ-$K?pmnc1F6HI z#@}KcK(2oL@PN8;s|(d3_3hMQZd5gC_;bq&mp!*EC_38UIfyRX%a^96FMX;zIwEZ- zBfGwPb^VsKjdH0>k%q(F@IBet@gwmOeGE{tYwDjXgfkJIk0GYZ|9ttB8f8Md7jV2> z>nD&AmZ!Bw%bM-cOA2e?`ECGQpOi##mqxtru}IB$SL(JI<<7^sZ%mNcXuxdXJ24G0uf*E-JKCZ z7)+3o)S0kHA45*3sSy{<={x(fF}+wlj@Wi&&t9bW?xl-Xuim(4_mJ%;1~?6=!lP2v zDcCGtYdkR7oBQNQ-@I8(Kxw_XmR6s_bgbx#SQN2FlbT*E*&Af0(I|EnQeH?)U!rb7 zz-+ie9E;ZqYGri^M{ZVKr>VCLUn>i~>PFGGWl@)dguwEJRD43lfWN#n2=-WKG)hqJ zB9An0(L$akBPU~4$94nn$FGRqe#lvwK-%?k^@;&|mb>}O_=3%!UPmjG+2Vuv9i&7? zYCIuq#k$N>kPEzxJ>ERM@OkqYL!h{0h@l%PufwSP)VxZ!$1cOOBE%8fi;`V@e3pXl z^HeXo)Mp7Xje3!C%Rv1&=$8ad>)7^RrQhAni~z29^cnb;H~rA`!>;3=+lx;mu^@%n zm_tuAPp_LbGjlK&K8ERzuWw#MDZ=LF<@R?+duekkW#-eSmoHFFN8hVUIntyw6ucm$ zVyBMAzB0C9?9A9$?3gplJvk&SG&La(zqz9>H8f#7G!AD=-gsPS-uS4STU>5jLQ`I9 zs&`I8YHA*c3aclxaTCOz>g`!T%(Of#I8R<|D$XR; zaq+G>yF5b@O;2|Kp5SP2Z#TD0g)u_uoTE>{1w*g<{G!O}>a3EitX^A9f7f98quUKM zzKQieL3^L0?E`sjd5*lKye4PT!-=t!hqXsiCdwWr5&l9342}hoUmB0!syos_{EPaP z5(Cqi5ET+eXUN*2O^(O~uRMA2B$$3NB`>A23PwL#4Kn$cAK90jRdJCD(zk@^Aq52~ zN6w6ewyO8%KzTqieSebZF)DBRcP_oSfwK%~tCh)axfO$h?KFJ2!R6)$|9JC#)bxpz zoZ&;10o;1~FTel&>;3oI6ASQWP&?=x2%zrJlhV;B`WppQ(jE#TodG5;jl1Rcw zGM6uiMGY@Gf3&JOyym#pEy`rdXVZHN!0Fi26`M{RV<1& znCHh^qf|U02^U}>Rn!(6BoBUuBy$^GC4YU>-k$B{_Pw84$?n)>&ejI z#!5y^C8eeN%gejU_or9qS0AmSFc}AopNF$7In}Xg^3jJ=H0|>B=gbtp9)6r|N~xqo zlnK>bzfmbvT=TtAmr}YPMR{gbWVJH>ReRsC$~=c7wboIV?99XI6XMG+WSbWaxx9FF z_8&3+ApO>pAbkeZjrZEJcvy15dMx?Qxw`8EV9HV`b5fDCw3N-QYeug5MU8 zo8)te>Gnlfu9YU;QG9OXb2-vkXzuec#`j{q%-{dMQPQo57sf7DPa|c#%zDFk_r5xP zVMfz$Ky+eS z4sXp)4-|yC0%K5ZdV-Oyt?Y#+g@uAd$Sh-b3uXk%x;t+fy-ls7=u-88qUSF?(mG0FsTa1`~8HKld z9?hKU(k+P@2lZ0Z!S)9u#5Cf5VY=6I6HJHYAE-eRazBhN$NADzOaJ85lEQgD%2O~PwVwH@VNXEV%NdG$C^g_a5$U4iYS=QY>Z}sZ$ zNB6Ysw%>f2s=-mn6*^X`%i3Z!Jlec{$L1|ts4QK#eFt5i)@}#g6^a=#2B$dp(0UZhO>wk|HAlk7l*5B!tyxN0D_uwNo?}*FU;tqQ-i*XB$?L2DF^ig` zUsJf^+-0}tlnU+|YHFELA|v|z(j`=q&NJaKr=qo?Y&^V?%hX^MRsDwYEc_WD>+EK4w|FI(i=Zuaf0gRyuPrY}zVJ-empXEy(`)%3-^Ia?da zga}kOcTUHMJ=iGtqF~}tGqou(*xQFCLw0SJ2@a(Reb7ogsnCz&donH zm7bdlPzk9fbv)laqyo`z@vf-!{OSPivRs^=Og1z*FP_0364Sl?rKZEZMb$@(Xnfw= zyDOKZmsf6q=|B49eW36}XF_^g`_UrsB!6Il*uA8(y1JC4GaJsNj2$UElC)_IK2NGk z;a}Zo=<(wlHV|)9cOEHgVH{a@@SgrIlF=eiH+&AIqoredIauyT_&Kv?G1t0PFH(B}_hgY7J2G~rbZaT0 zFYJa>{UAY&om;m)edgh>-bqWdF}y1mG}uZ)5G%KZYo_@TR~ z2lBgL7#}GobiAY713d7D5ZIsW?(fc+5aWxNmoFLhM7;p%>FI5_+BtJl*5!xIJRxb* zt%)ZY9lrYU+jn25ZEM&Ox`a+`-ZU7OMHEqie|hCW3Ix2AZK?NIaXDM5#f9*5>EPw8 zZBeEvDWPisbrki}FV<}h4(5~K6vKW|`u=MA$mSodN=NXgX%>O%#GH0aZoYqY*w@$3 zpR-idWn)_p;H-)#CbFm~_sS|tBr3f;aY}h|DkjP^GAgWs0b5oDf7y5Cx|caxHhD)i z=Y_brJImZxk+sz3OxGZUCv5*+5(s{J`YqVe-oeis3*t+X30ThxxiVDajjwtt88>y5r@4Y zb;IN4iWS!3jLFU%*}@2xbecaD8*yW>#T;$WJN_Kh2(pF{eE)y1mO(HrB7 zza-PkPI{(h_Y7rBktd!Ft@qO_su)vx{c4}SzT&CE!efhq7)mgt*jOLG;#9X!_?k3m z^YZ0WGDXbeCDcRdJsUUP1k^E<4;^UU(}&_4UKm}Iy$!vZ*x#B6{7HN*`juAyfHx6$ zI^&aKz4npIM8IHECx8VQpCYo62jT?7gOQJFXs_3g@rD0{WLqa*oe2{=`k&OM58?n2v?y@$o-_xh)##5_h zdTF_9E22p7@~JElrsE0+YXzf9QSVzLF?}5ojoY{HSeLySI0oXkp{1|eycPrd7P8E@ zlMX}w(zRr-V}zj=ZEF z3P_RAtpsuvlA@i%*s``TsgQHsy5jKpsObuJ7c;Yvwe>5)>-%a`{5^Y@uW}4jpk?N+ zqA&dN*c9iX^+7?;p^Yzzu19lMIt*$(kA(Y0&UdveQkzuzkD{l`E03nHrvB4!ROTn`d_up(@#uKM? zH28a_FckfK#za16PS6ui{IRXBKchdZv)9c$mstm!otr+#|7*C~KRao2*Ya7W7fkYj zpWXO(wM0#gxWvY0#&&ixZ>Crg($l?9=MvW~LA^CE&ykwvAD29y5EnO?P>~x_RppLI zR}oU>%#Vw!h-zg+&sNV0x2UMrgk<-GRx-XlBeA4o6M@gMBZ$=rm7stWtuojx%AX`| zGV+w0ew0AQ5cdSP+{J*p_kf_iAm5wqy#Z3-$({Byo>5fHA$8(EVGj)0ZTTf3VY_y5 z_6Ni74_^J&x2Pb!tu~yI1=VeBA-QqE$yMVayK?9^*+K`+uChFEIwj>{W7)*RBV)Z| z8;(yLIg(TtnksdDBEeZ#wqY#TKW{v%VtHfj?&k40JTE_Z^UXI;cAWs4%1>0E;ILHz zm6eSfk}Kjct-tw$CkJuWpFe-JEu9k2EFSvAi4!l31#b<`jIFJ0S@&m`F1-c%kB;L9 z>WI5NIDYS@lypjCZlb5(yF-(qhbf`sd9nN6eedIszrXYP^_tyfDdm+_10h-J+Uk#u z-$SHWl_Kp_lj3IRu@sU(UskLQp|Nhh3`FwsBl8Cu?$s-l@tOQYdK)!Jz>Qt7JoomU zoBzZ^Rpc%%-Ho05qoMOhOIBvC3NCLu&~*YNT%dx{l{v!0^XGqho}Q{%t&B4!Cm&7y z+2!v5=tf8XWa`l{0q+LTUBmh1%X2~#Qc~`|O)SDY@6hAaOuu;T#Os*TzxDCQfBDWm z%k^@;{ime1$@(nt!0Cdc3RW-RE6Ir- zuc(qJ?P;vX> z{SQA}w`Tw!Q6w#L{mN7PsRm}(YQCz~a#D%Z87?81m+)Sfh9-^HIR-l>Upx(`e@h|i zuk`lz#%7lCWouK3K|#63Z0W@QG~@%@fOgKR;j1sNo9ysk#d#EQIzl+(IeL*&W$oo( z$)Gl$o<-PR2nGrvXg@2eB1=W^Bqyty0p*K;63IvcTB-x&Ylkx{KF!-==g5IbCja)Nl*d#p|X6k|AY-(Jqu0 zOUpIxlG&wz^G~4d;%y7IL2whJ&Xv|0_|{h3(S1N(;=6fhBy?LhXPpkl#s1L~Fv7aV z0!+M&@6Q-sR7opN7oMB2bc5)>Ev7&I&YF9M-0lAc#5lrfivR&+E ze_^o2=p4od|5+<^2n*jWjJF^3^N(!y6DHd%ZEs~cVz%KnVL2-?yJ(FC>zYwMim_D4 z>_RUhT8x@lbL4A$%+uSM!##dzv&g=3VY_|n+Rcm#l(ooadVKTjl)flYozN2^WsFl@ z!n)k*!gihpPIbK;!e6kf>k%-($o*nWFlh$XS-5SR@xM^KsUAp7_|^lz95sFMQ#+3x zOWQrvgXu+>p1tNKg`(MMF_%}L+Cwh*3V0l|3pKA~GJ@%gR>!O%kT5>{6wFpQZ{AbO z{%&Lc;h~-j$must%Fa;jnixBsV*JSKQ%qlT>S(7hd6hx|K`w7dT#cAM8e|(7UF6b*>@wAp9-Rkv|D=m zsZ%30#dujp3bRMjE+1QX3=2CfPCq23`V7atJ)8=_5wr8Ff%oV;dYyUoH}a|9omR;1 z$M}zMV@AdS`*#Ji349(OgeyCc!b-&>3W2F1-6AzT8#Nsz9g{l1PPz-WkF`5C_Yqaj zdNn-)-0`au7DF8;YBdbIB$_?wYFbQFAXRWuKdMm1aCIe$4}yv@tl%|KAEBlAq2Ooi zGQhJ*OqplA-O5p40ZBu~3=OvJ*cKzN$=YpeSNP0dN`E5817xlg2a@#yIv2-mO7(Zk z?agu2OgT6oJI5_koJe{mf!TOk zcp9w753fN4BbOlTFF^}e1g+SycG*&Nec7Kd<`esZp&r~{$T2a$sEibg4A>5w<4w|9 zMYYfUT|wz*j@!pyKpWHZnEjfswMEXNCl<~0I-0Zi8P?4=qqD_1sx|fh%z?CE*1_h? zVY6s^EBrKTor-aMd{WYj{n&GG#=A}-thQ#4e~tkE`2PPU_W*P8ITd~7T`60U(Gk*N zA=LD-r?;YhdsZMBM>ih!AM7`6g zl>|dL0w_ZB&Ex>D1VS3+O$XBl^0Pw17+LaljeX(dx4!wUPw>1n$m~+x=5VC=H#Vm7 z6r)z|@~niID$8m&C6&>hGSz=W8FA`IQZ`IX9HF2zfn@ch<8>*=amGxf_zol|X1aB? z^fV8G>HCD~w^C0KtVg&W=JcvIWr=JU%o=@{HGjQCQ&jWu1dCOq}X^Q9|G z4*v9RfBdCS?kk@%VVGQ$;mJM{4B_;t2U9guaQaO!{o(O4w~E%_eeb^X-p`)expOCS zK&=xCMk}%|VICfFo-#`N(!tf;!xt|yL4RI6i-JgB(v0?+d&etO~rnEr|x`sqq|p3>zss<`29U1pNd3v%lrbY1Gfc~ zO7MR2gVpq>T+#o(h*H=dRdvXJT`~mm5I6y@18~n zfBU`HOG^fCPu~CVdv70N zUUT#CreQf}2xt7;S3f*?YhUl!R=@Hp&J^)0QQ&`&Hz~zEv9&0_C^;l<6}CjGRPR53 zBq5gH9%s2E{^az01(h00n9^Rb!QiWB3Tq9^3h{2BORXq9sw%m)s`-#ZMzc6i-(Yw0 zlYE1DnjC_21^*_Pj!G;}7pWUapW*b!T9Vox7|7OI1+kf*d zRF+f87QI928@FYvRP-iU{t&g~MCBS6JscyJlw2p&=no_DsNq|9D zPdj^fFCp)?=8iHP4JsZ}x6<(FFG)?Wd8#nHX7|vZh>_JkX^xDky?e9y-zK7_aCQBf zY+M`R^>{V5aS4o%zPzk^^|8J*gkmuLR8WxWVWT%*$i8+>ov8^*$Mn*3z>z_!I{R(e zO``e6^@aFiP^}4%>0=bb0E%yetSvQDf^E#{@#Lr*YNscu;q{FpjB;p%M1#_gs3g64 z4wrh*xwQV9vbAe5{Y-0c;9TyuV4OZjbGy42UM>t;SQy>SnSc@b(2d81uBC<1_5FM= zdXzYMs(bZUN1D@k&oz%_oz5YB%y-XSv}kqo-aXT%7o=`X9e6(oI#fj^sxoT#vcT<| z`?mCv_p(EIjoH{>)@|pFp=aq1{;i|P6jRJPJTB`t7ZY6`6GK9IJV}mJby88f4wF0F z4uYE+P?jJ_BaS1at92+0jD9`W2MUI2VO>!zrI;$=gr>n=S>X9J0AqTf#_WjETwvh# z__>Rga*ehgLlPuqrI&Hl?AVj%AIll+&^3kKBQJL5#6GiqB4>H-98?&`-f&)!(h+%8 z9CjW+ja;sg$P)OPF$u&@GkxXjt7#}3_)M_9hc-{L=NDn6v1gaDc!y)}*Ia&>ndAR1 z=0GMIufyq`U1jK$TerePu+$h0+_#RUI+Hz1qA+bZ98hj$oTfpH>IsmyRNW8>c)&TD zI4%_~-tL%u$5ZpMgP6%HxvG**MNV?%qNGkrtMsIOI-EgaCTZi^_2~J;qU0(@i*zB) z^&Y5hC@7){V}XAGYN6yp`mcn9dAe6Q!4P3OV1GXUXkAgozzWJ?heTzOj zS@^>Tsyt|}PTeSx>2WzZo?gy@D)+F8un_kuM^f{q=A@KHJl%B@n>N+eCFO-WjwjVk z)Ri5o8=E+k;#-xUwbHYUO2xt4UV6H}`sPbN>}aL0BswMY+&X&k&5ytR z(uVQ&_5)qIq|gl%X0P7Azo_Uu6HbrU&Tae7rB5z)-2VCP=P$iXQ1<1i8;@?>ctD_4 z#LauyUhX-DYL7qkU7i~{_TGCZfBCcPoWtv0-x3hQpvOJgSBZOJVZKz7MtUU^Z=*O8 z)!U{IR3(Oax&>Pq*}i!b^dfZzgwYeJIUA{?dwUs!l`J{aV`FnGXK zTq8RDC++PgN}xp>(YYzfv}k<+=LH7tJ##~hPO<3aOV=-b0;As{Srb6l#JP@@E7=uP zch(+%X0HexCH?KU-+B9;U-Vx)%>BEsojCFIyU^=@{P@2-GQN1;4T?w)GW@eZ`{`G< z(znP~)6eMJCjN%ZXTiCa&C=7SH_KKw{Xi3JmLesdU33zw7R{mt(s0(^z~eti$M zB!?umI4ExR&2+=0CObRdtVnl$!$j)V2RuiArI;){{1ha9>aMlrW7nclO~5Ijt_*c4 z%8!RL0^{<9faR`9BD$@p8y}32-R5;0(S_$mt~N1^pfO^)A!cA(Ag+J9SSq(*TC-Lb zx-p(h1y}8;Ae{{jliNEQk~d4tAr0ZPt8uWK2Q^_Z_Q7>vz#Q#d*XH3Ywck?zdDeQl zylA}z=E^wJEmOLNF^|1nzxK|*^iJC!l)+9K8`(q-5L--awGp+X@>!HDEPZU!c80bE z>RQ9ig&9SjMY>}h-9mM3WR5%Quv+$+Y4&>6jLza^soJ14OYAvzwsm#;FeuYCBr!H0 z=t)y@B5Jnnb+OGcvtP#Sd1HUkLG6XEb+d2vCTIheF{8Ww|3jh^qeO*oKEvEBb$y;w7GWgIxHU1_^Po%_{@8* zem!H4!zAA7oJP;kmG-s+d;8YbUk;CXrf+R{Vf>!mhc_PUHhz?2g_6=~HL5Gn98r7( z;|l^gfiKE?!3zVh3)+8 zQ!~2kGU4wvoB&t|rkfKL(LBM79zLh3dfe*W-CyZ$?im5oHQ(L62uvpfrhDF^)qfa$ zcu$Z0J`2eaycK5-QyUuxs6KCL5Z)3*^mQ@l;>4)St}Zx--gm&roA+*xS=YCPxb;3@ zJ$eQGk6`#6MqrN*r{a|J5g@tBJ3(^lO$kTgu!O=;Lu$O}I9n8c2-2DuLsRAnONCkI{R1dv4d^bUtv4eMf^W&`nt8d zQ;!{P-0+KEWcI5jvT=@yX6Nn~blxmBb_`J8S{mD#(gmzz4&G{HPuOT|EFfK;6YqQ~ zF{v{irC^k*K_VGj-Q1$Q39%!SWI(QIKpnpEwa^@)9agYl#|Y^P(onvl7oCeVdHIUc z@w~v?=Wsk(k~jtX%uNqKqW$=6JBkVl&ZDdEFK6tT_=1<&v?I*9j_S)Tbmo9zs-B14d&c(?~OrKo( z1T}r?=KJ?1n+LGJ5c$$lJ8?X9SFYO&w|;r@y^}RNukYMh*w@B@$31~J)H~TLiaf^1 zC|@t+bPZ@21`+a-UY!`}<_4#`LF&HF=HtgPVqoxTJ=!y}x_eQ5Ptoo6qLs+wQq#$L zp%LkgJGUz;N{6n|i1a5vm5iQgh|#F%vSTb*iGOME&hSn8-J9ga>uO;nJ32v|`ePtF z`W!xPY@{clNS{{EkB zexK;{d$&>PPaNbs^@?a)lSxDG?D7ZJU2JY4x@kT78D5`-@D|RGbuv^aB~bnKD|;~c z-?*_SFQu*eXq)(4l@J7&1fNbJt?S!#MZa(W14uCiuiaxOa0Llk3PZLRtK z8Z8}rx}Wt0W&7n9|>guD(Bbg;w z%1ao}@#qD9JQS{PVvLT8(ygBbrPPKp+&g+cc7b1|=Xla+&M0x{-#dL;p#HOy504~x zQ;f`al`_;6Qrd}@Np<dq-6)=W`$%^Xl=?(a}|*{;FWePYf&Zq}apHwIp)386C8VJ{8SDr^&vt?r?2j**H!tZWctFi_y5@ z?`fBcwZ`Q=r;gNOdbSp=+j6^|++r=UAs*X{>Q1>Z<9a9#FG|-W5gkvvL3Uyob{sx|WN|wGk-)d6Ru?d!+E0Ewoyc>@umlh}mUzG0RjBthg$tkZITpP>8$`dB zfslUqY|oVgC-#>f*qv5$xp3{8Jv*XFI4P{zyL->s&3M%pcKfXE?xqTqP?(IHq`s&z zsip{8kaEH1q8s2{hJ9Qw4`@s(NPn=t|J+#+-LU%2vto4wd8{!TLDCU57+rd5?x{bS z_b1)+=62707MUG6T_-6Ze^S)1^$ZaeLre^|_3l$&S)DPYNEr4(h4%^HLz_QSLb_=E z;j=NeHytDmfx^ zqBBXsj#+BP!zqqpe3XTp~FVZ9QK~q3x^%t|HKOwu0qa~ZjSpM`r9;{)R%lET9~k5_mxqP= z@y;_+;5jf_P*Ti7;$WzWr8<^@2o5JbJ-r$|UwPRT`mQ~hl@~?<>Qe3JEwqX?XCv_M zWWIT>^~dq6^OCHO)S*;H{Y_o#Yk$VB$92rIqc8oMEibxOn%l|YPE~yEgzG&MRQ;;XI4NWLc(_mg_667!CW4D@$@(GrcZ+DSy?3>l_^KY=vDN>kqv0-Np)r9y$lRy zWnqcAO*LKXIQR4N${f6=Dj44Ba5x)%9m-cP^Y;zG)LmZNGSuF>OPK!Zn?F<{e8M2y zOr>iG`Gph}dWRgj^(IM;PbO5Sr|hpLK5X8lm_6?3#AE2!r9q!-0dg({d`6vJR zlea*0L+Z5cyg81cy|o=qe{|2$Tsu(~x+}Nw)=4;hOW{sH{lTGeuS#DHe1Iq1L{T0B zcAZjSfPyt0P_K56RL!6$-7UB=spa^l+N4^?Kw?94TH)%Q-8J`k8!E^a!JE$ei97uU zEsk#QD!IZRx&EJ=D8+!mbbf){D+V7y$lSr=nvY`a+m4t_kQ-XzxeytPIM++rH1tTAFrJhr(?mv z2ETRdE8=wP%f;7>lQ%kXW8HV%m~Wo0?8VdfrxyV7+L>Vn#iZ1w*6zma-+yyARRiN{ zK!xFj308-{3#zfD2axa5RfRd-RF;~nbiRiLAT)U{n%ELYQCQr7!=aX1OkR{gkfH*o zvyPTX)Ip;-?|#$xGh+HhygeWP?Cp2YoY}M`W@_sB;f~(8(vlJabI1#g zWKhQgg@h!k$*u`y)H#dN(t>h`pHnVHWHgp~1|&I#haX*?x_|ZL>5l>RpIyE6kZ&8D zj*ZNHzf3PGs2~*5BNB&KZf+BuPM;_3lez#3s@**zBPkt8t;EC_r>~?^qK455+N-ZHEOyV zle&76sv{|MZrm;|P}i-QEG->y7qL&f)h+YOv_svH@vJLTLu#1W=5tFLH`jo)m|es! z$Yx$X7yH7EVQ;OnA>DGXgW_g;YxN&YZ)Fx*P;U;)3bDCBUBGTbyMc5-9Y|+*GQ;Vn zYE;&AdzzkcE%?{p+8>nBwP$2*2+|^IIm<1j+(vGjrCDsI$M4R9^T$>o(_5Q!1D(!V zH)E|4y3Y{0eI&C?yShx`%o@rT<64seb7rl@7J?&e8wfV{a%}T@NTtCj3?>_`R+Dk48>>2{lzaA^B}$y(3OkF%RTmj? zfvCoQeC;@2ETm|oH%keK&6sK$MiwmogCcw}|Zo<3s2 zRrUDt+Lw2{92f|uchB9nXLCfnXpNrmOS_+1vhhM%Ht9D~(|dZZv>#|YalWnXaNtN_ z-!py1LD4ZW(NF#5;o8014|OHvQSsjs<> ze}^~S6fk{c^mpbn&h?z@xq0p!sWOzDGQ7D=F{{c+PyNZMe^~kt_$>YeBrQ}J3|&S? zYO=9ap6v(IDKAyy(aYFec1{gN7|RQh>fMV9_ddc5gPOi`(YC!k+4k=WWJ-fi^$7yj z`B9!C9LlR+dWz(hVtg#rc;a)}j0J{3b(nekju;Ftee3u^XWx#fF0s82hYYB`xi6d0 z!tHQB#u>nW8P*U=H?fEyQZrG7irqX~$uHQvrMaU(FC*G~;Zoe{ro|~6QX+t*C9rrK zIWonxPvQyUfr(er%e-iw5CZ^Q?w1K}T)X+WvoRQNZ%XT~ilLF~*Z<~v_fs*+yK+Mt zL8j$#gL%!H|Lm!Mkh5kP88aB*=hKdeiqLQiu^B{Qb0O;;x|Ss!0bOdp%<}kh^iI&m zR3n(cZ6r)$4J(?-0u+}3%Y|2o|_s&2Rne);iTcZI!9wLoly)8 zac%iqh1E#FG~@|L_79tdtCNa!?l~qFef|`(C`VkeRMMV{v zjZXR$J$Xbei!?P2CnZff2F9_&90gx1vW|{7B$l*Rf$4zyzyNi14rf$Tvx3yAgI&36 zaY{=|^U zI&t2)(|l+0&ii*z%F`au`R)FtPk!{tk92kE(l-U_pJd;ddNe*5;@*Iqo`#$brcaE| ziA#8R^7Jo%@M1h_I&m)!%s{>&_=f`WQPVk@fiDOvgGikYq-4sYsCxqG7?OiM-Ta&r zEr-+?rIYmyrvvH>O7k(K z-{%RE>Vl4b*)aO;+ZC%wbP=c9S8j$eGyC0?9NIN%lfRj4;Li7O%=nNal8#mt>N=c=rmlFab*Gm8c zKE6g?e5(rFF~Bg##Ue%FE?R0zH zzn`#r4`*{y($%STS8u)h!;>eKqWzGGwiBTGvn^RpN#4O*_3 zQCgAu0_kCq1&rbNb@Qj%gW()s(qt+_!qCzarKe|QMR_IYrTHe;ZgN!eE4FxXuBWd| zFLXjuY$GA-QT!s>e@Z@!jlV6SyY@65Y-4<}^mIAY|JVj~TT?f9?((bKc>LiH>_cg-SX1KQR<8>R7;i`*^Gi`GHX+#sO4nB3Y>inYl` zUFo@RgVkO3bgP(^Xh@;!VcxCvAU!*qu>@4FX!65{(+-pWf>B+PdNIbAFG)?mu=zq^ zJ)W0{`qhOQ&DnjA&i3_jV&W98Z9yiwEe(5KmS!4%IjH+o_L}U#=ScK`Sm(_iTb zD=@xv1L`m&U5|k8QzP}!mud9czxQl5gP{JQeoQwcyPTqO)MsbSP(NT!(J5vZUNf=8 zc+-7W?~Kl9Nwbj(CRL+Nvd0x;g0Vzr59C#mYy6aaE27qLa2#13|BE1fM+}kbMmR@L zx2!RU>T6KcxyRa=7(i|rC8N@f4~eT!Y;4E0zRF9>@5PTut%{E^r7J z*o{_*qfi-4XM`Z>o}m&Py+Rs#aX6SBPo|8OrVgcV?>p{10;T7)Y~SlR@X__Z`RBj+ zo9jC_wuePMzj>m!7mIqUw_|VMQ$(@A;DnqnGCe|t>AX%x4_I)*8Jb8EN6e?w55qa<+q<~<*=&e zVdwCsgiylM!F2i>H4dkSx)HftfPnxY@-FZogbo|8A8h31Mb#+$O$&0>KDrYtNUR3w zFI;KzPVi2Mit_`wrHs4hC*l(ss7`lx%gt4~b4VCOg3Cpw1Jq38OrQykP@M-b`zYz9 zsG7h=+Llt*xcuo`Z>og!;_Zr}tP0OYuvv{oO>a>`(Homm8^?!-H%&T*^TrXqlgE=o zAQt&-HR9Ry#KzK^yZI0_%YK1EN{%lG2b>d$3j0fYt9~7D=hGA4EJUzrK zojTfdRRJKT)8B{^QoP0LU*lF;cKp!9p+haT0N1wdYF&MXed9K1qKtp4CAy41Yvga<8 z{?0G1z4H-QXYa!3T_(F*5q94-?;=>8l@T5jsz=rm(mAXnIjdktFuS^F=4BN=rTbE9>ZrbpO#0ZteTw zNz6j3Bz^M9jw7j!l`6@=pF-+pWJw}cnnZj@ag&dBT%8>4h11=9v8+(5K#yAg%1S>@ zRH;&=A(`?DzTP1X`jRL5(xf0csSL}SGig(vXAYRYd{r3z!rY?#^!=f0DWD$gk|12L z{Xcyx9x07*naROr)Mxkd11SMA0j&9!z#G3UN1IOUcln#=}V$(?RZ zuIK+pzyEbZ>7UWk4We6b=Whw>_Iv+pc-{U>?ozU6F}B6tpF;9!a2Bb4im%P0=_{mR zv)-uk92Q&ntb?KC_W{qV-d3+Q59>=wI zHixxd@$5%nGabxq<9ZbCK5mKOo(2e9gy&**W2-Uq>?HF!{ujB^RZxok#U#%d0}O}P z<_P{eDxBYc_;8wWzVuUHN>T3mnlH$)`sx4IpF5mUQ%?^eN=UocBu%CDk(u5Xv$oKu zcum^oEj!ljKua$!R@c$^pzftLTl%)q4o5BJDLy>r6CFcYEEA^m7Sxya1GQJ^CU<}` z+M#Agb|H?JJ%_jS(GTe|HKfHO*&{nQg6d?cN05m_2o7HX&LpUClmp6v7h&lZf>Gg|7GI|(1oSHXp=T5xoXYF@KVJx7r?AL)9JJ7Ca z-YIMkQs@gt6$UE22Wah-iJH(Cj4*`2^r`!inYM4=&LU=G2x?SGDXKaJo-5+F??6jm zh@nJfoIw<&(o$$Hu5*S1LGzXb%6g8Ugj&soDq@udT+N7hYzUt5!dirM-BnR4BMCJ0 z=)iDFNTbybbseLr`peNTZ$9Kq^^0Ae>%V#7bAR^$O8;j#{co7!DT*5;-0EL`uh=t`?=7p&+dzxRSuhS`_t`GB};Imz^{@aum_t zD3e4+3>brhlG8uHxL-8HiQE1R2X2_HxL%<2m7%wrOs)%t^ix!gqN6{$(?qOG?&9TA z+090oxvNG;2ZuN9xqJ35W*#`b{}&go-Nm_h@O&w>pNV#ydGKI)C*_^LdheaT_=}&t zN516$N)hRYlOOzdMW_3FJCBTwxhfuBmzG{$4y%LOub+9{eA%pTocY?>-@a*lHw&%x zq^Cc9MyGtrx3aGZeK|AK(|?mQp>3(oJQFyN1u5N&QDZtr7z%!&^nida>PP8*LgiWMe&f~Cw=O=3ZL5(Q2-NVXsL-&I^F`+ej<)LD zM$?+9t8bC=**i-1DXmipdttyq2P}7wFiJ(L8j>4Y5z+Gp#`ERya`&ioPuWE2baS46 zihr>Gf)$zDsID6q zwHs2`m4)m^nYQHVnXDIMesOWJxm62N1I;#AyXJK(_SRx!OA%}vshp}%Ez?3SQqwhK z!MLGy?P7K`w=A-DG|4VHtTxwD3^DAj#76T>7*=TFJV*xt%g+3l6)F=rmz zS_oY6uvzC2op|IR+ zY0kp^Z^bFmkpHcUoye)le@VfM6PaO;FTho`l`Q>#nK)M(`p01SV&4BZpB!x-!%s7*1#V zn`%$0GiSXGRp9 zj`H5^Q+SwyQo#P%)r;ykXJ^}Ls=O%l3>Bus#B>{t$E!}QBx7kD7ysHH3UFhm*Zqf zAO;$S2h?Q-N_a=F4vb#9l$dpv0sg>0l#Xi7M}l3PsF*;W-ZI)7VVQ}Kp<)$UzP#6xC*42neQKl$&5)1P~;JN}tiLVRgUn&n?syEz{2_LeHxjO^`>4;- zg(k1&|8bbU>JL9%4mx-3>#=#1Oau@zulGToREO^Hz6d!o!ZD% zE9q85&vuLfMF@+DMIlkE7B8Q(IId~{M>efm0{s2pba}B=ObR6HfnX{y-3uK&vAQii zBr0<`oSvKW3PCU5BsP7Jj*AKC=lewIKj&YEi`KPZ-;?_`?5o>AWvN&_p*5eF$BGJ% zWaQV7tTM!O$I{`X}Fn(TM=LFIc~H|Ix+UkEXUXwT4tWyV|Z~ z+`QRyueo_sQd3Sv!iE=Leed1(eztDU_3JxFc2_0P;TCgd#G`ueZ_{=L8WZ~yI=YH;+we*DI*_dob29yq@> z*nh*Bu~){-$(q-nrdtt}n4MeCaDSg%FV=U?eDTbc1?9TtpY_8wY-sLnWl#z8zhdO{ zGhIXIGdFu`y-CFJ_KI`|#K|Cn(yP*;YwRwVR;rNGP0|Y|CCvJChJ2FC`A6-8S3sGg z&D}GK` zfB3Eh^*3HU`7U4KBaOaMt*u#cT<9vxnV+IuQZYyAb$XR^TD_xjp-~>nY0)nk?(#}u zI%0Z$E8Te$^OeL{l2zoN>a46RbEM==)Kan?9K4DKV#^n!&?BdNxOw`q2uu$R{xqil z79{>_Nm6X8iC{)yx@A#EQh(N)u^+#6t?RkmgdTOmM}W^tQu0SF|&FO7OLa1aXkU)>vG-5 z?_=yQyFv6lN`cuU&$?-odKmYM*xnji$dP`*7}W`hB z;xo^z>7x;8;F7+Uw7$(T#V@1oLSahbD_q)rDs68zAc&l78shi_#blq&$nNhUB;d+{ z11GS(92jCcpqZ-L11+S;94pLr?47DFUQrkxv@yGW8@Vs@pW3-Gg4UolY3c}teZK~S zi;>ik(5GZMCrTav3q_{=JsR*4 zjc|1_CVy?m8ojAV>cpZWrek!GS}q&>vSnz|;enP`u7^UQW^@o<9KX;cnun9$NC+fs z445-w;D+a-de$8a=g(h)^<@QN?co09_$_5Ajj_wsQKq5?Tl(Mp^M5~j{vLAr-(0`m z9Z{YmOoxFyE6d8(1ma|oY7SCUsVY+o9+f4yT+}*r?)-VmVU*EDlOkty0sxI&Z%T|P zoyd3%DdNM6@!~Kbp^S7zxb$~SJK#D!T$j;aHHcYd%5eVR3-qS{?h%=a(8sZS&F?vX z_mBG9K0r#>~r!ueB-fcwK5LN;+zKU20xkYN*WV z0Q7$0Gq*~_poe+6KRfu#mrgERlpnRF0Hxw5l6^^r!B9YC3w?^hR(Z+=Y`Pn%ooHf6 z$tw6^aTw?9qawpR{8Iwth#_PKLYJL}3;o^8{So24F!v^+rbl_M!kMvaLG056y?pbN zw}z<`^=)iCA{kwfEHzwa`EoSyxL%S%b6XSMJ^j)zPrkio05!Zjtt=UTkT(^AD)m#Z8hk^Zo-D%ygcggS&YKIo zvoOj}4dRdR32mw!4@qbkA5xQ}%Y8#+GM2{TT8SJR?YLvP(+#GRY>wX~Ha0kQ`1wau zmrfCnPDc7CFnZeAb9Z~Lw3$XaRHiJa8SV1k;IXoKO<5xdMO#hD`uek@NzkhUaFm!9#!@8$qLk)yu zcS+H=t#j*E!`-?TjN8-9oNEcUES$l4HzrC}Wf;TRP76E*dA1 z$q1!a#x960V{A3taq;vUuYP>`^p15OzWnH7hp*iJrRV8V8^HGz=XoMoE-vky<^kyi zB`a~l6di@ralClDCnTS5IC^6Ld0EZIx^BJLhac+xnu|Zbby6bztEW$1eDZ~kjs%*C zG0{qtpdt)i6?1xfCnz|b+#uHrqgk)ybR0f%)GG@qjL~ipQaWyz)@0FomN&k1M-pM_ z&LsZYr}(*L=HyUVoI}_PeG58+p>(Fus8IW_#pCGx7&lsX9$WPI){os2rh};_LLF3R zvQQS;S<3UX@U5A%Irp&}h~4}cI+v3EN5b=Gt%c7{OY2axC5A)S){h}}sp4XCqo(Uo zU~))Ztj>ym?*ewStzmZ-YjbX_{S23z1qS!EjxDTz++pHjHSr=eu&{)58GQbj*DFfr zrT@NOz3ANf`L)*c&woEZf2nzc?GMU=PZymVqBd8;PQ#}zI5i9Gr8c=5LY+mm)2wZ6 z`>DGe_Ckyya^~!HGjsOgSw4HW+4D0`fVtV4`mATb8kiS42fKynn$v>WlfA2z8#BGH zbyqKW)}gi5+CuWVYqB3fhc|D8?ps@$1w5d^ZWqcMeO>$7_7|6=4y_ye%UMKo-Uo^B zlGM4r5OKl$aMW#I4yMnEjwY~Bn2zaXi=z+S<FVy(>?3_PBPGw&P9ZGQneWdQ9#>Ij@KC%MS3!O)aWaKY3PIQV! zX^iwhF_#}jklw;6UeaQ&DWg&5mj}l1zwI*47uegtIw_5yxG;SrBMowwl&(dmc6RqQ zM;t?ZXKO_Ev?013UG84AdeQp5JucG=?sKbX6g3-%30+2m0Aa(<>OLAxl6W+Qpwvea z{-Q|qn6;q!x^;-<82UG_>$BYH0`|Uj#ir(z5XBwa;B;Kzcf0YDl#SJyEx_8!3=6Yv(PRyR5i49Fq)j>c#Qd zNvVy#%U9)ugXJl}rP2PmKo+numwFxDIv`n9c~;Qu8YeVt;_RmG*zC2L&L9L-sLoFw-j)X zU_TNwXdH@|?g0RMgjj|R<$jC2eW^1|j*82S^6>X|2W4pHaz3jla#ckxYI+4}&WOjJ zekslr*|EV8qkNKd4Np-*S_!8Yq1NVRY$T)gS|`>($FSAX@RZ@&309{0^RzsUtfl@iiBw~taws$$X` z#_MvQy26gzO&v`eMuGjoj=?oAZ*f%RRduDDDZg^_X2w0oJ)T7>S@cb7-u~r#zr3}7 zi1hT4-FeCCLxXQvMSgz36ry@qlov>*Qh>yQ{D5RQJ<45$fZEcxGLLfDWPmw;e9y?U zq`jowBa?BZd@G)@qvNRQH$J#i)ZTxg{};cwd$6>#j$D_iOLQ4M1*Cr>ugj!^oW)<9 zBlrA#34U~q(tCS5j!ZniW{YvU-2MBrcUjBdZ{pXlZM;UR%aQdFD*44PJesS6pPRW5Fv&5(^w--sWqLDXcUd`+qHTVi_)Fk)x*EE?I-ImOl8WvPr6*uc=d2I~r_ORxV#>?g+Pst7@{+w*#U89} zX_lBy0qLu!-(I`+WfE})^GZpbKYzYj;V!u1v8SV*mqc`3=FETq-xC_A*r;p;5Rs|?2V;<;)i z!pvgQUi?wn11kOaUGwt|c60r8dJMJy|G6VdHIwCgF`Vx5s6**STDKwBxLwSZ3)XeV zsOhk<=1gGYp91QJ-=(OVh(-&Rfo5^GP}_oSA-i?&5B^+7)MCr)Vyvzc$_<$%mM8U%w|@IJ5P9}v}`t*fmah zHnq3n#ypwnhc?SGd%GUz@u%WiI=#1i;!K9mwUFZ&N!|5Y*nN7R$AcMd4%Y)4QlEK9 z?Eye*KOLI8hW^cBJ%*9axyQwYp{5^N)3+rirZ0Y;PYgEn;_Xv0J8HIVuZb=UkKVX( z`|eHIxTA~JwFYNHw@=XFy}Znf11EZhUK_eH1f&mToV|PC%7He-^`YIhusXe`nzx6K zU^id8F(`ZYmWa)cjAP;P_1*L7c~po%gi+m$ULroi3sf_rcaIcx4CgdCg4916fy4Xn zVR?B_v;G1O_K5Wl(9~szVZsQSK~?G5bNtVU%P0_yyqlbtr6SAjg{S8F&|kDZBLW}? z(61L>zTQo%ktu3OQQo!8=U7@Zm=4CT{@TVpwYB!|3Zk*eEFld%zFxdcGB}hh_Ydaq zwSf!g1{stNUxJ$hvk3K^v;hUH!DehPF*^t`m!^)!zSrb2%BHRmMUKQZMw#vLv?m4A zv3!T)7=iCiXCf%OSlgK{NX6UK9SNs8C7J}UC<~Iu#t6<6BJ2fqo`+%UrSq4rz>lN! zNTmK9&*U|RB1Ss;cDFW+fawp~OBSr+f0BPRg8G9Y3E`6PU$FBtTMqYpzQ#Wz^)mS!ZOicqg6Kyl zPyh1td+(kpi@3h}`c$)bYJ!B$P9t{en&A=#|A71gqC+sg$h*%;3f^B2`5k;4oq2i5 zQPc~Lx90VAuYUG=ea3*PA|<*oHf|i(%Z(fN?%d11aP1erxHeRaj*c5$eMa%4zpUuR z;lYy9uGjva%WGHKt6M1`&3R$N@U0iOy#4msx9{Hl`@4UC?yex64D{U?XZ}AIt{mLI zKRtkkv6TkW;o)@`ZzW?!u_wI3m;m+;xCcmv+50BT4^@h^) zmO#Z$C|ymp;B@Yvfzrj`7MMfgW?o2cO$N`;yuQ!evL(B0wO2vu2lrp$k9^v-XSz`7 zQ#v#K_QUB%sc24bqk`1g)};zkNL}7^rb;z4@}e)R zN}<8@Dn5C3XiFX-=`d<#=fjpwhw3`^38p_h{XH5^KVLWARD}bGe0U5fN_q4q+PTrKKgAd|&bK7oesS#^Oy(3km;FI%6FSKu^aet{Ssse(W!?Qr(Yxx1J<`>-KuM_H0bU`P-;v#uiz+I@ z_*L*u4hzdmrt-HX&kXwf{S)AH>a_VSbK{RXzp?!0t4KBYU&i#$p~cUHeSaE4B_$h9 zhgnHyv^X6+7ouB2y4)|;WY4)m87;TBI33@M;M@r5n%5fs87A{k(8NH=(G zxLSDq?4SS9pG!^WVy^$dAUfB&Wr?-Wte0TUjLR=$alV0a9ZhRgnQCnzHC@li*3m`k z(>l7*)Af>FLb~3FX-$3h$met4)!7?-?))^SgRV9(&la+$c{p2nEry*z(&?oZ>{{1i zRh%rYE3-9J-haU|%xHzy+k*kixz2%HP8Z{HnLe_s#9h6PWcRTo5i? zo}QQmcgZNXm)N&LXV)TY3v?J#?2VrcMXsp&iCuiu@q zyJv3=YIB+7q&L+DyExRQnB79?X^f7WE zx8R5GUcCrVM-gWj)DNIXOsSSsE|!}056F6{!R7J*O}(anV-0FL_u06=p8OYuzMR9R z{*!Y(H?hF<{N#XRZ#2G_@XOe9mYxc_eCpKPW5;~DBQ^&XqL-@?lH~N&M7^Y8R6jLW zs(W|8)b#FCi{|gdXP<`5tVuzHs+B}p2BuND1Icw!y{3?T+YY=P%V1RbPGDRtA)qTF zGK#n1bcMgfP(Zp}JxQ6?;7g~H6jI-gO~lCL>P*Ub$M{9!Nr@?5+lLnhy&e@E3w%77 z9u&Toex@kY@$uWpL&qH>U7!7kpV_gE$F|KcYXg`1NZW^wX_!>J{l&agfBr9at}U$Z zpTd~_kL?vow_90~_1{%Vdi{Dv@N(ZZeU99m*u}xAl@5$Aq)#GvlVt;4&xfy()3K?` z?1FCv)|R!LNjSgIhZ70KJEE2SLIo|aAf7}<9-IX@?os8#*J@`Dqoc^1&O690OIY-O z@uU~))Bo+STmEqNU))7W_SfgPKfv#D%jLldmHzZ)q{-rbfw~KU4wiSd?Z@%t@8xXX zw8@d+U*_8zH%cHQ35UZ?d5sub-O)yY>se)Y{?zWb{yzk2OgT@ShNgG+fle|-4S z{Wo9ztC#-zhZpxfth@MgE*mynoWQl8S_k=8HDv9&eWz~8&4%u9#T^S$X2A4YvCgCRf0Nbb(0=A=AEJ?_a_gU#C&XnSKQt7PSV z=&^KbW~;K(>8Ervd;L58?_9VLc=eC=FDPqU+` zZsPeD-+p`D+k5xkrF8V}-7CMMqGdVa_wEd&_ygk)%ZU4?ix%IoPQGd7KX(5jS$o%;`Ps`c>Mce^OA=q&ZyU$CG4SS1D3 zB%PzBbHVju#WAMfULn|%cy$x+$(OP~Jnj`0^8aJ+U*MuT({yh*G%2Qmt<_2?B9Vg# zn<5B%m<==H3lyQYO5g>Ca2P-iC9eY(2Tu?nh`WJE_{hizlz^w{g4d{Wz7U?O6L z=B&eY-Ih{XQ(!9EICAR#C!gHs@Qjb1LoH;~ z;Chj|g%WaM0&-KLO+!Q8DDS=zzTPfTR$~A?0`ke4)a&`(f!3YUfb<;b z8LN!8zc3H~o%%Ok7fOE!)D^00(z8l^QLJv$)0F|n&g`N8P+fI25=ytxxrXSP=jE$2nXlWy|17)Peo*kS_BD^Swkx)!!q0&8 zqbv=dK7_GAsQtl$Rq~By{uUSVVB5fRZo9=($+SS-k~8}pL9Hl{`r7f36-Dm1)AU!@ z)l_e>himuP9#-~%(&ryhW~($+3rIX?od++XJTvoei)Rzq7aq59xHgYa?_A_^?PQ~L z+pf`;*(jdsM^Iip1+Rzsd^7fRRCUGbT#+WFN>o>QG4fCXU^x4CN_ttb*tMPRMxv&> zW)IZEl#v6$1KXD`UO7;^Zd+=w$Hp?6@l=%&`QDOPQ6IStIy|dHS1FUa-dzqdto#xMMMIQl=6`2E7RY7HmmAu!t{Mwf%2QAEAzNumx zi7SA*9LtR#92oSklG0Ja8A))Fg3|S*r;j12uOEZp>2ky^?q|2+TZh%Jqo^N0e*QS1 ze*VPy>6_E$)`3-8UsA|<mwLFQ^TiCdXwn^YT>@FK1P>%)2)eA~z&afJ4jxX204 zoe@WJbK7nb`Euz}_BM0T*+Z3{OTZ_GxDs>GTI6|;q1FtWbZ6q zMzZ7b|Fr`d|JBqSx_N>9Z}QS2D)jzW8i5f+xzV4#G@-RL07{oM4bW&ye{8EYtE7Nq zQACVDG$yha`7UpWcyq<8}YsOcPz$EATQ!(^3) zq;_=@4pNlv>}bj;adra3iM?op({pm6^A&;VX}%7*DM?95_-B`h<`+VfEiBmN#sKS7 zp+f4hvA{ZQ9&-b{Lqky0#hWfcFVB5(YZeu;DXK;=eSRo0om-Nm-f8p0e7+C1#u0;4 zUATS2^TO)pdUHcJf+&>ExIv`g8Ms;9_#3GG#Ft-A_msqqbYf|F|ID#7-~0dm^&9&v zmi~SF_Mvv}+q)a{J(Zywdb%3Sv*ww(UcvMY6S3B;fYNS@TWnm752lBN*1HAnt!<^K z=~>kpr%#_daQXR&olV#7{|ZdM+~4YtJ3V!35}ws}g?Ucup>$9kBqx`VOh$s!6{lx< z2jEEJEIsLl>yfAY5lp{F4C9Kou$V5$S z0o_MsMp)-g9jVL;88&VFAt)C(f3R4gI%l$Kf9xK-BA)YiZpll^8BH9#aPbD19+tGF z&O*#MLUx|c0;N+z3TG?F3qErpZvl0g_fgl0lS&TL2OC`1bzt*dzjT_|Zz%Kb5^Wy)c0}TS{|6LWU*oC95tA zNDmMvjs;F9dIyV26qrsH5+CDkriSc^61RO@^m{QP!RZIzJ1Ewd*LejFNpSwoz1J^Z z-Mi1nhoG1A!gR-%KY8`Na}z#3M&WcvJT~MYafl$xJ0OKwz|fR;ic^YjN`!Bedq#{Y zQ~7!HE_5A>a*iXo(J4ga^cA7V=>!;IRMSZSzwIxQ{jb#gQ9m2OK* z*PQ9>jfY|Vk^S>vPuZ{i3-`3`2PM!b$gD!q1;)4WEejNyt4r-ZZJ8|Bh7CsL21sdJ zs4gBtdPUuu4Tihav)Kwr=Sf{X#Qu7suxqdR;0e*?2@&VEdS3hThd5omxV8nNYl~-G zI9=A52X9%-kf)I4>P?o(Rdr3SK<(N(vYxE<;5}(H&O!lo&eciCUCHNaxngqemu0Gy zR5pUu6~oIEK>1+grn<)K#Y;}3kovr`PWPk4qb;Po$P3AHp{M^lVfqt`mn|;Cn|^e# ztk-p*USZ|-P1_GGUO+$1wOdo?l7p&}gX5*t^R1)JjkVi0&UwJUe~iAm(ltEUV|{H) z3(fhCC*J5ArN7Z=-_Z*Y`Y7$`y0N}A&^9T)vZ8jda%eO@DBHiUC3)LhTVD*?8syiz z+;5f?paC5mybOajqWa{3s?^*dGT?@0cOq^nomk))ie>sVn3 zfVqBs<~*bhrJq0XX+y(ML2&jVVg(P098S+8a@4&BD$CA_XZ;en>6lv%g+Dn~QBk#2 z*jz@cIABO*3=iL$nmmu`_^X!^9**||QYGBngQlTK$G|aIy>;Un{N!RG7e1v+DTWhC z6erS<*})-6RhPE7VBb`aXa>-HO=&^b&(mH7{=;a$XQl%@px;*1* zG-_-jD*uqsMvxyM#*;1<87`#@X)wMP30V;zyRiCpKc%LNa|U^SbACxvVc?NBt}cJ` z&2R}!zXK2v>@pF#-CUS*Q!~C0doyQdEt>R%Vtzd^z*`~92E~3klP^hfSxrY$yeuq3 zA*Wp``vEr$k&SB>daYSYe2oWa&wPT%i4$nGm}8`IlM>Wda!%koVKID07Gq22NeO&e zAhU`8mti`8TlI~Rn>QELhuRw+{Vzl6=?)GN5i}QvBoYE>lGr1`j0{7MwJtig#GrSt z&u`2(>%(F_J)!iG2^75vp9lvB0u@aqG&n4_qM!SQ`oiZ<2A3$kP`}<7;p^n=PP~S) z0bm87^P^*yq~IwmGSS@L(U@xtAd`X!i|7zQaYcG)gwfHPzzv>=D2k-ekdQ(|^TMRU z^ukbhT^g8z>41~fTAGuP;2Wa6=^2CDgySHW|QVK_+I`;~Ii+Da?N2-M~B6W8v zIlc4q4dbk!WOmN>O-i_W&F+qlj!zY&U-_HAxpL(go|j*7%{Bzor+a#K@17n1=(W>l z&ivr7f3axN($nq6W62tfjkQ`ktZmj)$G)Xn=pJ1dxet<#aXYzA>G7~l(|Em`KhuacL}Of?!D$byefnrFS#vb(G=; zxJbdEqI86FZ_ULYpm#P|&H2rZ^)yzEGa8#xOxRv%lf=J|_(tkHx8xbgWc+aE&WG0r z-})f_{($N;diINf`!|O&BhsHJgwgp9#EzcZ+Q@O-nSp^B{$3wFdPNnDepw(!^1Qq{ z-biLnR$Xf!k&GW)Z#bD{aWvvuawL4F)Y9+nUKh|s96Pq5FE83%FTvNYef;Z>Z&n+X z*X4-ML}whrI-VDco0|?w?9#fC0^jr0t%$u}0lQ60=Y}SvKRdZ)k|&}BRx3XhHT~KC zEn&V{4cOCB(*@(Zkj{sRM@$IFl?qaVUicW=28U#zbCO_?%9TA`Y%h?yYHZ}Fa}iLd z$XR`6ntN_^ES}LhMZhE?AWeKIj=~>oVk{gX6M|LpL^tIzMF2Qc>ZkyGnFSw|;Q=EBl8Ou|bOct4I}s!7RhGG!JPlH%#$ zOZpDgu2W=ae(Schl!+zSWUZ*KP8-joF3PWr-5l|10AWQ2&oF*n<)AzPzAx?iXH= zq(m((Q9zy2Q5jl*BYlmyA~zM*s|P4J7f*}!aJd)tTp81~`?cG$T$yOphW&^C^py5y zB!yA4yr^zQym5u&a`w+~`GbA*b=SUWFWWI4CD#n5<+hFeAH0r6=JHCMSYHHk0dl#mU16bm zlu)|dA-)%ZZnljfkuPe8fs~S^q6GDd3JHG^UdI6=HW+cgP!G5S-vwH{1YwxcE1lO%y8NOiMrqr@mQ}IW~*CLt6zxCEn1?6_v^4Kc*%&2K%-5 z2Gwp3qT}dVl2#UHmj#z44kebw`%4z%ShD|^|5$SJkMEGucn8}H_>Q`c#E#a^PvSau z7zuolCZ!^$A3y);^!ZP3PB+x$64t(IjhI`&^p%HPmo8qITDwN*oGeDLsLU050)eT@ z)r}r4qBF9yi13H-ldly?UF{Qa|!C|1Cwxp=(HfbKXmefY#(4lYvalGjGVt7tU zO37>&7~i-KmkBRTE7P@fQX*6ZHb&W(&Dp-zZ{cD#0&W+vy}2aTm>w83K(HPvV&E(|WF7RBO<$Ki5WgcYU}g&j40(XM`B zbeO)M%2IMQVoy%n#PcgRu3owKr+<1_c-_wF+U1w^;~(9ZgqN$kc1>D_yZbGrOibL| z>MR}I-KFTRlQfdgxHa>$7nJE`Y8ZtXQ-gb4TuoGAdTz0MCas)GEWEu^JT@}}n=5ZN zjFz9b;8xfAy;`yBoH?@WQ29YqZ`MMh_z`k3DTNP$wuwq;w+1RKd{*dTz3l zQ-Jc6rkts%p@PPu=DP-A3xfM&*eBr6~1hQ(Zjf(HuniM>JcKJ zM!J6MtrOjN(?xWqr6wtZ&Y9NCXwqe*YPA50Ky|<8%ft8X{Tw0qk3OpubNWX#G<^f` z4x8M2x40e?(CxZksQM4D2)!t0>+CiF3dlz?u50dUPpwf%QXUDN=k6NK+MhwqNt;(W8Y#n z38OQsgnMQ1+hBh12B=4QV9<$(2s(X(@WX9H7bz!Ikb78;e`Zg_#2pFde0(5Ic#bQM@>Ue_a56nE+}G^ht)8mj~X% zp??3=`1sYUm(kR(96o&P*k8W$SMd75gS6ASy5Y!?=kLGw>V0B^(9#2pDJlK2a)e2K znR29f)RG z3F*`Ae(MwKZ?b{Cz47&ONR-a@8yAMR4-5o*RBhXunp#m=>& z(8@o4fvQ4R*Y@5u@ta%v8v1U~g*1^SM`C^HBjjbeLt%Qu=!Mk8hG?@tdi`|6Xh&;9 z#bD4_i@9`Ypvtd(edR!QHfi6mD}Oq(le9v5-+}6(#4|^d6C>}Jx4}CW zPZKFEt9S|Ybdo1mx-R1#;UHSMeB)XPisaycICGe);JyLV#pQySE;nQ|@aF_kOe(1{ z%9@TV2=HgRLo?N{CCbMO{|D>=h3OGK6GjAbBNAV6Y|R$D79=9-a&x^Mom>hIpdiN5 zqGk$nuE`V^XWCs7XNoG0qgd2XOaOCIXoRnx`ZPU`biKDo>zK;%fVhyI2p%ZIuZ`3} zc!18C1PnNxK8XP-blFTnOP7xH5k3xXysFNb)b$dRAtFU50qH5eXoS8bU5Eol4C$ds zxxN9p0WQu?5jv-unw)@rm&KZX`c~oWL`_W%iHnNMm2j@$oHLEo6}T_@yc0Qn0|s?0 zFOmYYcUS+SU7vR@>gk!M^e^v9m(lNid4k-MM>+jQ--mNx`r)@XEPA$XxUOzbfYC=` zda1PohXqrdq5As7JC`mArr(-^$i#ch&Y7xd@(nOh6gxDO;2yijEvve%<7VPO;!QFc z4-|}~Pi%Pky^B|_e0lO@R3B@f&}0;>L+DySwv}WEJ6bZ;pp#VtZ+j zOvblvG@uU~irw&BloDt{#J#DSG!yA~w59x@VEP}v^GEk;%|xevG&>teccaO$H^_T2 zr_c(^Gb}XJ$(WlPkmrW5F6ug_a-nP-S7_*DqzjcZ%~NnJXD<~BAoq0T}-EPUH|(doTKuObV{E%?om)TNBn3ZQ4%5nX*& zIfK^8R0QzR(&flatcB)CC9SPlI!E86*z$ADcWd_DI{e>M&P&l2KDr?R95N9~&+>Nk z&V=-7V9IQURK|c|^z+;Rx+%H2bxo3Anh-!BjJ1?Rn5?WQmHL=qspI&=a9v)KZ-9=5 zLvi{0-<$j7z4va7U!~~bvLvY=ymIip*DjyU+>Abb>RXUMQ_+U+^48(0R z)4hc&fS4Z3Ap!w)XO49_g{DdLX_}KB4@@!k8_uI_ zoj@Mq!AGxt6&=5N`_Z)@y)_T&k}R$`UCty$op14XYbB)`0CNta3z;iYmxVGE9&5zT zor=Q+$< z6qlSvNl~9?bXu08Myt+8|6aN2D_mWBt6IzrL?ec0*XCCeo4#pt>KZV8)26L{SS`v1 zDmQOTPR@QNJh`vF9DBs8XED9dU0!T23#)=jdTBsMM@^?UC}Ubo>g2pgj{4|@^@CK+ zCJu0%wr_NFXmqr%cD;XPL#sL7&#$Vsa%=YT_V%FV2<%l$5weJ_^JL&>_>({P63#AhW4kNbv z1=sq6>FwEPtE!-M1?0Vb6+yfj&5$_vrza^FuHnnxswnTX{jMlqy0qeiUCB1b0ghmf zo-Ohbh8k%H2-lB5FpDl%Ui4D!oW5M4n!GCSRowy*J8ym%?fJ=*u$ z$bvXG`~n&Nz2TR3;CT6UM@k6)s&hN;V8&-!m1<6DIxohTOYLu!hpFPez|gpY{7ner zOKDuh!2qw-eiFXOQ3Mho$)S-M%YtQ#QNqPS&ujvx%i3V}2X&(!9!y!3g1$P)Z;gb| zFr{Gw1=W{Re(MG7Yx_<@;_0o*8vg@$^zl=E?H&l!M|l$N#_);oX)@~d2E9OfY>B&f zZVKvPMoi;@#uZ&Rj=DJlY#cP!2z#xSD$_?xr;_L1f7h^WxJ^YeV(`P#otreYrE?6$t%dj-jjFouFakP%0*k&%aKXxZWMN8@4517 zovzC%EG#sn5TjLAS6)C~Qh@khma2qonadrsCcC8P<~EFDSv%pfG#lQd5P_(e!p1*MA9rH)jKdl4;NlhoY+ zT9w2oC@=Xiu~LFsU=8rrg*p{9-n|-gq*KK7V~0PxcsGfUqDJX;l=jk$OFr&+({&{5 zSJUn&gi|T`?eyw0@OwZ>1*?l+-I7JQS`Q{}h={$X%qIT!se{bE~y7%6D z8B*W13swE|MdJrQIgFdFq@TJl!nB{?N*ZmPX8KjZMs) z4TiYljQR{?VFb0>`eKtDA8<(^ZC`IB+%q(ZI?@&C4lYc!G0AgYZ2Qw-Cqi}kuR-xg z9{8I#YzB3kpl(yu0bP-$#q;t&PJeJsU|mCXk~k9lg>)O3Z@|5XX> zYApeC5!1QQ5Zw;yg5lzb(K?zcIbCjxkS;eA%fspNO4^HQlLecUuBpFexvws<{h)+|ZS*bB3Z+AxToct<4VKx_+b*vQjS3MfNLLS1XX^2C zO&dIlwZvm0L-iz8FT`?|aaC@mN;@O9m{-v*S*otg-;#$bG*{0h8>8K&Io7#}G_78R zb1s=fV0p1C=-jPb>S8_-Cyb(Xx!XTj3FjK6t7q2Ec!0cwJYGGYdPYHS2%MA50MyVB zoRx&qwV|%5Oc_Pxg7xYSQPbrlTDx{Bc&-gtJsE@t)TQOo14$iC{pit__~6K|{a^b( zeBsI+?S6yx4FhF^z1bD!=39+)Hws>p{j}HSfo;g#?Oq$VRt2@MBu%fSv9cLV$D01f z3tqtW;_4c{FlcLh<QF*o;^?S( zs6L*qN0qqM*91M&-tJe~xNUj6SJ|5O-o?+Xk7p;r>XL?josh;m$mwIErwgO6rn>Y_ zRr30=vFla-*ww}PqLDhFe&T$?bZKdbcM+x+s2^|op)oK2zP|O@*{iCy4OGlYqf$}R zdlPAC#Iyi4y*GS4u`jF{9=;>!twj3~4V6wJ@q=ErUZm20C znl2VV}14cMrNK$YZ) zekTdk*ff;qMdNfb1*IKhb!KK0m2QRU62kZdTDm^U$w(I&q)r#I;-(Cyp@N~I>gY_g zP*W!Mm!@cvp-B?=%}v4wlN*vAVswhyJJfLXurj?InCRRcw|B2iOn(^A?boG_6j+DT zrLuIFt)g_pt{y@7N%5s$5hTCc)4%9@VER8ywsyy!WOVbbP#uIHyd!G*`{NV)^qCO1 zbIwRqRGg_e!Af3@iRi`>Q&W@qj!^pP)8kFmaC&!XowGh_YN{qBB1C6uBkP1d(3XrltnA}8Kx;ML1;w?FRA;TbmPE#7a z{LoNOjk!*-1&qc<^HfIT%-k4xvX^#Tx-)hsb*8?c@hIy4k1kQ5bA7Py*1)0PpSv~t zM1(MUppDW0`t2Wn?=@y0hhIPZ9u=e04eoV$!^3;TXpW9 z1$Q$`+BzDhD@OY&8ajq^h-@6r>$#{*FMs&TXQS6}y?i{IGWiRT+Gk5xO^FM6n_)g- z4iSYrLvo#TP9))g>pG$%yGW8jPgk`O8m04?lLF(y1Kn^pkWPRRk?3NYVM@S^ zraFsVoI9L_IA6>G6*rwD8awRHK?GbetjMbhrkB#@s4h=eSEs9U(;4+9bJ2Yq>hIlu znT(f3_*}*}*yGfdRsG=j#LMeG!S&)3MscyHX8@fEd{NPJGEF&6Dc&v-PW-KoDUXTG zs5eJAP$|N^TJI>ioz8m5-pPR+CP`%sO!s6G$S<)R7qk5__$n02?QdqtZ@%X@p2x1J zYoPw1m{h6K5769pO`;iX!;a`SLRa>e2MGS3Y$56b(BQd<-x{TJg|4OlANkg(9O@SG z7ByWd>dKq0a2zTZB8SekR;8N9MJ*KVTs@(BQl;qsr~mY{W_bCwO-rZUC|{f@DP5`P z|Gi53SNG>vZ_8e_{h$bmgF3efmNG=AmP-wC75l0)S+23M+$FlQtgl#>m4R3hnpwcG zBebxt5Hu^Pq20FSy#U9u9^dxWwM%YOaH_4!UAFt#MD1?-MzF!!v&y+_hWfH?k9J*c zjGW2$Htk)hRn^;5k5S8Q?^i9Aw=R#K-ygOI$OZa0-$LqY1zBHNS73jQxH%V;7ZeBP zWf#dY2Tokr*j(LhKT}#d26Pm4>1l-fC7v>#T0Ae2VtheeuWZ?Tw6^l!hcDWDgSW+x zHry8axH&#?^BijWp+he$dtn*2 z5m(pjAle&YbQwJ^<)cXE4SmxcqNYCBp$_oFWXTsO72cEOB*$Aj#M^UHo(RD@X=;(ZLkOFw;TG{%l zDmb1p(&HEYRtf4vw|AHNHkmhq-G^2#?af}Eo!!!SbiH2{SvI#Sww;xhMu&Dh**nlI zn2wrGA!+jHKz48TQgYK*1t-q8H$nwpg-0Amx;Q@+eydP&fl&l?QPY8TBySuluqP`K z%|ezq9FHw~B~j|D@pX$A#B~|9rF8bhP{NAn=jhLCMOF{q4ur$$n9_NSsP^zLV-5Y1 z<)GJ-b9)=$p zAuH0;JZs!7M~Wo~HtXztMO-#(QtF1HnQ zFnR+S{d=#y_Wkdl`TpVWzyJP00_F8S4(Tg|%^#ukkR<_D_pAWC>7_l17jUOv;E#7t zoh6|TMn`wK&_Z7d{<3$pVw8FIiY@EqC&$}xr+;*90s$P`i;v#ZP0tY#=+YsL%2o2p zlLXSUvhdc3_a(1u&z_!>fVv{^`Pxx#34!}!Vwbzb3S%Ezy7F54$YUJs;jS<-xqBke z=b>>YK;>{cA3{gGC|Qnl;mS%7gF5MqBr*~qD(y(!wGXO|)8!*eL8iI`HC^Scllf9m z;_IRhaVV(IKX-Rx-_=k4N4e<6JnZlw@vm;T|Z;hYYaO>r( z``>%-6Uk`g>z!j)JICMq+{B#Hw}x*w6n*hIX`ZgYv=AtNR>mL9w27>>Zm zERH&FCLGSpp_$aNz#){lDN43IU1HuBk6!?uFb(8*o5on#yB5saGOMay9%-NlxY{;<>Kn^FDi;QL>`AGLo`D@4Oq zkS@Hc!MLC*94$Jt;Q2OzR{>;bS?E|{D)-51a?-Ba09WBO*U3$nySQI{31@RtV{myv zSulUHU6C0B7|%oLRvH}488>a;@)%%SR^dWzu*THtb>%e}LdNpNEz#5M1a4nlmNC>O zt4FBquq~3s>OS5gU)r|IGW$u^korgp{Dl-RdOwikdEl z7ly)iyywdFg0QZM>%>?}rn;hZAe|FmMgKl1v2x)+e0)V>50jJx<8qYM+tu%C8M#baVUOkPra*@+cn7>uub)%9ZlXpf%gk(hUxzO`F#~^X4-mrq6Wyc5T|Yxg7uM9rDt9 zcet*6^;~WaVmb<(zu$Kc1U?aHj4L>hO0XjNizLjfA^@Eim9RyGbet?KLt^*aUfbN< zT(rNksHia}e-q}LZLB4`0>6B)80OhWGJ62l*(dBdjwKLPNfeCGKJvQcz~kQcTK!l} z|DX129w>Pt(##T2*E>cvMKn3!Y|)!cSY5&NxER{Gn60Lv>fGqI)}bM50QT^tw4|^u z?8Tuz2Kuh}IFJn|nq09Z-m-Eo#dy9EA)zHPS1TK@9)9Pg=iYrk zhIXMErK_kHh39rg*Dh^h`aXekFuk9(NpIXMrKF$l-6h5rD81)gbK|+ohwpv=d!LWA zRZrDy=;!R$mQn4ZGsHbq3?{54sJs;lwsN41vbq};r7 z>FgJ%=|n{447VYcW_d?NO+_{N6#5b}ZXIf+Fwre5Ag8UPZ)R|&p?=g{zkA}y?5Tn6 zSAO-YU3*F^FTKz^S6^*1A)-Tm-rh~#E-p2WM(9>=i1MVY6eV4T6#wE_qLefx7r#Sw zLq+YJpKCaO7;TIWpx?Q3>CUAez4)Ua|MbV#FI;TcIdcEc&YpgGB<+c`us8OJPK%BX zqn~;0{U7{be0(1oZJ4-_mLwsgi;|9@o)kjN4kfHv&Oa| zzNQwe>UmuOS){xqxGATL;ILAz(XQRFy%7JxObG_ZfUa?Rmi8I7pL6s^wJ=qV7f8K0 zwxHF;=;D-ah$*i>xA(}tgRlS9pB($-;^jSgdxjHAE#gZ@OZRphA%{nNFOJ?AZM+5G zb3?L}N#2o+MmJ|d@1^k(3OiE>DW}HlkL{(jRdM=o9s4aSx^!r0BxU#gxow2nzei)z zm+y0a`;$-TrFHDEVEQ|U&yBx)`;&vn=?=a+UpdYdox`tEN(#jb-o-I7#SR(g4Elol zSeLl8P#_&ES)99xDYS2rgAsch^IS5cOgpE4``b@y z{f>mv|HD&%fa~QUNPhtA0_cy(>ULl!?F9tayy7e)QC-eJbWmIkjq6EWSM5Rt%i(V^ zr;EwuKMREOB`5AsZgs`w@|+Ub_@6b?y6vfWDRHB}z_+ISV@W5q22;B7rHhuX4H#Xs zq<=G@|MPoyevNP3&9)zu2Am)*NDP7s1_P!F&ov;{U{?{X@ag=QLe=@RhZb)GOl`&y zmTEZ9g#vh$>;iww+Z&e^?0l}CUK}tCfo|T5JX($*@Qi5X zYPksLvK=zS>SJ47bJ?i1c&rBLV7Vr+3$1I!&K+1^u)%CiZP|>XPL8@*U@9vr|DDwI z@bK)i0qpYeRlV7j)}i{y)Pd%KRqf%2;)8>?;>{qZd-d7XOPBf8)|Q=pH5f=okzTOu zh42?h_dqA!xanw1Un5yD63CcHkE0Hy!Hkyntxrs(B@uXznx0IW;(C9=&lRk&pgfiK3a~;cz+jmM6mp zMw1D7Q82%(s$xJe-Sz1m%TsGxY`-gl=}J+?3L;7|^tlG}HF@Zg$3joil`H*}tWDAj zh%J;3(o!KQ81E6ZltdKx8IUE)P+E9O|09WjAuUC!Gcl5YxD4Tb-0VCx&nCuibaSE( z<(51VuZ0g@JTSpxmBF1JJb=SpG8s|P(a%MZUqdHUw$fvBenzYVHK9A*uDHBLpM;0|V9zahIW(8&>q(X8?VEekYtNl0zAQKCD(`=Y{`ayoCEkTI< zEN1udjH)Vk)&Dd~{onqD(%gzY;U)taFD1AsQX(RnnjDNx-Xob!)z$h574?^qIn>&g zo6^=`E=V92kajJ!Csj?xqiXbM>iA}&49+OMbZ!)%i?_3)6FI%zJn_WN2)#b35Yu{eW|p)}0{K}xOXT#-Ogu91i_8*CnI)}IQ~+h9 zzG=P%=gw7D927PE-S7YSliu9k=ObdB1@^Fq?OP&#Tl9Uk$ii^RTY->#EN zOy9GmbNBP*=Pu&_`C;c&N840vY)?;5w}m-^HMU?^=c(I2Lrs4TXK<7ur#iBtB2BL_x5?XNwH9Z&xsjVP+}3ga z=*-~Fj{2Ks^F(0bY~RVA7wHbh@*GVyLmeJz*$U< zJbfm8Cc~Iy`8WkoK!{E4T19*i;ss)Q_?>~7IRG863v=%u{pcr9`cHoR!3Q5SjuhUy zefD>6kE5fHV@H4g_F+=s&zyPfAnlqu_tEf@Xc$3rDH^qNdH@?SHIrHf8LV$Un3B|$(AujLpJ0I6HLTkC8Vqv6~(v$-v0)?7rE zz^il8@aU7dxldmGM8wN>&2JDIT@ZM`7wHP zV{vFreVivImnb797^!fewSg0qE+#1&8>AzrKS94=?jeuyHv$>I*6H$%==hCy%v0z5 zl_!PK0d<@C1>}X()ezVgAbwCgsu|O5{&bd$5k?c%m3S^34L*ySE=`X(S8BTAYPro7 z8;y%lE^@j?=d$qOd*r&LyKuLh3G3TdQLiA+^q>AKkj`vE4IDe)#+WXYu7q?&>GN;! z-+bkt*_pQgR~qs{(ZQ+6<_fEYG-1;Rn5q`2yVNqdhcBgVivTV|qi{v1vLaS=tlyxx z2Gz2zdX%;r_X}#vm%7v*0jn#NSGT_AOfkRq2yN;hn;>6m$fj$&t+tMLAjBdsc2~QaI5|5Lvs8 z{|VUxsj1?j-X8qwtA2-8l54mr=n#+&p6NX}IS^7y_9Kvd3` zU?SKlL`6&&;aYTRwq@fQ`g^hw!9_6{v7t`{(#~Yd#aHNSMElX~qW?+9& zt0oo1kQS%+Owub(NAv~MNm6fu(yMEVV>m!!u5KdSys)}W@-t{xT2MmlwZ-BYRRcPv zrFkNx<8L>(knT-fqGkeydLABt9=yqk^Jo`g+UQ)wR9b2gBIFwasRyRhl!eN>99{wu zUMoD!%qh*uBCH#D&*46z|9rithK5>OhjO!YJAIw%WA`@35}OXD{~)7g5q*jtt{4?e zx9jP`<Fz}NpZJmZQu89cC#>5!Ny55QN=~6j^Mi9h`cs6w%ne*?Yol&dj*tC_R%Mrd`V+>V zfAGP@qvj`O@1Op&KfA3eM&a`_XKo)pcyN4t7leM~hzQbodEItOM@%0kY%rnJWh82( z#5X`X0#QS1X}!^M;e#I|r=Ju#y}RK&6{l34PE($L6EQt^xcemipA zJX%_ZDo$B6!#*3;UeYm3($o3S28aWvly#JPo{*KBM^Yn!`rgq@fDqQR*ok}SNJ>4x zFg3?*ne^$JJ$0*S|NThvGvAxLfB*jemv7w~AKyTO(my%&&b@ zIJ5ob`zmC912cZZ;;%mXH*SmIEMoeT5~3~!b#)H>Dn8fzE&}Qgg47ix3#kjU%eMk@ z(pQ9~|DzJpRdFfHWf9RVsOq-WSXHeibgm5OHW#{R>vm56&l04LG2OO~N`8^m)YEg$ zQ~Xyp&u(^Mdo>YVLHfg<^xt@||FQ-1dvgBDKl3=-4=S=&ogx#tl&hSpYqsUu0(FmC zQJvZE!=F(bDQAh=W7Q+&5u9X^oXZvM=KQ5xQ7dRy)C07qQqM+bdfRi@UQ8}zRc*QU zd_1{&mihbS)`Lars(Q?$Po*|W9wRHOOWBkMSLUy)7gQ_#=9;YZ$oR@lxlb*6a5lgC z=J{)nT#?0mZ4{rp6Shc*W za_~h!z3Qi9FOq2>tgqB_3P~v+l^W9ZcgpURRh4nAicIzOsv{|setdNFW`o%!W1Hx} z3wvF&!`l-p5|0k9ACoK>disdXMM_8qM#1z$hkp0a0!%LziP;MVMQQu=#%RtGW|!t{`L9X5QlSX|87C}r7^VhXZ~(o33-fIUUpR7 zl`fCzPZ%=lYuD0sRGK-7%SL7&_)|RKaP>wo)Gzn)TUXS~Z%*Zb0)3K@TR|joG~A6D zM|6L>9IcU@$~7DzpurLmFk+g)2g88XWirD3+6{De+sFIKZyX}YXye=8Vthx&Q`&f1 zMz|VG6X(a`M}`X7`6th0mowP)GVH5rx9sQggZUQ@`xE?=myc}X{0-Y%SgbBtx@?)e zIrTQ5mbd(!r_|g34*TI7_t$USVgCaX7+VlaBa{+1@UKf>yn8BYBud}pjXKwqITc3% zX>-0gGsV=FlG|p5pfNpI8VU+pNz)GXEROOF#n4_u;Gn8)H0Z?UA~kf%oBj~0D^t1{ z0|c$0=BW`q2)hS|)&a{#% zk`rJ}NDB!qsM%Y8_uxIj^p`V;Z4s9_LtHEh(Cv_JyVP>i5z|F%-@5@km&foRM0H7X zq19-8(f#HFcYko^%=gASN5ot1;@&N-9q_c|6xVc)-}>3@@1Hq59;LTfa5W&bmzG)x z?Q3lnQPqu>mu)%K%A1aw{{HO9$P_r%nvh_cGBri%eKC(1I8cCzIl*8kC6jS7>0F3{Y5<8#g>X zQ=+SfZqoYnl6)){WY5)_+j4SdJ7$#Kg$~0%y7ZHuyz=v(e?XApg#$;9?7n^a5C7Yl z!y=-;``Y^le{glfhW^R0u(Ts-Ta<{tr@LF6>3Cg|0(4n~*d#E$YVx)Q_&N*Gx+QeC zHeQGyeCxuO)7V}T5;{itqe}l$&ieR<(`j0FgXr{k?%n%8Ub%qlg+`# z8HP?D9|un-D4l}==4NH3fpUw8={VW>lHyWru!`7TBw?K+ zM^T}narH6gn5ZL1b{!_@<@NXSyN0`a5Ywf6RQ;Huy!qVIBbG@S2a|ZI1mK**K!l|; z#pE|9lfCDX;6hGaoHaFdD*qOE{_?GuQ@dw7 zX;(1OIsWo{B)%M$!yxaS8YxT}t|k?~t-3n8$=f(p5R*ZPh#LW)#pZKngF~pN!80O) z9qmNFFj8Sab)EG4}U7agA zUFqnWnm%uV0k;*J%jNtKDi?ZIin_w~7gz$YL+x<2EEbekjQ)VeMJdPHq8ZbL$?c@B zR^d(&(xr-2Ew@3sP(Dv3*7*lIy25l7^TM_H@vl!{{MYU|+YYt=+5Y;=e*+vo^3X?a zeEm!PiTj(6FIe#48GqwhnAOe?T)^r?N16F$ zwkx!PRM&pv@n2o>f6VRhAP#Nx)%uswZ&YD={JO}2s+HmGslh}BuA{T`t3h51dbc+A zZ7T~3nhRdDW(~HNKgRU}TL_sfYfs*Gl;Tr3T~ZfGWF($(u%&O1#-2jJ6<^rxJu%=9TS-NhPSlT2Q;OeQj`R)!2If>~JC)p>$T4vpY0` zBI4!FTRaW50Th#x&A49N>!|7egU4q^&!givOcku9eiJ#J+?b$Xtntg+nG3X&pq|}( zHv4Qlm|okAim&YJ3&O`L=ygP+qwuH0SGAz-Lk>gF=nzgt@#(m@&{nQqUleV*pjJ162|_OHX1?uD6NvS@-m zNS$PpIV>P^1>|qaN|$?VZZ4|bTohwSlTTo}Lru}T?Q2+VBleax+k-dC-eIGHB%P57 z412+YJ*JF6OkPx`rG%_A+gS4urgQZ5q0>BT3ZmOET`2tlqigI6t<2N8{R(|_9~xxV zvqS8s-#}-fa=ss2%(J-kN@ZyG+Lp?)uRCdX&)=iHihWJ{YZ6(?*Q3L>UH0vr-*VoI zS|;y_PvQem7glG;goXW~1S|V2W`3W2<%<39#7-y5+X`axW5WP-H-kfzHEzgcG|8d# zl;{k^^!oaYYVRDdeaNKR+hpl1RxsT;FWt$YPa>ch6&-JToS0mt%Q}SZoCT058-ehT zd?7T7+r=@{g!E+(VSsO2e^XLovFS9+J)OG$5%#^am1jekB@h5AShj;UiR@I zF}-xE&~%y$<fBY}Lf9BwZ&XJLvoTes61XK68sgc-xx=|dx#rY55@Qe-+7yPFhHIq7t6 z20|JoqeCC&=|J^p3Z``P&4DUBfZ@HpuNHCe19D3N)9+mR^&O6iUHb7)e*W`Ue)VPf z(ZS=`b;j?X{=?HR9eW9@%MX6=HU+gu#O9)`F5-4sGHl5T*_jj)8fD;R+!LsB6t%di zq)y4{30b5kP9MGS!3P&m)2F-LoQI}y5>B5#e&Kw>`QwS_J5bX51I9&L2exgcq+CNb z$CfV3U~{Fe3#4PC$)mLqlwQ%%-DBC3w56Xlwn*U17K0^L!c~-*9_6U#(*&n$iRd=H zyjYZT2DTTfO|$5OslY54X-rx}E8B-rqpAnIMWL%6VbRc!NbjvJF z!8VPJKyLY<;y71xQuzq$T&zSe674d~0UBj8nU(MkXdA$kwM#^r>67=}h|m!S@f}zBPi=X&6SYuI9JZ z+qkC&&JVSG{+7C8U;oji|K?jft=hIg z8R_c$!5J+86|~K7{nxzXfAbbReuBq);GfK+TL)l zZNaIVNJ*z9=~-OOwGE?hm94@4unsmvPG7KC?CGwH!W>4 zWvPjD2SoxuN@;7A|D4!oq@q-EUr2tTrj#~E_|*Y_amC4%m*)t>rRuWeruAWkdJRjZaO zl^KCppjABLqNYm?Cpb+kyO>$LD7zHFSS%fw$x)ZVbV(V9Tv67gh;+e9fS%okQyun) z(U;QPbE(vns?0{=c2=NZlMKYwObhVLu(n`2Wve_1!Zpve9a}o#F1Xd138;lUJpjLS z+2VyfHh6zNf!7Alq$6QPW8u_`3a0=1@2jgrCNFv|bY1-BGeM0hZG^l?@N#eVt->ds z@X07>4o1iKQZtFw;)Ca1;NM~M=)Ag$C`R5S&s{TT;A1x>yjM6n=*MDz4gR+C$M|n9ld>xzB=M9T@d7pQF#r{ zNxr!Oc+wjhZq3l7IebU&p^cjx>&+SNCim);>T83VIsMYui}(KM-o1mn3b2$%zI^Nb z+owCa&({k>bW_|V!q6r`u5L>M#ji+ySe4m8Kbl9(Rql*Zgb zj$C=tW=#D1h?W=+`YIJD<0fk z1I1l~7I%8N=YIF${Db5nJ8SPX=NN0~Z#ZEjbcX~DA7=kR&!c{$Hqnm@M6ys9Bo(5D zF%lh8Lye=ercM-?DEC;XCftf_C70i!R+jK&y$4oe>zvHhR^3O=g=PPaWCH^mn0c!( z&jNcZSJs-lWrITI`Wp~R6V~t34xNWwRhf{3MYS3_5Z=j2)zQM832!hDsf@xr04=8# z!wdRCSoZh7*PP?QtSOn9&{Qj#fCmfoKLvhB72C?NPb8--K_LECvh5Rb4U=*IFRQF$ zk_uo7kF(R&zLU+QWSikl43*)B%M{G?{Z`TMPS!WFh&nE9IY{||v5}5&R_x$%XTh9l zxHjTZZl{(YFwx0_b%fAPBKtpmW6#0nsFkpsRd_Q2R{?8+GSSX2&heNF-q+U~>CUe( zzS2VCu1^Q1|1?w5NU}*aU2Dou9t(pHM-}6_P0Z;>zkxz;6+T}Pj_&aAXJyT0mns-i z&BcjHy>v91dt!(!s%IR^b;NLSy22~vT;ijz7AUp;ynP{y#*h>%wY3>pPf4&%A(DY_ zBqmPCOvO?wcX|T1rd!EaM~QwYmrzMBO>Z{s4o-3+PzcZF>F z`-aZret&@}L#`41eEhy%z4`gqQXuMq=f`MoJL`*e!45|`uK5J` z^wr@IS{WIW!u6OT)y=oJ`@lMz;(4?R}QN^W9Sy?G*T(6@3_OAu7{|?WMxMJg8^*s?r!ipnaT0?fZ@x{tL9zR_4b{= zxs5?H@@h+wvB9IH z|B^SJZ>z_8&w>hkKI%uSML7(Dn!;=}{)`^?3Yg>k@shEIh&k^sXIo722LiLJXp<#( zY;zo5Q&U`%hv}1iARjQEw-gX**z>X-WVf*(ZC~_IR7BP}w<+zYGZ~+EdwN*JaJIxq08JPYJY1)wyyEbU zYKd&zeIzn*&l)CE=%nP)X*>24xgIbw-1N^lQ^k@R5g-DCx#SzJ3IarM7>)8EzwI3X z`MOTOR4P#EHZ!NGaWj$kzGqkXuR%Kk?x`-AIe?6PHqgG-I4o1(#@!Mwd;A6WsRZ6x zzeQeXtcw2HaC0`@ut}t=u>P_~AT6gPXeRjE9!UKyO}N49vd{W=)rK9vzWQwXl51o9 z@$5jFm&5KGCa&raGri@Z-?3U+1~7N^{7BkT9}wCvY+`@JDX_3gzv2|7p3vVKD&A`@ z-fbN?QZ+qDqgu3I<=f%Q`X`UW*G`KaKNzx=X$t9k_@Dc5RJYW`%&^!!UGCaE;iT@B zvQm#)>N$UN#DC4C+OYhhA{t|Y_B$rah%1~KSOFbZgA5x&!=*Z?21}bsDQ}px@@*FI z^rb%G{w+q=P~hnW&4bW{77>rlOiVxVlM^D>e(nwi6O_idgf3m~yNV{piEI3d%IG5U z*E1v&l7jObv{#S=b~yCze2XMb(W#DI`iBQ;8G}S=cjkIX?8sZoi6BFQV@Z(Hy$iOn z0BufzB17rA1MLQ@4b%%sGR56Af2n!tt+E#@r7DDz;r2VH8>b71z3);;my`^sHE4A> zlEp-afA&Q&C!-{90r<WUpP~#>t!C~*2W0K*W)Q)Yl6Tii#Vo?1Uk}iut&!RMHhjX5bid^#4hE;bZU>@ zfH&?l9WHfXwsiSqYHVtCx+jI7Q~MWV_~H=gd;RC&jO12S?GGTc*Y7z$W&SKMTAL4h zZ#V^zi_B;fm$|0l8W(b4s^Y|w*9f9_Dlt_tH)qtwF*m(DU+2aR8C+)W?QB}eO2|~R zD_M`FoS*{|B4tqGt$g@pt`)RjG2&}cz9Rs>N%>jY?j`#%8W~-wY*rB@_JJgWx(^yA zaPj?@Y0gpRfaNz>G@ORrb~S=7!j|lxKY74FnG-+Bv|?I|96`_BE&P(w;ixPT`S6&5 z){zSzj;iMdW*`v(cg!kyrPm#v@z`G_ zG4Z=wn{3SbObR4s%-nlxf_r!6GP3(_Y-A+^yF)u~CbxXVm210Cyo=pl-qun{HKf7& zxTdW31Z6+UmpS0R!AvZxpQ7krn@C_Fa9uf|h83X{ak?$@?b@ zl(Mru-^QXChZmwP&7qCd)0E=-FnyRmI1zBOJxtoPaGRWWl#{5Ab&L)#9+CJLQ+!4- zo(mW$SIP0m0Yl==Nh-<4ey!$5s7=u)_z=^a{4pk zOdIqv{|HkdB7NpQI%9UCe1Z-TV4$xE_Y?FpyE9$7w7sZ>OWt*RVsa}F9blhYaUJ&7+&M-+;GNQf*U^4NGbf)Nhs?XqNGL`vMxx0J{nboi!XtqNvl=A|k2-;Gon zG|~Dj#VT1lxj!u&SS{T`45}($+62;-?Bf`&4lX_{F%R=AcJK=btPHtK{dVX+t!(HV zx1Y>LAAF4&TN&NF>+^uD`bGt7jAcq`-Wvy63u}8m9vp0K5&wevAI6gi8>y?~x4|ov z`Op3yY+@#qxB56dJe4;&bXoYWoA}MhII1RkGaNC+z}?wb+u~2X@{FnxeQGDrc}A}7 z@TaQtqvWUGVRO>tn<_8w-`Gqvok((m-9t12Z?4yF$;h2aYd|G}N{EHvh_Uq#8}P9_Ki173vf2g|JJZNPFBWXbm-`}nz>(-n30-#`_N_c zWFiW-(IQ`NSPVZ&$wQ8tV0qQ!3Wx6cfqI~RB3MbEm`|T2(B`J6 z>zg<>J6GQ+K-nsYT=R{_#_^fvXX2B3irY%mlMFzkhbcwn2cL8S--p5?^kA< zpFi5UZO-pU-}~`=w%*{VeOQ{fULW49v1F|w%D;_e%C#WX=I)tnta5n(xPR|9y;_49 zbIUQ5SlwH`+wj%*_tBti=nlIP0coDstE%WJax*Jhaj@K~E|)2v1w_IA8FlI7ulOO@ zYiqpLg{1;T-@%Y>OkQ*g6)g&@OO0PsA00fuxPP5^hzItayV^QT32|H0SYs2nwtI5$ z{9%?Jg{B9*s!xnF%di0mvy@3qv&M$?#lZ}o2MK7y;T&#ssc{@L>}iYSA8hcfqveh>VPtYQkkX?xakYxY z9@T7bHU~|(89V3pR@f(9q78KBi1 zu0CfI3c`ltl$7y7i~0&t2e5^l<3@YfAt`-RTmq&_hv=xZs`5VUtpDyB)>}PpwW9Ih_|5FbB!9ihAto``QOIi~`%goHi z?n11%u4<);4Ta$tVH9M!1Bo05TM#*oY3T849+hpq32?m-;Eyhc zjvTncl+vb)LofX+LM)f&XBX&Mq_yrzb1u6zd6t4Z8K%HJT9*4hn|#;&H}P2 zU(;ANQ@|a$l-*ujz6jP^E}xE1T*?*sD5nDugn?Ih&vBG{w5Y{3Lw0c({w~gDb@}Ot zM?3BX^|J-+U2;AcN(dXigTG1g))#fd>bl5Y&^%^b$L`#)fqJl5iI9@Xa59j6FD?OPVf-qsLA>U7?K%?AEY8~Ivaid~6{@oQ#;#ra=m5=PT^%|iYM%XQEeK)Q(3-C*sC``<>R%a@%wcMD zD6_G&+YTolV=tLb2I~*u+ps7uG;Ink_T+AU5UjGdxBuzn%W=yPuY^Ui%=3)GV>rqG zaSs13DpJ6y=TypyE*hf6Oy33IUee;IS8pJE&Qt8G3z&l+u&Cs#b$z! zWvdY=kln4dp{m`@{s57UP0|?j^PG@Kk@<##vZltOB1aE1q8_%fObo@9Yv^Xx*p*JT$ zd;$s){xp?I)oI9gNsmCU%9S&$E=OkWB&T3>pFVc$dJ(_TmgsWUAOG)C|F(hl{)_B; z(+Ycd=or!m{&2<&G(|P-gMOvhP2}Mz!KSE&I}2l?lzh*qI4w~efU;9qzQ?^1F~9EB z0EIfL$}Vh$TyGPln^rh^Gfq)7YS|A1T5r)w*ETwzytIO+o z>x{=qX0}lo^}HCrI8I_AUNbM4h4nA+asKSFR;-bpW0R(%(LK~1+(4J8|DJM<6#D`2 z+0Po|FAc8@;m0vqjPgy!kn=1cA%2G=acTNKGVXynjT}_kMsVBpWCr&M?eSk28cEoZO=!GlE>fq#?xspE2(>CN6%{W^n_m6stm? z?|r!a1r;6X*X{1~bTGGj{r<1u)bUxE0f|-|0DgE8b@`WC2V8eK{VeFgA{F z6!Ge?l!3Lv#NwrO8WxCm+91s9Sl+Dlr(SFllBpm~UAu9P#kq|wXmQ)o_Sm6|&8-_{ zLPo3nP1_k6WvGam!c)YP9%W^7xg__AK9fe=NW4+7FNh+MHK~QJE_zThxo2<~wYYDt zsxGXkCFX#sjzQZ!TJw|MpaF$M!woEj-5~CVB0No|P)PKll3IZ6ZTelJ4kJ{PXOw|h8X9FZ}q#Byp6+Aq? zdO@o|HWiSa@gVC3brjRyACv7~@o6-m65F`?TL=#T$59`EpWP*)u#O)T#3+$nUw9qO zfs^PRLL@|1nv~m1n0EiAH-=c&k;0i!H=RCA%zwsil{I=OBWqm0L7$PFSTVv%UMCMU zd3IG7SAz|TwRX&LDqDAM#f~*lTMnNhh^-1^u#V76VD!~5Ulo~me}ozNBEReI4s=?D zuM*KUCZT0qNgq+PWu@&VUK>SuoNG3HgKs%Z4J3ERKkj=64^!jfxjftathvHpmdr3} zoB>Q0y*W}>R25-xJlFrD|Lo%GL6tn2pl&pqv%U9KjYP*VMHJu7gkxUzpWklKkQ*Ls z_-~Dlh*F|#Ln7s)5RFfjk~|=K7gr{pq;C-y(lLc0FzCm8{q^IsJ|QsTkjczod20GJ zZG*BO7`C=Svao~ONhiw5>Ny=-zU~rZDh{mjdoFaIU#zc6fV3Ux^qC~FYCgd4NIOkw z;h`y6t`JG(NogEj7E+PBHO1-9yT@~sZZ#VfFYvMM#~?<0;MBv0rDt_ufL#dCF}=O< z#5ix@=8D%B+)+f6*Ddt6azFj@_gY?Q$;+!F(vGgGQR6icn=s=v-K5oxj2XT3 z8h2}pL}-RKyw$gqMcy=Leh&8MDYE1*TlrwOafqN zj5)@l-~_L%wT5j%N66+zn}Op|MPA;w0^bvxK^sPwi+UiqIXk40tkaFN*Y*7PE##S! zRmO>gsACq(V{d-#BLDT9=aY)Ohc|_T;zpiuoVsRa$vKNx=88f@k!^N}(vRm6LP2g_ z+Kn5gTwiUCG(i>Y##`G7s70p|mVEgYUZN<=2)ojcDBg&O^u2>Go`H{t8ItF(+k*EZ z87vP+{ec}Gj?<&U-fdXEp6Ths1FmX88q;q9A=$XsJ6qWLctNm+bTsbA)R)1eNF~-G z8PZG?$^8d~`J5@0UG|Iet_$sJ1egXI2B_t}jlSGc>DO<}udivkH2PQgSi^jhb~H?< z9>-GZV_F-99#*L_y5RnyG+iH`kpp=;VuiYaAr%t--_+ILthY}GD(nxk@tsU%?_xus z!*Rg%pS9$z*cd>Osu!uuO7ORwUS_iKbvkE&KBGK^eVP~RgVG(_F*!xdzwX-G z?;8B=NEj*?h)**G1woRbA1l4q^Qi{eaWP&cbdhu8lP(^xwkUR<$Xb~*jM)?PQ#oFacDI_eNDxKwW7s(zHae8}82Kp4cicG-6cC}$VN;&~pn3$}t z-y1(@F;YmhM{mQR1wlbiNg0JEMoM3fV2^}KTK8O5Bo8eXO+xhc zX;*(^Opk*n+4Dw@>^8TQ(F`#td2aTrgqF}wv0p?n>Cw^|$#f*z(ZMVDrzkwh{m8CE zGONi(2cwweK#=>TvsiwefP0Y!4+ETlv=VMrvm;%`f|PZT;h7@h!)(D%U4vrw2KWgN zuQWw>;D~+@pP+v7;6j^()8J9Fpx)mZHNRSyHny(t!xi&+l-1;_#l0s=$$+0s=wdnv zsF~yPFyMm#Zz+vK^kBTJ_sSQldJfAJ;PTx5hZCi{J1BVlAt9^lqjP1pX5^GG>Hs4f zU?5|90T+jeE?N;80{9L+Fat_hiG8;nq1txgn$79UU{S_xFpSQP2Id(4qCx!hg3%4a z#R->im%!f%W;e0&6lWjKjfwx0A~t+0#s`d+MV_7Ev=xXBqjnn!&FXRss~rUzerE8{ zpThoi(vhp!39Z*$QLmi4kmF3joKtcZA}lts$m#HVoNz1K^mmjj``r<#)@7fxH#p7B zpPOxr-@F9U11owjv|XLb_ujDHgW9B&u?;&JGP=rTXo%F~LOBkOz~~grX$1u-%PrG> z|J)@^qS*__oWx(Ob)Uy5sn&eS_ zvYy_f$TXFE59=s_0nBytdJtLJ^w)%(fFdEDv-fU(+hV-`#Z@Y!r?F9|x$Mi}|6ylQE)4QFdKjbMl1HBHgrXDv|(}}%!;#LT0PObCnLUtq^cpo8E)PltP zo#eLTdo`VeJUP)(FZ)|zf9h^jIPedhgvB3rlBjL-+*`~s z$T)Y(xO{M_8F2VW=UoDd^29DVygRG`-*W8=;lfT ziIF#bYdOsVKUm*C#m7O<&dcw8@|J6J`x{$qr0 za59c;Tp}RSLI913iG?;cfkj6t(C43p0&aZz4p1feB{vu(B-|Daf|O_lR);BvzOAMGVmC?k!-;A>?QXf| z?UF^b?!YFRiAh0yYtWo+4(i~prYqOe!H)MOH5jrbLqPdcWdfOcB55xU3e?T@!UyC^ z$`P2dLgjt>otZO)Hvax6>`-?R^z+WL^U})AOi!=fxCr0+zNgu-f@I#&DO$Cfn#?!# zWQUlwFroIo3bv_^l2oA4pUjnb?#NT8R-|#}HooEy2qlm}WwZXvJJrlA*x09vt%8&~ zN!?+Wiw=_y;0A6)Bi1~V>IGpevX?0qgS~YA_Re(CWkx(q|Je9dLsG3QGXHL%vgGLv zNaFjQa(aD-8`yoiVQr%hhLa{nc@vm+vG&L5Q9+*DZFRKq2A2}s`v|gRR^wP2A>-b# zd`;PC|B4PAlj&|M`V~A>#JDd|5Zejp0iAoB4*$OU8n|kN(cR3axn+X)b?wiD>PN_@ z`NgC>)chKKNv_?yGZM3%p|Q9JmS}cHO?rhFz7ONzzct^v4Vf(_{cnItKFW3Z*7NY7 z^Y^PV9?Jw%ST=)Axa{XkB(l$|qoFq2uv<QgpPTCWf)Y_>nkQc&@E$288PO( z`Gp(U_t#ucOLh9E0OE}u;nv6Hj`p;rR znFh-W5Q$sDV@23aM43t=x+`#EqX{jHT>jJ`9@`byBrHz#NB>yBSCpDeb30Q6{+2@- z+#;|LEsnGAaFlduD^R)CaqybLS|X{C1LlprDP3_UCwHWEGzz4TBbW!c;S`Op>Xsrw zF>`Ku3RxC6rBoJ~jtR<=Cv4ox;r9G&+vEMqpFX&rcy>Ado7{k&ILLiyi51vHL`ZHE zDjM+HG8FH<2Fm*Fn4xl!9L?@O!SDGPL>Oi{0N=}t+wX+^b(AMFKv9e@`y5*iYB3`> zaH=)>Y;eaa2uqAgpR%dRWk9qCfB+6fi6}nNDK^WeRU9lv)Y8u zUi_pfAj$dL-tKAiYUt%~8Yuj*lKIYet4oKMnTk{2F!9lzEdG@22m8)roX+LJ#4ISG@2v$rTihEhRf3@44#X>* z?3+fHo$^q+OR^&BAPSAW8~fPXSWjU%i1nuEtImCmVVkS_zm-8j7UHvv0;jhD6uO7L z%WD(}ilg2vTY+t5QS^QlD8^GQHL zBA)0H>E_b*-9G3CW@O&^163@$5XE2+|Dhhfl;;$q_%)e#nSBE$!`23KU95Zg$VPs} zWu9Mfmv@YzB&4i;s->o>sp<0Q31Iy4f&Z0HSx(UaDn_eZ;*E`O^zKpcR&+(K5)4<} zcsM0S@_l^lBqW~OJ}O#D_H~u~;(Kc<@8rUrmz?~$Sa_Xgorb=e8g{dnw~s#fy9_Cx zFhw6N7Z-&;?KgugP9=|mL5kDKI{f+Bx%{)=Twj~jkQch8Dcxq)nlU}cnwVct(PEw) z4!m~TlH$u_!fZg&`wXL>gocArf2DtzXF5POP^!o4(DywjdEL5dkcCCI76k|XqrB#J zbGKP~7rMO*Ndh0Ad=GDEpn}LnlF%Hvje_9{1AB2vZ*fNQ)M8?2(%(fvcT3C111rn@ za4GxcA5!cJAFPr}xSi$YzI%SZ^4~tQJv!=P8o(i9Bg&nV$Kg4^HrzYM<;_)(R&|#+ zgKu6;=Fp&ey{~o3_{;T;RD-{iJUW@5MD4VY_o?*ZO0mj(VaLo)8^)dZ9H3eh6s?yP zUopx?YPdr3{k`ENk^AGnM_-2C~nApF&`Qmk0J$O%)J+wOhFNw4uVan0Lxra+$+8oHazYv%Hq+~0vM>zyTQ#;y=wmnGVFXI9=#UnXpT>xHmYBxg^S5=Zx`E{=Sis zeY0ayT*pZyo2*6|efiwHw6^uPUg|%$meDtKJcGks6Yd3H{cG+DZ$R}YuFX-A9gO&AKs%b51{OkSisuPuS z%RsByiJm1vU^Vcaiem)Y*E*C4tgkDv%?5N-3mnE>gCvkI$18b_;%Ht$f+QI25B5ox#4Uk`}#zyj3=|-c=Dbu zpaF`46rDz$c|}u?`p$%@;9Y8jnLg_rY*?HgXqQkv@|_;pdix5tvJdi0mql6qz<|BY zQqceihV1IRupzt@%YbFTST2W979-;SvjC-W8tOjL3)Ix>?;v;WiFBR6rTGE(2)n-b zg~g2Q{udkaqY?l_>!rwbkITm{e+KT?UjH2*Z|&>SO-H(T{`U@g&(Rr5GPa#vhEc9% zPpL|w@9i&L2wM00vTaGWx{9s6O!&gb()Oq<64+A7X7zF?>Fd*6ZsvNK5v72?pG71b zQfBd32sBKC#&$sd^yr80NUn#Rllur%N_8@$cH!{wLRnU&`_(v(Sj2CCtT%?S-}hn- zTco@9{_?$vR0MGhb=0xWI59ZDF1~2x(y4DpQfv|8EI!yf*w8m|!Yf=uUyLE=Ei*+| zA#LZ(!p}NYTdH6ne`M(#07b6 zL+Mk=3lmL`FK{k1+91bk29@^ z|GZ^A?L8&qK?4eMpQD`i^$>^1*>XLj((!`9Ce-o$l{7W`6gf-44wOd9ie!Yk+H!2YG{T(YA2W_FUdwg9%DDu_GZQr~lF57B}K zH_p8vA=bX-p7O1>IsqrNEa$?~-9T|kT#hh_!J#P=e_OfA44jNXJqle^OiAbr8#&Z9 z`w)jO9GLF=1)H0fhjhfbW*wC}W>tnm`)}KasW0_?k#uM$NPM4v#e`49mM8+gyVW3T zdpo4gxHfynS~NKuwzNfd93(~JV8pE&BL%v=62CwxO0kw3cqoP0ejONIA8=@0gZ+fe?VP7$wbTp(9IfHTp@QOc>Y;Q5X+0788wKp#Shr!I@fr&Q)&a#tB1&;z*F8eezdTK$rt<;LbgB_T>fK#oAQbEuM&ARxs8-q80W+wn4 zUXHIU1(86~`KbAd{_wZsJ@W7iLWvbQ%*>+wC2Van@;7y-#GjSSxxzsgboz^m)#W^N z64y*D9#m5jY{Xc+7E{|G6X_L9+nkzUBh1K%sZkft36z2;4B40Dv{1`Tea>H*BhWDp zr4R@<0nr(DdPhSPK>cd(rLDyrr0v;X-pC@t4%CmH7Nn)3CV(jZWFHdZcHjEE9{V1P zKxiO55KNe=f_f;wiw085H{=;9=Rvn670~C& zl|`NG7uW`vNA92#ZY}W@Ch znR9*?-soHoLwL=HR4cO^_bcwtjOsXwf5W8-;1Wl@&eqyqU?XU0tTqFo-5qXttM5RS z1PFb2_lGi4X_amj<7OzToxt|Fao;rpUW)-COZk!`Sn zQt}fQ@q?wL=rW6NA$k&_GG=uq$lewD1T3FnF)OUP-?(#8pQAu6lX&*tzGJzAn8;Isy`GIK&u27d;11)2%XND-1h44r?Jce<`Do*9Z!Zb` zt0qZ5EXj8_Go!YlnI17HN>vLgrzH49>=UuA>FQSK#;;)M;^`t!7VydVE7LZ#QGU+c z(*{qU2x@4FjrSPhbYN?gtax7Q0|?`$pQ`Ld%tY}#$UZGh99Pd&$K^XtY1kysM( z2dZZ6G9rqid-2Ee=f_z)#DB=TOeHC&`6c80UEe#HzOuey!K+fDD7*N^;1hcRcUv^r zfMmqBx%GCBS(B5K&y@BtW0POq`=BNQp!n^NE(SqDXJQydP{hyayMF48EJgsbJ6lU5 zBZdapjZ@c>6V8&Q){1hGAw!cjd>@N{o-KgA+@DE}>Bk{=KVN1VduB4=5?5b;Pn${H zqu0hLu?-vtze-<%myDM_^s0BeXSY-{GO(FgFTPvfxhQ~%Dl%W%<^06<+DCA{<#$rj zLr>#kg(@ugDe`vcQCR&qXj6k>~7uJ+4y@2sH9093&T&DyU&Na7UIzXot)m-II% zcm?2r+G^MgkJ8EA@XmM+T_ryN{bS~tLmg!upJNeBoD9rpZ=AbQh>K9pdRN>&S1^jN zzhN?|u~ttll#Zq?M@V>OIxW+!JNc;(f7u%ex*KvlG@H$*b+=VeD5yT=tmwi~2gWIm zOr_|>zh2C$(0YcTnoHJG%2QM6;N_arOEcZg%MKFTyx+JY8`3gh5sj(HSdy8L$%zxS zr-GL)92ZXZIXwO}+Gfn<3@MqTLpdCwqkr zuB@gh^4lty%9$o5&n{vhcgR3Jlsst)*$EDv;NImyai$zdt1CVD^`l4T3Pf|B^h*DB z&ZbkdSO^5_W0DhEN=x4}Aw8`GUXV6TeB;)JYd4opA;$ICw}Ww3!js)Qr-zrnnVbls z#uguxkk;Y~Kg_PSk#Y;W*?H`|Z66}~ECcq1r7B8NC1Eqo;@Mnud+Dj(@m9_wBYb|z zJjI?O9qtD6H%J#pU>o4quk{AGaStetM+pi*OmH=Y<-MOzaN%8iO|F1@&Dtma*RxgD z*K~6PG^57_PksWvyOt3s@4$`g>qAr=7VoOS#4YFNInU5|YMnIe$74{BD46q)IjzkU ze^D2#^OKs)>7G#t3vHQcIDP+8E|(5|6c=g}3>9PA z|LM;WIjT_nC!kSlE2oGVPXG~t>TYn|a};y4xMm>#>Gg)0?X@qegW8Gu92+&kl2SBK zA)*>7)E+l{CiQ4fD+#jMc7MJ3eA;316wx9>OF?an($-tMMT>8Dj&_Y&r{i&j; zJ|c`-8e4{M=I@BC^AALWBpDny%3*$w3yXhLCe9&$nStK8g~RYzWpLnTAt@-2M8xt! z6SIcwF@+D zT5e~1jWU*-8aM9p{Qi=UYO7l80#;IcY??_;0g#m#tPzUcK!b&2A;P};gyV#z%qS3d z7!*i}SFl2v?Cd)j>zi?eAIs?BN1h!o4CY*imk)h5m{ObwBewi8__>wpyq~2ih%MRY zr-FV}ly@Fd0j{>*N$*ZRysE0SxwTju0Au5#yd4BTwjF6V4>z~Hdx&z9(ZFpVHqisE zt6U=31YDL}yJV!jgc*Joh(+?hakTelhVwRw7mbjRAb&l_M)$h=FN&hyg@vyF#O&%K z>>tEld$e~Db*vV(9n!Mo<8|=W@c55A?N27N7aeaARl-K<^nZ!?-kmZq9oN)sZw5iS z&EakbJI}Owza~}A1D+CVYBfF!_Wl^#c9rcR76Zf!sNf;lrZ_{@6b?093DlP{pBciR zhRPL6&eWZk#bz`_;}?*98+`i%6+E8Y*>bgI_qq~JeRp0aeg?ku3^8PKFiG=@_yjVV zLOYQ^LWYwNcB`nMCHDy@$(^!{!YjR?)PHk?A~tas)M>eEH+SV#- zE0@m|yQ!$y9lqDP`8ABs2~OF?53e^C0qtpn&UDNOh86%64o(;u^{dnUwLr?*U`)ur z$U6?W1U)2pUr`GXJ4Df51LVW8L&^EYMJ1@9_)Hk)ooy{%ZSp1)$NN`=zp>{gR5;XW z3MUTpSJHAAz{v;3e%sYih`0+c8s|CgOh*c)1oQhRoiiKsabQ=Skdcr9?_^%%QHrp`<`@LSYFsx>W_1N{ZjTmmZB}L7o@w(xhT_$HU0>=c z?##E@!Mn+A4U|t%*R$SLOe38v@IwZdQo67WX_h20?M%l{mY+3rxty8j@T+K zcN(d@*Ql5dj+IcL)CK3J75tx z$GJN)3hKp!Esg)t{cpw1g4^SmnEEJ8@{6n3_i*Kp9(a;!5YA34yF0Mf=F4pf>Feo1 z#eKII^rm8&fZeNofvoLNT!CK3xPa=)Wv!aH`p*vC_~(*(;KghBaW*`gjvyAh)|2Fl zd;>jcmP$d05xXVzW=p09${68qJ*Hgc5!F5=RHrgC16WK{RM#2?P)Mbmd~h#*}zur>cuSISZH-~^P~JAGl+|ds?+N+qTUCo#d7|@ZZ6#jLIN-|L|E#y2kI>p0~-)6mo5fvgCVjpO&F!{z!CngOsZaL ztb%x~k~c^__%K2@!=o&%F5`2N+phy4t_Yf=o}})<+d5G^K&BNjeUZ>yD1fvNWO{TBObwIDy<5ShKM0rV zcUn|;)EeH$#tV5sY1i?BrV4RnU*pp=>aa_nD^+Taby9Z!zb{9R1G^?Z$3qP!;Ebv9 zlontV)cj2r0h6(r!P)07j&_xilA0dqA9SstY%EVWXUR&U-1tgVfv9zxg4tL;#z{{T zCNI2%vRe0#PT=+`sZc{69iRkwr-iy2(%P3dh8b?_)aA$~jL5^^g*r z995?f1-nalB5T)HO~|fBCxE-^sJ(?{4LUqaGlbwEH|z+}e`;XG((latbO^wIyF6e6%eASi(y4J{?dp<`hFo8DE}phI z#a*8h>_5*Q7U-d`ig2wpbGGz3H?cNx>aiIAt27Oq(E))#?s0c8oLq0X<(zKspCv{xLgxnxy9TT(JVXE(cuEsKBaGRW1l%_gA1 zaZ~Y)cxEUQwhU_@GxkN9103>DFgH8rpSa_`mBU-6B)@6HI6|%oW?ST?=dzV9Ku&o> zFJjzeZB_k5pYgfYgVGEF!BF*0p6z|`^HzG>XXGLmeqC9OxhpJO-2omf+(b0pc&m{j zKo+((ro)!*??jPH10VO(A=UWQ2sLkiC+Zh#Sh6e>b8ppsD2H-rWF^x-Ddcy$6NZ)r zb1Be}mTVx=4Cg4(5vzD!qA1(-={mE|^U3=bDSC=zb;d(2JKk@dX*;dDhc!&%bibsR z=AhxW)LiQXI_6N3$BOsr0>Q90d*^VOn@7%DNtyBULTW!rXSZ9$v2*;tB(SH{?e1Y& zlu1es=#<6WE%ks0jJkcS-Q{$nL7@S{voqvy+OVssb&iY5y#XPQG=+7pWw!kpu%M$Z z2@(D7PaFnq@8)}ct`%YZb#!iK(T`-fXFV%+zDqY7f2f*sNCb(AJmPrm8<&7DYY4-= zmKPeCgUpbPLIG-F^0T$M$tzKyQ@B89jt}3e4*4KgsyYG=V^YI*@ zv`{9Xy?4+@?dCZB)lSUICpuMCgP_>^Vs&670PXs|5^SEV@XdL=BJN}@CI_|5Q^iANt~vE(@Iy2S znfpig`oha9xzjSjnshU3;W)tiPuq)!m{Wn^fa6Qt6|7H0abqs_n<&Zu6^~cD5Q2?C zXDCj;Y9sIAAe;=0latxJXbx!lcwM+k_hPo|`t9DtW>0tSt3jY0xtB$<4vq%^|xWHa_9O1R@#c06%3hdj3N`gmS|^yKR_BSlMx z()mxvKdHg^fvsa_moGmHoR77{mz~WbI->VdsZUkVzT9hVW5I4ubQMEJeq~X<#_59TkUjjX zq7ntuSBbSm)Nk>Vs3GFCsxn=?a^uQ%yVM}5w z=;i^k`(&Kkzi#Pb09aObCHqlOQVVStrQTJ5e;G0E%EYvE8m#zLg_QO zlfHd{%|T2fq|}uMuk_-_&i+Du2Q5*DMM8%|QRrp+cp{-sZ9c$Gu>HP>nhsJ5sVgyE zu=61)UEYWNV1dT1qNmFjr$^*;0dtMa1%0(^b}Sb%W(yT9E1p)IZpU!BFC z|Ea-S6d1QXzxG_(4W3zE@X?x5jnQSJWSi|ny(jgyII|BSbep6u(-d|EwX|<)&KEV6 z!J;nH8qM~iiRxl{ksWIPi?qVm*-hkd>7^d!OzWMJDPy5gAB92vKz)A3h(lCniZ}KS zqcfe?-GtK#oJ&Juz&=ll?r`b zte69`M0#hy^DaYXR!%AOB}6VF#8_heN(CuC8vM@U#-Ofox}#eR!KKl;ZKg~UihoJQ z^LNQ(eCegv#yfZ0z3Cek*>clukS-VVy#9IT_=eB5taOFyoeI6V z?-u=#>E+f)O(sQwV7eh7&*;rgqE9`>g9K}PLIJj!bmE z{l!b~zI*uK!Hd5~Q0nzx{y%DlGILzY-^a+NB9v(^(cI=8P=`;X&VpM++M9|48KyHj z7n?_$M{hOfKW_+|^d@8H<{i<~=Z?3f z5X4c$OFJ5{rJp!Ys>})8ftX(E5_Eh#gws`!cS2U)63ppn@OgRD7cTrV^+ukXyHyT; zM0wNelbIX@s7s>GpsqV?OaH}V_ujep=DlY=YXH;5IP%7`&-UEy@+^tj4W>_`i-Xq+ zscB6_^oyats~`Id{f!u54oSW#DLy`L?0e&lBX3MhI5dsmQI8HlPM6GdszxiQX-cdZ z5;0v6T}D4cyCzXEGME7v5YMg5BB6AvSX^Qe)NSf{tj+JDY3c4Ic-NUe5vI~}_wJ2* z&%Al>%Dy8_AAS7yAJ0@|_>h*f?=nW7V~4L=aHxRk7Rjwd-Iki_1o9Z&%gbA>Oam~Z zV@+>utjn{qq%{whI&O6w>aB?Bmb&f&yy;+i?r=4qXHF?0ONR596UpHa!V^hXtTopYI2@S+?(%WJ-SC(yVF4{()qtzY*o4HH* zlf^SZs~!RM9UP^%nP0+t+mXs)?qu4MlDK$>+EVN-68<7FFJ&}3lAOjeu8Z-76Jq-M zJ6exYRQ2PDEys_(HJDgkk(k_`jfZ710WZ{=@>IB96sGr$9-kQ;tR1MLNR$#%SJ%|h zimI_yRHmlJx3t913H*;`XP+J0@#K!ON`I1Il;lpn%d*t+K>}r#_Db&L1>28N3Ld>w zK8aR8D#T6h;KuF2>(&KJnhUpw zp};TXuF17egWBSTUbt~>ZA^VpWsJcPSCEmG9_s0^A}u|zehq}GJwP4~KC?OxM+X3?+{%Xx6}4V`;_S8n}P;s(|G%63aHa3m`lX$EB#^~)R9K#3{zuwbNYP4r`;V&f6U2g zGfkPB^J98yd?@&Q>AB}_|8*y7`h4@zNwU*zNiUB;x_HqyjEgT_zITa#y>roq{*!mb znSS!*bc~ri#_wTGA750=AmbAUzXP zwk9O|?o1L)&oU5^*YP1$9+&36P-=QfX+mpBY>h#emEdeDv9h16G{A9oZ)L)gX)THE zKG{9pH#0MH>mwQ#HS9UEZ+7;JFHXO7@8H3M9=OwgirocJN8_Fu9J|Ed%HB&=_v>>~ zva(1MCr`Y~(hsIXaf-RnU>&E-^)ypG5VIGqV?ra@>6``|hVycBcSheN>gs0G&WZ84 z-#>ld1aVs(BSuE3(yhxh)nzsG4Pt>metf#){P8|0ovxZ#ocVzur8|1ly51KtJ!y%M zdIJrONKUT<)5X3-7$p_P%+@SfzDen!b=`GaPF{x6|LESmKl-e%tqn!`<5Qh)OrGrN z33J;$MRjO@|DI=s)a?Vpo}Ao5&muRF)Q9e*V0vN1z74znde`T>Hf*SwXfn|#Dj-*& zoT!({*owiH_`Z$+<^x*Li%|MWJEq&86;lnNH`07kYgTkXos(3MO8Kbm#D_Y; zTGCCNeb3&Wy;uIPpa0P-$L@yC-kc%nC9>JPcjCyRA0B(@oqNPFhM<1uSxT%@Egg`c zqK^`oyB3TV6tr3_4L#y}u{6~AS|p&+;=;MPq0ZWnklWgjRoByM=@B^{MIKi=)uTLD z0JWq13i4C*#EA~4>*Y)+-NDI0r}so)y1>(?!nh(%CP?&VVe%rJ@`uL z1CqLdw^J;?trUys^*CjO$6aF_9NJ98lg?rUk1_!TMvvwW+Yov7fMo*?MP&le+v18e5M-;$L$Fl5=Q{0?s{94;#s4zeMpdZ?wV>_2$?;gzVe~sy;!GbrK0^Vi zi0S?k<>J?SXvbJ$$289qOwLS8aMc*{`XxUR(+_>?$?z7zbS>uvVZL{;H9mW6dG^9( zJ6>!VwCxo!Y&E;_oDKhA6En%_lQ8p-s*Hsr}eDDzMnmn`pOP<%p?Aldr zQ#cnLT|0d}uG`~{iFE)- zSH@l%AW0kxls*IggpkwrrFN- z-#v4h3R1lr43F4uohq%yoUHsFzUhTJd<2=^QTndZn;%j{dKT{r-t^sg*h@-k^lp|` z7_bD8rG>m>7Q4!#bF^CBEql7VPbAI^R@C3DHUEKRkT!>L;s^&hfjP zIH4e&&7K=n)mv~+o{F1;;=w7K zX(c5+BzoxR;PLZqg@v=XfA{R|DJ0!)$B~f{Z?HPEskE-6@Azm3CY(<@$e$7aeS$6v z_@>D$M>TYg2{h$_(|OdAyx|)ce)+*$)7=T~(mZHHY%ksf0VP;TFiB6!YTc9f>}9fE z#GL+r9c}1P9gg-XOOoe@}`K&Q-!$a9>4vI)qVeoEtH*_v+Py zmk<8%>eX|*qi7P98J(Bcr4W2FwvwEehRnPzxMplmq&zv6x+#I5gS96? z#B@Hbip=eZE-^3SN@oT||50+)OL``E-T3UyH}BoMJTx@(;SAc&=E&xAyTlMqxlfN!?nqH}X+oya zfw&ho=97z;k4*UZ(BQT(!Wa#w8xhb+ab!O2n8mKd^rB*3cwRM^Q>b5T_p2k-hZ2)& z|3Clu^6?&cya#?;_dsA}a=5FsH=4^1A8XDS7^tr=Dk|E%-Osi6R#B?L^Z||0=>`vj z(q5=Nd_DP%wF7hbz^SZU15|pY5>~Rw!_V)#px7!u?BNSv2$x#79Xq}Sql^7zS^HR7 zu<*DPi&hPybK@?TdQtg?)CZ-2R5Pfv5>h*^mMWxlRCnR@!Q+FYbmvPQtdh!43^bz2 zU;in0lA2B*zw@%rKp9eV`$GQdC0C3l`jfwYGKz-CE=EuOPH$x*K`)Y_ zen@Ijd;QHvv)fmqrZ29lNVWYK#cLvYj5v9)rYLv1`0v+l#hb2(T(Z=?R!XiSNUmHj zg5*Jxt&S&#$JzbrS_BNts$At_5&<-kW;JFP9N!j`rdoWe=Ah+8`2{hNYgH3ah+KB2 za;S4D+wu^mi_Jt(oeQs(N*#w`1uEqQ#Lu#L@zZav^r)>M(<3VViKfU+^=WB7Q!zyY zeuCFe?|2jUw+OTt+F4t{u{u+XEENVK*FL>`U1ZVbO_653gHJ(Bfw?#?Mh~XPY{z(m z)*HSI%efNDWdKvAj}#{p!v@c`2`zstjrZkr)U(@_o66|LIP zRW2UEbWJ^1;HxlL179Iwa9Nzq@Ib`yo3F_)nOzJ9~QHkj`Ojoe3?G|ysFyE&9KhP==LklS#31B#EgMC`_uEt>ABHu)zwWaBCyZ* zkaGSjsUZD}&-cZuz(wKjMT;h-g!B^fioKkknP$|b56s9|cBzaQbm*ZXI zndI9vJM*(kFPtXnxsO2zPkKOIbu z(2tBvnGcAZ9v0w2=Jt*o5pC4^t#)82qhpto6Iazh3mhM&z z9ids>-FaJf9fZ>FVSBkaJ>2o}$NzY15rv<5TMQW)yE8I80rO|^nX92tUCwa7gwaY< z?-@$Rquj!@Ba1Ho@bVAezB~@6?}c0W$Yfc%$b$*f$Mzi^OtjXi0Co}5<%u3NI8rx( z^vV9%p4eEEbtq#De$jdH1tFdgYaS7oRUr zoN1XEXxVg;@!nzl;O`uJZ`_A@<&q^1HAB|SXk1yUf|L%V?s);NmZSikGg0RFzjQ`7 z8t)b+`TDvM*`jlF!dg$Gqa~C*bR{jx4X^^~)qJ2S9+l>(Y(gCAD`?!L#uIeoZlZpNS?F_akb$-WhK?N5@dz4N`TA zH60pf;853d+{LljAWx+YUJW_j{@38~<>Ni@cn|#6?t#=7pMEhBZQOq>{7|DgHMqIC zvU2mL?Q0h7*i3}_x>tkOZQ8VH9phD$^(w!yDnGiGR>XT``;qUmhWg1@gO)E`8C+ga zaG;i$^;O?p{ap`ffkZ;1Yxq-7+Z1)prw%HY4dQ804j8m>No9n^sU5YMT_m1SD4t+O z)t{7`{>hSz?!W%dTZ1!46XWNS$9l)Gy5OG~yaVVH_rgCX;uz8B=eCZ~1PM1w_~I&r z_oLDWHAn<=h3OLb(%bvwldg#^t2N7ux}$xtp?0iysaJdWj-OW8O)s3pwI=`U28DlbfsNXeL7q?;kl;77u0WFgHlh+B!%fr6Z}>Srn5nWxr>oRye={{Ocz_Y zfbGJiJR7)-#b%)x#D%~Y_+8w8;M}>Ih`^>PhrlC-nC5}iuF{JN$y({>qP_EAPQreI z>oy>yp$?$_wAZ@G+D)4xX_rLUHhF8Y1^Upm(8hKAbn(hyOjk6nrL9Y;t5n|lu^|f6 z1^WJm~DM3t|C;d%y^fzS-&tF?Ig?OS&^G zf;Am|JS7EC&xF6zcgiPrC#rlDWuHw=BTbGY8m4EGEke||uPH|;eP_C}!Dwoo$~4*R zE;iqbj{FglPOxe~=>m~$!#UKDlE)a~Y3QfX%i%N6Jx6z=&M4(g7psfN>h@v7b(C|h zgcQ%qLlvZ~)w#Flq*&9hOrN_^V2s$i;ox(Bdgk(?y$MLk-uj6sP`at9sZ^O>ZoPZv z%w@V~U13g{v$G%1T{`{T>D#v^nxYd*U8u8l zv3BSkO>}T_cCnV=@lT*lXjW+(sr3d+>v@TCxmkbh+^I?5;f}VcQ~9?V8^64={gq|C zb2Ig|>ys%Q?Zrqlc+-qQJEv_pAg``_Pu`v$%bq%#2JsWXG=z&m4F{ufWOq!=^Idwq zv&q_uJN;)LqGDV)(Va&#%+cf52X8i|Pux0vXzqRh?v?0~*@-69^sFe_^Yr0&K~3-I z`1C?wM^-7=Ev6Tu@G-q)>6{blh-4JMhRE<2etBW=trJ!iWiPb|a)@ELj`lsnOO_bB zhx4}dUr~{a|HtorcEi&4@jrh2(fAwvc~1QW&&Q37I5?n!3#DscHmZiRx8SwsV+Exr z<@z4kx9I8*|KT5g@rz&V8o#>h$dNP$BPMXSys)kbpPI(n_{3JFtxM;luN_PUdiKUz z3@+|N1+5~O<2o02I*=}4&JtyK5o||bM@_dTwBar)%a@PGSUh?jL4)#t{m=>Vht4ZI^Qn$1UF{`6IptHnS71bj1osAa1);l zqZ`;B?d=$l8{$hdBKBY|?Vx~kY6fzd87_}%JzfO*Ur64J9xi^&unZgZ&@3>c@t~l6;TO| z*h;WWhwqSTQW=WWcaW`!6iT&_&%{&KEHG6tC{lG9bOsW@cd@)k&a zaJ>legf>bdBZ7L_b+UlZ_a$;q;=mf3AT4!m5AR)%O$JD>%5Lw?_7WBS5YBY;bFAs@ zM8w;IUTAvM>)+T=G1lv~6ik2SLWS+;C{7l*99f(*h3TRUiwS)zU$h>jAuC0s%Z1kE zew)RGs22~9Dy%QeUKk*|>ca`9uTqgQq&z}xctXHi@t6xuE?pa=63NqXr|%3*FU~KD zDL4?UcpL;)YP4o~QRS!Np0N!D>&Wq9oe{eU`7xrcOZ6#*yjaJP*q1GS#&3J%f&6p3 z9he8C8O#R;)-DCoLE)#VNK~>l*8p^z;YIF}GEh(+F654t+nA*d)YfOj84R8d#c>V} zX`v2=$TePA)0q|U&O|h)t`$oQTWh-^D*tl1$pYpZGApqSyEk3j87hZSC|%W#$}EA& z!O&&BozjJ99|B%=RU=^gxj->^tXSB_?C`P;sqL3S)UwFV>2mqNhb~;M zeaSK@Ce?1u1H0|n9$aXUu2H&rZjICB+$Qzguh_O;Gt|%XIZJIr3w=?XF4Gl_(C2Ag zrc_L57$T@kOHvKgHLL%F-1H?nSOv>&iI)99)Jl_esHt$O9&h^dqNX=B6{b-8SnQsW zQBuM`e-{^tZ-m}FkNAjxmO?lApHCW~-~`#{xe{}o)0C1kHPuwOlX)dI$t3CxWq|)9 z-cc?ikSb|$9Fvz4Qe(i7Njxt*cRD)yI=bV7K}LVbn(pkK+0mDH{3w)8Z?X&L!Sw33 zoTkFSoemkzk^7&&eE6l8o+CEBQ`B@Dp6^{Wxl3Jt1lR4J7t&qS*tbhDeZQurf7x@l zsIln&=F2~P?oa>p>V_Jp;nGr4)1wSor6VaR7E2e_^!r%T!SuZ))}ijU9Aa#8Ol|aw zVRLEY8WQS8TwYF&gMQL-YvvlQD^b%=-#;})r~8s(y#sjZ=;)qdMV(G)bq>%a&?dC5 zv^yc8Mz2q35Kg~&^VX^H4Ms66*A30Yr(V2r5s_nVZjKfYFYLG!erfLJ&}?;1N=`L$ zIu7dYJ$rigbmiqq4^)NeOq@JDCk>uHO~#sxxJe(+8h5KDtL>V&Htvw1c%ysC&fJ@W zGlPAzPfVQp;`jgTz6Ipg&rXaq4R?2EnzAsxB%Y9dOP_WVt5e;tXK=Nt>Gf0Ma!~_auigEXg;IqRm}zU)}|!zw!Cy%j5gtbYCncZf@*q zy`j8i)6s@5!`JXR&$kESXY}vtk0tcp1v%YZz$YC$d5=9bU6L6!tGaNzf^<{ql(n>^ zpvLF!x_f{0%4e7FUb#4U6r*Iz#r2uPfHEGvSRl}Np~m4M3axOIw*~;$xV+>UA*S8C9Mg=DLI9qpI`pov3KZ+diD8< zh=`^M(vKWcyh)oU6DF4au?YzxrSljbDYkU6qRWh0rqz72fSF}6Mw`c&{#%P?k2n1B z9+=+)UW;9OW5O-HrJz}Z{P0W_0;N&{hJ1;nG`KOc>Akp#X-r5jTP}@ zRYy|=M&a>Sg-=)aE?ivI*tmAN-$saz%oEgfzcoauA3A%8y9Ccc^*48X=UX^n!rRCE zYw@G_S5Zz%S5it!$$v=($;F$VtS*$CPCY52`A+xDS0Qf;DbtF;Ron%mwP7wShKZys6~^NYsm^SCaQu4Y!MegJ>E zYICIONPkC4Naxk`6*@=Yz`evoV7iI0K$FhfYBKs}V0o#}n2;gI-xlB9t!)$&*?+ddlaNX1eKXh=2sr z#nmlsNQX*1)1~iGLV~wW{3EI~Q(0cXL+8@rQY;~e={R1FWN9=6c9UEJI{O^DC_t)P$cIM1W@BHEK{_Z7A=~Xkd7getR;kvvmc4ukc zaA^RX$h-&*Rn3{YJSQdgMPFhzw|e_xQgJ5MRsUBDe3%?e6aR@}ihT-nsY6pPv|}Nzlwp2UQR0BR&zu z1;iBQZP5r@j4$(`j(KI0-lSn@=`e8mkzf4qhyU=4H{N*T^S7`5!^9ErJv728#TOq| zX7uRb;L*`;?D@dBJQIc)b+HA1ySj!|9m9(p3_$VEgwx$Ix8Q7H;BZkox=84jo{|!a zwUh<{&KP8RN*ns$xOO;eD&2&BF}Zw|BZZj zBHaV{R2Ut69hxM!B_ah-=kKY}7$wFg%xNacRCkClMjZ*;clYA4 zW2pO`M|_S*-b+LiVKH(@WfFTjhf?CA_*|+(EXead8lVfMD@>;&64Muc>jQk{-^%0h zcn>_@1HaXKAo-ca*@@=*zJakFexn%!+bRzXY{G@UebrOp&CQ!Oy}AxHebd19wOf-t z)~9Z+sOYO`Ia;}`4EPjh`dZX<`VEoZSi9bD)r+fwHU{I~4&E4a*6%EN+RG1ltwia4 z^UbFfrHiPpOzLAqF!~Q3MI*=aQigj)jOh%>oNwXvsvoP|7w#WR#(};*`TF`FOZp29 zO8up;5h^@4iHy-KFF0HW5-aDJ8^GeOy=B2w*&3w7=}UofQPa;}I@G)4$!`TEZWUt; z%h1>T*0&_qkB+r_c@fC?%zPJ8vdi(f_$lu>%&jtCmJ_0gNKUmV?sUcHt5&JVMGi9H zhY^6sz0Q8|5Ui)H6d#Nj*5UM3UI0I#=hEy`L7VG>r6Si$_s`{PnggFuvjc645a@E? zKzZ{z`FXeLh|eH;eoEeVNplg>sqUZ=g0+|BGlFkS8wG2OPo^QIT2 zrVFFXNeV|rOs7UtjPlGDWG116^m#b9ajYgeL%6>&WRXH;8ZOd$%{SdA{ zm~yDM$d5w3ar+cyp3gN=UG@)qNP+s(Zz?@qY%dH7a=#@Rm-atLJM{)S*OR6UtGgFl zhZ2mwE+(VVoZpxq6FcD}kS@L!MF<9$DURZ2NbH`;Q_8wRC^P+UijdKB8U&GmwM zo8_F9Q#~x0-glm6os7OuJJ1oa(}aYUoQq1|0;W9o+;e|1t}Ry^#+AzH*#(Zk(|Ht0HKvi|7`QE4$0XHy|QkEhR1wG zkYqX%7?|DFbvN~HQde)`-A^BW_~C_|tYrUciO0NtIjK=O8 zc{qLk@mb%kq@Y_&)Q^}J9qOzd?HP>Vzy%LH9W^)@HQLk^iJv1`>)|8c2AD36mt}(K z8MRjizI^xH+0Mvp3*0d%%Al#Ot{S`ia7Jz}s(R=ABO)2kJ^1Sfg6a1@`vgq)o$%cj z=&j4@%IZQ+H?%4ex;75!cSI7nxii5uxe0ImZswhTzQZ{14r)4?h?wboO=5$Rnp1=B zgXvKvore^X3#A)j|Ip5zh6tI-Nn~mZTC7$iCD}I7Sg9}@V@m-MnL_Cd<#nN`v>?*9 zB9g;O`@6cDLS7iB_Vw-CkD&C%frzkxU;aHGg26LINif`6%3@De# zQ8Pkbva>Tl^ffk3S%ns65~6OA9F!i!Tn^7ZiRxxH$=O9jDK<3~38ohXnK?wS*~~K} z;w6&OSe5R{6qPApB!69cTCn;u`NHvH;!c5xQ|yE=yBdL1b5mmLVD0VD*KwTRk6#|& zf5d4LN}m`ZIh_jBog}4J=EM7e9PZ+;ls{o}`6CuB-Ao)XBBnb~YigO##GF!YVm*sciA zh`gw%#<<41vbr)>V{GxW6G)$SS!>l@R#TN$PJL-hi;GK4URnRHa@zb%BLgc++epiJ z4$&L!FMFknM+%5#gIxY)OV=)kIY$7PTsqrv|sza0rmPUk-d-kntP z{2iG!d0SR8!I8Xl1;U^()*11b&+j_&J_%+)q?4mURFrLjE5(JdS)HX zM~RUX#T;f-h^cLhBFEJ*GU7WxDwr<7Xu$LUFx@{hD=X1qnMq-ymzQ~bLME6l+XacU zQv}7u{K7^Gn4_yJewTv)>I3kZH^{GnnqU|)T{FC3Oc&5pj4pI8KMW9E=v>Lla;dgP zE<}GeP_03cHsY=k+SP`{ulMw1x{D? z7kMH&y1a;-|M)Pzo3<(3S~`rItv-!>BEv8&$Y)k+I$wg?8`^H+Qrkh0^7OK1*w*f_(4w z>v8JB#e{{x=qi&@oE9>IhAV3M!~IAa9H~~EZK=7b6+_PZ61D|zo9KOXmDuzb-@K!# z=}T~2L-WNIhVDjp!j;oSI9+ur4M$B^sp)4P&6Mr9AH3=vF#VnV*b17O^htrHI#JVO zV=Jgcy!Y_i*I&Qz@i>^Sv#?B}RJLHKP}<1Q+tC7RIudHWE!C~=?zX{+bNA=wzQ*+O z$-$8zqTYw5ENx-liuxcTM=W(B;pWr#X*eh&ea+VR&1-gc%?=LSjJi1&I(ODLA=mnF z)<^&N|NbK8)P>hC0J-;TE3E*HCii?jBb)S$T1FPRTeb1(p)d=alH(8&VCtj&ow#ru=JOJBmUjI7>U*p&|@%h7;> ztgNiA5Mt}$aWScLqIMMHOPADd5|mkh_l5O44_~Exl)BePgAoxqpWpubU;h2yD>41S z?LAlX{2%szek|veZGA+}CUBrA-7zw`pfJ)6Wjs1MJF8^0B%79`7RmIM+M14(j#y4A z5K=lnc+d-iC>SOA-_1Cw?0ytQQ{SvhdJCBOV^1qZdL0&$Nu=dVdJ76El9eCNI# z(UMd~sRNN*b?eE%$@s~mRJH#7=eG_Vt_*bYHSzV0b#|7!yd88Q+w_hsiWA)gg`K}w zp>v*VCaO9w!tt?u{{Hlq7D?Y*FnPM+PxrvnJz(4eFSS^;G=|nh?H=AG>^K^Ub5872cn|T#>a?x!2yE_-SrEc zDh647>rfiR+(OQ4IW>Ay{pTo+=xBdV~b%ZZ1?416HQ{POM%8@jFbuKpmxuvbLq z7V|h3axte1APawPa*<+DL--R) z!E_Llbw*4_%vK#?$xB=-&)H-b=HF1~@41D?OR71KHnue~@T`12^e*LH6(I^C6Xf!? z&xW);xL*8gwgu)}CxGcD%kaIFQ8KD9T|;xl;9AM6^1VpnyW9h$D_vcw>6)ItP(msZ zFGf@Pv(Jf$ZWtmS8zJ2YuZ!0PpNP6LVy}qjOgs!H#lwQ&+F2pA@lI~A)+n1R&KA_x z%qtpkv#dzmNZ$q&m+6bd(`&1>Tk;L5r^|)$w76h+Gp^L87&lK8e}<9M;qrx|8)9u6@l7C1Uf z51vFQy(YxL%fZ3RDIfE+Vg(6@bGNn*M1r%F3>3k1Z~<{n#5&;#^H?z5**DjO3*tkm zA0?S@vqk zbWy}$)O1p&b7KoCu(MmA%^WYeaq`6%U;gloJ9onACQ2XDRSLrw^mM`Tg<-V2utKw^ z-&u7SOqUj<67*6R8XA0bTw!`heix>ef~l#g{QR!$in|pRAzg*{9)3*-%xmFjuxz>| zY>K5sM|g*uS+$LGv{^P1yjewReW1B%V$EFU{W-kp(~l3Y9My)`+1t1K$w=EM7;nZZ*D2@WAm|MZXFe1n+&Gt~6k@0N|;lh!^J zm^Ca#1U4fr5+OY(Sz>RRDJH~ftH8mw!wjCk5z=@HhDdsw} zfO@Ez8wV!_28VJJ?r~W0;laK&YYy2)j?_D1SRo9aT>4?mNf}&KSGy%wD>WU{3jnG5 zT195#dSOx}C8S-L)33aHrM5{L(=q_jjOeYRwv#{;*;z}(<@|A?UQnX1f7w=X_p@Kq z;b`P;Wk^U?$l;wf9fpjSC-EBErqhvihtAA-YkID4-#?S|^4={t{lKcX1k+7WhMjYB z)A`VCJvSqW04Tj!f}Kdcin?M^JIkucj$Xbl8#5+^HX(&@dK3N@l3s+-8C)T-OHpY) z71G-e$L^5pMHMw_*Y_jxm}fcu(I;9|L1!y9X&V^pRjBV zobDDG*;HU5A3K_q^g^4AXg6s^YUY;V2A{hD>FF?fwQW&`n;TWOZfnx3xpX!of-#bjpY4rFuuO1^8Fk9u2QzI^B7@J@N^G+U-v-XOFnqhM+szHXIB%N=NZtS7a(@@fVI!A2#(6x?cuRuQrS>xaDnnqdaSj_gup4!^d!HBA|vbX@+XxdLx zIQjdvCw?!UXi?OEDB&++SjVPL)FK^@RBk$Mb@X*ab;uk6{Tnp%Z;E%7KPEX{^mJ_O zVo8trMGUmQefzs|!}SXh)0LXeG190wzw&8&baJZ|{c$RA5lYv_Z|O=ZZIMoZ>3bsv zH_&`^1@ykIW&8FPpLct}^o@e)-R18ZzC}BIVG7$dIJ6R16pb znn0$yP#~!lobsN+ib~AIvW{fCHf?uKSWa1HR{pm9ki@KQUhBQ$ZE|=`tz1+BXhiW> zK6OENnN(onm%3VEd3kefgA~hiw_y)!5iby?B)q767e%3(cC3l%vL(i0P?;6nDmi@t zbTyTFL91qgk0&txuMW||wFenkTQFN8wtAZIxH@s6m|SixuHrEZPm?8s*ON~@>^ zZ~8tP$zxP0%hpsl4w(__VyUNhP+g7Q9T+gt(ZMJ`P(YnXL2D zXs-h9q`L))KX(LDF$@Wx(b45Gw3L4=#5K(r?M%hwK^^73eO{FZ_s>7Np@LrS(pj_} z0ez`@u6bQpqn#IM-H^=~zDjCIX=8Ih#W9}g3Y`jVy8Pa8Nc=qnVu^B@n$mA8EbMA- zu4pdoN}T)T!w+A-@XkDBhw6$btI}^W%ptC9vkdbNU{7b0T3aL0v;# zW+(yLA(eskffa3pTF#!nQkqp=-E(E&bZKnD-MRBWdOYqMzcVA7zLxb#IBANK(^0}j z4i^vyx7{Lbp>IpF(^VNM-VT-ZvSu^Yk6`-Xl`r4D(gUVPMph@MJ8zBNx>cT)afpvt zdl625bmM`z)BpPV?Tekr>7OB|*N5mP_s=8udV4F^i;>bb&{n>c$(6)AL7cbdg6S2Zw2h8v#GO+*nw1TrtCujmj(S;ft9Phr6?y+UW=C*3 z-&NwLyRp&@ZenH_jOB?6OncKgA^}+2~j&BUa-9C4U7DAV9&4B6GZ{L_V z%S}ia$?QKC_V8%?L_z|k&v?4B&8m}0z}cFSRno+sqo+}5ZAnvh6Rk&Un`&!olZtAy zSdrYx(TSp_B33muVOGNN(vi`T&9sdv0@f2pcYgORE#Pz}%GMw^e{=x4Ni2)*>Tg0Q zomNNkXGg3$^D-v~-NdcW*~KSkCcG&4#&j0z42!E@1rXicO}LySccPjoV3lkaRXpkp z#nXwDMhUb`;IPp5l}ny(_tQP_bPp`-fe5R;Es~pFoZ=Hx6I#|Ekkgt+$!OS~4bSb} zQRTU7i_6B<8*=D3vAz5QkC&{T-(FY4gX{u6C!mqE0)^=*{)siagsxp(;|5F1u*Sp` zSJj02_s8woa$=L;Pfo1mgcfNoZE>4w|v8|q4Nyl}6b2huz~7`*1HzbLq855^0pBam{jIVYI7d##W6vQ9_{_Ad)lx(7g;i@e;NBq;1}6+?2tjJl39c%In6Cy_7EK!d6(JoJ*Js_c&-vJ=;d#kv z-O&(?b(usE;Lag2K)r=b9(W`647IRK1hj%zMe39ri|0i!U5qb+>io!Nxfp)&G%4NS zO4lN1gwy4H)euHiO0vuu77139(V<)gy2^yEVY%X6WdVo21;Evn0(QBjs9NJ@A#`gkk=`{#8pxPS<30jn-vO zB70vUIy*p4(7JpZ>=|`Za~Zi1QeW`Bh;c~%u0&6N<_E?LT|VIx`SO)+tDFi9gwvf&DB|0k5KpIBIqWX=qoVgYgXjq8n1)UCg;S;` zl9j%ho<=l{Z>oL&qH0d`Ptu{NwkX*`VY*GWg+;bSGC9&Tt&~!{t>mUi_fkzvHx-RP z5POVx)r&%FhYH%jomyHPHPi7vwjwrmpO^mZ+5Ph~muPPE;d^(0bkuaj^d+Re1k4u~ z?`WDj553baYWigF{G+dEZuElnL`6wm>pS!yeeH5VB&O^kjKYEX{1DrziVD4j?a-%R zi<hZAo+`xj2@@fpmlv+9ngqNSArc6SSHSN{@BJA)(N$LkP~nA+Rv`D2bX4 znOTLCf%?io$E4(1#Pr$Os?vf^0?!Ac?j|J6Jw9>%6(?_W@q#4s6s0%Oup)GUbOq{L zGmz8Gl9Q-LpusBLd&Jz*A&@R&dS~tIwE+b6CY&)uJ<32_UbCjUwr*A%k7jOs_2A_P z|Aj`R%JuRYa(YEb2XgtO_ax!x9Xrv^cP=y$l~_e+8#$dKQj=(Aeer$2o0+-uR$qKy zpEu#)nwZXS8uJo2ehr51M-4_0mpDjcySgsPjiDS>(isnE$S(bjczvKe8%odCMHV(? zH8m9!bZMk6S~}i!W@1darZ{*~m~Y|@rN8>>Pc%x82*8wn?&R_DnHdq&ugxA>lbf6C zHFEUfp3fhiZJ&tW%IA%CHjB3?-L^FVqd;80BfF%jwys1Pkk*be!K^JR z0@p9rHaA@?%4i~uzP72lI-RlvnGw-OR>C3ikqf1(8j(U;wlBxx#Y^)+P5$G_@#3XetA5+j}}K}^^_?%JDWK0dtmO181LrnOoY27pN}b? zsUSK-d0%KsrgOyZ#?0U;rW^k?e0u$K4}6dJK>0eWmVwaPvR$+{3JvY|+}*#UHH;$C zoGm`jRMilmF0poLakyN-(3I6FRdqB!O0)aP9)JI|6ZV_@{Onno+7vbRQn_nHV_8|1 zzZQcS5gKQ=YlnZ_mg#^hzqQlTYuBzgu@SEFk<1r>!eD;s#_A${jEX`0u`$BZ$F@^0 zItGmsnNB<-lDdj>8T$q&I+dfGP7f0CLgFnKBBuZ2>5r}qxJLN*?@n_`!R*qq*A)kk zAUe>F-K85!-*{r$Mb?nVIM(=5cMFbn)}BbQZ?OW?M`OCz+NW4?SEHdDgj9E;e~WaD zGOS@Tw25tnRz}k1$qqWlRu4!Lkz6#p5p8@&=XeLRbr!?t$Zl zhYP3s<>X5k<7O|1e4R-`LP)62q_Dw1Y{P1x5W3b9Rd~LL)563COc#fX=;%V=g6W2w z7e(n}7`M0I2&O-0#cL>`T>xHUW~8okwUDcZs)CEKrPK~Qx7v_PqGiFLr9b=Z>P=~T z;==mD^vtZpN_v;mqB=0xPVE@pgY8i^7lr9SxG4YZEk2lRtA^<^N0CGr&hjY?e=0vD zNKojKw>3nyYnF5ar)!G7QA<}?u0gEE>F_u}s{$8cZ3FqLB?acPBoMBBOg<CtY< zwWFgSy?>EDn(u!!dhw&$wq*P@I&cpg06%WHC6amizJ2LM%_zn}v8fbpni68ii3Tw` zn?OBI`6QC5k++MAI*U4ka?w$9x8|CjC6;C8#^+*9A4g0N$MJGNYjLDB^~H;Y5>g>_ zM08>H@JWN3-h1GTcwWxD5T7v8c6sKtpIx{x6Aq&n4TGE!+1=4S+6zxb2&Vf=r*`kj%ZI~{&R_ca!*5SKzE|IjHGODm zq<$nxOcvR+C31^S*z7fN=e;*hzV_N{Z@l)}n-@rQdGPZ~H*c1HT9TQWn43G2c;@J( z^Iv~>0ZhDchx5a9i<1QJJS;6lOx14jbcgBPg^osEjRm|c7N%D`Y-eZt+Z$$B~H?Y-tuC%axO7q*eOaAZK6 zYNQw0R+}YTM3On_h^TJCC(ll%_7UGp1{scIz2JK3bjwgG`aZej+^JD|-E8ZP*&CWU z{jVR~s2y(p3{1Z_T-e+3g7;gKbSRP@s&rA+_4ZEEE>sN_+0xrV%ciYf{Hpb_muBuv z^!dhnd&_U06Ej8N6?%1arYlzLNN7(KeXE7k(bVha6{;IvO0MK(Cv^nuWQ)xznUohe zo%&G$b2Z&6ux+yK>MFD?ptJ4JRETvSl>XrD>ri@CV`JPNlF~1nycK?6=Ej5D*RRcH zbx^RI8tc1luK)9}hjZ-{zA`sivo+ehgZ8Y^Znd>rGq$d&&T4|xYpY92x)9V6&xhIw z%@GM5Os}m4-@7t0*y9;)8R+RsPS4gSSqh}*+v+il>yW{~?gT5Tz(}^)!iZuj2R5u-i*V7g0aXoP2+KaA*)(ZO%s4?Jyh zcJ11*@&qX!o6?HyXaH(OK>7|(B2Danay4_$Mgl&hD`-q@)Zn|@U8AD%`qTW%H*Fw} z+$W-;+;42!<#B+=u9~sqBuJe=Z!~v{egFU<07*naR4XgtzrEyDps7EzcW<{3 zMwjgprA{;>N$KB^>q59X?Me~Sw^K;EomNNE->6t5bb5|58c$<|*&c!5A{C^kKRO-J z@1KKL+@+s4_}JtF?^GF%vF7)D8S^aDE{PP!^(|h*@%@zXdFIQ))oPFSp%qJd(oD~vQH7J z=iER z9R}=VSqv2zlz8?E7b-}@^2&}9wjG>r9q8c2Y$6z0UfzSvQC=Luak2HN$pNzn!E}w@ z)kMcdHeJMY?r<@hUZn6*LAt=E#-2(q)--f<ojcG6otZvvkrWR^R zu8l)JoXkF+80-Lpnr>K9qB^R&8iqZ#kj*F#bjh44?h2XQ`PK`4Z(*&@?&=_#rZ=RpS7G|^RI?+@D;<*^-n1e0 z^-buzGjl5(9A-x7l}j3<%nZfMVMd8^EKnLdb-%QyU;ed^h`4ekYPO{7%%L;Hyr8Pn zfmBEx<4Z4kIn9<)(-lD4tY8zn`Rq z`K=UOYkAJ<-MT2sqz2+Vi|tOhoN!5Ld4Ank*$%t3>F(|gV}5aUQE?KBLL|(z{f6$9 z-ROhRqLq)<@JI|WFO_fKE|`wj9Bmyrog5eNT)gYliI$U?PRa{wxRRRD`xm3ey79KB zxDqjjIi0Yvs{Y4*B)4>L5HURl>eehTg6Jpy8@jnV$s0yA64A&l@x!1l)7+^vG^YCm zfsA`!iZCXBlhwKv$ms&QQk}U) z^moZsf%Fv?L+2W$8!%m@bpxfd(O~+972;fm$^kr;5JF#4Y!bjXxr>TcVOBv!b+MZJ z$b|tbMQ~S7lX&ipTLSiY=JdB>hRrNVBrhc2M3>dT@d1s|4VaGih0n<02W_w@ZWxi! zW#eUr!3;$dcvc$zP>e!4HYkleMKe}5mnF2Sq;o-7LGncjT5c}Xj4oBpjY78Jnh(P; zkg{AEhFZnWl@;>C#Ob?(hkSR{(lzp`oHX87FQ?u}UQSMOp)JY6!Z3*Y>~MCuGVCnT z)zybGe0FV;BA9N3b+vP3N6CV=!;F`(I?ayc$bvXb0QZS!@7 zC4{Dj>g$JW-JEH0FJ)%bjnb-x|Jf}ad}&w2vxU;*qfO}ZvRN>FUxIXe*$k=E_GSGt zmUDAW3z~|gS023=0N6H>|u9 zu9cXsIy|}Ri1Ma`=~6&?W`4(9Y3b$n#Pbra6AG7dKDfzNUyvVy&1C4_JxnjJzZO0M zpaaPa!meY3+-d&k8|WS%ZxUEZH>70KKu7oVthvl>(NaQs{_(wuq-2OFkUGxxUYZfn z&t~7gJ}lQCUwHjRLG+g;0rItX-Z_5q^M}-sHo)mqxd~3;$A5}=|MHK88E?$YALzBg z=#rYGrw_fmWxi!ntTeBLj=4x}E^-4~0WY03kv;kO!s(>&Ic%$;TX8`pV!A0Aj-4e@ zR|iXHiAH(<%D|PVp#We(UP4+WFbpM>Kbxot-~3^Ocy>fBfM3qqa6W9DR24 zUQza>aJu&klQvyh9nm)VIK#Vy)3Li~V*1XVx(ThiQAJwj`Cd-lgQ%=HVVD|32i zKM91=-bfM{?Kh@)?l_v4Bh(&{_7gD7V-ra3lTy{wh?-uGV7z71wEdP1-K*F2m&K)x zl~2RNF^`MO<6QeATT;GgNAgX|o|0*o5!F@T z3zIK~aJpEDmZ<5tRuS@W#_F>Y-Ey5BZFGqxN9$@5P3!fJ>84HiV8CQNDDq!AGcZ$k zU+P0S5sIFWKrbsna@2G5bCwKWoKU(u2h+(Bzj!+8pE^;}+uA<5GKy@Q6qG~-D1Ayr zzy#PUQhj;!zFZhe=oef}l5#qkJeUE>BCfNT%o(3dQ9*NTZheJ5wxoCMs5nzO#keA{nH!781B-u~59e>lCjBblt1B>AH1gYxq$s2&|&gS#12AC4S~ zbaZyMw%kUSSS-vII=Y^c(PI*r7@VlOt&bj^IY8EnlGAa$-2L>^Pd>YsY~JA@_>Ai%pI{VSh%I3(U7~!81TM6W5eBor zxT&1_j?9d=`{w3u^^V3Ao-6BQ&`#4Uo;Y#t*$1ds42|~O9K0!_y2QPARaZyvbWmFQ z3uHcup5BF3sfh2a2m_MDy&$5~o~pTk$zf4;NJv35aXz{6FU;INcl}k|EwfkR!hX(X zpE@3%zGmm68;I%GdfJr3g;M9B+lCsCsmibxqaqJAQTMF(p~mTbW#?XOPG!oKBf%pqO0(MMS4;n^J8j zx#k8xx2^Qe1B-hgE+#I5_D221 z-OqVs)p!=irR~tS_FwAH33FNZjJ?j^js{0LkB`}5DcP`ML;sG3I9ihW{e-YVsJxi` zl$5c!C}}7vo(^d8#Fi6lTUMu(mF_OLn;w(w7rKF#H};g3MfH2yc}#EGlmfyaWJ8YN z1&v7!gESV3M8Am7VR6FnzD!fnk7xWoF z{Y6An+%XUP6D=E4T6|n<`aRInQ^-pfcgt_ZgO1-t1oR*5T^<(|1H!Yc29B6@-Bn=v ziI$e`z0bdEG`+x;h}L4=kdMSQ%D5lX6gmM}(U=HKH*mbdcPQ0EC|%YHru&s+cJXl8 zqLg(Zab5vZ2lg?jqjYaru~C{E3Hb~E2ei7c-@IOzn3b96wb{fZzos?MzosEz#p)Fp z%N35x@HTX2|}K zGZ>GYE<~>a-_^uogW)$%)L(f+gMCA06A-8-AcLvekPQ<&e*)53A^N`oa5erlPC68g z3nv?Xv?YGuBx#aeU^r_=btQVssy{OR*jiq~_(-)VFR3BAQCH_~xkv6$XSr7!Y=Cw$ zZm-NX3?G4OZ5Thcx>mbFlhak^i-L5+g^|*kN@@NizPtrB{XZN3w)dH01i;&Y1zbO* zPv45kS(kOR?r89kWm0{5ZUO1xR4$@#n>k`%FDNXqw4kA)dG1znTxf?Ygf3^)^n`uV zbClPG;1d#Jv9lB;1q~Nnr03=EN2hx_+h#>g4+?UNY?hAqP&!PTTG5>9B`=VRR?MA2 zpeW&VL5>p1D4C4X>xd|If%GKKD4Ds$fbVmQEUdYlIdk>)%XBw7j)A59$g1$elLm9T z@VDsa3w+LkDjgjk568yNkXtI1aT06#S6I`#5`A;ywbbTVx}h*V|0$ zDlIBd(?5Lu&Et3PHVqXJ-O}7l*COE9*O$V^K=*`r-$0tlI1X3Pfhd)^#89auy@;Al zs7+#;!)(2nn=nq0=9bP6B8*O)lZFB)>EpRoZQsVKUg+ z49=G`6kke(=jQ$lWTe6&|?E|Wq9>bTS;4AjY_-gjiA9z|Ws724WHqd;}~5z(8p$jzG)RptWd z=~AWIaVQ&m3x4pT$VipT7*dE6gx`BuJyJE-P0iivymS8cgIBL#zk1{9wX0;jJb3xk zYj@%^GUjhwgVJZ4VsojJ75BY-iN0t3kA+=o4Q`(Z4BinOQbJmKwwv2fQ$b`=H3i05 z+0ofJ&}qn8O|;AC#ip*N>W=K%tgh?~=R($I#HJRhIsoBxGjnGQER}?us`3H}MaMp_ zfSn6#Yg>v(O>Ip18YJ;OB;UryfexZNnO-NEg>=;Cj$FQVlHALa<9*UL7)-ZO_H+{` zH#4Gol9CwWaMg{_-u8ER6peJiUIp2cGVM@9iG=V0&ZS z;800a@y5L#p}}#xcc+!PztZoIp6<7D?+=5IQZacfY)@L+9zSCL?EC%mcF|;1(}~ON zcEzN{c*YI7ro1$^$pbhg`ek~{i4EO8#ib>l)4M!U?8jWjp!9*!(VEekn$mt&2}1r} z3?~@XSNlAxVqX-g`}jyXsj4QWe-Rn#?}F^EAAB)J`%(Cu6?kC4bW$bg&(RY%hMd0F zRWN;^r;Ns@CpNaUq^xc!D=nj!k(P}Pi?3AOM&a_Yly$t#V3|jYG$G~Gjoo2w%ewCV z+G4`i*IMmex80bVE`qhhu|Vk}s)MAUxyuF&A%N0Kdn9l$Tc#z-)50S}9WPg+IczR_ zhkfB8m`DW@oEe($mB9b3!8`J*S{wS;`dC?s zFC7e)tq{-`_D8*kkrgBho+~8Zz$an1s)AC(DjJiD6P-Xt?g1aUPZ(1eeuad+2qX%^ z8xT?0UAbNac%{D)h|Ysn(xoY24~(AY52pM3(%N1`27YF(+@W2`Zuygg2Wn$s!MK8JwQk{6v=`*k@cxGP(olY3`(#1w zd+i&L55|y>xNv%c))!qbd@20$8Ps$msDtUGGHS<2G&%i;KQ#VRv=6!1wm@9iXmdgC zNv38FA(x3`44u+fVErXYP#Uk$hR6aZ3P;E-OzD$YKqRx9uU0*pkRY~nq)w93;V3|z zm=_EQQ$q!*ZnXBfc>1HZ&QUJfFuio9rzVq5*i0UU;4H?C)TDY!ND0D5>V%?-u&YDq z;;3aAGMA7>F4c9iqa)kIOBcAUSz{iu?ckjoVETs_-cxamtAKQ|y$FGeOI>JOKz)JL zxrv&tR?CGdC2c>X#PmalO3NB*#>erzTo`Y+jV!Xnz*4EB-ZM3|K3g|AnN*QD_w|Jj z-+bd>1(6_}3Wo~F#1YBT+QypryabHGY#t$r6~pQGr$$2OO1~8~eLOHf`%s6IlT_Ve z-p0AscVzqxnv4GIopAvD$OOC1mk{fa-1@oxh=(`t->V6}br4QJ`{wI(ZhCO;uTR)r zy#c2y*9%-l-Uu}! zIi|W$|Ep2R>9rTJhm;K^jLc1+_}kXL&0EtsltB+5Te4pM!1Y4Cs*%zW(@A>C&Ng2| z2Tmb%TrarOuS8w!BqC-Qgg?}Arb`M)Z_GZbD|s|X@$1YC0EsUB_U+l>;d`j*pAFSJ zcl4f_pU=X*o>^$(Y(`QdL&J1M)!sX+JItbqdhsIRrLRvsQSsg&daf^&o{JegKHl4j zOi*{+FbL|@k}`rSnn_iOx*0(!QsZc(x1w};Ib~1pI7A92MFm8Gh8)hCryXgCEuDlS zBQZ5G^|aJEc=z?r-2U~uV$g!3#3ceB94jd zGYR(JbL`S92lr>b;vW*vaeqUB4+Q5#y7 zu8AgDJ(_j^LA;RcMUrChr@-TM50m-=4unYZsfs@pRHs0Lc`|>1W;PaN)lkx{(;fhSx-yg7X^)pq8 zVPVIPk?L|RZ3}6BF;z4mO-n0IE1xbePb>DU%4_r-jEbPGk&Adhrl;+vH?6flVPzFp zS6W=YD`iY!ddxsiPwoBC(9qF-1a+|U1Pza5tVQu%N6#appuV@8-bQ3HqN)?Nh5JcN|3=yw-E2c$>1m8BD|K1DxBH8asA7w{85iJ(!DeIk2CJCTsQwgtFq}$J zqSCvk*;sm$VstqH)sOW=rL<5m3Z?&7iGDfJO=>)tF6jQ;-r^j?*C-skb}dwC;Cr@)pgJ9Y?^&J7-*kR4Fxhy>-N2+xA`!m=_8 zu-lzUgCnodLV&93YRNPe-6*Of<_I~xnF{9c84)(+rgmtur9MC zG&s0nH?s_>3YD!9To?S7_m^#zt(8L!BBi6P%d|u=ogp7%0nrgiNt)m9lUWWTe)d?2pmm&tIvKt7=whAZucCZ}@*#AtfaSY7Qlxe#j- z=5(>WJgfQBmteYduCdeuoK8f~|@Eb}h4epbI z+~~h4IVX{(()9=<0!3?bB9mEMv0j^(5lNIlr%;J)!3<1Zw^GyF+TI@=Z6iRi07^%W z6tt47t+~rYjZY6kd2ebP!X!PMRFs;W3Zxg&TqiX(SUJib7A#x5zi6Rh0rx=J^TRWq#+uncS$>-vtmvE**_mX z*wmDdgQcP2sLwunUY?<^Vy z)oT)iFNXw6Zu+;0BiS7t8Q%QO(zKFJMn{fF!po^sZ@zPY6v;pfBJ}8~nOyBwQ6Jix z(|_~+{kh=Fmje@g@4P|J(+4mAmmi-P3%l{v4dnD}1kwEbK*xH=%1RIuYqMDgEpwV8 zrBM>8kogqnx;rKfMHac41HZP3!F4rLl5<&4RE;Aut-z_wM#1#=FAiRb>krM%y?5+K zbU50)Y%7g;s*`Ony+o3n{=~@07GJasRYIDL>!mP5l3uX1XJib&KRa-3U;ul1`fx^d zb;qGY;z+-7?M7?sEurIi?XUFO=Y>06 z%;`HdmkRp#&W>svB+VTZOxW_ggOO6#D-F`TSQYSq9+pqFZW}6d1XA95n58xWRnpD zzYnLn(ZvW%rd6!i;jsxtVswGef%E7N8}YfUam%(%s$ec!&2*F7=1AN8@gSg!jt*rj zC0!8RoymweR4nzbo)8=#8!PVb ziFjO&x_)9T#pjv5yBgwJy4P;(W*ZqK&vg6v#9?~rKGCvr?_Q5a!*1DRPtLjGPLZ*R zZP~C1#8#>?yk;eOI-E^vBmFjI5nBgTE`Aqff8iN&_9GM~AWfw7En*UKuyPVO7+xwd@nWr{{B@}VfLyk=mx=IhRE)`4pKVw%T{4?hkl`9dB9pF znv0%}tgSBCuL8gvvQR@KbfHW*(&ss)lneVRb_5W$ve6aLz38>_RB4U0af4r)XHH(L zg7k(R4Gl-BBn{4L2#^w3_K$2A{4LHM$+OWgolmH?QMN?s``Tto9W27SQB4<0HyB>j zJ1%%U1Wz?|<@&orglJ{yR)B5|H(E5q;x+EhTz4b&URb}hPJdupTu%2uc^pQB2GHBo!4T zxuLDgC@8?#s&hxogw1_bPjl43{CrUvf%RS#E3 zJ5xMrYK^Bqsh}v;*$pcRO{(f@LWkOhDpHfCFgD=h897*WWpH+IcJzHB3~TQC9(+9g zUq3%fb%9$!CkQLwa?y9p>Cx4;$;$MSj5(bLFk36^!1SWB)3qW}V%U2+hpRiQGY*02 zUGp=Kt~{EVpPzs9=<4ju%=isVFAskF;MHpv+lFzye0FmPOn>1FM)aKyPDFWfC;`(; zNQZK#6ZQh7a}jwSNEvu(eViyrPA2w_U#)N-4f#aa0j{3bCfU3jSxn!iOc<8e}3r|^3#Je zOR{XLZHAdA6eZDe6!Vactp#d2Uy+*|)|U=U`y^jRJ9jt$=5#4dPEAS*N-nTPUEhq+ zOnQXD=uo;esbV0fb3;I#3{-b_P}|yqfKnTsr7ebZj+Qu^kt$1#=UCqDqSx+DSf8ZY2KG;}Q+Efw|v(aZ$Nl8_)eR+S4 zS8z^nYup|es~@h&%nN&LXZJYIZhGU!)z3%N4aR`H<;AXX1D@1v?uyvGtF$i9GseRM zx3!<&PyGC(jnV3u($R=C{4Rd35%j2_4z%30u_pBXjo+=?WpObFm9)?wD_A}V15}mO~>on+MbAFPtO!;Prvx+{hq19fTLD_T~rBuU*+Ub=4Yz>q7H ze!^<+-j}KjUl5Y8aOftu7ZS$sg2P4Sm56+dM7(kBCh@U&5I)GK<{ojyFc8Sqf}J2Z z51_x1onSr>Mpx%Wcs>L#7ee={h?M29&;&2*;Kbl8Yjf0ehtM5j1o!t``RvLSFt?^d z^Kv``DrVmawJQ|X#A`%s727Dr5~W}ZORB<9D-qMVp`p5DtFyeqN10v>h$!MN{3juq zsOgZgFuIk`vy!jAcFUd|fB&*FV$&NmN^dyYP?D7ypr!{}rKrc24ff1X$cY#0i^@jd z#4!Wr3tDF-p?9Oo4%8byBp0Vo%QU=5MV&0$hlIXtJ!vtt?2_ad zuzf4J+pt-BZaVK%lthPh@mvq1u4~1m$`sR#KO6pElb)5;JK0Ws;>$08_y+9V-cCg* z(dh<2=gNTSTxm-OFt4MgFTr%~Xm9UQIWHYUbzNPRtKLIQpZQ(;h^0mTw#seWFh&$L z4_DMzR_YupFpEol>D;|-2eJL&FK!}UkpcT<+w!SM*n{8Bg!E>UCx{1r{9{Rad3ZNr zE0|7Oc<;U!?%a9jxMZZCI{7iZ-A5{I$QnU?mrq<2R8dhqU)6u}=BJ?zmyZSqdL0>m z4NSlAGOa?dqNcw?6={f+4_Zi3tBw}$wvjd+Vy$q?CaomdP1ud-^CW!*L4R)91=VI| zLp9_(j@C966%`celj;NO-2>}zy$oKN9UW|pD7zbb_u=&Ppy*FZZh;q@L9Zneby-k?g=_*4eZFZu0zd+*4u24tsn1n(QPl{TyWgw><|3`}=cnyr8AuI!KFFX+QeawK^Lt zFY$dlZETrAR2LMmleX^LoS%8=>&L`0COB0VhJfOc$wef+I2I)lHE)(}5hRC%aJHbM zo09}DI~B_d-WOY2jzwW6OKu|ZRLSWWP{fUHVx)9cNh(F8lzJ)?Iqr06^(AsTg(Q~A z#GzYQQrT;2;b`fm53MCAF9N;SXx+<4r5KvBh+-R ztj*lr9huzm-9E*1<3ERgnQOo0%a`vkbYJ;j`HnU6!gl|zSG2bO!4{Wic-j`Pf7kP# zKKTE@J@EYYoSvGdQcsU=AD5EM-7ejBc{_p|P}9RaT~_-1=iRU1dZA*}ZW@|+X|{A% z%u6w_H;pHXaY=Wlcz8DKps|op`m}KRG(jd-Db%DE)3nGlE}|b{d<;ZR85qTyP6=s> z3k`#WGhI;B5!6qtU9sZ7uE1Su)YG}fu0kJDq8LH-m>7vl|3b$0Z*Z)W|JFQQ)JCK7 zx+nq~v9a{rjEca81M;_6b;p&B?m|cB4N=lv2l{)W`e~8`rNilapBXFbC;MF(RxqB^ z#%?RrbXT##SnYkT#pq2J{071yPbA3as%eNqW$Gcpbj;?MP?W|k77t*Xq4aLK zLwxGoL{67me*7qghtidZPIW2}Z^uJGd=D2p|NPC?Sy^?#+elI=Osv_F*Pqj$m*WDz zit9y0bMe=REYF@3a9652^o!#~E~E{pEEtARIjT7YuPbD6K~aa%L3O33!-2x-f{Ru{ z=Bk2ponm7H0Iq&+h2L%r>1D00WjJ1T>_Aj+kYL8lnj9txRI|$96K!&lkI1r25oCuE z=)!ghrfXZoRD-+ZQ!HZoLc)uJbm8>HVbGIhV~j&2bb|=3Kv!Sj#`Xq{DTJ=A1F`fXX(qW+^CVi_J&3_SIjP(D)R`9(2cOJ z-BR6}mTW z8|vyZ3-yJC^#7DH&?H>zG)ctb3O1|5_>S;gaahfY=y|lJk3zAZbd52;OLOx{T+u794F}I{2O;x-MQ0#Pyn2)7vovoT7+`76t1~l zWEmIxojXS=&q#BlM=vH>&rsLV=A?-b zwd1IaFI*7K65`OOVLJBo&YshRz0B5jcCtG}O@HCcd>uiIGP)kk&iD4t-=GaCditx^ z9(9t*D4j?%p!7+UaHR5`P&%A$M$8~y4ce13=t1i39UaY%i{6TW4xanQ^FyqQmoF>4 zya04>K;6sR$;-EIbG(z&gp-rQq;Arh5OSOBtkTAa#+;}ub4^aCSoKgZ8`IliL*PqS zNMwDzyIE2}V&YIiK9+RmPm>2`uKonW%U{_Iu>W%|eSYfHxl^x=pRI^JG*27V+c&Oe zx$!%hYgUPM229VcriszkHT%*7=N?`n?q$NHu%xc8$%082iJ{`q;xEJzNGC^T>l$Q! zZ?bC;)8!Dv)(oWf$mArQshMLEeFX&gvAwvtnStqi3N<9)McLE2rB+)9R#N_HYOS-d z4JojVOg59=w}iOxHl~r7)|o}ehxs&)?2g_YO2cjY#@8WUdFXN=UbV5hJnb^irWu zGhLgbqPBN`@lQQHQ3HNduHr;*DUa$I#c4iP?i%OMOajkM`B?ebbW6$@F7#)tB1(!^ zbgx`%P}0ep5lnXt9YB3gp&)hjF2gs3;Tj2D8LY+CVdqKjB=NKW+??>hfayRu>N(&p zw5{k{#Bn*xg+}3c(=ofq^MG=>Qx%({$4ky5>!Ea>y2T|R)5|N1Y1p&9}sV3WWI zr320)Wp7-`O%ZQbtZ?x}(`P6(eMgyp8LpR_%%e5IJJLXM4ZVfEWx}BlT&6Y58Mt7q zT_Komu;Hlbj>?8H>|qs`F2o6UiiG~e&?NK)IbG!!swst0idMAy#D(H;0~{||Rwi-9 z(Xu}lhQH5*qNp2A22?jfx|q{7IbA6Ixdqe9dK(=g9hg2fM7$st*uvnt zqen|Z0t==b-SKfq{U)-VDzqa8U8*^Q+@z$lh>XU>g4iV6BxiSbC#TBEKrp>PA1xAj zLjBYT=t{t1TWu{>BHG~Zu`QC|K8bA<*Nb$m#QP#ge+AJwNnDIvDjP617#gb6Vza1V zsHlkO#-a)W^kUOfDI?vQTiDRraFl!tyygNCl~T$V*g$Cz&P zri1e=R%#Wb-qAsHjo<&?#~;4<+CNVoxf_U?S7)Oa3wm2qXJzF!X#MV;k6*uV;ql{N zKfHIhVyK|26HF)5gXXC)`n~%%zZrY{N$I_*k%I@v=f*#ll$Z18r$0GMU2S|kW|#Ng zpxLMzC*Qb5H>SH2sYM(n0JN&j(m76%lpGS0RTuTi&HnqrbVu4hkx@G&oCpSO&1WG@5?&S+Js}5FV*Wp)xaO3z)Rw0z` z#-_^L2r~}o6n z)5omVdDMA6U!E5g7ZB#Z!@nUc?bsH)4?Fsgk(2J?hke<;s;;WBtgNarE+)l=veE7q zpOyV}{{4H9m8Xv#6BZ>C`Jg-n@dY3~olqVoI*bwN5;6|6XJu&DdE)<$5KneJZq zgT2OSr(il5HNtV1Oaw`lM3P)Gwd7`e%B9B*3!k;c! z?#Cl|W!QBspshe&sqskbd4=(bp;@7scuPdH-qD&zA6SY5z-A2I_B=~?7)WPxHf$7A zxUjI|VT5WImnAGI@;O6spEA9$Vo?wVAg!KzR)AdiTq(2Soseihye{D4#+7m#aNL07 z1x;TteTkTURP^+tyX`kB0O!4VcPL#dNwtT1f7sOop)ov-SRdV!q2wg+)g-Z>{HNS}g&J{Ns+4{+A!@gk;8g`TH z%O(3$J^ByVXfGm|&TFe7*V=8vyBTh9CFdnWI}%_x7NBsQnaJX2mOY?;inj!yaD0*#WIh%o0Nc&N(LOLPBe(0nV~^*SY7q4@C;46N>0) zYFnU>EF_!{$ROU0g2ZH!)SL8TgrUWclY_Mc!I@6!qc`I@&vl#yYHWFH)tv#n< z$tIydQ2-rN4CWUYTyn%o@(?apv5b-$vq16tM6y)09>l|gr1-QM7Hw|k@eWzR^Op~t zd>KqXj+(AqFWAvVOqY`e=?jc*FuthUh6_0U&Z$7(gCf+)7;JtSc(qE?}R2mum1MZx{!s^b>)TCrGt<5kWSnIdxvAGw9 zmNwpecr!GUBGM6G-y`Ecd-3(3z5G|VueQ$II8Ju@nXZt00Zimr3!FAYmjLRtOd77{ zn8R>TEXElMQbnE50Ma{9c87+hhC*vGv;@`Hk5m-!1vDXB%n~k6BhsqTdR#9*qQlX8 zIvf=x)$0Y*jg3eNT-3l)Qq#q5!QflR{i3t9Q7A7Ezb2z=^fZ}_r>RT5h?QedNp!*wpfGKuSxK2pSyJIbN`0S%QabbO>W6< zWab2=2Qi6FPNv49C|SgGg3&v4Hi+p^x>WxUna+$J1rqUYDvgm$<>aUDPyY=DpH?Y`5LU zXIAIs?eRS3w+REriWssE8>$-jq?O}%DEHgcvY}fW zQ3H^A`52G0-vFPqSh-aB_dli)smrDmx*Q>HgYSNx5uSeN>98G82OyF`B1!5$F#2Bz zeu?=a>L#uivAl4}N!0Yg(-EgfyEQCETTj3BqXO^DzUBrKJ(B zNw5ChAtEib&CgGFkP!D6-;Lc@#CU_)VWK5mC1?{ z*j0flm7$&ufr(lBF(M*ZOCzD9JN!9{u|?V`3F(Ss1VmT95f@hQ8p;SRoG!JQ;!RiD zujuI1<${F@@kn&khO82)S1!SH6}K%CEJIl(2;89)5^$~@Fe2h_!0{rOUPa7{IMad5M6D*Of-*tlSl%UY=zQEYatawqSFz9 zW62nVwQ{upcJ1G@ebfyK(5r!Z4wE?tIU*US$2K>k!&`@h9NvEi)62^remsuvyj{7@ zp>ru6mBHc?RyTyZXm@Fszauz3q)UQc&KzpO8*+L44LF)amCAZ|nm5|m==Az+1qGd* z1T7X7O-MpF8FIBkwhc4gt0>7)~+sg5o)4uQH#eDL_BhemJqN8qYKPCw`y zJF)7G4`2V;gL6N=U2Z8u)d!K#s$*0YCbAtfXed%UmQc)a>Azd;QqX~G476?suW+vy} z;m~2N(@pAV=;Po-2qS~mn(iurQO)g0f1%4!y@PeW%1EDlVW&ffd3tIs?XDxDM%!$~ z?~V)pOc&BPDVzWRAOJ~3K~y1(jF3slJU)K&J|Z0_vo7Dd<$v|+FG-7h^{+gN1=0sT zdHDF}N=qNFw9cBnar^eQt5@gW%9`(+v^h*^K(@-CuZ}Fp)^^h7iGvMc$1XkGKM~s6 zU=vM?CprE@+>1DmGK%;TGHCgQ>JI*6nDH+GCQskv$vyDr)pUnv zOctMFwR}0A7a5^dOIB;Eo?d>>_P~0d7Ls0uN+XK9*QLaH#zo~tkeagNU~6mtp519% z_O9EVxqEkj--!(?SFhaVUzOJ{W^2@8fYUx@<8zxDTJyr}j{VZ_C&ysW=`CAQUTW!n zH)`N?)ac+?iiiCeN#TMn>--3KM0=k0BfC*)+(aZ6_xJY~+m&M>*&v}WaNqBN4`jh- z_iDO2ZAMYXak^+~y3*3W7@#%jAf#S9+!;0CdKzEs&B5X=v=rUg()~eH&)|UTl_(lv zU`TJFq!dg~Nom3MLIr8JYgHPdjpV$v*iS1(U8(8CZBck$rl~NsdfxEu2};A!ur@I! zFgLM;p1VE6JUw^s5*G`^4UpRV1*BnG!MTFG?k5fw(bG}g#c(dq@{?VqVLBgOj4)C( zD$W%{GK}JSa6N5LPHR@;{?M%88l2ym5~xxKrw7<=!bPuK=c3+2|6-Ka>RL51U5VMk zzv3-Hw-#y^`C5=&Lf+|*1i&*4gsy0PHEAHot_sf;q(A#C&@8bbFuKqmo);Q0?FmEB z$Mqswx`ETn@TcQ|DQh@tCsPNtIbgaRBOvoeZJ%t$7HM?Ef~eDL<=BBtGh}YUc|lDV zOou)drn9gpp$n(WX>ll^Re&zav%+zW$>me26hAKwj^t<;y{pQ=> zp8qXBBA|bGo`guoiyxl<@QpYA@Av-un=tx=m*Mm`KYnkVO$4y&WB3Uy!&s>Dpd(ZUJG)PR-5B~c4m9FNtk0g`vZf<>sw{#tHGsCvc zaKO7Q+O|VSMu)SvKqQhciZEijK~DE}@Sbp(AVu8TJ=QrkJvSCWm*HgMx>`znLG+__b)`}=lNF+)w6*In`uNPP8=sTF_&2Zq)vK@m_|=%l z1E2KYeAtTD{N;0}9=tQ&?xlNl<2HSbsxo!n`@?zN-VhspPtnQw{K)BKw7}io4#5wP zQAS!>c{I4NNv570_Tjsrqi*`vjO1$k@Yx+Qp^-;Nvo|TlHnYID5=h%F$7HgBh{DXE ziED-#okO)jji)<*QS1Wt0heNWac~HBTqN?Pwj#K^k>!d zoaKu=9s<=roud7zefj-c@6$3?JUCQ3Pz=Tf#BoG1ZkOMQoc%jm`;Vm^BhbgMFlUda z-A1xNHU@-YW3gYmh4ql?wEc<}pRmjwd3%(YK7Gute2Yi9N6hvQ_*ZlwqGxohWo(nn zi4#;eZuGI*)8M}+&2HKQd-^89^cGC;Wn~eMi__AkQ^dJUmO6RrzXue*6Q$n$+wI@b z)CfJDE=S)KE1No!`ryU3PI{~KP%_o%T5fN@v3qSxH`esQD@gg$`II_T@x+TQy=8i= z8#TQ=E~cfMls;lzrny_|Z`8eaS7;CM>SG&y_FA=Y555bf!|5W{^DOlQ&m8}T zn&7Og#6&o~37*ytBHd;#@ILwQ$MK(mhSTJ4LM}*N4)j41RoU5~9VOb5T)9Vy- zghELe6Pkq~r4cFK^Jjmk7+t_z4qw3R!g%6AA;w-=DXdnnRUerKr2Z<75mYY~JC2l+ z?$}Xw)KgN>WqVxg*P@=w3_;vMYJs;`MtL<`kXeJI<;bSV$$0!tgY=~s`UIIPMi+eT zRxGOlt>Rh5>gpKD0;Vt9Y$LKb zp>9(_)QTqQ5;N=Sjuz?)x0$)?>8VJQMoZ|7E-+?VTNEJ!1UW+VkOYT@Kqj-SHGj}t0N0dGj z6GHbS+e408B~V>TBc%kvbP^n6k>4v)x9+nH4bD2e|M&$=FXvIy#q+XYJJ$$Z(0mD_ ztHnEp*mOnn2aX&$a_FK8dg&|~IykcGA6`54v)2xEVP+{HP9xhk1phFZjDqRO`G>>b zLrnkgqNe})v(N6|zuy*`cyQanv-i$Ee0+WyLYLF|ZzaZkVO)6qXFnrV5heY?@#B{d z-aTA7QMrvKp=OSqU0qL@Br<~M zP`W}(+#JoxLg`c#M<%hV=1rE+xc)491G;c~>=SfXJ&**z zslTOnDOB%__s44@{MIE&zdU#HFwIDL7)7HzUuHZId91sm{PD_<4e^gM7f|kWA^7hf zkv!evKe`8g@aMegx*smVbUgA)ZvD|0e7f@cvj^69dw3L=hL%Re(1kOgsy`Bs!0;lK^8nXSj{j^PaV^D8g+@FIE5aIbcJG0EHzB4&&SaxE-f!-4Eia!Y%8xk56Dc(4 z+-SdY?eC?eaqrvD?Olj|@#)6;BL6UdfiqoF8u6!p(Rh0F{o2mjk9zJ8Mnwg9peIA+ zdt(L(XWYJ>Mx!(&Wq{%-K)HC+yM11Yh_Y*e9VOuf&&z+6Ohz8zx@XrJ zwO%1kznq)^@p2%QZ?W_A^rRPOe@>X^Zozbh2U{yjx*cs=k=O;#kqG%rKWZl8EUm zS8fW}qdu~~#Jn&>P^Y@JjtjZzA0W~4a$Ep4UEK0AbCB(jnFH^#R_y8QYvYFTiRA%2 z!tkeoBK%!O7a93GLo2Nmsuh@3bi0IbH5eA)6;wCEy2i%pJ}wrn`S5I#+6e|pT*zEb z+DeVVwKZz(A3*uS3gd$eugCM%Szbr>vU*c>`Fr*DYJ(Op;B|&!%E6VK<8pUvLc8hI9vGP9Sf5yc1kRvH&7|GQgeVTFAQenUO_#<%$=URI zsV+i!ZcY_S&&94n@f-R%t#OF^=9s@5aoZp#d3M>bzm0>pIh-c3&nAR>BtYq#X$_>x zOeJSMs2OQHHrIJu=(c#T%H!w3;x|R37EC|zq|3#qr~k?8JFAXpK`&=&tLEm;j?>ou z!aL!*rcOG(H!%wH^Wom~~Fsnv(W$KQDK^$$P%_VKsBe*Ads@#7r-9s6l&di*4T zE&}L`7r%XR38brX(GO9>LG|PGNj*3;gqggEV${@B{ZOJU;p>5cy1>e9;9n()gkAYb z6{%A-QT-D3l9_ow)G?v&-g|`0y!_yAJp4sWM@{d|4$)EAYD-c(9Y2+1-FZlf>A3&# z712^EeGPk5#PsS6w@9<}*ucUm3>Y|zgyZG7Mo?$z>Dkj?T)Fa(0|TLV=f0i((Zj%K z<69NmO9kDnmd%CooFAAz|lVc-%sU#34<7#Spzwt`r zwb@zZbP0P2$;zUHwDU|SXF>IO%;^tae(>POZ(qN5arok=pM65ui!Yc?28*}D3om$2 z_7c*jrqj|$@=DCi-B8DA4`$v2fupt)wdtKef{mXA3*BY|K|4XJp(uI zP2IhBZ|;>_Cr=6F-U{#Q^Den@?JEM)=k=k5-uttFbe)ZvP`V5zLLJEC9obz?8D85S zUV8lX+(ECvqje><^z%xkc%lt|k)aGX`p}^a;dJaTO-;67I-W6(*5EA1I@5%d-r1Ht zye2w5!#u-5#of4@z~<03KS=6aiI~nhNoEAo$ywyjP)MG&B)|lUb=}vw-m#vU%#r!y z;(IxHs~t|K&ylsegt}l(w|3_t);gNl>MTR_I=t!PST~V7c!c}+2SuK4>A$)Me)wn9 z^v(85!Q3BA_xe{~@9CZ2r#-N@B_*w_wl1Q4HT^it^5Wt=Jp;DbwVuuN&k2J*SHEpn zw`2EiyA_-KPD~Si0#*j39pjGa6Khwl3#e<2146}u?lCQC>T&NzL=6sX-|jllQyWn} z?J~UyGs=dRbuRsR$I_tbO`B4H)UjQzu03U=q4zPNP|TUanoZQ2Zfe;C>O8+<Elu z)FVK|^!_}_U-6WTMd;d(DoPLZaQ27T)>)xccF0xu8?_y#_7h5%2a|+iPhh+zr$g|f zjf34lecEoQpbW|SXi0ElVo0JY^E+Axs|O#=3-jDVEF=sH1Pk^<_y$autQc-c){EHx z#bScrT}XK$|Alr`>&Tvj6qVAfEpf~0IUfbcDnbN8lxY#!FN)g1J|TDB(1Y%ys(`eN z%`4kchhzSzN}(Z#W(VZnpC%I#KBl~_^0mO{GI8JxwhEq01u2&p*yR(;aRAv+!{3IY zbR&Yw_I!uYNnq5dRfAX!XBFJ4Si==6_fS5V$kgf+%Chk+ANCK2K)D)vs-$c6Fq%04mv zsPD;mp&(s3U$n#*Md*u^&TLEM^hMLlvh_C7hEU%;L~#00K|x{(v#ekTU15l6y&kuN zWTxXyw#=v0QTeEex!#6?ha^Yv^H4#(bF8&_uCFO_I=yOQ-E+56LApNIeJWL?-Bd6= zTSt4y=H?_UEl@h93(UG5*@vn*X+vo9P`1QcXM<}tT;*rmps0F@r0VYE)#n>ec8tU} zCam9=+D4Q0pv0PnqrsJd?c*PU>7*NCby-l;4O9-g8})RqWswIdON{mawI~&&U;XCM zaM$SBgX7~TPd)hAd+mYMo!PjrZJP=U3v3Guo4RT#eN8-k;2kV6AAbGed9eIPKboGV z8vgT3Cr|$T{EHXPzx*+Z47teqDBEIw&Uq1i!8{==>`uO9MCyyV0W9GdBcMczE zKb(aheYj09J(gak?SX;%{7T}ibv6*7P4@m?49$*NWl(wZ*9tZ_Lo}zBfc?nxrf*g6Tjon4STsH@ET1MbLA4Mh6`)F{it^RYxXU*oM}G)=R}M z7!Rc@yAh41qE27=f`FEXckg{Yeg5&;gf$s9wtD)E669hV$v0~msV^ecB%203*%s8( z3Rzk@T3e7$;uty9)GQ(PsYyZ3rWtNU)tx1?jaRNAr;9ng8g|8;gXcw1z3bw9*Zd<~ zFAq+g0*kNDbhX_TPQQ28ccPaLM{m7=S!L2;(#c`My?!Kig!ZCTBRfe~Bl!_m3uU7F za%IX!+zYb0lfzDY>>()V`G<7;%1|3Br-jURwWn@erS|jPYY_v33e@A!gx(cqr$Ths z2d~2EbTVRV9#EZotE41xYAW&G*|UUbiWdFTTl)_??3~A!e)}5vI*Fly@s?SM%wR~t zq|s?m5R`7_98GO#HgP}My1=u@=?`BydoVMR`f4(XWLFOl=gKjOj5P@SbfMKKoq12P zMK)6*8&eA?orzFqwKQ)X&L9s4JsmNfxd)hTf|_nEg14yY(7LPv)J+7_A$O@Xr9CM# z7A7}Px|4&suVZX%y|shW{#)bZz1%*&iaC$dC9z`&MvKv zWSB^|qwf=oJl)oRWeV`ri#;kl? z>Pr0M@L*FCy65QGhF5a-?D5;UdRnM%WcG^{ zTM9~d(H7Lx^WB(NBL>G_q66tbPrrw~SjIQl!_QTD#W8;69xf>^i1)i(`y+~r2O?@l z%gSj=1gCFsnMPNS0rNFyyLFpGU;(WOh1*m`2^AY)6 z#R972yzFg>8G8vre;y?r7N=}f0$tG4X)>C!x4XD1rX^+LMkTIG6DH|K+LGcCH(Fa; zeqwA>%euYK8Zn*R^et(5!I^mqMz>HbinPpuRngOT8=}xjR}ncKJm0fhH5;`PbsPd0 zi@GwXY+**jN^auh-$e8aO9I;rWqJ|ieYbeO={cH*qJ9}rPt20Em!s(E!6glOGAT&g zw36cy%3>m9E{e2}Iqb^~r1cFVtBe0z3G7_SBN+DfE8%U1B17#GdR(#kIhE+bT|$U5 zs81C43-K@O_@Q~H)yhqF0iH51sq&ZL^c^Cj8-{42fwAtVXj+XO=~Vu&w+k7U%P5XRg&}R9A~j ziivrM;o5kw0j1SVMc)SgUIg!d%aVd~O^H_z*KVs7#y8S7OYMBwPBpYGS6gKGJPWuk zw?#{T;&_7Ky0%k<+xd13haeQIE5FO4=|$BR$Z?ScHGNrvsOd@cG75^->+AJdHIzJL z+2j}IyIV{ZBvCJDivfgoK9=Uzrl@%44mvPhhYYMsN(Iy132`*dHKD_$c+->gre2hg zZqBuws))s$g4Wuh%T7)r^V~6dGv4yt^wh{~n_kqEkUTJ0zF+}nwmPhnun>vc`y-jxqOyzt=#&EBH)^YcGN z?f&q^^Dm!&@%;Ih(bTz;@qc}doXHmLmjv|v?d@z{`{dzCday!pcvI>}Dn}|&#icmc z)Xh1=CRqYcEGvR^g*8NQGFPn~<|m-7eS`3g0?x;Nx-NPdw- zrHd0B^_ok8bTFN(;hzO@$`t+4A zzZfXHN7l>vznxo;Z`y)%KZ$aQq@@l${63eZ#(COGzU0|SPr7kdXs6f62 zzEels?DDY4lG!V9*RDJw>t&cjBOzj&@9gTlh&!EeX67qV(@#F2RFmxVyKwqv`1?mF z?o@tqP<^MvgztzPml4akVsiMr&$mzF(#d4u>`NOX<@MO9B`@~kbLl;BhGwVpGqW?Z zH)e0#xO(H7ur-ErIlcPouYRG>e882&-k1;Q(D4l=qBkSny$!;Db(M$v&xiN+R$J;0 z?>{?td3^k1v~-N!VRgyrZdo^OT!+$+&L2J;;%&$mm53caGEt6{zebBy3rAE_Vc^-h zOOG#InmapJXi<<=OPw?Y6ikUkPFH-slWUT6pmN(LTXwKadTcCk6EP2>XD!E+e)vxq;RU`5n(AYIAnsOd5#2HtVQI9Lao)I;kI6k*5KbF}Mlc>CF_ z=g$57R=aP#$&t5+T!i&yxVzUo>ht-N;+xF3w2?$cGtuOQ)E&(K1JU9CFJ3w^AcxPf z{%C+lK!f&yO#B12~e~WQyWKy+7 zR%Us61niK5hKnQLKh49>GxN!ni+6|ak+-kevn9ZP(QW>Onx4?$X}2XUtY+aAyrlin z@ppip9-*y7ZUZ11srJR2n)O z7lU^@E2J#PlZsKhV|M+)!8NTpd+c1Ef6k*WFD}P!%VWWCsPP#2i^p)3pXgrKy`$8# z7(cp4aa?~~e}tVk(YL2%k-w-+k3QFjg|Jql;etdX;X}=Ya^{o zW4e91%kS6al}}H%oM>5#tUW#E;<~Hc1r>b5hL)8ZP<`=M|2LmSP$!}Bx8>q~+5XMD zTv8^*xsl|@-5!GJEh*3YY#)#Yq@tyZxGq^PsOHjvRB~RrT_apt)~2jnyB0CM1MGr$GV19pwJk+o};&qayTkguGDk~Q0jx~;Hz1698Y(~X!YB*<z7ap@tZC1k>e5O&<)u*+xVc6lU3zi!mBS>%jS$LYfjCRAYwD5M?HmPkhY_Q=Ed;f0i`QsSKf4y(+#kWnyxtA_;1H%8*6mZq@g4TIw)Nq zTvJDAdS!lywYz2El=zX!rU)r0wAGoDF(I^|%eN(XLr0^Xq#)FEU+bwU_t<(6`TQeybB$N zq?u=kPEz`8Xj@~`QHdKSJ~}>nD|M$qTXTJ_0}sMhA0uId>369Ir3SRsegT5*;+2V`SqJ`e*Ep5q%eN{As3nf=9NmM;J%5;GhKGgcUu4e zAOJ~3K~!Cnfg=pPBN2)P`0BBqV6RWr)5}y(5n)h}WW&2XR(;Lqf|UK8Y&5 zUoskcZ-Ow#_b|7=eD2ks%*@QNb@SD9yYJP3&zRfgh{Uj}A1!KY1Jvm~${p1lsSp=5 zmX{2=;Fw3&*3~5PhN)=0SYCK{q~43CdrqJJ@{2DAKAF4s@ci`j9BO(-c7C-4dW-Rz zqVz~QdLAt421%U_1kZyo>mB#?gU!O3eE zGlpyBMZdZ_A2QkAJL$~^<Zz!~^JUjRG4jq(6~r1bymzkg7D}%!AfvIMsgP+;vW`Cr8C}_(a#RV6Qo6X)k<;mM1dYS# zxLm|ruIL;w9W)2omFb1*QUQ0(5F_{VNHE=(8sQ+mB8nYa|Nh*mOXHYcoL(?-HW4d3 zW*U5H^bIzp>{JJqNf9ZN9+B%IbrTIFjsGM(y?$~J#P3*3lTN}=RtV%Sw~y!UJWSvW zfp_DG&-uafm78c3^o*xGVp;#Q>LJTd_^U?*tmNjpR$+&%0G=J9)`q50^l81!LGknQ zjZ3}=6T9W>@^*OsaQSooqJ3qmhc8@s`EOjlykVI&9u~&4JB)WMRnvDoyL_FWA6xO9 z;mMh7oMHGaYmnBX#-Ys_zWWJyQT0A)%kqhYS^k{KvVY^QFmBD$>%Z(CaKYvh)l?c+ zzIv}+XrX^t*zP^Y?11q)Vj=Rv!aP>KZNH-dI!(j)K`LPyg1R5xbie7fEk1TbWic); zX~nzZ`b(=kcX`k&XzvGQgT)?WE@S17`_o8%5f6q>OGH~K|Dwi}$Hc_tMMSug^&+0| zhW=e7tk@HIzILTJQ_71yUBS7O4I4KCo-hrmf<8}Vsbf>e?}F*&w2EdV&}G2YHH{{m z!uH)MQE>{>5z_&6fpmN?!ssW)QuZ$IZgeH&g>XpTlPty+sOc#wF1rR?dj!){TsE!# z;kxaHeJ?FGJ@)w59L*u{98L$R19HM(R%|c0)1}KO_VcwX?d@>8*zMW9o61t4Tliem zbkWTDAW~h5vz=;GEl*MCUS18)Isr0B>1hPi3-bcLRix-t5q)?$D>3VGLn|6Pf51DC z)A61JY(e-Io3{qSKrqZJ>a=o|h(;}>uI`mf*%`_h4$uiY3dU+zYL~8CCwjRM;A*Il zC>a*OI}To0u^vvuKCyaJKmZ0G?D(=x#yCbcQ)6_*e}r~VnRduYoG&sAk~#n^x7bF) z7*}qTCD{kx!E{YbUqp0;rABrYHaGsrI)f@MOU9%ZA@ikYjeXUJT>#}jvLL&|Fcfr) z5N;fcOU5glchf!1P?H#NiVL#rUiBINX-B*)6bxX>@a=3l>g0UOHe@H#p=14Mssy#3CdaT#;3 z%)K%9#>aFYeWhIt^?f^m>15dv;z#LhBOZ~QN;nx{0+k%y-S7;h2RS>tnMXT278K}g zLh^?iZW1MUziqT8_@L8UzxxNuP+ug~`}U0+qNbbaNE|_dJw*G{&g#w#33;L0a%~%> zxP-14d_;saHf4i`$=F}2!O+Bm1kMlRLQP}nF>Gw}xx$@woj$`d>Zx zv69Y}*IfMO;yUNV$_G4VPgq<;L{!<$p1Qi4lBS{NyZ1g}M9e-SqF&+|F9!$9F`3M{ zTeptCMq2v0Q&(HB=3Kkjc@fXdSGQ*$b?K}pdUZC+uN7NC$csf}WRaPq+_;GvE_D~l zI{nDOv;CLCF1>Pge`sApD1`tL?JshAx~Sx9cCOipmR?kZ!=IoRH1uj45ZzYhS?YKQ z1;FB35>D^1A(qjp-dBrx5l9E4mAeHlSDqIMW^tDmr4(9o#r?6=iE<}udQiQorS-Pp zgRP&R!}c;h;WT+f?$n06d60gJ!&4j*F;zvRBBo1msTzM-n)qJ5Tl{X&clmOcWexx7 z8LQ`HF>TpqJJ48R?gAe#vtGG;Z6Tkm#%KBR)e3v#MXY{ik>u@{`)yv2BoAOS@_B57 zpgWje$aB>2Ti7);23_mLtwQzg+_|J3()w+}`OB9dby%&Q#YL;(iA&ViNBUcOjAEH9ukRu^X1h^g{7w`Dk-bj4MPP5fO*og(}k3 zsM}FH`irMiraiE){En+fNAh?0o6hF?w7XXPVoQI z#gLi4VJ$64t%`eGRn=%WPed|Tr!ir5jORaiCMBX6JB>!?-Q6p!x;Mh+F$3l0Q5V}( z#QN&Jt78oNUMP4A=Jb+Qv35vs3(|NP$};wJTrX6S+JUGTPH?h_J3Sy^mxR8^4M|eh z#AA`#d7KB7iXDU(QF^;_bfcyN^#OSb(nXraTq2_ie@Sp?XbF2BUkO4xp@<~Rcy3v1 zMU*+hvPmq_QEL^Z!+ly+>1vpL zB|DtbQhU^N-q?`yqN+&Cw2c))hu_2cTk`_s*nqG)JkCTx#A%WAW&1Fqvk&pVtWef; znN+Aem<4Y-Z^|&}#j+*Fp?FoJRs+Kt!B!zJH#EG}AXsjyVYpht#l|%TM&`;$)eG0g zRZrZ*F8$7F;qeRW7uPIVdg4_U-&F(k#f>+(>g5}d&nm+}=?c;p_k=c=5=z&Gvh%Yj zsyZiBbnNMiV!BG}!6>%Q`0q!&jg6UwK61(}mYf$_RwAb7lPY0tZd$O-(G>fKC5B~7 z1avbSX~g61Zox5gn%&@#CYYqK-q#(k3@H*p#BR9jr!1TkB#^P*wBC_ubV4z*!FfP6 z$T_}mGngJrRG?70^15Jmc|oXLINd<%Trt$$hE#A$64BQob?@kSZ-wba`_`KTH@wo? zF!wcf@DJzO+YcW;jG09#=0*-*^rmapbfNbH<3y!vgJz|xR!xQ=rhoP5%%R%0ZToNB z{^~csneE~bFfe0gmR!(WPvg$!q0XXg%cQ`{a5{@V{`T0%?;U?lavOg}qawyT@63#k zADL(;myywa_u#?1cgMdyPsSlBk_ic^%|(2AcEk|2^v*L=BO~=AdMy98^lsOg0bB%x z$I?>Lfq0YDije%tko-ElT#AiXQf3C_6$oicLHy~^u$bm|4R=qT{_y1tv;~cyXRy)YUbgB~BIwTz;eVhCg5~O@d1x8~==gA=Fj4ow}L+D4HIs(%r`E}`PSvR@yoX! zUivv5jn3hDnxBulLM<$Bc>S8>Uxw(cL24V4{`chu=_76F{v?#{>}FxfAs1qC=mM&* z44epl`1tdObdL?GG;>!IRDyTV(?w24PtVX1yGTzk{OE$|HrQoI`VmHFh@4LAQoQK| zID+Z!Cem$H1abj!Xx!YIs29|5eCC{-iEET=ia_PU#5@*OXPDHd)}!?6@T^b$-v{Gf9vF%+(8akrm5V3sx^%mXChDT9d^$@rZ_n7h3xRwKg;~SRi{Fx_W3< zrhsqov-X+s%YsFHH`-_tQ0@i#mo205&~o&!-AbW1yjEh}Q32-$muEcka*+C&4QLNu z#>*MJ>7lGu&oSZMTntZKMn9v)Y?sYB-17QYK0$m#VE_*au(PibqEBon{I~21<9j{5 z{!8zHbtxVZqoHK3yp)p_Dwro-Hr)k1O{B(`hy&esKcMclFfJmnh9+!&*GoEmV7=vI{o~r~9ln_|&^&ietV2 z`W2+pZL}O5hmh>MyCb5~cr$QcUhl-lv1w&_K}zSvpYhpV+|q4D%*$HR7%3oKxv^zK z%Gma}l$3$ew&E7rGKuNMu=l}FJS(35nRPj|EP_TctNZQg2h;ug<#+?0bFs77Z?wmD zF0#0Cp#$oKx!6l#r2sW3E-{U~0K_WZa?K&Ec6)NjA=en4*VQ;Zuc{1VdT{1Z zDmVSh8vOhFMbggm^Z@1fkOJyL!OBP?iak2EycM9X$~M7d$Q_!L0dz|#rv{Q>qlmZS zO&2!jth8HUL@-d)bcQIlvbUdGw*fakX^c!8RKX~722uSH{Bh?qbJ!gQrk91;$@GPJ z2wNaSrVGj-Z@9sGZ(K=w0~8xrcoC6h=D;m&7pMt~63=CYTB(WPhP&n1gkjeipRjN(_bt-v>M@;R3*@bTevwNB;LEy=b~R&KCi7^|dJ_o$Pce z1zuFsRnm*TASt$@se%GhVqUVW@t>QU=nM1|5=LUAwIMYfMi(*N%$a6L(&dOC?INY7 z`}zh3Vo;AYm(DW;uj5T$zb^qNY%0MeV7i51dPQ@RLwsLf!oFDIq!mc+6he7oXsoVy z{fYJ5=s09^r~^5EO?*0;faLhx7Dyc^e*)UITcW!g zhO{X?JlQcXd5m4br$@8qZ(L{j{n|psW;TwNLsQMPQq{K=4BI9L0oVs0KK}NbZ$AkS zAD{Rd{~UHT%J{`@&O z{l>g$Eb-t{Ejf%Sy_5RGB7*1J+Q_y{AI1nn*(O8gI20{LyLGscL7p*OFf>HXd2N$a zeU1#%mkBlf{^;q`vsb#YyR?wG9dHdMLgB zl8jfv@!fCJ>+|*7wjJEYp$A>0ZD;32G9Cf-FNsgrTraiA=_06iJtFEwxxQ~7zj6D) z^;h41_4d`P{g?V5$KmdgXmuI$GmmC)vS4E21Z!Xa$#sw%Bg=KUl=G|Cm0Hfz-&O^n zuL9=hUOo4#bHDnD-R(WM!>;C)mDbc<-k%tLIGkzQ;Shep_Ya+w;!sKijvhTacTajN zee&??4!M2#m0SMDFCCXMV6mj1I(6!`naRnl(*xJ8saXM(ex}P-euZIiXCnKZY5GY3 zB~4PD&G-W_b#ye99b~Bw9PtgD%c059D+j$z-1)meOs{Ce_Cj>Jv@}9I$1M{?t6%i= zLIHJ33(jP#i7DR|nLO1^MdD(Q?#RIPQa?cpQSrF&OJNO&OBkayRile)IvThb%7xS& z%wu^VC8h55Q%My`dY#Q=`2GXOe-5Y5v=g`FCcj%UG}DWvj;R%uq)@uNg*aYBve%&U zFAWvnoA>hqQJ=H77Qf17;oQ|59AtUfZk9t0p8}jU0Qu$}tkz`lV3zh69NrMW0x;C#Lw|y1D>!! z&uWinvhbYYnQHSFCuIuLjW7B~Kfy8wUVHUQcz;J4pKtxYWmgzq@agqmdJlA4?R6<@ z>hT;~Q5+h48L{}7XMkUEKw3^oNnIC;X~0UK=NoML`-vjljU|0g7#C!wpIEVSuWM~j zSx;G1zw0gx>g9GREi0dY#-*w*4iWt^L5pb1Xz492K4UdB9g2z~;5@=L2E)sk{f6$f zKK(T{yQlrIHH&VpGS0_bM@P%cH+k%~W8DUF)Hif*lv+>h)a#abUtSs;D=z;APXDHS ztXRbKY0T|b9zNYsRplq>D=Kz$0d+;|Vme1x-}}s1L~%;@#uij`F|2p5=zc!sC69L_ zTwmIY);}PVgmrtLH>&B9oao|V7q;VQ9u925VNla9$6v!#PlGyjNEeJQqHja2yaww?bQGSJn;^Pmyx>>23&_#fSNtwwPM1@j_`$K6)Ey;FMH&hD z=c&Avyge=goBRlrtBO(HK{-jJnv@j+qeA4ouL08qP-Qa|szZtj2Duhjx}3peVP9EV zEde1~ETg2TKl{Vy*4l{~Up(l_eWRIj*gQ&T`9;_huqP*P#}4)lA4xJ9m3l54#>bSo z14yej7G@={k-f(~nl;^+^rEoSKo2ccULFlEyD~#woaY6 zFox8~M^#^iFuHs_oYXE^GLuoeOZ+a%{33d~64RBMu0gs4X=>r=#(zObdNCt(7lxRa>kIYzNDC_7IMSc5b9X@gB`w0;3~60qx&_oH-gMvCdf!;*^z=S! zC*Ryy=V%erx5Dj?74UhHDfS6v`f%_THJ!S{VM9}%B`mH<=(0kVjJ&?&0qDaW-fM_v zbjH`+oV+g~aR0%?g9qnMzDT&rIM(zfYWgCI8&G|L*TbnGUA5{CrJW!;YWm^HY^A2Z zP*^)!bL++pF#R|0kCx15?JrC$92y#$s+g*19%}3CN)D=+8o^Ng&98s^>$~k06(dp} zy6Q;#M15=p4Mm;e;}0fI)jLL-StR%3ksoLF@b%e*+%;Q^nwujFpz@GH66lMDr}TyS z`61-GSi|V_pApxBL~dX-c5+Hh&BrWFUSkc>={M)jhTd4yL~|W18zL zm`>E8_+AP+r5u!mm((B$pYN2Uaz+01(@WaR zu&C+3xppPu*HHSyyM4acr;*dEvkP#yqoSwM!v{qj6g4xYfli=x7QcM??3_?Kt`@j_j<4|BPagK~xyoSy#^*mjN&E~dxAK-YoQ39p&%}d08q^-@G`1oiCYB-`vly|G9-xK@B9q=Zmk_pSi#M#!zpI^$m zd^l^HK5hEEG>Z zW)=y1p#lVuwg%KWsS;9W{sfIfsy|r{vX-2AlccGnDN|FMke!pO4z!-UeeS{W@R7Ue z1jE>LOoHh)?y*6V^dc3cP&$Wlm?$E~Bd5dZ#(xc-UjNZOfX=-_b#Xu|7bH&59#z6} ztG1Z9eEAQIvh*^svec;c8<#Ktp{B7fTNY*{^JU8fk3+O4%A&zJBM5AaY2hV|NfqK# z(PHj#U|A|kq>=~YsWqkUwWq*EGEI#(> z(qDKFxVre1_tZq~Dz{pjml&Kw{~o%Jrj@(I1s7i4@rr-g9uKP(0d>JuIdR8!LFmUk z1=G_!P}8lVN~#!fG1QQ{cof^Yv{>z3y{mM`?&-0V>FKd)2vs5xtx{Y^Zw}s!!1E$$ zi4tj!`J}~TM}vPFb)zmR(=I1)ypW98Jyuidn$o=%uw$GcC2>;#*FY%0%31==QGk{8 zg}gaY)VosvbqZ2rV#Zv`W44TeK(Pf#u7khHrefIje=Ecx~ zbR}}S%QS+!Rdn+dkecSl=L(Qi$k9+13JgDSg5yST=&0E6L zcZr@3lZ)*IOqa8rUyPVsP|`PXiPHu77;lQG?T|StJ5a5LB6Ttzc`+2~Duw7;q>6Al zb*kchk@y#Q9q$X|POy4jfV}`8FbR2s-bm|;zXj2aiaBho&{Uziv>#RayLj4V*#Ljy z_lE)HmTnyazouwFE+v0gJML8s<4`VHDNV!5i6w?c~m*gPFf~k74Ibx+>5v7pSLZTn0 z(`q!=S5nhclPn}5gj&+(X4{=u);Hq7PS6BX_ zGmnU4%!u#$r};;}`8(9~fBYX}n*QvwPwz1_Ba2*4$i-RdZ1mg5_v&dtild>et+Pn< z>7ur#jICSU3L{CTp*~MPGI94T4UfM4zsDzhGlq+b3LN!%Q{?ml!q~S>=`ES;5DPEz zs0m#nW9x%rW1XxgCNL<}k4y~>wPknK_B2NHm(7j8_r`z!8OHRN@pR+v!1QwCsGb}Y zDn~_0?`&fR!DisDK((cbB~`afaA>RA#g41a&M=F#G;^kDjvI|)he8_~LiMI2f%VDK zRtiv0Y#1DrDpE`@=kJarV4z-~TY-TZ{737>oF6!18Ch*cl1qI(YVpLu%t5S(SMzeN zhUK(2@aN9INmYZ55sjs_Hs(5;>aN<0vt-9y`|`_ofAPUDu6=n$rKs~w)?VyHD*pg{VQMIzOM4pdnc_coxJ3` znV=t#bP! z+1j!RmX?8Hd3Q3AGE%aee7Q9KYw+~?kM04VMcc?`s5QXwph}kWv}N@11!KvwD%NYa zMDsR){O0EtA0V)-A-0mYjk}+>*`&Q(JP$AuyMTP=A8eLP5sb!oFW}su!!M}m>yIv9 zzFT{iC-)ks5b|Pw9Mk{ACs_6aRX)4${(pW~EIjn-!e4q1#B48qQ2$5(03ZNKL_t)J z82~O;DQm@%O{AemRShAA(^$?oZ7Iief^?4KJSqZ27e*&Fo$^jx;cHX+cT|bD*#%3A zJ+2fUI5sxW6ZN2B(_-vFq?EU<{?Qt$452~bbrd7yR5Cfx5xSt?KuE1d7||~SD89k`Mmvs z;dfr+X=LvJ@pXWn>c=ijF|~xfcnYT5Z6OG83!fkV3nmtk)LE+%TtIltGJHM~VMIO$ z-=%hx7gA*FvL!&IYW_b|RuWOtxux`UO;J}90(GZ(eo$Qo^}y3|(w;iU%0YPYCG*(*;BNL%eSRvNFh`?OgOj0dqOipkkC6tjJ-s?B_c_~cS z3@-*AS6AAFfQx}$Sb;dKsp~9JGzq4!U%$q^0@q9WzIZR+=q@n*bF#|69-lB^x*)l5 z_)7770`(UVziAe@AlM)~qXj(twdsoajaQa=7jN!=0 zdVQcZ8QBH&w!zXZm}PDTr&IR_W&u#??$!>VAbBPu6+>;QM2*izHQs!<tL z@#L-JR7aww&&)gQi>-IA?v%H0>uhTiP6yIc$>>S$kT6Sxb{V*Y%reaAQxqMY!Ep}C zVN1aDLes#ck!-Ob@var2Wmisr`Q??k>2E)|JK>B;X7j%KisqtZY~{TnlYxN~6ZK|L zI(Fy!dh3zIqy7=sBCbYUy_yH7ODRl$M1MqFTtr-BU6U?EmrZWvEH)adQosDg2QR() z(yxBeI9r!hy(U9E>hm|gLIj72KfiJOQOVVxTo=9k?YDpYSLc5JDl?F`U;VMsVgA?9 z`ng~I4NZrBMc<*@pA+Nq`PFMz{cqg5e0l!B{9E4P^OHNhclP$~+}Sms-O*c8GT#+) z3!_$c)?Ce8%@jqh43c1Oy)$#1mQcqpT_U{x!l?%jkn>Od^!(3%{!<(-Vw7h<=%-#L zzvtv@Gw;oW9|6;&YkR)@0>S_GjhV>;bfS=KL-O|@C6%#%E__>XLrFop#AC{LLll0JskNiEsP0r^GvUpafSBrzYR%n+ zZ|Tr5hdwk$Cza8S-wY>TIvF|G=pA4ih*xp2V*rM`6@$mH8qSrKXm8IecYF zM+1}nmk%80GoBnja>S{x9_tHVxSK=APMsy*_GfZJ4|IF%YOEO=jdJN;w<~{t9uO8lEMiJp-j1xwqu?REI5+Nn zZdXH29Hy7YdjcNwfB?U41lSn=U1Xz8M+_gC%6%q0C4Di<+bb`iOZ^8J$Tq9zTp zAyB%k5{-QelLxtN_zgEerkBbx5SVUDX1cAZnX@z&r+idzo1c#_U5A=(>S$S@r*lp{_UN9TQ2~?MQ5MqO za-H=A3!EVn}sU=)r?uzX+zEZ3oPilSP=^NaaR7U6a!dYWfm{zti46vPNOLpt?4`{NjJ0 zm?$7i4Z%V+=c>whuc#Pss%UCB!Uk_FRAJvX(qq-kfgHBE}JE1QDpBNO2d>2~zt zw{!LBZpqm7>#0bkXs|GO!UWebwYWAokP%5mO;3+?BZ|JVvU1zu%A~vWYURK}ZO_et zo0l$~I`!h~AAb1t8>qpzRSD^hnZ)|~q^&^RFlu^gvb1)+-`1RtzoMzYtfS+F7l_Xh zN@s_4xN+oT>zb|6&gqE1mWiPyiQ5pyF;0v84z?wiND--+(;wc=b<1|3*JrMUZMLo> zgdS76kV-v-7#Qe?mR`WG1x~~q8jZ%~T+PY5im8n@)Q#vDR~oOxMU`N+Pi|7S7xeUj zFRy&@cfWc`M)|eDo<|qwFFqoJ{QB*$PKvkW>gC`pDm4F&xI+=x`B7Kb&;8^lzr6iR z&Yy=}y&C4P>^qWFnv{(5 zMOB5Om)hE_8WL@rMlTMh<3=KdhgMOJf&7vnsXKBk$|AC>iT+;IGNn># zy0kYkP&%4Aiali={Fa#N^7WPZ1Of#HQp2FYTrRaULb@hgLA(;d52D}zPWe#x}D8;I&|2;^0t`8$}d-Sa0u0iR`Y0ZvnN};vR2lIU$kbDH~E+1e_olVp^=a z_d@DEsOGCVVPZjS?_P1jBPFGAz@wY0(-x)(06G|tY%aF+6niD6M=6M>fD|VTQH*27 z5sd@IV?z65QCTF!q_lvjEr!20G+{A*i-r!W3#~I?Zfq}*GgB8WJl)R2WrIEIfpLuZ z(ub5N%d|8t(gjKf&IQo5CDGh@A?10|v~=NgD0qR-6{J&Cs`y=9P_bIYnPbsqo^)u{ zun?|WqVJ-Y)BZ>a=%T4Jpmb5$rF)T5XyrnKJOEslfIk641EsSu2&I$F*-y%QO~Y~Yr~~WrO-T`{oE8R$M2!E4tar53Cl;EB_oX11zP6#JzV6n}&ZhZ=Qz+-? z=>>&_1$xXcrube&O1D53v_MUVP^mIS4^F~#KzoAGwl?Y#PY?DC*A_YJ3((T3nxjdP zsiP#QyLqFgZ}tYW30f5XUOX8zbG2siLK!$DP+c3@pv-3EOqA^Opscxu9i_7knR7pf zhCc?=4^X+ONLsci~^a_isME zr&(TVNq~ur)axtT+xwi_y|M0dd_kJY$CBo9^ykRwFMoY77H9sH-WoQtur0_=Hu0Un z%fO)9q)p!?rN1P;Wspiz9*O zqVf{5UBI{X#g&N1k3YHB+?2I#qAwxAJX`vCO5Y&N)7g>e`+)~TL+hd6YYT$PVtrd_jm2D zG^wn~oEw@7otx561!s-~24^0en5YatJ2!q7G7lezwvXdzIe7uuT;4+}LM6E6+&MA9 zvxEcv+%JF0)#sld`{lU@CvT8Kf8fA@-@P^YmUmzLQ9?C!vuL%VgVp)2X?<&%-FNojX{W*ih3f z2R!(aii!}?al43%o!+C8ro*VN)(S{5y<}u`cJaF{XEzjk!E`5I6Ej+c=EMG#+w_4r zUihVPcT#&o$EQwhxba_ur`LaU5Bw`^s=;{`^t%MpDcUqRQgke-a?))J)uFtD zJY14q7)#akjSFh}GJ783r5>P+?2BZrty`wl^g81W2Oh1}i!Q3^a-T!av(E%%Nji%W z)8*|JUreCg(1r9*eu5>_5_w6hKRshvvIFFiPsd+;572ffVzi{RtQbts-*z=Dz;9D` zi${M{RajWVEB<1+h_ics@9L_CeoxeNa!v?qbUCroXJdcPZt_ilbh~3j!=(9bX<4^A zr;ePLa=$Tqg!A&4U2zeEjd4ALG26=pjvBJc@=z8(V;{jU>Nx5Yxw82V+v!;&X99 zjX$B(b{JjMbUGXD-5U}0nDSDs<<|@MolUJMz)#3 z`~o3;qxggb;0+fF^%UzV=F`YnFpvT8sa!uGo*^i2wb5g@N{LrezbYH0gA?aHdv@`$ zrPouQKTX{;b0`6ZXSJOqyGy=bh7dU$D7R%VN?obud0C3-8hvVgN7V)issgN9Vxchk z0?)FraBGpwmoCY>8pLaLt!_TCMs1h@#^uq%<4Z0So2%OzpesCA#IA0uM{D;iEE*Qn zi#>56a{=REqZqO!PmU))sR7hw!h$V{BOU6S!KbdB3Z+YR^HP6blY zmNa_5P1=Z!eniilE2l??N1Jd4qy|->?OEt-EVzyZ)8i=trGzxS1JBDMqiah~&^b4Z z4^a0i?Cj`R6OZd9HXvAD)(F!aERRT<|ak~`y@XfSA5@*cG^Me zEQ*qbQ;RBMn`^VqKBUjl`LE{!3-lbSU>a0tTiDcO38hQt8VdhtE#u_S(P3std>XbyBp%6$JIsIl1YWjuOPri2~VdCz=@!Jn1>E*^uNt1JAQBd+QUglwn0g_Tn zcagwFXuH<6L z#ZheZ5qX)FPE;Ky1Dv(*!|7MP7`Vn`zxd#TSAX^Db@JY?e|7!uuocZ8Kl#(2p1O1k zV|nmpM0O$<=`lnr*va<5%BiWTyUq7P?+qOs@l9+9bPufw&YbeSd~|fW^E_jZ1uEsCV{f%hozvP~uef6{B$5Gp7 zX2xH+boKUCrU(ak=gFN8-rgC}=|w|l4^ExkW?r&mc934GSN)koOuhx4`;G+fuSB>f zpVYECvYN6BH+?}QGP-3_vSYF(YP!r+EzHa_$V1mvh8}(R`Qu9u&xQxjh3eCT+VCc& zXSfwbN+m~9pdp!{&ma-`zY*d$pjx{zF-t}C3s>HYWYd5zL zmM8}+cB@Nm-R3``rZ2&C34UzV9*t+k_=egFbtwY+f||aJ8_%iLOVxC*oF6>n=^(YM z3z+_7(u)?zsJ-Z)`~*v1k%#`-U7@|))64%Idmx3DL!(VS5yd`MY1=~mukQKPhUZ-d zs`~pq1M*t^Uuh*Re9tDI)oHr^-L%9Ed(0_dni%i2*8Ut%J6a(LrTZP5_M2{5*Ai9d zpXP!Q0t_y8b&Zp<(SgyjftX^yX^-hm)AsmCHqZ&wWpzuLzb8_8ibqWG_88a3!2#Ep zvF$x2QFJ9m1Mim1#1_0P<(~bGo-ty=5lU}ayRlp7tpzhWc;2#7$PDa1;bQ0F(Np?v zOUg=Qd;xRL-6_cGN=@(H`%FrIe~f7C4Dw&3@6kZiK=~N-55#{^R}$CKy&+}gYM+-3 z-+=ftlvRUEp-&OP(a6bC2T;LQ5tRj4?ff=v+yIISl-ptd5q1aOnY94uerheZ1k<^} zOE7?WPXmJsh#N$6F_=i43LX>ALh0NmeNUySQeJCKW<#Eb0sH_~B})sE!@$x(NQy>9 zMVAX%YtLhZ^Az<8sw?UP02Sv6?a7@+>DCY%f`~4U6QzCS20yInYAc9I=MV~f4y7x{ z3zRON7ipPVg6lt401+z|A_=$XOx#5>A&jPu{^JwX?j& zA03L!WvhhIm7K3IeQ~y-J{%XShV=IfM-=3H;cF09XYVXI$sSWfQqwgt{kv*9ju*;E zjsJ=ypr#jCI$Byd;(1{dTIvfC)NQxvP4QF{$j3ksEG*=L5Or+o#6^qc#R4?jX6o+l zmNa^??eyuJr+Y{bf!2G5FE*vSxzVPwf>xIKHl|Y9)*R&Ry>D~8H<+Fwbn+ypF9Gw# zdz60zv$dqCqZ6BZ!|CyKF>Na<2t7E_P?Ayj%0tw2Fnv)?UqJK)Kf1uVQC&B9(+#YC zxP78cVfu|nAN_w%|J^TcBeEVIkz!FbG)KCWlVVf<^uD_JKY#n%Uq2iwDw1;00$Z%; zI9-k$InvkH?mc0xBWN7cdNU=Uqgj{7--FXXhW|{ba1+@Qx!n|!?c__M3q2*p8B8#C zhgo)Q$!Jp(5$LrS-+!M@q9m2z4A(W?zuBMHk39VG8)qjrClL2|{Fe`ogX!~iB^^lx zQmu=E>z1CLY#9~MAKElD)I^(D8=63!Q87A1lyuo=WJYeImDXpFdWWq=l= z@A`SX8wa9Sm6eW`T+HgsF6gXox;PjS(eIx)5=h@#vuMmX7vGP%as@BU;4J-<{_a;q zvpo1pW*Bu{RFby-^rwG+>gtV#`QVUkp`#Zs3aMvh?N7`K4LzF}Dsp+fyH014xFaz% zI5e@LM3;Fh{P6hY!>h*Ws&uQh71%z0Qgn01&kbn)GF6~B%uj*mDpyhJL%I9-rK_!2 z(}DBxnfKoNXM!^Wo!;u3%%leP>g;S?-E3*kZ0YD|&*=LXFV==0)JHaT&JJFSxWWN~ z`N{qJC;P%HeG?7_pWU{9f2DU|NVa8UQFTxT>IdP`F`{Qqd=78cvG zj`j$u`M2(b`GS67lSB?KHJiT7J2bQww z5_NeI)B7P|W638^4B)1rzEf}-l#l=6lDn0f9-_U05WCTv4yGIb=UYa;%X4b>L;}m| zKQfJa!ke!0SJdkP)y6kUT)lj?3T%wyEsWlD+0eyrTiD#7rvJ%Lu;lZ~JN(&Qp?$2U zm;XEVfK|#$&(YADi1O~$X@$Xgp2eFs#sKLNVS5mLbNpK+@FQ)*x(zioah{|#hI!iU zPNP^fC9kaNSeW0jW5@isusbFqxK(j!$w0Z3caoGC7g05^J*K>6cb$JfIVW4D1>;mb zXv*|UdtK|wVp3ejXfH%?*I<GT4^#%{;N2lQ5%E(RVKDi;l%K}aJJ<#N9yl(X;q z|9|ZLdsJ0tn(hs22xNmpQCW&e6cAwmK^Pxnz;1PL3VZ^A0lXB4!BLjHz9J_NfWSr^ z%|YTI1ubl=<6l^`ZeS^+=z^n%2Ksx%o=5SFQsf;Fy z)Wt-hak^kHyvI;vt`u|a?h=}jYAC2VCstv4(IVB?5i`kjMB7a9r4zv@pe}|N+2=j{ zPHZ|vYFqUoPo4%>Ev^*|D z9#KP<=3TV6o4eLQU4Z>LL0#X;xxLlqC+eDGA)qcFn0}DtIL!@RP8aWsDCzUn^k3jz zn#1%g>!8FOf2+hG#PsTF3P`PUa{ZmG5_2uB>EEIam^>$!+(tomA#|0dZHaw71X6Hy z9UQE}?IQi>88@z>rh8??BHJSJHbD2Nw~dX-KG6wo@#%P0Y;-kU*j(|tAiGZP8l;QG zS}xM5RIcIl*4CZT@mykKY30)}9e8z9b$j5ES=988u8)xP5^hq{F|?qd&oiXYTU=%e zdI8*t)*fAWNmTUjzU!NMc&23I&rkn!B)DvHAjCGQbaK3OvQ%h&s!?uB70RfAD3xpewJ(TP9g0b z1J3?g3uv1(au?GJoc`dkMS4J1dWKE1(Z<}#JU6p^^Y((ohD34*gRP0)3pO5XMNB`3 z{h1D=8Riw{=^3pS#?WeVHaQdGkGDN3nao8HKWj2{VnQ&z=l=csJx?#+y?gok+i$*{DGHIcjHFqgWj+j=d)1?(P_d0e46pz!S2)FrhqRoMC@vdkWT`^ZTZwi&R5K0~{~q;qgXzba8&QWUGusETrT2VN*I8W@Y+oNZ zdg{OdKflSL17#s0V~!LDC+E?BG>-`SNGeAo#r8r{DQ7~=qp|;Im?ukr(cA;mm+#Kp zotc>>PLr7&aym7kMjTHzV0tnqOz1kb0!*h+f&NDFOOKjP^H?a|XQ#0%w>>l1ARWXA z>9owI0~WNNn@xxd0=mfNVwYlAEc7ZY%yP13+H5cbyJ2_{$R+B1g z5=>Ww%qo8NH8(QR1D`$o$JBJZ=_b49f`l}RPkD{X*Irp?c=n@nO9i~eGd2A+lNIIJ z)+H`|e`{0_uLnY|ISC?7t3FF zsSfS*boO1fD_ zOUH0YPejjC2wh?rJA9W%Rk_IW>#y%!rF+u>O3{ZIN&pwjie@+`N*$IKg;}6AjUbrS z&csu~>0)%5Q_^LHVsyOqJixN5DHY#K8u5xGrzjAYD-FrH!S*6va22M`dKeuV2GqNc z9HBF5wI>PkXv47Hl6A}?6sgm5i2xM^#u_jR#R|tNIA67h%z2H2g^7jG)ir#FUqYx) z7Q~j0=LOi4f>Tggz;S(=V7eOOOBX~}yGw~IsE#3qZ1+Qljvm@kPUiLhDo~YfbM`ZE&p}mrN(DW9jI~v2!ZHa84`eu!`WZE5V zKB8T#56lGW@|g*v%SSiwB1cUB(2&zj*7Wajx!R?t1GPl6pBHP}V*O=3sms&dU%TFKOYR0(`X=}80A6+O_c&+w6 zd^!5yd2yhj6O=Bqm9~aM)1;?Axjr-yf*)KaJ65*sMres)ZI6w?Z=tm%c;0y?>Wl{I zXa4z%hnE^%gD`(g-nn&a;#Sn`^vKB7qXn&A@uMvx$mw6-{`&Z5kByRmX+ssNO+#fR zF1O8FiVqzsswC;%fIe@7CM$>1crZh8dWKU*x>JTRw}9HPrm`)nU#lo<(E{wnZ{e!ChUE zM@&iNV0m44_mRMsQU4Gsj&mX#nyW5#-Z+B-|KPg^`{pQKzn?y91D46#8c05Cm+lgvS3JPwoZ*`3IiyasmI^~^}RhY2zadoep7x>+M zX?oW~{VX>6PgrrYyd1v^iSIX}217#!{6Yd-97hjKjt-2&>Gh6|G^R~Xrs-2;PG5s< zk~yXqZ0Tmm>5)O^3FN2~sFR$VW3(+hFx?HN-<>%!bfB`qwN3at!xG+>6HrEevD#Jm zA}wUe^J(YI2Qe?m>!AAz($(AX8QGYN-#pgB!d$stY_dbF(AM3p!E|x9_+yFj^Y)_4 zjD@B2my%|pv?L|6g}4?oF*TKzy4pz3QNP-utM{ag_Vn?QWi6wlv^TI2O1HPLmMeQR zJ}wE0#MdT8rKZ0IFK&PE2!PsiX^QjIWqX)cGrb^r&w0st1xznX-Sk%y{ynr{<&ya? zT+X^5_NJQzDmn={zxL`YOP9W~_J|3w=f8sTra!}UDo(Wxft+s#AIAh^jiY`n4o7F4qse4(SNNs^U|8 z>B_gV(aw`ZbJ5eGR~1l64W%6&kQ9}hLK!y$<)Wr<6t{~kis?mApM}la@T3FbCNW)O zVX>!6b*c=BOqVy1bd_xqy}AWQsj8eaV4W zlN0t|omHUCky>~T))l35B}Yywni7m$4gsI@utrWrK6kfy&)B&Tq%RKfc&{P_$C>qi+(*m(LP=Y z3zMXcsaLJzr~#@O5^wrP)8U6v&r#DwHi$kS0sV$8&@0gN^NZrH!``(TV@kW>SAMy7=$Tynm^4dPA5?0 zpWSnovsQa3+%E1*%*-Z^$F;RpFr5O$){1r`Wu!vsPBzBO>O%tRxdVO!R$`5|RiTVi zxLz2->2#*s^2uG=220>G;db43^1xZ5#q-D&X)Zzxfi&3!sjD{Ou=ydHwj+KICSc7{nuf$Yc_0?7d>KflQ5OEyzkJ^zQnMed_t$C+seWe*f(KvzYF=e}kk+>7aV! zOlLu8-%zdJz=5*S(F3^T2NFYb>uqStOHg`Va#CtiPG6*1fCHv9mxTY)zz#HSG+>hj0jyg8A*q<0CDj682(_%&wGokRH1WHP4phs#1Gu`J#l>^yl!0 zZ|Ae=JayR~=GExf4VaxLZm)ip2D8TdC9EuoCab!7{eP31zHyQL0{`6X_ysy(e{aj4 zQ`4nTHB>#pByg`0Q;fE1K^%+m+K)f)O;^>adZFqc-2>Ar>hJ%r9*Xa6=Zm}ljz^%0 zfb#s%L6_l zDynx|d3h8KOo!Lkq&PR#0N`hfI(Mxl`-O%?)u)E4pSBko%$*2rOFufZZ&fKwQ zz2^CbBE^cXtLe&C0ut+NDQP%xx!^BBE(Eq{qO4k@>E|pe0UfrJx>3`zu=;W(XDjMm z>9J>vY@sOn8l`KHj^#zZJUJo2Y(o4wJ9e`rP`J2S)>BCd1Ks zHJ?~((iCL2pp&}N(FM>2QPoD6==C}FX3L(tZ<5m$5-SSU*O(Yto7I?*TwkjJ``k)d z5IR>^8gHw+&(Ql{S<;?8@7nb4^KNBBWbz=JukD&?M|5158!p<790NJWz_;`yoxA8_ z`ZHF?rNl+#bonS1tGYX#4XjiJB4t&y37YfxVh`fAb_ z@Bi+1|9s~CGZRIj)40>8TLwnWk{uid!1Q*bN~>Pz=jbj8eYQE5t~Fm%Zhmq0PyFtS zOVzn$2d0qriEaP<*2JCZ$;3mXj^`2yIP%ubFM;&0Z{Ivr5aeL6r^GO`*k$)FPni#& z-R)VNn;SZAFt=}YYL#;pGC;u!Fg@BeJvzgXi8~!mPYkLZ$QCiZp`nxjkkTR-7ng_# z!p?hoB0%#`ZpLw94*lgO%QtS`xbc(o=l`a&p(5Gc-|s-T2TDzzXy_HVTVQlrA-T3i zR`XYG+mXPKQU9`0dSW#+R8@iLLg}B7KmPTXSXEA5zy6nh`Ij@-w;#<6ym#{ShvJz= z3!iys=K9IYn9P4p2`H=7MHaA`zlq_TFJXEDT6prw<3BzA*(k2sp_TQEqmrp)HLO**} zs$9?Za1mi$N$WQrTsjEnJ0>LfjgBV7j}BxdWHA||{y@ZZj4ptAat^o5Q^lChwVA<6 zTrcU-D^^rQ8i^nEFB^JGIQ{ADrbKTqdLcP^TabiqNvvrbR+l!|TreFyogz|cRF$DP zo%0=;nYmro3&mni&bqld3)!UqV14nYUKEMln#g_3FWw0WUKUnlq+(c6DUa^4G$yrR zzKBjPYCGq4#_X+~!17UvPnW=((m9D1CqLi4*SofSay;58GN3I3K zP3?`yWY_Z;CFNXG(?!JBUqRG#-GQ!xWvD9Ehdg4k!2Gd2n76<3Q~&y*FunMT+kfvP zu*Nwi228K^bY8S~SLU{+lDZ;zaq}^N+|GHe-KGQnN4f#^v~`PoJBkCh@7}%fgq@x9 zO3z}V8SS1gSgVVX{WPfa8|x`Y<<;;WmMFI}Y{e!))oQsx#?`Kgc_Z5-;}yj?Z?QSp@UxSa>a z6ApkTw#R6oj{OBB7Xcnxhx5huBA#wLyWLpOr6^M~y@;LhI{g3C;u+Aw5BI09YIos|5BmsuTTHz6JW^aRqf6*=b@d z2_dNIiwQmylw3&#Dch(N{oTs%qM6cVClL9zbxX19jw5ol%~?Dzad~G^`cR> zPCt$yJCv@PG3iHGwoAldxfL{5jIN|)<`&Li1(x_pqPiySNY80Da8YPxBnrG1q6(xLRFravKwbGT8w3*BtD(s(@ttRTFFY?txG z#9Wj;dK&Rxxw%1MdNOdr1tFcUBnM3G_BMpPUApv86_09H@9UVJ72DX?P@2%+@%UY7+=_KBK4?cWl~OvM&U5M`4vJY9yW^3u~| zgFXhy@TiEaFPg9k&HjOA+w;e`cP%4L#=C-LS%i(lDUEJC|5fM#}@{TCm8 z_@-bu7p>}3g|k59>h7;ZK>yY0y8!&b*kRncdUB|mZ5e#&)aobvJUS%J|+jh#Dp zzVXHzUHi|C)dzg$*bDvqh^JhzfYQst!UQsWB5fRqesp$(AvU(29L!b2~;^lIAVQ?>iV$>;`{mrR&m%v)?xk6N!}(SCtjw%n7qOXPN|qH|B~ zndS(8Y!BwZU%l9i_D0%a_|JLmS>jw%*H;}kylT;|VmpuW>T*Pv-Dv>$#&xR}Zw&N5 zx_#4;?qeIUczbL;r7K3q z!LnJa^`x+J&o0h4c;L(ydI#yXCP$djwfi0-BMZJusJh_0u4|S=_$;GXH7v zt=YiQ(^VT%WmXrjiOA_t{HCLaHf`AmFs@uHtOwyq9wP`W3@OAe*sj5*rk*S871ew` zri14?@X4(ZvZ7?2*oDaK zj6gcZ7Thgt8FqCU%Al?YURa&21)$kt{Rk`MoSQl*P-k-$r)#3JTt7eNq3=8jS8Km_ ze-6Dhm0RJsJWnlfr4F1NJXXnFc|gAOp_b$Tn=Wd-tbO*Jc~8||R(n`p@&^Z>nl{PM z_DSCWw?Ih0H$~}G5a>#}+H*M;Lg(sg4$(DK*N&RHmQRikQ9d{&rE^!b^gnxPsp;=b z!kRT}5(=@q=2lj2&2)!LvJz0#gMt&4@rD1&;dBQxTWUd*k|R0wpPVOW{256}fIR>4 zw-$6>dS6gedDE{o_h0G@h%8Ob5;?jwC&#SsP-<#ps{M*WKSK!0WFlBw zSd#G!-YaCeKbb!2v>#>B)!fMoOka?IhoL{cZ~`Ip7Xm1kDIt$ zmY0o;s2dIB>-TrHUy`7gFPcBUb>*Ac_ul#Fo#TmZsdOhQ9T-5wv@#%0(u|V^J7s15 z*}=j7leZpy`edS|B^e!4`aUs8sLUa?yw4%a+bprqjKeZ0wmR%TA5Tn7&px?8i&VcL zQPcg+Y}?yf#dW~T(qkU?M1OPV7uWcUBvd~!F;V<*`j$YtU^+dOZhby6F_qd_6}pwi znjtOw_B}>SKYsghaAkvGEIT+ev#+nOIkI7Uenh6hwjnpSFR?Gz%mQ;d5Ux%~w6}7c zU0pNs!1NqjV{SueQBmmlfVIKcWvs~SD~&~89WQ!%dFJxX+r1A+Q51{%eNi%So0s3a zx__*-y{-mKZ?8ypu<{?RJX_<@Q;;VkQgxR#7?X_+6%9o<5#qOR4K6F&ca-ycamq+? z78)iM{j<+*{%ZZkZPQaa&5Z%s76$={6f za%LWn3m#|gYX{BW6)-;)?-%dq9q;DmwqT7LrNm%ydiqX!1gX}m@HnG>|GvlJT-U36 zWG>3+s-VCiJ=X2iDW9&-Xk7Hk&F>yRZjhhbNlJMZ?QP?C9=j<3oC(Oak(E3e(4PM;-;1NJkHvN~h01)1&KS{hMyY*#B zP+X*2OPpU>YMA#r>v`z;BP`0bF1L%I9jyCW=t8cGA+SHwqfxqU*|wtkzR%w z(^fCqyD09^Hi-o%{~WgTOxyGHSX$byG!NLgX1FFLrjCM8mwfQsqXc$G%yucFZ&D1l zkc%5G4zCy0oJK}5=VPL7M7Z#*VdvFgIz|^75~V~G7rTgtj!@o|f?d67xTd2A0q0B| z+I)V=aLU@%DT_K%N@!>*oDQU?Ne<7+001BWNkl=>+~!^SVyk! z;31LH*{7E~VxGp80PplZ6-*x{iP43pktU<*u3&n8XyqXxUD})-IE76w9kgny0&Ki+GmezOX|neJE+%x zZew+gU!4q?n|lbVKbw-skyo~SnXPDy&gXdNvWpPoLJ`-jYcu{^H&=ZZL3Dscb$Ce%9T!Ts8SK1N z^#utZ{M&lJxv{Nruqrly_L`*#wy{Y;0f`T>zmS_==v`(-)AG!MgB3Z=IkbKuQ@S}X zAl<8pMNLogAMnpLwwv3NwBaC>o|Ko9*I0G!()%Ball{z@sJe;STb~P| zPr&DQ?qGUh@mh20cxYfqS!S-I{n-A`ZX>7PEUpf=AIr`rhP|($xv#lyS43!TLvCLt zp*p$t(XECqgFyN@OdoQ7!Zjm3sXyJd!qq7tl4hcVeL)68tI?R8N^(sta_!XY%!SiG zzj>Rv#r;S3KPL0#{>Ny`adkVc){ohb6~{FFZB$i1HlO6=Oqe~U$h99K-HI0W{uIqh z3i!c--t9NH+}yO|=#C@ZTeijBjH4BjXx5*6LJ?{2Cx81_>vtawJaBk&Xyo|G>&M@o zef#=5@B9Ud`iD4K#Ln{Jw?D3iw1hibuY!Bu|rTmrFOwmxYk2U=1NQoq8c`VG$ z30(;`NIxh(l<;;yzJ4tHar=G+<;z5IU$*~UzCm@3)7yC&nz3ZFBy;dE!s&{X`F6s=HP)1!i?T7O*wpyOPD%il4-7&nrs<=kH+k zyZ{$%J>GRweWys>x_QO=Wir;~6&N0@R)cl$_%{6=wFl)|yy>slsnv$%uPo85E6S1n znwl)Q!Tg*9uv_(VxhUxWZK;R+l$)FYcxByct*xoO0K6u-%VYAqKiC7=-VXO#db|;oqa|5m|oTsq6jT+*|TNOF?{D67BBK$9eN;e2Q^50j+LzS-P=*# zy?NJDyA2!cC@xB~+Y+}q->w8Hy(GrvEQu{~`6VR~dfM>Cw6wV0&K@;ARaMmyD5=iQ zDBHMHhCL`8?V%BM7}+g6cYTVaf~*#XE}%`p<+wyRye9ShvaX_w16+oZuX$y0 z#E6b9=q@Fthl+Qr!c2idiFpxB*C`!p1cn6&RoaV!NUns^MP?P)GjW|TxzI4HP;W)G zHW4zMr?I-MQkcGW18qjx5G{66lyp7921%Xin?$M?@8GxkGX-;RqCc< zTG=?(sM!v)8JRw?X{IBrwo6BJwPC!w+A1-9m@FYW(SDD3|JA#K$r_96M6Pl3d=#Hg z*4py-uVt2@eaYU;yF6Q*`w`RIXy~tPpZ=b6+o7#}j?v}ARA20|{w1>{hQf383C&Tu znq8f;2AYHyv2NH9n1ENh;(fij1K~4s(7n_?4gwNAsQO-+K1Jbkl2D3_2(^tf=@irKU zDY^8xHIML=0OU|Q6@lko{f*6n>*@Us%{h6lV0vD2n>D;sTho#`h}E?l1+wdB0RfWIWYw3^#k8iELOiA+t+Y0LxD zul-Jm>Ae#@PhoT#D3Q}%Nf0Ey7s6g9I-5%mAjle87y9gc45k0|*Ees58h7rrHrQfY zfztb;T)Hb8G8-~O`*MREEa;ddMt-U&X=aM|pIJ{TN7R*!b*H4h(8|!hB!AR&%Vdgs z!St@O$?5AKefZ@SzvcRVj|=~J?~NR2xw>V8$JxPyZDf15HS~JaoR6wV z4oG&euJs@FmpP2|>Zy9L9V>gCbSIU+Pj%vH7fAn7>QDdXZ~v<1{LKfCzdKhkJ~?vz z`a9RJ&)`(Q{+I8(^V8#q?L@TPd%XYMH^#>54K#upAGfja@%FLzaq_Vs^u%B^cTLVo zcCE-!F)5T?wx4^f^S2J>e42-)PD-1@1!J66*r@}&~SPEzxm@Q>n`(K^iGV_$n-I*VWE`X$XoNkq!Yi(g|zA)a~ z&)whM-VjtqX}9J*W6EF^85HT@0H%vMU9@y%YvEs?dF$91bHY-JkPm-#oFK~&PL3=) zB~hR}gOXEsX(((Zg(jQ<$gz$5k6?;FmG=zXgdZD#-4VDZe(QE$wOkyyVByiYKa=GR zJF>MsIf6aprL^sy%U@ad3~S{fw^gqknupnjLuvAJ|83jRc*73j(fO(ETkRKA9#LSu z?ue4v4eE|OsExJyEMe}TiJHFll|`Eh0=K>TinB)Pft$3g+aa@rL}75I6qyT@uTjLmaAu^9jep}I1B!84-R#!S9x{Y(L#CWf9s)`+sYRU|DH#{t;i!K z>`>n!)bzbgp0F1}u24DVhKr!y`oO@eThUTH_iRjA4GQZhJ5ZK_9!^G0ymd01#(o*C5}Q&U17qlfbeB=WVZ zo1B~0#}ySv8Xl6`~o3@stlQQ%x~zJ%w-3=g~X zNJ{4Xd}44Vs{D^oZ^`ld}sc3>;nvq98cjSg2XSt7J6vjc%dR*Ir7 zDy>+;Wi{?_s2xoA1=AJLX;dd_y4YbfMO{>DmK7)KdaUxu$U3a)n|BMROJ2I1Gmu$| zlG3@}%-)m7c!b{+ygG7zz>ayAP`a9yunn?xYTH(mD6jCHiJEMoZ08cw5!SX$Hc2KA zY=~U(-p`tl%7>#3lbmj{w(wG>MS)-0Vbd_J*C2TgpV=Ok<(cXto2LeAo*#0Q)sWrL zzvkA-1M;x`6!kpQmFbn_ZM31km-ddP4c0|}wO_J-OXPP@zi6z^97^70PULinO;__Pt$tK8UbJEQ^O2CSLW(o(LlM(+{nofCPFI?`m|+sU$YnO?th!Z@ znK{XVs!6&^jZUI9d0!A^Z8lEHWbh%SO91%b`|l4nV=~A|rF{;T^uD~LfWD&C=G1g@ z)4lw2vSQNkgoczyK+AXHGM&$-+)7D zU;hd(F}=jQEf`fvFK>@XAS2^hf#`nC{-W`@dQ2WhO*cJ-M-Cr02&UhE1g8J~&g4)3 z;@h8&TTf;G@-v-kQ3NpJEy5qd) ztLkfRu5;H^T#c30CpHG8 zM&>0Ob0`_jglA2RzJLEeartWhKP>x)Wy{`WB1UFKHb#SeM4Yhjlo0o^2p6-AT z-Hi4`RNwNEQ-R>>wW2WH+$u8C#%M4?)L!mR*kin?0cbE<8fhFFLWB+ZHL&{Kr&~4! z=5q3bBZcvW(De3-ozWQ;QcY@Xx0TZ#neAQnuHsX14+)~?!P3$un^+(^7G($1<~G|5 z-??|8_d<8f>vRs4lvD=?b2fuaNKX4Csbm;Y(;;wD{H^^3_v(?HWYXF!1vd@m6 zq>}XbXUlkkxYS5ccXxHbOE0c;=`S2_I>+7dkIrymH6f798EM&Q9Fv)}|+OTPe>c1M&~{ z;MsGi)mX6L-+CzIxi7}Q{}HIG+qJ#Ap(sw&^zFsc%!Y9nPCw?{vFOzefjhSE*tF$x zw`W=kfhvo-i?(d;Mrrq?fONgHXWYe-G*ZfYU3 zJ)MJfyj&CF`r>u;Bwa!c>E7YNf|3(!o4|Ba(u;sMRu*M;fyaqGTn(Yy33-bL25?o3 zZi0CpBHTqD5e=OIy|W0lv&8VQ+auv9V7hQQUnuJ8Kfh=HR-j@z^!f^s(gE~MMLRZa z+q?n)J8Y;1pbG@5dnP~>iewdluAJeTx{m1uOxGwJumk55-U+75O2xy90J)<~6TYi7 zOFLY+ZtX^m(wUq|4<~k3fx2RK)O6`V%6S2`sp$QCcxQ&}CzBGkQrj?2lc*R*k=bdL z3a10Ckf;6|t^=r$r`jMBt_!G3A*)iEHA*+3H}@0(bNxK0v-dh0%Of&0D3=>GxKT@{ zThpQY)03RigDP9eu${) zJk01DENx6p_wrid6&aacn%>Zm?&a<7ke=n0o`s^B<>c;e;k3|+F6IQr(IAl}a~pe$ z=yWFpRZPFp={A5%bo`n^uZ1?YfHbPQ8?FU6)bx)oym?_ZyrpHC0(Ed*1NM5l-FIn5 z^~17?^awr)19+4pj)^t>V=(>J!^y9H_Th)e_b)?&w70@kAiIPSIoTMD zk-N(($RWFZf4$AaN1y)kN@FSBbV9DNW>oa2(sb0;*pNfkIjxXXr&4rq2Ig{f@!vnW z@O0#GNMd7SZu|bs>;MNVY8>m!#>YzsQnTCJ3p%Tszqr=fIf2nd3F#9LCrjDAtjWpW zD+A1(TeF9X1{(vCqff=33ON)J@in%WEya%u#{K*gZF3U=@2IB{p_!S%!Bz$flKITY z=yO0)@1iFZa{5jw&ZVPHe}l1gXM12^;`jiSv6hjX=8*i809VJ+$=Mm4;wMiYc|h&! zBbUy&l1IP&?Qj2nBJS>WHGX`-qqvz;M~8uo!L#RUTn2NJ9BM&Bq~&DE>a?BGncOpXu<=oa7930~BzmGEsqb&#c)LMx038y91;jyv9V~5{; zcWl|I!-rYT!!4)6>%+M-f-8O5yN3nYWk{{*GLH7BKLLy52Sy8HOOJp3?UxU_Y-(di z6a2v>wONw`1N>fjIT>u-3ps7GW<^5$LW2W3dS0HgyF>`Y^+hfX4cL5aXg5TmsD(LAjc9IbnN5&SHub;;+mPIBf9gm5+`QdwtQU%V zz06-FqGDJPDI7bz8UJ!D1iw+r`SNk3)|9EWjR6L?OwAe(3b`77@9qbG_w(cLjX9yR zztLsmn$F3T)ayjb{`j)3Wp;~zeUM;3lx^_FKPEc};_@BBZw zbFaB@@n+Lr+=lRW()B~cXA7beT-_Z1qP4{gLr6JoHC?;>GI! ze;$D?<#kb&ebwD1zN_*Js<(R{+p`Bshs4t^cC31JL*fq3?QMcCH?Qtkw8%H5vT{%N zX6S8Cn%#zV8+W^S0^bp|9!=>iD2k))=0(`_7|e<%rDIV{(O_>$&9HOH#*(Mq#4qAM zfsuO$i}PV>NS4S%$wY*!KW?)FcSR)U zim$bTc>;tQjk6%ou7*5G7#SSod&wf{SF{+5Iv4p8IM<6y1&l?cmBD(!blS|TrwcVN zSxui&wgoMH7h1Y9yhvD$Qq(Dg-7WPmOgLmdhc9P~sbo}Px@?(ZS|DA_FhcMs?84}@ zrQ*f)BP<)Bed!ybwnkB@mh_^9&gfM8OpG=y3H6$Wf^@~oteN9<4b2s@YmlxVCw0ek z&`j&}TaKT0nZJG>lCxUv-u#FEV42sJF9uiIW|{7pws=0QYZDSt)J0a8p>%XPt)b>J zx~MK6n9k|yQ&X-NK4d;zK0+w{B^)m=aan5mYq7=+F@4R##DcArfeX01V{$7iZ`Sxw5qDl6&x2+FZd3or=yVfRSh;anz6Rf zD>BG6Cp|QjbM&AGLcDbGw6-?q+uGo7!!>DfIBZFvi}sGT@NvTWV3A>APDr>#G+Z7X zZJwN(p0xm5x?sB7;pvZl^wEXmfh~}kM(AIGXo}SLQ%k65ZQfNlJU=PjO20yW4R#!D z7SGH5TeElWG?)JGcTS&HnBHn*8xoY1+8;o@pe60wxfuL|0xW}3JW($bGz+TNWf;bu2nZ` zYQj2mlKgA^u{>#%Zf0q2X>6!2Cx0ALk1DEs*xY>XJE8PXKKTho_plp92>X1UGmaVj z_XSRGB`SS-dSv?e^jlXmGXq0|{8qSDG|(uC9zPkdr7^NShYPg;5afXa!ss9_ATE@? zZ1ganAq#XCJ=_w0Ap8LQUe>aYM@N@E=1H6{*%y9zte)$Z!`!FY?5O|vB&Q@svr4CK zlj2_fID24{l*|zS1V7?y2tZN!=>Fpe%+}DU2;MFf)4E%sx49Y4mH-MPyjDb0rI2kS zy-1TS4awQbPAi1dy(*}nHC7lZtf(=KF7y)04lDMp2DldsHYv2-Kk2yw~J&+plej82S8Pf=9m4b`x_Hx1 z@VySU-&@mJl`r#vMZaj$Nd`t2P8S3(p=HmyMN2TzqY6_h$|FisSMC;h3e86$Sm|EG z17b=SUDY-xOV`HSg2?B}>Y`o6iKecp>YH{Pp?lCaJC#1J94(@j zD}RdspwOt|b>LS+Q=X%gY|)&d#Kk1N2np-zt5C2|pHgZyBo@L`nCHvT4C>H4xs3E6 zC1wUn7f2U8XD8Jyi=w7`Zj(?+Hj`;Z_onWRg06hAyKJBm{e^7R0h4=z>1+{8EAhVT z|J-C-{>TuUw&K`l+OyhO6XVXi75r5Q{0xT`h4c2Z#&rD$Bt5rcK7uO%*H)Mo<@Wm* zepc- zwNFq&ULbTeOn=anfbM1;NDI`*VHeP+el3rOz;o|Cr*#pGING(YPVl#|qu-Vhq#Zf??505WfR%SpfCB`E!DKF19 z5-&24-fFN3qW5WVi1ifS^efE+W&Q^L?2wQU=@+VL=yQZFto>Uq0_wL!QNMEQ&eS9@ zUt#PDHptwiw6-*8Jcn*MgsoH!K74rRp(+=peDw2&Q%MWsv$7_qZXxjhe)iUrE3|)7T^5(_}3?IU#%W2bpX?I=<*tsUzZtauy?Ys zwxODp+SH&NibM%Ap(zyE>14eC>J&$|w&v2js;{(>b0K_SY)OA?x&?aj&~-5V!;@P! z(Np67{fW?rE|0$X?cYCoxNm6WEz#3wjyZ+k45{`Kt#?{lJH@RDNmwsXez;4wo;Vu=5EAe4S!XlQ6; zC^4`g$gj{Vn!F#`$o^#8VA}>`Lt8^m1DNU`bO1pbIemzeAP2y7(AyCtC-g>`9b9i2 z;`%^K*-*V`?L&g;_4WJe5!lNP?DMbR$6Y|4R~a~vIO;b!c=Ow@zkKjGId&l2e{{So zKAujaLw*C32eJ|p2Fenx*YHb4%wsf}LKIbd*;`t=qVIDO2qLG$5%_JHOfrhm)>0;o zUeOuGoCc#U2f}EZYZ<*J!CX?#ZLAGu*4EkR>4BAjOiP9i3{g({^zvInzvuHL&0r~mx;Xh1V#psd| z`U2BUe+~b$+-`nW*{N;PYUl55nn_Ln-s%^3{|g_1HQT~GBPz#>B2d$J*;aO=qs!%2 zn~xo%HPEY`fm`<++jfLrJ}Ik~cc4w@ZyVo1s`_TT4I7<3d>46yoeguYLC*6WJXEyX z?wH-viyMLTryB`x@ogGx?mRzSvdc3fqPr)bT2LApkz8I>(7kcP@Wm4+pkNi6xV|Z6 zdyz{G;VvaEI9*(N5XU=w7v&dsd#qizj*LcC656qDn0`mSbzv#5qpv&X$3@iq!?qX{V=Y~TCROX%w{y`5*mN|4f1TzbP&Ft`-)41x3$QZ_0A{N9w# zsx(bauhD-KbZ5E{>PF|av+_y3)`!P#1%Xc2PG9dRdYYC;Yo*`w?1&qowm&YvFGVcg5ok0V28za0`#K z0?aeHVw5pmC|x+6XNWv2FsyO8VEeQCiqS=hMN0R5jf-}L`(=F^?GNYK(m4!z5h=H# zrmI*Qwo|?~ZA#NLXmxZ1#)a7hWo4VWV!Fbu0#$t1rUWRHWUOh$Y6hWGyV^H+UZL#w z)O7VKioi7v=2~CHk&vTd0%WzQ?rKZwh{)A*LpGE{XS%3u)~=qdQ+p%(A^W4P)^?9q z((XU^l7DbVwokTL-N^Mb?~9s-$ecvG%&F;$)3qygc%&n#PU`w6DYGe&(dFX<*jI@! zT^U}4(@lTP++g!H@!4A|w+7m;A?1Sg&oCXGov}c!Ko_d(81Oc7Bc@)tG7UPpcx6R9 zxmtLyh+mQ5ZQ+32URoNP8jxhw*jE`Fi+2~1J&1J1*wBUmawz~1dkaFKNuJ=GJNIOT ztYsi0(ozO+hvC6_8ykBkAHn}Mh2E~|vC5+sbw2pV}+ zInYI2udgRdn@d-{d;xSVc+wl}n(L{8lZ(R}>RKIgaQ2WUp zA$82=sd*JNA+>VI9*5I80TG#Nq?u=9q8 zwNtYG$V^eGIq6_oMrZ%=K zG5z+h&rt!~4~fT~LwwxuIWH2vuSKNvp#y^HEZ2vGl ztwCXIGaG}uIhbx4xMS-+-ka@wYnITL>BKzj>9mKHvkP!K%Zv&e^HvKVf?9;qNk6wV z(BT#hJv-YL+Y77Rak^N0C&c3hvtNiao!P8lx(sGzq_t3yz^oRd3sSnf*wYsZ&(k-R zUkFRm-rX&O6R*BS-pkK_^}*faBd7d09p+A_(w#e*0$ZC~xLc6O{z6SR{W<(kaVvo> z<oTCz@+YzH`T+p-rC0((L}+O zopGyBL0X3$ypFV9>N}l>*QeApHN75JUF7NEadGvDizPrkBKV1pMfnATB~2wUXM1|< zqR4h(JeM5Eu^(OHzzAptL<&trIp)Ax3qslv6hwrSN~6>Y?? zgp$$)#<94prfd^BTCx&M$Hf7SLf>}E5+lMoo){r@E@JW6AQHM@I%q0=k38&lcdL9C z{OCHLi&!pWH_j3n3eF*O?O`HxSm%lTo93fbkE(!2&2%nwC{nDLM?@Q60`RG%bPd=w zmKRRd$W&Byo*~Xc3fq;M&OG5jnain zWi|T*r<;cCiD~FNsO_ZUU!Blpd2a8uRCqPt}*2R7nbt8tPUKg*qNeP1hM+ogdM? z={lurGCJ3|)0dk5q*08Sfcuf0m(X~O>Cbsy;B$gs6s5}}ZUDSn0#7Pbt3Y(19m}}b zc?-et!ov7yN;}=K$oOT&a>=T7qO(t5WtJCS0%dw}vdThDw=`HmJ;LK6s*5X^zAbca zk@hXzct>;Q9>1*;(nWB`yX)gEGJSk>Kx~3=I+#wM$dU%-!!&?>0}~;_@MpofBy{;jESRJS@EZQYNw>xk{H!* z-2&5ZO>|F8mnI&)R~qXcJofI`p=~$6{^{3W-h;LSQu{KAwm-C~a-1?=gE*0`D0HN{ zl?)L&91$u`rU-%EH0wlBcQqO_LmxKqgN->TuoP?txKaY(moPap^ClfZXS$CJN+{#Q z)W)bszx?fQdnTGwTfQRfd}ij@cAOcOwW-NfXU`9Z4ca;kxI5VDrWe$7G~L0oH8uAK z#l#Vr*WCW#OT_fAAGEg#dLL|6gnp1Z$+6(BT%&7VRVAE$U?^~3VnKmi3C^eszR3qriLpRX+OB zmVNX=)%5pqRQMtP7T|ppRId+lOeove;vZT>BUjY))}DBw=qV7*}0&)t(Bba@gnWT z9CEj@v9#eA$IQYiG}M2g|4<;L9yojKSobu0MkeDq3_u(xHIi*w%?V;;*2+HsFx|qb zRn1Q^*jNT*d$D%sp9X!jqT{{gDfFHVfz#C|tzTL4^T_SE#Zc4TMNOwwsr5o@I+%j- zmgY%04i*c`j$XZb_1^I>|L%j+pM{TNTpJxd{04EGuIA=^0qP62pb*oagcrB}(MMqO zE3d5bpSKa#i`UM(rxstR>EAyhFYYhcTzn|1Dlw`%X78%q?ngag$31tq+&u=CU0l+! z@zB;C+qZaL?mo7zV-=p4l3l|ax)T#O!Es>x%0=ruJZLzI^c_=KdFW}{Q_M1m>2_SN zM&<6U>g+iiQ63fHva4j+gZM?pqNb=rb(`(Plzx%=Q{o(v!F}^PdtJiL_DH6=sO|{d zHDsZe#|WP*O7A#vv17PoQA)(6UhL~G5uQltRGc;;tnaO%SrXf@WF;t1=DKqV5<6o4 z-lZ=s+1=Aij9O=B&oDJoJ@+AU-_Ajg4pLr7gW-jnl$t(#t*V4V*4JPEMU4In0iJ`U zD&NIJ+Gj2iF9>~nHfS}W8}PZ9yf5-ZJ5^PxZ0O37&5|IyXwSIPC4*7oTr{T(T+R@} z-Ho+G+$FLGSz5GdO=6d|+crVzTf}&SW)G%=!oqzD{Dl43CXHjkZpC||_ABg^C(6?h z+vORgy@)qm4CsRDCQKLPldKSNudjm5RhxM@9bjL)L0BAjOIjN5E_5z~!yz}DcTu}Q zNDaH-xtk89+q#cz!|S5GHSec*RyLK*0Mn(kR2k|eAyVA$CT}|M$(BE(Pz}Xvs!0#d4k5q+T&_jwnvVMwpEI<1-muGmMzx4Ot+?cb5GPDU4BG8 zQ+*Wbr?m&yHs3V=(54|8qU)qia=IGoKxl`DBVkh0)$B^HG&No3 zSuD}k2r=E1^YZFa(;qcAcMI=@*#%pxujW#kxn>Ptl>FS8)n4jP+=!2BG|v$#M# zOMX(?&tM#f@Fe_!s}?ld|SXH z($zd#xWzsiVGwGuP_~x^D+;r`6Nt7Je?r2k(H7bpUASCrJ3c<%Hx4`_wIZ~_>9}6L zdUyX<@3H`_zbnxn?^-8@FQfQSk$Zi8>D0#`gXv$i7aYAB*dmyI{Jro47F&!ZAhnvG_Q-O=sKc*erF0a*WkTzs=0Y;a%$$n|GY5s zD;A^rm2X%@_6)Bv zJsmYWaqHpufvfxa^GHR1w`F|dGHUvlHwOo+QqzNSa`k}O&OOkQ(t+>~oI2T9 z(TRIGc#sa47@;%zUHe@l^K$x{QPZ27`z%}S=^aZ3xebkcMu#p_L^?BjeN$2AnHwKJ zOiijf^XSoUfBEsXW+dwOetLc8=Uc9J85~jrk{hDV*Th8i1z0&az|n}c0_jvTHWcTl zoR4bj$Jk<>%B+MuKp4vF;~3r_3KofYj375&YF)zy_lTLYo=951h= zoXF&goHkpM3~{=Uh(gpQc|QaMIg~OX!jdu?64Fv19*E%uyNmr{EHCx@t|Fa>?>jtt z*b&>hkh)-cJs2N;U|)#XT$HUHfBIuE9pn0eeWSH~VEUI|-YhV>kA}ND5`9>f?SEis z07DFKb0Ek)+DF3FF>K`;qP_4~6>@S&5{by=bY&*W{0BFxYqv7<(WTU0Ijgrv7br{nfFGW|p^mncPRe&;Fs zY_*7X0{_v$&8=w^O8-$Fr8B94sVhxJ`PYG*9#SU1lrkcjH<+74>7vEUMS0WZX* z2zVluzqHL1>uA6I)kXH-+paZ7dCK<{_U}FC#ohmEM_`*vL{w-4sfBpc7glcDb8HLp zIW28AHmyqW+_f$AD5>dNHlJ9u95KBk#>3gAsHmZ!8;0Aw!FjFS9yo5px>bwnDhD_1 z+Pr(W0=qP^nNykB8C53%jQMD=8#i1;u3kxaj7M>GoY+D@_Te;XThx@|+i^dthhW7X zN=)TPYdSh=hC5=4Bd9Muv3mUp>0L_PiwE!DSydO~f|3r-tDnVM?t4BeO5EoJvGcRo z(s}I@DT}bBFY-8>7KVrB{Yz(P3D_Ay;>+H>QAN&}UDo|0{O`P;Y#2cO#$eSjX^(50 z=3%-Wc&zdkNqLck5(sl0Lb?=@B9(7sk6>{{v4YYi5V`yWrWfIKSw&;gjdq(=MP_#ZOQ_+HL1d82bjOP>drQ=ZSqpY~Pq_gu-FZ)rvo{ z*l3upP#qkUa!rw>MNJnII^Grq$~pwY!QdY8E<7q~I+%{PSz-DT4~#AN(kVZX9kYuO zM3)72*NzF=E;wCbx>OQx*;d?5;Vc`7mcE2d6Fpt$Siy9T$ZFXXHCK>2R{h_Xj-!I= z!s@0W_cTfuP*s@DuBh_@8sf?|hd{r2wydGKS}#DZzT`?fI65|)$XvTCn<;cX_azjr za9b_N%)@lg^gMY$Et{_8XVv#SFxMANvxT{hmCc6Gxjd()i{nN4U9_kdF{tZ99f?Ki z1N#Ft9Yog(gXwCd2>s7+y@-}RPffQrEVNGCT6w4-WPvw!m%{nB7YR|90hz}u{uU00 z%jHU4%aZ;`e7sNmDG*v4iqUy3ly!&DSa&OP?=@?@ta1voyc&YCoED1V#ojtwPS!76 zNMRi3^0B2GLKL=#Q?TA6=NaOi|+O#O$5v zJJZ@28k!0}aA0Vf+C!|#AtAwuftmY)1CJgGtXI}`i2&(qo)FJVaQ)G%Bl{1J&~E3i zN0yBb0MiY&?FJiKJLTp^3Z{?ST9pN(rZ)y#9{|&@pqiVk=!Ch5iVmV{kRCe;<}=1e z55G5a;R4N#o?f{H!pGL{Z;xcX6)A)5IY~*$L4BkX3g#=L3`9PeK%dP7{4Rh0%{N!B zNbJk+f&P}ESwb0i4EfiG3|?wz^?CQyz^vVA!qdO(?Hue&k0qhc-Wt)DV`ae6tS~(& z$$`{uAh3&eq+~K;D@RK2rx~eh0A;?CFqvmgOR6zBRbfFxdC7YD`3z(B$OJ{CUzGNb zKfI5e{@ahQ4J`ZWJ(AAv-rW)0McHXm&R|T_`5O&Ryhmh`ZhE1FG`WH3-1BEBr|il$ zxMsB9rhpV{dV5<&Mpyge%yt_l3mH4n_jev_Z)@vs8-&xhZVe1YOkd%U1E%MpGlShCW3)CDY)woY+InDg=*Z#}4mXR)6I52d7WIM=H)KF7~Y!>8`Hng6W*b`me?_ z|H=2)do2+D$}6v}-AHjCsqG$rc)DW~k9Yqk-;EcW_wRcI)~xr4t1HMWiWuIz$kTD_ zHc14>e;l(h#W}{s(_>TUp>5q;(oQUEH@%9*c6N%@9To-5h7&YNXiHe9x zq1Px~MN?ANHN8&%(59$}{MFQso;ZP(e60#<^!+rd6TKb#`mhv*%1Z#*bRcypp*WR% zM}7<=3!&*vzAx=vRTB}D-y4BQ-`RQN2Ave6hLP#_Mh!Z{MN1@$5y>4d3_&qbRWZ^% z>GfZn*AG5C3TF!pi!Kft15S$1eba z!^@nEu2H&>xX9^3<5<8Ip0h$YT?A^y={#fm5h#82YQkc)0!$%JQP8g=VN9Dq8Pn|r8L4{U~}14epU8RPP%D(n&}hf0LcYZm+q{b0Z?K(79I7TBIiF- z(@iX@ZcUtSx>ab(Bk-&2wnAIMUB$O*K>&RY&1H=cxpq;QtT03ElG%cM7^#mG!3Z#pez6LvsiNZ}R zt|R$#H`;R&7GQ{xL8tVf#6&YIbMdnWSvjTq^_hvt&I_(d@Wvy<8zflxTZ`Mp&)Q%m z$Raljz3mObx!DGsF9s_qGBw!v;2Ea2Po@W=rWcO3d^PhU;dEr{3s0ZU+?u&{>&h*L z?h?O6aybxv2Pet|-yr+}#MuF?62$eD4GN{-KF)aiz5o5c1k=B285cFZp*=X*-zq1u z!8VdaX{(^|+~B6QT%!MW|h*0r^|qn#)h3P&fih-^#n!zuImH{alZVUxx6 zGC4UqS{X5MYj$d2-_eIv73R71hX*F^N_hIWHw%ch3~=zKu+YM<){2RY*j{is;4$J% z0Ok=${h$cyG$XBWO{RyGvTu}14t%Q5PJ8k`?9DCA9R`r0r)Fk;_GETu=B=VLXKq|; z4sZ<^L{0zgZ~r;5rR6Jey_~#RADk255RiNcb4yPFN_UW}m|kdp#d})WG!)0w#Pqhc z9VCy?HTu$R)bvljBPkuH%l@vhE-FM@Gj_^2NCaV9TU96j4^$Tb@<0v06jV24xHcsA zC09g7BBe{PxDlI%gLyzeavrIV0jag);{y)v*7%s}$Ciz89X{4FRzF6RCPfECVBhtwHTTkfp1xri-2~t`~mQ3cX_Uh*OW{(@*!J-4#8(l!T6+&hI3RYH>zI+R!YO z&UeL22`SH{27zF8gC&771TmUplcBExzIIX5DIt|eM#*|{ zx6ZbbHo}%PsI{@T4h}4X%uj`1KK;RuPac2otHbY(E_8SBqD3v8ubjNhEiJTvtS_$r zvmAl=a;-U$qV>f;pqgh&%cWNXpOq2)XW8->+wmWG1bmzF%Ln@gD4QFDxHZa2kk^S@8O9lusyLZI9!@|Vw6ivPYGe^7l~!W z?*e_(eRP#eT~Um4QSWd~%$ZBq&b4ygnpHTy%v62Nyky~psxnc<&*$|x&SN_6wM(5x(nMPrt=DR__n1BkPLCN zFu-ylbA`EbXO9T#aeQO)jzeSTmepcZ-+rWfvlbR31(*u=L>N~JvuYc}W`T!*usGr2 zMCKH-shXzFPoQ5fR=g+Fr)lS+zlxniSdXh!g6X2OL+N5`R$97Xx(B8gX==ot=y8m) zQ?NQan}&kE$5ZXhZqBICl62GdJu2cwW)9j6L3%B%PzNK+IY4!w?ZvEC#GxYs}6{EWzx$vE*Dy7$g}1^o#$ys@Oe&GY%N#w#&dTRdn;`J z{xh_v=}(p$^#~-Gc;jhF zpsHHn&;S4+07*naRIt=LVNC)Kb*wI4L^E=0Z|>uju*PkL?!FN<-LYlpogaPl(MRak ze9L%pK^);%w9Az%M56O8?9SE1t?pYQxZjzcqWJJ|ef8~M|K`_Up8S>q%Afx9FFt(p z!}ku44y2~`=S5P1>28eygG_3=PYS2!;(2M`e>j}F&?_XkF#i7cpI?KpL-AK&i1%+H zPSVVs#-6FtvNX4T85uMeuD>@j!}F;jUDkCjvcECatTff3tUlzxxUQtjJYsSniw2Vk zM5TWYq~vseTU%yz=;*1I>Fsw<(v9?H^|_qnRCnS! zXf^48bPA-a1dt@`=}9z}WHu0dQ1o=1;RL+9W}ur=vnsQQsy-u;lGX&+Sl9$4l?g)5 z%)B#0lKCAl{S2+0oRSAo(|`NV&ACcWpZWRa$75Eh1MUGiJw!4N<|La%;+H^HHn&Dh zk2JR(467OLX*Sw)8L}fY9)E)8<@T??Yi=_JcXf@u(JE;(K06P-K~d{DD80Y!{c6H% zLJJ1LbUJ#{>y>a97(EjFrLm_2jXqJ+U72ts1tppJTLb800^~&ZP*nh!OF+7Ov1UK( zK=OKG(xsh|{=I+MKaBl@x+m+Fjg5LcIwr&iM};A$f7j}xrigA{J`!=l+$uJfw=xsI zONRVfaT{$B&B-4yJw25+y8We%XzJ+!$w>}o?6uJ{S*kM`hRAG7f>z9(h-@U_e?=iu zyenDi$@pH_g=8C>=-}YQts#l{;HNJ?-M-H!y7iz?`oVVNn6D~j z1X3F4Kx*JOo)byHx@hBA&zZEs=P2&rxHV>S`O=;|~zjkAHR8o8l3=iP4OezDicPR{w!$@#3w2@CYOv-MrFw>C#23 z;{r_<#Anaj!vDsc-S&NL)s|-~Uo8DsKLTrfJ)9$|at0$(d>6%yZry^@Ve_8N9_yBP zcI{&wm7@>i#nF?h0^2Bp4~QBFo=)5w|aZr7P~!IW5n~a$hjzSM~sN+yEbAr zcTRKJO@U`rSV;^9mJ|XFPl$D+3EJ*hI$T^FBgLdb>B8PIVRb#d6nA1-*#Ii1tR^3Q z5w;iK^3J%`l7ODF9$O5rL$gtE9!AI7f>TD?9ZB+HQ&UgTM1D!!aLNfL2p#ku?MPX? zckf=`;m%^V_fp+?wEFiiRb6TuJkv8=1EyCy6ZEojF>*Sg=_xTp(DZaRyELV&Z(6nL ztp4ku7+l0)i7#P5V5^-Gvyq7IQx#;PTE9?rUtG1-9)Yd?>o3}_qBi)cLTq^|5 zw@E@bEy{Yu=AIbTMO7D0CriZ>!;7YsE0z={SIs=p(0PBEKnSF3+XoQJMqztllc7d7 zRoWYg=S8PrMdz5)HA)u`k6^QAhA|n_H8p+Jx{YZ#)8(V}kUfLfrG|84i6V7&ROECf z7pUoi>08Rn_wW(R0b*Jq?=54kI#z5An6A7lOC&8v3^DoM< zQ?oyR^3D@nFHzUv^e>tljjeqjBd34-MIWaHkkjwpy%%hm6g1#afjRwrR0CaA9jwfg zu|})Bkz`{g_AZCinw4yNC}RAsC{>K=PzX9l&I89U$TdIL~zqmNPlrNN@2 z!OY64iVWAJBqkM+4Y^_?sSqCxSv3xV>EfNY#(i&_9UL6~m>7HpS5*5_4?OoJYo$CG ze6JTqpFg-Sovax3^?u%?32r-!!hZ7Qm*4G-c3Xg29v^LQX>D!h;O`z=8^lIPcncSj z7WuZZaY~TWKUuEQ8laiR0MY?K3P=rXqtQ~f)WC@ZD+?SiPSGo9A*!`JTCsu_M&@Kx z0_jFWwmA{^l_CCQv*S+Ra@5ByV`tkrN^LP538gP|v>#QKp9=|Tfu@sTbi##*b%et4 zzzBN_s2f0YQPYLe`6)DXE^HSNVK>L{ z!eM_QN})+U>iIO*kX8@g5RqpAPZeR1>R2)sA~e~L$-CT`fXpsxT-Umj;2 z*u6zCY~$)hDV`B&O?&sIwQt+Fu4A$9-i{ht38AJx7`#+8SX5jvc&Hf9h8-+-aq*&y z<<-S@8+WDIVQ?9Cj){w?i-?GefV`2-k=LD5E_yhxZK7&(Z%4$T2-=d0#E#`eVSrI-FAoNu(=LigU+$=i$|orydq|)&+M9rWog@C7?W>^2H~d zDL*ZVDvBE}d5V-y1*ueqb}ZiO>$`V(NmO0$+2RJOM`L<=1}{ClG#GV5l3oS}Q-HoD zC-9pSm0sdP1Jj7XDnevZQkE~jp?`u3fCYF3gHg}HP!<&suHWbkkSb2+NWXV*HD zn{I@^zyGbTdUhjEmRFej;*LI8P!E~zYkaQm$)-Oyw2$W*r?dO&vk`x~d_*#IP?w37 z$@0Q<3v0S$X{zc`D1H8z`zvH^9a6cqdTX|uq%d8idU++ufaGQLA7quj$P0_U z&d{WMSt9BsL6g(P^s+|frhlZ5H!r;T=9@qI(T_g*(T`YE(5_wmh3RCgw5?z0{U=Rv61{{Bw+tKf&~J`@8qg z^}Ft*a`%m$KBPh7czNTEHx3?DYI+rzUKu(V8kv_IkVHZ~Rii}7kdT7+I|;J}5FClG z!(fw5gkx~mY!*uI@9)F3ZX;s4Y^sU^GKlMh z%26i^SLJ!3Lz5Rljd@1QF*eD`24i++CH8ddeN<1-j`T=b{E8JAe~iXfd%zqWohx@h z9rRuZj7zMLk@F(iwl=8cRF^6>U3CGI;8NyRN-Wpbik=RkyNkH)F5Yyprb`tmyv}MH z@vjrkN%=K_K3Jn1t?7~Exa_l&-va7)-`Ypw3p0y^H5R#Bi+3C~{i}a*`{D?^I0ApN zN5G{nETXcipe|*(FPOe<3oNK9y7ypQhRQwc@(D_ei;IcrF7~h^h0y~M7T)w&-?R=feQ$m- zP82b%q@=7bNz0Fj>W!m>HOymp!>|M?UQAgJ&nwT%U@_>P(zG6Zo&HEJJ#|rM=t??F z#(ER}6lC_5>&QoMTC{5rUp=n#4j{b)ia)Vv?@OrZX#c%cJw;VTodn4AbiRM>h6KKx z?}!1@n^uzYNXq&N+A~Gur|fm}4x(?3QOYvC|qFF;+{)8&q!-)eEg2&W6W zBc6*BL{30}(2%Uo>1oo@$mB`~(YN7jiBozy_HzZ}`mK;T#48UePmF$d+cr--@tkWe z7M$J^F|$GF*@G(vSmyk&|;X{`Dd6O<@Wo-#O0=2d5Y;vUc~h7a|=u!bT&85B9!#6t<%MHHJ6ej z@Q>Ogg`HPJ0lH4=90=ib1?pPNi>T>Px_Fi3lT%VUOMIFB6uDVj=SoGNHGm9Qi;~V) z0{(IDEN>dWcxPoLcyZNoCQEs)jPX3HBoghMqRkId?MgMQ|F}@P z(ROs;?I#yzrV6w0n@ea*Y9krqsqTc)Xi_>RoLSWSQwa%#R!*vTmv6rL{Ncks8}hlw z2V$otm=Ao;ETDD@F@0iUFte&Tv@iD5sZ#@egWJCT>Fuv?es(Cdw$|OkhfqBW0~yMD{kI-??w-D_yD*@=JIkG@o{xSI`cj8R1T;gfe}W^NUo zseAC?%$aLdnNE!pzx?=@|9q|St4WGTXYO9!XGj{Y4RXD7Uu5&-NQ^a>$%x4qD}-Eg zJ7b2=_u{3o_RnckYWmmTU8-ty9mA~h#?ICZ*Va~{bS0-_dTAaUEE){0u4-st8bpvv z4(*I0smPRhhQ9+rg2rreP-YZy zzH~1C^w~eLzJ>m|@jioRKM^&3MM4%c&S)D>L0J0ZcS%LQkBr2dqs!?+>NdIA(vS;x zdO&(!V}E)-VtRwErHu{F96;U1%m$dYa(5z#F~JKdT_b$gB+W{i0P0zABr)z zvN9-S`iNlq-6Lf_fc!zc`sA}X3a6{Dg$mT^IBLs&Yt4X*DEn2t&=_0d(@gk>lgPJaKx|J0#rs_+XN6g1+UztI3amGQjmL;?JmKLDYNXv#{kyeTDS z5f<`dz!^1O8DoI-p5dsdsC*b51Zp~gYvu&RhNix~C}J0tqol8QT>KO>`=XcjzSOaI z`PtsE-a0n6r*kk0`*~+)-I>n!2k&>B87vy6sS(d!f@LPH+l8{yn9hgN#&o!&>5TrN zK~74I75)|O6eb6)#B{w@T8+ZV__0Og24!P_Sy7*&>ga@J|ybWy2=*tcyK!;8GH)+b55u1p8${fglmW>;D|*T68Vm`>1!3GiO!yL=IK zrfb(O=9UdsSj#OKsIi~Go+#<)u_DR(g64|S73`7p;=6pcOgse6xyXXhx!Nt+HFi}B zOg$yBF^y{DJtR(U+bHHBC{@lqh&z5Qu{gr4rs)CVI%2w-=$HZ-WsCk`$SOtb@}L%Z zBJ&D0OuHgGq#>_KQkT2(^+SV=Q1q-{sXHvo7h~?OT2`ynI`yzTMSGg|z}&T3sb9$} zsOPB#)9bM%ysop7bT2)ncKQ&c^RxRnYAqy;^SFfukND-0xbVe^lk zyh)iUq%N!8H0kVb{?AWt|N1At`E!C?QP`hceDw6n?8DGzMqgj!Kq(qJkt2DKI-!i? zwvml(4Y|R!=-}UcersxIoHRfGGV*Dp2a`i>Y`POp;?_|g$I+I0+SXJU4P~R#%m?14 zagNwm=tGLzg#2wi-i6+z6Vn5ur%rK{#P0GrZkKO9|NP-(siBobzaXJ`evFPs{j~#A zvs9`Mh7NWXg$@zh=r`H7{VwkGleag8W~C-ML_1}qJJ~4L3(Sl-EZQ)bZf0d0tkm># z2X~@oo3}b4YFFenSGBjd+WYvBYEO&U09SWI*Bg@c^0S}K-0GfE-sX zA6K=dFT^!l&I;`Rh3l@Rgrl)N=_kH?soKy9`~y zUBT^{kK3`l$oOpDwOZ6xX{)ImrE0YPjWM$2_fudhc6K_`D)Ty=zHiL2Hp}f)RnJep z{QAMc6)Um|S47*x#LR6l^Vf>=#^@?^o*`ElLZik=ANRG_mbzDiS#KaD$TiP0EO&S`QI5a)`^z!Toi7jw?e}=1T zY%M;Ng`-MScjwyLovcO7F6=oyNa>PfZ$T&{y-9fl@|GwVDK`~09Y?)DIRji5NgYN9 z)J2$AYP#l)v0w^jW`>Y%Vc+T=on_{bRqLKbF-ZJqxavsytK(x}I_XT5kMGz~WctVV z;`YT6cyR>&RFA+Ka?PU(l8Wj)e3xu<58bwVkKOtvD7}39?)8g&R~1w@y-r~I`Lj{P zw#4RoH`#jFg)l&0rip? zmpHOr!iH1oCOY#|s2g3|w2odzDb7@YdMpOsX-$NPPU)yTzhm#qWYR41Ey=GbIe)3M z_blFbf@JdRs6M?B)k~A>L8?qUPOPJEsq^NDI1fS^!=eVsgCr*A^-ld`1dJ4)1LyFc za)`^~64tInPFLWLzN{STu&mIl1gUFDj99y=9n}g)MI%>DMMY6p!RXpu>O~=R0dkGn zv< z?<&nCA}FW;P;oKLN8F0Sbg?%t5=?*XHI4Q((~E}b7;I#>cvG(6bq&-d)J9w{64?o+ zGxm5gAxV?%U=w6M!>t5ZuH&1bfwyeIVxjgWi8gAh zKQ#WxYK6^n0IkC}Ts;TcYC#U3ENGCe-_f2U56vI*fA;&&&|XX9b2U3KZK!PAvu~MX z=wogUrKU4#pVbHTERs=8P#|`V*HtPbwse*9qO^4R#6(M1UuuChrawh)_KA320uAw) zP=I5h^ejIZz|5Zult2Ue0K&OTgXr(mk5RWVkAk|`0IK_39rB3g6W72%5|`B4fLJGs zh2APW9RL-7dP01mcXpqHSC+LQ9^7`f^m7jlGF6aD&bk6{G(cFh1U2~j zM>8Ki(Uf=Ob>)xw`6oAi{p<4=Kb1jqQO5A2M?Di!6GacJrb@?i`Wj&LHe+67WKM3L zsw_>Nyz^UWJ2VthFL@&jgTX(jv{Vva5HiQc2xVVZPf&PpmvPh&HT}ZuKIM8Lx}~uh zH%;S1X=fxAttjaPZ%{5PJx8&-2&7Lnm-ZXa88MKT#>P%gJ_Oz;9+qNjzH@6LV&c%? z!-t`VLQb8EE$!R%!vNF-e$vndezXYI8#7mG_t%Fr+QffeenXPTRuBPwY znPHLPgfpi#qoTd4icEET_av#D3~;SAAL|+$9i5$d=cAd~r?=wr&;IVrnKPXYL9xwe zFsJ`>-(<_=|GIwt#0Q(u^uie}YU5 zoC*Na>$~=~?`v0-uG9EuCRzO%sOyhVQ_7qmoUeBB7~%A*`}ggm^i)&R$NXaxe0&;i zeDdXQ9-PZ4%wm>jlWhwTThb4TMD)DK3J6_;bh)M`)B*y}LQdxt5}#dae?WhQtBp;z zO|n?i8RV!~Svz@qMK2^UU8+Z2D{PH<6*(1>o+4VhgPDz`dA4P=)z(1218;5FGV|7f zc-nG7>2!eg8(4^lE}X6zUg*6G_ZzYL5Sxy!E=8mwrz=PoERXgkO zJTUXbbQE{>I6v=BsJaiii{^;_0qy|-v4vhtCkhiB_usqw!MB(9zw36&+b!PSKP0nq ztLb0gi`y4R;KdR6lRW}4adlAzeZ{*;CGWPX-nJ!webf3h>1@Btd6DnB;w`IQ+WUG~ zPgq3f*|3t^U`2(T->2RS|1&=OCuZxr;K>YQ+$C%m(dTjbF&;d1Z`k0WZisjF>Wf&@$w+T%s_95U11Gj+ zxFlv*RD@@~v?cAJixKO9wx$zM4^$4VcXVv%juXJf^>X4`rH?yb64g1_ zJAA%J!dyD5I&bvSkF;~JlgOBr9UY6BO5)<;b`cqanl6~W0prYBUHMzf+W=P(nuydA z@S?>sE?Nv>2_lOV22MvzC-OxhtR3m$8|*|;w}V_a(M=Rby25aQalvr88z-o)a9u!M zkevHEvGW{FOP7$wjq2S=UR0H$OmsXpZ`s33Z}AZMobpxSbg`AlHpA!sk4Jp`t<*>#5XqvAyv1+N-{c)-&l4uZw(mGNgV~FkKr$?n3Ge z4b!_fZ6`useDty@Ds_g#r-snEfF}j5iwJ+=Jr|pD({&Ix5vz7P-vu&9t)>ND2Cn6! zpU>o`Wz((3+9p6&%&b;DcO^%QZ|zEZMD9K}6x=_zX70|spEa$U|7`tD=eFUw1#Lh1 zp!m3SN|z5!A9AF$L#NbqIfhDGSGII@#m6W0qkuZ|Fcp<9n6747bG&Z)Q&i|4cy#O5 zOnb%Xm|hYRVyQ$_k}M2PMIYC-0kr|8jY&eQAWIwKBAqlFT?x(uXX*M9nbVhpkvc#| zZ7hi=u>-ZpwOO&|t*z#{4FRdKc}b9rmy>I3dT0*tgC5Rh1s86l;#9t#8*209Sx`T4 zA&=31MveGW@hj44Zp?k4s9A49eHbH zXnJ~NgzxE@>u=Kug807*na zRG8u9?jJ&?BW02y1Jhvo%+TS{A!#%!?T_%J^TT(@i=2IH2qm3SE26nj`mG5d9m@@l zZ>9uLy5PI$=~E;h-=ij|w6`GNE?fx(S{^P2a$*-pWa^{`8n;ut;*9KV{rQc{AUX?u8 zS~6G+hO*XRBNqPVy7R;5tAlN<2TJqWzoUlq>j#9oqbG*Gczrjn;p= zOgAJfl7%jMdRA&Prv8f7E*o0M8Y^tDlUOo^wX$~4^2YE&gI#{Nqg_dT$7f_qEvi?# zWsa4DyX62g*reo~%AEM2Zj3`CBUeY`iIC4Qx1g=mLe5oD_bJ~}&x@eWxf$`i^ZNK{ zaJ@^{B56J<*F>ksQwnPD2ds;zK5rn)Bh1H=Ea~pVB?;idq4C*KMznehYU$(%{-4J5>Yw+Us#SwUM1pZ`?K+158XLZA-7-!!_ z+e3=u@-bg;+_q^Oor+c?wXSU1yQ-<=Y#fG{-kR5mWIS6}*K-z4x}dshM@ez$rf$#8 zPhmPc=MyWT`j}nx1S)yGV|ht&b@v9ljcGI*-RN<#1UEVCyf!Wr93hx73Au;#o7vJ&yFM?`3CjHFuUF`gK1@)ckDqP2uecBDl0^cIO9J-;`~r89JJa4@XrQYX9~)dSrVxIP>g z)t%;yZH7>ohdmM>L!%@8V-(J$;E@3W!&4$)i(V}Zyi#GYXxZWfu_Nk6Kpm__QYJ;- z*=~!p9aUIP)S{{jg~e5iqd15i^NV^6aUCp|2ecvB&X?|a+2g!&r2r&Kx_To(dGl`1 z&6~G@>7t@bsyk7PLh35@P}Oisqa$IyC1PfI%@@;)LP5oTTnX|CDGQ^^MXC^$IbE6? z0qJ16v^QF8!gO{CKM&XJkF7JjEq?@2<}H!+`aMP7Le8d(rj)C@ z`Z_*Yllmv~H99BcB9iJ)v~qYZ6`Ue- z8*_7W^CiAv^}K%9HzZ^`x^5It&2@94Qk}aux;1Y4wMGO;tw!pW~Mf#<~g7^ zW~Dnh#a8yErY`jJ_9nRn0*Alj+I~)N1y%=4b-{*CGqIQna9?~j@3iy`|ESq@9~zQTep6H zb^NXgWPXp=X zSb9@AO3P6RN@r34q^G6|qf?a19A{v>ksqLnbaHfnD$POqqFOd1#;u=WpTW{^?Q)?5`a{8t-_GYtgURGbrY`q#J5wKey9`E+sG z;SKCI1gDFf?z2;BNNGgcS=3onz=kyEHR9%vB;F+3+TV)ALjx0sU?6=TmUI>Gq7nIX z*BW@UYHnfwvT$0F(&%VkeP(zW4NGZDT7Q7dMs0ldPs>KLyfWGzeEFL%A2cMsqPNz?SYU zj+bb28z3Fa3Y_lh6q_{8jKhrcEU8I(Okx9%+`W7G_`TzoullsMR+yVFq!FliS-61J zTnT@>XH!5boUW=O(m%cZA4YKz^{Vs#pHdNkLia;9o_xN?2mPdrJ7XKcEon% zd4EU8Q?67PM@PG-^Y4X`;4PH?)jxfPJ^l3Y!+u%r4z*5xe$=n(e{Wyhyf^|cj=-Pp z5y-DeDJin7-t6q_yWJsb^M==Vm2WFA-;LQ}Eotd{UtLub6LvO^Z&c{L=j$S9S%mL9 zqPM8MvV2#0a~kH)^DJ>5%Da(zGsW7cSCm<8N(M#$V^{{5vHT(Qk07e zzV-+gLSQH&6^}{@xiOoaoiBQ9ytw)z?v;)vkEW)mhANkmvp1r8;#^_`pP_0BJIlRM8D2 zb;0x~dBv1rm%8n{J&@JKigO7}$D5vF!gLyHQt_zqICQ=a=eLs6At&K?V3Y?nE4m$e zIv6Xey7PL zV9Gl|=}Q3kKZfZ_TGr52GNvMI71&uxoN>C7?MaE9!$Nb1k;r<#z+%tQ}+5maY# zsOD7~r^}p2Y7m6UMM0l~bbVo|>2Hx+$ksz!1MSIW5m2YiPEZix=7{J?sSX3Mo+yG2 zV&6>?dqQLLrT4FOUb_UT_rolCWQe4vyC$Qiixnmn6GLABunwljig_czyuv24Dxk46 zz@ZQ|J>4NGbuhHA6l=G?g+29m(Q8)tMBCE~oxt>HA8&^EWnpp!>cZ|T#E8z>E2XAO zYe=N{Q>VBlOD6oCH^ubw=JoKyrxM&+yMj+Swvb|O&5KwE2aj2EN`JJh%-?ST%5}o2 z*!02${3wf4Gk^DgenkQ4uMNbFJj}`P_H*pJ1E^nA7hP7z84jHV84O+R*~ug|_8pj> zxkA*-fq@+Q`!EY3elZD7C!d3MHWjp8uf@?nFj?COiTaO@%+hjcdNd(cqFqb_!FqOT zltYdCpTbcb>4Y$fCmmtCQJQb&38v$t891Q*)WqbZCa3pI^wm0+1qUyrY{2U1&2I@$ zKY9Cc`@?bjGCU4G*5*k;c{oM743^1Mzvl3HFoCK_rrl*%YlY0M@{H|WD7pQO4OLZD zneA|B26L|f*K8a6!-uD4Kl<=5X2JBQpMHA(4BaCN4n{ZsGhr`L2L=w%;fNyAY9qz6 z=EmHp^Gz|;k**b#DB!QLlH|dPiiXbnDNQjC63aL&Ne9n;Cy9)Y$-MDe(b`@QoRh~$ z57I6;U5jLFzJxMTRFGra&?l#7*k1b1ni=FQfPtp7?cweF_i>Tn#qW>L=2pxzz$~NP z=sxkI?|WPpo){k7(o)uPDtuqdoSOdG{?S^ejEV=JeEXZ*4HaHlE21lCBWh!YnvT_+ zmZBA!n696&$*6EmUy)vs7a(j~Sjew(Y5-;zgHh^(gKdev46=%)Gk_P?7%v(jt#C4@ ztr5kgWV_hfO4vT9p!~UzAd~F6!uIH<%XepvpZvRD9dGwJXw&MnaC9_&bfE;CI|@%z z7wVS~Z%@z*E}Ud>{3EBEk)tmD6`q8CZf);f=tg)tE50`z9eq&KMHKgg(OKkiqI_Cy zZ0va?mO7Fwc7cC4@@waYl)nG3kDokE+{^L(U^)W4pA+i4>94_y+ZRXR#S!>ZJpya$ zT!uZWokDl7UbSeud$~u`+PI?f@@>SYd#t1L4VtWT*sh4)y1JOon3$Mt%J*S$tmhEmcx z-0Z_=BO<~)R*G7(PKlyp1x zlw#TS8`j%xQH@8HG#+Piw3s*@3Rj>mHWy`uVL_FSqO}9+q`%<#=8CFWm4&o{fTZ0d>XciqIvjkxeQ;vW-a^QyB?_6wH(c zsT?$|#S$KQ>6IxP1I{innO?MQ`lHwSmd`_20e?+am%Y?kUG1<2?Xpf`u@JK9qAjR< zT$$FI78Q)oA-Z~89x@FTTVuNOuixsgugwhPjrFaO4VxPpq008~y|{V7VwtlnCg>8+74{8&4Vf=;eq5(yZok$pi9 z0m=fC7m%0JSXDJho8DgR%Tj6G+(3Jjbm{Cu=a+y0a3DPZp2^CJr2;dR2yr?%rl%7f z9Wb71Zcdn^SC(x~V^Jvl@9!YJ6paRZys`@oA=&sGq=JriqyGMqY_ZVKkDzC7Y3=Ca zd}Ukt^F0HeVGN-1({GY2v3o0Mu3CgSJSsX{P6mdTc1CV zBBvL$AMBSR(w@rkmdTO71k-mkSem(;*&2)TYdoT=Tmz)l57nQpuE}i;nGepAr+y* zp~*ie2uu$S&cu<9mX6s-L-Nm_yO}4UYwJ~R`q(~+PDf2|DXR}hQ*UVrA38uEBz^qT zet(DL){OUWfBW@=HdimN=nM)-Ev+T?oe@dd@0^tGwqj?6F_Lf>uh_;MCofuV6*B*1 z9+k?!2}wgIBr-e5-yQIcCWjG9$MAyr$;y)CL&@8*WR4`i7)cHiv6$!TmEgw*Hgosn zk3aa;-FsuLt;yzoqocT2lrcpFb%{iGi(hCXag3H$60Aw$xh1w2Oy{Jw(4rKWUl_k2 zfmWpIhgd6LLgWg{c>?!LLsr=cs`G2XKSp}F))M@=0Kd!V;gNeV`Ui~DcaI-lh)v6! z=Edpvrv&ursvvK9pyQmDeLp;aKCMrVE5uxtN!fORVf=w zJkZZ+Y2?{kUR)Q~3!{g{6-ULKjUn!(ydZHCb&q>?A+g$(Y`BOW-5FLcDXuKvn6_c# zMKWGgZ&9h(tm(mXLa1VX36zd{O{U9w=ZNCUqFpH)oF(@BBH@c29lStKWnFIsb)zLU zaC}q8qK+DZ)T4^yhF5khk=~oQC+DjVk8bmn0MFK`iWy8bbWJ41K3Kv*D?sM;z} zMPa(g>EbuRGN}Re-9~213i_=7HiBkSGof(Q{9wBici_`3+Lm8s2RQQwO2+IZRh#I8WCu0<217mWBC)S21nBS`^<4(-3W# zZnb*?$U@>er0b+SAH4r{)_(R3rIbIr`$J32jGi03y&CGB_3h9%hLa<5VMZZCzhOz+ zJ+;!bqwJvi(kWfEbot~=pBOV9ZEB?mU07ZFR zActUV#p&=~5><(2SYL1;Hz0zZIWuu4iVL7Vn3I$=$8t$&$6mSmdUBP0SiXpvS) zL1sa=x#UQ<8{30`KYx24k{e-Ongd}p$LT#XGCT8uVETn8)02R2mKPn{eWEcUWJ%p0 zlL89nL?h)pBSR84gv4N-$w^e>3wyxywv5cm#Ob~aZyz5KO|vEs5XfqO&w0@oZg>-nqHC97g|tV{kXlWHMl*vE4e=)HK+yUf97W&iYe#m(~jZ$ z|9s}bRH1bL3Cg%D(C1iQ|@mnlE5{;CuT;*m^x*6v+`udWH#k4eI%3+hSqR`9j zRQOvz|M8EB=>OHtdY@LK4Ql$RpXx&-e693y@AznU1BJ9wpvrv6O41&k(9XpZgVjZB z>27Pht!=C|Lg&Y@tt(KcOO=h>a~yR%%(s%$EzDh=TwTpG_(wT89y&dJ0Grj}mXYI^ z?+T)S`@!kc$3I*4uC=QL|91HYZ26)Ksp-$*i`y4R;7|4ltcf5zu_!2T_sZ8gwpW*= z+rqcVIh76+e}mxMV~Gu=lMZ69sVAcI?rx9o*<~hPXg&Ys70mYVNsM$3ns-?9z*pf4>A!r;V!1jT=2NDX+srBEd%$^#J{(&X_QLxq#6U zNf;D~TF?+I7vr@^(%cb?iH6UL(t&6+X3@L1qopffI%T4&QgoYKvnvnGx02k1cm=|DB95Bwj13`%7sRN@zcnr2hpikc(VMK+BT&)y7 zR@7R1-Do?_56mBm zi`fKqnY+;`UB55))DhBn`nhWn&*ubm4Zyjp4IYrM?~l2s%LDSd>gDCV^d;FGeW?8t zQlB?5kxx;5lHAC?@o~!FMt$*7!Ror0E+3d_Zbe|aCZU_yT&H#IuIX=4Lc!Joa$e{$ zL^C6A7flWR~QQ>WIC=wxRjb;KNJw>V2p#RecWpKX1-|^@`KQ>k=E_ zKvH8YA|2KjvQ0!#4-IvwO|Z7X%;J}BmD5*L)z}yb-=`zQy1L?;O~{h?3JVKY3NdA* z2N3BkZF(%NkU5QQIpa{eF(cYd!VB*_(T6M$v-lCFmzfdtX|Ty_#VM?}ZVBEAZiNWv zT)TPEmPv+0Vx#G1h%!Gpb>+&1|G8N(J+HFzz>opKK0`2Ff+Zh`21cz7A>@?U+6D#DmdJ0Epl>`d{*$AV6sm&tPp-fH&O7*D zX!1GILdGBRCcE+5D;QpW|M{Kf(oq6q%#yG?cTtxq2_YCNs0FA^YHU<}kfsLw#|}Ka zb!Yb0L}<3nSa7!Af_TS)z%3u3rhk1iG&U=1p`#CG5Ve(O*HVNyE_x)tN?I>0Pa^u>r9I%y(u!{Lu`hu2-%+P3aKV%i~M! z8Ev>;9-RqAO;_ght7Xd|LBE=y3iHs%(%yDWTvI0=m5;Vp+954Uhb=F7XpwlgGj{h#*Nn;8#g zw0}Zhs7n>;>Fw>o!A9|Rp@G{3Gn>&Sar~yx1u7VGi5SX&dKgzH6u(`7*G z46(qtQj*%b)82=EvW};CS^O{jdsHLKjnCu2(9l~W1Z&pJ_H1=|RNVm0Kr+Aim|~Z@f`ZV3?fGGJrj&G$ zjTb%Ecf8iIZO3-xc#jgA7D@8C$8e0aFpUd~!NnpY1!v4^K)Werdr{QWl+~octmk>8 zA`XYS5WwhJf+Zb5Z(f@?ks$c@kL@^?9x295yXfuU1*%at!8@x#QBmD z2bc?*gXE^6)N|<;gf0z*bJ^y(8ND3RQ$ubQ%CScL@O1nX9#p_5c5~S{<_!|lsDY&V zNlY)RXmqqhCK(#sDa;e>1KQt`x<} zuBq`opp_|!P^>^KM}((v80P3$-IXJwE*d6l_gMKa4vo%rAQv*%Xk8u6XKQ7pJfwf= z_k`YmfZz44l8=J7R-cHrOEMjii+rTo5J1<5qI6| zk*RYaCRA5Sy3Dmqe~J6DcIQd_?GDDWx&c|8sa!KrFNo4i_V54Y5ZbE&^N z5*|M1dHHPr{&s7dgBj;g(?9vHy{)vp3r@F<6!o6pYsz3{CMRFf8Ict>M&i^Jr+ayc zUcQrG94CI4`BW^aZVfirdy|$PtxM@d#zb1#@NdK)`P@p}Vp7G?NQc$P;NaGbXm5Ld zr$&yS{@~3wPoMta^v%cOGSD#pS(X)G(M?S@*)On_mdw%wOOjuo=r)NH>M;9bXO%_x1L4PgQzD)h ziDP_;@$$<{f%Uzse(^e!gX*aBVG(iyKo}iJe{}!8802>i!~Zlh<;8tFiU*~=Q3}o) z{bLmUnJz%0Qm+(9f(v0S$wtHhgK=H=n@tfQd`_rO&uIMsuuAEf(@ zY_{%j){#%$V_EH=Qr4xIluo21r|W9^YfG^5NDETgEjV3UP>3!Glxjkv%jt^M_jq<6 z*<>e-F32heNQMBl95xv=T9VY9^-wzWsUKm}&VBz@1NGzn1Pf>j6*1$x+HDEf{ zZ%IiXM+$U63?%p&H64Z1EXd!ChKd!rQ2Lq9&TAN7I3*U7-enOwnJ15f4bMdtOEC=+xULI)C!y_xhr=A7zo8!`WN6?lADg zOx+ook^n|7QzJv5yQAN!Q;t$Q>gGmART0y#T)2Rm{{O*yQ8_i_w;~=)msUekYO2O4 z_80W)r%&`qbtql3)#;VQ`%NFeH!|`S+HH%BQ3uXAM6ydn;m{eWk-$TYLjJWaEhE=2 z{OAddm1vE6;hlR_xt=+2$7RHsb8Z^WaC6 zxuqG#bYn$ugRwQ8#BV6QqP^XC5G;;Nt}s>=R5et%QV(hy(lYYa%!enLMZ7&Nb*@*Q zI;RYOe5O}nIR0T4MoPO|N6@H%GKeZ`6jPD3OU0AujCM%*U?T>^13sC1A?XKJcp zY|O?QaUEM#x^y1($#69qBW*~J=VN2a#*`M<5}2NoQxRDKq(?_PTAzAXDE)&EJ_OT0 zIC*cG4=_#b1q7}Xb@*Eh=L;7`+uLLt$$FGw$!ytDvd@+0h3kd*T`VAZIGulRVr-X3 z)J3Z*^|AM{mnc*sUmX1$%l3`z+c$D=)A9H2T|RmF8FmI<6_^Y;k#5U08W9E|I9tvngj|TuNLb(mY~{izCS96SJ~ZHg2G> zaO1`_kJanRNY9Vx9IW#=A5&LcT;81qqN6>FpSpvp&yGcLQQJ%KrPJ`pBSwlwvASR) zr|FPV%HeVPjW(s!_`ZI2Fs^2;c+uB`>7t>Fn65nODDXAIF)?7b7}H;Q`Q?{he(9y9 zOJ9Cz=`TDse^Ojk6?dM%cliIl%Y8-|l-?8NGQ4sT26tRG6ruWRYC3t2i$EF~!m%R# z0-wYQq6#ZQR&qLUrL!S-Rahc4iytIS5?+MS_efNs@|X*&V`I^gU6#?x8Ct0*TrNF= zWC*RR>)qtMY}vAh;1tjgtOMl0H9(J{^PUhpb)^c_HBJa@@uLe@OFL8^c3w?iC74}1zzcL{oqr=g&Cs-TxmF;n-#i0ac~N0n z9d~)&vqPitxv;s0=W1c@o_=`d-Ew`a3h zE7$5GyT&l>liDAJ>9RL!hm_TY9pm#75uJ;Y(-o!5tWh7UUQ-b-nuxBP=`8BEiqrKY zydXaFXsEsP09~^{QeKkiHVUUF=kZN*MocfFrW>s2dmh}-I2d)Ns_I(rnTMA;&vb@1 zI&jk59)3_GHa4j*)+@_38Y7I+);s{yODXAurB#)+L0OJI#3&l9)7@hSL+MhVo}Q7O z0Y8dx9-GA*FSIZxEG45qkM>F6dTAwJ@VcN_UC1Wpho0Vp>#Fy z!t^E8`uhu}e{|tZ5FJvV`QL}%J>}*{PWl}RM~PudyowCh3S%37^~iwqfS{ofV&p&M za(#q+c3P}H-PrNzqidMcFSV!l<9fM&zj6Gq!t~>T@GQaW&1Z&d&Y!*UN!a=GK>FW0 zpWhV`HQ3xtY|MCSt>3_CaQk=PeL~U;m>xodpqzGbyFlrZn=VTSF};ZE1x&w`%nYT! zw7D&(A(wPSO9|3^A`^v_V?3blnG~Q zDN4GdPy7mR(v8fMGkkoaTPw)pv^3{4lWt&EWYwV1C*?_VEOY8h)3J}AI(+pwe(=+$ z!SvG~{Oa<4$HUgD$FHOGC=x&y;)cF0>}@y+!bd05EK4ifY%>wfJ%d&lhKb}1K^PeN%bNN;#38%&D@)#Tc$iA!ht`_7v z<i(&ftuwh5!D4nb~Uf<^{B(Y(7kEfF}pu^KCzs_ z!o5phTDteORh(yEyQR2%_v>NXii*P`!sfXydM)y6rtK!!;d? z&JI@7frv(<9VR94Y)6@~;5>_&t@;aFQ z@+%Csdg;rrEPdTGY)@TvL1!IJOkK{p^xRjZ&ZbB7{#HQm=#;3yh1 z=5DdQtX3$i*iqmN@Dk({M*{0)Z&cRH#?9TuM>cf>=?Y&3V2>&K76O-^ooMCSmqzL= zlRU17URW36Ro-^Y=Tapq@hyP37H=rYkU+59S9A#L$$UZXsFiYuEn&*QkUKoYea-@) z`^(TUT_8|mU__b~k2vQGlwStwMV_5g(*@I&{~Syg9M>qlgnQ(}%XUdxyx=>euIJBq zZr{FHaWNm2yrY71D4kBEVClL=au}K0Af^MJ{{p7#fUaov*%ds?t9*X|w(0?%r&F-T z>fF)ps}0gISysv+`N5&HxjLW<$F*l^2Us2O6gkrB;Hz8Hm3nOMC+1$AY62PauGvCu zaI1cg^c&eHZO_!lWV(_`l~B5(buE@rNL>SUlJ0$9T`HWe9533HIuoKmT_p9Trawhs zdZOgK6w-gxFKJx#b4j$oC~X;OW!p!e7JoBqOX$(qV9cxPjB0KhJaeYG?ON}(J}bQG zw79{qfK|f^H+oV)x`QQjO@?$pdTFCL8X6lzD@(_--bG7}H#oSb22?hu1Lx^9Uq>{D z(#dYbn_>}}n)k6?9F$$g0-M5`oG2}xpnKPljmIphBR z#syx#$WmBl>vlF3xmYIhV!Sur+)7$P6%J}u|o1wLSbeW`x(8ik7 z4!?z?{?y)P)4GS?zgFBFY*U31Vw?`ZH!R?@|m= zUtN@$9+2niWN!|p=h`w%e+^#TzBmFej=-Pn5olUoQ&*i?9J6}wYr78ZDC+Lsv;{c3 zcyT374w0w%Z{K&7@A8#tn|7r&IiHQdmLAs=A)QEXL=DEoM8%}!?^@^k((?QrJL15$ zr+aoQi#mAcaRSRqid~#b$$A9qnyAo%Zac(u85=g1kgm?dF`ZG8xaf=~-yPB2lh1NT zM^AO9a}$KF+$|?g@Nmkiu+HjyFnu-N^c1=!VSWMD@w^Xv$d3$DnJO(!_r4^M{)(vS zzgYSboW6MNdXJd6-rgQOFZW$~P}1+aoRR8OGGpZZPc-3wUnH0=-t?439Z-!7D3-uN z!oDRl1z-}K5+W2>gTOX8tB#rw>1x=OUA5cQz2j(c`8G1-iL%s(t~P5pu4B1^cDWKA zT8&*?3#D%qg&J+zbIWG2(1>u2OfJTUb-brWipm}j?1}qE28U9EMvYBn7QuZv!mFJ@ zauI0-_A~&Ly^xoap&AWA=?ZmME(g;IdlARPYkPgcbR=`JqO%`zE6I%FO;?mI3@?xH z#Rtt6Q$xC~d$SxBIrYF>396%^<8ToQUAK4@s{UH0HB!+^HK}%h7ib_WFsr_Ww)HPL z&e}>7-s+SqLbUqQ;Z|X;dbWC^`XOFJ4ve~z1#LWk*F@y{gC^|OSI^!3!3Du``BFnM zx|$ZLmlEKYIg(m!+6LJm*)w$`i>94XjIL3-?1&sW8GKmsiHVM`o71(=i%3S9TP?5p;ROkySF_`_U+BWDfgmzklBC%=<%~&@R-&fkOh?$+5Abrjv@&_b{k0*2hOo zFAfglse^rr(n0aOemGq;cYp6SUgnl$ReRx0Zzw3j+CkHy&|Gs@8&^E(K@D_QSCszr zmJ9Ou^w8`reKar633;*-YH}M(234_1+cRxRQ`N+MY@Rl-6;kkXu z>8be3gF;$HTW}-){Qvx)3n$+i8MzLp&!Xg`jekSW(JK=ZQ;nsQrHv1(swSc)&Rl!{ zOfQ$t=D{k?A*h5vx`ZOnr`9qz0i7rAkoKb4ULN*^R#qntuyvy$TRr!D{q@)1-Yf`k z^vklh@o6$ZLP@I=eoMcULotHt*W6fHK5ji;6UK) z^$*{f`H1$cBQ2v@lh-D$faye0VrcsAQhP;uGp?79uk{^R_TKfGlb4SMx0;jS*j9Dp zyt29sdz{@=UGO-w-Hft?Nv2z+jeVJqA3r9J@i)Ku_3a1WHTZbB`2}YRp8Fu8%Po}N zdXP@2$myN5l4}q<4*hIV(~a3+I#M)8Fu4AQ?JmOGYJ4{DT3aL6NaNp!R^BZ3{v3(b-ulLYluQ`2-; zi}+LF_bx-rCy(!c@Azrx`Sg#EkG$)+Fg;bQD@rOyaL2pC2`S!yBGO<>l2;fKoesc5 z>B_`zEyBCV>3S$5g`zlLc#!N;jP9egu@>%>U#Gvj|Fh#KzttFBM07#))5nj0CNmXI zHCQ|PEOd9MtjtTT8myu>lZ80~esInUOgH^Gd~y5Y2>j_Dfs~Z|sKLyrT}^vm_sl%B zY1`%P$L#EWMG5I*NPs|zr7w}CP5ehOm{zjOB`z$#?#9{98*q9=Psi}ClwF=g!MyzP z-u2x(x;J`=m<-+FYq`kxy1lP8VNpk~etoz&w3^3R3DKcJ)5NF-BJT_vCd(z}X+%_c zPd>5e6oIBhM7e057myrd%ZarReMEJX2LX-}2IDNjjl=6#gVn%(39r&b#-kLacD()z zoaswndFdrc{lERU*M70|7q2h>#V?w|>TbA%h2_KO7+%iwxa7ys2}vpGsuoq$^a#B1 zDJiS=>YpQ_cXSAXi$qRW>648ym=Sl=So^vbS`VStDYe2D^`--yUB8qA;(H_`Z}G;HN9N6f%F&QVj*(5 zrzQ`Ooj1{ztTCZW+FY0x$Q(m#-G5)rYcCN^H)Wqa9I|KAyA&YU@O=FAzy_j%6qc|O_>bYz=1;b<^jy9{GGk?F|#ifPwI zjIj5x1+M*WS%JmpW(W79T!Zfpy0t!`LxtAcvAAAoUS)XLtWz_;JhWHD;^syZiJDxSX5y;!7fK;1IE zNJz(aWqDrMiG*evB)1fF^T0xNkvbQyj=x3oXN6C~?y(L%eH~p1^FnFf1EeDs@-sSv z>VHI$Sl#RBSBekU!xXBrW5DT{owO2Su$hle+W zFAU#0Yunb$%JD9NOE;Ho=TE=-8EX1}#eDqnB|3fP9&@}4+*;MK<-{q>{2{`Jeh!~i3+I@uzyx{Di8j1|Kp-$zUT z<*%PU&_zBV{YXE*C`kWA?Tieh^TG2=(R&LxF1(&MOsPNcUk-MGGWVQ6U4g6W5bH*K7WJN=^z(Obh^rjwjbH`4JTA)bTM z)9E!I7Uou2>9NRp(fCD42<&%>dl)ik*!{k z_Vr6@lPWp==uyn+)dPz@ef_x)UT^3=v5N*rXZLc}WN;K!sQZ0>Mcgi}>$at4V$606 zOLxOfUy57(+#7FPLE=YE|LBctr>f?yo7YxdeDFd4XT<5-EB)J6v{hDPdMVGM5h>B> z<#~<#!jV8?9iMdq+-RgyFstN;h))w1m+KP6>RL!KmrQ2h(u8yd_Nk06o1CruUzZ z;RUCQvyL&5%t_2wTDmh)qHb=3+?@0YX!n$mpz2Z^pZ^ zwwD9H*nMbVNTUVmRu!n#=4hb*yz#E1GX`_0M&JwHbky_#CfP-~=^g`F*2wAf6)=2m z-L#6*1D6IC4M4eX3)^IR7d`qJ7MoY;RjYc@mh<@ZaRiYo9~>4OIKC);Ye{MNhV@&= z2hJOhSBkEugY3TsM!)(iZ@zXH<2zi<_&Vd8U;pMefB4NG{_xx1{=fI%|Ih#YgZsYs zt?zx8@oUD*k3GgtVB-$Fdf=%8Pd#8b8%0=*L{2`1wzt zw71W?dsQc&UjFWV|9t-@gC;ADZz^hCa9%-}$=P5%ylu-Caf%v`*pwl{@zj z7Pmh*y#aDMPnZig=04{H^SJ5M#0h&s_l{wv^uhw&P{Bc!_3gm}J?=kG%ly$%(dyOO zI-RondlV0L4*^8^3|ba&Lu)Z!qnDbO=V*<$Zyd9&C+%Binzzm2u{MkcEqYDgm527l zn&o)v&)!Eyo-o_M3R$V%KnhS?XDTMwU=k? z%8A^ytFvHs@$A`=1+yb(&n}pqlb;jJ4^Kx#T<*It5wV7!%kEp;mq)TBi$u}|JGFE9 zIrkT4{`=qZ8~S&@Ch-xU=#?cKS0_#$wlQ;~az`%L)&^~H-y+L0g_xXTzx(0ILxYyh z^qv^AasAwwIY)4>9{%moXgVGFm1R$fi<{|PGi>cQh9uKG6HB@ZNl6Hq>Nj?3+1(?& z)$XWfL_luzddf=MbKAk2L}Xx9Y}Pa%*`NEX=G+)O>AgNk>C|+VJuoLaI@jCJsu5L* zC#*iiJ9=weVh!GOE@OFRGwffMXe{lCH6zM$b4@5rUCjvebP7nHo&1gO-1ScZVd zr;qc-i!#yM7N#eRn~KovzGTm~y~{~?p+k{%oMK2_+}$?}uA@D}wI+Ab_NA}V9C5l{ z!Qz0spL!QT=|MWA!A{P*8P%L5b;FCWCAEMgVRd?ug&bi!@97`!$U2u8uzm^HVdY-;3krD;SBFBB$qJ;J|eOY@o9ZqP`3-0-%n*9)*$$S~b3R1k=ll zN6%zrC54Rlr5_6p3kZ%5MLzukS#-yZ#(uUIVJTL!y=aZTq3Z^%Z za~B)yl)=l%fnmgkOkX#Ry3>JZh#BDxlh#egW4&N{aQNPBnFC#&<}F$@t;w>yP%lzg z+Eh?+W6Js+yKV{GFJ3JuxY5$mT5#iP>(%-jC$8QyN##JX6m?S-smjRPqZh^a*3Gl8 zKL0x~{q>KZ!-Db-`R))l0U0TTI^JW6>X5p6Dj7+An<>A~%X4!w_@{`tjEu)Cc8;BA!jZn>P{ zykp0%??3!Ha{AH#0@U}vx4v9E1JX_-ljV3;cWhHeL&J5BI5?1qjc>X^cKW4@Tf6hN zZVOLYKnnJT?3rNtN0&G5&GZ#+P>E(3qo6VBbPxTb~Pol%obFUvedE@5O z2c9}R3o8#_wVPYX`u+QlZ3{1nqB(0`QISV*aZgv*xpQyK{P+LocX+?AT>0Hczq#<6 zYcEz2f?0g9t>|2F?ciz+L(Q@Kg{A*PqAMsi~KEx}b%+DOt%$!J_Jg9dqq;5bQe z3#%4n|7lV`ucys8Z{O<^i64%38lWcUOxNi6h+DcbAO75 z{gISMPMel8ZRE&xG!so9Jjj_WP*=EPbQYA(`2+*%XWomQHg6v7v!L`v@%-lUO+nM? z$mq^o$b9GGh65%cfyi>i`T71FCmljdfBL1DpYQ03B+fFk1579HWnatg@xF~fHr#Ei z<#0NV7P|7f(%6X83ZWbw4|1lvk!5)?P8X_34Xj(f7g0WfI@QAiCviZ>zg()Mhm(x1 z2BY}Ue}0~^?>|Yv;n%geU^d56&KT$iyDa702gku%w}vka^&G!+Jk}ZB$Np>Z2UPe! z&oCScrgQnucPvm9wSuqT24nC4!9RcR2jBY^jQ;X>U;g#WM8}hNV;EhO{)B<_eNQ~` zfBv}$(Pyju@9fCpg8nbHrgO|19jp7pd%Xe6nD;SI zZKiq1o6?cEC9=mn#RGHw3+}c23GEKyzFyYS+0_-<$)i1ww+F3puY0JjK{pV z3Y;Dg@bHkaK@-Q7O<7NOBcBgx=DC0WoJXSf&&{o$yRkkFKTO$}yCw(KFF`3@?d}eB z&P;9}RaY~nE+%;*m7+Ck=d9o84qO87VoPtMlh?e!T4WmE85h&6u$KuCdE(sl(b(11 z>xOup+b zOaR}ZUk`^GxrcqQycjk8=>GNP>$BA$3HLjP0KBj!pnm^cwJ}Ys8D;N(g&7)ah{1GV zSDGf(mLfuQYy*+_ybXX-J-TGW;>FvRFE^OJ+Gyj3&JB6@BXx=Da*3=~>I<;G21%Vq zfI4?1TI%8IHQG(sPS{nqG2H+<^9>}j2?BW-5m>jeP@HZJF`tMXLgd!MLESOeIx(Q< zHJhc3<$dh9p#k4e)XO(8zD%ARFoCzXFkPU|uqa(xI(uGHI~4Dp%;svF5!2!HB|%i$ zLgMC~_0}pN)&3zCQt>XMF!SpK1;0@C9yS2W-qfzVW9ZfTv7XV>)(C`@3Dm!~xbNiF}?diT(8CrL|Dd!ZdjnKWl zVP?zNHcmJ6eE?0EN4GJ(kJs5_T=Avr#D|74rbFsDUiw6H$7KI|1L}^yA@jq6C8jU< z%2#5Wiei&8;`0dbj!GaeTh4N8c;tAiS_N$(QIq zltf}K=u+>=x&A0rQZT)+Dx^rMfxz1Y<=;e~0voI$=xYcXG?8S>SJ;=*QvBY!$`@^G!rFl*HTVMF?Zpl*Om4``eWSbS>aAO(zYqg+=~C~di??o}zIR`} zvG1wREKFA(`lYL}Nx_3pl0)h1T@``B%^G`#JyXy-#5&bH6WJ`q|-!{8v1)Tdo%l6Qt!|x{ljL zHtwwQEQMQw!$&`T@%5v>B|E2leIW-n?6G)YZ~JlA?(V#XlBlZ}mG*MAXmEV_hD$VA zx>|Z;!-m3G)cxWctFP<>)301u8Sduqv3tb|4z8g8!D(PRU3k#bNgB)`Z)7t;jMXLl zRQDV|?&~}{eDRK5`_4X%F8H%oJI+4Y-5ppI0x##~9TTRXZhzC~^%swR(X-NH`inx; zxyR~jA3JdN?2Urp;MQOlQU=|C(KHulj%&d5ynf1Zd;J&r&*M}ORR~ETo=$Fb6u|5P zrCS$b{x>@>qBAL4`anMSgOQ4Oc?m9`oe`2!nMzqFp#ExC@uZMOc~axZRm_98~a{2%vI(GwUH9)>gU@I*~&+F}eP3Gdh zF0|*}oh#=pm_L1fVEn=i>Lw^sNGb~D-#Cp)!?!LBY+bl*p=V%h;3N$11MI&Be;yJ4 z=(854i_xKUaXPqaN$G}UzxRW087=)~wDgxBHB!2v^aFjAE(!+HrDOMlbhLB{=?p|~ zhn5au^Y89&6VrK>rKUUd^k-~2-Mq(sg(v-PZ**37=QG&8jkIXKr^awvBO-nnhr1abrHeXMS_l*Rt| zy_wA(uvRRv*L&^S*U{0ni#;;q-S+m{2r&KfuE#HLsok}wqrJAa{c-m_owqvnyacNk zaI}$AkRLg_08zaFN}oMDXODZWgV4==#2SO_+|+K_!=gEni#sE>Y?-iS+yh(wJ>msN zXt(3P*?-J^nRm?2l?f|XjhkGyHLRX2lFLwft@}$;M-3U~9g{tZENw!XCqGQU--yYH zb7NxYQgrmlZ}<*Qxi)$YF%Pqk4)V7hKz=ZWDVUK>wz#`TTNal|B2Fx|3JIyw(a8p#ureTkfLxyFz1q5w!*BwmgjVZ;3c#GdD zfz>J}$eYg2!u!JBGnj7EIR^_yQ|F<*0S45A_$0=x!(jz!?`y#Hp<^afD{9c6H4^V4 zuZ!AcY9_k9S{<2T|5iJw_7Cs1gZmA`y4vq|3>$YrT!x;}7h^!!ENWg4MjJGD2;A%! z>#@z(=J7;`TszDfeR{b?=6y(h8`kwLIF|0ax8KIR(d~CL8==kD=9$}mA3>0=O*gl? z(HFyy28eE{=@zB)n~3KHSXcNG!xql_h(Bq1qGxT! z^O81tG-vcBx5avT#-=1emeEId3N7dA<_KbFN=OvyAN8Y(5!C7aERyz)Mx&F$Z`fYQ z6->wic)I5u0(gs(PBs)Z6I6zu&L>E?<+|ay>EpErpBc1kK>p6JsTw-7;<3qDFE02{8Ru#R4{*C)XK248r*@e)?k)7h&~BA0tXb z68rPd3*8@m^~s7uhx{LW=9&NaDVdSR?{d9VkWT(~V`<)^tZmy)(aiPrGoK!P{piud zFP85w&!YDwn4XY!yjqyvP+pR75_kG1?_4d-N=Ujo_w7q>ufL9kC_H>Aa(d2^Rc}a6 zKeu)3Z0sZ}TxfAmTug!+Uk3dztBsltH?CMzxoC41WV(6#@dr08@^ww!yQkx6i_#CA zC9!frcT*Coc4;1mGw-~88tsD(da-Av|MbSUKKT7}AI|MW*_ye`W@t4x&Tq|9RGpVl(=#(ONeo9#Ct+xiQPcZDb|0RbT2T9@@2>AzDE)j_53Y3l z>0O)7(|Oc9bzGhoI6c)ZB`;;s`70lNc0o;9Q%277ClFnf&hKG}@6u`aOuJ{`=yarU zS1LH;DIVZt0+jy$8t2Pf*Bht7>4@o6lV+7R@=e7%1!Ho8(}_!W;(*qP2=>jcocn>& z{VO>H*u81r6}0qy=XX~GQ(^1t+S&2^s~pnpYZ=s-G9K(Uxr$(_N?2$7jcWSWjNwHbdY2&Gj6O=2l>P%r z>EDu){#}&x$DYUVLQE3Zr=GHu^e3L!Cq|c)Zp<#mdh#Ft_TT>oJR43okS9%jKjVuw#QL%1^q>CRp{JXB&H+6Cy&ve)ae2t%bW2U=_UksN zTY9>K)Bou%OHKb@(9`Wd+X8V!b1CWk0P51yMeEYiC9msFi%4JZl!mN_wwlgsXYctfW#kl|a zy>ydVqjjtGeEDLY)=I6n(Az|^w2{9Jh3g6Hkx|9Xq_q+WlfU z|F-*k;$p~Cj7nYdNWi$QnHy31*VJwa+7dK%?9j2R=45Zo9x_>=4yTj&5-^OeLot|M zI7j{4!#>{48#lzQUM&VC{3B@W(6!$gI(16@l5FI3zhtiTGD;+E5vcZ_G9|a2=taMF z)Y)7>hmi8M&4+g$-uXgIE_I;ZW#bad#`z_V@LsllBLV4B%VB5;AIZB03wnDqCY5%< zyD`j^CFattw5IG=F)=dL;DAAUpFj`OVP$^fNO>`TVD7qm#2Atp*VgzTrlY0DWPjL9 z1CNF&=;mg%=B6xQtSalUWo9v2vn{C$&o!)DT9ukQ(kT(}IchW|nCfliQFUr}65tGNT z&!A4@O{XY##O)GNv)#9EwApNzhJ9zWCQM#TJoSWNzl+L8}$mVp%yO{65Y!Y*AZF_7E{lavnd=cOf}1M=nKk6MZzAs>kSUg_zefVH6jqbSIavH0OlIs#9l9m190G zCjvW#1# zTjZ>Qz|v#KnhL8%8fW_HOK8<^Q$h!d%N;u3vU&)?w!$4 z6uM(;Yj93ZaDM0BVz2zYd%SXXoxm-Ai<{Z!zUbNai{TZ)t&8_{J@Nd%gXu4pU%d{e zU(chRQhaO(4V?y!M#`?{07c$L_I~^U&5XL;z&K}o9TH<3ufKTe=;8l5 z`d=^dBQ<@0VOAApqd{&o5)Gc6lbIjf6c`(eoDQg8O>*7butC}I$4;dNFKv=#zV!Ox zX36OveYC$cb}2e{bxGCc&9q#Ka&vBT&7U1Si8CO+GMiNT51=x#u@URb@w}#jmM4Gw z;~)R*XRkhev;Iaw_kzHtrlKTSlv1W$f9I1=dVAme_`^?+UOQHu+P3{gqBb_Kl0ib~PbE$@sLZ1Z22GVjz!pZ)F);&nLk5~AOGFO=>} zjwNSv=3!A!;N(tTUQ{~f`A?18Nb_g6y;+z4zYfF6qIFVT7G&J}O&_ix;^tlgz&l{TuP3$?kL)dLNDF-=*drJm}AQ z3R=$Md;g4sf=$EsZVlVIK59JH_{vE|PA5Y{Ga91wOBWJCi{W_B*rm=T3tcjIY@IbL z%q4%)bXB3+Snx;n@;@{4F6+P0uiu4^ZnShGDLV`=!t`%hw)B@D#g*>xyBN2N!<25M zbYyEwz&4h2QF?z{x((^l()G_znEuyW3e3y+N6Q}~Glc!OIbE!-_qHwS)}1+UkfM(N zg+mE@{1{As`FmhGAMc_2E!Rt*@x@ltzplN(fy-?{9Zr{`{%7{(U-p#!MH&8v&QZ)e zPs|deTXS@0klcP~;W~2+xN~nDFCeJP^g~{B0y7Nkz-I`V=M6ExZwOe-Y!8cd?FZ=P zplopk)jRyx0j9SG=L6_iMY!U85$)SU#BJ7Zu{Wj}EG&ID);pVb)bhh^d0#IvPw{H= zI&F=S$c=f$+}J4J2j$k&)>3AgPb!;>*42qe5eNFd+Lt;yPDJjS(f-h=33cz*1>G0X zQM={wh~8hex4(PeyY2G4%;@Oo1k#bx`8>r!b;R_F*##XK*CT4zbin7BUDjNlB3d_k zdTqp->6if-pIZ~LWX-B`e;a83ov)g^KQ4E@YwFy@0Kb*#8xYgi)VgC% zA3I^3&lJC0!qNlQ-W{N(hm#RQhdkn!JLkh_QF`>@M{?uhqGwDo{7DGo>Q&z4tbb?n z#3l8hyLU3F+k}Mp`JtxQHTz9j?LKiTl-?}Yv-emu@_?F04&xc0ll#cn#Hr2WkjZN% zjta=$uw$7zlGcIH>OKTM%bg-AohU{>vKxivP|MSHFXpe%IYY9-;(xEghD?bOpVT+8Eu?FjuR@L8BGRn!Yx1|9WG33COi~CgC>X zbbJ~(t-)cb+GxW(6s7~ba=yS+gfM_gJoT z2c;XI3ko`DE*V|H>SFaJKss`KM6xJdpw2xKHo`QKDQtwKbHmE!#s+V3p@rRs5Cx5z z5Twhj4u(o^m-en3qt1hZd?K5L&C+8hfaxMWRg!*V#8@397(_S58<}skHDXlOV>V6Y zu`;jAq|R`kxg>6?v7+mAgR*gqmX0JGfS8UptO7__(=~){VN{Ra9(-GOUMz{-Ea3Qq zpue;x`q#W{KeycHhKn9~71Tp-id z@jhOM<{ugm>=d{lI5Rc1?NDoeK|xaK{u>aL#Pm;2zkRs(T+jLQ7rxkf?LrUkYGY1s z=`P;8D<>&@|JByL%NDwX?!BQZCa>bo9jTG2yY^J%?44DCbNvRvisyQ&&+qBUoZU2Q z#`z}?P(u2f7YnP@5){`9+Zdk|PX%X`>D@UxDhd+g7^1Wx)N_(6u9w*1Prml(O<}r0 z1?@9U&=v{TI$XF9H@Zmu*XV}NQ&So_{Lq30f%8V9?_~ba!t)*mf}epj%pe z2o40)Rz;2qR0GmK$zh1(gezm*7HEQeI zxYM^*9d{!lardF!MR5AL3xua%=$tmK2tPzvT2)Ef=-^=WNa7rHa8YauluouwrQ3Gb z&D$HdR~cbeTOMWJtQF2n z$rp=qTf|Fc>M~5QNhpNVeu*j^?LC*9Ic5w~g zHY-dkB#pgjQedq8*WfQhMaNPOF)V(Qrn>~^&laVt|1VOsrPAXo2cqq@*{ij* zZEK~LM&9>sAbN!`-F}I=gVD7Lk-gTXAFllr_5P3ho|K*4dW)`(t{m$7TUvJQqEa;C zrS_L1x)$ScsjI7dcfz}MkGpqtv_Jlm`?v5+x4&E0v3J*H_u7um6BOCz8%hV$fpwUD z*P1QH^CB=8pRWPVDIqmCOThQ#i#r$ZSc3klxog(EuqMJz1N*ovulKiOtG)c?7-P z3Ra~0w2a=RQ=;R%$KZ7N>R0dj>esNR-*wm5hQuJGf1K;{;T)0}6Qc_oHiG^tMir-% z8Oec2^!jERn>Gg|+dDKMK$vcGy2Naia>{INI9<#PtOHoXFnWw#mKr`QeAd>zJC@H_ zqV7d9Z5tE1!qNLM-S}U41iM=rx;P!E=VtX9>M(v@PE>oKA?8>? zvu%z91VyA~=&-?_h8H!<@~q2zPH$3HXW^yH?0S_M!gT9UgO`pPVbpZKWm`=bmz#n4 z#whA+j#-I;bXB)nLmUsKCr2!+4}vn${mm9lP?V+UoP!;iHSoUZUP<(Qwju+v4#G9} zqT9Y1X3DJ0d?GVt4lT@wz5{kGWg6tQ7P4@dRq;@3)Tee_wR-D4ET-;1-S^h)t}k6I zC^vJpGezd+_13+$s=k-&E%ZUm1~6r|)p4h9s&80|I>#8+wLhjC+ zxLhYa%*idjsxMtc=+->P9|fJbs5+A2LlVndu!`YO{(OJfztSemqS-SpsMk3;jlTs)Qr7KG1QxovT3MQhWE_>^Ne z$`@G$q;DVgS#$2fdBRODoacJuhH<^z3NFssdt>pj8wIVM%V&E8cXk$&d0iZNeoxol zuFlT3oURj`o^9FHa^uE^)V9v9U0cITQ}=HAg~9aST)TdienTIWcPEvGlG$ApQWQeY zjRs|cjJ$@1lUTju8ylNiZa(_`n=SLFV@@Yvo&WHS*OmXJ%zykMbrp_Uxi6IMnZ*{Q zOgkwt{gqo6Y2y>yly=Z94DogFX57uC$IcYKC_sPl=zsl|wyp%^C4?j>sb%);Ol;tj zyaHPnECACjIXy4_WcUqwt*)ndlS7WkL;kVd<;UJIVJ|(4rWF;rcvV)@wP>_ka020m z6m+?aACH<|iENB3ozV2E<5g*yv%2$hk2AM0@)xyS?(KKJ1U`XGJ&)0W+B)!R4cC55)pEQ#;n%I_qjqoVVb zTs!~87d>R8R~GMT|L4csmqfq##e0pLeFu2CrBznSt!;)F9W{E933|D75KeFk`g+8k?*2;0~gU;Xazo%%BU=Q=Qfs~!4JiF{pfq5bUpa+^)po| zAxo!?T;%LJXfU>yBu~0nQIrV^yC&dhkD};v9-oh1T=V>&A#nw4CWx`8*u`~_r+%Fp zvs#N=C|-W-<;z{ImC97-gp2X5(31!>S2p^*1^05mYT#Us7$kLFiuhp>U0KE}aNPpg zUtC?(+Nc6iw99(4=MUiZ>1^|#wKBB51 zzi{vV(Z%df-D#n@JTAg=%bw0XOb(hGGMCn_Ct!7m-I!wJdQk;vSaCjQHNCu$LgY?2 zWGsn0vN*rZlGvGrAG~jX%J%gRR_A=7;dG;>=L59G1qG6d%g)b`eLov9F*DQi@(NdO|+BvzQe?$`5wY3aC~FU(!(JbGu@+L+Wy zJC;nTCHT9Ria@`(n1Fzq=(w7IwUY6^bJyL^4juJ?_f8sjK)rJguZr>6xSm?ODSMXJ zW3qNnp0W!2bkUlDHZ5t8=I3x_kTOPHk@YYxc`Ex^gn9j(!w7N^q^o^~oms zJjTy^V%b<|5^f$lq^5pbbS{?j2{xsprVG{iQBf%YFMxV(vv+P8Ym_OSfg^pCbay23 zW0_qYJ2gPPS8=@<+Y1u0!E~b+8w(0EEZD+1KFn{=LO6Za)@?g>?5QV^QRSePJ$()3 zq;NW4uC6wxL-3~b(wJTN(izghM+q4}Or3(N-K;GT3pn*Zt z{Zko@))38WNm)(cbPE~$1 zPdVmTxXlMP!{T1+li0{>S-iDR93RjD$=vfEy0zxqt_`)`+Ckd=$lUt0_Lf;}&PH07 z+raLaVQqdQi{Bpho8I1F!|FDn_XBmq>6Vag-CB+p!|2qH;u_M0z;sSW$d_(my6zoB z-jCJo^cS9V{9zEK-%BOXwD^XQq=pRVK~Y@dX$T3nW(0e9f$87^f;zz#h=_8r(AK_D zfpnuYK@%J=@lHPD!6^IuGWf+N6HERiOZU?!zMkV+fd%;rTM0~MKlZD}o6{9jO zGpiB7IX#>2H7d?{ARyCrrQa z(S`G!R&x5qZkW7t)~pjJTPsqFcenAUo>9Ch^8ESEo}M-y7Z2zBY-h`f69r*y!y`{@ zy_%PiI=scSH~P)7ZC5WEb9y6UI`SwN4UxL;^OCaSDUo%FDs3!k`Puise>Sq!rA=}s zAuyo2YSK8w;eiNZw;-`Aa=3&#N$v{*vA4(GxcSN}pWnQ(FsU>?xWdgX4NB)0-B@aR zVd0A}g6U^oEG#cCydGXk4@%2uDedg<+p(e?YcHk>%o zSuua<(!7S5S1#=P=)%70X(WBLdgK$g?&}to;F=y5)|T%vAQsQd=FRe?i_@#B2A@1} z>j2G+Uc33!=V#9n!x%gpJvcuz-*o`}G%FX4PrCXEYC6&B)U=+7J~bG7%6qgpf>uvn zy+ssdODl(6SsAH4*DhR;3H>u7(m&%1`Qi)KZ^rgEj}r(~?Y;HU*IwM-xM&($8|;b! zoT^Gq$eRwy%9*}@e_?sy89XH!6gY$t-aU9TNuW;r)+pVp19HycoTry3H#i$+zdqXTQ5Z3XM3H&GD}!2()rMX7b85VnqC12T?kJ zeE!z&fpn57&zyOW0)p3H|M0ojUq92>$mt1R_4C5Ul9l9%>t%58ph2!Wu8WHD9G`;C zeNiKx_efLBiMZXhDW}*YJ<2nLUoXzgQ095yvB%Vk)Zc~DO`_BJhb1vxrKBnl^_YI| zf%IVDa zavK;DyA(s2ujk+lj=FMcEMJ-GvUKVA*uMeOB@Xld z=6CpkNj3Uh>BKPJFIW1@-x8w#nl=NEnSd9Q!T7{e4)=&Hr5kIBnAn1JV@tQN8GHtz zA8w2Vf zyUAvhq;3#hj}69aDJCVA>m~;^JwH8P=W<#r4hfBOlwFvE*?c}VH==B@btH$q*2Eoj zZJx5`6dR4_-uYf$!4zE@-%F%UW||dPT+f0awb8_l7;cDL)Gb8Ut=80UmG-orHcy!+ znKElLHwMlf0B?ZYJh0i^y0d_umx1T|c6GGiX6d@oB@g<$L)#yUsBN!%XlUJi?R6c! zwKHme@X*kQYL|Sgeaq#b$K6S0?3l4@R^*9U#`RKw@uh$QC+Hm=-Pl}aP&1lL%_(RD zpTll5Ythdk_S%SEVI2d$3;N4{HUIaPyvHvtZsSVllDJ1E2c4z@xuO7M-IoJgL|)YbVUOUWZV_;F);y;C@}qz+{6jkRz}H{&Y}}@ zeWFQytf82d=ydxu)YtxLNcQ2wAAbC+4`ULW8FP;v>(z=$je*nEf~ltFSI3Su*RcKo zKYPbcCh=s9hUIe+;t4|mU+76Xx=oC7EV%E;T)1%7%Efz)oW5EZu82ik+sNhy)5Wuh z&Kf#c(f6+ebwW}o8eOu4!cmr+f;D|c{Y*a?e1eHsG*FH;okN9D6Y1LuGYiwrkb*9l z7lfKS+vp;^$0;L0UN#+bfFVv5jp9Pr!G(~~F<@!AMaB)`^IDddyYC(|RjhWD9 z=xSg1u;#*zuJ(;4%x=&u$D;Oq-)i+<4C_t%zALk})+U>1d&l0_7VA`iPJ7&m=?2uz z$s5a=K15xO44s>Hu|`oBq1#sp>1J4S9Df`L)q>L3t&5Fs2nCqYzfs>3;^T>G3C#=k z!2K#ZFwM#_a0}1rMVUaGPz=R%N(>8)A50b_R+)^FQ^#K1e@0e@7muBi@IH8Sn_Fd= zD?M>SrU}&u21)X*JXpDTk#nWn!ODZ%(@Go3dI<^595jEvN3j1PFE{^t=Xqe1sPu4M zcq6AZf8n5%8}uK-^K$y_4}XHMLYNMxfArD$*#%aEqwb1|;WC`#Kre1H?I+dcX87*N z;RlO1wH3Fuwb7Q6N5h+1^*_kTlS#3I!-oIj4V94o=2Ug;)ptI|oKD)LP>PK<8If}9 zao%;^ z(xN6WmyFWJ5HbM=5%iL;?(@EtzLlG+Wl2AN>UdQKKB1dGdsUEr^H$3V!Wz=UR1q5H z;;(Yb6_ty~WJFFs{bn==Ef`$@bd4@BU44#@_q~wSanLp> zX;JEhkFI%sR*s~s2oo?%gA|X)pTDXZjpq@>!S46FP*uhssYXqQ9bZFg8C(@ zVmJF%y0UYfbQ~8SAM6&auyhzbD}tfzm?=Y8*|6RAOVCGE*~|^2E_j zQHTp4+O0Bk@5&viv$lrv9gPpM{~G*J0rwAQDqPUErAsi@RgkWP7nF2S`u$3H`L2}o zN7b~~3SoRz35>QU{mV+a#l|wFTcx95vw?IdovS(W%>15bSqP6yL}@T^KnNm1vcgX!iTN&Q*d_+lyQlGMfO zI;{D_o%z?zu|GL#I-oA+OAF#(@n!fzD%zEx_qdc-gc4|b#LYmzC8zO98FSZ=@6te}t4&AW0+ z4O{xYTdE7a{L7oW@S(TYz5DJ^q;s_Mpt`y(?i~@hULGFuPGtv1={r%SLeGe9%k$@O|f);0-!R35JW8-7Lq{+D1~ zi7s&sUp*FYx*MjKnRGT9HEisvXrE@PJYU@Q2w~&_0bivYlTJa;4w*A|f3#1`(N)b$ zmTa8j6O=o#E@;V(z4eIc5UKmBDXV5?j|)J|UYj^)!-nkaxR{_-t8#N^_U5i~&jsvq zF}?VC2h9xfF7u07P3KVAT`*L%kHv#hHnzFlCwgu&AfH>8>!)&2^mDu{3TrfydSY{K zwohVN^v;+V<{+sjCW6hf#Z2(aj+>KPADxZdUNeHWOw!Z&*Yi(zeYI@PoS0wz`-gGO zH34P0iL1AUA4WlM#`|9PCNe#gUiRVsW6hXmY66DXzN5*==}5rxr&9tclMD1L?}4$t z7{9t@8UeXx?#)~n2BxE?%l0Ch3l!eRsbz$+8ipFj z3e)vcFkQrlokD85;c;Vj;YA{L;i(`Mbho_d0(8DhJ{Diy%w;osVH?{Whj+jY4t#IB-~#HZeOW*?Qi3!rW?u%@C8{W_6&~(7H8K z3nc2sLg;=k|09#uR+#P4CfO6*J0=}Z{oxGeI9Avnjnc zQ)z3ajG}IS&rHsXDk7BeVj0t6bM=e8b69Y0QM{%de-n%~{hoD8Lp<{u$VPM{a3f(* zLcC`PWDyk{jN-znb;AhhgR}60B+!EfF3F(x5eANQx|9wMjfZNpa2w0B{$AnrQ>XB! zBc~6hu&&L?6W@26@ zrXS^SN(kGy7;5JU{`VM8hIBb$F;DC(tL?VRF6Z8hDLzQX9- zbCzIqzH51D!P(bd`&mmg&vL2=c7io%i1BFEpJ-^HhoH zXHN_-KEA1K_in^_3`K)n2a~X!kb3IWv14b}qp4pnynYP7f2n6w$->M~dD2^(PA=Sf z1KlPlsJU0s?(bZ@n%C6SaOrJgCXcPZK5LNEti`hf3+l6ju%}-**W6MN(F*kRJcRqx zZ@0gh`yp^j_~oLJBg;Si5M3E$<$tgXR0h!blycE4SAOynP#rruhXAC=Fi1l`UbVf_ zwYB0#?S1X-_0jurrzfN=RotO3`G+Y93GAPQs00M(M%?L~deN17M87mvVM{j=FK5cx2e0?Tbaf+b-0bYpmY?rBD1<}VCZ}M8 z^+EdWPw>_E-H3BtL7hN4+2#8>hqvVuVXt4U!5IyuA)d4GUtK0i{qp%|T-=;7B~hO( z)49oAL{Nv-2hN`kz3U<+-ImlnIOc-a2ddF*th1-n0BGtN#B>vsZoSv}eLdBSj~#1> zj~zeBcf6D5_*f|2GcEDx<{=JtCrHj!`KO_7u4kg_{dcSlRN;e^6BW7E=ww=T1 z(9+HMDF>>OVAcy6sTcag2l01?hh$sM}wZZ8n(5L@rW?&jsnTnB>7M z+0xA%`O@Ls0z5A`;-sbr>(a_!MB)Tn=ie(x{|dsm^bYJVEKM3raZa%pdrTycX5DY7 z7PPoRTo0!6qTmV%>ID^%Z&{yKYcg(;gH-mm@xmtS|Wm6`eC`+iflV@|vzaQ@5a+ zipcmO(t}&&y+riZu3lX)YdWeV3cJmS_V@JU~y({&5$9oy^w8)!t71R`G?IubE$Z&U$cc)Jm9U*v4)NHQ<9Tog4{{{ z21A1;f@EvIT9cT&DsGBTw$JL^?A+wsAo*T`P?_mxNr$6}BpK3qK5^{SAd(yXf|^mc zrJ}btPi+Rzt;<+E=w$}drI!2Qav7T)U@$$8=u5JD>hVG+>)jmm3zQ6ErO^pmobv2k}C`XMsyc0~<8rKHcJKdqC z1L|-(_y_K(qo&A-&=RcT5EqavIW&23{=&>zB)#ld4yT(l3pS@4zrK0<4jp1%Zs3R?1Zs4ZA%j;jhrJ9Z|GZ$tgC>VcemJFBq%N%rvnH@H;OJb zlW-M!s0uZ;JfNu;vAJ@rD^F5GX9#o%GSm)w5dq5dqC*0uyI6yDh*ve&8Ul1P@GE({ z$L(3Xa)$dTJoIdUc0I>8vbk`aV`42eA>#|DC-88LvG=gez}nv1FnoJTGxf;&u~^=s zX?<9By)^{A)>Yq#V=&8tV-^#pe|hNhaB&Rtu-{wjIlXcJS$&{xP1sAA4K&lN%dytJ z72Df*$K7pCx6TD{(8TYM5Z#v4`}tmMTe^Hh64NbPI{Ee*)Z}XQbz=NX^U3bSQUmOGh&V(J{qfMo-5a>+0eX?BW!f z!R#!e7^C-}!SJ#lu%Q64A<5SjcfcU5Bju%e>&VntM=%_iE^4f#DdoY+?Nr+d(-))< zo<85pfBqq_75DnP9&`g3T?Y;f-4;GDtka|5gjyS&?tSAoa=To>0{z=_!t|c_f{UN< zOiMRvI)3Ec6*(0`^2qmx4}X97GrM;S(|2z|O6S7q+uiT;;QjX@`r(mn|MBxH2Gf6Y zD(|YIUP@^hpEf8hYA{`yjGUg8lpr;oBzV{KwERisc_(hZ_S#QdLaVac+JJY7@9~4; zJtvWF#}yRC)PYvKXr62^wEZAJWZKA-kfsx8>7U04g7{}>@Ja4*%QB~fJSWM&G}2Pfd6LQc;FtM3?q_U+O4pl^c3JNfdv zaS7n`oR_S>WX^{LuV{nydgasM#0s&R9|K#yY1LO|*9@somGUEC5ld`;qfk@;-%522;g zVdy3KU8?gvD#J=j5D72bW2X>tt?D8m8-`1;_$wh>=#o?YO}g!+4=eNmg_~3{w{htMWiYt zHF~<7FN#q&#uuC~f^_XChn)U*fx7)gf#41#$M|BrEmGDEpUV#;sa*;?Qu-`S^Q1-T zux)XLOGPjzY&dHfEOn!msB?C%84LVdz1Y=K*dtr#A8MUV!1|#>6y#6=kz-NxZB;#A zuUbHtBcfhhMCr<7G>SS5Z4JwNF7y_3+c$j^%yLXKWmc?130>?vqo}ixnZYfK>lNm8 z{cp?@^2wO>u)G$eY7{s5<;zruz7)}mZth+;bONn?roLNOH?{7iTM-XI-yO9NwZrA^ z$mHub;6JB-tCws=uPU^49hkv2Zox{Ao3Rhc$JHi!iX`( z8*V3mF*nA0#M&~Xb_!6{gcMMps7g=)Hii`%owChxv(${5@DLSu*vIaI(i7(pnXcl| zW)|b4>~E+i6GjdjCCDUVSofK0WBQ1-_K{LRfLt%~z2Mg{HWy%P90m>(r%qQ*&`RAl z0jzQE+cGnaH+}h@4a=7=-xxtcp^?;;@dA>|oNfU&`-WjyU2;2`J7yQ7spEQDU6193 zBo!ljPvlU>3<48XLpoIKY;!WZ<g9`6TT7_n6olJ=S^_6^SSO*TwyuGnH0l?@} z(=}x!GD=N1rK9ExRT3iyjuO=Mqc&7#SZMBGbu&}597p^5OZ$~|fuVUJv8B{_#v}b1 zj?AZyFD%%jRa!bNhg@7pM^`I!w02wxB+$u8i^4a_Gc+pRmn^~ZV@D4kjRw)_mvD6d zsnYmCP&$Nw`y5PP$N!6yPZRJ!7e ziQ2Z(KPZ<+iP<3`Ss{%fb}!a6Y}2j{CvUt4rbnJ^ z%*roT6bR=PIGqrhmvyoxY$(qtFTtyQBzpZ;(xCR#_x8Fsx7SS^`>lU{WMXqO{Yzy} z&udDOJN?$B@NnRMYXN(-`%+9UlJ-aEmQf4)HtmzTORElMc)HU0v$bvDfbr8uPRC4L zgng#v)=fH{|Ln(Tye-`YCvF@IZz#j3(;^O22fpaJ>JDd5voF z^TBf;e)yqDUIfxV``sHCu2C>rO_qx_sx}MLG1t)TG;KxLj^6fvZtvYld1xbkr=?31 zGNOEeSSnf*(AA}^H&)5&gObh-YI;=3W;lKHpakbAj$)iVmHU1NV(UTwao&1h-BQyRnBK`Ll{?k+9_jOy!KJ0AIMldu?O+;db0&K#MTwHSYy#&Pn$04FlIhW+C17Z3cf#V3>st~1Ydpb#s zOu*^`Xn-_nfGd#hj1;cGrP%Srsk>D8)4qs!p(~H6O!a(MTWiz8tqlVMol{~%IN;%* zuIm7D76T`x&(^;}XdN%Sfpnc1^JsHxo9>aiE!{PcKIlOr`Skt{x(<_ zrX#1{t{}xo(^o=j#Poi?7Z_dJV>ET7b(8mEJJglU$k>ND{YSW7P|}T}j-GD0UdT~@ z7ETA#@BZf9#`+?Ux}~S<;O2ixO}ABZ)O48KT#amQ$>~zk#qP5tr>n|T!a8-NkyJ*i zxe=TmoR0!d(0PTrhZYo1XQ%4AV7iw|OI2H%?}FIiUlEq?gmF{8Skqp+H{$Wyhw5tE zht>^kuiexB?nCd^z59c91O{1Na&~nr=~#mMocW38*loI zh4na7u%}BN|Hj=9Ow5frl1t;#`ua7ZH6qb-56@kHEXLbC0!|ly!*Q!u1^Lk#v}Vj& zTi2fb^x4#lsw|=cO#~g&i(>Y`r$c} z=q0AFJyJebh)&y5De;LuhiPOQz22`3J$=Ypd*25<3s}liExxqkT>vbCU917PBSa5T zThDP5llLy1ohono@(p`tEZ;!wY_fE74GYPc;8RNr7olq=VdD;0jDdBvAtfz^`cY&4 z7OeY$$L3guqXSq?b)9-_W*QfY2-FOKP*Oibpe`zAtF42Kq2Qt@R2~|`wPHdFOAXAz zjkf6pZ@S?>EDc^plK6|=DO4q3n^I2qom*r+^a>R_q;79T(4hn{eGKZm_bGTp} z>g>4*^gY7#f|@=;(Sm(RFJP@U%9v_61hClGcx*JwzE}(CIUAGBVis46hHuO2f?s=B zq;3o9i4xOw=0Qsfr>#44&yBg5mG<5AdvCVFF*MgaG!u@w+N<`oy^r_6<~zP9 zeOvt*-LbvKtN$@qcpxG-qa{apPS%GO8~*+?n||@rS6?s@^sZ+qIRzL%pW;_ z-oP~Hl%fhckbeGT_khin&P7YR>G&i}_jJP80o`q8q?Ke~^w_*PW97BOFU31%6cgHr(B0K%oB|I_>;W>w%X?Zy)>&j-ihNUuQsqRaOw2%Nl8r=-7OcNy!q5?uYUj4AD?a69oTxZ{21pu z!owR>McFszjo)5be&&-;q^8qI>gcCOkI|&Ze;RW7b00kS`g0%RM%TD<;o7#&o`Vmr zSV4_wqh4M~Q6lF@MCptb$5VIp-d7hiW&gJF(yAoRHQ;xF&^ZOcH7SJ@`jkbbBzmfZ z^c0dh5_Ji^H{om)8%>D)Dzh@ zKP9&6+((~XxzJP1_qOg{ibkg|1!rluW!hLN)aAJkUnhLA@f78~zqL#+>O%G2nGZQ! z;fa)K(`k;L?n)=7_;@H?&U2kP!7xt!9a=h$m&*jaxQ3;Lm2h0kF$y^=E}rox`RYAg zgAaBZIeqt``SW~{4YB<`L z?qWGe`lNJWupBRre3#phPJyR!rrdU>LxsBj4Ww>ix?av7A~U`$raLfQhYQ*mi_(pn zZY%zV)aBPvC(`eI??>M@k&L#S{%wQlc0K8{CZ5q8z^Im#U8RdT1Mzo~y8UMxb=-*L z^0QbT7ie5^x~^h)!{tUqm#8jC$M7OZ7h#Le-6~v)XX8&1x93x!1f$<`518%}Oy45B z=B?!O-#edxAyOC7%cl?U3I?VDd!mIZ+FILaXXG_~{(OparsKf!0PnH4D{mZoI>Q0q zVrpHCU&WHcrIefJjrPs5cZ9UtU~k>o541v!J~iFETsL|f$Xqwp#UgZ>U|PC%bv*u3 zZG8m2i`wgwJ5KCse`vy}x(Pv3+Jn~Y+7;A}F})r(mr)%({h>MvNo(I7^>F))y*GAs zo~Ydt!Sj1g4H$u> zPKQdrInjq}a^vbFf`Z!HCypy?_BourKb(d^e(tN(do(CH1_Y(EQBZawX7IHEH39h4 z{j&MwKH1PX29O}~U%YdtdMi{NV0VYS#pyxKQ>S7!N2G10foU$Tmx-wCT>bofR{LdV zXD7$R#JH=eQO(#gBz`Vnx)IaS)0^?$tT$r11Jj2FJbV|Sj5Qw~{w=MTa!FpSs~JKL za1;;UN&r;!C1x-3@~nP6z}5B!3)5vPitYiG<925*93|>ntH^NDZIoS#DIbZ z*9|4gTBFDovK4`6i_-<0f<6s&TN%+!O{u_7HJq@zK0v_GaXdxJyYzPeQ4}qnw1i?XV|b2!au`(cYkAu7S}-m!xWKfE11;x#s}dGV>863ta;qTpw-J{_1UmSm~JSY z_cnB{(0O(oeMlzOo2qZKHrrtB1{;2b z=2EE5$pUNd7(CZ<4oKHZtgF~x7ss6doGq~K><4U2yEe#dnR(Ljz`A!px>Gv!c4@KmOHj}bSsp2Edg7E6L2fg^K4LiG}hmFoym^nC#@={5`JWq+@fC2L;Zo`@$ z9$wF=~zg} zbqtwA%Og+vrDF$?E5@~QbLz3e&8Z7rW=S(YU4ITr|Kj|n2b)SuyKn5np?8VL)@H4 z9(g43kw-XO^Ok~8m*^ej=YH;7PvL$aY%izZc^f$$+Y7FjiNZjUHW+nda)8?&gY`?l~wdwLgG=dHRlw7yHSc^DRBpj&9m&iLZEN3(=+%@;jB|$XdZ`XZuyaWSmeN_XAZ6NZA^(ZeT(EpF&XJzQq(y~6*xW6g;t~Z zU{phD0NYt5rsin^UWy~T_Nj98r32^o_4pU>nAK29d*7u+t%K!e=W~EO-GH{#WJM>==2*!kiKnr0fSYq*sG5sNBG8)^DWmH$-3&$>w zN>YdO#i;3jm*?f5>@P|jZUMT{)h*fF0J`ECnSiL_ZxCGxFKTN9rjutr8`kAH^1y}a z#;(py{(N@Kf@xI3qoxPT48wImAdQQr`%gzyr_m@Lx_koBfpi_?ps#zOx=#nv7ffR* zFAw0|3wt_?KRL$YqBPORg< z^}11Yqd-8%|F8eh`&Dz69SM(0-T27li7WFr&K&oE-?He9ak<&<+3pi258L6kY}M*y z%1E)9$R9g#B6jZFDREN>gqb>SRH9$pk=*9}$9%l~uu9CFGG)~&KX-SCIyopN8!m;Z zDL=*h5>V63++6Qfy^_wU4JD@$aeX2lm*g0{E?8Qa_$MZAq8e< zA((E6omKfArswI}wR4W;mLc5tsp-O8MCr+sL3NY%qTq4{PH{M0b6`-VHG;_QU^+=J zDj?l6W7#rDeF@Q&9I)ud8dzA2g(QfFMou@BZnSmTVl?P?6y%NDM4&Dn6c`&#Tc9oS zM7IajO(m&9+W|psk^b)&X^!Pt!;A)@1*@i%Qyz41+*>vos!`?EVMtRKB94Wg=;w~%tr7MVNU@Z;D(?sc@Mi#7B$SYNKb z7bB$KR@0$$b|@Yqz7<(sOqp+=f^H$Y!S!zt(_>ArFVj6cJTN?tP!F)!U7vpFoNJeNFhRwYRu`=JzRiv zk|@GbudQ4(dSO$mJTI?wkN}7;{rH2e`3T>7NFG^PyjcS$F$$JaM2eRLGYp=r~{W9U6}=zRjrh2UL8Q%4bSM0zE^M1wqO zIxuijQT$2t_XM}Fit`;Wz5Lj|$V2lJ8bc}DRf^0^ps-UQjSoKUSPO^rG((`B@7YHgi&9q#h__Ax`pP(&HD zk)d`44U!c5=M&W5`5T-%%wv(isUAT%Hw+(;@Z5#F)80G5c2@ z%SBypt^?C+AVWmruYR>Ad*{(3KF#nu`RWsfVtUybz6?wkr3@U4L>dB9DHB<>Blz%@H)`NFW&S+i6@3a~D#U$$`>CneCH7ja)@ z001BWNkl9ZX~An-C}`R9kH6oMJQ3AF1cDHD4&d`g>`_n#o@r< zI9bX;b885wSwd!L!`7@uY)E=}0J^pXg0Laru4qR~O}BuM2B+BGM_?+a^uXk9-@SJ7 zP*!3AtpRm|u2%7=&VH~pf>3P`TKZJN824=0NdMG`QLM;VZg>;vz^La?yE+`n+doXF zAdFevf$4^Xt&eGcS__6P0{+r1dqdYdhS^Mm#fFM40`8B$+DPpa$1p5y-3X}vVCX&B zclO14$2%X|^ZI7?Uxh{d_Hlq=bJI@BhV_1=Zhnt!O1D|vp{CnQ=6|l~f#W?-hD=K$jUuTu3xZTf6!I47wKF<&w3?$h5t8mH z$BXMAHz(*lJuE#lgLWyQ8R>&Poju8DtU4Bb1o@P)|LEK^r>Zw^CW0;xvdk-`w-01C zazGyD_cRHvU^?D(>h>)lIZTRqxZ=^)<(xOJ1N{e9XQJ@wkzvmA;nEh?hb zs&iP+j;?Ln*00RsYq9inIqT=)M=F2k6YMi@zWL^vPtW}J=&6*ED+oWKy5M^Bnk#So z2x2<~HsZ;NrQXwr@%(qB1r+kH@PLI4LkNc2Y=uXa=Wd!cf95OL5=r@5=`z6VJ=T zcf5yOFF^D_ykr!Q4jdRbe?j0tIn*KaBEr&R2L{UR;`Pi5LLEB}y!7(Fy!6t(eS4lc z)H-X&tnl@zDFn7~tmx?$%=s?-=%Bd=Dko<5bkz$&>B@?+f*mELD-d#lvs2)p@U7vV z1MR;Ce*vaDSo1q~eaAMY8(X^7(&&4PZ^@KSSo&ke?_%dK?t8+vr1$CQ7Whg>??ZIO zyL=hab@aoK&*g8mr91x8v4$@}x?MqPp?ZHxH{!k>plN{OAV0c^WTY$U4}o^8<&mNpMd^mqjq%0ozQ3avsr_M$tp!B4VBOqed6|V3T`K!5 zwJ}27Hb6eBCnu)|9H;F)#&MEftU=z3(p=CFKsbFm2aNN% zC>mWFd#l%UuRsvpt95_@cp<#xbnNVeGVfS-4 zpE{J&2@kv1F2RvL(S6IZ+NpIo(&=zCw65-9PXDbTjWJ@&mNi&F+?RCh*gIp_o{suj zcK{tRovS;k(s6NfXXa8bO7dbaW*4GeYS)l8j^|~I0S0hP%y#>??jJXG&yd`m(Wx0* zmz7QSPF*?k5${#!Hg2egD>0r^S-9M7*$aN&4-93}N?eQg_!RKS2`IIm2QQ*fyXWB(!9ON9NUdD zoXL#^qTs0@UI583uqaH|sQ?DsDqlDshkH%Ie}J@{DC*%fME-FH@l778)!0L5%y#oR zI9}jGXw}*WMg!)cAjo|Ui9f1}UgAA$m=*BC%C%y>rQQmIkYLkFe$l4bdsy3TR&Mr; zePivW{&VbUbJXIPZZH#$=S=Ox6teS`1-yV|I9S2lq+pG<=H}VcO-Q>M+0L8Br$Cw&8UMwx0Z^t-a zELV#jsg6`Xd~y2jtS5{E#-XMgN?$Nwl2hpD*riDs$m#KbHGo}ulFCn-i>f`!X!2jO zN@PrTa&>Yhh+`1V-7yn~hVrBn33_sHlk{>lTCpX^_Fvk+pDgWCgLl_2zV*&q*RRuQ zeVUS9HbZiokX@A%i1J=qN^~Ozb()cucEd|c1L=A1mfG31w=-;T=)!K(fb=!O!KoR2 zaK&*f*Hxtrk^g34dXp8&c$Ij8_lN%{EsX@}!;6*e(r;AA`UuCrKm4FsptyKbPuFX& zyz67;6z^pD@^E>autibK;|0ru`2v_>`K zY)i%NZv62{o+rtCT-ejo)46|r2_fcYtQ)ytdpgd&@w=b=`t z$O}I?T+TV46zXZON$!8~#r^aGC@i7WcmI2h?-5S<)|t|jBTGh)TnjK5w2Y zCV*##o0di|J>St4i9Vj5F?vv1#^|*11L0wM62a-QNl`ky%P%hO+4s`FJb$3YYou>{ z(INE70lvN<`asF)DBdXO1Sk!hj|IVFQZQ=z0J0SUbs_elw&KX1eMCCG{PL9p9bG+L z!w)TJDriXER^p7iCe$RkI}O6!A5Rn$9}YSfq3Zy^DD@a58T?A3(+znbT3zANaxj z50Ld@C#Qc?YC8UO)9}bjfB7brq*kvZ%b;#Jofv51a{iWKe{{QURQ?t-Ome!VryFTq z{7nbV$WCFbhMH-rVUNYPVq5{bh#GLumz-{Bo7z%9ySMMWwb!uaJmKB3SVIev^&ilO&RRIeeZZ^p8pd!_A=bDK5oqw zWgZ1xq3R&IK9W>*A$v=Y5z`4xuXS(7-9m~>d#w!UK|`q*ozPwvM8RlX-PoCQI~wv( z-I81GLx$818(JrWOzjrj>Z96&mMxnSLB~?Y7J^+Y%S*&dduHs7TQ+xf&}vvresnsK zUdEm7?jEsmL)^J#=a%e5ja;^j4E4YLcl7UgWsP6l#*#r>=MD{+xMSHw_qZd=;vyoF zgQmJC*A2OQ#B$fw-v3(W{ld-|?;&f^@V@p9_l?`u^L$YIs8QaexWrIrntg0_E-Z>z z>`mgi&xQ@FXHqPhoE?Os9wfgyzH@IXN-@AlSEsotwVSjb#pq%La#1=$c{BB?i0MWy zA5+5%u&78XZ-&va$LQ3t%0|r%PV;d*Ft!&G9Nm3rnVNlUeJ)Qc#086QjYyQ4bB|Cy zO4(`6Fsv{&bz{cFl|=JujppRTal|xo5Rte(Mzd=Al3uJ(L0lSW>R8lOM=GO;s84nh zv|%V$wvM60y!WIQEDWEub;q6!)R0=7PBo|iTvw^%>>JJ>*t~1z<9%U|3FO7@?s#6@ z4fk1cEMzVOw2bHm2c-&|OhvpA!+2|9x|VUs$)b3}vi2+p)o%OAXD|jHtoD;p*NxxV z9AFqo=XeBo=hT6OSY0L$12MHGYi&%hi8iDgM2CUpo53nSl>-bCCAk3V?g;1B5Skm| z9Bij}R7I^itl=btCLNe={Qd^j?ayh7V~sV)G6>yq%Vy|o#2o{KHanniCs;ge)N1Qc z;!a4n_Lr76uj_YX0lB?$^SP~0&m8MfzxQQ^xjKlR*IM7hmsV`Ex{eR}W4bwrFgNz0 zgpPRbP}6mMDNB{{raLHovUuD;xXdr|zu0(g5jwYKSj#y67^p#oziWDWW@t*RZ&GMT zN=O#SEFGMYG{}jR=BW6ncmXMx?(FGIR-=>KV9YQyAH}`l8B7r!oSsolV@U?-g4`Dt z9*5KE6Z3m(&>N;Ig`PI0joXj+NOM)ti_-5Hd5s|{LcvmeAx$U4w{Bh8$+_C%%Gu!y zySwE~e@g24`L@8uszqMTRi$|a1Tuc~#TQj%5K2wob%K`H@3(D|njUHDNfrE}Vo`=X z5c0za)HQo}G3nap&mVa7m8X8ub#~gcO&G{7HZ=EuECr;_8awnlA84Xv`w3C5yZpJUm$|kNEhI-dd8Caj_R~ zdQ0m_4oG5)61G=vcH?ZsU=-~`|>=AFRU_PWRKqgm;#8z%}{gQGS>u7y>p zE5lP$SEiPfG&J1k#huOu!i$5tFUs|@f9tX3dwU{V1DAGFMS6uDbRhZT)2BcA`1A+w zlr|x5FnUtD;YpBm|QP=$1B`43`A>F(FF@mwfdl$BxnttDFK-IK5=ElGBCh2g8Kv zMe(>^{*bf($ei=HeJ!|JEI`MkZn79}8`D`A3sy%Se5NvCQ8k!;<=SyV&L_DXn!f-_ zAHS&Ti~st`@2>prC;vY4$jMlWUKg=_^q<1`@*=;?g)3K{+Ez%SI<}X$_~=Cgr#q+N zv`dhja^R~o2fKO8buHNt5vUwhGhbc<~@ZoqACuaE$1I(^U~FHGNVnMFxR^1H4+>c5muBcK}oR zOV9I8{62TiYCRO#S`eO^uxJsz3^1ex^N&(qtkBTGF7UYE+&TbY5;fhxzB&ujdekL& z!1U0C;RWG4mfL>~{sM3mW`6xHFdZX@%-2eIv3nZfN;g_M)uTx1#_;0sq&wU$V6I_w zeBYwABmM8jbWs106`XFo>3<^X#W>UZLAt~4A|V|@x7_K^ zzx<;g{m7A=ZmH?Ay?k4JNlhUsin?h@>WF4k;)~U_mCTC25z_zZwl^J6-`jbkHp4*hJIkY`ix#%JOW+&VtpE&4<>#OApfa zci(+?)Ts7%!SpR1$p8<%NJqWdg|DqRlR}1M{-fE+l!NAywK7D)`d8O}Entii z8=-ct_CRgdtgp#ZKBTM;Kc`||2u6U+@paOel%_-)Wp%mU+>NUds(brougcC%3|QN| zZCfrXIham$D2+)UC_{=r96k5L+($tE31!S3I-w@uaLIkPM5zqV3^)WE4C38a%Mx>60+IN zi=j%Q*XfIjFG{ZZHOhXkpE&^x*L$$1q|S@UX+x@05wwb86JT{wy2JFsK@KcxmF7C$ z%TG0{yx$*OwF5=z)}8&pu(SF6lCjxn4edT@=p0d5TPrbLtgNBM`gWUR*YV~P%`~6a z`pk|`?zsO0NY`?D((G;XTJ3qW_sxCZ)>vNM zVbK^&WhMRFaW3eds!+P~M2*hK&?B0q<0RH7CGCa&m!s3tqTtoiYO?m;d&h=!?wDxDlq~zt5Uo9;~j75;mD$Qz0C9?FytgYb-gS}RS^=zBf-L1^@&kyWV z0OR!7q(zk;zKuzF!@=|m7p|3bUo}s^4W=903k2>M4oKG=k^~I38%o#Xp7UL=zViL2 z{_V!4OYeO0);m|Pf~Lm&qC(9}7cVk{iqMmihJs1Ji48vSi`PDX?d*w@S9f`Ay2B6;gQ?u_jzf8w-CM^GMmRVqQ41e|98?8}+}ua)9HOEAG!-qJ`-1-?`q6Pjq){ z6MOI0+r26rz1h;Tdv|MVQ)^q;pux@qFnu09nRMl5#fn8K>i7`+r`-@b?oJ!Uso;ZUD- ztC!-eCEGG!bADk4QJs87m8t$ZWu!&)7fP!(&ADK7|3lF8 zfh!2yB)kwy9qdBcCb5VmCH$Llb(z%4r6{lnvlFLbD95g7i`?@P9`>%z)JdeVw0aSn zF1t7&4N@!2Wm4>E+& zeS*5$k)FWs!dMuY$!&gXKEVZ+oK@<9_>;A6a z*T4G3iP_#hl#te!O)gs!w|eJ>jpx)(w04Vo(7Qt?PlyhS8G>7V=f>n9?;15(nJ{Bv z>Xhu{iNl7CTTLQ*c5~U7wJ|GwKr2}|pmY*fw)#w2zoS0cZ%VQ^Es4<7{l+$PGnF=^ z*^-zL*5!f$(BXA1fVr{6$Q8p-pdi{d&T$0pu_`H*7Oxq)FT<4HoE^8ZnchTZg_Q`+vTX}DaAZy$O zvI<5KU`ij?ojs3z1*jXHT?_HZUBGEz7{r8M#}NksmKtU@$>jz?jW~-vo(4;X(hXP& zs)eQu8x;*TLgHdU<-{P*iql7s^v*DIP13r&Df%43L8Np+;FwVcXbpo}n`A?}`Q%3W zWwpE|pM;|gJ_ct3A|mP|#u~w#9X57jv*K(ct#Ly z?H^E`(=z<%!i44O*S_e3bbCsBm8)Y@Z8+9;T374jhd5nTq!yyvJIEqzeLjn~_14xf zTVZyqHRYK9$L@J&1L@X!>_Y$^=*@)f+LH`(pr9SEVGbYk68=Q_ujm84=;K3gL!M;#mfJx4ph59;qRc>2=U}6>^jJ*uBmY|VufK}<_c>3$^2#d*S}GQ-TT03c z)(~z=8%G!Kj%>Mj_2N5kV^U$Xv(U|3R|_g&^h4dPO$7xDPcB4BM@TQJ!fsI#T(GOX z{Y_IvS~5Dn=_;6x?mlbr%5A0b;avyNEk6U(Kf2O<`1(6ad%4<8_wFK&1K$4p=FQiB z_SDTAthqIi8rg)f&6RYsf3U5%I;SnHb7eI)amKoPbW3*nijlE-*WZ5UlaF6{^Y@pI zMjw6g#i}Y_UtcyoH29fK(O^2R7tHC@8~A1s$%7EC^cvr^gseuEQcW;P_`Z$4C7cMD z@%Vl1H*XchXE_B2hdMbEK$*4KGwP%#p72=CtZ*jf%!_BD>2jo#Dx0e^qDm-N#!5uz zAiU{rVa0!$oc<*o*F#R9{E@jBWg;WnrdRe{JICj^aH=FP#oq|ku|>f>P&%A`;lNAZ zeI@ADiNFQx*7>sUt8{kg*fH8p;V0p%Z7ifg>06)Ti#c@Y!R@{&OMU4&DpUHt=N0hM zv9|y@k&^-()25G3Em0IBnde3kclIRmC6B0eI+s=ycXmAg^798S@9A9Fv~Fo2v8VK) zs&uY&R<=0=t(xi(PhSoe#=BPfR{~0EIr=_9>AcNLm(T6n!#@>(EZCp!y?PCbeu^`Z zOP;~5!7dy;=hJ=^N4iy(iYeXLX>=SQzl$VxrX{uym`)k#!U6MbAo!oubc-=@Z%9g) zm@X~-hjtF5@uh$Fy0mmP9RA*rh8N3t0yJBo-bd*oYQ*$I z@}~d2YP#{J+j_bsr%Sar@7ZT~u{O-2b8W7O9ZFYoBLLlm{43t0001BWNklZ~YK|Eq=r z)3LkA@j}<#+ZWVy2o-}1D4oABCpBlb8jV8g69ypU-c&1?mI5h$F(J&TlWjM`-DY>A`M#KPmL)Xuu+E zpjlMDr}Il>eg}s~sx8@1M~^J>ZD8WPJHMk_ZD%nYqwPdM()lAT>Ac6ILA6X9Mv zBcg7Iyyp|f4jnZ$D0!H)^xBDa54DdP(k?QutzC|OKDF-MvF=;Oz56ctFWxonYi8C> z81m4Fx-IT9yl} zLj%4sq<-PnxMV-?35h=S8|SXh9gCACH+(g@bwr{Q>@wu=&S;-R_mu?;H}HXTNt(=U zhc?^szfeMzo4v}Nz!p^X#AZktA5Fi3eFmW%n~T^P`;51rZpT_Mu3J!@1ps$%KcD4u zy+!UdiGIyK8!SvuT)!iGY|R9N>1E@Ti9V!x=UlQFn_05GuB>d-1QK2X;>!2ybuovd zqYulGPKD~)VVAN6{SU0Q_o#@~Qh%j1i_`DMz5%DhS&BS_q>TOAVET;I0x*5$;%%xQ zm6~pG`V@EhS&U*1;~BA)dt)JCwh)&)9)r3z$_oX-J8U&5&EqIJV+r=1UTkpB$inFD znA52twYZj-FfkDpx9HT6y4Ew%V7g#XWupd@hl~;>>amu^|7?IAVjMLB800hZIY+Q! zh9OTOusOzHZH6kfCLODYV9hZGpAg>*XNi`?1#$4eE*r`M@VJ$ju7e$^=;*?_^*FBZ>`VJx>n2k>Oh4ZBr`ns-06{-FhaYfwcDHIxMNfJv<_T$>?niiLgGZRu{p#s z*zEXRju#NOXfe6&{@AdN5B%(1?jMZvwmPi3I`!DK zZ7-%3wHmSf=Dw~y#9XJj1}^YASUIU^fLB--R`oY79BXL0Do@Pk7YhhqRQDom>30rG zUYD9KZf7tBrk}rX;QQbI>5~@$@=G+X;ozYg3yL0M%yzK)MaI>F?xv>J)|Ss-!y^-! zSxw`Z$b;C@(*Vl!O1JdPbhrF`w+gp>67Vv^NL-I%Hyk5dG51%wkBogJ5deSXW=kv3 zmsF0s!)=i4F~Jq|8ahqcs%5po34Zg&iOBAXZf=@d^G_BmTo?|fmw@SnikFmx7Zlv+ zZSPeT>D$*&1~(NL+soC0g^L%?+I8+};xt};^~WDQ@zEQ(AAcZBKm88J9VgZ9s8@YQ ziAooxH?ZAuLiRfxUX_+0PT!nR zRh^pJ+1q~K3L$p4yK)UEcJDswnoZ5;2L{ z(Xk<0`Df(x^QIa!Woxiiw!xunCf{9#5|I?M;yj1~Qd-x>$2+^Yea`HFUt&xIQ+lAUS6xzb}KqfaMDhLpVl9>K2D zr@PsI4gLpWv?$$(=|)Q@EnQl=BZ!g4qteoec#-4fDWjz;76rn!C>`20pl%RdjBYsH zNZ5{q7h6qNai^W~;;^RwFL=`t)3LnRYP#{JJ8UogDIFnQ+i7iT->m_4i_|5iKk*bb zq~BE3i`4Xo?pGwE#pyD=!0D!t6i#OsJxs479o2m2ZdrvKJJCS;UrXr@(+h+yO6TWB zXBR)lkglMY$cp^PU`j4Lpy}DD2>F!L!0N#m)s327fVMsxHC>(;TTVwfAF$52%rQd= z$}2$n0_-jFx;P-+G#8al&JT-FOX`8sg|ruv)%lIG-Ro|_=oosn(X=Ji3)c-ua z=noT|UQ1H=jEHx)xYu5;zqM=E#0g`AMh%6~>$ZFg?Y(ByIKPRbhCDlTm>MHdB`Qq6 zJkx#8o()sx&fQQSH#0fHea-5bwe;bnCrnA|hE+aC;^N|bR%3j@MFOlj{(t?4-mh9a zBqqFJTlBcKiK}Mr+z>rQ+Ze%-iucffyVoAuk?6B==aMB;u<5whp*s)R7`1X05iH&@ zSnBIn`C)|#aGw^!de$1(3A=sUSbQOMT2_DbgzzlL3y<_Ig-AVmu;sXJ> z8`fu&dWHdAYbz^zr0kKn=)*oSsP}p)gQse0dj`+^{jSw$yx_4jFi@;nx zd63g_g&3V#&J8qd8X5`H)m@VdTChq;<#}05f1`~{>ZvkVLa8vNm4tBO-w<_zx?(qR zwE<5co%&J@fjlO4F}#)$1>!)LAB9l%iBgjV>Y`+WwNiR#KkyBf9w$G&Un)&4*{3W;edh6zD=@;5}ej+g`#W~Tg$Jl z^mI-itQo5#7n8#tz#Y+*>^b(CCD;S#sw=&X>H4JlT&$S=sUcJ+&c>`&h;A-s2Z+&a zTo=G=Cu*OX8{KJWlguzQuFs&)Xk8K^X6-m@0WE8;+5qiD>!OutRc3Y8JJ@faXZk&7 zJ+yBfuQvDGa5Zp#8`bsRW{>h~%|_UpWbX8B=rfxOl&*soaXQC1I{yKs_oH(WIuFgQ zv8S6!2wlV0(ZO{LF^)eU_hL)N^x_Jl`yz0MW;jjaygc%Go2x4wL;*5#JQCtPk-cGY zJ>rf&ompAndABMdOX=`~rM)r1cM(zH^A?3PHs&?jQu+ti%jG)1Do+34OsH2Y0{Xpy zc{tKbo4QY)2oHzTX;V3EB+h{af!*D+wq3in=ZlrqbRorcEe8MD*d$`m<0o5&w+03_ z1ryfiykdp_iU$uy(g)~Z&#azQe^L6nb%fP%zhcFTkt;?{TiUH-6(y%1rlIU93Pkg= z(vGLO1n+KJ`GzoEEq+QHlRP)4RaX0bv^y~ zL+$tV76g7}DaRT#UaI0FQTH0!kP%->1AzC=NKbz+C52FyNeRwNr_bNb`3zj?2ljOi zFXsG`hs&VM5;A}ii0mvODxR>UbT_Iv1~V_7e>YK{PQm$Y`JGSj8p=&)696=c@Jx?N zS6Amsba4sllY9qac^OFWqre3Nf(Lj!^UUx~E&HCw?eg-|2lnmh**{+;Q?r_vQ#YV`n}~zkM!`rtc278 zOhpSC#|!fDv;Rkq7jY@Rbc@m-HEHQ4E?qH<2GUL4r9+q&n;RXyAEgV@Z5iFZ7o%$! zEu9;sw9rQM?;EVc;&fJMtLb)fx{c{3+=YV)8`S&JI+Sk2boBI}a$zXy<(rl{{Q>Fe z7NtKcb2=rZGQL=P`VXJ|Ki{1EO?)r9KGed5eDRi*-kDdrBR2 z^u<^(AboabK8-JeJv>_TgN@|{ncV2=@}?V7kHo@0J9s+HjVK1Sv7De6m5@@%Y#?0% zxj}E?x5`V&fq~P-=5o8}w}>g~F-XXgoIV>leW6j)xrvNCq3TYkx=WsvNVeBPbNkLb zKs|Brx@K!J8@(+6x8`XP<32Z57sKfGV*QskLOb1A5z}WpzO1&lW6BhA7$*|uGPHdv zO<=~)j>Q2G+R`%qBCmLHCDKi58FRNWA&774u@ODm%_ z#4(zvmzgv7Y&*9su72A_!nBidG7y|ME@<_R!QpW+;N|{faXwS#;_aQenuw6U?>F^t zeD#jRvh48CtsBZ}g5u&fuHO*1noRT#T=r9k(cNdm+?ePM8#hh~TC%4WOdk?3WTVrz zY`?OyIdeDej3ZI8ZrG5?U^+O}zGZApna}gAP997yX^fc90d^T%u()7y5ws$h<4VVq?mbQ*4N2o5I4R z-L_*7wscZY@HMRwx#Bms3>@qP>8ip+!KGny`C;7IZL};kd5R#O2o;E&h|sORLkc{X zxx_CB#E0-K#^Vl9*R5HdUSn449TYUvUFj+!Ugf2W(z!~cWfr(>uhfP^dWMc2D<3#= z{J0SSo~5P_Wz`l{O2XG$u^k=0M!VABvmtA<>#Xh7CR=1~ zb{QTWb_biSBM)u6p=sUqBXq6k_Jv9FF1P3CJ**$*(Vh!^z27k30*|$74c^5ZE|{-f zoNj-CW;?8n60n=W?~{YmElf8_FYHAzIp%(w)g8oc&AokVDE(Q<>1&_0Xx;ILK!Ldf zoINQiBmaA8Y*IsLtg9O>NV&AR;cg&BP$IgmnTPNQX9rrSfh?p{p5P&V<3{i-gl7rw zJ9FuhRXh6DbwPS*cd2oye|#w%A|-AFtIO3Jx6A;smv%2*I^Taq-~s@&p|F}J^vCC| zV6zq!^cb$FZmDkR` zA32&3b($aP6EUYEV@85x+-b_E)c5zv0Nu$6slGeg!ZoNDr8#IS_Y0{UZNPPbM;$f&#I5%G z-aP#Q-g$OlVE2vQTLAm@T^%O$PGb72KYn80`6H_dQhe^Y)4%_KQqtbu1MvHgpL+5? zWK%D4g%!tRcX_Z4_B{x&cAnqc=?a}s8@Z03dq(`pQy%YZpDZsprB+Ksr(Cn+^qc?m0(y@w#8$ z!l*P)U6-mjwn*?CMEcK3&k(+J(q4@1rO{QV_+6(Ts^}pFo!FJGoZ+p(`ScPPn2?Fv zg?i4cEI55Mr(NhTfvfE zES1iXH>Ib+^hXW!`p-@0jopQ?$BwR?u3dI$)AK{w z3JK}v24oYc3)l^+OHQ}oUBu3qJ|J^exc%4QPb1^kObbl|>J*Sl8r_m~f1+&f6=7NsTG(UXF4=4HQhK~pmM3>!g~8sFxzsz;7=E&vy>V6{Gtb^ zhsq8wNY_BtJ`uUgKzB|TW^rufU83zjH(>5NhD3BTPtJ5!jC^iP==MDGob2h$Zs{_| z1v$HB?76jPM#oF-muaiGp_bG1?o)?7G-0ay1m(GmXr~hN){=MY+}p`Hr;@a`eT?$X z9~!l0i~HCuM7>P(t{K7quR{Xfbyv)bIGy11h?gQZrp}DsxMAhSo#&F1$2~xV^thmn z3o|#&nG#)pxc=DI>xj}zmhIfQe9FYJj{jf(q4z$1iE&%AR&Gd~n7wnu`sK*}y^4#h zT@xfs-#K?~^u~>Ilcz@PS`)Mdxp~O4!5iEY%VLg1M=x7V+ThrsV;**2yoRo=?cQ}` zv!kPT9?nH{UzHk;%!)Z?EZ!A58u2u(J!mzWo7XDi^va6G~}Ob(`d=Yp~z zdLj?X6rc{3qntCCpoG*C)W^v#lf40RdQDmGoViEl#?X_rrflt;ZQFtpc|%$-DM}{s zk=z&dZ@qrRi0N=TbEKvR94?PeeB@V$j~w=CX1z767EIp|!y6=)^_gCvbPYr4sc8*t>1{#wpY!V0uALhg>7j$qm~H+zhNS0qsdaHvr15 z27RKC&Up&{g!F{zro*YwcpNWaW*_FU9y4u2yn#h;Y+3Gvn8!to8#WFmmoCjVg3Lld zqtOb}L3mYd+AOHF7#%p!#dO?+G2f8sh0A0xT~N!LXp_y2fpo*^hN1Nl4AJspeH!^* zI4D^&)^hJp7%^G>jPO;D86ruTqZ`giP;D!FJRooXa_iG--Ajz2;6 zW7$!mK0D=4PxZdywA$n^QG7^{`y^2$?BBAcIzQuO*F zFx_i~7vA)?9`sK*eOspOdO1;1k%Nq0QEa(hP|YQr_YKvM633{=a<8|brk{J|(MNAy zd`DvX|N8|Edya3ao*mqTb6%o4Z%)@EydR=<#@lcA;;bR8u{7^wT6I`x-pP}Bc_^b$ zdAujie6d$3!YRE=v*65<{ke~n9WGo{S)ID)vBzI|^Yq1DKKSAKOIIo9S|}+UV~sU1 z-CU(B(#eK!(nJaiO9bVGg{ck5=na_-CAw!|k-zmy9ifamXkhc2Zrr+g>C(kpMlOH# z)w5^Miq!XA*mo|d22MwJM^VS{qPahRzoNCNC=Z*G2ey_61?XlJ_v~HX6ILlTedM~O z&I9MolLKZ^%E)!GoKi5D{@{z$uQbq|%Ip z@ryR6l}JnXr4X3ki*jmUai@3QtV2#;oZ(dD=|p26`dlR>g@nZBrEqK~MlXGjMyF?@ z&r~&*QbP*UW~RB&L36VbVQ8?`_GiuM=N)dB^Y$nDpYP89ch9EcgZ`L(HeLALXCGaw zrt8+C2hT(4jL$A?Y7IWIbynA&4xI$JacIFk(>7OC)3=Lw^o-EKPBf)bYo=14V*z(lZA6I#Xqx6cyz} zrg{GPeYisow6xy4w6Tcj^nsNFA@zZ-!gGe8o#cCdc}S zW)6Cu{{oZt&(M{CLpAypr=U8-%{%@1IeaAebryEMg_4538@Bh&^fA}pL z91)u?clr<2ja6AMKTvB@lVznN=U6zQ)6(~!n8y((z_U4MW?(tGM^9`Fdom9QW#mvjP!h?rgJ3C?Ky<>)z7~^=}+{5mXIeYeCNS{$Vqjt|OVmg8% z+83Xg)jN)G7sXQ#nJ@u18#*?CdOz5^?xCS09vb#;U66Z6MEl(nMtyzQL@Y1wzKe@} z*sy>xWfLA4Is*P8F5SMYagSKOeAN`6^(*V^x2>5oVg$-w%<}M+^)Yj!eGW$-3vbw3 zA5D9h4I9_E|NrDoA5rGM@mToQ^|)9TuiRKq4^1e&cS`LVKb2PQ+!?(rZpj*IN|&vn zwNv8S5j*2|`X%OKVy~Yyu`c;b9-*goR}%c3c+-lV@Bb6#|lF*jnApWzxr5Ox+opH z4e3t)>O0R~~hXKHXUqTTnhtwG6zGGHu_{yz&X+w&fj*uP^ zCpmrQ>Lp7^S+t2zye3gqh$yn<)PlS8bP>C|9~mklW}&Hw57!GgEveN2H%|%i0CVZ< ztcQotIAXX~D(b`@<2P>9ME99NPo5Sqq3h2n422`x`yF%O$gO(H%uQ{Ywu})=&GG# z!!c{qzOr|iy!={BZ{KgQIei;r_*_tK{5E`Hnzo*1(rmbSrDIC_gBkj=9mD#j9GhWp zh}pUJSE=t)!vb~3@sv(|^rLhg9^Nq=q;AXU2Hqv8)0j%P{Y@|TOpEnQvM3#ylb$ts zMJ_Hh;sEnN48P*@nP2>LxhB(=N>So8j3vYZ;jbM*f z-_$z)(2BsNv0iNl3%`KV--upWdcs69UhF31g?6K0x@AGP3Ejx)K)M|1!#4@tC8xK1 z!K)v8<@=wbXkYsD)8Bki)d*W*=FNA@T-ZPcOSf`Z1nSWA@6E*&mtMSh{c8Ba)P+qI zO-%(&`Luk@pM5faa8rD!F68ggqZOk=L*cOxo10_yZzg+t)2&z9KR;~(UEchd6qy@0 zF5UY0^v6=tjRpSd)q>ehp5cX}bkbc6si#8c8QNJS{r~_V07*naRGDb$j10iNFub6( z;zsX%?KoQ4qKnI3`^877=^wrhrYE>&h7swqofbcXahgp*s`t!^jHZ zG47xoKK*^Q%NGuIn&des9z@4Gg~1*eau3n->2=LGGctPC>E-Q0$sKR_JH*~kUcVnc{d z7nw5z+y>Mu$v5}%+I^@MgUi|H4WwT=x3BXV>@NAlTn7eDDhg$97J2$Y>8>vL+C3!1 z!|C{4Oo=EEE;$_%HxG@6SX2(M8^a6fGHQ9`?6F|}0>?4?9|J?jJe2f*QX|biNbgVS zKd`lQ!qQ(=#*17bw<%o)Z->>zcBHFtv@b2)P`V(!57hCZ7_nQFZp-O^uQ#37gZeVP znDIwAU6y%4`cMB2AUAL>PrXg-I@mD27qoO4U+6=6|FNoc^q!ow8EM zo%nQz??o+1?`F?gc`tUOBTi6Q26e|S{tNEyZwdunklxh^qMO0p36frN$g-^{NOu9# zjU7c=Iw>ym=li?N4$FblElda0RYwYN7gV&;NNd5m1-R3RdXYE1La8tWD-MReixuf8 zDcx|l?u??2o^FgU9J`Cs`#>E5UN7PmW_fM_b@92B?#`SRO$p!s>~PSx7P5r&esjzW z*1^5Bbz5kU%o)D7>qKYQvVAvp&FDY?pRuQQOVE}zK}%*VPp%uK){GBR4{8+DvBTaC zx=~+O2f2?S-=+Q5u3PS-9)5P{RPT4+eU_Thy1EfV#;grM2YYscyZhxO9T6S+A?#)5 zxou01Y}~nZ<+7bCca9tNz?er?Z^M$(}GyTc}9{4bN?vc2e0D3J|r8AR*>M*^m^hxxY zyR1Ggxi&~{{b3IW_C z*o6cbgis+3NR=o`9}BvRn#;zar30o0w^7OIKia%{!}{K4C|lNY<)4=Y1jHPRp$wEj z_bC82NMDy2ki2zkGNq&VU6{d9$IdwqJhCA*+K+X@=o1Xf*VF`L?>~GPN;ie2B6uYF zfSPC>2JngPT`#|j1?m>9n_zLPj1;&Ms#}x}c1}p%k(z_)W%0JSZdK%0Y%b8&?-2f*rr+QEa z_KjtI?8@XN$)kpmmIw&a_){tA)(|8kX`B2*v-M&@6`^{M6V;C!H9~PVa=qM*H=Utx zfbYPu~aWI=Te>()&6-RMQu3x(|F<%XTva&wTutr669c%x6H zoy@PEec)t1h;`#2ZVS3CAh(#@meb9)^>f+qWZy7o4xVdOdT0GY8-uz{==R})wJF+b z=38GUw-hXg08oG$wdeS0wLApiieQNr;rAeWAV0vsU!Gd{7 z)OE(jy0|%^UtcW;x$rljjHVIykyc$o30+Dox;ma>)bqD4A)9~v-0z?3hvv5@2|A=l z5)^;wo$J>x_09kI&Gz0m9emz*j|=?LTW8Jy{UAL`yMxlt?t9~Rm{MGex(OR;XkBo~ zrFCid^tOXNr@-_J=eCtL7)*ci>hS8~_fgX~9kfg@x5ab_JyO@=$?coY|K>Lr zZocy9=NCUY{nn?y`G2VtY%1~$p5)?ou)6wSSaAU!lqSU)%Kc(lQ>1+xu7=djCTcUO zFy+D~+n4aG*TZ#I;rjK%AHUgrxIAfTNJUHU=cJkAatF={U)1f}($cjug~>Dpp4_@^ zWg*er4K(AdE-6&JOGd^*wDb&`ok~kDOigVK98Lf*_H@1OYIl6jt6&JIFQ?zWdG@KF{p@G2K5>52>`c$1ywZ4I8D3!4K1#>+a&6D~ zZCgtQjra8ob(%Eq9zcEMqLK6b*LA;h>671|Zho`(Wjh9kZHt@FQUpezq9x8e{R1O9;(i({P-qu z3W6g+&f7S=>G1ifGnmuC^sEfjbST}`ErI?#V7gma^`GlRdj1Xs*MmQpDXSrGHubK%_V%$!Gi}6 z@(fm@qUY=ZN!Q`@w?1uLiVb7YfA7OD-qAU{)hl@R$$V0V{2hU|N2kr&trgBsm4x7u0E-E+u zO>fKTusYF;D94iqjE|pEcE^lG5)-NmudcqnPbQ z>90~edYjS>?h1e{C^xq@pIeTXJ|(@6(H)uTB58-3u8@|$)0=)fG~GDURYGc6UQGF_ zjv8c1H)6WY=!V&)t=mPg;&ePO3S~4=FFyjxO%dr2@Vq$G^dCa#nAM^6XXSe_db%jx zcU|6XCb zS1?u-&^*&*zd+d%(`QE(=hIe{P{noA7EDu{A`e5{7N^fnmr=$T(v383Y%JUqps8b4 z=hPtmj%X;STQ1PLC_T6$zc^B<>|AWnmVj>5bgD@?mN4}FC9T{ndi%z)jG3bclFzx< zq}FR)jn&1Tj@-42eX(m-!HK=QX4Li8*HSR5(H_^UPLE?iB}iiwMT299jH+Ecqn)^y zcM(*BlBp)Gdw0m>5i_?889I6LyLHb#boZDc0btOuaY&011iV1#a;MLnxoq32jd2^o z3+v-jx5m-ZXZ5yibK^)5jEgpu9$r5;Zq=$atLP8&|C5@Y9Jg^*Vfgx;iDk=14_>~c z1IxymHMLVBvT=UL?B5?9OvO1NJ;(!6vL2If+n|;<7MnmOdYSZzkETCr2`j|&z4$qlO_2{sgQHf*g5{Kq) z+nTNI;6GJ;o%;*df;Y}}f?;i@3rwwHi>+K?_0wo-;WQyOzbG6c?N6fqiBv`AfM4bT&^ z6Mni|8u~=5WYk?Uvq0T=SKv%ltP=epja;y4H0_DdI6G0?siOwN)vPUfO|k)Kwr`ly zRs_4Y$%Sp5pjT^Qk?^pgW5u|f1YtGffNOocZ+s&_#|GL+BmbHk!KB{Yu)C3qwIP~g z9dHnyPH}~5NI7UB7bjo@drS>bEfw8ZUaVaRzTfUb%Ez@)Sj4Nd2sRV*JE9MzkFAaA z)6{k9K|hY+;CJpN&0DB$_}Ri_@v`N6;Z~nOA4)TgzliTdZ~5gR+P4lEj8bp5P>N_UJzvnSby8fNFQJ!ZdJoNlqYzAC&SHFl|28?}o@PQO-|XUXYTBdd!m-ZyIcAIRzY z<1Tf*joUWCdgK>h{N_RjnEuHpmoEM0Q^a&gltdQ~kNktxJqHgGN8MD=eNyQ!GQTLQ z5fK|eHb#}VxI3*YTdhIVI-xC>wAdxM{t}w`JMVmqqJ2p|{DQYXXW@4~x%AElypATJ zGOm~*NJpVQxozjpV*)#5a~aW@!af6~8!>$$+C^GMW>esy6IiC()#K=si&vfS!1TU- z>+O!4ubgdZdB1gO?6J5j&wuvgACt%#t4G_x zVo@s1fc{%IGN*T~U%!59Nqp!@r%4N>rq3IhGHu0*rHW)EfW7_AOSoQ$tBjrY;K75f z>y|dP9Va>6GN-5byJ2go@}0MCu-p7eL8CfAz67#bzCCv@M^`CzTOMTs%#hF>o z2~mScOHmAeh%a%Bj6BdBIH!hm|EcoEs={&%?W6IdxTPh~=$3Z3Zs|r&*QWldao&2u zzWY;4nfWa9-zMv2Q=7}^l9H9@KKkr4LOrog{f?MP#)VA>oj8$F#P8URdd>peyb*XW zhOk9xC7GFY+9f~V)00Zj;MSD#_avuZFFJJZw6uLxkE-ox5fDFESwCqds-{It$AUkJ z-oChHl(UaJ-8DUPbd;$o&BzFi8XXpi5dY|}5A1SUw~n$unO$T{mxE=%Kxe7|E1+~m zF#Zx#&C^ex>l*%ye@l zl^Si*U5tt@Fz<)!dT1-@y6+o~oEHbA8~OY1Rnw8uEl}@gdby*3lp_g)=Tg({@ly&% z|IH+&%kN@<-Rf`j)1N>2gw*tJ-v6)PlI2CF7vyvuzYwObj7F}Ehx!UhNqkW^DD6HI z&IqYHK>e>NBelP%F2re7keWzFo7B~Wl*{aj;9!|ifOM4ZU@zP(s&B~853{`KlD}0F zDyw=i3%9mTpT1z-wE5HK&%-GtOfRUwu+AbF)QvCQc-ZAMw?JKjx-@m#AQcz0I9zTn z6>Y&4ZhD}$MrH`rPefAZn!}L<`R-kvU0u7n3~Sp<^uM#`_j{U2>yb5KrY%A@^R;?y z6)P#|+_Q@h&ru4;Eqg%DQA3A4G~}TnLu;nGkDX96c$0gw55ktN+=3y?xQg4|#^QCjfmTuLM&WxC`EpD#Q{=)FMo!i!@ zQgs=3WJ(+lM!y$)St>SzE)5px+7>8RuE?czJ9yE0<4)#^YlxLnxXn0&Q zIW}V_j9BY8YoWV$koTyvVeT6?Y>0j#Xl&is_U4IoiR~aL<)Kr(n}w;~a>XQ0oZ8&( zjYoW}Df2Xvy2Z~1s}q}X2(6FKt!Xw7)tHnT(ihef@$%b^J73@d^LhUvxjWWpw_7jC z^()H;-~%3sUKl+QIxnL|QrQE7^qRG0N6C2c$+b-HWfYrQYC6l10dH5F%am>?ov;!* zkb;_4pCfX>hp3FwaIPe3tRqwQhR+J0wRp#l<;yqhS-xRegj)WrUNaMXokFu&IE~LK zOf#GgELwmlu!QbxU^mETm|b04Y3C{`2I-JlB`xDsk;g@($xK$k7U+?oK3LW;D7Vt0 zc_dSgiFxONHK>}vi*DhnBzmN3+AOhU96Rxi3^9}rsgIe!TJ#PqYp>m+NzJmL)51$F zgeM-)4o4*%j}Qhl6}%LlquU!XovpUdIY8$Sx(<5#OfQz5N76PIj#l7ba|aLW@Ifaa z_!w|2#}zu7ahE%Y8}6WW?V|p}dXY4BBdcp~GIV^TUC#&M>iAsN2QiSY&o11Skwv<^ zSlry18$D*2J3XWA(>*_CYvq2?#k>_OvaaUddS~n1El@XGVZIA(hkg~T{i@BB7c<3azuoG+L3qov_`ddbJe1{W-B0Ml{36kg|b{a^d$?>|1>Ov)e% z^P6Ah{L{ZT2v3FSvW_l7UcRWRu4r8si=MtTur;`;sEN3hLKF6~WM%19Bd51?SGQT- zbW2SamOF+;>ATHnQ)j%EFHqCZJtj5%11d;gtjdb*Ue~=Yw$*C|a{BhPuyhce92!ua z2_u_pgDzTj^50u`{ca7wOCINHkJA`ks6E97Rh`h08C!^2+lhyu9|>lLRpamv9PXP#7&v45W)##pwDuzwKJr zw)I<6;YgS91Jd36QPWdGs@sg~<@fK<`1Ip5*N*NlCo;40cuz1jy_J++g6Ti`^u45! z^IYBNWaYbPI;~Osofl!rAH5m3zD~DHTNj&}Id4U!|AIp;z4zVMyDO9GQjs_PF^fDy zin5Z(16Sixj``j@v;Qc;=~eK0V@VXswYs|wa!wGYyQPO!vz>o(oVTBG-2cf1`<~E} zJ&|n#JPS9xaOKJsj%tWueB&o?AgF(I;rQ_|Q{Eap>&A^+ihM5!yq6@LMQ)j+N3-n~ zrh6h8ZhlX;mru+6=ld37M|r-hxU~s4So~mmgpCeM%SemLic+deY~Z9x!Gi}o4IUI4 zHhVBOVS;REH;^S4epY;1+wc}5Vjk=0^t$&@YpXw$j*gBn4obUC3iRK-TXF0Mh<70< zy`!tEg)>2sZ65wKobm8*8!SjqqAWKn-Y_~CE=IR*43pE)RN*cbm}7k5p*5d{C?e&V zNxa`cXBTI#lkC3+e_Tx$q<`(Mui|$RWJ*i7q;yd_TDqk4e*w~8e%=(1J|$PWINfN_ zhIb93-yxw3&>8(0y^qrS7~M$eHmQrS|2{QcE0E>IHoZux?-SFJ(>Z*wA>D!K(7OCD z(#{R2TaFj&Lm87g!Re^!nA5Sn7*4lbFW)ql7dc-X26db-&;IaX64bTx0CmMOen*&Y zgZdxe>wkQ%{YBY;-a>A=iDk5I>23tJsv9WjQ?_Y*z`gUA4j>R{_Uwh3{1phJ+LJ0z zhWHlNMg$*V#PoU715F?!ZA1~<)xA`uq+BdM=Z=-z15Pg}rp`1nA5Fsu?jrUIR)*!p zP`WLrw?yvgutvn?4lb83*Iu3>+_vz$Kc)AZwy4~maYye`Avw?LPCsVoh-22CUAy4) zSyY|HxGwLYW6F>Ta?>8q2IrzR$5 zAMrU-m@orvSW3EnrjEjGvYs;0`YG-ZS_CHLQ8jDVu38TWL+QBHgE)jCnQyK4tXZVP z`;8m+z^aWKH*5s2Xdyb45>Bb-M64@Bog{Vc{9ts<>g~Pw5;X< zE@f+*>!qc?sTE6m*Lv4tdf|<|6CGaxR8Eg2D`kW4pHxO+J9;yvrMSP1QABz=zYX3? z7Kew=+PZD;jtzS@%-FDJ#xnMv+H>j#P7e~^s!r4388=|MK~sw(AwKp2rKaLbiNZFI z8umjD7OcW>!{|FIzLe5zaM@yX3-+{-2#^~l1cZp`V~lrQv-A|nEApcAyj}vOkDI7t z0qcmtV7iRycYk99RBT?L7cp#>WS-H59W%6yPL2T0d`h(;CE><>f<$z4=7Br3d{MeF z@Eb;l(lzW~ZtKx7Hbm!E1kL(Y0D8@SFnG){gj99yZKJ81{;lrBd_wBxs);WRRw9tL z2)ZAr>yX2IE*;z$mD~R4+Ru91zG129qH@QI1nQF5Ej-tJgXciHHPQD{O$gRCjH<48 zvMJqsEoPUREwL$G`xi(zU$FsoojBnj=gZ^HxEDQZi|N*c(c3jwwiicz#aGs)6d`eX zI(f$af9(BxT$T5o?hn^8unRUJ5fsrxzyn(d(QZ1@3PB(+9E1lbRVbp!VN($hH3C8q z8bOIKtW;7ng3u;A$+po(CK>__S~8;>%ri+*gNebKYE3j6G}glonMULDzP|Up(4_6& zGo9aW=AY-gV6A(d*Sgo~{k`t%bA9~smn=z6UbBYg>6I;aH4y#Xzx?iZzoT2{pW4rV z$B7@v2Xa;2L?L-=5B}=P>S<`eQqEZ_J#B8fdhW!le|Y+ngLl(C%U?xwb2c@Qw{G3I zoz_@h8sEBuc#Xs>h`4QC-H^JDh|jG9bCP}BVsp-c?=iePB$B=JkxF@=^ z6JycNPiNFO#grU`Q~#}j~3>(G$)cqKT<&oqXvL(iOK-$;0T*AW8lw* z+0N-v!3%;PT#{KDm7m|tW5t|~>E%^}=}WRl>g5MnKL3k%|#=~mCe*)zw_BE`nb6)1KxYI;wVXHA#n z^b^Nx#+PjR{K?Os?<0{OOfN~y1=ABfYZBG`3m;K_KuAbKBzn3Vg`{M!gjczFxM86w zN$l)&%kkPf9A`B~5_XZoK)x)9ysbOY-SHC?Xs zQP;~IIUTED!`{-ZqvGQ#eUV0~flM^utp4s|Y!o-Q$6dODbHyI%fH&KK*c zuj#vByy>EKboK4HUks@CAt$rJ1;;q4LuQ2cFUW_#-NOqjqFS*_S(z+S)1xYiAzgSp zT+O`llS7gzEH+}gd@kfJk_~Gh-9mHRvRy=)4<6E_$fdX%Ibqp`ousHg{ z`PW|u&R>VmwLAapFE^WHM*BivIrtL2>xg~A-KQI^-V*HPyuo`@3#0dLkJwC3x;IgS z&w}LGo+;kC7Z7}5?ur+vw!3Gl_q`Ag!sOI@MeO%Zz~}&ejGc&Uo!01c<~%^o33(`U z9(V|+`gHGypP2r$>EHhF+mn9!!V5oT_kwqIeO`B3LQM01EG|hYX)6L}(Bfxr+5S@1 z{-dVv?+8j+G54vldk`EQ4I2Ntx9VSet*7Gh(n_1^_NP3y!fSo~G8*)Bgas|8ZPAMI z#+0O(jK)>)`RiahUUby-`xYe?B$ZVYr|9k7F?af;r>4$%ENa&Xc#m{?90$oR;?7Zd<fph+gq>x356bgm4{qhLl%0(;;z(;DdV$-Mq2;l)`}eC5bkS4FM4vGuWzkb( z7nL`c5gKD(4)2g5obS~sk_u?=~n^(P9qP+!EaM`2zVv#bY) z?5^|8 zEmmjW@lCL1RzAVye)+Rhy-6z9gW{~z=C9!NpBx1_5zeu%i%_ULrN)$sQ;vz%6^iZI z&@gN;{c>g2aAk4b@ts#>F?jFXC8E8*I$k!$?UyZR|1DvHw{Lf!eD6w~XMex1$AOK` zxI-#ww6g?*MqyDiGHw%c`t>tI;}4LW4yJ?Q^0h$d#_7Udd>==^bp2{< zncRQ4wL+MF>iJ*Zpam(Ieqfge5i>ODB&#EU6g@J*c@~wG1LO&Z4-63h()z2L1Tq>s zx@<6`xIPNvhQ1A}JC^8@q#eXAXum009WT4C@EMqWxjCkEq$202LgmjT?8Wp_oE}Z( zC=rY%;014bQw(By`anQtjeqvMCHeWo>G9iRDMx*q+?lh)P(tY)w|j?cudUyIbj$9A z`3>>EdhxB#-%>YHDo5XX<;gdmyg(P$s_>Gw;&%1rbXZbqHv#vg#qbN z$qQyaILkGseO7+Y*>j(La2q*Y4UU**Ey->>T2$HGoJ+zuU<;<_`}v}w`_m?KW<^f0 z?+%yb9e&BPmMqDi#~g3r*TzId5gn5ZF5JSL-cg#nBbz+%*&*)X@{M@mjv-@ZJc4@5 z(K@{8`;XF~mVEM}red#L*GyLro6}w0ibo&qziZ)uu6@d$po|>$jfm;2Ym9rJ9!DqH zIPm`Ur!StlLMmr_ra$?b=~?|DxQdRD_R{~gHM7PiJLh_pm?T9X>_ZKaxlHBYbSi1P zTFRgN{H+V?`m1OH)&-_}6}q_x1h~TDBuEF0>8H@sX&^E(!_`UfO}umfxs0wjUlKDD z=aqOx56Uz1;`8?}n3?R%3YzRUCK)|_Oz`a1-Yr`${PLGD`YW$rJavET(unZ%^eA^c zF~aLH?zAJ*TB6ZdQHh%yZA$}yaGTVPaxN&B??p$nZ!L@0p?L?%2e>$6nRkn%MArT` z`16=g9WnU~&2Ow?D*&Zq#&>y79#f9_|pd?FuugMPF71JGoq^qXru>Gh;Mjt^yCE$Upg28<5JV3 z342i&qshTDACxbhBIEEv&Os@!mH%Acb&TjnOb7oXjPc!KcI_L$ZnZGmB6GfPNXE4X z=bOJl$oyFVoj-Y^A$78f7zVtl?&s^-9RHKOQ8Kq1kSYk^eys3!4XRyn#mBeyh8|ls zIJmuf+fZ8Es<>%0rY%~0x{PS zgE^{!vJTT{>dnbhrg*}0a?oE#L`LOeNA6CEK9a`R)w0CD+{rb-R zK{L|!CL{zAP|{J?8Pgd0f^u(g3;@whoNib@s0vS>w8c~W)CQ%L4(QOij#2cz{bR)^N{kdu!t zDIG|bH=P5i<`!8m+VESJ4$dI_5i#9C>C)Ptc_!}Y(S0)-4{?*QHkKD7ujXTI02g^Fkxd;mTQ_qYWD=~e;V|&YzQh1T!QMgEjKR0cd7 zMARMtDL$3&g8={<02eKq5Jq#Jk(n*aIjk&Nl~qNGu;FimdQh}@)r z^FIaK42wJp$=AmAqM#R>^(Tx~Y`W$k_t;pkt6G%K6-G~U+!yEZ(0B_l6Ir~HE~G&O z#uo%lA|QtkhC&!c>6Vtxb_wCQV%yE3{Z@tBH8T~$Gt{({dok)hPu}pc5LuMW+F`cA zlj8j8S~I*GM^T+VQNVf%ylxMBwqr~*7Cmb{^Hj}~w^os!w^pHs?J>Ut+Pn%JF}!YW z%Yt@`%k^Niq)S_HK8on#bMs1CH_N_#CpyslNgFvFW0ca(DrOBEN*AL`0}yw!Dd%51 z9C)tFn`OtB!5WJEAAHbctkCIbfwH+4F37JmYWnXG(!Wg9oPe&b^cHF7L|+rFmnySE zR+cLoVv$#FXA@B$%`L^Q%5c2Qroc`l%I0+$&FuuNT)%#1=d0&PY<$^9a&zmKE?s(+ zZ-Ar|FTZ?=rb3@8zc4N7i}nK>cT~0Be|R|^OB>KzyYd^{5+e)g(}>n zl&!yJTrb1%?X(xQApI^mo!Zflh3QcG{nz6AdUFo@wzftI(?>2GyZPA%CN=%=WZ%}> z;r{!3Oon>Y974oCY zl8&Y>qk2qnWaL1Vi;I8Pl6e#iRJt9$zxT#%6Uum6ZAfqN*OT86bF}_S1tH(5{p)_N z+?TghNcxk{aSH$V`H$~!4R`M<%0WjTwY;1fEwmijvaW*ddok(6n$LDeO%Gl$b9Qb_ z$*ftCS3kIP`t7$rJ$T~PyQ%PIh&iz-f?l1k~=sQMEe=Rd)!SdYVrlyRL+4!aD zz?wTbdAxImUw-Nu7jj5^Bcg+`#njfeZa(szBj>NwwbQ`0DrBL1xLY_rc`vWTE@ApC zEa|Tue{JXSqvX5*>P5L;#csKo9lM0{mygx3m4>MrM&Q` zad>MfF`=)1`fCtfl#b)&GFK+z zabJu)UUWZl^D1g7N{rfa;YIlN#S4d%lU?-JnR2k?7Ed%BY<G zvBh+b!1W#;#6@}u)a`GBKZogvy&6VJH>MZ)uQf!X#_=LbCyCKSy!>L6(vhA`Op2wY zk7h95A#)+JMe7b?7d0Cx-3E2LeiW=0TU(@!MD|yKI;rdIxVE`1VY*d6s)ry-cZlhh zlx}F;qVv)HpKHmcc6sj&rkg&btcgb-+4Do&)$${m)1{{CK&_6D)a@ZbU5YvzCD<_W zU9(~(rvIxc-R?p zP*rMx>`?4RyE|o&*=km9tYCrJTPa@ zedC@83k@Ao`KSsmy~7@UV(!H!<_?wTbtfe4FI(SPzIJcY3}oS;wbKsnjESjBEQ;A* ziaWh5p)oCP(a)ZF6i0^R_w_&YFsOUwK7Kn;)2B79FGxt6v2rDm=79&(s`sYNNUG~3 z0-OnlH{sZe10S9+Zc%x8{mzwg9!OZ67P#T5agTQITU%dOU%In9E^ckyT5$WBXZE!u zrKB7T?B;hWX+_G)wQ~Ecn4zq6bFhNroUnp_9cXYSr>>Zxu_7*xHb=yU0ds~Xy~9?8%{6p(7pDu^M2UiJ*v$ev zL+QY|;YTUEI@v(E(2!%oW?`LmT`@MdYfh3f&TVl-H_QRn^s!UTz33Q2(J`7_Sl7^& z0Q76{SMbW26Yeo;I#2B$j+x1Txug-(bv3gyhk7nt%c68+?vdpM(@She?8B@qJ|-yW zY>KkEoVBN&Q2oo8eix)0QkUF*uO1h$%i7c5=wNM_M`|86HKo?7y|d4{#;)$o<;@ih zNDHZj)3&UA7bKgfpf$w`)&(r&Hd?x-L}sUlU}ST%V4rAXyV3l)ZQJ}}-HSET(iG}T z14ws_NfeUmuJ2l#=Cu)}gXw(vV0&>mUhblF7VnnUze4Yl)a6KbxM1#5(;uV@DZgLi zXA0712G67`CBKQ4R{>~noa`05SJ9M@rLjxd> z8n5=;8inq)#B>hyGz@pva-{=+HJpC&lXJg2apKa;>^MB}$3Oh>op-KiP|&E@6#8eL zi)n6Z-?3}{{9Omy?|*4|HqCH8YHQo!>zi2;8RgMc*_NA|Gr~ZQPk(P;EvbVF zq-@Z0ApE+7o{{t&Ef%If`EINHFY3(1xLi3*&!)@lIQ-Jk`~}NQDrqmDek!BO*|WE9 zym{l+aR1j*l}L`7&TX{R9c8>WBMh_V>nrtT))-?bUA`B-XH`q;6~OOlfD2-JS5_)k zf8Uq3_TEBH7x=4ywBy#bhJ}8)_*O>RQQLR-J^$8Ee)5x_U%&njfcjgXKl#e@@ofC| ztZ9SNfb?|F9Xotmi%Uyp`4wwAp+=;r>8~E&w=e1V zYp#ggp8>ejE~}Ga+8z2ihb~TRHYx@y*na0Wc-et z^!V0mZ_a(<+3NcC_Trr4ss)&4J$biy=6WS&kM9~k9yR^={{2Ux^e#1W5~k-SA`^ql zuC8uSabf$PK5Xm3Tl=T(KJw?5|F;p*xslOJo?5pxcuP}f^SMtydHT|&mp^&>X$ z{`nW5B$aV6cgd`LJO>iXgM;1E2P-Z-f9#ivV}JhC7T&Z7oj|%X9wV$n@HgRlo*J$m zxrvz+w{j=cs~T8`zM*wP;Re+~b8PA66i&BwbRDpBp{mu*&1|~(zhSx{-EyYeV!Gne zfAGB@e4B(9K{|c5P6?Fsbf^-dsntlh;4Wo;%^)UY` zNdFpyuEEv$c9Z30{wSx5((j1r0J^26Te|tEmj08U|NT#xf~Wy0|2lZ(d*5TiLL#FH zc6sDO)N)qQH@?YfGQ#Lzh%PxD-^(5%Uy#$SMn?{Rx&`Y07CGI1p-ky0V1A)*JN9&I z*Q*-R-U#gGFgT!Y4youQ+eIhPYINa3I%0+JDda4I771;MuA-Qj?P$pgaD?o+U@d%( zhF+`kOfw9lYmXBMRg93l{^z0E*49VQ)CC7OBcsdRt^K*rK6@;0`{?=qwuSq#!M9TM z3YcSwr&6QURI;Ml4_??_ae-Wuf@*vzX`tOoBBzbpSUp%YEIE)qr2L4Yq$8knlD6rC zY|uK+7t~c5m=ywY&%@p%I(k15hU?{tCw}(C>L)O&Pk&+vr(8;7Qd3=8N=HJ@lo+$Kpp3ervV^?GG(6fHNP)3msQ=i5prjeqb(u~3Q@*~otiHOsx}dQm zE$DU-aqcrP=hW3F?Q3KmDcU`ufKIA;_4U;WY1KrbHzKPyHttK~X;sJVE8V%XJgK}9 z;X5hmy*O;+`}Xa9Z^queNeYWe(#iXFCTYyW{B_wh2S9iX*R}Wwx ze~qv1+soAq><4j^Gg8bA?@dXWk&vKx#=R+v4jx?l)Il55c}@4|b;j}{6UQht;oknb z8k8EN2D~+O>ZGt`OP3<1Z(k-g9Z1j1%PS}dS}fp$8)e;AF1mqXDAVZhh7$p68`Gt= zihH>VesQCh3m}bZE|j!1b-Esjsg1VHDZ+FBP}Ik%Iu5mq2qlo~f#E*aRXK(Grel&) zUvxK8_IV(3$&BjlQ|>Xwbh;be%Z=$)ETEJz+f&+x-7Ov6`m-V39B_R(|9KV$n1$ZV2Q2`%s!Bz+ zXyA&mv@sp~i#2p%)}TEMZd;l+Ye)2KKP~f2%u_L-Zj(CDZMfUUZ@^rDZvUIYQXMg; z2;aG^wdc5!#ry1=JJUX^nw|9$Xe$VRT61RD(;g1=ijI0-_@3b{$6!h*I_I5dAl;z3 z#p-79OM6n#?~wXqqu%rfrBT7?=6~k+-N8iYE_f+8Rha%e0ZjP673t?@utwyi`4H{#ileLSZ6r>`o%wd zB0N9w>L2k`T=~K=Mh+Y}ymhy4&%m|ep2}38$^4McUw7cZ@8<`1HDCRR7DT)Ief`^t zJUz0yYT9$#*8T76*RO;YlsnY)1M%xj-r|<~4-@tRsoS7VmKT)XzcqeyYkzd{;i`x& zHNy1L%gzy0(CLi_M=FHKBu_6?_| z&Kf>Th6-wWa~%DMKYi}j>D#w1_bd#~9Vsonl9NA7x#so%0jB>1IUV22^`E@)q6`2b{^k1 zbmi4|sJ49i>Gw)QLPm-`aJek>MNJP5&Mhq-KdUL-DL-UER7KV9{=w+UlZ)}phxE~j zJ9g-`1KGhtJ-Q%!Dh5v~^x89EH6N3Q!n zMKW3lE;=8Da2@%|IAuuRWTso^V5CUztZX^)@+WM)Iq?U?^y{ZaYFNV!QBj8vd+umj zpWb@;+Krn>{@dbBE;D(Uw#-Ti}utraouvnep$;qULUWQkuuYQyBo;h0{cqG+X* z$%Y4~j0R4$)O17NWHHKzZg!x#TrQH>IWQ&|7Wh-=BNslaZXO=^keuxA+dreGJH&Lv zU->m;O#hK3r9-0M{@zz?>BjS-kQZ_bl{jvsbc@n0*NX+@4o<%#r;mdAU23{;8bUV% zxV9`WBJIC|eI7)NfYQ0DxjD=9qDcWW2Mx_9ER&A$yf{eRsOPrp1xmNGpWy*=GxmZR@oxFP5w2 zFIZmw^u{#@plnq-zx*`XDbU>vdGfb!FAW{)ZmdoUTpYNFqES=yhF<_-OEE4~i;kPR zc-lQL&{T0M7$MUOmKUp_Q0&1Eswzk)K6KAC@7Qexfw4oOtIw|KK7#D!*328jk?zBcOv9BX7ts{umM|rq- z;#SN^n~|1~wr}6Q#=S5v&^se;?~G62YYsRLHskiuK5T4`qm17@xTv)4PgczM6cK&K zrz~@$aa@XXklQ&LXKCM(-PdZMeM?tI442G4gNvZCb3`{RiClw+k;1K-Ki$F#%eiiu zW^laVdC@<~?lWe5YI)NS+3Qnv2WaO2Cql4;(jg`pLliJRhpw82U#Cn9+O*wRUW}Sv zU69uSr*}|dD^mzVEW7w&;h4o^Hu)M@GdyhAO(ZU9H_+s)i|GJ7bBZhdudO2%~hIq|Fu@>VOBW-Mfh^Tlk2uuLslhgQ-H6Wx34H4LH) z(;fRPYI~It+}UhpLfz#&VXEVxa1PmgV{IPbsacXbwi|E#nUNw+_cp8D+7qhVVz<^W z!%S>=TAHV5g=wYRYPx_M_%_P9rKB6uH^&_!y>$@_-*wZ5+qLP#>?{Y2&FSXubcds3 zbp6?@)2v{#jvZ>c40Qr?z4KTywkzI-<_$P!j}FY4x`5+|QPaN!>Z9KD2lewcegT^L zg7L}8!O6+_Gk3of+@OX;ziY|L^q7^3`CL3&Ndr>5v5?x-NUOmx=_6j zJw1GA)|l9wkwMj?XKqweZcV0tiF|v_Jz0^Fw7u!7Ik0XWhH`=4AC4bwKVX3Iz<~p8 zzkg}|`~x3-K@lIno>cN}Y}?pY92xGuqy4~vUucsg=xn)dJA@YIZ}!>K(D{nu{3`R2R*q;d~m z=03r6<~waIIXQKu>my3H#f6oZuD=?CG2I$y9j^ zT~WK%jf|-MsGYKTYAjat)Fcl0>sbc#qn{p7tf zS3vbYT)Fb<@tr%b?0faqKj3*|YQgVu}|8*QSRrm>nD) z;W;z-RQ#BLieAF!)3;sx{Nl+g?b*8zS5(Yil9l1(8t(5*$DkTQR8Z5~j<&Sy-}xGm zj4gE~C5gPJq9`3j;mt)U=2-jatYY1|1M3cq@D^g6(*LPbBL_wtXKQo8pA5_Ba_SDD zn@Gm^;N8JTU+eng2{_$YUe0_mlDjcCao!UDLcMf}0c6=n)DGNI3)O22ALM~1`zIF7 z%cw+Buap61o>N9vGjjSTmp=LLZ~XH4KHe@p4O#v*8$Eo-_yz=oq=tl;WX15F@Blv- ze}BYydN;Mv04p)ExHHl%a-e7+oL0WgMFXV05RmfA=eOi9WY(vk96o-#U+R1Qm#;tZ z`nLG!!KLXwA^C8>VQXK}Kkj0s;CPXW0CQ`5amoeS)WuOsTl)i^tK`7nPdi0HN<4b3rVdBzXv@%|v zv#Li;BTt%-e#x0`u-I16M^Rm{tkdjqmzZutx?JfJ(k*NGUq$I(`3)3w|w?G|dy4j7&>4Nj0jP8JROHF_4jqlN3^atPm(D++qdqGWSF0)5! z`rUH664W1|vQ)_e9321vAOJ~3K~#de4eBuZ1Ea1NNc~?u>>tL#YlIsTa(Io9Lnyr$ ziJJkeqL24iVOU4brAWERf$m6opNqHL#$k9H5CU+L`G*rX8Cfpl{_ z@#*Hk+@Pr(H8;=2Y4xdyMZ?J!Adix=4a|3)WiH;g`Pli_S0klA%bzs$W5-O=ix}G) z`hu2IX7tZ-#-BUnUhcXF2c^gNULfwVcUf%g6B|}HPI>g1d+(WI3PkS_Jly*Nz1GLg zp=5OI3v=&fll0@}ys4Z;#}=?dK4lE)fEzeBj<%$E%c|$j-M&e*ax9PTMg^gSEL;BPWeash5C;@*pRkw zCmFswBwIQ0eNHw6-Hf&&#LA@uyD@k+hq769F=?j#y zIA!fxEH7(Q4nfZbdDpHzgpGuzeJN{=#f39iJcPsKkaYpsOss*B?HC(a2%M&_qcW-M z4{JGo^U?8?$#Nl~1&2Dz&ulQ4k)fSqx|W80O~(<={H?hSgXIR$*|Qz+9N5>}aB%HD zd)-f<=71MjtO=$|*|Y{>DAJwL(~a>3b`6Z(w7q`mcBL`mc_An#PvL~5h~r-oW(w5R zqZKaHpGE10@S(QR0d*>#QD`n~G%Bnp-MBV%f;e0nx^P|;??_&>P*2z{1GG6uXeeHu zFx|d7CtyYwmvRZ+2GY867i~j~ZsJ~JO~2z!x6d+yfBkLbX@%jt_)eU5pN)~5cXqIv-EVf=fLTjB+hwg z56o_MV)ZZ4y8Xs{%sTv%H~qm`$;o~$&H>IYG*}7n@Ms9}o&S<=>SavnzdK$MMMzy% z778|$p4(22Tt;Rhv_YMpt6OKWmy1@vG zi5zIJsmb&>fSyi};`Qq%|M*&4&2q%@b@LA#Xx})0_x$l~2iiE?%FdTq?XF6kBp9+Q zD^uA#ot=tJq`7i@_VTS;!+k1KE4$h-Y>bRt=({zVzJ8hhMN#Cuprc!a&Y~IWK^lL5 zKc1HOQzP-a2YOo%$eP}J`S|J2&Yt*R?;P0C)7KgeqSw;a2!*MibUe%=Rnh6`#rV@H z(i@0>4orW3q@|^^lk}GX3O2WQJz zRM|s(N`CO+!-qBBI7@pZwga5IeJdh7go@3qk?mg`&GB8hF#gtyH*WmmtzW$L>o_?5 z%=ORdh;x5cPsXmOc1$UTVNaQTaJN0GYDaLe$6)>TVo%TT$>CsnPK`(Qa7cS;_`=A# zx~t4#!1UklEjx4N53o7GjIXhs;MKkF32dK!`rOrw7}w6QeeJ7s1R6)~Oka)QzY=XVI*LUlMDJ>AyV4dv6C6nhOf z;Kda)GBcfgoSpw7rrTQjmn<(9r9Xn>MG-Hm9>wya&ZBpgkD4x?mXvOBx{<7n=f!4n z+y7z!{Y#Agr=}OBDB2pj$$GIjX8)TA=t0YvZd=puP&)T-#@%YV!d^@kBa!K&rk9`p z#I7V2up3T)>+c@H#3Iwn&+w+321gI5`4bBJqXKmbNp+UIFX-tcsM{8Gs~@S+(~X)g zJ^gR~wWMx6>4km9mySK%gs1mO?S@}zJ7je)GMJu@$y}(8NhGQwy&}DzZleok`|7*R z+C}4I?+4S#(06BZkG}I98oGt)%65VMp?~@o!j!SJ9+lk%zQ9|H<>j7x$2~p{1jp7(NuK<+^o)_rsxgNI#yO8eY_xNk zI(K#6vd}>9yrAu|>JO9`8oKQHZQHiR4s9CB+uxb67A={ebhPw3+|wz0*O#R=dao_0 z-qabBUe?i3&>h(AJ@?n%8~#o2&i|(_oPte@K;52p&@?0B=7rLxnpAvk4;`l@lw)S$8E#LBi)K7E z;RWkNBa)lKQR{S*nQmXoKKSiZiw^3{r=IyO_w-vcr#O^kuhr=j&^0Ycm#R5BV04y+ z>N38FT<3O>@lsFB3zUvE$Y46$+L5=4Bu1mN3TPj;0bMX=h7eK1Ay1n?Mo~Dt&JOAm zvx@v5WzMtLu(t7cVv8xG^4eA!9 zJA%&bH8)9#O?v9)6)-1SoDIzzM%OFAg5hxc7KG$qS~QmwqKne?I$5H+Md{|%v+m8- z)9*04COoWA!|FT-^LAkK1`{j!t28V?m#(gzZG*9n=*?&?nM*qMcvo7^7je4dn_-P# zfU{uRs}NbutphLhE`j@=xvQyZM`&?+*9p=i^ziTrXgHyBdua6_?GJ zvA>gsqfk1~Zh^WJ$sNY!oH=g^ewQU7zRB4hWJzxA?}7BmPX8UIlugm$&XuXN@}map zOH0#3X14ad``o)KB8`h1dJ#;A)8Flj_i@U_WdZI&=oY53#3ZN6bFxQN>84FNGz)bH z(~F~$ld~5ttjeicGf>yoe3q1&w-0`Lx@qLfmDgVT;>wk}=B&)7?K~;{&Opn1WsSWA9;RDUZr#}Du{flRg?%Ew(QM_hJNrt~u zcw#2QLy_d!U2QvG+rPi1<+VC(H9$>oDlT-x^5T(8e7ed4+P})@dK&z*L4XOK)ODk$ z+ntMah8g1aQ}*)R2V(e_g2&G~e*E|eQ$hOv(`Q0Q4!ctR%-qwNOqX0|4;R1U(k4H5 zxzoRM`&x)xFXR1+is+z9pI#^(4ZElX>(}u=Ui#z-#hOzD(9>gK`VMM90~!K+!l86$ z-V^jT%A~ToNJ;9siQ;K-x-+M>du66J^!IP=dlyXq@v(~Vh52k7S+iyVlpg=?>u6%$YDr01^o3lIqcQL#@tR-1pP|qg= z@jNm?yz(3=M|F1P8E5!p`ZziJlWA{%8+=vNHIxo|0-qWftI>n)xbz>W^Qh6%f6SZC zmeP$I#12eHN;hKqXvm9kn8;<~5Y8<@-EoXVD~-`|q{#3hIsI$e*_5sW<9%^_d;RMV zjh2p_tXUA0KA$_$9XrHyBd6Q87bB)iOScDv4x5h}UPS2{FA|*o&2O3DbUDzartbm1 z?WmU@{NO`C9YB|J9d|naGQRBj5t}1SF5?4#m7Z=t;q7V_L=+<;@?c*?FI3I8M7hwB z%1M$<$G>J87%8x&7Dlh22YR$GNiT@zi0h^dvkIJ!?hjc&T%)_J><%qmh(6+=a{#@s zSCaq>(k)Q8=-9Bb#mrj7D_+&AoWw5~Vg|`bR2ZZ8v**JQ)V*KN+jeZT4dtz(a}mCg z(rr+evToFM>rU?8=Mom5vu`~R$HVE3-y9lxY^WgYVZ!Rh-usNyKOs7ZA-+J_ntB9X zkY1$5V@new2J|7pOPV@^pGtwr>mFR-aRb zi#lO%HSLUAI_vi1d08726ST5AXjOqjO(&DF+xypH-Tyh>^c9T>X*=uo@86k*fn`Pz z&5l-juT4RyT#H^#j>g)+#VL!|rg)=;rx4?Ul&*5m6ly#HdV(?(cfRPzv?FUDrmZN# z`-W*7IE@8sw`kh*4Z74pb961&r^IynLC#gq%QV^!IizwhUDPj~p01&wH;dLuPgyW; zh+C5bK;Fy~6rgThXsXzotI)#qsi}s&IbHb9AH$%&7Buc0(FK?nJY%WpDOl4TYWl;| zr}8>m)uVWu^g2sJ*Pd}D=m^1#fbZObP4&yr(wA)uRRyVp^jOl;!PYP(ro-0{2YMSh zT|B02Yz9jPGlhu;*CZPY^914s#o8kY#qM9@4No0ebxe?tWk4BI# z4rgXLfnan|x=xXNt~=xcCP9YBBgci)50Fe{0XuK{KsY^6h1t~R)QqeT)*67@3HA)6PrG2dYR=1N&wnu;-o%!6-IV?wfc_9syq&+|I5{u3@@Lo z4AgXtFS+f-iCmEQHa6e0k0-&+8FRB2xFAd?3Ily^9!+X;3-PVj6g9)sopqg^MFWw! zK)hS-d`kJ$KJ?6cuaVnw7)a0dZ)<5UN$np#``p>*uHAa>*5+%su9+PE#3|F=+nFT#lpxM^eet1j!$hKoQ-!z>5_Dy13?r$}aZud7@$5*{Q_yxJY ze`{@D>){c8Ne1I(O|R=UHgP4rG}XrUhxcN7sinK)m@%^#BBuNH(_o#Bka(mcz54rZ zeE&DU_*G6@SC&r?BQrNMvCzpc(yfry;3bcSr;{_(i;;D^T(N1nf#`m?$UVG@GHdGUN@HSrPrvz{?>u|0FnK&F@3c`R=OxkyH9eP) zNhLKKZO8xkN!aVkV|hNF%$UfdSHU;**f64PH=_x$TbVqDm=+t(LFCu^RR$1y4dm1Cvf z*WH5~XMW6Fne=qIaC{PrTq#qfJB@92xkKwfx{=aJS67%Lw9W;MmL8et!zErsB zl3pBAx-cF5G@;;kSzatH{l|)8L`(mPotKU&ot0KFaKODE;o7 z7p&w^I-V{I)c+b=y7?_ZOgDfJrCXeCRghYgZsoj;deha`NZm)ZZwxQ08Fj=mg6qbl z{trL@#T)<4^f&q$G%gnZ@P|M8<^$hlUG4c>sp+D04Usw>kO29=wer(dNvcVYh~Add zWi3)6>HmG$Ka4Q?wL$GP$V#lhrl)Wh!|Axoiz}ik$Xp!FYl(oh?G8UAs4CMOx^}AZl0B(=ojiGzNKx$(r76 zzfk|N2Z8v{%l7Zvzn_94?B@wVX=yWpf)=j~TD4+v3UX;!*vi{0!iayly=vvkIPiSM zjJ*jfXLK~qSb_Au!h1##u_kMe7#VXeVKBxI0ZTo+7>wqFgiL=UWx@;8%`nA{_Od~CF}*RO@Unu& zVPw2uOc$hUb{ad4o?l~er?aI2=G45_DCuCjZ0OR)DaN+fusK(c>MswjpwA-*#{Xh~ z+^FUbR%gA4e2u2g!_gz+Z8++EnJayrM=HiP^sTjF(0LMbZ{4s%P&aE%E8M~8=C$CB zX|8QWTFZ{P8>P2qyA2|M zvOrB9sLkm1DIhyvJJ?_N6UduCy)ms}zKmGBTTKVjo!JSsQPbVhYu$a_8&X>o#dz*2 z?sO+NCyxw_vy{G}9w!zR(>@(Qb#pCB_kui%yxgEvAQhWy5utT%O;KK?S>z^?%-BgH zV<(PoAJ5##652H4Q4ptJf9H#q<|Pz~1}BrY-c*yCe|gls!or(3Z;QWg+`Mt)CJEuz zS#Mv)Xs~1+rh*0<1^_HrvGbSpFc4xd|?Zshc>yW@NNY4dY< zOU1fVVETdDv&h=#{`k)S8p-J$rpOgFJ$lR-KNmk73u7Akp(5zU1wMjne)StLy|1aQ zBn#N;X()jr6Wx5=oB(wU!W8DQ-iUAXat&CL8jkISm6GUDQ&P7x?a+n|@70xr^#2M> zf9^8b>^E-0=@gb$wt(eDN?15RI&uz&D*(q67#Cx+yH*DOK= z;dH~O?BNyJ0;N+4>lu|(&lbM=h(h<-?oGvh&bg`iQK;!5#lm!A-*2BjJ6yZP(`H?y8 zyAF(~6hTQU^L^9P^YfkcW|FS#m78tJ=}kxXV^2SRTt1+p#HL)t=1AU%i0LxDs12zj zr3J